From 3c94dbfb8bbe7ceaad784cc2efe7b7917f5c73e6 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Thu, 12 Dec 2024 12:58:05 +0900 Subject: [PATCH 001/334] fix(tier4_perception_launch): update multi-channel subscribing channel name to lidar_detection_model_type (#9624) * feat: update object detection channels in tracking.launch.xml The object detection channels in the `tracking.launch.xml` file have been updated to include the lidar detection model type. Signed-off-by: Taekjin LEE * feat: support even the validator is not used add variable use_validator to the tracking launch and determine the subscribing channel depends on the use_validator value Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE --- .../tracking/tracking.launch.xml | 19 +++++++++++-------- .../launch/perception.launch.xml | 1 + 2 files changed, 12 insertions(+), 8 deletions(-) diff --git a/launch/tier4_perception_launch/launch/object_recognition/tracking/tracking.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/tracking/tracking.launch.xml index cc9fe78b748a4..ce13a742c6202 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/tracking/tracking.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/tracking/tracking.launch.xml @@ -15,6 +15,7 @@ + @@ -68,21 +69,23 @@ + + - - + + - - + + - - + + - - + + diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index 5c04cc3e10679..83c7c202e8c0a 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -272,6 +272,7 @@ + From 41ca7686d7439b5ebb5a9ad903a3bd827289427b Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> Date: Thu, 12 Dec 2024 13:34:48 +0900 Subject: [PATCH 002/334] refactor(autoware_test_utils): enhance makeMapBinMsg to accept package name and map filename parameters (#9617) * feat: enhance makeMapBinMsg to accept package name and map filename parameters Signed-off-by: kyoichi-sugahara * feat: set default package name to 'autoware_test_utils' in makeMapBinMsg and related functions Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- .../autoware_test_utils.hpp | 14 ++++++++++---- .../src/autoware_test_utils.cpp | 5 ++--- .../autoware_planning_test_manager_utils.hpp | 18 ++++++++++++------ 3 files changed, 24 insertions(+), 13 deletions(-) diff --git a/common/autoware_test_utils/include/autoware_test_utils/autoware_test_utils.hpp b/common/autoware_test_utils/include/autoware_test_utils/autoware_test_utils.hpp index 3721dc67526b5..b98af2133f175 100644 --- a/common/autoware_test_utils/include/autoware_test_utils/autoware_test_utils.hpp +++ b/common/autoware_test_utils/include/autoware_test_utils/autoware_test_utils.hpp @@ -213,15 +213,21 @@ LaneletMapBin make_map_bin_msg( const std::string & absolute_path, const double center_line_resolution = 5.0); /** - * @brief Creates a LaneletMapBin message using a predefined Lanelet2 map file. + * @brief Creates a LaneletMapBin message using a Lanelet2 map file. * - * This function loads a lanelet2_map.osm from the test_map folder in the - * autoware_test_utils package, overwrites the centerline with a resolution of 5.0, + * This function loads a specified map file from the test_map folder in the + * specified package (or autoware_test_utils if no package is specified), + * overwrites the centerline with a resolution of 5.0, * and converts the map to a LaneletMapBin message. * + * @param package_name The name of the package containing the map file. If empty, defaults to + * "autoware_test_utils". + * @param map_filename The name of the map file (e.g. "lanelet2_map.osm") * @return A LaneletMapBin message containing the map data. */ -LaneletMapBin makeMapBinMsg(); +LaneletMapBin makeMapBinMsg( + const std::string & package_name = "autoware_test_utils", + const std::string & map_filename = "lanelet2_map.osm"); /** * @brief Creates an Odometry message with a specified shift. diff --git a/common/autoware_test_utils/src/autoware_test_utils.cpp b/common/autoware_test_utils/src/autoware_test_utils.cpp index d42a5219e374c..08c4a3b5e9264 100644 --- a/common/autoware_test_utils/src/autoware_test_utils.cpp +++ b/common/autoware_test_utils/src/autoware_test_utils.cpp @@ -180,10 +180,9 @@ LaneletMapBin make_map_bin_msg( return map_bin_msg; } -LaneletMapBin makeMapBinMsg() +LaneletMapBin makeMapBinMsg(const std::string & package_name, const std::string & map_filename) { - return make_map_bin_msg( - get_absolute_path_to_lanelet_map("autoware_test_utils", "lanelet2_map.osm")); + return make_map_bin_msg(get_absolute_path_to_lanelet_map(package_name, map_filename)); } Odometry makeOdometry(const double shift) diff --git a/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager_utils.hpp b/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager_utils.hpp index b61c579df83b9..5081b14dda63b 100644 --- a/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager_utils.hpp +++ b/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager_utils.hpp @@ -24,6 +24,7 @@ #include #include +#include #include namespace autoware_planning_test_manager::utils @@ -34,9 +35,11 @@ using geometry_msgs::msg::Pose; using nav_msgs::msg::Odometry; using RouteSections = std::vector; -Pose createPoseFromLaneID(const lanelet::Id & lane_id) +Pose createPoseFromLaneID( + const lanelet::Id & lane_id, const std::string & package_name = "autoware_test_utils", + const std::string & map_filename = "lanelet2_map.osm") { - auto map_bin_msg = autoware::test_utils::makeMapBinMsg(); + auto map_bin_msg = autoware::test_utils::makeMapBinMsg(package_name, map_filename); // create route_handler auto route_handler = std::make_shared(); route_handler->setMap(map_bin_msg); @@ -67,16 +70,19 @@ Pose createPoseFromLaneID(const lanelet::Id & lane_id) // Function to create a route from given start and goal lanelet ids // start pose and goal pose are set to the middle of the lanelet -LaneletRoute makeBehaviorRouteFromLaneId(const int & start_lane_id, const int & goal_lane_id) +LaneletRoute makeBehaviorRouteFromLaneId( + const int & start_lane_id, const int & goal_lane_id, + const std::string & package_name = "autoware_test_utils", + const std::string & map_filename = "lanelet2_map.osm") { LaneletRoute route; route.header.frame_id = "map"; - auto start_pose = createPoseFromLaneID(start_lane_id); - auto goal_pose = createPoseFromLaneID(goal_lane_id); + auto start_pose = createPoseFromLaneID(start_lane_id, package_name, map_filename); + auto goal_pose = createPoseFromLaneID(goal_lane_id, package_name, map_filename); route.start_pose = start_pose; route.goal_pose = goal_pose; - auto map_bin_msg = autoware::test_utils::makeMapBinMsg(); + auto map_bin_msg = autoware::test_utils::makeMapBinMsg(package_name, map_filename); // create route_handler auto route_handler = std::make_shared(); route_handler->setMap(map_bin_msg); From 4bfb753eb42d0f7954578954b62614314d05c6e7 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Thu, 12 Dec 2024 14:16:24 +0900 Subject: [PATCH 003/334] refactor(tier4_perception_launch): refactoring detection launchers (#9611) * feat: Update object detection launch files to include input and output arguments The object detection launch files have been updated to include input and output arguments for better flexibility and modularity. This allows for easier integration with other components and improves the overall performance of the system. ``` Signed-off-by: Taekjin LEE * feat: Update object detection launch files to include input and output arguments Signed-off-by: Taekjin LEE * refactor: Update object detection launch files for better readability Signed-off-by: Taekjin LEE * Update object detection launch files to include clustering output argument Signed-off-by: Taekjin LEE * fix: pass ns argument to the lidar_rule_detector Signed-off-by: Taekjin LEE * refactor: make euclidean_cluster not to use use_pointcloud_container and mark explicitly Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE --- .../detection/detection.launch.xml | 55 +++++++----- .../detector/camera_lidar_detector.launch.xml | 83 ++++++++++++------- .../detector/lidar_rule_detector.launch.xml | 25 ++++-- .../tracker_based_detector.launch.xml | 6 ++ .../launch/perception.launch.xml | 2 +- 5 files changed, 112 insertions(+), 59 deletions(-) diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml index 499cf3c192164..912a7f3e48f41 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml @@ -47,37 +47,40 @@ - + - - - - - - - - - + + + + + + + + + + + + - - - - - - + + + + + + - - - + + + - - - - + + + + @@ -129,6 +132,7 @@ + @@ -159,6 +163,7 @@ + @@ -182,9 +187,11 @@ + + @@ -217,6 +224,8 @@ + + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml index e06682853d956..da30500070850 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml @@ -1,5 +1,8 @@ + + + @@ -41,6 +44,35 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - + + @@ -110,14 +142,11 @@ - - - - - - + + + @@ -151,8 +180,8 @@ - - + + @@ -161,21 +190,21 @@ - - - + + + + - - + + - @@ -207,8 +236,8 @@ - - + + @@ -216,24 +245,22 @@ - - + + - - - - + + - - + + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_rule_detector.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_rule_detector.launch.xml index 76ed8ad5b2700..50cde24473d2c 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_rule_detector.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_rule_detector.launch.xml @@ -1,20 +1,31 @@ + + + + + + + + + + + + - - + + - @@ -22,16 +33,16 @@ - - + + - - + + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/tracker_based_detector.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/tracker_based_detector.launch.xml index 754542f65b0ba..286bd43a8cc1e 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/tracker_based_detector.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/tracker_based_detector.launch.xml @@ -1,11 +1,17 @@ + + + + + + diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index 83c7c202e8c0a..02a34eab8fe9a 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -77,7 +77,7 @@ - + From b58d8f6d0d55ed94f2c15ece571c536a73eda6dc Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 12 Dec 2024 16:31:09 +0900 Subject: [PATCH 004/334] fix(lane_change): remove overlapping preceding lanes (#9526) * fix(lane_change): remove overlapping preceding lanes Signed-off-by: Zulfaqar Azmi * fix cpp check Signed-off-by: Zulfaqar Azmi * start searching disconnected lanes directly Signed-off-by: Zulfaqar Azmi * just remove starting from overlapped found Signed-off-by: Zulfaqar Azmi * return non reversed lanes Signed-off-by: Zulfaqar Azmi * fix precommit Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Zulfaqar Azmi --- .../utils/utils.hpp | 16 +++++++ .../src/scene.cpp | 5 +-- .../src/utils/utils.cpp | 43 ++++++++++++++++++- 3 files changed, 60 insertions(+), 4 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp index 5dcd132f16377..1386c60d29aea 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp @@ -383,6 +383,22 @@ bool filter_target_lane_objects( const bool before_terminal, TargetLaneLeadingObjects & leading_objects, ExtendedPredictedObjects & trailing_objects); +/** + * @brief Retrieves the preceding lanes for the target lanes while removing overlapping and + * disconnected lanes. + * + * This function identifies all lanes that precede the target lanes based on the ego vehicle's + * current position and a specified backward search length. The resulting preceding lanes are + * filtered to remove lanes that overlap with the current lanes or are not connected to the route. + * + * @param common_data_ptr Shared pointer to commonly used data in lane change module, which contains + * route handler information, lane details, ego vehicle pose, and behavior parameters. + * + * @return A vector of preceding lanelet groups, with each group containing only the connected and + * non-overlapping preceding lanes. + */ +std::vector get_preceding_lanes(const CommonDataPtr & common_data_ptr); + /** * @brief Determines if the object's predicted path overlaps with the given lane polygon. * diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index 2770831dbc485..5b8b8966f965b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -112,9 +112,8 @@ void NormalLaneChange::update_lanes(const bool is_approved) common_data_ptr_->lanes_ptr->target_lane_in_goal_section = route_handler_ptr->isInGoalRouteSection(target_lanes.back()); - common_data_ptr_->lanes_ptr->preceding_target = utils::getPrecedingLanelets( - *route_handler_ptr, get_target_lanes(), common_data_ptr_->get_ego_pose(), - common_data_ptr_->lc_param_ptr->backward_lane_length); + common_data_ptr_->lanes_ptr->preceding_target = + utils::lane_change::get_preceding_lanes(common_data_ptr_); lane_change_debug_.current_lanes = common_data_ptr_->lanes_ptr->current; lane_change_debug_.target_lanes = common_data_ptr_->lanes_ptr->target; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp index 4d46f8270fac3..13a119848a87a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp @@ -34,9 +34,12 @@ #include #include #include +#include #include +#include +#include #include -#include +#include #include #include @@ -56,6 +59,7 @@ #include #include #include +#include #include namespace autoware::behavior_path_planner::utils::lane_change @@ -1246,6 +1250,43 @@ bool filter_target_lane_objects( return false; } +std::vector get_preceding_lanes(const CommonDataPtr & common_data_ptr) +{ + const auto & route_handler_ptr = common_data_ptr->route_handler_ptr; + const auto & target_lanes = common_data_ptr->lanes_ptr->target; + const auto & ego_pose = common_data_ptr->get_ego_pose(); + const auto backward_lane_length = common_data_ptr->lc_param_ptr->backward_lane_length; + + const auto preceding_lanes_list = + utils::getPrecedingLanelets(*route_handler_ptr, target_lanes, ego_pose, backward_lane_length); + + const auto & current_lanes = common_data_ptr->lanes_ptr->current; + std::unordered_set current_lanes_id; + for (const auto & lane : current_lanes) { + current_lanes_id.insert(lane.id()); + } + const auto is_overlapping = [&](const lanelet::ConstLanelet & lane) { + return current_lanes_id.find(lane.id()) != current_lanes_id.end(); + }; + + std::vector non_overlapping_lanes_vec; + for (const auto & lanes : preceding_lanes_list) { + auto lanes_reversed = lanes | ranges::views::reverse; + auto overlapped_itr = ranges::find_if(lanes_reversed, is_overlapping); + + if (overlapped_itr == lanes_reversed.begin()) { + continue; + } + + // Lanes are not reversed by default. Avoid returning reversed lanes to prevent undefined + // behavior. + lanelet::ConstLanelets non_overlapping_lanes(overlapped_itr.base(), lanes.end()); + non_overlapping_lanes_vec.push_back(non_overlapping_lanes); + } + + return non_overlapping_lanes_vec; +} + bool object_path_overlaps_lanes( const ExtendedPredictedObject & object, const lanelet::BasicPolygon2d & lanes_polygon) { From cccbcef3210b55700ca24fab92108af1286faabe Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 12 Dec 2024 17:39:23 +0900 Subject: [PATCH 005/334] refactor(lane_change): separate structs to different folders (#9625) Signed-off-by: Zulfaqar Azmi --- .../{utils => }/base_class.hpp | 24 +++++++++---------- .../interface.hpp | 6 ++--- .../manager.hpp | 2 +- .../scene.hpp | 4 ++-- .../data_structs.hpp => structs/data.hpp} | 15 ++++++------ .../debug_structs.hpp => structs/debug.hpp} | 10 ++++---- .../{utils => structs}/parameters.hpp | 6 ++--- .../{utils => structs}/path.hpp | 17 +++++++------ .../utils/calculation.hpp | 2 +- .../utils/markers.hpp | 4 ++-- .../utils/utils.hpp | 4 ++-- .../src/scene.cpp | 2 +- .../src/utils/markers.cpp | 1 - .../src/utils/utils.cpp | 4 ++-- .../test/test_lane_change_scene.cpp | 2 +- .../test/test_lane_change_utils.cpp | 2 +- 16 files changed, 52 insertions(+), 53 deletions(-) rename planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/{utils => }/base_class.hpp (93%) rename planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/{utils/data_structs.hpp => structs/data.hpp} (95%) rename planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/{utils/debug_structs.hpp => structs/debug.hpp} (87%) rename planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/{utils => structs}/parameters.hpp (95%) rename planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/{utils => structs}/path.hpp (78%) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/base_class.hpp similarity index 93% rename from planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp rename to planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/base_class.hpp index 741b5afb50e08..5317b94db2d6b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/base_class.hpp @@ -11,12 +11,12 @@ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__BASE_CLASS_HPP_ -#define AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__BASE_CLASS_HPP_ +#ifndef AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__BASE_CLASS_HPP_ +#define AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__BASE_CLASS_HPP_ -#include "autoware/behavior_path_lane_change_module/utils/data_structs.hpp" -#include "autoware/behavior_path_lane_change_module/utils/debug_structs.hpp" -#include "autoware/behavior_path_lane_change_module/utils/path.hpp" +#include "autoware/behavior_path_lane_change_module/structs/data.hpp" +#include "autoware/behavior_path_lane_change_module/structs/debug.hpp" +#include "autoware/behavior_path_lane_change_module/structs/path.hpp" #include "autoware/behavior_path_lane_change_module/utils/utils.hpp" #include "autoware/behavior_path_planner_common/interface/scene_module_interface.hpp" #include "autoware/behavior_path_planner_common/turn_signal_decider.hpp" @@ -276,20 +276,20 @@ class LaneChangeBase } } - LaneChangeStatus status_{}; + LaneChangeStatus status_; PathShifter path_shifter_{}; LaneChangeStates current_lane_change_state_{}; - std::shared_ptr lane_change_parameters_{}; - std::shared_ptr abort_path_{}; - std::shared_ptr planner_data_{}; - lane_change::CommonDataPtr common_data_ptr_{}; + std::shared_ptr lane_change_parameters_; + std::shared_ptr abort_path_; + std::shared_ptr planner_data_; + lane_change::CommonDataPtr common_data_ptr_; FilteredLanesObjects filtered_objects_{}; BehaviorModuleOutput prev_module_output_{}; std::optional lane_change_stop_pose_{std::nullopt}; - PathWithLaneId prev_approved_path_{}; + PathWithLaneId prev_approved_path_; int unsafe_hysteresis_count_{0}; bool is_abort_path_approved_{false}; @@ -311,4 +311,4 @@ class LaneChangeBase friend class ::TestNormalLaneChange; }; } // namespace autoware::behavior_path_planner -#endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__BASE_CLASS_HPP_ +#endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__BASE_CLASS_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp index 07920f83fd980..9d6fbd65acfd8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp @@ -15,10 +15,10 @@ #ifndef AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__INTERFACE_HPP_ #define AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__INTERFACE_HPP_ +#include "autoware/behavior_path_lane_change_module/base_class.hpp" #include "autoware/behavior_path_lane_change_module/scene.hpp" -#include "autoware/behavior_path_lane_change_module/utils/base_class.hpp" -#include "autoware/behavior_path_lane_change_module/utils/data_structs.hpp" -#include "autoware/behavior_path_lane_change_module/utils/path.hpp" +#include "autoware/behavior_path_lane_change_module/structs/data.hpp" +#include "autoware/behavior_path_lane_change_module/structs/path.hpp" #include "autoware/behavior_path_planner_common/interface/scene_module_interface.hpp" #include "autoware/behavior_path_planner_common/turn_signal_decider.hpp" #include "autoware/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/manager.hpp index 2a1862de6a27e..124579735e5d8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/manager.hpp @@ -15,7 +15,7 @@ #ifndef AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__MANAGER_HPP_ #define AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__MANAGER_HPP_ -#include "autoware/behavior_path_lane_change_module/utils/data_structs.hpp" +#include "autoware/behavior_path_lane_change_module/structs/data.hpp" #include "autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp" #include "autoware/route_handler/route_handler.hpp" diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp index 7202a1c6a9108..9bf66722dcec2 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp @@ -14,8 +14,8 @@ #ifndef AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__SCENE_HPP_ #define AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__SCENE_HPP_ -#include "autoware/behavior_path_lane_change_module/utils/base_class.hpp" -#include "autoware/behavior_path_lane_change_module/utils/data_structs.hpp" +#include "autoware/behavior_path_lane_change_module/base_class.hpp" +#include "autoware/behavior_path_lane_change_module/structs/data.hpp" #include #include diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp similarity index 95% rename from planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp rename to planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp index c121ab8512cce..4dcb1c7b685d0 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp @@ -11,10 +11,10 @@ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__DATA_STRUCTS_HPP_ -#define AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__DATA_STRUCTS_HPP_ +#ifndef AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__STRUCTS__DATA_HPP_ +#define AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__STRUCTS__DATA_HPP_ -#include "autoware/behavior_path_lane_change_module/utils/parameters.hpp" +#include "autoware/behavior_path_lane_change_module/structs/parameters.hpp" #include "autoware/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "autoware/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" @@ -72,6 +72,7 @@ struct PhaseMetrics double actual_lon_accel{0.0}; double lat_accel{0.0}; + PhaseMetrics() = default; PhaseMetrics( const double _duration, const double _length, const double _velocity, const double _sampled_lon_accel, const double _actual_lon_accel, const double _lat_accel) @@ -103,10 +104,10 @@ struct Info PhaseInfo duration{0.0, 0.0}; PhaseInfo length{0.0, 0.0}; - Pose lane_changing_start{}; - Pose lane_changing_end{}; + Pose lane_changing_start; + Pose lane_changing_end; - ShiftLine shift_line{}; + ShiftLine shift_line; double lateral_acceleration{0.0}; double terminal_lane_changing_velocity{0.0}; @@ -294,4 +295,4 @@ using FilteredLanesObjects = lane_change::FilteredLanesObjects; using LateralAccelerationMap = lane_change::LateralAccelerationMap; } // namespace autoware::behavior_path_planner -#endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__DATA_STRUCTS_HPP_ +#endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__STRUCTS__DATA_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/debug_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp similarity index 87% rename from planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/debug_structs.hpp rename to planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp index a28b8523a75c7..ea9807ad1616f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/debug_structs.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp @@ -11,11 +11,11 @@ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__DEBUG_STRUCTS_HPP_ -#define AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__DEBUG_STRUCTS_HPP_ +#ifndef AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__STRUCTS__DEBUG_HPP_ +#define AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__STRUCTS__DEBUG_HPP_ -#include "autoware/behavior_path_lane_change_module/utils/data_structs.hpp" -#include "autoware/behavior_path_lane_change_module/utils/path.hpp" +#include "autoware/behavior_path_lane_change_module/structs/data.hpp" +#include "autoware/behavior_path_lane_change_module/structs/path.hpp" #include @@ -76,4 +76,4 @@ struct Debug }; } // namespace autoware::behavior_path_planner::lane_change -#endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__DEBUG_STRUCTS_HPP_ +#endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__STRUCTS__DEBUG_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/parameters.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp similarity index 95% rename from planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/parameters.hpp rename to planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp index a76742307e061..719bbbbf3057a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/parameters.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PARAMETERS_HPP_ -#define AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PARAMETERS_HPP_ +#ifndef AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__STRUCTS__PARAMETERS_HPP_ +#define AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__STRUCTS__PARAMETERS_HPP_ #include "autoware/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" @@ -177,4 +177,4 @@ struct Parameters } // namespace autoware::behavior_path_planner::lane_change -#endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PARAMETERS_HPP_ +#endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__STRUCTS__PARAMETERS_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/path.hpp similarity index 78% rename from planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp rename to planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/path.hpp index 5623f03a22eb3..0fa0a9d977a26 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/path.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PATH_HPP_ -#define AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PATH_HPP_ +#ifndef AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__STRUCTS__PATH_HPP_ +#define AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__STRUCTS__PATH_HPP_ -#include "autoware/behavior_path_lane_change_module/utils/data_structs.hpp" +#include "autoware/behavior_path_lane_change_module/structs/data.hpp" #include "autoware/behavior_path_planner_common/turn_signal_decider.hpp" #include "autoware/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" @@ -29,19 +29,18 @@ using autoware::behavior_path_planner::TurnSignalInfo; using tier4_planning_msgs::msg::PathWithLaneId; struct Path { - PathWithLaneId path{}; - ShiftedPath shifted_path{}; - Info info{}; + PathWithLaneId path; + ShiftedPath shifted_path; + Info info; }; struct Status { - Path lane_change_path{}; + Path lane_change_path; bool is_safe{false}; bool is_valid_path{false}; double start_distance{0.0}; }; - } // namespace autoware::behavior_path_planner::lane_change namespace autoware::behavior_path_planner @@ -50,4 +49,4 @@ using LaneChangePath = lane_change::Path; using LaneChangePaths = std::vector; using LaneChangeStatus = lane_change::Status; } // namespace autoware::behavior_path_planner -#endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PATH_HPP_ +#endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__STRUCTS__PATH_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp index 29047c90590b3..eced227a5be32 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp @@ -14,7 +14,7 @@ #ifndef AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__CALCULATION_HPP_ #define AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__CALCULATION_HPP_ -#include "autoware/behavior_path_lane_change_module/utils/data_structs.hpp" +#include "autoware/behavior_path_lane_change_module/structs/data.hpp" #include diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/markers.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/markers.hpp index c95b388a2e4a4..4c2712f053b13 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/markers.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/markers.hpp @@ -15,8 +15,8 @@ #ifndef AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__MARKERS_HPP_ #define AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__MARKERS_HPP_ -#include "autoware/behavior_path_lane_change_module/utils/debug_structs.hpp" -#include "autoware/behavior_path_lane_change_module/utils/path.hpp" +#include "autoware/behavior_path_lane_change_module/structs/debug.hpp" +#include "autoware/behavior_path_lane_change_module/structs/path.hpp" #include "autoware/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp index 1386c60d29aea..0adb9409fb4b0 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp @@ -15,8 +15,8 @@ #ifndef AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__UTILS_HPP_ #define AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__UTILS_HPP_ -#include "autoware/behavior_path_lane_change_module/utils/data_structs.hpp" -#include "autoware/behavior_path_lane_change_module/utils/path.hpp" +#include "autoware/behavior_path_lane_change_module/structs/data.hpp" +#include "autoware/behavior_path_lane_change_module/structs/path.hpp" #include "autoware/behavior_path_planner_common/parameters.hpp" #include "autoware/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "autoware/behavior_path_planner_common/utils/utils.hpp" diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index 5b8b8966f965b..a1c2d8467d1fc 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -681,7 +681,7 @@ void NormalLaneChange::resetParameters() is_abort_approval_requested_ = false; current_lane_change_state_ = LaneChangeStates::Normal; abort_path_ = nullptr; - status_ = {}; + status_ = LaneChangeStatus(); unsafe_hysteresis_count_ = 0; lane_change_debug_.reset(); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp index ff0bd4437c21c..c7514fea01535 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp @@ -14,7 +14,6 @@ #include "autoware/behavior_path_planner_common/marker_utils/colors.hpp" #include "autoware/behavior_path_planner_common/marker_utils/utils.hpp" -#include "autoware/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" #include #include diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp index 13a119848a87a..2b1c744a926e3 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp @@ -14,8 +14,8 @@ #include "autoware/behavior_path_lane_change_module/utils/utils.hpp" -#include "autoware/behavior_path_lane_change_module/utils/data_structs.hpp" -#include "autoware/behavior_path_lane_change_module/utils/path.hpp" +#include "autoware/behavior_path_lane_change_module/structs/data.hpp" +#include "autoware/behavior_path_lane_change_module/structs/path.hpp" #include "autoware/behavior_path_planner_common/parameters.hpp" #include "autoware/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp" #include "autoware/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp index ea36e4dc6960a..96b24d5aa9a9e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp @@ -14,7 +14,7 @@ #include "autoware/behavior_path_lane_change_module/manager.hpp" #include "autoware/behavior_path_lane_change_module/scene.hpp" -#include "autoware/behavior_path_lane_change_module/utils/data_structs.hpp" +#include "autoware/behavior_path_lane_change_module/structs/data.hpp" #include "autoware/behavior_path_planner_common/data_manager.hpp" #include "autoware_test_utils/autoware_test_utils.hpp" #include "autoware_test_utils/mock_data_parser.hpp" diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_utils.cpp index 68547a491324d..147a53672f30a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_utils.cpp @@ -11,7 +11,7 @@ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware/behavior_path_lane_change_module/utils/data_structs.hpp" +#include "autoware/behavior_path_lane_change_module/structs/data.hpp" #include #include From a1dad4467c5a56faab7d41aee8231add06a84957 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Thu, 12 Dec 2024 17:59:03 +0900 Subject: [PATCH 006/334] fix(tier4_simulator_launch): add use_validator argument to simulator launch (#9634) * feat: add use_validator argument to simulator launch Signed-off-by: Taekjin LEE * feat: set variables explicitly Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE --- launch/tier4_simulator_launch/launch/simulator.launch.xml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/launch/tier4_simulator_launch/launch/simulator.launch.xml b/launch/tier4_simulator_launch/launch/simulator.launch.xml index 4b2cefa02c2fa..73b00adf923be 100644 --- a/launch/tier4_simulator_launch/launch/simulator.launch.xml +++ b/launch/tier4_simulator_launch/launch/simulator.launch.xml @@ -89,6 +89,9 @@ + + + From 1d9a2beb73d02fc114f5d046028292acc1d85da5 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Thu, 12 Dec 2024 19:00:57 +0900 Subject: [PATCH 007/334] fix(autoware_overlay_rviz_plugin): fix clang-tidy errors (#9627) * fix: clang-tidy errors Signed-off-by: kobayu858 * fix: clang-fmt Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../autoware_overlay_rviz_plugin/src/speed_display.cpp | 8 +++++--- .../src/steering_wheel_display.cpp | 2 +- .../autoware_overlay_rviz_plugin/src/traffic_display.cpp | 3 --- .../src/turn_signals_display.cpp | 2 +- 4 files changed, 7 insertions(+), 8 deletions(-) diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_display.cpp b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_display.cpp index faf9c39af672d..83d7f2f76bde3 100644 --- a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_display.cpp +++ b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_display.cpp @@ -84,7 +84,8 @@ void SpeedDisplay::drawSpeedDisplay( painter.setFont(referenceFont); QRect referenceRect = painter.fontMetrics().boundingRect("88"); QPointF referencePos( - backgroundRect.width() / 2 - referenceRect.width() / 2 - 5, backgroundRect.height() / 2); + backgroundRect.width() / 2.0 - referenceRect.width() / 2.0 - 5.0, + backgroundRect.height() / 2.0); QString speedNumber = QString::number(current_speed_, 'f', 0); int fontSize = 40; @@ -96,7 +97,7 @@ void SpeedDisplay::drawSpeedDisplay( // Center the speed number in the backgroundRect QPointF speedPos( - backgroundRect.center().x() - speedNumberRect.width() / 2, + backgroundRect.center().x() - speedNumberRect.width() / 2.0, backgroundRect.center().y() + speedNumberRect.bottom()); painter.setPen(color); painter.drawText(speedPos, speedNumber); @@ -106,7 +107,8 @@ void SpeedDisplay::drawSpeedDisplay( QString speedUnit = "km/h"; QRect unitRect = painter.fontMetrics().boundingRect(speedUnit); QPointF unitPos( - (backgroundRect.width() / 2 - unitRect.width() / 2), referencePos.y() + unitRect.height() + 15); + (backgroundRect.width() / 2.0 - unitRect.width() / 2.0), + referencePos.y() + unitRect.height() + 15.0); painter.drawText(unitPos, speedUnit); } diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/steering_wheel_display.cpp b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/steering_wheel_display.cpp index d475a8231e595..fec3ecfb90a43 100644 --- a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/steering_wheel_display.cpp +++ b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/steering_wheel_display.cpp @@ -93,7 +93,7 @@ void SteeringWheelDisplay::drawSteeringWheel( QImage rotatedWheel = wheel.transformed(rotationTransform, Qt::SmoothTransformation); QPointF drawPoint( - wheelCenterX - rotatedWheel.width() / 2, wheelCenterY - rotatedWheel.height() / 2); + wheelCenterX - rotatedWheel.width() / 2.0, wheelCenterY - rotatedWheel.height() / 2.0); // Draw the rotated image painter.drawImage(drawPoint.x(), drawPoint.y(), rotatedWheel); diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/traffic_display.cpp b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/traffic_display.cpp index dddd9b52f3d0b..817d49889162a 100644 --- a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/traffic_display.cpp +++ b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/traffic_display.cpp @@ -83,9 +83,6 @@ void TrafficDisplay::drawTrafficLightIndicator(QPainter & painter, const QRectF painter.drawEllipse(circleRect); break; case 4: - painter.setBrush(tl_gray_); - painter.drawEllipse(circleRect); - break; default: painter.setBrush(tl_gray_); painter.drawEllipse(circleRect); diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/turn_signals_display.cpp b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/turn_signals_display.cpp index 6748f01fe139b..ef0721d821e63 100644 --- a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/turn_signals_display.cpp +++ b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/turn_signals_display.cpp @@ -76,7 +76,7 @@ void TurnSignalsDisplay::drawArrows( QImage scaledLeftArrow = arrowImage.scaled(50, 32, Qt::KeepAspectRatio, Qt::SmoothTransformation); scaledLeftArrow = coloredImage(scaledLeftArrow, gray); QImage scaledRightArrow = scaledLeftArrow.mirrored(true, false); - int arrowYPos = (backgroundRect.height() / 2 - scaledLeftArrow.height() / 2 - 4); + int arrowYPos = (backgroundRect.height() / 2.0 - scaledLeftArrow.height() / 2.0 - 4.0); int leftArrowXPos = backgroundRect.left() + scaledLeftArrow.width() * 2 + 180; int rightArrowXPos = backgroundRect.right() - scaledRightArrow.width() * 3 - 175; From 46cfadbe7397501e7669eda24bd9cde25e242039 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Thu, 12 Dec 2024 19:01:54 +0900 Subject: [PATCH 008/334] fix(tier4_state_rviz_plugin): fix bugprone-integer-division (#9628) fix: bugprone-integer-division Signed-off-by: kobayu858 --- visualization/tier4_state_rviz_plugin/src/custom_container.cpp | 2 +- visualization/tier4_state_rviz_plugin/src/custom_icon_label.cpp | 2 +- .../tier4_state_rviz_plugin/src/custom_segmented_button.cpp | 2 +- .../src/custom_segmented_button_item.cpp | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/visualization/tier4_state_rviz_plugin/src/custom_container.cpp b/visualization/tier4_state_rviz_plugin/src/custom_container.cpp index 681cebbefd492..5f0895ddae9e7 100644 --- a/visualization/tier4_state_rviz_plugin/src/custom_container.cpp +++ b/visualization/tier4_state_rviz_plugin/src/custom_container.cpp @@ -51,7 +51,7 @@ void CustomContainer::paintEvent(QPaintEvent *) // Draw background QPainterPath path; - path.addRoundedRect(rect(), height() / 2, height() / 2); // Use height for rounded corners + path.addRoundedRect(rect(), height() / 2.0, height() / 2.0); // Use height for rounded corners painter.setPen(Qt::NoPen); painter.setBrush(QColor( autoware::state_rviz_plugin::colors::default_colors.surface.c_str())); // Background color diff --git a/visualization/tier4_state_rviz_plugin/src/custom_icon_label.cpp b/visualization/tier4_state_rviz_plugin/src/custom_icon_label.cpp index 6e4d32d40f7fb..e01d2904ffbd2 100644 --- a/visualization/tier4_state_rviz_plugin/src/custom_icon_label.cpp +++ b/visualization/tier4_state_rviz_plugin/src/custom_icon_label.cpp @@ -65,7 +65,7 @@ void CustomIconLabel::paintEvent(QPaintEvent *) // Draw background circle QPainterPath path; - path.addEllipse(width() / 2 - radius, height() / 2 - radius, diameter, diameter); + path.addEllipse(width() / 2.0 - radius, height() / 2.0 - radius, diameter, diameter); painter.setPen(Qt::NoPen); painter.setBrush(backgroundColor); painter.drawPath(path); diff --git a/visualization/tier4_state_rviz_plugin/src/custom_segmented_button.cpp b/visualization/tier4_state_rviz_plugin/src/custom_segmented_button.cpp index 8063bdc0fbc28..87b4f7dba4653 100644 --- a/visualization/tier4_state_rviz_plugin/src/custom_segmented_button.cpp +++ b/visualization/tier4_state_rviz_plugin/src/custom_segmented_button.cpp @@ -66,7 +66,7 @@ void CustomSegmentedButton::paintEvent(QPaintEvent *) // Draw background QPainterPath path; - path.addRoundedRect(rect(), height() / 2, height() / 2); + path.addRoundedRect(rect(), height() / 2.0, height() / 2.0); painter.setPen(Qt::NoPen); painter.setBrush( diff --git a/visualization/tier4_state_rviz_plugin/src/custom_segmented_button_item.cpp b/visualization/tier4_state_rviz_plugin/src/custom_segmented_button_item.cpp index cdd3aa0d25263..192b1cbfa86f5 100644 --- a/visualization/tier4_state_rviz_plugin/src/custom_segmented_button_item.cpp +++ b/visualization/tier4_state_rviz_plugin/src/custom_segmented_button_item.cpp @@ -125,7 +125,7 @@ void CustomSegmentedButtonItem::paintEvent(QPaintEvent *) } QPainterPath path; - double radius = (height() - 2) / 2; + double radius = (height() - 2.0) / 2.0; path.setFillRule(Qt::WindingFill); if (isFirstButton) { From 413805a0738e4b8aecb190d08bf7eaeafe7f8eaf Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Thu, 12 Dec 2024 19:02:12 +0900 Subject: [PATCH 009/334] fix(autoware_pid_longitudinal_controller): fix bugprone-branch-clone (#9629) fix: bugprone-branch-clone Signed-off-by: kobayu858 --- .../src/smooth_stop.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/control/autoware_pid_longitudinal_controller/src/smooth_stop.cpp b/control/autoware_pid_longitudinal_controller/src/smooth_stop.cpp index cb87157fe1114..9ee4763c6c05f 100644 --- a/control/autoware_pid_longitudinal_controller/src/smooth_stop.cpp +++ b/control/autoware_pid_longitudinal_controller/src/smooth_stop.cpp @@ -140,9 +140,9 @@ double SmoothStop::calculate( // when the car is running if (is_running) { // when the car will not stop in a certain time - if (time_to_stop && *time_to_stop > m_params.weak_stop_time + delay_time) { - return m_strong_acc; - } else if (!time_to_stop && is_fast_vel) { + if ( + (time_to_stop && *time_to_stop > m_params.weak_stop_time + delay_time) || + (!time_to_stop && is_fast_vel)) { return m_strong_acc; } From e8ea100332028f463de7ab215da5d433ff20952f Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Thu, 12 Dec 2024 19:02:40 +0900 Subject: [PATCH 010/334] fix(perception_online_evaluator): fix bugprone-branch-clone (#9631) fix: bugprone-branch-clone Signed-off-by: kobayu858 --- .../src/metrics/detection_count.cpp | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/evaluator/perception_online_evaluator/src/metrics/detection_count.cpp b/evaluator/perception_online_evaluator/src/metrics/detection_count.cpp index 4a1d97aeeb90b..1bbfb9e3ee963 100644 --- a/evaluator/perception_online_evaluator/src/metrics/detection_count.cpp +++ b/evaluator/perception_online_evaluator/src/metrics/detection_count.cpp @@ -110,10 +110,9 @@ void DetectionCounter::initializeDetectionMap() ++i) { for (const auto & range : getRanges()) { std::string range_str = range.toString(); - if (time_series_counts_.find(i) == time_series_counts_.end()) { - time_series_counts_[i][range_str] = std::vector(); - seen_uuids_[i][range_str] = std::set(); - } else if (time_series_counts_[i].find(range_str) == time_series_counts_[i].end()) { + if ( + time_series_counts_[i].find(range_str) == time_series_counts_[i].end() || + time_series_counts_.find(i) == time_series_counts_.end()) { time_series_counts_[i][range_str] = std::vector(); seen_uuids_[i][range_str] = std::set(); } From c77f1b923c8465a1bd32bf49945d2f27d04dadcb Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Fri, 13 Dec 2024 01:26:17 +0300 Subject: [PATCH 011/334] ci(build-and-test): set concurrency to sequential and remove workflow_dispatch (#9638) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .github/workflows/build-and-test.yaml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index 6b3886f124a44..60567d18b6beb 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -4,11 +4,11 @@ on: push: branches: - main - workflow_dispatch: concurrency: - group: ${{ github.workflow }}-${{ github.event.pull_request.number || github.run_id }} - cancel-in-progress: true + # Ensures sequential execution of this workflow + group: ${{ github.workflow }} + cancel-in-progress: false env: CC: /usr/lib/ccache/gcc From 2127ca81d7631f098dd63de08b67bebb9c47d811 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Fri, 13 Dec 2024 03:29:15 +0300 Subject: [PATCH 012/334] build(autoware_freespace_planning_algorithms): increase test timeout to 2 mins (#9639) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- planning/autoware_freespace_planning_algorithms/CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/autoware_freespace_planning_algorithms/CMakeLists.txt b/planning/autoware_freespace_planning_algorithms/CMakeLists.txt index 5b6013528f7fc..7ac50842d21e3 100644 --- a/planning/autoware_freespace_planning_algorithms/CMakeLists.txt +++ b/planning/autoware_freespace_planning_algorithms/CMakeLists.txt @@ -34,6 +34,7 @@ if(BUILD_TESTING) ament_add_ros_isolated_gtest(${PROJECT_NAME}-test test/src/test_freespace_planning_algorithms.cpp ) + set_tests_properties(${PROJECT_NAME}-test PROPERTIES TIMEOUT 120) target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME} ) From 86ba21f14dc31b53c7c06aba8644651ce120812a Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> Date: Fri, 13 Dec 2024 15:17:05 +0900 Subject: [PATCH 013/334] test(autoware_behavior_path_start_planner_module): add unit tests for geometric shift pull out planner (#9640) * feat(behavior_path_planner): add unit tests for geometric pull-out planner and improve collision check Signed-off-by: kyoichi-sugahara * feat(behavior_path_planner): add boolean parameter for divide_pull_out_path and update tests Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- .../CMakeLists.txt | 11 + .../geometric_pull_out.hpp | 2 + .../src/pull_out_planner_base.cpp | 3 + .../test/test_geometric_pull_out.cpp | 229 ++++++++++++++++++ 4 files changed, 245 insertions(+) create mode 100644 planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_geometric_pull_out.cpp diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/CMakeLists.txt b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/CMakeLists.txt index 2da3051702103..3fa8ad7218fa2 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/CMakeLists.txt +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/CMakeLists.txt @@ -15,4 +15,15 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/util.cpp ) +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() + file(GLOB_RECURSE TEST_SOURCES test/*.cpp) + ament_add_ros_isolated_gtest(test_${PROJECT_NAME} + ${TEST_SOURCES} + ) + target_link_libraries(test_${PROJECT_NAME} ${PROJECT_NAME}) +endif() + + ament_auto_package(INSTALL_TO_SHARE config) diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/geometric_pull_out.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/geometric_pull_out.hpp index 70ca2bdb10d37..18d1f3c3b9b81 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/geometric_pull_out.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/geometric_pull_out.hpp @@ -45,6 +45,8 @@ class GeometricPullOut : public PullOutPlannerBase GeometricParallelParking planner_; ParallelParkingParameters parallel_parking_parameters_; std::shared_ptr lane_departure_checker_; + + friend class TestGeometricPullOut; }; } // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/pull_out_planner_base.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/pull_out_planner_base.cpp index f7713ea2e91b2..42c5bead33604 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/pull_out_planner_base.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/pull_out_planner_base.cpp @@ -24,6 +24,9 @@ bool PullOutPlannerBase::isPullOutPathCollided( // check for collisions const auto & dynamic_objects = planner_data_->dynamic_object; + if (!dynamic_objects) { + return false; + } const auto pull_out_lanes = start_planner_utils::getPullOutLanes( planner_data_, planner_data_->parameters.backward_path_length + parameters_.max_back_distance); // extract stop objects in pull out lane for collision check diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_geometric_pull_out.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_geometric_pull_out.cpp new file mode 100644 index 0000000000000..fb39e186afd4e --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_geometric_pull_out.cpp @@ -0,0 +1,229 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include +#include + +using autoware::behavior_path_planner::GeometricPullOut; +using autoware::behavior_path_planner::StartPlannerParameters; +using autoware::lane_departure_checker::LaneDepartureChecker; +using autoware::test_utils::get_absolute_path_to_config; +using autoware_planning_msgs::msg::LaneletRoute; +using RouteSections = std::vector; +using autoware_planning_test_manager::utils::makeBehaviorRouteFromLaneId; + +namespace autoware::behavior_path_planner +{ + +class TestGeometricPullOut : public ::testing::Test +{ +public: + std::optional plan( + const Pose & start_pose, const Pose & goal_pose, PlannerDebugData & planner_debug_data) + { + return geometric_pull_out_->plan(start_pose, goal_pose, planner_debug_data); + } + +protected: + void SetUp() override + { + rclcpp::init(0, nullptr); + node_ = rclcpp::Node::make_shared("geometric_pull_out", get_node_options()); + + load_parameters(); + initialize_vehicle_info(); + initialize_lane_departure_checker(); + initialize_routeHandler(); + initialize_geometric_pull_out_planner(); + initialize_planner_data(); + } + + void TearDown() override { rclcpp::shutdown(); } + // Member variables + std::shared_ptr node_; + std::shared_ptr route_handler_; + autoware::vehicle_info_utils::VehicleInfo vehicle_info_; + std::shared_ptr geometric_pull_out_; + std::shared_ptr lane_departure_checker_; + PlannerData planner_data_; + +private: + rclcpp::NodeOptions get_node_options() const + { + // Load common configuration files + auto node_options = rclcpp::NodeOptions{}; + + const auto common_param_path = + get_absolute_path_to_config("autoware_test_utils", "test_common.param.yaml"); + const auto nearest_search_param_path = + get_absolute_path_to_config("autoware_test_utils", "test_nearest_search.param.yaml"); + const auto vehicle_info_param_path = + get_absolute_path_to_config("autoware_test_utils", "test_vehicle_info.param.yaml"); + const auto behavior_path_planner_param_path = get_absolute_path_to_config( + "autoware_behavior_path_planner", "behavior_path_planner.param.yaml"); + const auto drivable_area_expansion_param_path = get_absolute_path_to_config( + "autoware_behavior_path_planner", "drivable_area_expansion.param.yaml"); + const auto scene_module_manager_param_path = get_absolute_path_to_config( + "autoware_behavior_path_planner", "scene_module_manager.param.yaml"); + const auto start_planner_param_path = get_absolute_path_to_config( + "autoware_behavior_path_start_planner_module", "start_planner.param.yaml"); + + autoware::test_utils::updateNodeOptions( + node_options, {common_param_path, nearest_search_param_path, vehicle_info_param_path, + behavior_path_planner_param_path, drivable_area_expansion_param_path, + scene_module_manager_param_path, start_planner_param_path}); + + return node_options; + } + + void load_parameters() + { + const auto dp_double = [&](const std::string & s) { + return node_->declare_parameter(s); + }; + const auto dp_bool = [&](const std::string & s) { return node_->declare_parameter(s); }; + // Load parameters required for planning + const std::string ns = "start_planner."; + lane_departure_check_expansion_margin_ = + dp_double(ns + "lane_departure_check_expansion_margin"); + pull_out_max_steer_angle_ = dp_double(ns + "pull_out_max_steer_angle"); + pull_out_arc_path_interval_ = dp_double(ns + "arc_path_interval"); + center_line_path_interval_ = dp_double(ns + "center_line_path_interval"); + th_moving_object_velocity_ = dp_double(ns + "th_moving_object_velocity"); + divide_pull_out_path_ = dp_bool(ns + "divide_pull_out_path"); + backward_path_length_ = dp_double("backward_path_length"); + forward_path_length_ = dp_double("forward_path_length"); + } + + void initialize_vehicle_info() + { + vehicle_info_ = autoware::vehicle_info_utils::VehicleInfoUtils(*node_).getVehicleInfo(); + } + + void initialize_lane_departure_checker() + { + lane_departure_checker_ = std::make_shared(); + lane_departure_checker_->setVehicleInfo(vehicle_info_); + + autoware::lane_departure_checker::Param lane_departure_checker_params{}; + lane_departure_checker_params.footprint_extra_margin = lane_departure_check_expansion_margin_; + lane_departure_checker_->setParam(lane_departure_checker_params); + } + + void initialize_routeHandler() + { + // Load a sample lanelet map and create a route handler + const auto shoulder_map_path = autoware::test_utils::get_absolute_path_to_lanelet_map( + "autoware_test_utils", "road_shoulder/lanelet2_map.osm"); + const auto map_bin_msg = autoware::test_utils::make_map_bin_msg(shoulder_map_path, 0.5); + + route_handler_ = std::make_shared(map_bin_msg); + } + + void initialize_geometric_pull_out_planner() + { + auto parameters = std::make_shared(); + parameters->parallel_parking_parameters.pull_out_max_steer_angle = pull_out_max_steer_angle_; + parameters->parallel_parking_parameters.pull_out_arc_path_interval = + pull_out_arc_path_interval_; + parameters->parallel_parking_parameters.center_line_path_interval = center_line_path_interval_; + parameters->th_moving_object_velocity = th_moving_object_velocity_; + parameters->divide_pull_out_path = divide_pull_out_path_; + + auto time_keeper = std::make_shared(); + geometric_pull_out_ = + std::make_shared(*node_, *parameters, lane_departure_checker_, time_keeper); + } + + void initialize_planner_data() + { + planner_data_.parameters.backward_path_length = backward_path_length_; + planner_data_.parameters.forward_path_length = forward_path_length_; + planner_data_.parameters.wheel_base = vehicle_info_.wheel_base_m; + planner_data_.parameters.wheel_tread = vehicle_info_.wheel_tread_m; + planner_data_.parameters.front_overhang = vehicle_info_.front_overhang_m; + planner_data_.parameters.left_over_hang = vehicle_info_.left_overhang_m; + planner_data_.parameters.right_over_hang = vehicle_info_.right_overhang_m; + } + + // Parameter variables + double lane_departure_check_expansion_margin_{0.0}; + double pull_out_max_steer_angle_{0.0}; + double pull_out_arc_path_interval_{0.0}; + double center_line_path_interval_{0.0}; + double th_moving_object_velocity_{0.0}; + double backward_path_length_{0.0}; + double forward_path_length_{0.0}; + bool divide_pull_out_path_{false}; +}; + +TEST_F(TestGeometricPullOut, GenerateValidGeometricPullOutPath) +{ + const auto start_pose = + geometry_msgs::build() + .position(geometry_msgs::build().x(362.181).y(362.164).z(100.000)) + .orientation( + geometry_msgs::build().x(0.0).y(0.0).z(0.709650).w( + 0.704554)); + + const auto goal_pose = + geometry_msgs::build() + .position(geometry_msgs::build().x(365.658).y(507.253).z(100.000)) + .orientation( + geometry_msgs::build().x(0.0).y(0.0).z(0.705897).w( + 0.708314)); + + // Set up current odometry at start pose + auto odometry = std::make_shared(); + odometry->pose.pose = start_pose; + odometry->header.frame_id = "map"; + planner_data_.self_odometry = odometry; + + // Setup route + const auto route = makeBehaviorRouteFromLaneId( + 4619, 4635, "autoware_test_utils", "road_shoulder/lanelet2_map.osm"); + route_handler_->setRoute(route); + + // Update planner data with the route handler + planner_data_.route_handler = route_handler_; + geometric_pull_out_->setPlannerData(std::make_shared(planner_data_)); + + // Plan the pull out path + PlannerDebugData debug_data; + auto result = plan(start_pose, goal_pose, debug_data); + + // Assert that a valid geometric geometric pull out path is generated + ASSERT_TRUE(result.has_value()) << "Geometric pull out path generation failed."; + EXPECT_EQ(result->partial_paths.size(), 2UL) + << "Generated geometric pull out path does not have the expected number of partial paths."; + EXPECT_EQ(debug_data.conditions_evaluation.back(), "success") + << "Geometric pull out path planning did not succeed."; +} + +} // namespace autoware::behavior_path_planner From fee8fe528d38d92e1dc2ccd253d4913dc721ce87 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> Date: Fri, 13 Dec 2024 19:00:52 +0900 Subject: [PATCH 014/334] ci(codecov): comment out unmaintained planning components from tier-iv-maintained-packages (#9646) chore(codecov.yaml): comment out unmaintained planning components Signed-off-by: kyoichi-sugahara --- codecov.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/codecov.yaml b/codecov.yaml index 89b40a063b0ed..7bec89dd5a552 100644 --- a/codecov.yaml +++ b/codecov.yaml @@ -202,9 +202,9 @@ component_management: - planning/autoware_path_optimizer/** - planning/autoware_path_smoother/** - planning/autoware_planning_test_manager/** - - planning/autoware_planning_topic_converter/** + # - planning/autoware_planning_topic_converter/** - planning/autoware_planning_validator/** - - planning/autoware_remaining_distance_time_calculator/** + # - planning/autoware_remaining_distance_time_calculator/** - planning/autoware_route_handler/** - planning/autoware_rtc_interface/** - planning/autoware_scenario_selector/** From 9ff1c382a0f4e2f24b35561fdd39ad75f2b71467 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Fri, 13 Dec 2024 19:50:39 +0900 Subject: [PATCH 015/334] fix(autoware_stop_filter): fix bugprone-reserved-identifier (#9643) * fix: bugprone-reserved-identifier Signed-off-by: kobayu858 * fix: fmt Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- localization/autoware_stop_filter/src/stop_filter.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/localization/autoware_stop_filter/src/stop_filter.cpp b/localization/autoware_stop_filter/src/stop_filter.cpp index f5e29419105d4..17eaafdc3002a 100644 --- a/localization/autoware_stop_filter/src/stop_filter.cpp +++ b/localization/autoware_stop_filter/src/stop_filter.cpp @@ -22,8 +22,6 @@ #include #include -using std::placeholders::_1; - namespace autoware::stop_filter { StopFilter::StopFilter(const rclcpp::NodeOptions & node_options) @@ -33,7 +31,7 @@ StopFilter::StopFilter(const rclcpp::NodeOptions & node_options) wz_threshold_ = declare_parameter("wz_threshold"); sub_odom_ = create_subscription( - "input/odom", 1, std::bind(&StopFilter::callback_odometry, this, _1)); + "input/odom", 1, std::bind(&StopFilter::callback_odometry, this, std::placeholders::_1)); pub_odom_ = create_publisher("output/odom", 1); pub_stop_flag_ = create_publisher("debug/stop_flag", 1); From 657c89477a196d9de1e3780c7c29e36033c801f2 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Sun, 15 Dec 2024 16:40:15 +0900 Subject: [PATCH 016/334] feat(goal_planner): divide Planners to isolated threads (#9514) Signed-off-by: Mamoru Sobue --- .../CMakeLists.txt | 1 + .../goal_planner_module.hpp | 194 +++--- .../thread_data.hpp | 186 +++-- .../src/goal_planner_module.cpp | 649 +++++++++--------- .../pull_over_planner/geometric_pull_over.cpp | 5 +- .../src/pull_over_planner/shift_pull_over.cpp | 2 +- .../src/thread_data.cpp | 66 ++ 7 files changed, 568 insertions(+), 535 deletions(-) create mode 100644 planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/thread_data.cpp diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/CMakeLists.txt b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/CMakeLists.txt index 8e945093659c1..d680fd2ecd695 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/CMakeLists.txt +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/CMakeLists.txt @@ -19,6 +19,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/util.cpp src/goal_planner_module.cpp src/manager.cpp + src/thread_data.cpp src/decision_state.cpp ) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp index 5e6afa16d1f9f..9dad3681f7570 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -18,9 +18,7 @@ #include "autoware/behavior_path_goal_planner_module/decision_state.hpp" #include "autoware/behavior_path_goal_planner_module/fixed_goal_planner_base.hpp" #include "autoware/behavior_path_goal_planner_module/goal_planner_parameters.hpp" -#include "autoware/behavior_path_goal_planner_module/goal_searcher.hpp" #include "autoware/behavior_path_goal_planner_module/thread_data.hpp" -#include "autoware/behavior_path_planner_common/interface/scene_module_interface.hpp" #include "autoware/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp" #include "autoware/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" @@ -89,27 +87,44 @@ struct PullOverContextData PullOverContextData() = delete; explicit PullOverContextData( const bool is_stable_safe_path, const PredictedObjects & static_objects, - const PredictedObjects & dynamic_objects, std::optional && pull_over_path_opt, - const std::vector & pull_over_path_candidates, - const PathDecisionState & prev_state) + const PredictedObjects & dynamic_objects, const PathDecisionState & prev_state, + const bool is_stopped, const LaneParkingResponse & lane_parking_response, + const FreespaceParkingResponse & freespace_parking_response) : is_stable_safe_path(is_stable_safe_path), static_target_objects(static_objects), dynamic_target_objects(dynamic_objects), - pull_over_path_opt(pull_over_path_opt), - pull_over_path_candidates(pull_over_path_candidates), prev_state_for_debug(prev_state), - last_path_idx_increment_time(std::nullopt) + is_stopped(is_stopped), + lane_parking_response(lane_parking_response), + freespace_parking_response(freespace_parking_response) { } - const bool is_stable_safe_path; - const PredictedObjects static_target_objects; - const PredictedObjects dynamic_target_objects; - // TODO(soblin): due to deceleratePath(), this cannot be const member(velocity is modified by it) + // TODO(soblin): make following variables private + bool is_stable_safe_path; + PredictedObjects static_target_objects; + PredictedObjects dynamic_target_objects; + PathDecisionState prev_state_for_debug; + bool is_stopped; + LaneParkingResponse lane_parking_response; + FreespaceParkingResponse freespace_parking_response; std::optional pull_over_path_opt; - const std::vector pull_over_path_candidates; - // TODO(soblin): goal_candidate_from_thread, modifed_goal_pose_from_thread, closest_start_pose - const PathDecisionState prev_state_for_debug; + std::optional last_path_update_time; std::optional last_path_idx_increment_time; + + void update( + const bool is_stable_safe_path_, const PredictedObjects static_target_objects_, + const PredictedObjects dynamic_target_objects_, const PathDecisionState prev_state_for_debug_, + const bool is_stopped_, const LaneParkingResponse & lane_parking_response_, + const FreespaceParkingResponse & freespace_parking_response_) + { + is_stable_safe_path = is_stable_safe_path_; + static_target_objects = static_target_objects_; + dynamic_target_objects = dynamic_target_objects_; + prev_state_for_debug = prev_state_for_debug_; + is_stopped = is_stopped_; + lane_parking_response = lane_parking_response_; + freespace_parking_response = freespace_parking_response_; + } }; bool isOnModifiedGoal( @@ -133,6 +148,11 @@ bool checkOccupancyGridCollision( const PathWithLaneId & path, const std::shared_ptr occupancy_grid_map); +// freespace parking +std::optional planFreespacePath( + const FreespaceParkingRequest & req, const PredictedObjects & static_target_objects, + std::shared_ptr freespace_planner); + bool isStopped( std::deque & odometry_buffer, const nav_msgs::msg::Odometry::ConstSharedPtr self_odometry, const double duration_lower, @@ -150,6 +170,61 @@ class ScopedFlag std::atomic & flag_; }; +class LaneParkingPlanner +{ +public: + LaneParkingPlanner( + rclcpp::Node & node, std::mutex & lane_parking_mutex, + const std::optional & request, LaneParkingResponse & response, + std::atomic & is_lane_parking_cb_running, const rclcpp::Logger & logger, + const GoalPlannerParameters & parameters); + rclcpp::Logger getLogger() const { return logger_; } + void onTimer(); + +private: + std::mutex & mutex_; + const std::optional & request_; + LaneParkingResponse & response_; + std::atomic & is_lane_parking_cb_running_; + rclcpp::Logger logger_; + + std::vector> pull_over_planners_; +}; + +class FreespaceParkingPlanner +{ +public: + FreespaceParkingPlanner( + std::mutex & freespace_parking_mutex, const std::optional & request, + FreespaceParkingResponse & response, std::atomic & is_freespace_parking_cb_running, + const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr freespace_planner) + : mutex_(freespace_parking_mutex), + request_(request), + response_(response), + is_freespace_parking_cb_running_(is_freespace_parking_cb_running), + logger_(logger), + clock_(clock), + freespace_planner_(freespace_planner) + { + } + void onTimer(); + +private: + std::mutex & mutex_; + const std::optional & request_; + FreespaceParkingResponse & response_; + std::atomic & is_freespace_parking_cb_running_; + rclcpp::Logger logger_; + rclcpp::Clock::SharedPtr clock_; + + std::shared_ptr freespace_planner_; + + bool isStuck( + const PredictedObjects & static_target_objects, const PredictedObjects & dynamic_target_objects, + const FreespaceParkingRequest & req) const; +}; + class GoalPlannerModule : public SceneModuleInterface { public: @@ -217,48 +292,16 @@ class GoalPlannerModule : public SceneModuleInterface CandidateOutput planCandidate() const override { return CandidateOutput{}; } private: - /** - * @brief shared data for onTimer(onTimer/onFreespaceParkingTimer just read this) - */ - struct GoalPlannerData - { - GoalPlannerData( - const PlannerData & planner_data, const GoalPlannerParameters & parameters, - const BehaviorModuleOutput & previous_module_output_) - { - initializeOccupancyGridMap(planner_data, parameters); - previous_module_output = previous_module_output_; - last_previous_module_output = previous_module_output_; - }; - GoalPlannerParameters parameters; - autoware::universe_utils::LinearRing2d vehicle_footprint; - - PlannerData planner_data; - ModuleStatus current_status; - BehaviorModuleOutput previous_module_output; - BehaviorModuleOutput last_previous_module_output; // occupancy_grid_map; - - const BehaviorModuleOutput & getPreviousModuleOutput() const { return previous_module_output; } - const ModuleStatus & getCurrentStatus() const { return current_status; } - void updateOccupancyGrid(); - GoalPlannerData clone() const; - void update( - const GoalPlannerParameters & parameters, const PlannerData & planner_data, - const ModuleStatus & current_status, const BehaviorModuleOutput & previous_module_output, - const autoware::universe_utils::LinearRing2d & vehicle_footprint, - const GoalCandidates & goal_candidates); - - private: - void initializeOccupancyGridMap( - const PlannerData & planner_data, const GoalPlannerParameters & parameters); - }; - std::optional gp_planner_data_{std::nullopt}; - std::mutex gp_planner_data_mutex_; + std::pair syncWithThreads(); + + // NOTE: never access to following variables except in updateData()!!! + std::mutex lane_parking_mutex_; + std::optional lane_parking_request_; + LaneParkingResponse lane_parking_response_; + + std::mutex freespace_parking_mutex_; + std::optional freespace_parking_request_; + FreespaceParkingResponse freespace_parking_response_; /* * state transitions and plan function used in each state @@ -297,9 +340,6 @@ class GoalPlannerModule : public SceneModuleInterface autoware::vehicle_info_utils::VehicleInfo vehicle_info_{}; - // planner - std::vector> pull_over_planners_; - std::unique_ptr freespace_planner_; std::unique_ptr fixed_goal_planner_; // goal searcher @@ -317,11 +357,6 @@ class GoalPlannerModule : public SceneModuleInterface autoware::universe_utils::LinearRing2d vehicle_footprint_; - std::recursive_mutex mutex_; - mutable ThreadSafeData thread_safe_data_; - - // TODO(soblin): organize part of thread_safe_data and previous data to PullOverContextData - // context_data_ is initialized in updateData(), used in plan() and refreshed in postProcess() std::optional context_data_{std::nullopt}; // path_decision_controller is updated in updateData(), and used in plan() PathDecisionStateController path_decision_controller_{getLogger()}; @@ -369,12 +404,7 @@ class GoalPlannerModule : public SceneModuleInterface // status bool hasFinishedCurrentPath(const PullOverContextData & ctx_data); double calcModuleRequestLength() const; - bool isStuck( - const PredictedObjects & static_target_objects, const PredictedObjects & dynamic_target_objects, - const std::shared_ptr planner_data, - const std::shared_ptr occupancy_grid_map, - const GoalPlannerParameters & parameters); - void decideVelocity(); + void decideVelocity(PullOverPath & pull_over_path); void updateStatus(const BehaviorModuleOutput & output); // validation @@ -385,21 +415,13 @@ class GoalPlannerModule : public SceneModuleInterface bool isCrossingPossible( const Pose & start_pose, const Pose & end_pose, const lanelet::ConstLanelets lanes) const; bool isCrossingPossible(const PullOverPath & pull_over_path) const; - bool hasEnoughTimePassedSincePathUpdate(const double duration) const; - - // freespace parking - bool planFreespacePath( - std::shared_ptr planner_data, - const std::shared_ptr goal_searcher, const GoalCandidates & goal_candidates, - const std::shared_ptr occupancy_grid_map, - const PredictedObjects & static_target_objects); bool canReturnToLaneParking(const PullOverContextData & context_data); // plan pull over path - BehaviorModuleOutput planPullOver(const PullOverContextData & context_data); - BehaviorModuleOutput planPullOverAsOutput(const PullOverContextData & context_data); + BehaviorModuleOutput planPullOver(PullOverContextData & context_data); + BehaviorModuleOutput planPullOverAsOutput(PullOverContextData & context_data); BehaviorModuleOutput planPullOverAsCandidate( - const PullOverContextData & context_data, const std::string & detail); + PullOverContextData & context_data, const std::string & detail); std::optional selectPullOverPath( const PullOverContextData & context_data, const std::vector & pull_over_path_candidates, @@ -411,7 +433,9 @@ class GoalPlannerModule : public SceneModuleInterface const PullOverContextData & context_data, BehaviorModuleOutput & output) const; // output setter - void setOutput(const PullOverContextData & context_data, BehaviorModuleOutput & output); + void setOutput( + const std::optional selected_pull_over_path_with_velocity_opt, + const PullOverContextData & context_data, BehaviorModuleOutput & output); void setModifiedGoal( const PullOverContextData & context_data, BehaviorModuleOutput & output) const; @@ -421,10 +445,6 @@ class GoalPlannerModule : public SceneModuleInterface TurnSignalInfo calcTurnSignalInfo(const PullOverContextData & context_data); std::optional ignore_signal_{std::nullopt}; - // timer for generating pull over path candidates in a separate thread - void onTimer(); - void onFreespaceParkingTimer(); - // steering factor void updateSteeringFactor( const PullOverContextData & context_data, const std::array & pose, diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/thread_data.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/thread_data.hpp index 549319b42ee4c..bfef4226b2661 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/thread_data.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/thread_data.hpp @@ -16,143 +16,123 @@ #define AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__THREAD_DATA_HPP_ #include "autoware/behavior_path_goal_planner_module/decision_state.hpp" -#include "autoware/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" +#include "autoware/behavior_path_planner_common/interface/scene_module_interface.hpp" #include #include -#include #include +#include #include namespace autoware::behavior_path_planner { -#define DEFINE_SETTER_WITH_MUTEX(TYPE, NAME) \ -public: \ - void set_##NAME(const TYPE & value) \ - { \ - const std::lock_guard lock(mutex_); \ - NAME##_ = value; \ - } - -#define DEFINE_GETTER_WITH_MUTEX(TYPE, NAME) \ -public: \ - TYPE get_##NAME() const \ - { \ - const std::lock_guard lock(mutex_); \ - return NAME##_; \ - } - -#define DEFINE_SETTER_GETTER_WITH_MUTEX(TYPE, NAME) \ - DEFINE_SETTER_WITH_MUTEX(TYPE, NAME) \ - DEFINE_GETTER_WITH_MUTEX(TYPE, NAME) - -class ThreadSafeData +class LaneParkingRequest { public: - ThreadSafeData(std::recursive_mutex & mutex, rclcpp::Clock::SharedPtr clock) - : mutex_(mutex), clock_(clock) + LaneParkingRequest( + const GoalPlannerParameters & parameters, + const autoware::universe_utils::LinearRing2d & vehicle_footprint, + const GoalCandidates & goal_candidates, const BehaviorModuleOutput & previous_module_output) + : parameters_(parameters), + vehicle_footprint_(vehicle_footprint), + goal_candidates_(goal_candidates), + previous_module_output_(previous_module_output), + last_previous_module_output_(previous_module_output) { } - bool incrementPathIndex() - { - const std::lock_guard lock(mutex_); - if (!pull_over_path_) { - return false; - } + void update( + const PlannerData & planner_data, const ModuleStatus & current_status, + const BehaviorModuleOutput & previous_module_output, + const std::optional & pull_over_path, const PathDecisionState & prev_data); - return pull_over_path_->incrementPathIndex(); - } + const GoalPlannerParameters parameters_; + const autoware::universe_utils::LinearRing2d vehicle_footprint_; + const GoalCandidates goal_candidates_; - void set_pull_over_path(const PullOverPath & path) + const std::shared_ptr & get_planner_data() const { return planner_data_; } + const ModuleStatus & get_current_status() const { return current_status_; } + const BehaviorModuleOutput & get_previous_module_output() const { - const std::lock_guard lock(mutex_); - set_pull_over_path_no_lock(path); + return previous_module_output_; } - - void set_pull_over_path(const std::shared_ptr & path) + const BehaviorModuleOutput & get_last_previous_module_output() const { - const std::lock_guard lock(mutex_); - set_pull_over_path_no_lock(path); + return last_previous_module_output_; } + const std::optional & get_pull_over_path() const { return pull_over_path_; } + const PathDecisionState & get_prev_data() const { return prev_data_; } - template - void set(Args... args) - { - std::lock_guard lock(mutex_); - (..., set_no_lock(args)); - } - - void clearPullOverPath() - { - const std::lock_guard lock(mutex_); - pull_over_path_ = nullptr; - } - - bool foundPullOverPath() const - { - const std::lock_guard lock(mutex_); - if (!pull_over_path_) { - return false; - } +private: + std::shared_ptr planner_data_; + ModuleStatus current_status_; + BehaviorModuleOutput previous_module_output_; + BehaviorModuleOutput last_previous_module_output_; + std::optional pull_over_path_; // pull_over_path_candidates; + std::optional closest_start_pose; +}; - void reset() +class FreespaceParkingRequest +{ +public: + FreespaceParkingRequest( + const GoalPlannerParameters & parameters, + const autoware::universe_utils::LinearRing2d & vehicle_footprint, + const GoalCandidates & goal_candidates, const PlannerData & planner_data) + : parameters_(parameters), + vehicle_footprint_(vehicle_footprint), + goal_candidates_(goal_candidates) { - const std::lock_guard lock(mutex_); - pull_over_path_ = nullptr; - pull_over_path_candidates_.clear(); - last_path_update_time_ = std::nullopt; - closest_start_pose_ = std::nullopt; - prev_data_ = PathDecisionState{}; - } - - // main --> lane - DEFINE_SETTER_GETTER_WITH_MUTEX(PathDecisionState, prev_data) - - // lane --> main - DEFINE_SETTER_GETTER_WITH_MUTEX(std::optional, closest_start_pose) - DEFINE_SETTER_GETTER_WITH_MUTEX(std::vector, pull_over_path_candidates) - - // main <--> lane/freespace - DEFINE_GETTER_WITH_MUTEX(std::shared_ptr, pull_over_path) - DEFINE_GETTER_WITH_MUTEX(std::optional, last_path_update_time) - -private: - void set_pull_over_path_no_lock(const PullOverPath & path) + initializeOccupancyGridMap(planner_data, parameters_); + }; + + const ModuleStatus & getCurrentStatus() const { return current_status_; } + void update( + const PlannerData & planner_data, const ModuleStatus & current_status, + const std::optional & pull_over_path, + const std::optional & last_path_update_time, const bool is_stopped); + + const GoalPlannerParameters parameters_; + const autoware::universe_utils::LinearRing2d vehicle_footprint_; + const GoalCandidates goal_candidates_; + + const std::shared_ptr & get_planner_data() const { return planner_data_; } + const ModuleStatus & get_current_status() const { return current_status_; } + std::shared_ptr get_occupancy_grid_map() const { - pull_over_path_ = std::make_shared(path); - - last_path_update_time_ = clock_->now(); + return occupancy_grid_map_; } - - void set_pull_over_path_no_lock(const std::shared_ptr & path) + const std::optional & get_pull_over_path() const { return pull_over_path_; } + const std::optional & get_last_path_update_time() const { - pull_over_path_ = path; - last_path_update_time_ = clock_->now(); + return last_path_update_time_; } + bool is_stopped() const { return is_stopped_; } - void set_no_lock(const std::vector & arg) { pull_over_path_candidates_ = arg; } - void set_no_lock(const std::shared_ptr & arg) { set_pull_over_path_no_lock(arg); } - void set_no_lock(const PullOverPath & arg) { set_pull_over_path_no_lock(arg); } - - std::shared_ptr pull_over_path_{nullptr}; - std::vector pull_over_path_candidates_; +private: + std::shared_ptr planner_data_; + ModuleStatus current_status_; + std::shared_ptr occupancy_grid_map_; + std::optional pull_over_path_; std::optional last_path_update_time_; - std::optional closest_start_pose_{}; - PathDecisionState prev_data_{}; + bool is_stopped_; - std::recursive_mutex & mutex_; - rclcpp::Clock::SharedPtr clock_; + void initializeOccupancyGridMap( + const PlannerData & planner_data, const GoalPlannerParameters & parameters); }; -#undef DEFINE_SETTER_WITH_MUTEX -#undef DEFINE_GETTER_WITH_MUTEX -#undef DEFINE_SETTER_GETTER_WITH_MUTEX +struct FreespaceParkingResponse +{ + std::optional freespace_pull_over_path; +}; } // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index e1f667d91b692..8e935c73c6ce9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -15,6 +15,7 @@ #include "autoware/behavior_path_goal_planner_module/goal_planner_module.hpp" #include "autoware/behavior_path_goal_planner_module/default_fixed_goal_planner.hpp" +#include "autoware/behavior_path_goal_planner_module/goal_searcher.hpp" #include "autoware/behavior_path_goal_planner_module/pull_over_planner/freespace_pull_over.hpp" #include "autoware/behavior_path_goal_planner_module/pull_over_planner/geometric_pull_over.hpp" #include "autoware/behavior_path_goal_planner_module/pull_over_planner/pull_over_planner_base.hpp" @@ -70,17 +71,9 @@ GoalPlannerModule::GoalPlannerModule( : SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT parameters_{parameters}, vehicle_info_{autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()}, - thread_safe_data_{mutex_, clock_}, is_lane_parking_cb_running_{false}, is_freespace_parking_cb_running_{false} { - LaneDepartureChecker lane_departure_checker{}; - lane_departure_checker.setVehicleInfo(vehicle_info_); - lane_departure_checker::Param lane_departure_checker_params; - lane_departure_checker_params.footprint_extra_margin = - parameters->lane_departure_check_expansion_margin; - lane_departure_checker.setParam(lane_departure_checker_params); - occupancy_grid_map_ = std::make_shared(); left_side_parking_ = parameters_->parking_policy == ParkingPolicy::LEFT_SIDE; @@ -88,26 +81,6 @@ GoalPlannerModule::GoalPlannerModule( // planner when goal modification is not allowed fixed_goal_planner_ = std::make_unique(); - for (const std::string & planner_type : parameters_->efficient_path_order) { - if (planner_type == "SHIFT" && parameters_->enable_shift_parking) { - pull_over_planners_.push_back( - std::make_shared(node, *parameters, lane_departure_checker)); - } else if (planner_type == "ARC_FORWARD" && parameters_->enable_arc_forward_parking) { - pull_over_planners_.push_back(std::make_shared( - node, *parameters, lane_departure_checker, /*is_forward*/ true)); - } else if (planner_type == "ARC_BACKWARD" && parameters_->enable_arc_backward_parking) { - pull_over_planners_.push_back(std::make_shared( - node, *parameters, lane_departure_checker, /*is_forward*/ false)); - } - } - - if (pull_over_planners_.empty()) { - RCLCPP_WARN( - getLogger(), - "No enabled planner found. The vehicle will stop in the road lane without pull over. Please " - "check the parameters if this is the intended behavior."); - } - // set selected goal searcher // currently there is only one goal_searcher_type const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo(); @@ -119,18 +92,27 @@ GoalPlannerModule::GoalPlannerModule( lane_parking_timer_cb_group_ = node.create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); lane_parking_timer_ = rclcpp::create_timer( - &node, clock_, lane_parking_period_ns, std::bind(&GoalPlannerModule::onTimer, this), + &node, clock_, lane_parking_period_ns, + [lane_parking_executor = std::make_unique( + node, lane_parking_mutex_, lane_parking_request_, lane_parking_response_, + is_lane_parking_cb_running_, getLogger(), *parameters_)]() { + lane_parking_executor->onTimer(); + }, lane_parking_timer_cb_group_); // freespace parking if (parameters_->enable_freespace_parking) { - freespace_planner_ = std::make_unique(node, *parameters, vehicle_info); + auto freespace_planner = std::make_shared(node, *parameters, vehicle_info); const auto freespace_parking_period_ns = rclcpp::Rate(1.0).period(); freespace_parking_timer_cb_group_ = node.create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); freespace_parking_timer_ = rclcpp::create_timer( &node, clock_, freespace_parking_period_ns, - std::bind(&GoalPlannerModule::onFreespaceParkingTimer, this), + [freespace_parking_executor = std::make_unique( + freespace_parking_mutex_, freespace_parking_request_, freespace_parking_response_, + is_freespace_parking_cb_running_, getLogger(), clock_, freespace_planner)]() { + freespace_parking_executor->onTimer(); + }, freespace_parking_timer_cb_group_); } @@ -241,6 +223,35 @@ bool checkOccupancyGridCollision( return occupancy_grid_map->hasObstacleOnPath(path, check_out_of_range); } +std::optional planFreespacePath( + const FreespaceParkingRequest & req, const PredictedObjects & static_target_objects, + std::shared_ptr freespace_planner) +{ + auto goal_candidates = req.goal_candidates_; + auto goal_searcher = std::make_shared(req.parameters_, req.vehicle_footprint_); + goal_searcher->update( + goal_candidates, req.get_occupancy_grid_map(), req.get_planner_data(), static_target_objects); + + for (size_t i = 0; i < goal_candidates.size(); i++) { + const auto goal_candidate = goal_candidates.at(i); + + if (!goal_candidate.is_safe) { + continue; + } + // TODO(soblin): this calls setMap() in freespace_planner in the for-loop, which is very + // inefficient + const auto freespace_path = freespace_planner->plan( + goal_candidate, 0, req.get_planner_data(), BehaviorModuleOutput{} + // NOTE: not used so passing {} is OK + ); + if (!freespace_path) { + continue; + } + return freespace_path; + } + return std::nullopt; +} + bool isStopped( std::deque & odometry_buffer, const nav_msgs::msg::Odometry::ConstSharedPtr self_odometry, const double duration_lower, @@ -267,50 +278,72 @@ bool isStopped( return is_stopped; } +LaneParkingPlanner::LaneParkingPlanner( + rclcpp::Node & node, std::mutex & lane_parking_mutex, + const std::optional & request, LaneParkingResponse & response, + std::atomic & is_lane_parking_cb_running, const rclcpp::Logger & logger, + const GoalPlannerParameters & parameters) +: mutex_(lane_parking_mutex), + request_(request), + response_(response), + is_lane_parking_cb_running_(is_lane_parking_cb_running), + logger_(logger) +{ + const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo(); + LaneDepartureChecker lane_departure_checker{}; + lane_departure_checker.setVehicleInfo(vehicle_info); + lane_departure_checker::Param lane_departure_checker_params; + lane_departure_checker_params.footprint_extra_margin = + parameters.lane_departure_check_expansion_margin; + lane_departure_checker.setParam(lane_departure_checker_params); + + for (const std::string & planner_type : parameters.efficient_path_order) { + if (planner_type == "SHIFT" && parameters.enable_shift_parking) { + pull_over_planners_.push_back( + std::make_shared(node, parameters, lane_departure_checker)); + } else if (planner_type == "ARC_FORWARD" && parameters.enable_arc_forward_parking) { + pull_over_planners_.push_back(std::make_shared( + node, parameters, lane_departure_checker, /*is_forward*/ true)); + } else if (planner_type == "ARC_BACKWARD" && parameters.enable_arc_backward_parking) { + pull_over_planners_.push_back(std::make_shared( + node, parameters, lane_departure_checker, /*is_forward*/ false)); + } + } + + if (pull_over_planners_.empty()) { + RCLCPP_ERROR(logger_, "Not found enabled planner"); + } +} + // generate pull over candidate paths -void GoalPlannerModule::onTimer() +void LaneParkingPlanner::onTimer() { const ScopedFlag flag(is_lane_parking_cb_running_); - std::shared_ptr local_planner_data{nullptr}; - std::optional current_status_opt{std::nullopt}; - std::optional previous_module_output_opt{std::nullopt}; - std::optional last_previous_module_output_opt{std::nullopt}; - std::shared_ptr occupancy_grid_map{nullptr}; - std::optional parameters_opt{std::nullopt}; - std::optional goal_candidates_opt{std::nullopt}; + std::optional local_request_opt; // begin of critical section { - std::lock_guard guard(gp_planner_data_mutex_); - if (gp_planner_data_) { - const auto & gp_planner_data = gp_planner_data_.value(); - local_planner_data = std::make_shared(gp_planner_data.planner_data); - current_status_opt = gp_planner_data.current_status; - previous_module_output_opt = gp_planner_data.previous_module_output; - last_previous_module_output_opt = gp_planner_data.last_previous_module_output; - occupancy_grid_map = gp_planner_data.occupancy_grid_map; - parameters_opt = gp_planner_data.parameters; - goal_candidates_opt = gp_planner_data.goal_candidates; + std::lock_guard guard(mutex_); + if (request_) { + auto & request = request_.value(); + local_request_opt.emplace(request); } } // end of critical section - if ( - !local_planner_data || !current_status_opt || !previous_module_output_opt || - !last_previous_module_output_opt || !occupancy_grid_map || !parameters_opt || - !goal_candidates_opt) { - RCLCPP_INFO_THROTTLE( - getLogger(), *clock_, 5000, - "failed to get valid " - "local_planner_data/current_status/previous_module_output/occupancy_grid_map/parameters_opt " - "in onTimer"); + if (!local_request_opt) { + RCLCPP_ERROR(logger_, "main thread has not yet set request for LaneParkingPlanner"); return; } - const auto & current_status = current_status_opt.value(); - const auto & previous_module_output = previous_module_output_opt.value(); - const auto & last_previous_module_output = last_previous_module_output_opt.value(); - const auto & parameters = parameters_opt.value(); - const auto & goal_candidates = goal_candidates_opt.value(); + const auto & local_request = local_request_opt.value(); + const auto & parameters = local_request.parameters_; + const auto & goal_candidates = local_request.goal_candidates_; + const auto & local_planner_data = local_request.get_planner_data(); + const auto & current_status = local_request.get_current_status(); + const auto & previous_module_output = local_request.get_previous_module_output(); + const auto & last_previous_module_output = local_request.get_last_previous_module_output(); + const auto & pull_over_path_opt = local_request.get_pull_over_path(); + const auto & prev_data = local_request.get_prev_data(); if (current_status == ModuleStatus::IDLE) { return; @@ -326,13 +359,14 @@ void GoalPlannerModule::onTimer() } // check if new pull over path candidates are needed to be generated - const auto current_state = thread_safe_data_.get_prev_data().state; + const auto current_state = prev_data.state; const bool need_update = std::invoke([&]() { - const bool found_pull_over_path = thread_safe_data_.foundPullOverPath(); - const std::optional pull_over_path_opt = - found_pull_over_path - ? std::make_optional(*thread_safe_data_.get_pull_over_path()) - : std::nullopt; + { + std::lock_guard guard(mutex_); + if (response_.pull_over_path_candidates.empty()) { + return true; + } + } const std::optional modified_goal_opt = pull_over_path_opt ? std::make_optional(pull_over_path_opt.value().modified_goal()) @@ -345,9 +379,6 @@ void GoalPlannerModule::onTimer() RCLCPP_DEBUG(getLogger(), "has deviated from current previous module path"); return false; } - if (thread_safe_data_.get_pull_over_path_candidates().empty()) { - return true; - } if (hasPreviousModulePathShapeChanged(previous_module_output, last_previous_module_output)) { RCLCPP_DEBUG(getLogger(), "has previous module path shape changed"); return true; @@ -431,51 +462,42 @@ void GoalPlannerModule::onTimer() throw std::domain_error("[pull_over] invalid path_priority"); } - // set member variables - thread_safe_data_.set_pull_over_path_candidates(path_candidates); - thread_safe_data_.set_closest_start_pose(closest_start_pose); - RCLCPP_INFO(getLogger(), "generated %lu pull over path candidates", path_candidates.size()); + // set response + { + std::lock_guard guard(mutex_); + response_.pull_over_path_candidates = path_candidates; + response_.closest_start_pose = closest_start_pose; + RCLCPP_INFO( + getLogger(), "generated %lu pull over path candidates", + response_.pull_over_path_candidates.size()); + } } -void GoalPlannerModule::onFreespaceParkingTimer() +void FreespaceParkingPlanner::onTimer() { const ScopedFlag flag(is_freespace_parking_cb_running_); - std::shared_ptr local_planner_data{nullptr}; - std::optional current_status_opt{std::nullopt}; - std::shared_ptr occupancy_grid_map{nullptr}; - std::optional parameters_opt{std::nullopt}; - std::optional vehicle_footprint_opt{std::nullopt}; - std::optional goal_candidates_opt{std::nullopt}; + std::optional local_request_opt; // begin of critical section { - std::lock_guard guard(gp_planner_data_mutex_); - if (gp_planner_data_) { - const auto & gp_planner_data = gp_planner_data_.value(); - local_planner_data = std::make_shared(gp_planner_data.planner_data); - current_status_opt = gp_planner_data.current_status; - occupancy_grid_map = gp_planner_data.occupancy_grid_map; - parameters_opt = gp_planner_data.parameters; - vehicle_footprint_opt = gp_planner_data.vehicle_footprint; - goal_candidates_opt = gp_planner_data.goal_candidates; + std::lock_guard guard(mutex_); + if (request_) { + auto & request = request_.value(); + local_request_opt.emplace(request); } } // end of critical section - if ( - !local_planner_data || !current_status_opt || !occupancy_grid_map || !parameters_opt || - !vehicle_footprint_opt || !goal_candidates_opt) { - RCLCPP_WARN_THROTTLE( - getLogger(), *clock_, 5000, - "failed to get valid planner_data/current_status/parameters in " - "onFreespaceParkingTimer"); + if (!local_request_opt) { + RCLCPP_ERROR(logger_, "main thread has not yet set request for FreespaceParkingPlanner"); return; } - - const auto & current_status = current_status_opt.value(); - const auto & parameters = parameters_opt.value(); - const auto & vehicle_footprint = vehicle_footprint_opt.value(); - const auto & goal_candidates = goal_candidates_opt.value(); + const auto & local_request = local_request_opt.value(); + const auto & parameters = local_request.parameters_; + const auto & local_planner_data = local_request.get_planner_data(); + const auto & current_status = local_request.get_current_status(); + const auto & pull_over_path_opt = local_request.get_pull_over_path(); + const auto & last_path_update_time = local_request.get_last_path_update_time(); if (current_status == ModuleStatus::IDLE) { return; @@ -489,10 +511,6 @@ void GoalPlannerModule::onFreespaceParkingTimer() return; } - const bool found_pull_over_path = thread_safe_data_.foundPullOverPath(); - const std::optional pull_over_path_opt = - found_pull_over_path ? std::make_optional(*thread_safe_data_.get_pull_over_path()) - : std::nullopt; const std::optional modified_goal_opt = pull_over_path_opt ? std::make_optional(pull_over_path_opt.value().modified_goal()) @@ -502,7 +520,7 @@ void GoalPlannerModule::onFreespaceParkingTimer() return; } - const double vehicle_width = planner_data_->parameters.vehicle_width; + const double vehicle_width = local_planner_data->parameters.vehicle_width; const bool left_side_parking = parameters.parking_policy == ParkingPolicy::LEFT_SIDE; const auto pull_over_lanes = goal_planner_utils::getPullOverLanes( *(local_planner_data->route_handler), left_side_parking, parameters.backward_goal_search_length, @@ -527,19 +545,87 @@ void GoalPlannerModule::onFreespaceParkingTimer() (clock_->now() - local_planner_data->costmap->header.stamp).seconds() < 1.0; constexpr double path_update_duration = 1.0; if ( - isStuck( - static_target_objects, dynamic_target_objects, local_planner_data, occupancy_grid_map, - parameters) && - is_new_costmap && + isStuck(static_target_objects, dynamic_target_objects, local_request) && is_new_costmap && needPathUpdate( local_planner_data->self_odometry->pose.pose, path_update_duration, clock_->now(), - modified_goal_opt, thread_safe_data_.get_last_path_update_time(), parameters)) { - auto goal_searcher = std::make_shared(parameters, vehicle_footprint); + modified_goal_opt, last_path_update_time, parameters)) { + const auto freespace_path_opt = + planFreespacePath(local_request, static_target_objects, freespace_planner_); + if (freespace_path_opt) { + std::lock_guard guard(mutex_); + response_.freespace_pull_over_path = freespace_path_opt.value(); + } + } +} - planFreespacePath( - local_planner_data, goal_searcher, goal_candidates, occupancy_grid_map, - static_target_objects); +std::pair GoalPlannerModule::syncWithThreads() +{ + // In PlannerManager::run(), it calls SceneModuleInterface::setData and + // SceneModuleInterface::setPreviousModuleOutput before module_ptr->run(). + // Then module_ptr->run() invokes GoalPlannerModule::updateData and then + // planWaitingApproval()/plan(), so we can copy latest current_status/previous_module_output to + // lane_parking_request/freespace_parking_request + + std::optional pull_over_path = + context_data_ ? context_data_.value().pull_over_path_opt : std::nullopt; + std::optional last_path_update_time = + context_data_ ? context_data_.value().last_path_update_time : std::nullopt; + + // NOTE: Following clone process is rather lightweight because most of the member variables of + // PlannerData/RouteHandler is shared_ptrs + // begin of critical section + LaneParkingResponse lane_parking_response; + { + std::lock_guard guard(lane_parking_mutex_); + if (!lane_parking_request_) { + lane_parking_request_.emplace( + *parameters_, vehicle_footprint_, goal_candidates_, getPreviousModuleOutput()); + } + // NOTE: for the above reasons, PlannerManager/behavior_path_planner_node ensure that + // planner_data_ is not nullptr, so it is OK to copy as value + // By copying PlannerData as value, the internal shared member variables are also copied + // (reference count is incremented), so `lane_parking_request_local.planner_data_.foo` is now + // thread-safe from the **re-pointing** by `planner_data_->foo = msg` in + // behavior_path_planner::onCallbackFor(msg) and if these two coincided, only the reference + // count is affected + lane_parking_request_.value().update( + *planner_data_, getCurrentStatus(), getPreviousModuleOutput(), pull_over_path, + path_decision_controller_.get_current_state()); + // NOTE: RouteHandler holds several shared pointers in it, so just copying PlannerData as + // value does not adds the reference counts of RouteHandler.lanelet_map_ptr_ and others. Since + // behavior_path_planner::run() updates + // planner_data_->route_handler->lanelet_map_ptr_/routing_graph_ptr_ especially, we also have + // to copy route_handler as value to use lanelet_map_ptr_/routing_graph_ptr_ thread-safely in + // onTimer/onFreespaceParkingTimer + // TODO(Mamoru Sobue): If the copy of RouteHandler.road_lanelets/shoulder_lanelets is not + // lightweight, we should update lane_parking_request.planner_data.route_handler only when + // `planner_data_.is_route_handler_updated` variable is set true by behavior_path_planner + // (although this flag is not implemented yet). In that case, lane_parking_request members + // except for route_handler should be copied from planner_data_ + lane_parking_response = lane_parking_response_; + } + + FreespaceParkingResponse freespace_parking_response; + { + std::lock_guard guard(freespace_parking_mutex_); + if (!freespace_parking_request_) { + freespace_parking_request_.emplace( + *parameters_, vehicle_footprint_, goal_candidates_, *planner_data_); + } + constexpr double stuck_time = 5.0; + freespace_parking_request_.value().update( + *planner_data_, getCurrentStatus(), pull_over_path, last_path_update_time, + isStopped( + odometry_buffer_stuck_, planner_data_->self_odometry, stuck_time, + parameters_->th_stopped_velocity)); + // TODO(soblin): currently, ogm-based-collision-detector is updated to latest in + // freespace_parking_request_.value().update, and it is shared with goal_planner_module. Next, + // goal_planner_module update it and pass it to freespace_parking_request. + occupancy_grid_map_ = freespace_parking_request_.value().get_occupancy_grid_map(); + freespace_parking_response = freespace_parking_response_; } + // end of critical section + return {lane_parking_response, freespace_parking_response}; } void GoalPlannerModule::updateData() @@ -576,52 +662,7 @@ void GoalPlannerModule::updateData() goal_candidates_ = generateGoalCandidates(); } - // In PlannerManager::run(), it calls SceneModuleInterface::setData and - // SceneModuleInterface::setPreviousModuleOutput before module_ptr->run(). - // Then module_ptr->run() invokes GoalPlannerModule::updateData and then - // planWaitingApproval()/plan(), so we can copy latest current_status/previous_module_output to - // gp_planner_data_ here - - // NOTE: onTimer/onFreespaceParkingTimer copies gp_planner_data_ to their local clone, so we need - // to lock gp_planner_data_ here to avoid data race. But the following clone process is - // lightweight because most of the member variables of PlannerData/RouteHandler is - // shared_ptrs/bool - // begin of critical section - { - std::lock_guard guard(gp_planner_data_mutex_); - if (!gp_planner_data_) { - gp_planner_data_ = GoalPlannerData(*planner_data_, *parameters_, getPreviousModuleOutput()); - } - auto & gp_planner_data = gp_planner_data_.value(); - // NOTE: for the above reasons, PlannerManager/behavior_path_planner_node ensure that - // planner_data_ is not nullptr, so it is OK to copy as value - // By copying PlannerData as value, the internal shared member variables are also copied - // (reference count is incremented), so `gp_planner_data_.foo` is now thread-safe from the - // **re-pointing** by `planner_data_->foo = msg` in behavior_path_planner::onCallbackFor(msg) - // and if these two coincided, only the reference count is affected - gp_planner_data.update( - *parameters_, *planner_data_, getCurrentStatus(), getPreviousModuleOutput(), - vehicle_footprint_, goal_candidates_); - // NOTE: RouteHandler holds several shared pointers in it, so just copying PlannerData as - // value does not adds the reference counts of RouteHandler.lanelet_map_ptr_ and others. Since - // behavior_path_planner::run() updates - // planner_data_->route_handler->lanelet_map_ptr_/routing_graph_ptr_ especially, we also have - // to copy route_handler as value to use lanelet_map_ptr_/routing_graph_ptr_ thread-safely in - // onTimer/onFreespaceParkingTimer - // TODO(Mamoru Sobue): If the copy of RouteHandler.road_lanelets/shoulder_lanelets is not - // lightweight, we should update gp_planner_data_.route_handler only when - // `planner_data_.is_route_handler_updated` variable is set true by behavior_path_planner - // (although this flag is not implemented yet). In that case, gp_planner_data members except - // for route_handler should be copied from planner_data_ - - // GoalPlannerModule::occupancy_grid_map_ and gp_planner_data.occupancy_grid_map share the - // ownership, and gp_planner_data.occupancy_grid_map maybe also shared by the local - // planner_data on onFreespaceParkingTimer thread local memory space. So following operation - // is thread-safe because gp_planner_data.occupancy_grid_map is only re-pointed here and its - // prior resource is still owned by the onFreespaceParkingTimer thread locally. - occupancy_grid_map_ = gp_planner_data.occupancy_grid_map; - } - // end of critical section + auto [lane_parking_response, freespace_parking_response] = syncWithThreads(); if (getCurrentStatus() == ModuleStatus::IDLE && !isExecutionRequested()) { return; @@ -631,17 +672,18 @@ void GoalPlannerModule::updateData() resetPathReference(); path_reference_ = std::make_shared(getPreviousModuleOutput().reference_path); - const bool found_pull_over_path = thread_safe_data_.foundPullOverPath(); + const bool found_pull_over_path = + context_data_ ? context_data_.value().pull_over_path_opt.has_value() : false; std::optional pull_over_path_recv = - found_pull_over_path ? std::make_optional(*thread_safe_data_.get_pull_over_path()) - : std::nullopt; + found_pull_over_path + ? std::make_optional(context_data_.value().pull_over_path_opt.value()) + : std::nullopt; const auto modified_goal_pose = [&]() -> std::optional { if (!pull_over_path_recv) { return std::nullopt; } - const auto & pull_over_path = pull_over_path_recv.value(); - return pull_over_path.modified_goal(); + return pull_over_path_recv.value().modified_goal(); }(); // save "old" state @@ -656,21 +698,35 @@ void GoalPlannerModule::updateData() modified_goal_pose, planner_data_, occupancy_grid_map_, is_current_safe, *parameters_, goal_searcher_, isActivated(), pull_over_path_recv, debug_data_.ego_polygons_expanded); - context_data_.emplace( - path_decision_controller_.get_current_state().is_stable_safe, static_target_objects, - dynamic_target_objects, std::move(pull_over_path_recv), - thread_safe_data_.get_pull_over_path_candidates(), prev_decision_state); + if (context_data_) { + context_data_.value().update( + path_decision_controller_.get_current_state().is_stable_safe, static_target_objects, + dynamic_target_objects, prev_decision_state, + isStopped( + odometry_buffer_stopped_, planner_data_->self_odometry, parameters_->th_stopped_time, + parameters_->th_stopped_velocity), + lane_parking_response, freespace_parking_response); + } else { + context_data_.emplace( + path_decision_controller_.get_current_state().is_stable_safe, static_target_objects, + dynamic_target_objects, prev_decision_state, + isStopped( + odometry_buffer_stopped_, planner_data_->self_odometry, parameters_->th_stopped_time, + parameters_->th_stopped_velocity), + lane_parking_response, freespace_parking_response); + } auto & ctx_data = context_data_.value(); - thread_safe_data_.set_prev_data(path_decision_controller_.get_current_state()); - if (!isActivated()) { return; } if (hasFinishedCurrentPath(ctx_data)) { - if (thread_safe_data_.incrementPathIndex()) { - ctx_data.last_path_idx_increment_time = clock_->now(); + if (ctx_data.pull_over_path_opt) { + auto & pull_over_path = ctx_data.pull_over_path_opt.value(); + if (pull_over_path.incrementPathIndex()) { + ctx_data.last_path_idx_increment_time = clock_->now(); + } } } @@ -678,7 +734,7 @@ void GoalPlannerModule::updateData() last_approval_data_ = std::make_unique(clock_->now(), planner_data_->self_odometry->pose.pose); // TODO(soblin): do not "plan" in updateData - decideVelocity(); + if (ctx_data.pull_over_path_opt) decideVelocity(ctx_data.pull_over_path_opt.value()); } } @@ -696,7 +752,7 @@ void GoalPlannerModule::processOnExit() resetPathCandidate(); resetPathReference(); debug_marker_.markers.clear(); - thread_safe_data_.reset(); + context_data_ = std::nullopt; last_approval_data_.reset(); } @@ -833,48 +889,6 @@ double GoalPlannerModule::calcModuleRequestLength() const return std::max(minimum_request_length, parameters_->pull_over_minimum_request_length); } -bool GoalPlannerModule::planFreespacePath( - std::shared_ptr planner_data, - const std::shared_ptr goal_searcher, const GoalCandidates & goal_candidates_arg, - const std::shared_ptr occupancy_grid_map, - const PredictedObjects & static_target_objects) -{ - auto goal_candidates = goal_candidates_arg; - goal_searcher->update(goal_candidates, occupancy_grid_map, planner_data, static_target_objects); - debug_data_.freespace_planner.num_goal_candidates = goal_candidates.size(); - debug_data_.freespace_planner.is_planning = true; - - for (size_t i = 0; i < goal_candidates.size(); i++) { - const auto goal_candidate = goal_candidates.at(i); - { - const std::lock_guard lock(mutex_); - debug_data_.freespace_planner.current_goal_idx = i; - } - - if (!goal_candidate.is_safe) { - continue; - } - const auto freespace_path = freespace_planner_->plan( - goal_candidate, 0, planner_data, BehaviorModuleOutput{} // NOTE: not used so passing {} is OK - ); - if (!freespace_path) { - continue; - } - - { - const std::lock_guard lock(mutex_); - thread_safe_data_.set_pull_over_path(*freespace_path); - debug_data_.freespace_planner.is_planning = false; - } - - return true; - } - - const std::lock_guard lock(mutex_); - debug_data_.freespace_planner.is_planning = false; - return false; -} - bool GoalPlannerModule::canReturnToLaneParking(const PullOverContextData & context_data) { // return only before starting free space parking @@ -890,6 +904,11 @@ bool GoalPlannerModule::canReturnToLaneParking(const PullOverContextData & conte if (context_data.pull_over_path_opt.value().type() == PullOverPlannerType::FREESPACE) { return false; } + // TODO(soblin): return from freespace to lane is disabled temporarily, because if + // context_data_with_velocity contained freespace path, since lane_parking_pull_over_path is + // deleted, freespace path is set again + // So context_data need to have old_selected_lane_pull_over_path also, which is only updated + // against lane_pull_over_path in selectPullOverPath() const auto & lane_parking_path = context_data.pull_over_path_opt.value(); const auto & path = lane_parking_path.full_path(); @@ -954,7 +973,7 @@ BehaviorModuleOutput GoalPlannerModule::plan() RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, " [pull_over] plan() is called without valid context_data"); } else { - const auto & context_data = context_data_.value(); + auto & context_data = context_data_.value(); return planPullOver(context_data); } } @@ -1228,13 +1247,14 @@ std::vector GoalPlannerModule::generateDrivableLanes() const } void GoalPlannerModule::setOutput( + const std::optional selected_pull_over_path_with_velocity_opt, const PullOverContextData & context_data, BehaviorModuleOutput & output) { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); output.reference_path = getPreviousModuleOutput().reference_path; - if (!context_data.pull_over_path_opt) { + if (!selected_pull_over_path_with_velocity_opt) { // situation : not safe against static objects use stop_path output.path = generateStopPath( context_data, (goal_candidates_.empty() ? "no goal candidate" : "no static safe path")); @@ -1244,7 +1264,7 @@ void GoalPlannerModule::setOutput( return; } - const auto & pull_over_path = context_data.pull_over_path_opt.value(); + const auto & pull_over_path = selected_pull_over_path_with_velocity_opt.value(); if ( parameters_->safety_check_params.enable_safety_check && !context_data.is_stable_safe_path && isActivated()) { @@ -1343,15 +1363,14 @@ void GoalPlannerModule::updateSteeringFactor( steering_factor_interface_.set(pose, distance, steering_factor_direction, type, ""); } -void GoalPlannerModule::decideVelocity() +void GoalPlannerModule::decideVelocity(PullOverPath & pull_over_path) { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const double current_vel = planner_data_->self_odometry->twist.twist.linear.x; // partial_paths - // TODO(soblin): only update velocity on main thread side, use that on main thread side - auto & first_path = thread_safe_data_.get_pull_over_path()->partial_paths().front(); + auto & first_path = pull_over_path.partial_paths().front(); const auto vel = static_cast(std::max(current_vel, parameters_->pull_over_minimum_velocity)); for (auto & p : first_path.points) { @@ -1359,21 +1378,19 @@ void GoalPlannerModule::decideVelocity() } } -BehaviorModuleOutput GoalPlannerModule::planPullOver(const PullOverContextData & context_data) +BehaviorModuleOutput GoalPlannerModule::planPullOver(PullOverContextData & context_data) { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto current_state = path_decision_controller_.get_current_state(); if (current_state.state != PathDecisionState::DecisionKind::DECIDED) { const bool is_stable_safe = current_state.is_stable_safe; - // clang-format off const std::string detail = - goal_candidates_.empty() ? "no goal candidate" : - context_data.pull_over_path_candidates.empty() ? "no path candidate" : - !thread_safe_data_.foundPullOverPath() ? "no static safe path" : - !is_stable_safe ? "unsafe against dynamic objects" : - "too far goal"; - // clang-format on + goal_candidates_.empty() ? "no goal candidate" + : context_data.lane_parking_response.pull_over_path_candidates.empty() ? "no path candidate" + : !context_data.pull_over_path_opt ? "no static safe path" + : !is_stable_safe ? "unsafe against dynamic objects" + : "too far goal"; return planPullOverAsCandidate(context_data, detail); } @@ -1381,12 +1398,12 @@ BehaviorModuleOutput GoalPlannerModule::planPullOver(const PullOverContextData & } BehaviorModuleOutput GoalPlannerModule::planPullOverAsCandidate( - const PullOverContextData & context_data, const std::string & detail) + PullOverContextData & context_data, const std::string & detail) { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); // if pull over path candidates generation is not finished, use previous module output - if (context_data.pull_over_path_candidates.empty()) { + if (context_data.lane_parking_response.pull_over_path_candidates.empty()) { return getPreviousModuleOutput(); } @@ -1413,8 +1430,7 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsCandidate( return output; } -BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput( - const PullOverContextData & context_data) +BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput(PullOverContextData & context_data) { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); @@ -1422,16 +1438,15 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput( start = std::chrono::system_clock::now(); // if pull over path candidates generation is not finished, use previous module output - if (context_data.pull_over_path_candidates.empty()) { + if (context_data.lane_parking_response.pull_over_path_candidates.empty()) { return getPreviousModuleOutput(); } - auto context_data_with_velocity = context_data; /** NOTE(soblin): this path originates from the previously selected(by main thread) pull_over_path which was originally generated by either road_parking or freespace thread */ - auto & pull_over_path_with_velocity_opt = context_data_with_velocity.pull_over_path_opt; + auto pull_over_path_with_velocity_opt = context_data.pull_over_path_opt; const bool is_freespace = pull_over_path_with_velocity_opt && pull_over_path_with_velocity_opt.value().type() == PullOverPlannerType::FREESPACE; @@ -1439,19 +1454,22 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput( pull_over_path_with_velocity_opt ? std::make_optional(pull_over_path_with_velocity_opt.value().modified_goal()) : std::nullopt; + const auto & last_path_update_time = context_data.last_path_update_time; if ( path_decision_controller_.get_current_state().state == PathDecisionState::DecisionKind::NOT_DECIDED && !is_freespace && needPathUpdate( planner_data_->self_odometry->pose.pose, 1.0 /*path_update_duration*/, clock_->now(), - modified_goal_opt, thread_safe_data_.get_last_path_update_time(), *parameters_)) { + modified_goal_opt, last_path_update_time, *parameters_)) { // if the final path is not decided and enough time has passed since last path update, // select safe path from lane parking pull over path candidates // and set it to thread_safe_data_ RCLCPP_DEBUG(getLogger(), "Update pull over path candidates"); - thread_safe_data_.clearPullOverPath(); + context_data.pull_over_path_opt = std::nullopt; + context_data.last_path_update_time = std::nullopt; + context_data.last_path_idx_increment_time = std::nullopt; // update goal candidates auto goal_candidates = goal_candidates_; @@ -1459,13 +1477,17 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput( goal_candidates, occupancy_grid_map_, planner_data_, context_data.static_target_objects); // Select a path that is as safe as possible and has a high priority. - const auto & pull_over_path_candidates = context_data.pull_over_path_candidates; - auto path_and_goal_opt = + const auto & pull_over_path_candidates = + context_data.lane_parking_response.pull_over_path_candidates; + const auto lane_pull_over_path_opt = selectPullOverPath(context_data, pull_over_path_candidates, goal_candidates); // update thread_safe_data_ - if (path_and_goal_opt) { - const auto & pull_over_path = path_and_goal_opt.value(); + const auto & pull_over_path_opt = + lane_pull_over_path_opt ? lane_pull_over_path_opt + : context_data.freespace_parking_response.freespace_pull_over_path; + if (pull_over_path_opt) { + const auto & pull_over_path = pull_over_path_opt.value(); /** TODO(soblin): since thread_safe_data::pull_over_path was used as a global variable, old * code was setting deceleration to thread_safe_data::pull_over_path and setOutput() accessed * to the velocity profile in thread_safe_data::pull_over_path, which is a very bad usage of @@ -1476,7 +1498,10 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput( * As the next action item, only set this selected pull_over_path to only * FreespaceThreadSafeData. */ - thread_safe_data_.set(pull_over_path); + context_data.pull_over_path_opt = pull_over_path; + context_data.last_path_update_time = clock_->now(); + context_data.last_path_idx_increment_time = std::nullopt; + if (pull_over_path_with_velocity_opt) { auto & pull_over_path_with_velocity = pull_over_path_with_velocity_opt.value(); // copy the path for later setOutput() @@ -1492,20 +1517,19 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput( // set output and status BehaviorModuleOutput output{}; - setOutput(context_data_with_velocity, output); + setOutput(pull_over_path_with_velocity_opt, context_data, output); // return to lane parking if it is possible - if (is_freespace && canReturnToLaneParking(context_data_with_velocity)) { - // TODO(soblin): return from freespace to lane is disabled temporarily, because if - // context_data_with_velocity contained freespace path, since lane_parking_pull_over_path is - // deleted, freespace path is set again - if (context_data_with_velocity.pull_over_path_opt) { - thread_safe_data_.set_pull_over_path(context_data_with_velocity.pull_over_path_opt.value()); + if (is_freespace && canReturnToLaneParking(context_data)) { + if (pull_over_path_with_velocity_opt) { + context_data.pull_over_path_opt = pull_over_path_with_velocity_opt; + context_data.last_path_update_time = clock_->now(); + context_data.last_path_idx_increment_time = std::nullopt; } } // For debug - setDebugData(context_data_with_velocity); + setDebugData(context_data); if (!pull_over_path_with_velocity_opt) { return output; @@ -1526,8 +1550,9 @@ void GoalPlannerModule::postProcess() getLogger(), *clock_, 5000, " [pull_over] postProcess() is called without valid context_data. use dummy context data."); } - const auto context_data_dummy = - PullOverContextData(true, PredictedObjects{}, PredictedObjects{}, std::nullopt, {}, {}); + const auto context_data_dummy = PullOverContextData( + true, PredictedObjects{}, PredictedObjects{}, PathDecisionState{}, false /*is _stopped*/, + LaneParkingResponse{}, FreespaceParkingResponse{}); const auto & context_data = context_data_.has_value() ? context_data_.value() : context_data_dummy; @@ -1535,7 +1560,6 @@ void GoalPlannerModule::postProcess() path_decision_controller_.get_current_state().state == PathDecisionState::DecisionKind::DECIDED; if (!context_data.pull_over_path_opt) { - context_data_ = std::nullopt; return; } const auto & pull_over_path = context_data.pull_over_path_opt.value(); @@ -1552,8 +1576,6 @@ void GoalPlannerModule::postProcess() has_decided_path ? SteeringFactor::TURNING : SteeringFactor::APPROACHING); setVelocityFactor(pull_over_path.full_path()); - - context_data_ = std::nullopt; } BehaviorModuleOutput GoalPlannerModule::planWaitingApproval() @@ -1567,7 +1589,7 @@ BehaviorModuleOutput GoalPlannerModule::planWaitingApproval() " [pull_over] planWaitingApproval() is called without valid context_data. use fixed goal " "planner"); } else { - const auto & context_data = context_data_.value(); + auto & context_data = context_data_.value(); return planPullOverAsCandidate(context_data, "waiting approval"); } } @@ -1586,7 +1608,7 @@ std::pair GoalPlannerModule::calcDistanceToPathChange( } const auto & pull_over_path = context_data.pull_over_path_opt.value(); - const auto & full_path = context_data.pull_over_path_opt.value().full_path(); + const auto & full_path = pull_over_path.full_path(); const auto ego_segment_idx = autoware::motion_utils::findNearestSegmentIndex( full_path.points, planner_data_->self_odometry->pose.pose, std::numeric_limits::max(), @@ -1667,11 +1689,10 @@ PathWithLaneId GoalPlannerModule::generateStopPath( // 4. feasible stop const auto stop_pose_opt = std::invoke([&]() -> std::optional { if (context_data.pull_over_path_opt) - return context_data.pull_over_path_opt.value().start_pose(); - if (thread_safe_data_.get_closest_start_pose()) - return thread_safe_data_.get_closest_start_pose().value(); - if (!decel_pose) return std::nullopt; - return decel_pose.value(); + return std::make_optional(context_data.pull_over_path_opt.value().start_pose()); + if (context_data.lane_parking_response.closest_start_pose) + return context_data.lane_parking_response.closest_start_pose; + return decel_pose; }); if (!stop_pose_opt.has_value()) { const auto feasible_stop_path = @@ -1743,46 +1764,38 @@ PathWithLaneId GoalPlannerModule::generateFeasibleStopPath( return stop_path; } -bool GoalPlannerModule::isStuck( +bool FreespaceParkingPlanner::isStuck( const PredictedObjects & static_target_objects, const PredictedObjects & dynamic_target_objects, - const std::shared_ptr planner_data, - const std::shared_ptr occupancy_grid_map, - const GoalPlannerParameters & parameters) + const FreespaceParkingRequest & req) const { - const bool found_pull_over_path = thread_safe_data_.foundPullOverPath(); - const std::optional pull_over_path_opt = - found_pull_over_path ? std::make_optional(*thread_safe_data_.get_pull_over_path()) - : std::nullopt; + const auto & parameters = req.parameters_; + const auto & planner_data = req.get_planner_data(); const std::optional modified_goal_opt = - pull_over_path_opt - ? std::make_optional(pull_over_path_opt.value().modified_goal()) + req.get_pull_over_path() + ? std::make_optional(req.get_pull_over_path().value().modified_goal()) : std::nullopt; - const std::lock_guard lock(mutex_); if (isOnModifiedGoal(planner_data->self_odometry->pose.pose, modified_goal_opt, parameters)) { return false; } - constexpr double stuck_time = 5.0; - if (!isStopped( - odometry_buffer_stuck_, planner_data->self_odometry, stuck_time, - parameters_->th_stopped_velocity)) { + if (!req.is_stopped()) { return false; } - if (!found_pull_over_path) { + if (!req.get_pull_over_path()) { return true; } - const auto & pull_over_path = pull_over_path_opt.value(); if (parameters.use_object_recognition) { - const auto & path = pull_over_path.getCurrentPath(); + const auto & path = req.get_pull_over_path().value().getCurrentPath(); const auto curvatures = autoware::motion_utils::calcCurvature(path.points); + std::vector ego_polygons_expanded; if (goal_planner_utils::checkObjectsCollision( path, curvatures, static_target_objects, dynamic_target_objects, planner_data->parameters, parameters.object_recognition_collision_check_hard_margins.back(), /*extract_static_objects=*/false, parameters.maximum_deceleration, parameters.object_recognition_collision_check_max_extra_stopping_margin, - debug_data_.ego_polygons_expanded)) { + ego_polygons_expanded)) { return true; } } @@ -1790,7 +1803,7 @@ bool GoalPlannerModule::isStuck( if ( parameters.use_occupancy_grid_for_path_collision_check && checkOccupancyGridCollision( - thread_safe_data_.get_pull_over_path()->getCurrentPath(), occupancy_grid_map)) { + req.get_pull_over_path().value().getCurrentPath(), req.get_occupancy_grid_map())) { return true; } @@ -1805,9 +1818,7 @@ bool GoalPlannerModule::hasFinishedCurrentPath(const PullOverContextData & ctx_d return false; } - if (!isStopped( - odometry_buffer_stopped_, planner_data_->self_odometry, parameters_->th_stopped_time, - parameters_->th_stopped_velocity)) { + if (!ctx_data.is_stopped) { return false; } @@ -1824,10 +1835,12 @@ bool GoalPlannerModule::hasFinishedCurrentPath(const PullOverContextData & ctx_d // to prevent increment before driving // when the end of the current path is close to the current pose // this value should be `keep_stop_time` in keepStoppedWithCurrentPath + if (!ctx_data.last_path_update_time) { + return false; + } constexpr double keep_current_idx_time = 4.0; const bool has_passed_enough_time_from_increment = - (clock_->now() - *thread_safe_data_.get_last_path_update_time()).seconds() > - keep_current_idx_time; + (clock_->now() - ctx_data.last_path_update_time.value()).seconds() > keep_current_idx_time; if (!has_passed_enough_time_from_increment) { return false; } @@ -2433,8 +2446,8 @@ void GoalPlannerModule::setDebugData(const PullOverContextData & context_data) add(createPathMarkerArray(pull_over_path.getCurrentPath(), "current_path", 0, 0.9, 0.5, 0.0)); // visualize each partial path - for (size_t i = 0; i < context_data.pull_over_path_opt.value().partial_paths().size(); ++i) { - const auto & partial_path = context_data.pull_over_path_opt.value().partial_paths().at(i); + for (size_t i = 0; i < pull_over_path.partial_paths().size(); ++i) { + const auto & partial_path = pull_over_path.partial_paths().at(i); add( createPathMarkerArray(partial_path, "partial_path_" + std::to_string(i), 0, 0.9, 0.5, 0.9)); } @@ -2567,48 +2580,4 @@ void GoalPlannerModule::setDebugData(const PullOverContextData & context_data) } } -void GoalPlannerModule::GoalPlannerData::initializeOccupancyGridMap( - const PlannerData & planner_data, const GoalPlannerParameters & parameters) -{ - OccupancyGridMapParam occupancy_grid_map_param{}; - const double margin = parameters.occupancy_grid_collision_check_margin; - occupancy_grid_map_param.vehicle_shape.length = - planner_data.parameters.vehicle_length + 2 * margin; - occupancy_grid_map_param.vehicle_shape.width = planner_data.parameters.vehicle_width + 2 * margin; - occupancy_grid_map_param.vehicle_shape.base2back = - planner_data.parameters.base_link2rear + margin; - occupancy_grid_map_param.theta_size = parameters.theta_size; - occupancy_grid_map_param.obstacle_threshold = parameters.obstacle_threshold; - occupancy_grid_map = std::make_shared(); - occupancy_grid_map->setParam(occupancy_grid_map_param); -} - -GoalPlannerModule::GoalPlannerData GoalPlannerModule::GoalPlannerData::clone() const -{ - GoalPlannerModule::GoalPlannerData gp_planner_data( - planner_data, parameters, last_previous_module_output); - gp_planner_data.update( - parameters, planner_data, current_status, previous_module_output, vehicle_footprint, - goal_candidates); - return gp_planner_data; -} - -void GoalPlannerModule::GoalPlannerData::update( - const GoalPlannerParameters & parameters_, const PlannerData & planner_data_, - const ModuleStatus & current_status_, const BehaviorModuleOutput & previous_module_output_, - const autoware::universe_utils::LinearRing2d & vehicle_footprint_, - const GoalCandidates & goal_candidates_) -{ - parameters = parameters_; - vehicle_footprint = vehicle_footprint_; - - planner_data = planner_data_; - planner_data.route_handler = std::make_shared(*(planner_data_.route_handler)); - current_status = current_status_; - last_previous_module_output = previous_module_output; - previous_module_output = previous_module_output_; - occupancy_grid_map->setMap(*(planner_data.occupancy_grid)); - goal_candidates = goal_candidates_; -} - } // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp index f75358601d877..c0bac5c5ce2a8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp @@ -78,9 +78,6 @@ std::optional GeometricPullOver::plan( auto pull_over_path_opt = PullOverPath::create( getPlannerType(), id, planner_.getPaths(), planner_.getStartPose(), modified_goal_pose, planner_.getPairsTerminalVelocityAndAccel()); - if (!pull_over_path_opt) { - return {}; - } - return pull_over_path_opt.value(); + return pull_over_path_opt; } } // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp index 501502125d7ee..edecfd733d3be 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp @@ -67,7 +67,7 @@ std::optional ShiftPullOver::plan( modified_goal_pose, id, planner_data, previous_module_output, road_lanes, pull_over_lanes, lateral_jerk); if (!pull_over_path) continue; - return *pull_over_path; + return pull_over_path; } return {}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/thread_data.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/thread_data.cpp new file mode 100644 index 0000000000000..f12d510e23030 --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/thread_data.cpp @@ -0,0 +1,66 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include + +namespace autoware::behavior_path_planner +{ + +void LaneParkingRequest::update( + const PlannerData & planner_data, const ModuleStatus & current_status, + const BehaviorModuleOutput & previous_module_output, + const std::optional & pull_over_path, const PathDecisionState & prev_data) +{ + planner_data_ = std::make_shared(planner_data); + planner_data_->route_handler = std::make_shared(*(planner_data.route_handler)); + current_status_ = current_status; + last_previous_module_output_ = previous_module_output_; + previous_module_output_ = previous_module_output; + pull_over_path_ = pull_over_path; + prev_data_ = prev_data; +} + +void FreespaceParkingRequest::initializeOccupancyGridMap( + const PlannerData & planner_data, const GoalPlannerParameters & parameters) +{ + OccupancyGridMapParam occupancy_grid_map_param{}; + const double margin = parameters.occupancy_grid_collision_check_margin; + occupancy_grid_map_param.vehicle_shape.length = + planner_data.parameters.vehicle_length + 2 * margin; + occupancy_grid_map_param.vehicle_shape.width = planner_data.parameters.vehicle_width + 2 * margin; + occupancy_grid_map_param.vehicle_shape.base2back = + planner_data.parameters.base_link2rear + margin; + occupancy_grid_map_param.theta_size = parameters.theta_size; + occupancy_grid_map_param.obstacle_threshold = parameters.obstacle_threshold; + occupancy_grid_map_ = std::make_shared(); + occupancy_grid_map_->setParam(occupancy_grid_map_param); +} + +void FreespaceParkingRequest::update( + const PlannerData & planner_data, const ModuleStatus & current_status, + const std::optional & pull_over_path, + const std::optional & last_path_update_time, const bool is_stopped) +{ + planner_data_ = std::make_shared(planner_data); + planner_data_->route_handler = std::make_shared(*(planner_data.route_handler)); + current_status_ = current_status; + occupancy_grid_map_->setMap(*(planner_data_->occupancy_grid)); + pull_over_path_ = pull_over_path; + last_path_update_time_ = last_path_update_time; + is_stopped_ = is_stopped; +} + +} // namespace autoware::behavior_path_planner From 5ced41edbb054454f9afeab0c731a223b8a281a3 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 16 Dec 2024 00:32:32 +0900 Subject: [PATCH 017/334] feat(goal_planner): add bezier based pull over planner (#9642) Signed-off-by: Mamoru Sobue --- .../CMakeLists.txt | 1 + .../config/sample_planner_data_case1.yaml | 267 +++++++ .../config/sample_planner_data_case2.yaml | 261 +++++++ .../config/sample_planner_data_case3.yaml | 261 +++++++ .../examples/plot_map_case1.cpp | 706 ++++++++++++++++++ .../{plot_map.cpp => plot_map_case2.cpp} | 338 ++++++--- .../pull_over_planner/bezier_pull_over.hpp | 66 ++ .../pull_over_planner_base.hpp | 1 + .../package.xml | 3 +- .../pull_over_planner/bezier_pull_over.cpp | 404 ++++++++++ .../bezier_sampling.hpp | 3 + .../src/bezier_sampling.cpp | 27 + 12 files changed, 2218 insertions(+), 120 deletions(-) create mode 100644 planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/sample_planner_data_case1.yaml create mode 100644 planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/sample_planner_data_case2.yaml create mode 100644 planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/sample_planner_data_case3.yaml create mode 100644 planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case1.cpp rename planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/{plot_map.cpp => plot_map_case2.cpp} (66%) create mode 100644 planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/bezier_pull_over.hpp create mode 100644 planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/bezier_pull_over.cpp diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/CMakeLists.txt b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/CMakeLists.txt index d680fd2ecd695..bc8705dc76174 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/CMakeLists.txt +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/CMakeLists.txt @@ -14,6 +14,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/pull_over_planner/freespace_pull_over.cpp src/pull_over_planner/geometric_pull_over.cpp src/pull_over_planner/shift_pull_over.cpp + src/pull_over_planner/bezier_pull_over.cpp src/default_fixed_goal_planner.cpp src/goal_searcher.cpp src/util.cpp diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/sample_planner_data_case1.yaml b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/sample_planner_data_case1.yaml new file mode 100644 index 0000000000000..7bbc4b54e7f08 --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/sample_planner_data_case1.yaml @@ -0,0 +1,267 @@ +# +# AUTO GENERATED by autoware_test_utils::topic_snapshot_saver +# format1: +# +# format_version: +# map_path_uri: package:/// +# fields(this is array) +# - name: +# type: either {Odometry | AccelWithCovarianceStamped | PredictedObjects | OperationModeState | LaneletRoute | TrafficLightGroupArray | TBD} +# topic: +# +format_version: 1 +map_path_uri: package://autoware_test_utils/test_map/road_shoulder/lanelet2_map.osm +dynamic_object: + header: + stamp: + sec: 909 + nanosec: 742399532 + frame_id: map + objects: [] +traffic_signal: + stamp: + sec: 0 + nanosec: 0 + traffic_light_groups: [] +route: + header: + stamp: + sec: 125 + nanosec: 213336488 + frame_id: map + start_pose: + position: + x: 748.132 + y: 708.703 + z: 381.187 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.235076 + w: 0.971977 + goal_pose: + position: + x: 798.040 + y: 689.386 + z: 381.187 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.659713 + w: 0.751517 + segments: + - preferred_primitive: + id: 15214 + primitive_type: "" + primitives: + - id: 15214 + primitive_type: lane + - id: 15213 + primitive_type: lane + - preferred_primitive: + id: 15226 + primitive_type: "" + primitives: + - id: 15226 + primitive_type: lane + - id: 15225 + primitive_type: lane + - preferred_primitive: + id: 15228 + primitive_type: "" + primitives: + - id: 15228 + primitive_type: lane + - id: 15229 + primitive_type: lane + - preferred_primitive: + id: 15231 + primitive_type: "" + primitives: + - id: 15231 + primitive_type: lane + uuid: + uuid: + - 100 + - 171 + - 232 + - 218 + - 65 + - 244 + - 197 + - 172 + - 167 + - 40 + - 148 + - 169 + - 170 + - 48 + - 29 + - 68 + allow_modification: false +operation_mode: + stamp: + sec: 902 + nanosec: 525199106 + mode: 2 + is_autoware_control_enabled: true + is_in_transition: false + is_stop_mode_available: true + is_autonomous_mode_available: true + is_local_mode_available: true + is_remote_mode_available: true +self_acceleration: + header: + stamp: + sec: 909 + nanosec: 769937073 + frame_id: /base_link + accel: + accel: + linear: + x: -0.581360 + y: -0.290347 + z: 0.00000 + angular: + x: 0.00000 + y: 0.00000 + z: 0.00000 + covariance: + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 +self_odometry: + header: + stamp: + sec: 909 + nanosec: 769937073 + frame_id: map + child_frame_id: base_link + pose: + pose: + position: + x: 760.155 + y: 713.417 + z: 381.187 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.116943 + w: 0.993139 + covariance: + - 0.000100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.000100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + twist: + twist: + linear: + x: 3.83825 + y: 0.00000 + z: 0.00000 + angular: + x: 0.00000 + y: 0.00000 + z: -0.0756457 + covariance: + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/sample_planner_data_case2.yaml b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/sample_planner_data_case2.yaml new file mode 100644 index 0000000000000..ab86692166164 --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/sample_planner_data_case2.yaml @@ -0,0 +1,261 @@ +# +# AUTO GENERATED by autoware_test_utils::topic_snapshot_saver +# format1: +# +# format_version: +# map_path_uri: package:/// +# fields(this is array) +# - name: +# type: either {Odometry | AccelWithCovarianceStamped | PredictedObjects | OperationModeState | LaneletRoute | TrafficLightGroupArray | TrackedObjects | TBD} +# topic: +# +format_version: 1 +map_path_uri: package://autoware_test_utils/test_map/road_shoulder/lanelet2_map.osm +dynamic_object: + header: + stamp: + sec: 57 + nanosec: 642011543 + frame_id: map + objects: [] +traffic_signal: + stamp: + sec: 0 + nanosec: 0 + traffic_light_groups: [] +route: + header: + stamp: + sec: 49 + nanosec: 727009929 + frame_id: map + start_pose: + position: + x: 266.506 + y: 343.545 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.695321 + w: 0.718700 + goal_pose: + position: + x: 291.295 + y: 346.135 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.999225 + w: 0.0393747 + segments: + - preferred_primitive: + id: 697 + primitive_type: "" + primitives: + - id: 697 + primitive_type: lane + - preferred_primitive: + id: 759 + primitive_type: "" + primitives: + - id: 759 + primitive_type: lane + - preferred_primitive: + id: 675 + primitive_type: "" + primitives: + - id: 675 + primitive_type: lane + - preferred_primitive: + id: 676 + primitive_type: "" + primitives: + - id: 676 + primitive_type: lane + uuid: + uuid: + - 126 + - 92 + - 126 + - 245 + - 182 + - 56 + - 251 + - 150 + - 125 + - 65 + - 22 + - 180 + - 59 + - 40 + - 250 + - 241 + allow_modification: false +operation_mode: + stamp: + sec: 40 + nanosec: 229462653 + mode: 2 + is_autoware_control_enabled: true + is_in_transition: false + is_stop_mode_available: true + is_autonomous_mode_available: true + is_local_mode_available: true + is_remote_mode_available: true +self_acceleration: + header: + stamp: + sec: 57 + nanosec: 675161172 + frame_id: /base_link + accel: + accel: + linear: + x: -0.0735332 + y: -0.539254 + z: 0.00000 + angular: + x: 0.00000 + y: 0.00000 + z: 0.00000 + covariance: + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 +self_odometry: + header: + stamp: + sec: 57 + nanosec: 675161172 + frame_id: map + child_frame_id: base_link + pose: + pose: + position: + x: 288.819 + y: 363.189 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.0508455 + w: 0.998707 + covariance: + - 0.000100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.000100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + twist: + twist: + linear: + x: 1.95939 + y: 0.00000 + z: 0.00000 + angular: + x: 0.00000 + y: 0.00000 + z: -0.275215 + covariance: + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/sample_planner_data_case3.yaml b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/sample_planner_data_case3.yaml new file mode 100644 index 0000000000000..48a84480dd3a4 --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/sample_planner_data_case3.yaml @@ -0,0 +1,261 @@ +# +# AUTO GENERATED by autoware_test_utils::topic_snapshot_saver +# format1: +# +# format_version: +# map_path_uri: package:/// +# fields(this is array) +# - name: +# type: either {Odometry | AccelWithCovarianceStamped | PredictedObjects | OperationModeState | LaneletRoute | TrafficLightGroupArray | TrackedObjects | TBD} +# topic: +# +format_version: 1 +map_path_uri: package://autoware_test_utils/test_map/road_shoulder/lanelet2_map.osm +dynamic_object: + header: + stamp: + sec: 59 + nanosec: 863135063 + frame_id: map + objects: [] +traffic_signal: + stamp: + sec: 0 + nanosec: 0 + traffic_light_groups: [] +route: + header: + stamp: + sec: 49 + nanosec: 727009929 + frame_id: map + start_pose: + position: + x: 266.506 + y: 343.545 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.695321 + w: 0.718700 + goal_pose: + position: + x: 291.295 + y: 346.135 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.999225 + w: 0.0393747 + segments: + - preferred_primitive: + id: 697 + primitive_type: "" + primitives: + - id: 697 + primitive_type: lane + - preferred_primitive: + id: 759 + primitive_type: "" + primitives: + - id: 759 + primitive_type: lane + - preferred_primitive: + id: 675 + primitive_type: "" + primitives: + - id: 675 + primitive_type: lane + - preferred_primitive: + id: 676 + primitive_type: "" + primitives: + - id: 676 + primitive_type: lane + uuid: + uuid: + - 126 + - 92 + - 126 + - 245 + - 182 + - 56 + - 251 + - 150 + - 125 + - 65 + - 22 + - 180 + - 59 + - 40 + - 250 + - 241 + allow_modification: false +operation_mode: + stamp: + sec: 40 + nanosec: 229462653 + mode: 2 + is_autoware_control_enabled: true + is_in_transition: false + is_stop_mode_available: true + is_autonomous_mode_available: true + is_local_mode_available: true + is_remote_mode_available: true +self_acceleration: + header: + stamp: + sec: 59 + nanosec: 863135063 + frame_id: /base_link + accel: + accel: + linear: + x: 0.0180450 + y: -0.573187 + z: 0.00000 + angular: + x: 0.00000 + y: 0.00000 + z: 0.00000 + covariance: + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 +self_odometry: + header: + stamp: + sec: 59 + nanosec: 863135063 + frame_id: map + child_frame_id: base_link + pose: + pose: + position: + x: 292.928 + y: 362.175 + z: 100.000 + orientation: + x: 0.00000 + y: -0.00000 + z: -0.283955 + w: 0.958837 + covariance: + - 0.000100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.000100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + twist: + twist: + linear: + x: 2.01175 + y: 0.00000 + z: 0.00000 + angular: + x: 0.00000 + y: 0.00000 + z: -0.284920 + covariance: + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case1.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case1.cpp new file mode 100644 index 0000000000000..56e207c160873 --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case1.cpp @@ -0,0 +1,706 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/behavior_path_goal_planner_module/goal_searcher.hpp" +#include "autoware/behavior_path_goal_planner_module/util.hpp" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace std::chrono_literals; // NOLINT + +using autoware::behavior_path_planner::BehaviorModuleOutput; +using autoware::behavior_path_planner::GoalCandidate; +using autoware::behavior_path_planner::GoalCandidates; +using autoware::behavior_path_planner::GoalPlannerParameters; +using autoware::behavior_path_planner::PlannerData; +using autoware::behavior_path_planner::PullOverPath; +using autoware::behavior_path_planner::utils::parking_departure::calcFeasibleDecelDistance; +using autoware_planning_msgs::msg::LaneletRoute; +using tier4_planning_msgs::msg::PathWithLaneId; + +std::vector g_colors = { + "#F0F8FF", "#FAEBD7", "#00FFFF", "#7FFFD4", "#F0FFFF", "#F5F5DC", "#FFE4C4", "#000000", "#FFEBCD", + "#0000FF", "#8A2BE2", "#A52A2A", "#DEB887", "#5F9EA0", "#7FFF00", "#D2691E", "#FF7F50", "#6495ED", + "#FFF8DC", "#DC143C", "#00FFFF", "#00008B", "#008B8B", "#B8860B", "#A9A9A9", "#006400", "#A9A9A9", + "#BDB76B", "#8B008B", "#556B2F", "#FF8C00", "#9932CC", "#8B0000", "#E9967A", "#8FBC8F", "#483D8B", + "#2F4F4F", "#2F4F4F", "#00CED1", "#9400D3", "#FF1493", "#00BFFF", "#696969", "#696969", "#1E90FF", + "#B22222", "#FFFAF0", "#228B22", "#FF00FF", "#DCDCDC", "#F8F8FF", "#FFD700", "#DAA520", "#808080", + "#008000", "#ADFF2F", "#808080", "#F0FFF0", "#FF69B4", "#CD5C5C", "#4B0082", "#FFFFF0", "#F0E68C", + "#E6E6FA", "#FFF0F5", "#7CFC00", "#FFFACD", "#ADD8E6", "#F08080", "#E0FFFF", "#FAFAD2", "#D3D3D3", + "#90EE90", "#D3D3D3", "#FFB6C1", "#FFA07A", "#20B2AA", "#87CEFA", "#778899", "#778899", "#B0C4DE", + "#FFFFE0", "#00FF00", "#32CD32", "#FAF0E6", "#FF00FF", "#800000", "#66CDAA", "#0000CD", "#BA55D3", + "#9370DB", "#3CB371", "#7B68EE", "#00FA9A", "#48D1CC", "#C71585", "#191970", "#F5FFFA", "#FFE4E1", + "#FFE4B5", "#FFDEAD", "#000080", "#FDF5E6", "#808000", "#6B8E23", "#FFA500", "#FF4500", "#DA70D6", + "#EEE8AA", "#98FB98", "#AFEEEE", "#DB7093", "#FFEFD5", "#FFDAB9", "#CD853F", "#FFC0CB", "#DDA0DD", + "#B0E0E6", "#800080", "#663399", "#FF0000", "#BC8F8F", "#4169E1", "#8B4513", "#FA8072", "#F4A460", + "#2E8B57", "#FFF5EE", "#A0522D", "#C0C0C0", "#87CEEB", "#6A5ACD", "#708090", "#708090", "#FFFAFA", + "#00FF7F", "#4682B4", "#D2B48C", "#008080", "#D8BFD8", "#FF6347", "#40E0D0", "#EE82EE", "#F5DEB3", + "#FFFFFF", "#F5F5F5", "#FFFF00", "#9ACD32"}; + +void plot_footprint( + matplotlibcpp17::axes::Axes & axes, const autoware::universe_utils::LinearRing2d & footprint, + const std::string & color) +{ + std::vector xs, ys; + for (const auto & pt : footprint) { + xs.push_back(pt.x()); + ys.push_back(pt.y()); + } + xs.push_back(xs.front()); + ys.push_back(ys.front()); + axes.plot(Args(xs, ys), Kwargs("color"_a = color, "linestyle"_a = "dotted")); +} + +void plot_lanelet_polygon(matplotlibcpp17::axes::Axes & axes, const lanelet::BasicPolygon2d polygon) +{ + std::vector xs, ys; + for (const auto & p : polygon) { + xs.push_back(p.x()); + ys.push_back(p.y()); + } + xs.push_back(xs.front()); + ys.push_back(ys.front()); + axes.fill(Args(xs, ys), Kwargs("color"_a = "grey", "alpha"_a = 0.5)); +} + +void plot_goal_candidate( + matplotlibcpp17::axes::Axes & axes, const GoalCandidate & goal, const size_t prio, + const autoware::universe_utils::LinearRing2d & local_footprint, const std::string & color) +{ + std::vector xs, ys; + std::vector yaw_cos, yaw_sin; + const auto goal_footprint = + transformVector(local_footprint, autoware::universe_utils::pose2transform(goal.goal_pose)); + plot_footprint(axes, goal_footprint, color); + xs.push_back(goal.goal_pose.position.x); + ys.push_back(goal.goal_pose.position.y); + axes.text(Args(xs.back(), ys.back(), std::to_string(prio))); + const double yaw = autoware::universe_utils::getRPY(goal.goal_pose).z; + yaw_cos.push_back(std::cos(yaw)); + yaw_sin.push_back(std::sin(yaw)); + axes.scatter(Args(xs, ys), Kwargs("color"_a = color)); + axes.quiver( + Args(xs, ys, yaw_cos, yaw_sin), + Kwargs("angles"_a = "xy", "scale_units"_a = "xy", "scale"_a = 2.0)); +} + +void plot_goal_candidates( + matplotlibcpp17::axes::Axes & axes, const GoalCandidates & goals, + const std::map & goal_id2prio, + const autoware::universe_utils::LinearRing2d & local_footprint, + const std::string & color = "green") +{ + for (const auto & goal : goals) { + const auto it = goal_id2prio.find(goal.id); + if (it != goal_id2prio.end()) { + plot_goal_candidate(axes, goal, it->second, local_footprint, color); + } + } +} + +void plot_path_with_lane_id( + matplotlibcpp17::axes::Axes & axes, const PathWithLaneId & path, + const std::string & color = "red", const std::string & label = "", const double linewidth = 1.0) +{ + std::vector xs, ys; + std::vector yaw_cos, yaw_sin; + for (const auto & point : path.points) { + xs.push_back(point.point.pose.position.x); + ys.push_back(point.point.pose.position.y); + const double yaw = autoware::universe_utils::getRPY(point.point.pose).z; + yaw_cos.push_back(std::cos(yaw)); + yaw_sin.push_back(std::sin(yaw)); + axes.scatter( + Args(xs.back(), ys.back()), Kwargs("marker"_a = "o", "color"_a = "blue", "s"_a = 10)); + } + axes.quiver( + Args(xs, ys, yaw_cos, yaw_sin), + Kwargs("angles"_a = "xy", "scale_units"_a = "xy", "scale"_a = 2.0)); + + if (label == "") { + axes.plot(Args(xs, ys), Kwargs("color"_a = color, "linewidth"_a = linewidth)); + } else { + axes.plot( + Args(xs, ys), Kwargs("color"_a = color, "linewidth"_a = linewidth, "label"_a = label)); + } +} + +void plot_lanelet( + matplotlibcpp17::axes::Axes & axes, lanelet::ConstLanelet lanelet, + const std::string & color = "blue", const double linewidth = 0.5) +{ + const auto lefts = lanelet.leftBound(); + const auto rights = lanelet.rightBound(); + std::vector xs_left, ys_left; + for (const auto & point : lefts) { + xs_left.push_back(point.x()); + ys_left.push_back(point.y()); + } + + std::vector xs_right, ys_right; + for (const auto & point : rights) { + xs_right.push_back(point.x()); + ys_right.push_back(point.y()); + } + + std::vector xs_center, ys_center; + for (const auto & point : lanelet.centerline()) { + xs_center.push_back(point.x()); + ys_center.push_back(point.y()); + } + + axes.plot(Args(xs_left, ys_left), Kwargs("color"_a = color, "linewidth"_a = linewidth)); + axes.plot(Args(xs_right, ys_right), Kwargs("color"_a = color, "linewidth"_a = linewidth)); + axes.plot( + Args(xs_center, ys_center), + Kwargs("color"_a = "black", "linewidth"_a = linewidth, "linestyle"_a = "dashed")); +} + +std::shared_ptr instantiate_planner_data( + rclcpp::Node::SharedPtr node, const std::string & map_path, + const std::string & sample_planner_data_yaml_path) +{ + lanelet::ErrorMessages errors{}; + lanelet::projection::MGRSProjector projector{}; + const lanelet::LaneletMapPtr lanelet_map_ptr = lanelet::load(map_path, projector, &errors); + if (!errors.empty()) { + for (const auto & error : errors) { + std::cout << error << std::endl; + } + return nullptr; + } + autoware_map_msgs::msg::LaneletMapBin map_bin; + lanelet::utils::conversion::toBinMsg( + lanelet_map_ptr, &map_bin); // TODO(soblin): pass lanelet_map_ptr to RouteHandler + + YAML::Node config = YAML::LoadFile(sample_planner_data_yaml_path); + + auto planner_data = std::make_shared(); + planner_data->init_parameters(*node); + planner_data->route_handler->setMap(map_bin); + planner_data->route_handler->setRoute( + autoware::test_utils::parse(config["route"])); + + auto odometry = autoware::test_utils::create_const_shared_ptr( + autoware::test_utils::parse(config["self_odometry"])); + planner_data->self_odometry = odometry; + + auto accel_ptr = autoware::test_utils::create_const_shared_ptr( + autoware::test_utils::parse( + config["self_acceleration"])); + planner_data->self_acceleration = accel_ptr; + return planner_data; +} + +bool hasEnoughDistance( + const PullOverPath & pull_over_path, const PathWithLaneId & long_tail_reference_path, + const std::shared_ptr planner_data, const GoalPlannerParameters & parameters) +{ + using autoware::motion_utils::calcSignedArcLength; + + const Pose & current_pose = planner_data->self_odometry->pose.pose; + const double current_vel = planner_data->self_odometry->twist.twist.linear.x; + + // when the path is separated and start_pose is close, + // once stopped, the vehicle cannot start again. + // so need enough distance to restart. + // distance to restart should be less than decide_path_distance. + // otherwise, the goal would change immediately after departure. + const bool is_separated_path = pull_over_path.partial_paths().size() > 1; + const double distance_to_start = calcSignedArcLength( + long_tail_reference_path.points, current_pose.position, pull_over_path.start_pose().position); + const double distance_to_restart = parameters.decide_path_distance / 2; + const double eps_vel = 0.01; + const bool is_stopped = std::abs(current_vel) < eps_vel; + if (is_separated_path && is_stopped && distance_to_start < distance_to_restart) { + return false; + } + + const auto current_to_stop_distance = calcFeasibleDecelDistance( + planner_data, parameters.maximum_deceleration, parameters.maximum_jerk, 0.0); + if (!current_to_stop_distance) { + return false; + } + + /* + // If the stop line is subtly exceeded, it is assumed that there is not enough distance to the + // starting point of parking, so to prevent this, once the vehicle has stopped, it also has a + // stop_distance_buffer to allow for the amount exceeded. + const double buffer = is_stopped ? stop_distance_buffer_ : 0.0; + if (distance_to_start + buffer < *current_to_stop_distance) { + return false; + }*/ + + return true; +} + +std::vector selectPullOverPaths( + const std::vector & pull_over_path_candidates, + const GoalCandidates & goal_candidates, const std::shared_ptr planner_data, + const GoalPlannerParameters & parameters, const BehaviorModuleOutput & previous_module_output) +{ + using autoware::behavior_path_planner::utils::getExtendedCurrentLanesFromPath; + using autoware::motion_utils::calcSignedArcLength; + + const auto & goal_pose = planner_data->route_handler->getOriginalGoalPose(); + const double backward_length = + parameters.backward_goal_search_length + parameters.decide_path_distance; + + std::vector sorted_path_indices; + sorted_path_indices.reserve(pull_over_path_candidates.size()); + + std::unordered_map goal_candidate_map; + for (const auto & goal_candidate : goal_candidates) { + goal_candidate_map[goal_candidate.id] = goal_candidate; + } + for (size_t i = 0; i < pull_over_path_candidates.size(); ++i) { + const auto & path = pull_over_path_candidates[i]; + const auto goal_candidate_it = goal_candidate_map.find(path.goal_id()); + if (goal_candidate_it != goal_candidate_map.end() && goal_candidate_it->second.is_safe) { + sorted_path_indices.push_back(i); + } + } + + const double prev_path_front_to_goal_dist = calcSignedArcLength( + previous_module_output.path.points, + previous_module_output.path.points.front().point.pose.position, goal_pose.position); + const auto & long_tail_reference_path = [&]() { + if (prev_path_front_to_goal_dist > backward_length) { + return previous_module_output.path; + } + // get road lanes which is at least backward_length[m] behind the goal + const auto road_lanes = getExtendedCurrentLanesFromPath( + previous_module_output.path, planner_data, backward_length, 0.0, false); + const auto goal_pose_length = lanelet::utils::getArcCoordinates(road_lanes, goal_pose).length; + return planner_data->route_handler->getCenterLinePath( + road_lanes, std::max(0.0, goal_pose_length - backward_length), + goal_pose_length + parameters.forward_goal_search_length); + }(); + + sorted_path_indices.erase( + std::remove_if( + sorted_path_indices.begin(), sorted_path_indices.end(), + [&](const size_t i) { + return !hasEnoughDistance( + pull_over_path_candidates[i], long_tail_reference_path, planner_data, parameters); + }), + sorted_path_indices.end()); + + const auto & soft_margins = parameters.object_recognition_collision_check_soft_margins; + const auto & hard_margins = parameters.object_recognition_collision_check_hard_margins; + + const auto [margins, margins_with_zero] = + std::invoke([&]() -> std::tuple, std::vector> { + std::vector margins = soft_margins; + margins.insert(margins.end(), hard_margins.begin(), hard_margins.end()); + std::vector margins_with_zero = margins; + margins_with_zero.push_back(0.0); + return std::make_tuple(margins, margins_with_zero); + }); + + // Create a map of PullOverPath pointer to largest collision check margin + std::map path_id_to_rough_margin_map; + const auto & target_objects = autoware_perception_msgs::msg::PredictedObjects{}; + for (const size_t i : sorted_path_indices) { + const auto & path = pull_over_path_candidates[i]; // cppcheck-suppress containerOutOfBounds + const double distance = + autoware::behavior_path_planner::utils::path_safety_checker::calculateRoughDistanceToObjects( + path.parking_path(), target_objects, planner_data->parameters, false, "max"); + auto it = std::lower_bound( + margins_with_zero.begin(), margins_with_zero.end(), distance, std::greater()); + if (it == margins_with_zero.end()) { + path_id_to_rough_margin_map[path.id()] = margins_with_zero.back(); + } else { + path_id_to_rough_margin_map[path.id()] = *it; + } + } + + // sorts in descending order so the item with larger margin comes first + std::stable_sort( + sorted_path_indices.begin(), sorted_path_indices.end(), + [&](const size_t a_i, const size_t b_i) { + const auto & a = pull_over_path_candidates[a_i]; + const auto & b = pull_over_path_candidates[b_i]; + if ( + std::abs(path_id_to_rough_margin_map[a.id()] - path_id_to_rough_margin_map[b.id()]) < + 0.01) { + return false; + } + return path_id_to_rough_margin_map[a.id()] > path_id_to_rough_margin_map[b.id()]; + }); + + // STEP2-3: Sort by curvature + // If the curvature is less than the threshold, prioritize the path. + const auto isHighCurvature = [&](const PullOverPath & path) -> bool { + return path.parking_path_max_curvature() >= parameters.high_curvature_threshold; + }; + + const auto isSoftMargin = [&](const PullOverPath & path) -> bool { + const double margin = path_id_to_rough_margin_map[path.id()]; + return std::any_of( + soft_margins.begin(), soft_margins.end(), + [margin](const double soft_margin) { return std::abs(margin - soft_margin) < 0.01; }); + }; + const auto isSameHardMargin = [&](const PullOverPath & a, const PullOverPath & b) -> bool { + return !isSoftMargin(a) && !isSoftMargin(b) && + std::abs(path_id_to_rough_margin_map[a.id()] - path_id_to_rough_margin_map[b.id()]) < + 0.01; + }; + + // NOTE: this is just partition sort based on curvature threshold within each sub partitions + std::stable_sort( + sorted_path_indices.begin(), sorted_path_indices.end(), + [&](const size_t a_i, const size_t b_i) { + const auto & a = pull_over_path_candidates[a_i]; + const auto & b = pull_over_path_candidates[b_i]; + // if both are soft margin or both are same hard margin, prioritize the path with lower + // curvature. + if ((isSoftMargin(a) && isSoftMargin(b)) || isSameHardMargin(a, b)) { + return !isHighCurvature(a) && isHighCurvature(b); + } + // otherwise, keep the order based on the margin. + return false; + }); + + // STEP2-4: Sort pull_over_path_candidates based on the order in efficient_path_order keeping + // the collision check margin and curvature priority. + if (parameters.path_priority == "efficient_path") { + std::stable_sort( + sorted_path_indices.begin(), sorted_path_indices.end(), + [&](const size_t a_i, const size_t b_i) { + // if any of following conditions are met, sort by path type priority + // - both are soft margin + // - both are same hard margin + const auto & a = pull_over_path_candidates[a_i]; + const auto & b = pull_over_path_candidates[b_i]; + // otherwise, keep the order. + return false; + }); + } + + std::vector selected; + for (const auto & sorted_index : sorted_path_indices) { + selected.push_back(pull_over_path_candidates.at(sorted_index)); + } + + return selected; +} + +std::optional calculate_centerline_path( + const std::shared_ptr planner_data, const GoalPlannerParameters & parameters) +{ + const auto original_goal_pose = planner_data->route_handler->getOriginalGoalPose(); + const auto refined_goal_opt = + autoware::behavior_path_planner::goal_planner_utils::calcRefinedGoal( + original_goal_pose, planner_data->route_handler, true, + planner_data->parameters.vehicle_length, planner_data->parameters.base_link2front, + planner_data->parameters.base_link2front, parameters); + if (!refined_goal_opt) { + return std::nullopt; + } + const auto & refined_goal = refined_goal_opt.value(); + + const auto & route_handler = planner_data->route_handler; + const double forward_length = parameters.forward_goal_search_length; + const double backward_length = parameters.backward_goal_search_length; + const bool use_bus_stop_area = parameters.bus_stop_area.use_bus_stop_area; + /* + const double margin_from_boundary = parameters.margin_from_boundary; + const double lateral_offset_interval = use_bus_stop_area + ? parameters.bus_stop_area.lateral_offset_interval + : parameters.lateral_offset_interval; + const double max_lateral_offset = parameters.max_lateral_offset; + const double ignore_distance_from_lane_start = parameters.ignore_distance_from_lane_start; + */ + + const auto pull_over_lanes = + autoware::behavior_path_planner::goal_planner_utils::getPullOverLanes( + *route_handler, true, parameters.backward_goal_search_length, + parameters.forward_goal_search_length); + const auto departure_check_lane = + autoware::behavior_path_planner::goal_planner_utils::createDepartureCheckLanelet( + pull_over_lanes, *route_handler, true); + const auto goal_arc_coords = lanelet::utils::getArcCoordinates(pull_over_lanes, refined_goal); + const double s_start = std::max(0.0, goal_arc_coords.length - backward_length); + const double s_end = goal_arc_coords.length + forward_length; + const double longitudinal_interval = use_bus_stop_area + ? parameters.bus_stop_area.goal_search_interval + : parameters.goal_search_interval; + auto center_line_path = autoware::behavior_path_planner::utils::resamplePathWithSpline( + route_handler->getCenterLinePath(pull_over_lanes, s_start, s_end), longitudinal_interval); + return center_line_path; +} + +std::vector getBusStopAreaPolygons( + const std::shared_ptr planner_data, const GoalPlannerParameters & parameters) +{ + const auto pull_over_lanes = + autoware::behavior_path_planner::goal_planner_utils::getPullOverLanes( + *(planner_data->route_handler), true, parameters.backward_goal_search_length, + parameters.forward_goal_search_length); + return autoware::behavior_path_planner::goal_planner_utils::getBusStopAreaPolygons( + pull_over_lanes); +} + +struct SortByWeightedDistance +{ + double lateral_cost{0.0}; + bool prioritize_goals_before_objects{false}; + + SortByWeightedDistance(double cost, bool prioritize_goals_before_objects) + : lateral_cost(cost), prioritize_goals_before_objects(prioritize_goals_before_objects) + { + } + + bool operator()(const GoalCandidate & a, const GoalCandidate & b) const noexcept + { + if (prioritize_goals_before_objects) { + if (a.num_objects_to_avoid != b.num_objects_to_avoid) { + return a.num_objects_to_avoid < b.num_objects_to_avoid; + } + } + + return a.distance_from_original_goal + lateral_cost * a.lateral_offset < + b.distance_from_original_goal + lateral_cost * b.lateral_offset; + } +}; + +int main(int argc, char ** argv) +{ + using autoware::behavior_path_planner::utils::getReferencePath; + rclcpp::init(argc, argv); + + auto node_options = rclcpp::NodeOptions{}; + node_options.parameter_overrides( + std::vector{{"launch_modules", std::vector{}}}); + node_options.arguments(std::vector{ + "--ros-args", "--params-file", + ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner") + + "/config/behavior_path_planner.param.yaml", + "--params-file", + ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner") + + "/config/drivable_area_expansion.param.yaml", + "--params-file", + ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner") + + "/config/scene_module_manager.param.yaml", + "--params-file", + ament_index_cpp::get_package_share_directory("autoware_test_utils") + + "/config/test_common.param.yaml", + "--params-file", + ament_index_cpp::get_package_share_directory("autoware_test_utils") + + "/config/test_nearest_search.param.yaml", + "--params-file", + ament_index_cpp::get_package_share_directory("autoware_test_utils") + + "/config/test_vehicle_info.param.yaml", + "--params-file", + ament_index_cpp::get_package_share_directory("autoware_behavior_path_goal_planner_module") + + "/config/goal_planner.param.yaml"}); + auto node = rclcpp::Node::make_shared("plot_map", node_options); + + auto planner_data = instantiate_planner_data( + node, + ament_index_cpp::get_package_share_directory("autoware_test_utils") + + "/test_map/road_shoulder/lanelet2_map.osm", + ament_index_cpp::get_package_share_directory("autoware_behavior_path_goal_planner_module") + + "/config/sample_planner_data_case1.yaml"); + + lanelet::ConstLanelet current_route_lanelet; + planner_data->route_handler->getClosestLaneletWithinRoute( + planner_data->self_odometry->pose.pose, ¤t_route_lanelet); + const auto reference_path = getReferencePath(current_route_lanelet, planner_data); + auto goal_planner_parameter = + autoware::behavior_path_planner::GoalPlannerModuleManager::initGoalPlannerParameters( + node.get(), "goal_planner."); + goal_planner_parameter.bus_stop_area.use_bus_stop_area = true; + goal_planner_parameter.lane_departure_check_expansion_margin = 0.2; + const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(*node).getVehicleInfo(); + autoware::lane_departure_checker::LaneDepartureChecker lane_departure_checker{}; + lane_departure_checker.setVehicleInfo(vehicle_info); + autoware::lane_departure_checker::Param lane_departure_checker_params; + lane_departure_checker_params.footprint_extra_margin = + goal_planner_parameter.lane_departure_check_expansion_margin; + lane_departure_checker.setParam(lane_departure_checker_params); + const auto footprint = vehicle_info.createFootprint(); + autoware::behavior_path_planner::GoalSearcher goal_searcher(goal_planner_parameter, footprint); + auto goal_candidates = goal_searcher.search(planner_data); + std::sort( + goal_candidates.begin(), goal_candidates.end(), + SortByWeightedDistance( + goal_planner_parameter.minimum_weighted_distance_lateral_weight, + goal_planner_parameter.prioritize_goals_before_objects)); + std::map goal_id2prio{}; + for (auto i = 0; i < goal_candidates.size(); ++i) { + goal_id2prio[goal_candidates.at(i).id] = i; + } + + pybind11::scoped_interpreter guard{}; + auto plt = matplotlibcpp17::pyplot::import(); + auto [fig, axes] = plt.subplots(1, 2); + + auto & ax1 = axes[0]; + auto & ax2 = axes[1]; + // auto & ax3 = axes[2]; + const std::vector ids{/*15213, 15214, */ 15225, + 15226, + 15224, + 15227, + 15228, + 15229, + 15230, + 15231, + 15232}; + for (const auto & id : ids) { + const auto lanelet = planner_data->route_handler->getLaneletMapPtr()->laneletLayer.get(id); + plot_lanelet(ax1, lanelet); + plot_lanelet(ax2, lanelet); + // plot_lanelet(ax3, lanelet); + } + + // plot_goal_candidates(ax1, goal_candidates, footprint); + + // plot_path_with_lane_id(ax2, reference_path.path, "green", "reference_path"); + + const auto start = std::chrono::steady_clock::now(); + std::vector candidates; + for (auto i = 0; i < goal_candidates.size(); ++i) { + const auto & goal_candidate = goal_candidates.at(i); + auto shift_pull_over_planner = autoware::behavior_path_planner::BezierPullOver( + *node, goal_planner_parameter, lane_departure_checker); + auto pull_over_paths = + shift_pull_over_planner.plans(goal_candidate, 0, planner_data, reference_path); + if (!pull_over_paths.empty()) { + std::copy( + std::make_move_iterator(pull_over_paths.begin()), + std::make_move_iterator(pull_over_paths.end()), std::back_inserter(candidates)); + } + } + + const auto filtered_paths = selectPullOverPaths( + candidates, goal_candidates, planner_data, goal_planner_parameter, reference_path); + std::cout << filtered_paths.size() << std::endl; + const auto end = std::chrono::steady_clock::now(); + std::cout << "computed candidate bezier paths in " + << std::chrono::duration_cast(end - start).count() * 1.0 / + 1000000 + << "msecs" << std::endl; + std::cout << "filtered " << filtered_paths.size() << "/" << candidates.size() << " paths" + << std::endl; + /* + for (auto i = 0; i < filtered_paths.size(); ++i) { + const auto & filtered_path = filtered_paths.at(i); + const auto goal_id = filtered_path.goal_id(); + const auto prio = goal_id2prio[goal_id]; + const auto & color = (i == 0) ? "red" : g_colors.at(i % g_colors.size()); + const auto max_parking_curvature = filtered_path.parking_path_max_curvature(); + plot_goal_candidate(ax1, filtered_path.modified_goal(), prio, footprint, color); + if (i == 0) { + plot_path_with_lane_id(ax1, filtered_path.parking_path(), color, "most prio", 2.0); + } else { + plot_path_with_lane_id( + ax1, filtered_path.full_path(), color, + std::to_string(prio) + "-th goal(id=" + std::to_string(goal_id) + + "): k_max=" + std::to_string(max_parking_curvature), + 0.5); + } + } + */ + const auto original_goal_pos = planner_data->route_handler->getOriginalGoalPose().position; + ax1.plot( + Args(original_goal_pos.x, original_goal_pos.y), + Kwargs("marker"_a = "x", "label"_a = "goal", "markersize"_a = 20, "color"_a = "red")); + if (goal_planner_parameter.bus_stop_area.use_bus_stop_area) { + const auto bus_stop_area_polygons = + getBusStopAreaPolygons(planner_data, goal_planner_parameter); + for (const auto & bus_stop_area_polygon : bus_stop_area_polygons) { + plot_lanelet_polygon(ax1, bus_stop_area_polygon); + } + } + + for (auto i = 0; i < filtered_paths.size(); ++i) { + const auto & filtered_path = filtered_paths.at(i); + const auto goal_id = filtered_path.goal_id(); + const auto prio = goal_id2prio[goal_id]; + const auto & color = (i == 0) ? "red" : g_colors.at(i % g_colors.size()); + const auto max_parking_curvature = filtered_path.parking_path_max_curvature(); + if (i == 0) { + plot_goal_candidate(ax1, filtered_path.modified_goal(), prio, footprint, color); + plot_path_with_lane_id(ax2, filtered_path.full_path(), color, "most prio", 2.0); + for (const auto & path_point : filtered_path.full_path().points) { + const auto pose_footprint = transformVector( + footprint, autoware::universe_utils::pose2transform(path_point.point.pose)); + plot_footprint(ax2, pose_footprint, "blue"); + } + } else if (i % 50 == 0) { + std::cout << "plotting " << i << "-th filtered path" << std::endl; + plot_goal_candidate(ax1, filtered_path.modified_goal(), prio, footprint, color); + plot_path_with_lane_id(ax1, filtered_path.full_path(), color, "", 2.0); + } + } + ax2.plot( + Args(original_goal_pos.x, original_goal_pos.y), + Kwargs("marker"_a = "x", "label"_a = "goal", "markersize"_a = 20, "color"_a = "red")); + + const auto centerline_path = calculate_centerline_path(planner_data, goal_planner_parameter); + if (centerline_path) { + // plot_path_with_lane_id(ax2, centerline_path.value(), "red", "centerline_path"); + } + + ax1.set_aspect(Args("equal")); + ax2.set_aspect(Args("equal")); + ax2.legend(); + plt.show(); + + rclcpp::shutdown(); + return 0; +} diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case2.cpp similarity index 66% rename from planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map.cpp rename to planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case2.cpp index 40c2bd201abc7..102e5ef53b164 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case2.cpp @@ -17,6 +17,7 @@ #include #include +#include #include #include #include @@ -28,6 +29,7 @@ #include #include #include +#include #include #include @@ -40,6 +42,8 @@ #include #include +#include +#include #include #include @@ -52,7 +56,6 @@ #include #include #include - using namespace std::chrono_literals; // NOLINT using autoware::behavior_path_planner::BehaviorModuleOutput; @@ -65,9 +68,28 @@ using autoware::behavior_path_planner::utils::parking_departure::calcFeasibleDec using autoware_planning_msgs::msg::LaneletRoute; using tier4_planning_msgs::msg::PathWithLaneId; +std::vector g_colors = { + "#F0F8FF", "#FAEBD7", "#00FFFF", "#7FFFD4", "#F0FFFF", "#F5F5DC", "#FFE4C4", "#000000", "#FFEBCD", + "#0000FF", "#8A2BE2", "#A52A2A", "#DEB887", "#5F9EA0", "#7FFF00", "#D2691E", "#FF7F50", "#6495ED", + "#FFF8DC", "#DC143C", "#00FFFF", "#00008B", "#008B8B", "#B8860B", "#A9A9A9", "#006400", "#A9A9A9", + "#BDB76B", "#8B008B", "#556B2F", "#FF8C00", "#9932CC", "#8B0000", "#E9967A", "#8FBC8F", "#483D8B", + "#2F4F4F", "#2F4F4F", "#00CED1", "#9400D3", "#FF1493", "#00BFFF", "#696969", "#696969", "#1E90FF", + "#B22222", "#FFFAF0", "#228B22", "#FF00FF", "#DCDCDC", "#F8F8FF", "#FFD700", "#DAA520", "#808080", + "#008000", "#ADFF2F", "#808080", "#F0FFF0", "#FF69B4", "#CD5C5C", "#4B0082", "#FFFFF0", "#F0E68C", + "#E6E6FA", "#FFF0F5", "#7CFC00", "#FFFACD", "#ADD8E6", "#F08080", "#E0FFFF", "#FAFAD2", "#D3D3D3", + "#90EE90", "#D3D3D3", "#FFB6C1", "#FFA07A", "#20B2AA", "#87CEFA", "#778899", "#778899", "#B0C4DE", + "#FFFFE0", "#00FF00", "#32CD32", "#FAF0E6", "#FF00FF", "#800000", "#66CDAA", "#0000CD", "#BA55D3", + "#9370DB", "#3CB371", "#7B68EE", "#00FA9A", "#48D1CC", "#C71585", "#191970", "#F5FFFA", "#FFE4E1", + "#FFE4B5", "#FFDEAD", "#000080", "#FDF5E6", "#808000", "#6B8E23", "#FFA500", "#FF4500", "#DA70D6", + "#EEE8AA", "#98FB98", "#AFEEEE", "#DB7093", "#FFEFD5", "#FFDAB9", "#CD853F", "#FFC0CB", "#DDA0DD", + "#B0E0E6", "#800080", "#663399", "#FF0000", "#BC8F8F", "#4169E1", "#8B4513", "#FA8072", "#F4A460", + "#2E8B57", "#FFF5EE", "#A0522D", "#C0C0C0", "#87CEEB", "#6A5ACD", "#708090", "#708090", "#FFFAFA", + "#00FF7F", "#4682B4", "#D2B48C", "#008080", "#D8BFD8", "#FF6347", "#40E0D0", "#EE82EE", "#F5DEB3", + "#FFFFFF", "#F5F5F5", "#FFFF00", "#9ACD32"}; + void plot_footprint( matplotlibcpp17::axes::Axes & axes, const autoware::universe_utils::LinearRing2d & footprint, - const std::string & color = "blue") + const std::string & color) { std::vector xs, ys; for (const auto & pt : footprint) { @@ -79,43 +101,77 @@ void plot_footprint( axes.plot(Args(xs, ys), Kwargs("color"_a = color, "linestyle"_a = "dotted")); } +void plot_lanelet_polygon(matplotlibcpp17::axes::Axes & axes, const lanelet::BasicPolygon2d polygon) +{ + std::vector xs, ys; + for (const auto & p : polygon) { + xs.push_back(p.x()); + ys.push_back(p.y()); + } + xs.push_back(xs.front()); + ys.push_back(ys.front()); + axes.fill(Args(xs, ys), Kwargs("color"_a = "grey", "alpha"_a = 0.5)); +} + +void plot_goal_candidate( + matplotlibcpp17::axes::Axes & axes, const GoalCandidate & goal, const size_t prio, + const autoware::universe_utils::LinearRing2d & local_footprint, const std::string & color) +{ + std::vector xs, ys; + std::vector yaw_cos, yaw_sin; + const auto goal_footprint = + transformVector(local_footprint, autoware::universe_utils::pose2transform(goal.goal_pose)); + plot_footprint(axes, goal_footprint, color); + xs.push_back(goal.goal_pose.position.x); + ys.push_back(goal.goal_pose.position.y); + axes.text(Args(xs.back(), ys.back(), std::to_string(prio))); + const double yaw = autoware::universe_utils::getRPY(goal.goal_pose).z; + yaw_cos.push_back(std::cos(yaw)); + yaw_sin.push_back(std::sin(yaw)); + axes.scatter(Args(xs, ys), Kwargs("color"_a = color)); + axes.quiver( + Args(xs, ys, yaw_cos, yaw_sin), + Kwargs("angles"_a = "xy", "scale_units"_a = "xy", "scale"_a = 2.0)); +} + void plot_goal_candidates( matplotlibcpp17::axes::Axes & axes, const GoalCandidates & goals, + const std::map & goal_id2prio, const autoware::universe_utils::LinearRing2d & local_footprint, const std::string & color = "green") { - std::vector xs, ys; - std::vector yaw_cos, yaw_sin; for (const auto & goal : goals) { - const auto goal_footprint = - transformVector(local_footprint, autoware::universe_utils::pose2transform(goal.goal_pose)); - plot_footprint(axes, goal_footprint); - xs.push_back(goal.goal_pose.position.x); - ys.push_back(goal.goal_pose.position.y); - axes.text(Args(xs.back(), ys.back(), std::to_string(goal.id))); - const double yaw = autoware::universe_utils::getRPY(goal.goal_pose).z; - yaw_cos.push_back(std::cos(yaw)); - yaw_sin.push_back(std::sin(yaw)); + const auto it = goal_id2prio.find(goal.id); + if (it != goal_id2prio.end()) { + plot_goal_candidate(axes, goal, it->second, local_footprint, color); + } } - axes.scatter(Args(xs, ys), Kwargs("color"_a = color)); - axes.quiver( - Args(xs, ys, yaw_cos, yaw_sin), - Kwargs("angles"_a = "xy", "scale_units"_a = "xy", "scale"_a = 1.0)); } void plot_path_with_lane_id( matplotlibcpp17::axes::Axes & axes, const PathWithLaneId & path, - const std::string & color = "red", const std::string & label = "") + const std::string & color = "red", const std::string & label = "", const double linewidth = 1.0) { std::vector xs, ys; + std::vector yaw_cos, yaw_sin; for (const auto & point : path.points) { xs.push_back(point.point.pose.position.x); ys.push_back(point.point.pose.position.y); + const double yaw = autoware::universe_utils::getRPY(point.point.pose).z; + yaw_cos.push_back(std::cos(yaw)); + yaw_sin.push_back(std::sin(yaw)); + axes.scatter( + Args(xs.back(), ys.back()), Kwargs("marker"_a = "o", "color"_a = "blue", "s"_a = 10)); } + axes.quiver( + Args(xs, ys, yaw_cos, yaw_sin), + Kwargs("angles"_a = "xy", "scale_units"_a = "xy", "scale"_a = 2.0)); + if (label == "") { - axes.plot(Args(xs, ys), Kwargs("color"_a = color, "linewidth"_a = 1.0)); + axes.plot(Args(xs, ys), Kwargs("color"_a = color, "linewidth"_a = linewidth)); } else { - axes.plot(Args(xs, ys), Kwargs("color"_a = color, "linewidth"_a = 1.0, "label"_a = label)); + axes.plot( + Args(xs, ys), Kwargs("color"_a = color, "linewidth"_a = linewidth, "label"_a = label)); } } @@ -151,7 +207,8 @@ void plot_lanelet( } std::shared_ptr instantiate_planner_data( - rclcpp::Node::SharedPtr node, const std::string & map_path, const LaneletRoute & route_msg) + rclcpp::Node::SharedPtr node, const std::string & map_path, + const std::string & sample_planner_data_yaml_path) { lanelet::ErrorMessages errors{}; lanelet::projection::MGRSProjector projector{}; @@ -166,20 +223,21 @@ std::shared_ptr instantiate_planner_data( lanelet::utils::conversion::toBinMsg( lanelet_map_ptr, &map_bin); // TODO(soblin): pass lanelet_map_ptr to RouteHandler + YAML::Node config = YAML::LoadFile(sample_planner_data_yaml_path); + auto planner_data = std::make_shared(); planner_data->init_parameters(*node); planner_data->route_handler->setMap(map_bin); - planner_data->route_handler->setRoute(route_msg); + planner_data->route_handler->setRoute( + autoware::test_utils::parse(config["route"])); - nav_msgs::msg::Odometry odom; - odom.pose.pose = route_msg.start_pose; - auto odometry = std::make_shared(odom); + auto odometry = autoware::test_utils::create_const_shared_ptr( + autoware::test_utils::parse(config["self_odometry"])); planner_data->self_odometry = odometry; - geometry_msgs::msg::AccelWithCovarianceStamped accel; - accel.accel.accel.linear.x = 0.537018510955429; - accel.accel.accel.linear.y = -0.2435352815388478; - auto accel_ptr = std::make_shared(accel); + auto accel_ptr = autoware::test_utils::create_const_shared_ptr( + autoware::test_utils::parse( + config["self_acceleration"])); planner_data->self_acceleration = accel_ptr; return planner_data; } @@ -302,7 +360,7 @@ std::vector selectPullOverPaths( std::map path_id_to_rough_margin_map; const auto & target_objects = autoware_perception_msgs::msg::PredictedObjects{}; for (const size_t i : sorted_path_indices) { - const auto & path = pull_over_path_candidates[i]; + const auto & path = pull_over_path_candidates[i]; // cppcheck-suppress containerOutOfBounds const double distance = autoware::behavior_path_planner::utils::path_safety_checker::calculateRoughDistanceToObjects( path.parking_path(), target_objects, planner_data->parameters, false, "max"); @@ -390,9 +448,9 @@ std::vector selectPullOverPaths( } std::optional calculate_centerline_path( - const geometry_msgs::msg::Pose & original_goal_pose, const std::shared_ptr planner_data, const GoalPlannerParameters & parameters) { + const auto original_goal_pose = planner_data->route_handler->getOriginalGoalPose(); const auto refined_goal_opt = autoware::behavior_path_planner::goal_planner_utils::calcRefinedGoal( original_goal_pose, planner_data->route_handler, true, @@ -434,78 +492,45 @@ std::optional calculate_centerline_path( return center_line_path; } +std::vector getBusStopAreaPolygons( + const std::shared_ptr planner_data, const GoalPlannerParameters & parameters) +{ + const auto pull_over_lanes = + autoware::behavior_path_planner::goal_planner_utils::getPullOverLanes( + *(planner_data->route_handler), true, parameters.backward_goal_search_length, + parameters.forward_goal_search_length); + return autoware::behavior_path_planner::goal_planner_utils::getBusStopAreaPolygons( + pull_over_lanes); +} + +struct SortByWeightedDistance +{ + double lateral_cost{0.0}; + bool prioritize_goals_before_objects{false}; + + SortByWeightedDistance(double cost, bool prioritize_goals_before_objects) + : lateral_cost(cost), prioritize_goals_before_objects(prioritize_goals_before_objects) + { + } + + bool operator()(const GoalCandidate & a, const GoalCandidate & b) const noexcept + { + if (prioritize_goals_before_objects) { + if (a.num_objects_to_avoid != b.num_objects_to_avoid) { + return a.num_objects_to_avoid < b.num_objects_to_avoid; + } + } + + return a.distance_from_original_goal + lateral_cost * a.lateral_offset < + b.distance_from_original_goal + lateral_cost * b.lateral_offset; + } +}; + int main(int argc, char ** argv) { using autoware::behavior_path_planner::utils::getReferencePath; rclcpp::init(argc, argv); - autoware_planning_msgs::msg::LaneletRoute route_msg; - route_msg.start_pose = - geometry_msgs::build() - .position(geometry_msgs::build().x(729.944).y(695.124).z(381.18)) - .orientation( - geometry_msgs::build().x(0.0).y(0.0).z(0.437138).w( - 0.899395)); - route_msg.goal_pose = - geometry_msgs::build() - .position(geometry_msgs::build().x(797.526).y(694.105).z(381.18)) - .orientation( - geometry_msgs::build().x(0.0).y(0.0).z(-0.658723).w( - 0.752386)); - - route_msg.segments = std::vector{ - autoware_planning_msgs::build() - .preferred_primitive( - autoware_planning_msgs::build() - .id(15214) - .primitive_type("")) - .primitives(std::vector{ - autoware_planning_msgs::build() - .id(15214) - .primitive_type("lane"), - autoware_planning_msgs::build() - .id(15213) - .primitive_type("lane"), - }), - autoware_planning_msgs::build() - .preferred_primitive( - autoware_planning_msgs::build() - .id(15226) - .primitive_type("")) - .primitives(std::vector{ - autoware_planning_msgs::build() - .id(15226) - .primitive_type("lane"), - autoware_planning_msgs::build() - .id(15225) - .primitive_type("lane"), - }), - autoware_planning_msgs::build() - .preferred_primitive( - autoware_planning_msgs::build() - .id(15228) - .primitive_type("")) - .primitives(std::vector{ - autoware_planning_msgs::build() - .id(15228) - .primitive_type("lane"), - autoware_planning_msgs::build() - .id(15229) - .primitive_type("lane"), - }), - autoware_planning_msgs::build() - .preferred_primitive( - autoware_planning_msgs::build() - .id(15231) - .primitive_type("")) - .primitives(std::vector{ - autoware_planning_msgs::build() - .id(15231) - .primitive_type("lane"), - }), - }; - route_msg.allow_modification = false; - auto node_options = rclcpp::NodeOptions{}; node_options.parameter_overrides( std::vector{{"launch_modules", std::vector{}}}); @@ -537,11 +562,12 @@ int main(int argc, char ** argv) node, ament_index_cpp::get_package_share_directory("autoware_test_utils") + "/test_map/road_shoulder/lanelet2_map.osm", - route_msg); + ament_index_cpp::get_package_share_directory("autoware_behavior_path_goal_planner_module") + + "/config/sample_planner_data_case2.yaml"); lanelet::ConstLanelet current_route_lanelet; planner_data->route_handler->getClosestLaneletWithinRoute( - route_msg.start_pose, ¤t_route_lanelet); + planner_data->self_odometry->pose.pose, ¤t_route_lanelet); const auto reference_path = getReferencePath(current_route_lanelet, planner_data); auto goal_planner_parameter = autoware::behavior_path_planner::GoalPlannerModuleManager::initGoalPlannerParameters( @@ -555,7 +581,16 @@ int main(int argc, char ** argv) lane_departure_checker.setParam(lane_departure_checker_params); const auto footprint = vehicle_info.createFootprint(); autoware::behavior_path_planner::GoalSearcher goal_searcher(goal_planner_parameter, footprint); - const auto goal_candidates = goal_searcher.search(planner_data); + auto goal_candidates = goal_searcher.search(planner_data); + std::sort( + goal_candidates.begin(), goal_candidates.end(), + SortByWeightedDistance( + goal_planner_parameter.minimum_weighted_distance_lateral_weight, + goal_planner_parameter.prioritize_goals_before_objects)); + std::map goal_id2prio{}; + for (auto i = 0; i < goal_candidates.size(); ++i) { + goal_id2prio[goal_candidates.at(i).id] = i; + } pybind11::scoped_interpreter guard{}; auto plt = matplotlibcpp17::pyplot::import(); @@ -563,42 +598,107 @@ int main(int argc, char ** argv) auto & ax1 = axes[0]; auto & ax2 = axes[1]; - const std::vector ids{15213, 15214, 15225, 15226, 15224, 15227, - 15228, 15229, 15230, 15231, 15232}; + // auto & ax3 = axes[2]; + const std::vector ids{759, 675, 676, 1303, 677, 678}; for (const auto & id : ids) { const auto lanelet = planner_data->route_handler->getLaneletMapPtr()->laneletLayer.get(id); plot_lanelet(ax1, lanelet); plot_lanelet(ax2, lanelet); + // plot_lanelet(ax3, lanelet); } - plot_goal_candidates(ax1, goal_candidates, footprint); + // plot_goal_candidates(ax1, goal_candidates, footprint); - plot_path_with_lane_id(ax2, reference_path.path, "green", "reference_path"); + // plot_path_with_lane_id(ax2, reference_path.path, "green", "reference_path"); + const auto start = std::chrono::steady_clock::now(); std::vector candidates; - for (const auto & goal_candidate : goal_candidates) { - auto shift_pull_over_planner = autoware::behavior_path_planner::ShiftPullOver( + for (auto i = 0; i < goal_candidates.size(); ++i) { + const auto & goal_candidate = goal_candidates.at(i); + auto shift_pull_over_planner = autoware::behavior_path_planner::BezierPullOver( *node, goal_planner_parameter, lane_departure_checker); - const auto pull_over_path_opt = - shift_pull_over_planner.plan(goal_candidate, 0, planner_data, reference_path); - if (pull_over_path_opt) { - const auto & pull_over_path = pull_over_path_opt.value(); - const auto & full_path = pull_over_path.full_path(); - candidates.push_back(pull_over_path); - plot_path_with_lane_id(ax1, full_path); + auto pull_over_paths = + shift_pull_over_planner.plans(goal_candidate, 0, planner_data, reference_path); + if (!pull_over_paths.empty()) { + std::copy( + std::make_move_iterator(pull_over_paths.begin()), + std::make_move_iterator(pull_over_paths.end()), std::back_inserter(candidates)); } } - [[maybe_unused]] const auto filtered_paths = selectPullOverPaths( + + const auto filtered_paths = selectPullOverPaths( candidates, goal_candidates, planner_data, goal_planner_parameter, reference_path); + std::cout << filtered_paths.size() << std::endl; + const auto end = std::chrono::steady_clock::now(); + std::cout << "computed candidate bezier paths in " + << std::chrono::duration_cast(end - start).count() * 1.0 / + 1000000 + << "msecs" << std::endl; + std::cout << "filtered " << filtered_paths.size() << "/" << candidates.size() << " paths" + << std::endl; + + /* + for (auto i = 0; i < filtered_paths.size(); ++i) { + const auto & filtered_path = filtered_paths.at(i); + const auto goal_id = filtered_path.goal_id(); + const auto prio = goal_id2prio[goal_id]; + const auto & color = (i == 0) ? "red" : g_colors.at(i % g_colors.size()); + const auto max_parking_curvature = filtered_path.parking_path_max_curvature(); + plot_goal_candidate(ax1, filtered_path.modified_goal(), prio, footprint, color); + if (i == 0) { + plot_path_with_lane_id(ax1, filtered_path.parking_path(), color, "most prio", 2.0); + } else { + plot_path_with_lane_id( + ax1, filtered_path.full_path(), color, + std::to_string(prio) + "-th goal(id=" + std::to_string(goal_id) + + "): k_max=" + std::to_string(max_parking_curvature), + 0.5); + } + } + */ + const auto original_goal_pos = planner_data->route_handler->getOriginalGoalPose().position; + ax1.plot( + Args(original_goal_pos.x, original_goal_pos.y), + Kwargs("marker"_a = "x", "label"_a = "goal", "markersize"_a = 20, "color"_a = "red")); + if (goal_planner_parameter.bus_stop_area.use_bus_stop_area) { + const auto bus_stop_area_polygons = + getBusStopAreaPolygons(planner_data, goal_planner_parameter); + for (const auto & bus_stop_area_polygon : bus_stop_area_polygons) { + plot_lanelet_polygon(ax1, bus_stop_area_polygon); + } + } - const auto centerline_path = - calculate_centerline_path(route_msg.goal_pose, planner_data, goal_planner_parameter); + for (auto i = 0; i < filtered_paths.size(); ++i) { + const auto & filtered_path = filtered_paths.at(i); + const auto goal_id = filtered_path.goal_id(); + const auto prio = goal_id2prio[goal_id]; + const auto & color = (i == 0) ? "red" : g_colors.at(i % g_colors.size()); + const auto max_parking_curvature = filtered_path.parking_path_max_curvature(); + if (i == 0) { + plot_goal_candidate(ax1, filtered_path.modified_goal(), prio, footprint, color); + plot_path_with_lane_id(ax2, filtered_path.full_path(), color, "most prio", 2.0); + for (const auto & path_point : filtered_path.full_path().points) { + const auto pose_footprint = transformVector( + footprint, autoware::universe_utils::pose2transform(path_point.point.pose)); + plot_footprint(ax2, pose_footprint, "blue"); + } + } else if (i % 50 == 0) { + std::cout << "plotting " << i << "-th filtered path" << std::endl; + plot_goal_candidate(ax1, filtered_path.modified_goal(), prio, footprint, color); + plot_path_with_lane_id(ax1, filtered_path.full_path(), color, "", 2.0); + } + } + ax2.plot( + Args(original_goal_pos.x, original_goal_pos.y), + Kwargs("marker"_a = "x", "label"_a = "goal", "markersize"_a = 20, "color"_a = "red")); + + const auto centerline_path = calculate_centerline_path(planner_data, goal_planner_parameter); if (centerline_path) { - plot_path_with_lane_id(ax2, centerline_path.value(), "red", "centerline_path"); + // plot_path_with_lane_id(ax2, centerline_path.value(), "red", "centerline_path"); } + ax1.set_aspect(Args("equal")); ax2.set_aspect(Args("equal")); - ax1.legend(); ax2.legend(); plt.show(); diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/bezier_pull_over.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/bezier_pull_over.hpp new file mode 100644 index 0000000000000..e1e91a1bd8af6 --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/bezier_pull_over.hpp @@ -0,0 +1,66 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__PULL_OVER_PLANNER__BEZIER_PULL_OVER_HPP_ +#define AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__PULL_OVER_PLANNER__BEZIER_PULL_OVER_HPP_ + +#include "autoware/behavior_path_goal_planner_module/pull_over_planner/pull_over_planner_base.hpp" + +#include + +#include +#include + +namespace autoware::behavior_path_planner +{ +using autoware::lane_departure_checker::LaneDepartureChecker; + +class BezierPullOver : public PullOverPlannerBase +{ +public: + BezierPullOver( + rclcpp::Node & node, const GoalPlannerParameters & parameters, + const LaneDepartureChecker & lane_departure_checker); + PullOverPlannerType getPlannerType() const override { return PullOverPlannerType::BEZIER; } + std::optional plan( + const GoalCandidate & modified_goal_pose, const size_t id, + const std::shared_ptr planner_data, + const BehaviorModuleOutput & previous_module_output) override; + std::vector plans( + const GoalCandidate & modified_goal_pose, const size_t id, + const std::shared_ptr planner_data, + const BehaviorModuleOutput & previous_module_output); + +private: + const LaneDepartureChecker lane_departure_checker_; + + const bool left_side_parking_; + + std::vector generateBezierPath( + const GoalCandidate & goal_candidate, const size_t id, + const std::shared_ptr planner_data, + const BehaviorModuleOutput & previous_module_output, const lanelet::ConstLanelets & road_lanes, + const lanelet::ConstLanelets & shoulder_lanes, const double lateral_jerk) const; + + PathWithLaneId generateReferencePath( + const std::shared_ptr planner_data, + const lanelet::ConstLanelets & road_lanes, const Pose & end_pose) const; + + static double calcBeforeShiftedArcLength( + const PathWithLaneId & path, const double after_shifted_arc_length, const double dr); +}; + +} // namespace autoware::behavior_path_planner + +#endif // AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__PULL_OVER_PLANNER__BEZIER_PULL_OVER_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/pull_over_planner_base.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/pull_over_planner_base.hpp index e061a0203602f..5b336a7de6acc 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/pull_over_planner_base.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/pull_over_planner_base.hpp @@ -33,6 +33,7 @@ namespace autoware::behavior_path_planner { enum class PullOverPlannerType { SHIFT, + BEZIER, ARC_FORWARD, ARC_BACKWARD, FREESPACE, diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/package.xml index dead1e4fe0f37..232c548b28da3 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/package.xml @@ -22,8 +22,10 @@ autoware_behavior_path_planner autoware_behavior_path_planner_common + autoware_bezier_sampler autoware_motion_utils autoware_rtc_interface + autoware_test_utils autoware_universe_utils pluginlib rclcpp @@ -34,7 +36,6 @@ ament_index_cpp ament_lint_auto autoware_lint_common - autoware_test_utils ament_cmake diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/bezier_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/bezier_pull_over.cpp new file mode 100644 index 0000000000000..0da5ab5dae38b --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/bezier_pull_over.cpp @@ -0,0 +1,404 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/behavior_path_goal_planner_module/pull_over_planner/bezier_pull_over.hpp" + +#include "autoware/behavior_path_goal_planner_module/util.hpp" +#include "autoware/behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" +#include "autoware/behavior_path_planner_common/utils/path_utils.hpp" +#include "autoware/behavior_path_planner_common/utils/utils.hpp" + +#include +#include +#include + +#include +#include +#include +#include +#include +#include +namespace autoware::behavior_path_planner +{ +BezierPullOver::BezierPullOver( + rclcpp::Node & node, const GoalPlannerParameters & parameters, + const LaneDepartureChecker & lane_departure_checker) +: PullOverPlannerBase{node, parameters}, + lane_departure_checker_{lane_departure_checker}, + left_side_parking_{parameters.parking_policy == ParkingPolicy::LEFT_SIDE} +{ +} + +std::optional BezierPullOver::plan( + [[maybe_unused]] const GoalCandidate & modified_goal_pose, [[maybe_unused]] const size_t id, + [[maybe_unused]] const std::shared_ptr planner_data, + [[maybe_unused]] const BehaviorModuleOutput & previous_module_output) +{ + const auto & route_handler = planner_data->route_handler; + const double min_jerk = parameters_.minimum_lateral_jerk; + const double max_jerk = parameters_.maximum_lateral_jerk; + const double backward_search_length = parameters_.backward_goal_search_length; + const double forward_search_length = parameters_.forward_goal_search_length; + const int shift_sampling_num = parameters_.shift_sampling_num; + [[maybe_unused]] const double jerk_resolution = + std::abs(max_jerk - min_jerk) / shift_sampling_num; + + const auto road_lanes = utils::getExtendedCurrentLanesFromPath( + previous_module_output.path, planner_data, backward_search_length, forward_search_length, + /*forward_only_in_route*/ false); + + const auto pull_over_lanes = goal_planner_utils::getPullOverLanes( + *route_handler, left_side_parking_, backward_search_length, forward_search_length); + if (road_lanes.empty() || pull_over_lanes.empty()) { + return {}; + } + + // find safe one from paths with different jerk + for (double lateral_jerk = min_jerk; lateral_jerk <= max_jerk; lateral_jerk += jerk_resolution) { + const auto pull_over_path = generateBezierPath( + modified_goal_pose, id, planner_data, previous_module_output, road_lanes, pull_over_lanes, + lateral_jerk); + if (!pull_over_path.empty()) { + return pull_over_path.at(0); + } + } + + return std::nullopt; +} + +std::vector BezierPullOver::plans( + [[maybe_unused]] const GoalCandidate & modified_goal_pose, [[maybe_unused]] const size_t id, + [[maybe_unused]] const std::shared_ptr planner_data, + [[maybe_unused]] const BehaviorModuleOutput & previous_module_output) +{ + const auto & route_handler = planner_data->route_handler; + const double min_jerk = parameters_.minimum_lateral_jerk; + const double max_jerk = parameters_.maximum_lateral_jerk; + const double backward_search_length = parameters_.backward_goal_search_length; + const double forward_search_length = parameters_.forward_goal_search_length; + const int shift_sampling_num = parameters_.shift_sampling_num; + [[maybe_unused]] const double jerk_resolution = + std::abs(max_jerk - min_jerk) / shift_sampling_num; + + const auto road_lanes = utils::getExtendedCurrentLanesFromPath( + previous_module_output.path, planner_data, backward_search_length, forward_search_length, + /*forward_only_in_route*/ false); + + const auto pull_over_lanes = goal_planner_utils::getPullOverLanes( + *route_handler, left_side_parking_, backward_search_length, forward_search_length); + if (road_lanes.empty() || pull_over_lanes.empty()) { + return {}; + } + + // find safe one from paths with different jerk + std::vector paths; + for (double lateral_jerk = min_jerk; lateral_jerk <= max_jerk; lateral_jerk += jerk_resolution) { + auto pull_over_paths = generateBezierPath( + modified_goal_pose, id, planner_data, previous_module_output, road_lanes, pull_over_lanes, + lateral_jerk); + std::copy( + std::make_move_iterator(pull_over_paths.begin()), + std::make_move_iterator(pull_over_paths.end()), std::back_inserter(paths)); + } + + return paths; +} + +std::vector BezierPullOver::generateBezierPath( + const GoalCandidate & goal_candidate, const size_t id, + const std::shared_ptr planner_data, + const BehaviorModuleOutput & previous_module_output, const lanelet::ConstLanelets & road_lanes, + const lanelet::ConstLanelets & pull_over_lanes, const double lateral_jerk) const +{ + const double pull_over_velocity = parameters_.pull_over_velocity; + + const auto & goal_pose = goal_candidate.goal_pose; + + // shift end pose is longitudinal offset from goal pose to improve parking angle accuracy + const Pose shift_end_pose = goal_pose; + + // calculate lateral shift of previous module path terminal pose from road lane reference path + const auto road_lane_reference_path_to_shift_end = utils::resamplePathWithSpline( + generateReferencePath(planner_data, road_lanes, shift_end_pose), + parameters_.center_line_path_interval); + const auto prev_module_path = utils::resamplePathWithSpline( + previous_module_output.path, parameters_.center_line_path_interval); + const auto prev_module_path_terminal_pose = prev_module_path.points.back().point.pose; + + // process previous module path for path shifter input path + // case1) extend path if shift end pose is behind of previous module path terminal pose + // case2) crop path if shift end pose is ahead of previous module path terminal pose + const auto processed_prev_module_path = std::invoke([&]() -> std::optional { + const bool extend_previous_module_path = + lanelet::utils::getArcCoordinates(road_lanes, shift_end_pose).length > + lanelet::utils::getArcCoordinates(road_lanes, prev_module_path_terminal_pose).length; + if (extend_previous_module_path) { // case1 + // NOTE: The previous module may insert a zero velocity at the end of the path, so remove it + // by setting remove_connected_zero_velocity=true. Inserting a velocity of 0 into the goal is + // the role of the goal planner, and the intermediate zero velocity after extension is + // unnecessary. + return goal_planner_utils::extendPath( + prev_module_path, road_lane_reference_path_to_shift_end, shift_end_pose, true); + } else { // case2 + return goal_planner_utils::cropPath(prev_module_path, shift_end_pose); + } + }); + if (!processed_prev_module_path || processed_prev_module_path->points.empty()) { + return {}; + } + + // calculate shift length + const Pose & shift_end_pose_prev_module_path = + processed_prev_module_path->points.back().point.pose; + const double shift_end_road_to_target_distance = + autoware::universe_utils::inverseTransformPoint( + shift_end_pose.position, shift_end_pose_prev_module_path) + .y; + + // calculate shift start pose on road lane + const double pull_over_distance = autoware::motion_utils::calc_longitudinal_dist_from_jerk( + shift_end_road_to_target_distance, lateral_jerk, pull_over_velocity); + const double before_shifted_pull_over_distance = calcBeforeShiftedArcLength( + processed_prev_module_path.value(), pull_over_distance, shift_end_road_to_target_distance); + const auto shift_start_pose = autoware::motion_utils::calcLongitudinalOffsetPose( + processed_prev_module_path->points, shift_end_pose_prev_module_path.position, + -before_shifted_pull_over_distance); + + std::vector> params; + const size_t n_sample_v_init = 4; + const size_t n_sample_v_final = 4; + const size_t n_sample_acc = 3; + for (unsigned i = 0; i <= n_sample_v_init; ++i) { + for (unsigned j = 0; j <= n_sample_v_final; j++) { + for (unsigned k = 0; k <= n_sample_acc; k++) { + const double v_init_coeff = i * 0.25; + const double v_final_coeff = j * 0.25; + const double acc_coeff = k * (10.0 / 3); + params.emplace_back(v_init_coeff, v_final_coeff, acc_coeff); + } + } + } + + std::vector bezier_paths; + for (const auto & [v_init_coeff, v_final_coeff, acc_coeff] : params) { + // set path shifter and generate shifted path + PathShifter path_shifter{}; + path_shifter.setPath(processed_prev_module_path.value()); + ShiftLine shift_line{}; + shift_line.start = *shift_start_pose; + shift_line.end = shift_end_pose; + shift_line.end_shift_length = shift_end_road_to_target_distance; + path_shifter.addShiftLine(shift_line); + ShiftedPath shifted_path{}; + const bool offset_back = true; // offset front side from reference path + if (!path_shifter.generate(&shifted_path, offset_back)) { + continue; + } + const auto from_idx_opt = + autoware::motion_utils::findNearestIndex(shifted_path.path.points, *shift_start_pose); + const auto to_idx_opt = + autoware::motion_utils::findNearestIndex(shifted_path.path.points, shift_end_pose); + if (!from_idx_opt || !to_idx_opt) { + continue; + } + const auto from_idx = from_idx_opt.value(); + const auto to_idx = to_idx_opt.value(); + const auto span = static_cast( + std::max(static_cast(to_idx) - static_cast(from_idx), 0)); + const auto reference_curvature = + autoware::motion_utils::calcCurvature(processed_prev_module_path->points); + const auto & from_pose = shifted_path.path.points[from_idx].point.pose; + const auto & to_pose = shifted_path.path.points[to_idx].point.pose; + const autoware::sampler_common::State initial{ + {from_pose.position.x, from_pose.position.y}, + {0.0, 0.0}, + reference_curvature.at(from_idx), + tf2::getYaw(from_pose.orientation)}; + const autoware::sampler_common::State final{ + {to_pose.position.x, to_pose.position.y}, {0.0, 0.0}, 0.0, tf2::getYaw(to_pose.orientation)}; + // setting the initial velocity to higher gives straight forward path (the steering does not + // change) + const auto bezier_path = + bezier_sampler::sample(initial, final, v_init_coeff, v_final_coeff, acc_coeff); + const auto bezier_points = bezier_path.cartesianWithHeading(span); + for (unsigned i = 0; i + 1 < span; ++i) { + auto & p = shifted_path.path.points[from_idx + i]; + p.point.pose.position.x = bezier_points[i].x(); + p.point.pose.position.y = bezier_points[i].y(); + p.point.pose.orientation = + universe_utils::createQuaternionFromRPY(0.0, 0.0, bezier_points[i].z()); + } + shifted_path.path.points = + autoware::motion_utils::removeOverlapPoints(shifted_path.path.points); + + autoware::motion_utils::insertOrientation(shifted_path.path.points, true); + + // combine road lanes and shoulder lanes to find closest lanelet id + const auto lanes = std::invoke([&]() -> lanelet::ConstLanelets { + auto lanes = road_lanes; + lanes.insert(lanes.end(), pull_over_lanes.begin(), pull_over_lanes.end()); + return lanes; // not copy the value (Return Value Optimization) + }); + + // set goal pose with velocity 0 + { + PathPointWithLaneId p{}; + p.point.longitudinal_velocity_mps = 0.0; + p.point.pose = goal_pose; + lanelet::Lanelet goal_lanelet{}; + if (lanelet::utils::query::getClosestLanelet(lanes, goal_pose, &goal_lanelet)) { + p.lane_ids = {goal_lanelet.id()}; + } else { + p.lane_ids = shifted_path.path.points.back().lane_ids; + } + shifted_path.path.points.push_back(p); + } + + // set lane_id and velocity to shifted_path + for (size_t i = path_shifter.getShiftLines().front().start_idx; + i < shifted_path.path.points.size() - 1; ++i) { + auto & point = shifted_path.path.points.at(i); + point.point.longitudinal_velocity_mps = + std::min(point.point.longitudinal_velocity_mps, static_cast(pull_over_velocity)); + lanelet::Lanelet lanelet{}; + if (lanelet::utils::query::getClosestLanelet(lanes, point.point.pose, &lanelet)) { + point.lane_ids = {lanelet.id()}; // overwrite lane_ids + } else { + point.lane_ids = shifted_path.path.points.at(i - 1).lane_ids; + } + } + + // set pull over path + auto pull_over_path_opt = PullOverPath::create( + getPlannerType(), id, {shifted_path.path}, path_shifter.getShiftLines().front().start, + goal_candidate, {std::make_pair(pull_over_velocity, 0)}); + + if (!pull_over_path_opt) { + continue; + } + auto & pull_over_path = pull_over_path_opt.value(); + + // check if the parking path will leave drivable area and lanes + const bool is_in_parking_lots = std::invoke([&]() -> bool { + const auto & p = planner_data->parameters; + const auto parking_lot_polygons = + lanelet::utils::query::getAllParkingLots(planner_data->route_handler->getLaneletMapPtr()); + const auto path_footprints = goal_planner_utils::createPathFootPrints( + pull_over_path.parking_path(), p.base_link2front, p.base_link2rear, p.vehicle_width); + const auto is_footprint_in_any_polygon = [&parking_lot_polygons](const auto & footprint) { + return std::any_of( + parking_lot_polygons.begin(), parking_lot_polygons.end(), + [&footprint](const auto & polygon) { + return lanelet::geometry::within( + footprint, lanelet::utils::to2D(polygon).basicPolygon()); + }); + }; + return std::all_of( + path_footprints.begin(), path_footprints.end(), + [&is_footprint_in_any_polygon](const auto & footprint) { + return is_footprint_in_any_polygon(footprint); + }); + }); + const bool is_in_lanes = std::invoke([&]() -> bool { + const auto drivable_lanes = + utils::generateDrivableLanesWithShoulderLanes(road_lanes, pull_over_lanes); + const auto & dp = planner_data->drivable_area_expansion_parameters; + const auto expanded_lanes = utils::expandLanelets( + drivable_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset, + dp.drivable_area_types_to_skip); + const auto combined_drivable = utils::combineDrivableLanes( + expanded_lanes, previous_module_output.drivable_area_info.drivable_lanes); + return !lane_departure_checker_.checkPathWillLeaveLane( + utils::transformToLanelets(combined_drivable), pull_over_path.parking_path()); + }); + if (!is_in_parking_lots && !is_in_lanes) { + continue; + } + bezier_paths.push_back(std::move(pull_over_path)); + } + + return bezier_paths; +} + +PathWithLaneId BezierPullOver::generateReferencePath( + const std::shared_ptr planner_data, const lanelet::ConstLanelets & road_lanes, + const Pose & end_pose) const +{ + const auto & route_handler = planner_data->route_handler; + const Pose & current_pose = planner_data->self_odometry->pose.pose; + const double backward_path_length = planner_data->parameters.backward_path_length; + const double pull_over_velocity = parameters_.pull_over_velocity; + const double deceleration_interval = parameters_.deceleration_interval; + + const auto current_road_arc_coords = lanelet::utils::getArcCoordinates(road_lanes, current_pose); + const double s_start = current_road_arc_coords.length - backward_path_length; + const double s_end = std::max( + lanelet::utils::getArcCoordinates(road_lanes, end_pose).length, + s_start + std::numeric_limits::epsilon()); + auto road_lane_reference_path = route_handler->getCenterLinePath(road_lanes, s_start, s_end); + + // decelerate velocity linearly to minimum pull over velocity + // (or keep original velocity if it is lower than pull over velocity) + for (auto & point : road_lane_reference_path.points) { + const auto arclength = lanelet::utils::getArcCoordinates(road_lanes, point.point.pose).length; + const double distance_to_pull_over_start = + std::clamp(s_end - arclength, 0.0, deceleration_interval); + const auto decelerated_velocity = static_cast( + distance_to_pull_over_start / deceleration_interval * + (point.point.longitudinal_velocity_mps - pull_over_velocity) + + pull_over_velocity); + point.point.longitudinal_velocity_mps = + std::min(point.point.longitudinal_velocity_mps, decelerated_velocity); + } + return road_lane_reference_path; +} + +double BezierPullOver::calcBeforeShiftedArcLength( + const PathWithLaneId & path, const double target_after_arc_length, const double dr) +{ + // reverse path for checking from the end point + // note that the sign of curvature is also reversed + PathWithLaneId reversed_path{}; + std::reverse_copy( + path.points.begin(), path.points.end(), std::back_inserter(reversed_path.points)); + + double after_arc_length{0.0}; + + const auto curvature_and_segment_length = + autoware::motion_utils::calcCurvatureAndSegmentLength(reversed_path.points); + + for (size_t i = 0; i < curvature_and_segment_length.size(); ++i) { + const auto & [k, segment_length_pair] = curvature_and_segment_length[i]; + + // If it is the last point, add the lengths of the previous and next segments. + // For other points, only add the length of the previous segment. + const double segment_length = i == curvature_and_segment_length.size() - 1 + ? segment_length_pair.first + : segment_length_pair.first + segment_length_pair.second; + + // after shifted segment length + const double after_segment_length = + k > 0 ? segment_length * (1 + k * dr) : segment_length / (1 - k * dr); + if (after_arc_length + after_segment_length > target_after_arc_length) { + const double offset = target_after_arc_length - after_arc_length; + after_arc_length += k > 0 ? offset * (1 + k * dr) : offset / (1 - k * dr); + return after_arc_length; + } + after_arc_length += after_segment_length; + } + + return after_arc_length; +} + +} // namespace autoware::behavior_path_planner diff --git a/planning/sampling_based_planner/autoware_bezier_sampler/include/autoware_bezier_sampler/bezier_sampling.hpp b/planning/sampling_based_planner/autoware_bezier_sampler/include/autoware_bezier_sampler/bezier_sampling.hpp index a832ef1f5cd39..7c0db035d29e4 100644 --- a/planning/sampling_based_planner/autoware_bezier_sampler/include/autoware_bezier_sampler/bezier_sampling.hpp +++ b/planning/sampling_based_planner/autoware_bezier_sampler/include/autoware_bezier_sampler/bezier_sampling.hpp @@ -40,6 +40,9 @@ struct SamplingParameters std::vector sample( const autoware::sampler_common::State & initial, const autoware::sampler_common::State & final, const SamplingParameters & params); +Bezier sample( + const autoware::sampler_common::State & initial, const autoware::sampler_common::State & final, + const double initial_velocity, const double final_velocity, const double acceleration); /// @brief generate a Bezier curve for the given states, velocities, and accelerations Bezier generate( const Eigen::Vector2d & initial_pose, const Eigen::Vector2d & final_pose, diff --git a/planning/sampling_based_planner/autoware_bezier_sampler/src/bezier_sampling.cpp b/planning/sampling_based_planner/autoware_bezier_sampler/src/bezier_sampling.cpp index c36b8f88c8486..637cb0482e033 100644 --- a/planning/sampling_based_planner/autoware_bezier_sampler/src/bezier_sampling.cpp +++ b/planning/sampling_based_planner/autoware_bezier_sampler/src/bezier_sampling.cpp @@ -58,6 +58,33 @@ std::vector sample( } return curves; } +Bezier sample( + const autoware::sampler_common::State & initial, const autoware::sampler_common::State & final, + const double initial_velocity, const double final_velocity, const double acceleration) +{ + const double distance_initial_to_final = std::sqrt( + (initial.pose.x() - final.pose.x()) * (initial.pose.x() - final.pose.x()) + + (initial.pose.y() - final.pose.y()) * (initial.pose.y() - final.pose.y())); + // Tangent vectors + const Eigen::Vector2d initial_tangent_unit(std::cos(initial.heading), std::sin(initial.heading)); + const Eigen::Vector2d final_tangent_unit(std::cos(final.heading), std::sin(final.heading)); + // Unit vectors + const Eigen::Vector2d initial_normal_unit = initial_tangent_unit.unitOrthogonal(); + const Eigen::Vector2d final_normal_unit = final_tangent_unit.unitOrthogonal(); + const double initial_tangent_length = initial_velocity * distance_initial_to_final; + const double final_tangent_length = final_velocity * distance_initial_to_final; + const double acceleration_length = acceleration * distance_initial_to_final; + const Eigen::Vector2d initial_acceleration = + acceleration_length * initial_tangent_unit + + initial.curvature * initial_tangent_length * initial_tangent_length * initial_normal_unit; + const Eigen::Vector2d final_acceleration = + acceleration_length * final_tangent_unit + + final.curvature * final_tangent_length * final_tangent_length * final_normal_unit; + return generate( + {initial.pose.x(), initial.pose.y()}, {final.pose.x(), final.pose.y()}, + initial_tangent_unit * initial_tangent_length, initial_acceleration, + final_tangent_unit * final_tangent_length, final_acceleration); +} Bezier generate( const Eigen::Vector2d & initial_pose, const Eigen::Vector2d & final_pose, const Eigen::Vector2d & initial_velocity, const Eigen::Vector2d & initial_acceleration, From 91984f819fdbef89e7c7e4c0785857c9b6b2ee70 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Mon, 16 Dec 2024 09:04:53 +0900 Subject: [PATCH 018/334] feat(autoware_lidar_centerpoint): process front voxels first (#9608) * feat: optimize voxel indexing in preprocess_kernel.cu Signed-off-by: Taekjin LEE * fix: remove redundant index check Signed-off-by: Taekjin LEE * fix: modify voxel index for better memory access Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE --- .../lib/preprocess/preprocess_kernel.cu | 19 +++++++++++-------- 1 file changed, 11 insertions(+), 8 deletions(-) diff --git a/perception/autoware_lidar_centerpoint/lib/preprocess/preprocess_kernel.cu b/perception/autoware_lidar_centerpoint/lib/preprocess/preprocess_kernel.cu index 502ad04223ce9..f300411a44aad 100644 --- a/perception/autoware_lidar_centerpoint/lib/preprocess/preprocess_kernel.cu +++ b/perception/autoware_lidar_centerpoint/lib/preprocess/preprocess_kernel.cu @@ -148,7 +148,7 @@ __global__ void generateVoxels_random_kernel( int voxel_idx = floorf((point.x - min_x_range) / pillar_x_size); int voxel_idy = floorf((point.y - min_y_range) / pillar_y_size); - unsigned int voxel_index = voxel_idy * grid_x_size + voxel_idx; + unsigned int voxel_index = (grid_x_size - 1 - voxel_idx) * grid_y_size + voxel_idy; unsigned int point_id = atomicAdd(&(mask[voxel_index]), 1); @@ -185,12 +185,14 @@ __global__ void generateBaseFeatures_kernel( unsigned int * mask, float * voxels, int grid_y_size, int grid_x_size, int max_voxel_size, unsigned int * pillar_num, float * voxel_features, float * voxel_num, int * voxel_idxs) { - unsigned int voxel_idx = blockIdx.x * blockDim.x + threadIdx.x; - unsigned int voxel_idy = blockIdx.y * blockDim.y + threadIdx.y; - - if (voxel_idx >= grid_x_size || voxel_idy >= grid_y_size) return; - - unsigned int voxel_index = voxel_idy * grid_x_size + voxel_idx; + // exchange x and y to process in a row-major order + // flip x axis direction to process front to back + unsigned int voxel_idx_inverted = blockIdx.y * blockDim.y + threadIdx.y; + unsigned int voxel_idy = blockIdx.x * blockDim.x + threadIdx.x; + if (voxel_idx_inverted >= grid_x_size || voxel_idy >= grid_y_size) return; + unsigned int voxel_idx = grid_x_size - 1 - voxel_idx_inverted; + + unsigned int voxel_index = voxel_idx_inverted * grid_y_size + voxel_idy; unsigned int count = mask[voxel_index]; if (!(count > 0)) return; count = count < MAX_POINT_IN_VOXEL_SIZE ? count : MAX_POINT_IN_VOXEL_SIZE; @@ -220,9 +222,10 @@ cudaError_t generateBaseFeatures_launch( unsigned int * pillar_num, float * voxel_features, float * voxel_num, int * voxel_idxs, cudaStream_t stream) { + // exchange x and y to process in a row-major order dim3 threads = {32, 32}; dim3 blocks = { - (grid_x_size + threads.x - 1) / threads.x, (grid_y_size + threads.y - 1) / threads.y}; + (grid_y_size + threads.x - 1) / threads.x, (grid_x_size + threads.y - 1) / threads.y}; generateBaseFeatures_kernel<<>>( mask, voxels, grid_y_size, grid_x_size, max_voxel_size, pillar_num, voxel_features, voxel_num, From 35da6d89b03b4a4667071eb6124f1585b4095faa Mon Sep 17 00:00:00 2001 From: jakor97 <51270271+jakor97@users.noreply.github.com> Date: Mon, 16 Dec 2024 01:29:43 +0100 Subject: [PATCH 019/334] refactor(autoware_multi_object_tracker): add configurable tracker parameters (#9621) * refactor(autoware_multi_object_tracker): add configurable tracker parameters Signed-off-by: jkoronczok * style(pre-commit): autofix * refactor(autoware_multi_object_tracker): remove default values from parameter declarations Signed-off-by: jkoronczok * refactor(autoware_multi_object_tracker): update schema file Signed-off-by: jkoronczok * style(pre-commit): autofix * Update perception/autoware_multi_object_tracker/src/processor/processor.cpp * Update perception/autoware_multi_object_tracker/src/processor/processor.cpp --------- Signed-off-by: jkoronczok Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Taekjin LEE --- .../multi_object_tracker_node.param.yaml | 15 ++++ .../multi_object_tracker_node.schema.json | 69 +++++++++++++++++++ .../src/multi_object_tracker_node.cpp | 42 ++++++++--- .../src/processor/processor.cpp | 50 ++++++-------- .../src/processor/processor.hpp | 27 ++++---- 5 files changed, 152 insertions(+), 51 deletions(-) diff --git a/perception/autoware_multi_object_tracker/config/multi_object_tracker_node.param.yaml b/perception/autoware_multi_object_tracker/config/multi_object_tracker_node.param.yaml index 7dd588ec8eeba..c9d0a3676b526 100644 --- a/perception/autoware_multi_object_tracker/config/multi_object_tracker_node.param.yaml +++ b/perception/autoware_multi_object_tracker/config/multi_object_tracker_node.param.yaml @@ -15,6 +15,21 @@ enable_delay_compensation: false consider_odometry_uncertainty: false + # tracker parameters + tracker_lifetime: 1.0 # [s] + min_known_object_removal_iou: 0.1 # [ratio] + min_unknown_object_removal_iou: 0.001 # [ratio] + distance_threshold: 5.0 # [m] + confident_count_threshold: + UNKNOWN: 3 + CAR: 3 + TRUCK: 3 + BUS: 3 + TRAILER: 3 + MOTORBIKE: 3 + BICYCLE: 3 + PEDESTRIAN: 3 + # debug parameters publish_processing_time: false publish_tentative_objects: false diff --git a/perception/autoware_multi_object_tracker/schema/multi_object_tracker_node.schema.json b/perception/autoware_multi_object_tracker/schema/multi_object_tracker_node.schema.json index a40eb12d99b38..f32db284c1738 100644 --- a/perception/autoware_multi_object_tracker/schema/multi_object_tracker_node.schema.json +++ b/perception/autoware_multi_object_tracker/schema/multi_object_tracker_node.schema.json @@ -56,6 +56,69 @@ "description": "If True, tracker use timers to schedule publishers and use prediction step to extrapolate object state at desired timestamp.", "default": false }, + "consider_odometry_uncertainty": { + "type": "boolean", + "description": "If True, consider odometry uncertainty in tracking.", + "default": false + }, + "tracker_lifetime": { + "type": "number", + "description": "Lifetime of the tracker in seconds.", + "default": 1.0 + }, + "min_known_object_removal_iou": { + "type": "number", + "description": "Minimum IOU between associated objects with known label to remove younger tracker", + "default": 0.1 + }, + "min_unknown_object_removal_iou": { + "type": "number", + "description": "Minimum IOU between associated objects with unknown label to remove unknown tracker", + "default": 0.001 + }, + "distance_threshold": { + "type": "number", + "description": "Distance threshold in meters.", + "default": 5.0 + }, + "confident_count_threshold": { + "type": "object", + "properties": { + "UNKNOWN": { + "type": "number", + "default": 3 + }, + "CAR": { + "type": "number", + "default": 3 + }, + "TRUCK": { + "type": "number", + "default": 3 + }, + "BUS": { + "type": "number", + "default": 3 + }, + "TRAILER": { + "type": "number", + "default": 3 + }, + "MOTORBIKE": { + "type": "number", + "default": 3 + }, + "BICYCLE": { + "type": "number", + "default": 3 + }, + "PEDESTRIAN": { + "type": "number", + "default": 3 + } + }, + "description": "Number of measurements to consider tracker as confident for different object classes." + }, "publish_processing_time": { "type": "boolean", "description": "Enable to publish debug message of process time information.", @@ -93,6 +156,12 @@ "publish_rate", "world_frame_id", "enable_delay_compensation", + "consider_odometry_uncertainty", + "tracker_lifetime", + "min_known_object_removal_iou", + "min_unknown_object_removal_iou", + "distance_threshold", + "confident_count_threshold", "publish_processing_time", "publish_tentative_objects", "publish_debug_markers", diff --git a/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp b/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp index a8e27ed4f0146..d2d2d3e087c4e 100644 --- a/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp +++ b/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp @@ -64,12 +64,12 @@ boost::optional getTransformAnonymous( return boost::none; } } - } // namespace namespace autoware::multi_object_tracker { using Label = autoware_perception_msgs::msg::ObjectClassification; +using LabelType = autoware_perception_msgs::msg::ObjectClassification::_label_type; MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) : rclcpp::Node("multi_object_tracker", node_options), @@ -166,23 +166,45 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) // Initialize processor { - std::map tracker_map; - tracker_map.insert( + TrackerProcessorConfig config; + config.tracker_map.insert( std::make_pair(Label::CAR, this->declare_parameter("car_tracker"))); - tracker_map.insert( + config.tracker_map.insert( std::make_pair(Label::TRUCK, this->declare_parameter("truck_tracker"))); - tracker_map.insert( + config.tracker_map.insert( std::make_pair(Label::BUS, this->declare_parameter("bus_tracker"))); - tracker_map.insert( + config.tracker_map.insert( std::make_pair(Label::TRAILER, this->declare_parameter("trailer_tracker"))); - tracker_map.insert(std::make_pair( + config.tracker_map.insert(std::make_pair( Label::PEDESTRIAN, this->declare_parameter("pedestrian_tracker"))); - tracker_map.insert( + config.tracker_map.insert( std::make_pair(Label::BICYCLE, this->declare_parameter("bicycle_tracker"))); - tracker_map.insert(std::make_pair( + config.tracker_map.insert(std::make_pair( Label::MOTORCYCLE, this->declare_parameter("motorcycle_tracker"))); + config.channel_size = input_channel_size_; + + // Declare parameters + config.tracker_lifetime = declare_parameter("tracker_lifetime"); + config.min_known_object_removal_iou = declare_parameter("min_known_object_removal_iou"); + config.min_unknown_object_removal_iou = + declare_parameter("min_unknown_object_removal_iou"); + config.distance_threshold = declare_parameter("distance_threshold"); + + // Map from class name to label + std::map class_name_to_label = { + {"UNKNOWN", Label::UNKNOWN}, {"CAR", Label::CAR}, + {"TRUCK", Label::TRUCK}, {"BUS", Label::BUS}, + {"TRAILER", Label::TRAILER}, {"MOTORBIKE", Label::MOTORCYCLE}, + {"BICYCLE", Label::BICYCLE}, {"PEDESTRIAN", Label::PEDESTRIAN}}; + + // Declare parameters and initialize confident_count_threshold_map + for (const auto & [class_name, class_label] : class_name_to_label) { + int64_t value = declare_parameter("confident_count_threshold." + class_name); + config.confident_count_threshold[class_label] = static_cast(value); + } - processor_ = std::make_unique(tracker_map, input_channel_size_); + // Initialize processor with parameters + processor_ = std::make_unique(config); } // Data association initialization diff --git a/perception/autoware_multi_object_tracker/src/processor/processor.cpp b/perception/autoware_multi_object_tracker/src/processor/processor.cpp index ebc11ea63e199..b3bcd018faf9d 100644 --- a/perception/autoware_multi_object_tracker/src/processor/processor.cpp +++ b/perception/autoware_multi_object_tracker/src/processor/processor.cpp @@ -30,21 +30,10 @@ namespace autoware::multi_object_tracker { using Label = autoware_perception_msgs::msg::ObjectClassification; +using LabelType = autoware_perception_msgs::msg::ObjectClassification::_label_type; -TrackerProcessor::TrackerProcessor( - const std::map & tracker_map, const size_t & channel_size) -: tracker_map_(tracker_map), channel_size_(channel_size) +TrackerProcessor::TrackerProcessor(const TrackerProcessorConfig & config) : config_(config) { - // Set tracker lifetime parameters - max_elapsed_time_ = 1.0; // [s] - - // Set tracker overlap remover parameters - min_iou_ = 0.1; // [ratio] - min_iou_for_unknown_object_ = 0.001; // [ratio] - distance_threshold_ = 5.0; // [m] - - // Set tracker confidence threshold - confident_count_threshold_ = 3; // [count] } void TrackerProcessor::predict(const rclcpp::Time & time) @@ -95,34 +84,36 @@ std::shared_ptr TrackerProcessor::createNewTracker( const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, const geometry_msgs::msg::Transform & self_transform, const uint & channel_index) const { - const std::uint8_t label = + const LabelType label = autoware::object_recognition_utils::getHighestProbLabel(object.classification); - if (tracker_map_.count(label) != 0) { - const auto tracker = tracker_map_.at(label); + if (config_.tracker_map.count(label) != 0) { + const auto tracker = config_.tracker_map.at(label); if (tracker == "bicycle_tracker") return std::make_shared( - time, object, self_transform, channel_size_, channel_index); + time, object, self_transform, config_.channel_size, channel_index); if (tracker == "big_vehicle_tracker") return std::make_shared( - object_model::big_vehicle, time, object, self_transform, channel_size_, channel_index); + object_model::big_vehicle, time, object, self_transform, config_.channel_size, + channel_index); if (tracker == "multi_vehicle_tracker") return std::make_shared( - time, object, self_transform, channel_size_, channel_index); + time, object, self_transform, config_.channel_size, channel_index); if (tracker == "normal_vehicle_tracker") return std::make_shared( - object_model::normal_vehicle, time, object, self_transform, channel_size_, channel_index); + object_model::normal_vehicle, time, object, self_transform, config_.channel_size, + channel_index); if (tracker == "pass_through_tracker") return std::make_shared( - time, object, self_transform, channel_size_, channel_index); + time, object, self_transform, config_.channel_size, channel_index); if (tracker == "pedestrian_and_bicycle_tracker") return std::make_shared( - time, object, self_transform, channel_size_, channel_index); + time, object, self_transform, config_.channel_size, channel_index); if (tracker == "pedestrian_tracker") return std::make_shared( - time, object, self_transform, channel_size_, channel_index); + time, object, self_transform, config_.channel_size, channel_index); } return std::make_shared( - time, object, self_transform, channel_size_, channel_index); + time, object, self_transform, config_.channel_size, channel_index); } void TrackerProcessor::prune(const rclcpp::Time & time) @@ -137,7 +128,7 @@ void TrackerProcessor::removeOldTracker(const rclcpp::Time & time) { // Check elapsed time from last update for (auto itr = list_tracker_.begin(); itr != list_tracker_.end(); ++itr) { - const bool is_old = max_elapsed_time_ < (*itr)->getElapsedTimeFromLastUpdate(time); + const bool is_old = config_.tracker_lifetime < (*itr)->getElapsedTimeFromLastUpdate(time); // If the tracker is old, delete it if (is_old) { auto erase_itr = itr; @@ -168,7 +159,7 @@ void TrackerProcessor::removeOverlappedTracker(const rclcpp::Time & time) object2.kinematics.pose_with_covariance.pose.position.y); // If the distance is too large, skip - if (distance > distance_threshold_) { + if (distance > config_.distance_threshold) { continue; } @@ -184,7 +175,7 @@ void TrackerProcessor::removeOverlappedTracker(const rclcpp::Time & time) // If both trackers are UNKNOWN, delete the younger tracker // If one side of the tracker is UNKNOWN, delete UNKNOWN objects if (label1 == Label::UNKNOWN || label2 == Label::UNKNOWN) { - if (iou > min_iou_for_unknown_object_) { + if (iou > config_.min_unknown_object_removal_iou) { if (label1 == Label::UNKNOWN && label2 == Label::UNKNOWN) { if ((*itr1)->getTotalMeasurementCount() < (*itr2)->getTotalMeasurementCount()) { should_delete_tracker1 = true; @@ -198,7 +189,7 @@ void TrackerProcessor::removeOverlappedTracker(const rclcpp::Time & time) } } } else { // If neither object is UNKNOWN, delete the younger tracker - if (iou > min_iou_) { + if (iou > config_.min_known_object_removal_iou) { if ((*itr1)->getTotalMeasurementCount() < (*itr2)->getTotalMeasurementCount()) { should_delete_tracker1 = true; } else { @@ -226,7 +217,8 @@ bool TrackerProcessor::isConfidentTracker(const std::shared_ptr & track // Confidence is determined by counting the number of measurements. // If the number of measurements is equal to or greater than the threshold, the tracker is // considered confident. - return tracker->getTotalMeasurementCount() >= confident_count_threshold_; + auto label = tracker->getHighestProbLabel(); + return tracker->getTotalMeasurementCount() >= config_.confident_count_threshold.at(label); } void TrackerProcessor::getTrackedObjects( diff --git a/perception/autoware_multi_object_tracker/src/processor/processor.hpp b/perception/autoware_multi_object_tracker/src/processor/processor.hpp index 851a0f6a26717..80ca92bc43671 100644 --- a/perception/autoware_multi_object_tracker/src/processor/processor.hpp +++ b/perception/autoware_multi_object_tracker/src/processor/processor.hpp @@ -31,11 +31,23 @@ namespace autoware::multi_object_tracker { +using LabelType = autoware_perception_msgs::msg::ObjectClassification::_label_type; + +struct TrackerProcessorConfig +{ + std::map tracker_map; + size_t channel_size; + float tracker_lifetime; // [s] + float min_known_object_removal_iou; // ratio [0, 1] + float min_unknown_object_removal_iou; // ratio [0, 1] + double distance_threshold; // [m] + std::map confident_count_threshold; // [count] +}; + class TrackerProcessor { public: - explicit TrackerProcessor( - const std::map & tracker_map, const size_t & channel_size); + explicit TrackerProcessor(const TrackerProcessorConfig & config); const std::list> & getListTracker() const { return list_tracker_; } // tracker processes @@ -62,17 +74,8 @@ class TrackerProcessor void getExistenceProbabilities(std::vector> & existence_vectors) const; private: - std::map tracker_map_; + TrackerProcessorConfig config_; std::list> list_tracker_; - const size_t channel_size_; - - // parameters - float max_elapsed_time_; // [s] - float min_iou_; // [ratio] - float min_iou_for_unknown_object_; // [ratio] - double distance_threshold_; // [m] - int confident_count_threshold_; // [count] - void removeOldTracker(const rclcpp::Time & time); void removeOverlappedTracker(const rclcpp::Time & time); std::shared_ptr createNewTracker( From d5cd150c8611804d264a6f33cdab38c55c0087c9 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 16 Dec 2024 10:33:49 +0900 Subject: [PATCH 020/334] perf(goal_planner): remove unnecessary call to setMap on freespace planning (#9644) Signed-off-by: Mamoru Sobue --- .../goal_planner_module.hpp | 7 ++++--- .../pull_over_planner/freespace_pull_over.hpp | 2 ++ .../src/goal_planner_module.cpp | 7 +++---- .../src/pull_over_planner/freespace_pull_over.cpp | 2 -- 4 files changed, 9 insertions(+), 9 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp index 9dad3681f7570..aed8066ef30af 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -18,6 +18,7 @@ #include "autoware/behavior_path_goal_planner_module/decision_state.hpp" #include "autoware/behavior_path_goal_planner_module/fixed_goal_planner_base.hpp" #include "autoware/behavior_path_goal_planner_module/goal_planner_parameters.hpp" +#include "autoware/behavior_path_goal_planner_module/pull_over_planner/freespace_pull_over.hpp" #include "autoware/behavior_path_goal_planner_module/thread_data.hpp" #include "autoware/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp" #include "autoware/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" @@ -151,7 +152,7 @@ bool checkOccupancyGridCollision( // freespace parking std::optional planFreespacePath( const FreespaceParkingRequest & req, const PredictedObjects & static_target_objects, - std::shared_ptr freespace_planner); + std::shared_ptr freespace_planner); bool isStopped( std::deque & odometry_buffer, @@ -198,7 +199,7 @@ class FreespaceParkingPlanner std::mutex & freespace_parking_mutex, const std::optional & request, FreespaceParkingResponse & response, std::atomic & is_freespace_parking_cb_running, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock, - const std::shared_ptr freespace_planner) + const std::shared_ptr freespace_planner) : mutex_(freespace_parking_mutex), request_(request), response_(response), @@ -218,7 +219,7 @@ class FreespaceParkingPlanner rclcpp::Logger logger_; rclcpp::Clock::SharedPtr clock_; - std::shared_ptr freespace_planner_; + std::shared_ptr freespace_planner_; bool isStuck( const PredictedObjects & static_target_objects, const PredictedObjects & dynamic_target_objects, diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/freespace_pull_over.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/freespace_pull_over.hpp index ee370fd96b9a0..e32488965f69a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/freespace_pull_over.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/freespace_pull_over.hpp @@ -36,6 +36,8 @@ class FreespacePullOver : public PullOverPlannerBase PullOverPlannerType getPlannerType() const override { return PullOverPlannerType::FREESPACE; } + void setMap(const nav_msgs::msg::OccupancyGrid & costmap) { planner_->setMap(costmap); } + std::optional plan( const GoalCandidate & modified_goal_pose, const size_t id, const std::shared_ptr planner_data, diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 8e935c73c6ce9..61b4bf00fc13c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -16,7 +16,6 @@ #include "autoware/behavior_path_goal_planner_module/default_fixed_goal_planner.hpp" #include "autoware/behavior_path_goal_planner_module/goal_searcher.hpp" -#include "autoware/behavior_path_goal_planner_module/pull_over_planner/freespace_pull_over.hpp" #include "autoware/behavior_path_goal_planner_module/pull_over_planner/geometric_pull_over.hpp" #include "autoware/behavior_path_goal_planner_module/pull_over_planner/pull_over_planner_base.hpp" #include "autoware/behavior_path_goal_planner_module/pull_over_planner/shift_pull_over.hpp" @@ -225,7 +224,7 @@ bool checkOccupancyGridCollision( std::optional planFreespacePath( const FreespaceParkingRequest & req, const PredictedObjects & static_target_objects, - std::shared_ptr freespace_planner) + std::shared_ptr freespace_planner) { auto goal_candidates = req.goal_candidates_; auto goal_searcher = std::make_shared(req.parameters_, req.vehicle_footprint_); @@ -238,8 +237,8 @@ std::optional planFreespacePath( if (!goal_candidate.is_safe) { continue; } - // TODO(soblin): this calls setMap() in freespace_planner in the for-loop, which is very - // inefficient + + freespace_planner->setMap(*(req.get_planner_data()->costmap)); const auto freespace_path = freespace_planner->plan( goal_candidate, 0, req.get_planner_data(), BehaviorModuleOutput{} // NOTE: not used so passing {} is OK diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/freespace_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/freespace_pull_over.cpp index b51d5df42c75b..5b11d1b170ce1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/freespace_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/freespace_pull_over.cpp @@ -64,8 +64,6 @@ std::optional FreespacePullOver::plan( { const Pose & current_pose = planner_data->self_odometry->pose.pose; - planner_->setMap(*planner_data->costmap); - // offset goal pose to make straight path near goal for improving parking precision // todo: support straight path when using back constexpr double straight_distance = 1.0; From 9ee2c5aec8c0723e91675f9d54c2408e8b34c7c1 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 16 Dec 2024 10:34:07 +0900 Subject: [PATCH 021/334] refactor(goal_planner): divide sort function (#9650) Signed-off-by: Mamoru Sobue --- .../goal_planner_module.hpp | 6 + .../src/goal_planner_module.cpp | 138 ++++++++++-------- 2 files changed, 81 insertions(+), 63 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp index aed8066ef30af..3a1773324fe24 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -159,6 +159,12 @@ bool isStopped( const nav_msgs::msg::Odometry::ConstSharedPtr self_odometry, const double duration_lower, const double velocity_upper); +void sortPullOverPaths( + const std::shared_ptr planner_data, const GoalPlannerParameters & parameters, + const std::vector & pull_over_path_candidates, + const GoalCandidates & goal_candidates, const PredictedObjects & static_target_objects, + rclcpp::Logger logger, std::vector & sorted_path_indices); + // Flag class for managing whether a certain callback is running in multi-threading class ScopedFlag { diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 61b4bf00fc13c..60c056280e4db 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -981,63 +981,14 @@ BehaviorModuleOutput GoalPlannerModule::plan() return fixed_goal_planner_->plan(planner_data_); } -std::optional GoalPlannerModule::selectPullOverPath( - const PullOverContextData & context_data, +void sortPullOverPaths( + const std::shared_ptr planner_data, const GoalPlannerParameters & parameters, const std::vector & pull_over_path_candidates, - const GoalCandidates & goal_candidates) const + const GoalCandidates & goal_candidates, const PredictedObjects & static_target_objects, + rclcpp::Logger logger, std::vector & sorted_path_indices) { - universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); - - const auto & goal_pose = planner_data_->route_handler->getOriginalGoalPose(); - const double backward_length = - parameters_->backward_goal_search_length + parameters_->decide_path_distance; - const auto & prev_module_output_path = getPreviousModuleOutput().path; - const auto & soft_margins = parameters_->object_recognition_collision_check_soft_margins; - const auto & hard_margins = parameters_->object_recognition_collision_check_hard_margins; - - // STEP1: Filter valid paths before sorting - // NOTE: Since copying pull over path takes time, it is handled by indices - std::vector sorted_path_indices; - sorted_path_indices.reserve(pull_over_path_candidates.size()); - - // STEP1-1: Extract paths which have safe goal - // Create a map of goal_id to GoalCandidate for quick access - std::unordered_map goal_candidate_map; - for (const auto & goal_candidate : goal_candidates) { - goal_candidate_map[goal_candidate.id] = goal_candidate; - } - for (size_t i = 0; i < pull_over_path_candidates.size(); ++i) { - const auto & path = pull_over_path_candidates[i]; - const auto goal_candidate_it = goal_candidate_map.find(path.goal_id()); - if (goal_candidate_it != goal_candidate_map.end() && goal_candidate_it->second.is_safe) { - sorted_path_indices.push_back(i); - } - } - - // STEP1-2: Remove paths which do not have enough distance - const double prev_path_front_to_goal_dist = calcSignedArcLength( - prev_module_output_path.points, prev_module_output_path.points.front().point.pose.position, - goal_pose.position); - const auto & long_tail_reference_path = [&]() { - if (prev_path_front_to_goal_dist > backward_length) { - return prev_module_output_path; - } - // get road lanes which is at least backward_length[m] behind the goal - const auto road_lanes = utils::getExtendedCurrentLanesFromPath( - prev_module_output_path, planner_data_, backward_length, 0.0, false); - const auto goal_pose_length = lanelet::utils::getArcCoordinates(road_lanes, goal_pose).length; - return planner_data_->route_handler->getCenterLinePath( - road_lanes, std::max(0.0, goal_pose_length - backward_length), - goal_pose_length + parameters_->forward_goal_search_length); - }(); - - sorted_path_indices.erase( - std::remove_if( - sorted_path_indices.begin(), sorted_path_indices.end(), - [&](const size_t i) { - return !hasEnoughDistance(pull_over_path_candidates[i], long_tail_reference_path); - }), - sorted_path_indices.end()); + const auto & soft_margins = parameters.object_recognition_collision_check_soft_margins; + const auto & hard_margins = parameters.object_recognition_collision_check_hard_margins; // STEP2: Sort pull over path candidates // STEP2-1: Sort pull_over_path_candidates based on the order in goal_candidates @@ -1065,14 +1016,14 @@ std::optional GoalPlannerModule::selectPullOverPath( // compare to sort pull_over_path_candidates based on the order in efficient_path_order const auto comparePathTypePriority = [&](const PullOverPath & a, const PullOverPath & b) -> bool { - const auto & order = parameters_->efficient_path_order; + const auto & order = parameters.efficient_path_order; const auto a_pos = std::find(order.begin(), order.end(), magic_enum::enum_name(a.type())); const auto b_pos = std::find(order.begin(), order.end(), magic_enum::enum_name(b.type())); return a_pos < b_pos; }; // if object recognition is enabled, sort by collision check margin - if (parameters_->use_object_recognition) { + if (parameters.use_object_recognition) { // STEP2-2: Sort by collision check margins const auto [margins, margins_with_zero] = std::invoke([&]() -> std::tuple, std::vector> { @@ -1085,11 +1036,11 @@ std::optional GoalPlannerModule::selectPullOverPath( // Create a map of PullOverPath pointer to largest collision check margin std::map path_id_to_rough_margin_map; - const auto & target_objects = context_data.static_target_objects; + const auto & target_objects = static_target_objects; for (const size_t i : sorted_path_indices) { const auto & path = pull_over_path_candidates[i]; const double distance = utils::path_safety_checker::calculateRoughDistanceToObjects( - path.parking_path(), target_objects, planner_data_->parameters, false, "max"); + path.parking_path(), target_objects, planner_data->parameters, false, "max"); auto it = std::lower_bound( margins_with_zero.begin(), margins_with_zero.end(), distance, std::greater()); if (it == margins_with_zero.end()) { @@ -1119,7 +1070,7 @@ std::optional GoalPlannerModule::selectPullOverPath( // STEP2-3: Sort by curvature // If the curvature is less than the threshold, prioritize the path. const auto isHighCurvature = [&](const PullOverPath & path) -> bool { - return path.parking_path_max_curvature() >= parameters_->high_curvature_threshold; + return path.parking_path_max_curvature() >= parameters.high_curvature_threshold; }; const auto isSoftMargin = [&](const PullOverPath & path) -> bool { @@ -1155,7 +1106,7 @@ std::optional GoalPlannerModule::selectPullOverPath( // STEP2-4: Sort pull_over_path_candidates based on the order in efficient_path_order keeping // the collision check margin and curvature priority. - if (parameters_->path_priority == "efficient_path") { + if (parameters.path_priority == "efficient_path") { std::stable_sort( sorted_path_indices.begin(), sorted_path_indices.end(), [&](const size_t a_i, const size_t b_i) { @@ -1182,14 +1133,14 @@ std::optional GoalPlannerModule::selectPullOverPath( const std::string path_priority_info_str = goal_planner_utils::makePathPriorityDebugMessage( sorted_path_indices, pull_over_path_candidates, goal_id_to_index, goal_candidates, path_id_to_rough_margin_map, isSoftMargin, isHighCurvature); - RCLCPP_DEBUG_STREAM(getLogger(), path_priority_info_str); + RCLCPP_DEBUG_STREAM(logger, path_priority_info_str); } else { /** * NOTE: use_object_recognition=false is not recommended. This option will be deprecated in the * future. sort by curvature is not implemented yet. * Sort pull_over_path_candidates based on the order in efficient_path_order */ - if (parameters_->path_priority == "efficient_path") { + if (parameters.path_priority == "efficient_path") { std::stable_sort( sorted_path_indices.begin(), sorted_path_indices.end(), [&](const size_t a_i, const size_t b_i) { @@ -1202,6 +1153,67 @@ std::optional GoalPlannerModule::selectPullOverPath( }); } } +} + +std::optional GoalPlannerModule::selectPullOverPath( + const PullOverContextData & context_data, + const std::vector & pull_over_path_candidates, + const GoalCandidates & goal_candidates) const +{ + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); + + const auto & goal_pose = planner_data_->route_handler->getOriginalGoalPose(); + const double backward_length = + parameters_->backward_goal_search_length + parameters_->decide_path_distance; + const auto & prev_module_output_path = getPreviousModuleOutput().path; + + // STEP1: Filter valid paths before sorting + // NOTE: Since copying pull over path takes time, it is handled by indices + std::vector sorted_path_indices; + sorted_path_indices.reserve(pull_over_path_candidates.size()); + + // STEP1-1: Extract paths which have safe goal + // Create a map of goal_id to GoalCandidate for quick access + std::unordered_map goal_candidate_map; + for (const auto & goal_candidate : goal_candidates) { + goal_candidate_map[goal_candidate.id] = goal_candidate; + } + for (size_t i = 0; i < pull_over_path_candidates.size(); ++i) { + const auto & path = pull_over_path_candidates[i]; + const auto goal_candidate_it = goal_candidate_map.find(path.goal_id()); + if (goal_candidate_it != goal_candidate_map.end() && goal_candidate_it->second.is_safe) { + sorted_path_indices.push_back(i); + } + } + + // STEP1-2: Remove paths which do not have enough distance + const double prev_path_front_to_goal_dist = calcSignedArcLength( + prev_module_output_path.points, prev_module_output_path.points.front().point.pose.position, + goal_pose.position); + const auto & long_tail_reference_path = [&]() { + if (prev_path_front_to_goal_dist > backward_length) { + return prev_module_output_path; + } + // get road lanes which is at least backward_length[m] behind the goal + const auto road_lanes = utils::getExtendedCurrentLanesFromPath( + prev_module_output_path, planner_data_, backward_length, 0.0, false); + const auto goal_pose_length = lanelet::utils::getArcCoordinates(road_lanes, goal_pose).length; + return planner_data_->route_handler->getCenterLinePath( + road_lanes, std::max(0.0, goal_pose_length - backward_length), + goal_pose_length + parameters_->forward_goal_search_length); + }(); + + sorted_path_indices.erase( + std::remove_if( + sorted_path_indices.begin(), sorted_path_indices.end(), + [&](const size_t i) { + return !hasEnoughDistance(pull_over_path_candidates[i], long_tail_reference_path); + }), + sorted_path_indices.end()); + + sortPullOverPaths( + planner_data_, *parameters_, pull_over_path_candidates, goal_candidates, + context_data.static_target_objects, getLogger(), sorted_path_indices); // STEP3: Select the final pull over path by checking collision to make it as high priority as // possible From 496fb5e9f1c453ca771e46e75724ddc7d6ca17a0 Mon Sep 17 00:00:00 2001 From: Masaki Baba Date: Mon, 16 Dec 2024 10:55:27 +0900 Subject: [PATCH 022/334] feat(image_projection_based_fusion): add timekeeper (#9632) * add timekeeper Signed-off-by: a-maumau * chore: refactor time-keeper position Signed-off-by: Taekjin LEE * chore: bring back a missing comment Signed-off-by: Taekjin LEE * chore: remove redundant timekeepers Signed-off-by: Taekjin LEE --------- Signed-off-by: a-maumau Signed-off-by: Taekjin LEE Co-authored-by: Taekjin LEE --- .../config/fusion_common.param.yaml | 3 +++ .../fusion_node.hpp | 6 ++++++ .../roi_cluster_fusion/node.hpp | 1 + .../roi_pointcloud_fusion/node.hpp | 2 ++ .../segmentation_pointcloud_fusion/node.hpp | 1 + .../src/fusion_node.cpp | 21 +++++++++++++++++++ .../src/pointpainting_fusion/node.cpp | 15 +++++++++++++ .../src/roi_cluster_fusion/node.cpp | 13 ++++++++++++ .../src/roi_detected_object_fusion/node.cpp | 15 +++++++++++++ .../src/roi_pointcloud_fusion/node.cpp | 14 +++++++++++++ .../segmentation_pointcloud_fusion/node.cpp | 12 +++++++++++ 11 files changed, 103 insertions(+) diff --git a/perception/autoware_image_projection_based_fusion/config/fusion_common.param.yaml b/perception/autoware_image_projection_based_fusion/config/fusion_common.param.yaml index 662362c4fd7c5..347cb57b484e9 100644 --- a/perception/autoware_image_projection_based_fusion/config/fusion_common.param.yaml +++ b/perception/autoware_image_projection_based_fusion/config/fusion_common.param.yaml @@ -12,3 +12,6 @@ filter_scope_max_x: 100.0 filter_scope_max_y: 100.0 filter_scope_max_z: 100.0 + + # debug parameters + publish_processing_time_detail: false diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp index c9b4f1f7b903f..04ecf89faa0d4 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp @@ -18,6 +18,7 @@ #include #include #include +#include #include #include @@ -142,6 +143,11 @@ class FusionNode : public rclcpp::Node /** \brief processing time publisher. **/ std::unique_ptr> stop_watch_ptr_; std::unique_ptr debug_publisher_; + + // timekeeper + rclcpp::Publisher::SharedPtr + detailed_processing_time_publisher_; + std::shared_ptr time_keeper_; }; } // namespace autoware::image_projection_based_fusion diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_cluster_fusion/node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_cluster_fusion/node.hpp index 2c0283a190023..be05c0a1c4bc6 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_cluster_fusion/node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_cluster_fusion/node.hpp @@ -53,6 +53,7 @@ class RoiClusterFusionNode double fusion_distance_; double trust_object_distance_; std::string non_trust_object_iou_mode_{"iou_x"}; + bool is_far_enough(const DetectedObjectWithFeature & obj, const double distance_threshold); bool out_of_scope(const DetectedObjectWithFeature & obj) override; double cal_iou_by_mode( diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp index 4de49df61a071..9baf754e224a7 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp @@ -19,8 +19,10 @@ #include +#include #include #include + namespace autoware::image_projection_based_fusion { class RoiPointCloudFusionNode diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp index b09e9521bdcdb..0bec3195bb402 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp @@ -20,6 +20,7 @@ #include #include +#include #include #include #include diff --git a/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp b/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp index 6c575752b52e5..bd4d57e45c582 100644 --- a/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp @@ -42,6 +42,7 @@ static double processing_time_ms = 0; namespace autoware::image_projection_based_fusion { +using autoware::universe_utils::ScopedTimeTrack; template FusionNode::FusionNode( @@ -130,6 +131,17 @@ FusionNode::FusionNode( debugger_ = std::make_shared(this, rois_number_, image_buffer_size, input_camera_topics_); } + + // time keeper + bool use_time_keeper = declare_parameter("publish_processing_time_detail"); + if (use_time_keeper) { + detailed_processing_time_publisher_ = + this->create_publisher( + "~/debug/processing_time_detail_ms", 1); + auto time_keeper = autoware::universe_utils::TimeKeeper(detailed_processing_time_publisher_); + time_keeper_ = std::make_shared(time_keeper); + } + point_project_to_unrectified_image_ = declare_parameter("point_project_to_unrectified_image"); @@ -170,6 +182,9 @@ template void FusionNode::subCallback( const typename TargetMsg3D::ConstSharedPtr input_msg) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + if (cached_msg_.second != nullptr) { stop_watch_ptr_->toc("processing_time", true); timer_->cancel(); @@ -306,6 +321,9 @@ template void FusionNode::roiCallback( const typename Msg2D::ConstSharedPtr input_roi_msg, const std::size_t roi_i) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + stop_watch_ptr_->toc("processing_time", true); int64_t timestamp_nsec = (*input_roi_msg).header.stamp.sec * static_cast(1e9) + @@ -378,6 +396,9 @@ void FusionNode::postprocess(TargetMsg3D & output_msg template void FusionNode::timer_callback() { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + using std::chrono_literals::operator""ms; timer_->cancel(); if (mutex_cached_msgs_.try_lock()) { diff --git a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp index d4601e26dda46..4d12de2685c95 100644 --- a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp @@ -24,6 +24,7 @@ #include #include #include +#include #include #include @@ -35,6 +36,7 @@ namespace { +using autoware::universe_utils::ScopedTimeTrack; Eigen::Affine3f _transformToEigen(const geometry_msgs::msg::Transform & t) { @@ -202,6 +204,9 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt void PointPaintingFusionNode::preprocess(sensor_msgs::msg::PointCloud2 & painted_pointcloud_msg) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + if (painted_pointcloud_msg.data.empty() || painted_pointcloud_msg.fields.empty()) { RCLCPP_WARN_STREAM_THROTTLE( this->get_logger(), *this->get_clock(), 1000, "Empty sensor points!"); @@ -273,6 +278,9 @@ void PointPaintingFusionNode::fuseOnSingleImage( if (!checkCameraInfo(camera_info)) return; + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + std::vector debug_image_rois; std::vector debug_image_points; @@ -372,6 +380,10 @@ dc | dc dc dc dc ||zc| } if (debugger_) { + std::unique_ptr inner_st_ptr; + if (time_keeper_) + inner_st_ptr = std::make_unique("publish debug message", *time_keeper_); + debugger_->image_rois_ = debug_image_rois; debugger_->obstacle_points_ = debug_image_points; debugger_->publishImage(image_id, input_roi_msg.header.stamp); @@ -380,6 +392,9 @@ dc | dc dc dc dc ||zc| void PointPaintingFusionNode::postprocess(sensor_msgs::msg::PointCloud2 & painted_pointcloud_msg) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + const auto objects_sub_count = obj_pub_ptr_->get_subscription_count() + obj_pub_ptr_->get_intra_process_subscription_count(); if (objects_sub_count < 1) { diff --git a/perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp index 9a94613a2b788..7520647544684 100644 --- a/perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp @@ -16,12 +16,14 @@ #include #include +#include #include #include #include #include +#include #include #include #include @@ -36,6 +38,7 @@ namespace autoware::image_projection_based_fusion { +using autoware::universe_utils::ScopedTimeTrack; RoiClusterFusionNode::RoiClusterFusionNode(const rclcpp::NodeOptions & options) : FusionNode( @@ -55,6 +58,9 @@ RoiClusterFusionNode::RoiClusterFusionNode(const rclcpp::NodeOptions & options) void RoiClusterFusionNode::preprocess(DetectedObjectsWithFeature & output_cluster_msg) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + // reset cluster semantic type if (!use_cluster_semantic_type_) { for (auto & feature_object : output_cluster_msg.feature_objects) { @@ -67,6 +73,9 @@ void RoiClusterFusionNode::preprocess(DetectedObjectsWithFeature & output_cluste void RoiClusterFusionNode::postprocess(DetectedObjectsWithFeature & output_cluster_msg) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + if (!remove_unknown_) { return; } @@ -91,6 +100,9 @@ void RoiClusterFusionNode::fuseOnSingleImage( { if (!checkCameraInfo(camera_info)) return; + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + image_geometry::PinholeCameraModel pinhole_camera_model; pinhole_camera_model.fromCameraInfo(camera_info); @@ -110,6 +122,7 @@ void RoiClusterFusionNode::fuseOnSingleImage( } std::map m_cluster_roi; + for (std::size_t i = 0; i < input_cluster_msg.feature_objects.size(); ++i) { if (input_cluster_msg.feature_objects.at(i).feature.cluster.data.empty()) { continue; diff --git a/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp index 3ef3af8168f53..035bc259ab73c 100644 --- a/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp @@ -18,14 +18,17 @@ #include #include +#include #include #include +#include #include #include namespace autoware::image_projection_based_fusion { +using autoware::universe_utils::ScopedTimeTrack; RoiDetectedObjectFusionNode::RoiDetectedObjectFusionNode(const rclcpp::NodeOptions & options) : FusionNode( @@ -49,6 +52,9 @@ RoiDetectedObjectFusionNode::RoiDetectedObjectFusionNode(const rclcpp::NodeOptio void RoiDetectedObjectFusionNode::preprocess(DetectedObjects & output_msg) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + std::vector passthrough_object_flags, fused_object_flags, ignored_object_flags; passthrough_object_flags.resize(output_msg.objects.size()); fused_object_flags.resize(output_msg.objects.size()); @@ -81,6 +87,9 @@ void RoiDetectedObjectFusionNode::fuseOnSingleImage( const sensor_msgs::msg::CameraInfo & camera_info, DetectedObjects & output_object_msg __attribute__((unused))) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + if (!checkCameraInfo(camera_info)) return; Eigen::Affine3d object2camera_affine; @@ -117,6 +126,9 @@ RoiDetectedObjectFusionNode::generateDetectedObjectRoIs( const Eigen::Affine3d & object2camera_affine, const image_geometry::PinholeCameraModel & pinhole_camera_model) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + std::map object_roi_map; int64_t timestamp_nsec = input_object_msg.header.stamp.sec * static_cast(1e9) + input_object_msg.header.stamp.nanosec; @@ -202,6 +214,9 @@ void RoiDetectedObjectFusionNode::fuseObjectsOnImage( const std::vector & image_rois, const std::map & object_roi_map) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + int64_t timestamp_nsec = input_object_msg.header.stamp.sec * static_cast(1e9) + input_object_msg.header.stamp.nanosec; if (fused_object_flags_map_.size() == 0 || ignored_object_flags_map_.size() == 0) { diff --git a/perception/autoware_image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp index f9eb4ef909282..206a5f77a0235 100644 --- a/perception/autoware_image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp @@ -17,6 +17,9 @@ #include "autoware/image_projection_based_fusion/utils/geometry.hpp" #include "autoware/image_projection_based_fusion/utils/utils.hpp" +#include + +#include #include #ifdef ROS_DISTRO_GALACTIC @@ -31,6 +34,8 @@ namespace autoware::image_projection_based_fusion { +using autoware::universe_utils::ScopedTimeTrack; + RoiPointCloudFusionNode::RoiPointCloudFusionNode(const rclcpp::NodeOptions & options) : FusionNode( "roi_pointcloud_fusion", options) @@ -47,12 +52,18 @@ RoiPointCloudFusionNode::RoiPointCloudFusionNode(const rclcpp::NodeOptions & opt void RoiPointCloudFusionNode::preprocess( __attribute__((unused)) sensor_msgs::msg::PointCloud2 & pointcloud_msg) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + return; } void RoiPointCloudFusionNode::postprocess( __attribute__((unused)) sensor_msgs::msg::PointCloud2 & pointcloud_msg) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + const auto objects_sub_count = pub_objects_ptr_->get_subscription_count() + pub_objects_ptr_->get_intra_process_subscription_count(); if (objects_sub_count < 1) { @@ -81,6 +92,9 @@ void RoiPointCloudFusionNode::fuseOnSingleImage( const sensor_msgs::msg::CameraInfo & camera_info, __attribute__((unused)) sensor_msgs::msg::PointCloud2 & output_pointcloud_msg) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + if (input_pointcloud_msg.data.empty()) { return; } diff --git a/perception/autoware_image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp index e678a956bc64e..afeff213c0afe 100644 --- a/perception/autoware_image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp @@ -17,6 +17,7 @@ #include "autoware/image_projection_based_fusion/utils/geometry.hpp" #include "autoware/image_projection_based_fusion/utils/utils.hpp" +#include #include #include @@ -32,6 +33,8 @@ namespace autoware::image_projection_based_fusion { +using autoware::universe_utils::ScopedTimeTrack; + SegmentPointCloudFusionNode::SegmentPointCloudFusionNode(const rclcpp::NodeOptions & options) : FusionNode("segmentation_pointcloud_fusion", options) { @@ -49,11 +52,17 @@ SegmentPointCloudFusionNode::SegmentPointCloudFusionNode(const rclcpp::NodeOptio void SegmentPointCloudFusionNode::preprocess(__attribute__((unused)) PointCloud2 & pointcloud_msg) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + return; } void SegmentPointCloudFusionNode::postprocess(PointCloud2 & pointcloud_msg) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + auto original_cloud = std::make_shared(pointcloud_msg); int point_step = original_cloud->point_step; @@ -82,6 +91,9 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage( [[maybe_unused]] const Image & input_mask, __attribute__((unused)) const CameraInfo & camera_info, __attribute__((unused)) PointCloud2 & output_cloud) { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + if (input_pointcloud_msg.data.empty()) { return; } From 51a74c62aa95f28d4f8f2d66778ea35972e2f2f9 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Mon, 16 Dec 2024 11:03:25 +0900 Subject: [PATCH 023/334] fix(autoware_multi_object_tracker): fix bugprone-errors (#9651) fix: bugprone-errors Signed-off-by: kobayu858 --- .../lib/tracker/model/bicycle_tracker.cpp | 7 ++----- .../lib/tracker/motion_model/bicycle_motion_model.cpp | 6 +++--- .../src/processor/input_manager.cpp | 10 +++++----- 3 files changed, 10 insertions(+), 13 deletions(-) diff --git a/perception/autoware_multi_object_tracker/lib/tracker/model/bicycle_tracker.cpp b/perception/autoware_multi_object_tracker/lib/tracker/model/bicycle_tracker.cpp index 098ad39dd3df9..69a9edd9c9d9e 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/model/bicycle_tracker.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/model/bicycle_tracker.cpp @@ -208,11 +208,8 @@ bool BicycleTracker::measureWithShape(const autoware_perception_msgs::msg::Detec constexpr double size_min = 0.1; // [m] if ( object.shape.dimensions.x > size_max || object.shape.dimensions.y > size_max || - object.shape.dimensions.z > size_max) { - return false; - } else if ( - object.shape.dimensions.x < size_min || object.shape.dimensions.y < size_min || - object.shape.dimensions.z < size_min) { + object.shape.dimensions.z > size_max || object.shape.dimensions.x < size_min || + object.shape.dimensions.y < size_min || object.shape.dimensions.z < size_min) { return false; } diff --git a/perception/autoware_multi_object_tracker/lib/tracker/motion_model/bicycle_motion_model.cpp b/perception/autoware_multi_object_tracker/lib/tracker/motion_model/bicycle_motion_model.cpp index 89258835f920b..c65efffe99a47 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/motion_model/bicycle_motion_model.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/motion_model/bicycle_motion_model.cpp @@ -315,7 +315,7 @@ bool BicycleMotionModel::predictStateStep(const double dt, KalmanFilter & ekf) c double w = vel * sin_slip / lr_; const double sin_2yaw = std::sin(2.0f * X_t(IDX::YAW)); const double w_dtdt = w * dt * dt; - const double vv_dtdt__lr = vel * vel * dt * dt / lr_; + const double vv_dtdt_lr = vel * vel * dt * dt / lr_; // Predict state vector X t+1 Eigen::MatrixXd X_next_t(DIM, 1); // predicted state @@ -332,11 +332,11 @@ bool BicycleMotionModel::predictStateStep(const double dt, KalmanFilter & ekf) c A(IDX::X, IDX::YAW) = -vel * sin_yaw * dt - 0.5 * vel * cos_yaw * w_dtdt; A(IDX::X, IDX::VEL) = cos_yaw * dt - sin_yaw * w_dtdt; A(IDX::X, IDX::SLIP) = - -vel * sin_yaw * dt - 0.5 * (cos_slip * sin_yaw + sin_slip * cos_yaw) * vv_dtdt__lr; + -vel * sin_yaw * dt - 0.5 * (cos_slip * sin_yaw + sin_slip * cos_yaw) * vv_dtdt_lr; A(IDX::Y, IDX::YAW) = vel * cos_yaw * dt - 0.5 * vel * sin_yaw * w_dtdt; A(IDX::Y, IDX::VEL) = sin_yaw * dt + cos_yaw * w_dtdt; A(IDX::Y, IDX::SLIP) = - vel * cos_yaw * dt + 0.5 * (cos_slip * cos_yaw - sin_slip * sin_yaw) * vv_dtdt__lr; + vel * cos_yaw * dt + 0.5 * (cos_slip * cos_yaw - sin_slip * sin_yaw) * vv_dtdt_lr; A(IDX::YAW, IDX::VEL) = 1.0 / lr_ * sin_slip * dt; A(IDX::YAW, IDX::SLIP) = vel / lr_ * cos_slip * dt; diff --git a/perception/autoware_multi_object_tracker/src/processor/input_manager.cpp b/perception/autoware_multi_object_tracker/src/processor/input_manager.cpp index fa333ea06a4b9..d5b12ed7b2b82 100644 --- a/perception/autoware_multi_object_tracker/src/processor/input_manager.cpp +++ b/perception/autoware_multi_object_tracker/src/processor/input_manager.cpp @@ -263,11 +263,11 @@ void InputManager::getObjectTimeInterval( // The default object_earliest_time is to have a 1-second time interval const rclcpp::Time object_earliest_time_default = object_latest_time - rclcpp::Duration::from_seconds(1.0); - if (latest_exported_object_time_ < object_earliest_time_default) { - // if the latest exported object time is too old, set to the default - object_earliest_time = object_earliest_time_default; - } else if (latest_exported_object_time_ > object_latest_time) { - // if the latest exported object time is newer than the object_latest_time, set to the default + if ( + latest_exported_object_time_ < object_earliest_time_default || + latest_exported_object_time_ > object_latest_time) { + // if the latest exported object time is too old or newer than the object_latest_time, + // set to the default object_earliest_time = object_earliest_time_default; } else { // The object_earliest_time is the latest exported object time From 932e87fde0614e9342e8889c7961f103e615e4e3 Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Mon, 16 Dec 2024 12:18:07 +0900 Subject: [PATCH 024/334] chore(autoware_costmap_generator): suppress Could not find a connection between 'map' and 'base_link' (#9655) Signed-off-by: Y.Hisaki --- .../autoware_costmap_generator/src/costmap_generator.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/planning/autoware_costmap_generator/src/costmap_generator.cpp b/planning/autoware_costmap_generator/src/costmap_generator.cpp index 052bb2728a3b1..081a6ead91cda 100644 --- a/planning/autoware_costmap_generator/src/costmap_generator.cpp +++ b/planning/autoware_costmap_generator/src/costmap_generator.cpp @@ -51,6 +51,7 @@ #include #include #include +#include #include #include @@ -68,14 +69,15 @@ namespace // Copied from scenario selector geometry_msgs::msg::PoseStamped::ConstSharedPtr getCurrentPose( - const tf2_ros::Buffer & tf_buffer, const rclcpp::Logger & logger) + const tf2_ros::Buffer & tf_buffer, const rclcpp::Logger & logger, + const rclcpp::Clock::SharedPtr clock) { geometry_msgs::msg::TransformStamped tf_current_pose; try { tf_current_pose = tf_buffer.lookupTransform("map", "base_link", tf2::TimePointZero); } catch (tf2::TransformException & ex) { - RCLCPP_ERROR(logger, "%s", ex.what()); + RCLCPP_ERROR_THROTTLE(logger, *clock, 5000, "%s", ex.what()); return nullptr; } @@ -253,7 +255,7 @@ void CostmapGenerator::update_data() void CostmapGenerator::set_current_pose() { - current_pose_ = getCurrentPose(tf_buffer_, this->get_logger()); + current_pose_ = getCurrentPose(tf_buffer_, this->get_logger(), this->get_clock()); } void CostmapGenerator::onTimer() From a85c67b2864007a77641ba3713e9c668fe2d6b1b Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Mon, 16 Dec 2024 16:56:27 +0900 Subject: [PATCH 025/334] fix(autoware_radar_fusion_to_detected_object): fix bugprone-errors (#9654) fix: bugprone-error Signed-off-by: kobayu858 --- .../src/node.cpp | 10 ++++------ .../src/radar_fusion_to_detected_object.cpp | 4 +--- 2 files changed, 5 insertions(+), 9 deletions(-) diff --git a/perception/autoware_radar_fusion_to_detected_object/src/node.cpp b/perception/autoware_radar_fusion_to_detected_object/src/node.cpp index 58e893032340c..fcebbbc905425 100644 --- a/perception/autoware_radar_fusion_to_detected_object/src/node.cpp +++ b/perception/autoware_radar_fusion_to_detected_object/src/node.cpp @@ -25,7 +25,6 @@ using namespace std::literals; using std::chrono::duration; using std::chrono::duration_cast; using std::chrono::nanoseconds; -using std::placeholders::_1; namespace { @@ -58,7 +57,7 @@ RadarObjectFusionToDetectedObjectNode::RadarObjectFusionToDetectedObjectNode( { // Parameter Server set_param_res_ = this->add_on_set_parameters_callback( - std::bind(&RadarObjectFusionToDetectedObjectNode::onSetParam, this, _1)); + std::bind(&RadarObjectFusionToDetectedObjectNode::onSetParam, this, std::placeholders::_1)); // Node Parameter node_param_.update_rate_hz = declare_parameter("node_params.update_rate_hz"); @@ -93,11 +92,10 @@ RadarObjectFusionToDetectedObjectNode::RadarObjectFusionToDetectedObjectNode( sub_object_.subscribe(this, "~/input/objects", rclcpp::QoS{1}.get_rmw_qos_profile()); sub_radar_.subscribe(this, "~/input/radars", rclcpp::QoS{1}.get_rmw_qos_profile()); - using std::placeholders::_1; - using std::placeholders::_2; sync_ptr_ = std::make_shared(SyncPolicy(20), sub_object_, sub_radar_); - sync_ptr_->registerCallback( - std::bind(&RadarObjectFusionToDetectedObjectNode::onData, this, _1, _2)); + sync_ptr_->registerCallback(std::bind( + &RadarObjectFusionToDetectedObjectNode::onData, this, std::placeholders::_1, + std::placeholders::_2)); // Publisher pub_objects_ = create_publisher("~/output/objects", 1); diff --git a/perception/autoware_radar_fusion_to_detected_object/src/radar_fusion_to_detected_object.cpp b/perception/autoware_radar_fusion_to_detected_object/src/radar_fusion_to_detected_object.cpp index 98f429292ec73..6d19f299973bd 100644 --- a/perception/autoware_radar_fusion_to_detected_object/src/radar_fusion_to_detected_object.cpp +++ b/perception/autoware_radar_fusion_to_detected_object/src/radar_fusion_to_detected_object.cpp @@ -158,9 +158,7 @@ bool RadarFusionToDetectedObject::isYawCorrect( const double object_yaw = autoware::universe_utils::normalizeRadian( tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation)); const double diff_yaw = autoware::universe_utils::normalizeRadian(twist_yaw - object_yaw); - if (std::abs(diff_yaw) < yaw_threshold) { - return true; - } else if (M_PI - yaw_threshold < std::abs(diff_yaw)) { + if (std::abs(diff_yaw) < yaw_threshold || M_PI - yaw_threshold < std::abs(diff_yaw)) { return true; } else { return false; From 9167bfb6c6d0c500a9e61451c3d1d4822f4602b4 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Mon, 16 Dec 2024 16:57:01 +0900 Subject: [PATCH 026/334] fix(autoware_control_evaluator): fix bugprone-exception-escape (#9630) * fix: bugprone-exception-escape Signed-off-by: kobayu858 * fix: cpplint Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../src/control_evaluator_node.cpp | 79 ++++++++++--------- 1 file changed, 43 insertions(+), 36 deletions(-) diff --git a/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp b/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp index 9c8579469f878..b0db41b0fdc73 100644 --- a/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp +++ b/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp @@ -21,6 +21,7 @@ #include #include #include +#include #include #include #include @@ -52,45 +53,51 @@ ControlEvaluatorNode::~ControlEvaluatorNode() return; } - // generate json data - using json = nlohmann::json; - json j; - for (Metric metric : metrics_) { - const std::string base_name = metric_to_str.at(metric) + "/"; - j[base_name + "min"] = metric_accumulators_[static_cast(metric)].min(); - j[base_name + "max"] = metric_accumulators_[static_cast(metric)].max(); - j[base_name + "mean"] = metric_accumulators_[static_cast(metric)].mean(); - j[base_name + "count"] = metric_accumulators_[static_cast(metric)].count(); - j[base_name + "description"] = metric_descriptions.at(metric); - } + try { + // generate json data + using json = nlohmann::json; + json j; + for (Metric metric : metrics_) { + const std::string base_name = metric_to_str.at(metric) + "/"; + j[base_name + "min"] = metric_accumulators_[static_cast(metric)].min(); + j[base_name + "max"] = metric_accumulators_[static_cast(metric)].max(); + j[base_name + "mean"] = metric_accumulators_[static_cast(metric)].mean(); + j[base_name + "count"] = metric_accumulators_[static_cast(metric)].count(); + j[base_name + "description"] = metric_descriptions.at(metric); + } - // get output folder - const std::string output_folder_str = - rclcpp::get_logging_directory().string() + "/autoware_metrics"; - if (!std::filesystem::exists(output_folder_str)) { - if (!std::filesystem::create_directories(output_folder_str)) { - RCLCPP_ERROR( - this->get_logger(), "Failed to create directories: %s", output_folder_str.c_str()); - return; + // get output folder + const std::string output_folder_str = + rclcpp::get_logging_directory().string() + "/autoware_metrics"; + if (!std::filesystem::exists(output_folder_str)) { + if (!std::filesystem::create_directories(output_folder_str)) { + RCLCPP_ERROR( + this->get_logger(), "Failed to create directories: %s", output_folder_str.c_str()); + return; + } } - } - // get time stamp - std::time_t now_time_t = std::chrono::system_clock::to_time_t(std::chrono::system_clock::now()); - std::tm * local_time = std::localtime(&now_time_t); - std::ostringstream oss; - oss << std::put_time(local_time, "%Y-%m-%d-%H-%M-%S"); - std::string cur_time_str = oss.str(); - - // Write metrics .json to file - const std::string output_file_str = - output_folder_str + "/autoware_control_evaluator-" + cur_time_str + ".json"; - std::ofstream f(output_file_str); - if (f.is_open()) { - f << j.dump(4); - f.close(); - } else { - RCLCPP_ERROR(this->get_logger(), "Failed to open file: %s", output_file_str.c_str()); + // get time stamp + std::time_t now_time_t = std::chrono::system_clock::to_time_t(std::chrono::system_clock::now()); + std::tm * local_time = std::localtime(&now_time_t); + std::ostringstream oss; + oss << std::put_time(local_time, "%Y-%m-%d-%H-%M-%S"); + std::string cur_time_str = oss.str(); + + // Write metrics .json to file + const std::string output_file_str = + output_folder_str + "/autoware_control_evaluator-" + cur_time_str + ".json"; + std::ofstream f(output_file_str); + if (f.is_open()) { + f << j.dump(4); + f.close(); + } else { + RCLCPP_ERROR(this->get_logger(), "Failed to open file: %s", output_file_str.c_str()); + } + } catch (const std::exception & e) { + std::cerr << "Exception in ControlEvaluatorNode destructor: " << e.what() << std::endl; + } catch (...) { + std::cerr << "Unknown exception in ControlEvaluatorNode destructor" << std::endl; } } From 19ca9f774da7e2e888aa4d62a381b623dce5cd8f Mon Sep 17 00:00:00 2001 From: Mitsuhiro Sakamoto <50359861+mitukou1109@users.noreply.github.com> Date: Mon, 16 Dec 2024 17:02:46 +0900 Subject: [PATCH 027/334] docs(obstacle_cruise_planner): add supplemental figures (#9154) * add behavior determination flowchart * add cruise planning block diagram * style(pre-commit): autofix --------- Signed-off-by: mitukou1109 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../README.md | 8 + ...ehavior_determination_flowchart.drawio.svg | 1961 +++++++++++++++++ .../cruise_planning_block_diagram.drawio.svg | 989 +++++++++ 3 files changed, 2958 insertions(+) create mode 100644 planning/autoware_obstacle_cruise_planner/media/behavior_determination_flowchart.drawio.svg create mode 100644 planning/autoware_obstacle_cruise_planner/media/cruise_planning_block_diagram.drawio.svg diff --git a/planning/autoware_obstacle_cruise_planner/README.md b/planning/autoware_obstacle_cruise_planner/README.md index 42a569c07ddb2..273363489d56f 100644 --- a/planning/autoware_obstacle_cruise_planner/README.md +++ b/planning/autoware_obstacle_cruise_planner/README.md @@ -75,6 +75,10 @@ The obstacles not in front of the ego will be ignored. ![determine_cruise_stop_slow_down](./media/determine_cruise_stop_slow_down.drawio.svg) +The behavior determination flowchart is shown below. + +![behavior_determination_flowchart](./media/behavior_determination_flowchart.drawio.svg) + #### Determine cruise vehicles The obstacles meeting the following condition are determined as obstacles for cruising. @@ -241,6 +245,10 @@ $$ | `lpf(val)` | apply low-pass filter to `val` | | `pid(val)` | apply pid to `val` | +#### Block diagram + +![cruise_planning_block_diagram](./media/cruise_planning_block_diagram.drawio.svg) + ### Slow down planning | Parameter | Type | Description | diff --git a/planning/autoware_obstacle_cruise_planner/media/behavior_determination_flowchart.drawio.svg b/planning/autoware_obstacle_cruise_planner/media/behavior_determination_flowchart.drawio.svg new file mode 100644 index 0000000000000..e37e2250ed3f8 --- /dev/null +++ b/planning/autoware_obstacle_cruise_planner/media/behavior_determination_flowchart.drawio.svg @@ -0,0 +1,1961 @@ + + + + + + + + + + + + + + + + + +
+
+
+ + Stop obstacle + +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ + Slow down + +
+ + obstacle + +
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ + Object + +
+ (PredictedObject / PointCloud) +
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ + Cruise obstacle + +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ Type + for +
+ cruising? +
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + +
+
+
+ Type + for +
+ stop? +
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + +
+
+
+ Should +
maintain stop?
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + +
+
+
+ Previously +
stop obstacle?
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Previously +
slow down obstacle?
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + +
+
+
+ Lateral +
distance > C1?
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + +
+
+
+ Ego + driving +
+ forward? +
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + +
+
+
+ Moving in +
+ same + direction? +
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + +
+
+
+ Lateral +
+ distance + < A1? +
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ Not + crossing +
ego's trajectory?
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ Inside ego's +
trajectory?
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ Ego moving? +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ Lateral +
+ distance + < B1? +
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + +
+
+
+ Type for +
outside stop?
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + +
+
+
+ Time to approach +
+ ego's + trajectory < B2? +
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + +
+
+
+ Type for +
outside cruising?
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + +
+
+
+ Type for +
inside cruising?
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+
Collision
+
predicted?
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + +
+
+
+ Type for +
inside stop?
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ Longitudinal +
velocity > A3?
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ Longitudinal +
velocity > A4?
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + +
+
+
+ Previously +
cruise obstacle?
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + +
+
+
+ Longitudinal +
velocity > A5?
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + +
+
+
+
Collision
+
predicted?
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + +
+
+
+
Collision
+
predicted?
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + +
+
+
+
+ Not + transient +
+
obstacle?
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ Type + for +
+ slow down? +
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + +
+
+
+ Lateral +
distance < C2?
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + +
+
+
+ decrement +
count
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ increment +
count
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
count > -C3?
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
count > C4?
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+
Collision
+
predicted?
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+
reset
+
count
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + +
+
+
+ + A1: + + + behavior_determination.cruise.max_lat_margin +
+
+
+ A2: + + behavior_determination.cruise.outside_obstacle.max_lateral_time_margin +
+
+
+
+ A3: + + behavior_determination.obstacle_velocity_threshold_from_cruise_to_stop +
+
+
+
+ A4: + + behavior_determination.obstacle_velocity_threshold_from_stop_to_cruise +
+
+
+
+ A5: + + behavior_determination.cruise.outside_obstacle.obstacle_velocity_threshold +
+
+
+
+ +
+
+
+
+ B1: + + behavior_determination.stop.max_lat_margin +
+
+
+
+ B2: + + behavior_determination.stop.outside_obstacle.max_lateral_time_margin +
+
+
+
+ B3: + + behavior_determination.stop.crossing_obstacle.collision_time_margin +
+
+
+
+ +
+
+
+
+ C1: + behavior_determination.slow_down.max_lat_margin +
+
+ + + behavior_determination.slow_down.lat_hysteresis_margin + +
+
+
+
+ C2: + behavior_determination.slow_down.max_lat_margin +
+
+ - + behavior_determination.slow_down.lat_hysteresis_margin + +
+
+
+
+ C3: + + behavior_determination.slow_down.successive_num_to_exit_slow_down_condition +
+
+
+
+ C4: + + behavior_determination.slow_down.successive_num_to_entry_slow_down_condition +
+
+
+
+ +
+
+
+
+ D1: + + behavior_determination.obstacle_velocity_threshold_from_stop_to_cruise +
+
+
+
+ D2: + + behavior_determination.stop_obstacle_hold_time_threshold +
+
+
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + +
+
+
+ Time to approach +
+ ego's + trajectory < A2? +
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + +
+
+
+ Should maintain stop? +
+
+
+ Transient obstacle? +
+
+
+
Collision predicted?
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
Obstacle velocity < D1 AND elapsed time since last stop decision < D2
+
+
Time to reach collision point > B3 OR collision not predicted at the time of reaching collision point
+
+
+
+
At least 1 vehicle footprint polygon at each point on trajectory intersects object footprint polygon
+
+
+
+
+ +
+
+
+
+
+ + + + + + +
+
+
+
diff --git a/planning/autoware_obstacle_cruise_planner/media/cruise_planning_block_diagram.drawio.svg b/planning/autoware_obstacle_cruise_planner/media/cruise_planning_block_diagram.drawio.svg new file mode 100644 index 0000000000000..c6b29be2b1096 --- /dev/null +++ b/planning/autoware_obstacle_cruise_planner/media/cruise_planning_block_diagram.drawio.svg @@ -0,0 +1,989 @@ + + + + + + + + + + + + + + + + + + + +
+
+
+ Obstacle velocity +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ Obstacle acceleration +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Ego velocity / acceleration +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Actual distance to obstacle +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+
Normalize
+
&
+ LPF +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ PID +
&
+
suppress output
+
when accelerating
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Ideal distance to obstacle +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Distance error +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Normalized distance error +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Target acceleration +
+
+
+
+ +
+
+
+
+ + + + + + + + + + +
+
+
+
RSS
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ +
+
+
+
+
+ + + + + + + + + + + + + + + + + + + + +
+
+
+ Actual distance to obstacle +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + +
+
+
+ + +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ - +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ LPF +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ Square +
(preserve sign)
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Squared distance error +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ Trajectory +
+
+
+
+ +
+
+
+
+
+
+
+
From 219b8ca4af34d99262cd29c4baf090f8d70f3808 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Mon, 16 Dec 2024 17:50:01 +0900 Subject: [PATCH 028/334] fix(autoware_radar_tracks_msgs_converter): fix bugprone-reserved-identifier (#9658) fix: bugprone-error Signed-off-by: kobayu858 --- .../src/radar_tracks_msgs_converter_node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/autoware_radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node.cpp b/perception/autoware_radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node.cpp index 005138623427e..0e06541f90af1 100644 --- a/perception/autoware_radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node.cpp +++ b/perception/autoware_radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node.cpp @@ -34,7 +34,6 @@ using namespace std::literals; using std::chrono::duration; using std::chrono::duration_cast; using std::chrono::nanoseconds; -using std::placeholders::_1; namespace { @@ -73,6 +72,7 @@ enum class RadarTrackObjectID { RadarTracksMsgsConverterNode::RadarTracksMsgsConverterNode(const rclcpp::NodeOptions & node_options) : Node("radar_tracks_msgs_converter", node_options) { + using std::placeholders::_1; // Parameter Server set_param_res_ = this->add_on_set_parameters_callback( std::bind(&RadarTracksMsgsConverterNode::onSetParam, this, _1)); From e808fdc0a565e80161c03f36489822bda3478e8c Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Mon, 16 Dec 2024 19:32:40 +0900 Subject: [PATCH 029/334] feat(pid_longitudinal_controller): update trajectory_adaptive; add debug_values, adopt rate limit fillter (#9656) Signed-off-by: yuki-takagi-66 --- .../debug_values.hpp | 6 +++-- .../pid_longitudinal_controller.hpp | 12 ++++++---- .../src/pid_longitudinal_controller.cpp | 23 ++++++++++++++----- 3 files changed, 29 insertions(+), 12 deletions(-) diff --git a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/debug_values.hpp b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/debug_values.hpp index a0bceda625b21..84f2c76815a3a 100644 --- a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/debug_values.hpp +++ b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/debug_values.hpp @@ -34,9 +34,9 @@ class DebugValues NEAREST_VEL = 4, NEAREST_ACC = 5, SHIFT = 6, - PITCH_LPF_RAD = 7, + PITCH_USING_RAD = 7, PITCH_RAW_RAD = 8, - PITCH_LPF_DEG = 9, + PITCH_USING_DEG = 9, PITCH_RAW_DEG = 10, ERROR_VEL = 11, ERROR_VEL_FILTERED = 12, @@ -61,6 +61,8 @@ class DebugValues ERROR_ACC = 31, ERROR_ACC_FILTERED = 32, ACC_CMD_ACC_FB_APPLIED = 33, + PITCH_LPF_RAD = 34, + PITCH_LPF_DEG = 35, SIZE // this is the number of enum elements }; diff --git a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp index 7daf3013bab4a..8c78b2b871fda 100644 --- a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp +++ b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp @@ -216,6 +216,7 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro std::shared_ptr m_lpf_pitch{nullptr}; double m_max_pitch_rad; double m_min_pitch_rad; + std::optional m_previous_slope_angle{std::nullopt}; // ego nearest index search double m_ego_nearest_dist_threshold; @@ -411,11 +412,14 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro /** * @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) + * @param [in] pitch_using + * @param [in] traj_pitch + * @param [in] localization_pitch + * @param [in] localization_pitch_lpf */ - void updatePitchDebugValues(const double pitch, const double traj_pitch, const double raw_pitch); + void updatePitchDebugValues( + const double pitch_using, const double traj_pitch, const double localization_pitch, + const double localization_pitch_lpf); /** * @brief update variables for velocity and acceleration diff --git a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp index 7f6da35527290..6057408674744 100644 --- a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp +++ b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp @@ -584,13 +584,21 @@ PidLongitudinalController::ControlData PidLongitudinalController::getControlData } else { control_data.slope_angle = m_lpf_pitch->filter(raw_pitch); } + if (m_previous_slope_angle.has_value()) { + constexpr double gravity_const = 9.8; + control_data.slope_angle = std::clamp( + control_data.slope_angle, + m_previous_slope_angle.value() + m_min_jerk * control_data.dt / gravity_const, + m_previous_slope_angle.value() + m_max_jerk * control_data.dt / gravity_const); + } } else { RCLCPP_ERROR_THROTTLE( logger_, *clock_, 3000, "Slope source is not valid. Using raw_pitch option as default"); control_data.slope_angle = m_lpf_pitch->filter(raw_pitch); } - updatePitchDebugValues(control_data.slope_angle, traj_pitch, raw_pitch); + m_previous_slope_angle = control_data.slope_angle; + updatePitchDebugValues(control_data.slope_angle, traj_pitch, raw_pitch, m_lpf_pitch->getValue()); return control_data; } @@ -1189,13 +1197,16 @@ double PidLongitudinalController::applyVelocityFeedback(const ControlData & cont } void PidLongitudinalController::updatePitchDebugValues( - const double pitch, const double traj_pitch, const double raw_pitch) + const double pitch_using, const double traj_pitch, const double localization_pitch, + const double localization_pitch_lpf) { const double to_degrees = (180.0 / static_cast(M_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_USING_RAD, pitch_using); + m_debug_values.setValues(DebugValues::TYPE::PITCH_USING_DEG, pitch_using * to_degrees); + m_debug_values.setValues(DebugValues::TYPE::PITCH_LPF_RAD, localization_pitch_lpf); + m_debug_values.setValues(DebugValues::TYPE::PITCH_LPF_DEG, localization_pitch_lpf * to_degrees); + m_debug_values.setValues(DebugValues::TYPE::PITCH_RAW_RAD, localization_pitch); + m_debug_values.setValues(DebugValues::TYPE::PITCH_RAW_DEG, localization_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); } From c7ecf7adc03917498a0ea4836981656a2aef9994 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Mon, 16 Dec 2024 13:14:49 +0000 Subject: [PATCH 030/334] chore: sync files (#9602) Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> Co-authored-by: github-actions --- .github/dependabot.yaml | 3 ++- .github/workflows/deploy-docs.yaml | 2 +- .github/workflows/pre-commit-autoupdate.yaml | 2 +- .github/workflows/pre-commit-optional-autoupdate.yaml | 2 +- .pre-commit-config-optional.yaml | 2 +- .pre-commit-config.yaml | 4 ++++ 6 files changed, 10 insertions(+), 5 deletions(-) diff --git a/.github/dependabot.yaml b/.github/dependabot.yaml index 8fd9b7f4ae0a5..8e2d7193aed5d 100644 --- a/.github/dependabot.yaml +++ b/.github/dependabot.yaml @@ -6,8 +6,9 @@ version: 2 updates: - package-ecosystem: github-actions directory: / + # https://docs.github.com/en/code-security/dependabot/dependabot-version-updates/configuration-options-for-the-dependabot.yml-file#scheduleinterval schedule: - interval: daily + interval: monthly open-pull-requests-limit: 1 labels: - tag:bot diff --git a/.github/workflows/deploy-docs.yaml b/.github/workflows/deploy-docs.yaml index d39e97e540794..47009a25e69fd 100644 --- a/.github/workflows/deploy-docs.yaml +++ b/.github/workflows/deploy-docs.yaml @@ -26,7 +26,7 @@ jobs: prevent-no-label-execution: uses: autowarefoundation/autoware-github-actions/.github/workflows/prevent-no-label-execution.yaml@v1 with: - label: tag:deploy-docs + label: run:deploy-docs deploy-docs: needs: prevent-no-label-execution diff --git a/.github/workflows/pre-commit-autoupdate.yaml b/.github/workflows/pre-commit-autoupdate.yaml index 489e32a1de166..60c17d9dabf72 100644 --- a/.github/workflows/pre-commit-autoupdate.yaml +++ b/.github/workflows/pre-commit-autoupdate.yaml @@ -6,7 +6,7 @@ name: pre-commit-autoupdate on: schedule: - - cron: 0 0 * * * + - cron: 0 0 1 1,4,7,10 * # quarterly workflow_dispatch: jobs: diff --git a/.github/workflows/pre-commit-optional-autoupdate.yaml b/.github/workflows/pre-commit-optional-autoupdate.yaml index be79ad481d16e..6639e5ca6c61a 100644 --- a/.github/workflows/pre-commit-optional-autoupdate.yaml +++ b/.github/workflows/pre-commit-optional-autoupdate.yaml @@ -6,7 +6,7 @@ name: pre-commit-optional-autoupdate on: schedule: - - cron: 0 0 * * * + - cron: 0 0 1 1,4,7,10 * # quarterly workflow_dispatch: jobs: diff --git a/.pre-commit-config-optional.yaml b/.pre-commit-config-optional.yaml index ff325af5e8774..56000d93a8af5 100644 --- a/.pre-commit-config-optional.yaml +++ b/.pre-commit-config-optional.yaml @@ -4,7 +4,7 @@ repos: - repo: https://github.com/tcort/markdown-link-check - rev: v3.12.2 + rev: v3.13.6 hooks: - id: markdown-link-check args: [--quiet, --config=.markdown-link-check.json] diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 6e7c64fd982fc..a87ad293fd933 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -2,8 +2,12 @@ # https://github.com/autowarefoundation/sync-file-templates # To make changes, update the source repository and follow the guidelines in its README. +# https://pre-commit.ci/#configuration ci: autofix_commit_msg: "style(pre-commit): autofix" + # we already have our own daily update mechanism, we set this to quarterly + autoupdate_schedule: quarterly + autoupdate_commit_msg: "ci(pre-commit): quarterly autoupdate" repos: - repo: https://github.com/pre-commit/pre-commit-hooks From a37eca41e64f9b88bd69140ff316eb0399173312 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Mon, 16 Dec 2024 16:41:58 +0300 Subject: [PATCH 031/334] chore: update CODEOWNERS (#9623) Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> Co-authored-by: github-actions --- .github/CODEOWNERS | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 7403da173eb13..cda3c8ceaca89 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -140,7 +140,7 @@ planning/autoware_obstacle_cruise_planner/** berkay@leodrive.ai kosuke.takeuchi@ planning/autoware_obstacle_stop_planner/** berkay@leodrive.ai bnk@leodrive.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp planning/autoware_path_optimizer/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp planning/autoware_path_smoother/** maxime.clement@tier4.jp takayuki.murooka@tier4.jp -planning/autoware_planning_test_manager/** kyoichi.sugahara@tier4.jp takamasa.horibe@tier4.jp +planning/autoware_planning_test_manager/** kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp planning/autoware_planning_topic_converter/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp planning/autoware_planning_validator/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp planning/autoware_remaining_distance_time_calculator/** ahmed.ebrahim@leodrive.ai From d99caf9a5474fa53968d6598d0034215409bb97b Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Mon, 16 Dec 2024 13:57:03 +0000 Subject: [PATCH 032/334] chore: sync files (#9665) Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> Co-authored-by: github-actions --- .pre-commit-config.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index a87ad293fd933..48a97c13ef958 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -74,7 +74,7 @@ repos: args: [--line-length=100] - repo: https://github.com/pre-commit/mirrors-clang-format - rev: v19.1.4 + rev: v19.1.5 hooks: - id: clang-format types_or: [c++, c, cuda] From b9ebc42a6c3ce63030fdf8f5d59fa232c9ecad2c Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Tue, 17 Dec 2024 10:19:55 +0900 Subject: [PATCH 033/334] feat(autoware_test_utils): add visualization (#9603) Signed-off-by: Mamoru Sobue --- common/autoware_pyplot/CMakeLists.txt | 4 + .../autoware_test_utils/visualization.hpp | 229 ++++++++++++++++++ common/autoware_test_utils/package.xml | 1 + 3 files changed, 234 insertions(+) create mode 100644 common/autoware_test_utils/include/autoware_test_utils/visualization.hpp diff --git a/common/autoware_pyplot/CMakeLists.txt b/common/autoware_pyplot/CMakeLists.txt index 6922d5d9306f7..5871929676a2d 100644 --- a/common/autoware_pyplot/CMakeLists.txt +++ b/common/autoware_pyplot/CMakeLists.txt @@ -15,8 +15,12 @@ autoware_package() ament_auto_add_library(${PROJECT_NAME} STATIC DIRECTORY src ) +target_compile_options(${PROJECT_NAME} PUBLIC "-fPIC") target_link_libraries(${PROJECT_NAME} ${Python3_LIBRARIES} pybind11::embed) +# NOTE(soblin): this is workaround for propagating the include of "Python.h" to user modules to avoid "'Python.h' not found" +ament_export_include_directories(${Python3_INCLUDE_DIRS}) + if(BUILD_TESTING) find_package(ament_cmake_ros REQUIRED) diff --git a/common/autoware_test_utils/include/autoware_test_utils/visualization.hpp b/common/autoware_test_utils/include/autoware_test_utils/visualization.hpp new file mode 100644 index 0000000000000..c2185e65422e8 --- /dev/null +++ b/common/autoware_test_utils/include/autoware_test_utils/visualization.hpp @@ -0,0 +1,229 @@ +// Copyright 2024 TIER IV +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +// NOTE(soblin): this file is intentionally inline to deal with link issue + +#ifndef AUTOWARE_TEST_UTILS__VISUALIZATION_HPP_ +#define AUTOWARE_TEST_UTILS__VISUALIZATION_HPP_ + +#include +#include + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +namespace autoware::test_utils +{ + +struct PointConfig +{ + std::optional color{}; + std::optional marker{}; + std::optional marker_size{}; +}; + +struct LineConfig +{ + static constexpr const char * default_color = "blue"; + static LineConfig defaults() + { + return LineConfig{std::string(default_color), 1.0, "solid", std::nullopt}; + } + std::optional color{}; + std::optional linewidth{}; + std::optional linestyle{}; + std::optional label{}; +}; + +struct LaneConfig +{ + static LaneConfig defaults() { return LaneConfig{std::nullopt, LineConfig::defaults(), true}; } + + std::optional label{}; + std::optional line_config{}; + bool plot_centerline = true; // alpha{}; + std::optional color{}; + bool fill{true}; + std::optional linewidth{}; + std::optional point_config{}; +}; + +/** + * @brief plot the linestring by `axes.plot()` + * @param [in] config_opt argument for plotting the linestring. if valid, each field is used as the + * kwargs + */ +inline void plot_lanelet2_object( + const lanelet::ConstLineString3d & line, autoware::pyplot::Axes & axes, + const std::optional & config_opt = std::nullopt) +{ + py::dict kwargs{}; + if (config_opt) { + const auto & config = config_opt.value(); + if (config.color) { + kwargs["color"] = config.color.value(); + } + if (config.linewidth) { + kwargs["linewidth"] = config.linewidth.value(); + } + if (config.linestyle) { + kwargs["linestyle"] = config.linestyle.value(); + } + if (config.label) { + kwargs["label"] = config.label.value(); + } + } + std::vector xs; + for (const auto & p : line) { + xs.emplace_back(p.x()); + } + std::vector ys; + for (const auto & p : line) { + ys.emplace_back(p.y()); + } + axes.plot(Args(xs, ys), kwargs); +} + +/** + * @brief plot the left/right bounds and optionally centerline + * @param [in] args used for plotting the left/right bounds as + */ +inline void plot_lanelet2_object( + const lanelet::ConstLanelet & lanelet, autoware::pyplot::Axes & axes, + const std::optional & config_opt = std::nullopt) +{ + const auto left = lanelet.leftBound(); + const auto right = lanelet.rightBound(); + + const auto line_config = [&]() -> std::optional { + if (!config_opt) { + return LineConfig{std::string(LineConfig::default_color)}; + } + return config_opt.value().line_config; + }(); + + if (config_opt) { + const auto & config = config_opt.value(); + + // plot lanelet centerline + if (config.plot_centerline) { + auto centerline_config = [&]() -> LineConfig { + if (!config.line_config) { + return LineConfig{"k", std::nullopt, "dashed"}; + } + auto cfg = config.line_config.value(); + cfg.color = "k"; + cfg.linestyle = "dashed"; + return cfg; + }(); + plot_lanelet2_object( + lanelet.centerline(), axes, std::make_optional(std::move(centerline_config))); + } + + // plot lanelet-id + const auto center = (left.front().basicPoint2d() + left.back().basicPoint2d() + + right.front().basicPoint2d() + right.back().basicPoint2d()) / + 4.0; + axes.text(Args(center.x(), center.y(), std::to_string(lanelet.id()))); + } + + if (config_opt && config_opt.value().label) { + auto left_line_config_for_legend = line_config ? line_config.value() : LineConfig::defaults(); + left_line_config_for_legend.label = config_opt.value().label.value(); + + // plot left + plot_lanelet2_object(lanelet.leftBound(), axes, left_line_config_for_legend); + + // plot right + plot_lanelet2_object(lanelet.rightBound(), axes, line_config); + } else { + // plot left + plot_lanelet2_object(lanelet.leftBound(), axes, line_config); + + // plot right + plot_lanelet2_object(lanelet.rightBound(), axes, line_config); + } + + // plot centerline direction + const auto centerline_size = lanelet.centerline().size(); + const auto mid_index = centerline_size / 2; + const auto before = static_cast(std::max(0, mid_index - 1)); + const auto after = static_cast(std::min(centerline_size - 1, mid_index + 1)); + const auto p_before = lanelet.centerline()[before]; + const auto p_after = lanelet.centerline()[after]; + const double azimuth = std::atan2(p_after.y() - p_before.y(), p_after.x() - p_before.x()); + const auto & mid = lanelet.centerline()[mid_index]; + axes.quiver( + Args(mid.x(), mid.y(), std::cos(azimuth), std::sin(azimuth)), Kwargs("units"_a = "width")); +} + +/** + * @brief plot the polygon as matplotlib.patches.Polygon + * @param [in] config_opt argument for plotting the polygon. if valid, each field is used as the + * kwargs + */ +inline void plot_lanelet2_object( + const lanelet::ConstPolygon3d & polygon, autoware::pyplot::Axes & axes, + const std::optional & config_opt = std::nullopt) +{ + std::vector> xy(polygon.size()); + for (unsigned i = 0; i < polygon.size(); ++i) { + xy.at(i) = std::vector({polygon[i].x(), polygon[i].y()}); + } + py::dict kwargs; + if (config_opt) { + const auto & config = config_opt.value(); + if (config.alpha) { + kwargs["alpha"] = config.alpha.value(); + } + if (config.color) { + kwargs["color"] = config.color.value(); + } + kwargs["fill"] = config.fill; + if (config.linewidth) { + kwargs["linewidth"] = config.linewidth.value(); + } + } + auto poly = autoware::pyplot::Polygon(Args(xy), kwargs); + axes.add_patch(Args(poly.unwrap())); +} + +/** + * @brief plot the point by `axes.plot()` + * @param [in] config_opt argument for plotting the point. if valid, each field is used as the + * kwargs + */ +/* +void plot_lanelet2_point( +const lanelet::ConstPoint3d & point, autoware::pyplot::Axes & axes, +const std::optional & config_opt = std::nullopt); +*/ +} // namespace autoware::test_utils + +#endif // AUTOWARE_TEST_UTILS__VISUALIZATION_HPP_ diff --git a/common/autoware_test_utils/package.xml b/common/autoware_test_utils/package.xml index 22572abb72b69..c328f37ba357d 100644 --- a/common/autoware_test_utils/package.xml +++ b/common/autoware_test_utils/package.xml @@ -23,6 +23,7 @@ autoware_map_msgs autoware_perception_msgs autoware_planning_msgs + autoware_pyplot autoware_universe_utils autoware_vehicle_msgs lanelet2_io From a98bb83b943c6cb26485969d118be509c8104347 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Tue, 17 Dec 2024 10:20:07 +0900 Subject: [PATCH 034/334] chore(autoware_test_utils): update test map (#9664) Signed-off-by: Mamoru Sobue --- .../test_map/road_shoulder/lanelet2_map.osm | 668 ++++-------------- .../test/test_util.cpp | 2 +- 2 files changed, 127 insertions(+), 543 deletions(-) diff --git a/common/autoware_test_utils/test_map/road_shoulder/lanelet2_map.osm b/common/autoware_test_utils/test_map/road_shoulder/lanelet2_map.osm index 09c6297f83752..2c86dad61875f 100644 --- a/common/autoware_test_utils/test_map/road_shoulder/lanelet2_map.osm +++ b/common/autoware_test_utils/test_map/road_shoulder/lanelet2_map.osm @@ -1,6 +1,6 @@ - + @@ -2336,31 +2336,6 @@ - - - - - - - - - - - - - - - - - - - - - - - - - @@ -2771,316 +2746,6 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - @@ -3831,41 +3496,6 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - @@ -47975,9 +47605,9 @@ - - - + + + @@ -48018,8 +47648,8 @@ - - + + @@ -48053,9 +47683,9 @@ - - - + + + @@ -48108,19 +47738,19 @@ - - - + + + - - - + + + - - - + + + @@ -48128,15 +47758,15 @@ - + - - + + - - - + + + @@ -48180,9 +47810,9 @@ - - - + + + @@ -48243,14 +47873,14 @@ - - - + + + - - - + + + @@ -48258,9 +47888,9 @@ - - - + + + @@ -48333,9 +47963,9 @@ - - - + + + @@ -48343,6 +47973,71 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -49132,99 +48827,6 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - @@ -49658,17 +49260,6 @@ - - - - - - - - - - - @@ -64187,15 +63778,6 @@ - - - - - - - - - @@ -64239,19 +63821,6 @@ - - - - - - - - - - - - - @@ -64330,6 +63899,22 @@ + + + + + + + + + + + + + + + + @@ -64478,7 +64063,7 @@ - + @@ -67744,15 +67329,14 @@ - - - - - - + + + + + diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/test/test_util.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/test/test_util.cpp index de231b78041b4..472adb2d57944 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/test/test_util.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/test/test_util.cpp @@ -92,7 +92,7 @@ TEST_F(TestUtilWithMap, getBusStopAreaPolygons) const auto shoulder_lanes = lanelet::utils::query::shoulderLanelets(lanes); const auto bus_stop_area_polygons = autoware::behavior_path_planner::goal_planner_utils::getBusStopAreaPolygons(shoulder_lanes); - EXPECT_EQ(bus_stop_area_polygons.size(), 1); + EXPECT_EQ(bus_stop_area_polygons.size(), 2); } TEST_F(DISABLED_TestUtilWithMap, isWithinAreas) From 91bfe5c3b8d2c694f306a8e4b03fefbd6279fc1a Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 17 Dec 2024 12:45:38 +0900 Subject: [PATCH 035/334] fix(autoware_shape_estimation): fix bugprone-branch-clone (#9659) * fix: bugprone-error Signed-off-by: kobayu858 * fix: fmt Signed-off-by: kobayu858 * fix: pre-commit Signed-off-by: kobayu858 * fix: pre-commit Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- perception/autoware_shape_estimation/lib/corrector/utils.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/autoware_shape_estimation/lib/corrector/utils.cpp b/perception/autoware_shape_estimation/lib/corrector/utils.cpp index 5e90c9d54f78a..678eb41c56831 100644 --- a/perception/autoware_shape_estimation/lib/corrector/utils.cpp +++ b/perception/autoware_shape_estimation/lib/corrector/utils.cpp @@ -163,7 +163,7 @@ bool correctWithDefaultValue( (param.min_width < (v_point.at(second_most_distant_index) * 2.0).norm() && (v_point.at(second_most_distant_index) * 2.0).norm() < param.max_width)) // both of edge is within width threshold - { + { // NOLINT correction_vector = v_point.at(first_most_distant_index); if (correction_vector.x() == 0.0) { correction_vector.y() = From c17b000ddd91920baa4c46eb49c7d09fa864387b Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 17 Dec 2024 12:45:59 +0900 Subject: [PATCH 036/334] fix(autoware_tracking_object_merger): fix bugprone-branch-clone (#9662) * fix: bugprone-error Signed-off-by: kobayu858 * fix: fmt Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../autoware_tracking_object_merger/src/utils/utils.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/perception/autoware_tracking_object_merger/src/utils/utils.cpp b/perception/autoware_tracking_object_merger/src/utils/utils.cpp index 15d130b4fcd50..2d7b930da9e66 100644 --- a/perception/autoware_tracking_object_merger/src/utils/utils.cpp +++ b/perception/autoware_tracking_object_merger/src/utils/utils.cpp @@ -98,10 +98,10 @@ TrackedObject linearInterpolationForTrackedObject( output_shape.dimensions.x = shape1.dimensions.x * (1 - weight) + shape2.dimensions.x * weight; output_shape.dimensions.y = shape1.dimensions.y * (1 - weight) + shape2.dimensions.y * weight; output_shape.dimensions.z = shape1.dimensions.z * (1 - weight) + shape2.dimensions.z * weight; - } else if (shape1.type == autoware_perception_msgs::msg::Shape::CYLINDER) { - // (TODO) implement - } else if (shape1.type == autoware_perception_msgs::msg::Shape::POLYGON) { - // (TODO) implement + } else if (shape1.type == autoware_perception_msgs::msg::Shape::CYLINDER) { // NOLINT + // (TODO) implement and remove NOLINT + } else if (shape1.type == autoware_perception_msgs::msg::Shape::POLYGON) { // NOLINT + // (TODO) implement and remove NOLINT } else { // when type is unknown, print warning and do nothing std::cerr << "unknown shape type in linearInterpolationForTrackedObject function." From 9de2af3ab4fbeefe76d33e61bfe14b8b478540e4 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 17 Dec 2024 13:23:43 +0900 Subject: [PATCH 037/334] fix(autoware_traffic_light_visualization): fix bugprone-branch-clone (#9668) fix: bugprone-error Signed-off-by: kobayu858 --- .../src/traffic_light_map_visualizer/node.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/perception/autoware_traffic_light_visualization/src/traffic_light_map_visualizer/node.cpp b/perception/autoware_traffic_light_visualization/src/traffic_light_map_visualizer/node.cpp index ccfaf37fd7c6d..f12eb656033b6 100644 --- a/perception/autoware_traffic_light_visualization/src/traffic_light_map_visualizer/node.cpp +++ b/perception/autoware_traffic_light_visualization/src/traffic_light_map_visualizer/node.cpp @@ -169,7 +169,7 @@ void TrafficLightMapVisualizerNode::trafficSignalsCallback( visualization_msgs::msg::Marker marker; if ( isAttributeValue(pt, "color", "red") && - elem.color == autoware_perception_msgs::msg::TrafficLightElement::RED) { + elem.color == autoware_perception_msgs::msg::TrafficLightElement::RED) { // NOLINT lightAsMarker( get_node_logging_interface(), pt, &marker, "traffic_light", current_time); } else if ( // NOLINT @@ -177,7 +177,6 @@ void TrafficLightMapVisualizerNode::trafficSignalsCallback( elem.color == autoware_perception_msgs::msg::TrafficLightElement::GREEN) { lightAsMarker( get_node_logging_interface(), pt, &marker, "traffic_light", current_time); - } else if ( // NOLINT isAttributeValue(pt, "color", "yellow") && elem.color == autoware_perception_msgs::msg::TrafficLightElement::AMBER) { From fc2b93e03072d789697a78aa955a10fd028fc97d Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 17 Dec 2024 13:39:43 +0900 Subject: [PATCH 038/334] fix(autoware_costmap_generator): fix bugprone-branch-clone (#9669) fix: bugprone-error Signed-off-by: kobayu858 --- .../src/utils/objects_to_costmap.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/autoware_costmap_generator/src/utils/objects_to_costmap.cpp b/planning/autoware_costmap_generator/src/utils/objects_to_costmap.cpp index 64f558b4f5604..6b1f4331f55ad 100644 --- a/planning/autoware_costmap_generator/src/utils/objects_to_costmap.cpp +++ b/planning/autoware_costmap_generator/src/utils/objects_to_costmap.cpp @@ -200,10 +200,10 @@ grid_map::Matrix ObjectsToCostmap::makeCostmapFromObjects( grid_map::Polygon polygon; if (object.shape.type == autoware_perception_msgs::msg::Shape::POLYGON) { polygon = makePolygonFromObjectConvexHull(in_objects->header, object, expand_polygon_size); - } else if (object.shape.type == autoware_perception_msgs::msg::Shape::BOUNDING_BOX) { + } else if (object.shape.type == autoware_perception_msgs::msg::Shape::BOUNDING_BOX) { // NOLINT polygon = makePolygonFromObjectBox(in_objects->header, object, expand_polygon_size); } else if (object.shape.type == autoware_perception_msgs::msg::Shape::CYLINDER) { - // TODO(Kenji Miyake): Add makePolygonFromObjectCylinder + // TODO(Kenji Miyake): Add makePolygonFromObjectCylinder and remove NOLINT polygon = makePolygonFromObjectBox(in_objects->header, object, expand_polygon_size); } const auto highest_probability_label = *std::max_element( From 178b6c003ae5f5c2838352f397df7a0bbea9e6bb Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Tue, 17 Dec 2024 14:31:05 +0900 Subject: [PATCH 039/334] feat(autoware_detected_object_validation): set validate distance in the obstacle pointcloud based validator (#9663) * chore: add validate_max_distance_m parameter for obstacle_pointcloud_based_validator Signed-off-by: Taekjin LEE * chore: optimize object distance validation in obstacle_pointcloud_validator Signed-off-by: Taekjin LEE * chore: add validate_max_distance_m parameter for obstacle_pointcloud_based_validator Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE --- .../obstacle_pointcloud_based_validator.param.yaml | 2 ++ ...obstacle_pointcloud_based_validator.schema.json | 5 +++++ .../obstacle_pointcloud_validator.cpp | 14 ++++++++++++++ .../obstacle_pointcloud_validator.hpp | 1 + 4 files changed, 22 insertions(+) diff --git a/perception/autoware_detected_object_validation/config/obstacle_pointcloud_based_validator.param.yaml b/perception/autoware_detected_object_validation/config/obstacle_pointcloud_based_validator.param.yaml index cddee782e8af0..37b77eb436c7d 100644 --- a/perception/autoware_detected_object_validation/config/obstacle_pointcloud_based_validator.param.yaml +++ b/perception/autoware_detected_object_validation/config/obstacle_pointcloud_based_validator.param.yaml @@ -12,5 +12,7 @@ #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN [800.0, 800.0, 800.0, 800.0, 800.0, 800.0, 800.0, 800.0] + validate_max_distance_m: 70.0 # [m] + using_2d_validator: false enable_debugger: false diff --git a/perception/autoware_detected_object_validation/schema/obstacle_pointcloud_based_validator.schema.json b/perception/autoware_detected_object_validation/schema/obstacle_pointcloud_based_validator.schema.json index d7aa970993ca1..95c83a90f075f 100644 --- a/perception/autoware_detected_object_validation/schema/obstacle_pointcloud_based_validator.schema.json +++ b/perception/autoware_detected_object_validation/schema/obstacle_pointcloud_based_validator.schema.json @@ -30,6 +30,11 @@ "default": [800, 800, 800, 800, 800, 800, 800, 800], "description": "Threshold value of the number of point clouds per object when the distance from baselink is 1m, because the number of point clouds varies with the distance from baselink." }, + "validate_max_distance_m": { + "type": "number", + "default": 70.0, + "description": "The maximum distance from the baselink to the object to be validated" + }, "using_2d_validator": { "type": "boolean", "default": false, diff --git a/perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp b/perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp index 194f333acd87e..979cdd3909f14 100644 --- a/perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp +++ b/perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp @@ -295,6 +295,8 @@ ObstaclePointCloudBasedValidator::ObstaclePointCloudBasedValidator( declare_parameter>("max_points_num"); points_num_threshold_param_.min_points_and_distance_ratio = declare_parameter>("min_points_and_distance_ratio"); + const double validate_max_distance = declare_parameter("validate_max_distance_m"); + validate_max_distance_sq_ = validate_max_distance * validate_max_distance; using_2d_validator_ = declare_parameter("using_2d_validator"); @@ -346,6 +348,18 @@ void ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud( for (size_t i = 0; i < transformed_objects.objects.size(); ++i) { const auto & transformed_object = transformed_objects.objects.at(i); const auto & object = input_objects->objects.at(i); + // check object distance + const double distance_sq = + transformed_object.kinematics.pose_with_covariance.pose.position.x * + transformed_object.kinematics.pose_with_covariance.pose.position.x + + transformed_object.kinematics.pose_with_covariance.pose.position.y * + transformed_object.kinematics.pose_with_covariance.pose.position.y; + if (distance_sq > validate_max_distance_sq_) { + // pass to output + output.objects.push_back(object); + continue; + } + const auto validated = validation_is_ready ? validator_->validate_object(transformed_object) : false; if (debugger_) { diff --git a/perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.hpp b/perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.hpp index 6d9a11634ea08..f10dbb7531d36 100644 --- a/perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.hpp +++ b/perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.hpp @@ -152,6 +152,7 @@ class ObstaclePointCloudBasedValidator : public rclcpp::Node typedef message_filters::Synchronizer Sync; Sync sync_; PointsNumThresholdParam points_num_threshold_param_; + double validate_max_distance_sq_; // maximum object distance to validate, squared [m^2] std::shared_ptr debugger_; bool using_2d_validator_; From 33190c620cbaed34970dd674cfdc92d4a8888872 Mon Sep 17 00:00:00 2001 From: Amadeusz Szymko Date: Tue, 17 Dec 2024 09:56:20 +0100 Subject: [PATCH 040/334] fix(dummy_infrastructure): schema file name (#8249) Signed-off-by: amadeuszsz --- ...tructure_node.schema.json => dummy_infrastructure.schema.json} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename system/dummy_infrastructure/schema/{dummy_infrastructure_node.schema.json => dummy_infrastructure.schema.json} (100%) diff --git a/system/dummy_infrastructure/schema/dummy_infrastructure_node.schema.json b/system/dummy_infrastructure/schema/dummy_infrastructure.schema.json similarity index 100% rename from system/dummy_infrastructure/schema/dummy_infrastructure_node.schema.json rename to system/dummy_infrastructure/schema/dummy_infrastructure.schema.json From f8ef146562c12f6063a31b08bc8f8455c14f4d2c Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 17 Dec 2024 22:08:28 +0900 Subject: [PATCH 041/334] feat(pid_longitudinal_controller): add smooth_stop mode in debug_values (#9681) Signed-off-by: Takayuki Murooka --- .../debug_values.hpp | 4 ++ .../smooth_stop.hpp | 6 ++- .../src/pid_longitudinal_controller.cpp | 2 +- .../src/smooth_stop.cpp | 10 +++- .../test/test_smooth_stop.cpp | 54 ++++++++++++------- 5 files changed, 54 insertions(+), 22 deletions(-) diff --git a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/debug_values.hpp b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/debug_values.hpp index 84f2c76815a3a..e1cc4d2fd1690 100644 --- a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/debug_values.hpp +++ b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/debug_values.hpp @@ -63,6 +63,7 @@ class DebugValues ACC_CMD_ACC_FB_APPLIED = 33, PITCH_LPF_RAD = 34, PITCH_LPF_DEG = 35, + SMOOTH_STOP_MODE = 36, SIZE // this is the number of enum elements }; @@ -78,6 +79,9 @@ class DebugValues * @return array of all debug values */ std::array(TYPE::SIZE)> getValues() const { return m_values; } + double getValue(const size_t index) const { return m_values.at(index); } + double getValue(const TYPE type) const { return m_values.at(static_cast(type)); } + /** * @brief set the given type to the given value * @param [in] type TYPE of the value diff --git a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/smooth_stop.hpp b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/smooth_stop.hpp index e84b44d95c886..8f8fc57e278ef 100644 --- a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/smooth_stop.hpp +++ b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/smooth_stop.hpp @@ -15,6 +15,7 @@ #ifndef AUTOWARE__PID_LONGITUDINAL_CONTROLLER__SMOOTH_STOP_HPP_ #define AUTOWARE__PID_LONGITUDINAL_CONTROLLER__SMOOTH_STOP_HPP_ +#include "autoware/pid_longitudinal_controller/debug_values.hpp" #include "rclcpp/rclcpp.hpp" #include // NOLINT @@ -85,7 +86,8 @@ class SmoothStop */ double calculate( const double stop_dist, const double current_vel, const double current_acc, - const std::vector> & vel_hist, const double delay_time); + const std::vector> & vel_hist, const double delay_time, + DebugValues & debug_values); private: struct Params @@ -106,6 +108,8 @@ class SmoothStop }; Params m_params; + enum class Mode { STRONG = 0, WEAK, WEAK_STOP, STRONG_STOP }; + double m_strong_acc; rclcpp::Time m_weak_acc_time; bool m_is_set_params = false; diff --git a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp index 6057408674744..4338b73ccef19 100644 --- a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp +++ b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp @@ -871,7 +871,7 @@ PidLongitudinalController::Motion PidLongitudinalController::calcCtrlCmd( } else if (m_control_state == ControlState::STOPPING) { raw_ctrl_cmd.acc = m_smooth_stop.calculate( control_data.stop_dist, control_data.current_motion.vel, control_data.current_motion.acc, - m_vel_hist, m_delay_compensation_time); + m_vel_hist, m_delay_compensation_time, m_debug_values); raw_ctrl_cmd.vel = m_stopped_state_params.vel; RCLCPP_DEBUG( diff --git a/control/autoware_pid_longitudinal_controller/src/smooth_stop.cpp b/control/autoware_pid_longitudinal_controller/src/smooth_stop.cpp index 9ee4763c6c05f..2dd2950d4356e 100644 --- a/control/autoware_pid_longitudinal_controller/src/smooth_stop.cpp +++ b/control/autoware_pid_longitudinal_controller/src/smooth_stop.cpp @@ -116,7 +116,8 @@ std::experimental::optional SmoothStop::calcTimeToStop( double SmoothStop::calculate( const double stop_dist, const double current_vel, const double current_acc, - const std::vector> & vel_hist, const double delay_time) + const std::vector> & vel_hist, const double delay_time, + DebugValues & debug_values) { if (!m_is_set_params) { throw std::runtime_error("Trying to calculate uninitialized SmoothStop"); @@ -132,8 +133,11 @@ double SmoothStop::calculate( // when exceeding the stopline (stop_dist is negative in these cases.) if (stop_dist < m_params.strong_stop_dist) { // when exceeding the stopline much + debug_values.setValues( + DebugValues::TYPE::SMOOTH_STOP_MODE, static_cast(Mode::STRONG_STOP)); return m_params.strong_stop_acc; } else if (stop_dist < m_params.weak_stop_dist) { // when exceeding the stopline a bit + debug_values.setValues(DebugValues::TYPE::SMOOTH_STOP_MODE, static_cast(Mode::WEAK_STOP)); return m_params.weak_stop_acc; } @@ -143,19 +147,23 @@ double SmoothStop::calculate( if ( (time_to_stop && *time_to_stop > m_params.weak_stop_time + delay_time) || (!time_to_stop && is_fast_vel)) { + debug_values.setValues(DebugValues::TYPE::SMOOTH_STOP_MODE, static_cast(Mode::STRONG)); return m_strong_acc; } m_weak_acc_time = rclcpp::Clock{RCL_ROS_TIME}.now(); + debug_values.setValues(DebugValues::TYPE::SMOOTH_STOP_MODE, static_cast(Mode::WEAK)); return m_params.weak_acc; } // for 0.5 seconds after the car stopped if ((rclcpp::Clock{RCL_ROS_TIME}.now() - m_weak_acc_time).seconds() < 0.5) { + debug_values.setValues(DebugValues::TYPE::SMOOTH_STOP_MODE, static_cast(Mode::WEAK)); return m_params.weak_acc; } // when the car is not running + debug_values.setValues(DebugValues::TYPE::SMOOTH_STOP_MODE, static_cast(Mode::STRONG_STOP)); return m_params.strong_stop_acc; } } // namespace autoware::motion::control::pid_longitudinal_controller diff --git a/control/autoware_pid_longitudinal_controller/test/test_smooth_stop.cpp b/control/autoware_pid_longitudinal_controller/test/test_smooth_stop.cpp index a6d03b8032fe6..30d582bbbf1ef 100644 --- a/control/autoware_pid_longitudinal_controller/test/test_smooth_stop.cpp +++ b/control/autoware_pid_longitudinal_controller/test/test_smooth_stop.cpp @@ -21,6 +21,7 @@ TEST(TestSmoothStop, calculate_stopping_acceleration) { + using ::autoware::motion::control::pid_longitudinal_controller::DebugValues; using ::autoware::motion::control::pid_longitudinal_controller::SmoothStop; using rclcpp::Duration; using rclcpp::Time; @@ -40,9 +41,10 @@ TEST(TestSmoothStop, calculate_stopping_acceleration) const double delay_time = 0.17; SmoothStop ss; + DebugValues debug_values; // Cannot calculate before setting parameters - EXPECT_THROW(ss.calculate(0.0, 0.0, 0.0, {}, delay_time), std::runtime_error); + EXPECT_THROW(ss.calculate(0.0, 0.0, 0.0, {}, delay_time, debug_values), std::runtime_error); ss.setParams( max_strong_acc, min_strong_acc, weak_acc, weak_stop_acc, strong_stop_acc, max_fast_vel, @@ -62,34 +64,45 @@ TEST(TestSmoothStop, calculate_stopping_acceleration) stop_dist = strong_stop_dist - 0.1; current_vel = 2.0; ss.init(vel_in_target, stop_dist); - accel = ss.calculate(stop_dist, current_vel, current_acc, velocity_history, delay_time); + accel = + ss.calculate(stop_dist, current_vel, current_acc, velocity_history, delay_time, debug_values); EXPECT_EQ(accel, strong_stop_acc); + EXPECT_EQ(debug_values.getValue(DebugValues::TYPE::SMOOTH_STOP_MODE), 3); // weak stop when the stop distance is below the threshold (but not bellow the strong_stop_dist) stop_dist = weak_stop_dist - 0.1; current_vel = 2.0; ss.init(vel_in_target, stop_dist); - accel = ss.calculate(stop_dist, current_vel, current_acc, velocity_history, delay_time); + accel = + ss.calculate(stop_dist, current_vel, current_acc, velocity_history, delay_time, debug_values); EXPECT_EQ(accel, weak_stop_acc); + EXPECT_EQ(debug_values.getValue(DebugValues::TYPE::SMOOTH_STOP_MODE), 2); // if not running, weak accel for 0.5 seconds after the previous init or previous weak_acc rclcpp::Rate rate_quart(1.0 / 0.25); rclcpp::Rate rate_half(1.0 / 0.5); stop_dist = 0.0; current_vel = 0.0; - EXPECT_EQ( - ss.calculate(stop_dist, current_vel, current_acc, velocity_history, delay_time), weak_acc); + accel = + ss.calculate(stop_dist, current_vel, current_acc, velocity_history, delay_time, debug_values); + EXPECT_EQ(accel, weak_acc); + EXPECT_EQ(debug_values.getValue(DebugValues::TYPE::SMOOTH_STOP_MODE), 1); rate_quart.sleep(); - EXPECT_EQ( - ss.calculate(stop_dist, current_vel, current_acc, velocity_history, delay_time), weak_acc); + accel = + ss.calculate(stop_dist, current_vel, current_acc, velocity_history, delay_time, debug_values); + EXPECT_EQ(accel, weak_acc); + EXPECT_EQ(debug_values.getValue(DebugValues::TYPE::SMOOTH_STOP_MODE), 1); rate_half.sleep(); - EXPECT_NE( - ss.calculate(stop_dist, current_vel, current_acc, velocity_history, delay_time), weak_acc); + accel = + ss.calculate(stop_dist, current_vel, current_acc, velocity_history, delay_time, debug_values); + EXPECT_NE(accel, weak_acc); + EXPECT_NE(debug_values.getValue(DebugValues::TYPE::SMOOTH_STOP_MODE), 1); // strong stop when the car is not running (and is at least 0.5seconds after initialization) - EXPECT_EQ( - ss.calculate(stop_dist, current_vel, current_acc, velocity_history, delay_time), - strong_stop_acc); + accel = + ss.calculate(stop_dist, current_vel, current_acc, velocity_history, delay_time, debug_values); + EXPECT_EQ(accel, strong_stop_acc); + EXPECT_EQ(debug_values.getValue(DebugValues::TYPE::SMOOTH_STOP_MODE), 3); // accel between min/max_strong_acc when the car is running: // not predicted to exceed the stop line and is predicted to stop after weak_stop_time + delay @@ -97,19 +110,22 @@ TEST(TestSmoothStop, calculate_stopping_acceleration) current_vel = 1.0; vel_in_target = 1.0; ss.init(vel_in_target, stop_dist); - EXPECT_EQ( - ss.calculate(stop_dist, current_vel, current_acc, velocity_history, delay_time), - max_strong_acc); + accel = + ss.calculate(stop_dist, current_vel, current_acc, velocity_history, delay_time, debug_values); + EXPECT_EQ(accel, max_strong_acc); + EXPECT_EQ(debug_values.getValue(DebugValues::TYPE::SMOOTH_STOP_MODE), 0); vel_in_target = std::sqrt(2.0); ss.init(vel_in_target, stop_dist); - EXPECT_EQ( - ss.calculate(stop_dist, current_vel, current_acc, velocity_history, delay_time), - min_strong_acc); + accel = + ss.calculate(stop_dist, current_vel, current_acc, velocity_history, delay_time, debug_values); + EXPECT_EQ(accel, min_strong_acc); + EXPECT_EQ(debug_values.getValue(DebugValues::TYPE::SMOOTH_STOP_MODE), 0); for (double vel_in_target = 1.1; vel_in_target < std::sqrt(2.0); vel_in_target += 0.1) { ss.init(vel_in_target, stop_dist); - accel = ss.calculate(stop_dist, current_vel, current_acc, velocity_history, delay_time); + accel = + ss.calculate(stop_dist, current_vel, current_acc, velocity_history, delay_time, debug_values); EXPECT_GT(accel, min_strong_acc); EXPECT_LT(accel, max_strong_acc); } From 6524f38d8037282795a4d1b563a14b67280e0fe9 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 18 Dec 2024 09:16:39 +0900 Subject: [PATCH 042/334] fix(autoware_probabilistic_occupancy_grid_map): fix bugprone-branch-clone (#9652) fix: bugprone-error Signed-off-by: kobayu858 --- .../lib/costmap_2d/occupancy_grid_map_fixed.cpp | 9 +++++---- .../lib/costmap_2d/occupancy_grid_map_projective.cpp | 9 +++++---- 2 files changed, 10 insertions(+), 8 deletions(-) diff --git a/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_fixed.cpp b/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_fixed.cpp index 518052a1a4b8c..da22ef125fb19 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_fixed.cpp +++ b/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_fixed.cpp @@ -144,10 +144,11 @@ void OccupancyGridMapFixedBlindSpot::updateWithPointCloud( transformPointAndCalculate(pt, pt_map, angle_bin_index, range); // Ignore obstacle points exceed the range of the raw points - if (raw_pointcloud_angle_bins.at(angle_bin_index).empty()) { - continue; // No raw point in this angle bin - } else if (range > raw_pointcloud_angle_bins.at(angle_bin_index).back().range) { - continue; // Obstacle point exceeds the range of the raw points + // No raw point in this angle bin, or obstacle point exceeds the range of the raw points + if ( + raw_pointcloud_angle_bins.at(angle_bin_index).empty() || + range > raw_pointcloud_angle_bins.at(angle_bin_index).back().range) { + continue; } obstacle_pointcloud_angle_bins.at(angle_bin_index).emplace_back(range, pt_map[0], pt_map[1]); } diff --git a/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_projective.cpp b/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_projective.cpp index dd934dea26c55..4f5b8b8eeabed 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_projective.cpp +++ b/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_projective.cpp @@ -153,10 +153,11 @@ void OccupancyGridMapProjectiveBlindSpot::updateWithPointCloud( const double dz = scan_z - obstacle_z; // Ignore obstacle points exceed the range of the raw points - if (raw_pointcloud_angle_bins.at(angle_bin_index).empty()) { - continue; // No raw point in this angle bin - } else if (range > raw_pointcloud_angle_bins.at(angle_bin_index).back().range) { - continue; // Obstacle point exceeds the range of the raw points + // No raw point in this angle bin, or obstacle point exceeds the range of the raw points + if ( + raw_pointcloud_angle_bins.at(angle_bin_index).empty() || + range > raw_pointcloud_angle_bins.at(angle_bin_index).back().range) { + continue; } if (dz > projection_dz_threshold_) { From 4c1153f85c3e3a44d87f0e0e6f89c56027dae656 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 18 Dec 2024 10:27:28 +0900 Subject: [PATCH 043/334] fix(autoware_ground_segmentation): fix bugprone-branch-clone (#9648) fix: bugprone-branch-clone Signed-off-by: kobayu858 --- .../src/scan_ground_filter/node.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/perception/autoware_ground_segmentation/src/scan_ground_filter/node.cpp b/perception/autoware_ground_segmentation/src/scan_ground_filter/node.cpp index 488de2da47f91..74b4edbe595ea 100644 --- a/perception/autoware_ground_segmentation/src/scan_ground_filter/node.cpp +++ b/perception/autoware_ground_segmentation/src/scan_ground_filter/node.cpp @@ -246,7 +246,7 @@ void ScanGroundFilterComponent::classifyPointCloud( float radius_distance_from_gnd = pd.radius - prev_gnd_radius; float height_from_gnd = point_curr.z - prev_gnd_point.z; float height_from_obj = point_curr.z - non_ground_cluster.getAverageHeight(); - bool calculate_slope = false; + bool calculate_slope = true; bool is_point_close_to_prev = (points_distance < (pd.radius * radial_divider_angle_rad_ + split_points_distance_tolerance_)); @@ -264,8 +264,6 @@ void ScanGroundFilterComponent::classifyPointCloud( // close to the previous point, set point follow label point_label_curr = PointLabel::POINT_FOLLOW; calculate_slope = false; - } else { - calculate_slope = true; } if (is_point_close_to_prev) { height_from_gnd = point_curr.z - ground_cluster.getAverageHeight(); From 3b56716f7504470574c1d14e2b8e5c6d4381549f Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Wed, 18 Dec 2024 18:43:24 +0900 Subject: [PATCH 044/334] fix: enable to copy all information in pickup based pointcloud downsampler (#9686) enable to copy all information in downsampler Signed-off-by: yoshiri --- .../pickup_based_voxel_grid_downsample_filter_node.cpp | 10 +--------- 1 file changed, 1 insertion(+), 9 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter_node.cpp index 10e2fa2511478..3d2bc0a206c94 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter_node.cpp @@ -124,15 +124,7 @@ void PickupBasedVoxelGridDownsampleFilterComponent::filter( size_t output_global_offset = 0; output.data.resize(voxel_map.size() * input->point_step); for (const auto & kv : voxel_map) { - std::memcpy( - &output.data[output_global_offset + x_offset], &input->data[kv.second + x_offset], - sizeof(float)); - std::memcpy( - &output.data[output_global_offset + y_offset], &input->data[kv.second + y_offset], - sizeof(float)); - std::memcpy( - &output.data[output_global_offset + z_offset], &input->data[kv.second + z_offset], - sizeof(float)); + std::memcpy(&output.data[output_global_offset], &input->data[kv.second], input->point_step); output_global_offset += input->point_step; } From f41ae016267ac05d6f36d0d84e8c48d6e3abeba0 Mon Sep 17 00:00:00 2001 From: Yuki Kimura <35513518+wakabame@users.noreply.github.com> Date: Wed, 18 Dec 2024 23:31:35 +0900 Subject: [PATCH 045/334] docs: modified minor sign error (#8140) Signed-off-by: wakabame --- .../model_predictive_control_algorithm.md | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/control/autoware_mpc_lateral_controller/model_predictive_control_algorithm.md b/control/autoware_mpc_lateral_controller/model_predictive_control_algorithm.md index a1116d8a11c74..f28869bf950fb 100644 --- a/control/autoware_mpc_lateral_controller/model_predictive_control_algorithm.md +++ b/control/autoware_mpc_lateral_controller/model_predictive_control_algorithm.md @@ -365,10 +365,10 @@ and aligning the inequality signs $$ \begin{align} -u_{1} - u_{0} &< \dot u_{max}\text{d}t \\\ + -u_{1} + u_{0} &< -\dot u_{min}\text{d}t \\\ -u_{2} - u_{1} &< \dot u_{max}\text{d}t \\\ + -u_{2} + u_{1} &< - \dot u_{min}\text{d}t +u_{1} - u_{0} &< \dot u_{max}\text{d}t \\\ +- u_{1} + u_{0} &< -\dot u_{min}\text{d}t \\\ +u_{2} - u_{1} &< \dot u_{max}\text{d}t \\\ +- u_{2} + u_{1} &< - \dot u_{min}\text{d}t \end{align} $$ From 351fabb4c62aa3ae08e2c4a827d0639abcc8a24f Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 19 Dec 2024 13:22:05 +0900 Subject: [PATCH 046/334] feat(pid_longitudinal_controller): remove trans/rot deviation validation since the control_validator has the same feature (#9675) * feat(pid_longitudinal_controller): remove trans/rot deviation validation since the control_validator has the same feature Signed-off-by: Takayuki Murooka * fix test Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- ...are_pid_longitudinal_controller.param.yaml | 2 - .../pid_longitudinal_controller.hpp | 9 --- ...udinalControllerStateTransition.drawio.svg | 6 +- ...re_pid_longitudinal_controller.schema.json | 12 ---- .../src/pid_longitudinal_controller.cpp | 57 ------------------- .../test/test_controller_node.cpp | 28 --------- 6 files changed, 1 insertion(+), 113 deletions(-) diff --git a/control/autoware_pid_longitudinal_controller/config/autoware_pid_longitudinal_controller.param.yaml b/control/autoware_pid_longitudinal_controller/config/autoware_pid_longitudinal_controller.param.yaml index 6d9b93ab98870..bd905cf9be0f1 100644 --- a/control/autoware_pid_longitudinal_controller/config/autoware_pid_longitudinal_controller.param.yaml +++ b/control/autoware_pid_longitudinal_controller/config/autoware_pid_longitudinal_controller.param.yaml @@ -16,8 +16,6 @@ stopped_state_entry_vel: 0.01 stopped_state_entry_acc: 0.1 emergency_state_overshoot_stop_dist: 1.5 - emergency_state_traj_trans_dev: 3.0 - emergency_state_traj_rot_dev: 0.7854 # drive state kp: 1.0 diff --git a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp index 8c78b2b871fda..1fe78852047c6 100644 --- a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp +++ b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp @@ -87,7 +87,6 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro struct ControlData { - bool is_far_from_trajectory{false}; autoware_planning_msgs::msg::Trajectory interpolated_traj{}; size_t nearest_idx{0}; // nearest_idx = 0 when nearest_idx is not found with findNearestIdx size_t target_idx{0}; @@ -162,8 +161,6 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro double stopped_state_entry_acc; // emergency double emergency_state_overshoot_stop_dist; - double emergency_state_traj_trans_dev; - double emergency_state_traj_rot_dev; }; StateTransitionParams m_state_transition_params; @@ -246,12 +243,6 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro // Diagnostic std::shared_ptr diag_updater_{}; // Diagnostic updater for publishing diagnostic data. - struct DiagnosticData - { - double trans_deviation{0.0}; // translation deviation between nearest point and current_pose - double rot_deviation{0.0}; // rotation deviation between nearest point and current_pose - }; - DiagnosticData m_diagnostic_data; void setupDiagnosticUpdater(); void checkControlState(diagnostic_updater::DiagnosticStatusWrapper & stat); diff --git a/control/autoware_pid_longitudinal_controller/media/LongitudinalControllerStateTransition.drawio.svg b/control/autoware_pid_longitudinal_controller/media/LongitudinalControllerStateTransition.drawio.svg index 88ac881f4f43c..f669b647dbf84 100644 --- a/control/autoware_pid_longitudinal_controller/media/LongitudinalControllerStateTransition.drawio.svg +++ b/control/autoware_pid_longitudinal_controller/media/LongitudinalControllerStateTransition.drawio.svg @@ -175,7 +175,7 @@ : For 500 [ms], self velocity is smaller than C1, and self acceleration is smaller than C2.
emergency condition - : Speed command is zero velocity, and distance to stop is smaller than D1, or self pose is not within D2, D3 from trajectory. + : Speed command is zero velocity, and distance to stop is smaller than D1.

@@ -315,10 +315,6 @@ C2 : stopped_state_entry_acc
D1 : emergency_state_overshoot_stop_dist -
- D2 : emergency_state_traj_trans_dev -
- D3 : emergency_state_traj_rot_dev

diff --git a/control/autoware_pid_longitudinal_controller/schema/autoware_pid_longitudinal_controller.schema.json b/control/autoware_pid_longitudinal_controller/schema/autoware_pid_longitudinal_controller.schema.json index ef1272582e52b..14a34f04458eb 100644 --- a/control/autoware_pid_longitudinal_controller/schema/autoware_pid_longitudinal_controller.schema.json +++ b/control/autoware_pid_longitudinal_controller/schema/autoware_pid_longitudinal_controller.schema.json @@ -71,16 +71,6 @@ "description": "If `enable_overshoot_emergency` is true and the ego is `emergency_state_overshoot_stop_dist`-meter ahead of the stop point, the state will transit to EMERGENCY. [m]", "default": "1.5" }, - "emergency_state_traj_trans_dev": { - "type": "number", - "description": "If the ego's position is `emergency_state_traj_trans_dev` meter away from the nearest trajectory point, the state will transit to EMERGENCY. [m]", - "default": "3.0" - }, - "emergency_state_traj_rot_dev": { - "type": "number", - "description": "If the ego's orientation is `emergency_state_traj_rot_dev` rad away from the nearest trajectory point orientation, the state will transit to EMERGENCY. [rad]", - "default": "0.7854" - }, "kp": { "type": "number", "description": "p gain for longitudinal control", @@ -326,8 +316,6 @@ "stopped_state_entry_vel", "stopped_state_entry_acc", "emergency_state_overshoot_stop_dist", - "emergency_state_traj_trans_dev", - "emergency_state_traj_rot_dev", "kp", "ki", "kd", diff --git a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp index 4338b73ccef19..54a5702f333a0 100644 --- a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp +++ b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp @@ -79,10 +79,6 @@ PidLongitudinalController::PidLongitudinalController( // 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 @@ -286,8 +282,6 @@ rcl_interfaces::msg::SetParametersResult PidLongitudinalController::paramCallbac 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 @@ -423,24 +417,6 @@ trajectory_follower::LongitudinalOutput PidLongitudinalController::run( const auto control_data = getControlData(current_pose); - // self pose is far from trajectory - if (control_data.is_far_from_trajectory) { - if (m_enable_large_tracking_error_emergency) { - // update control state - changeControlState(ControlState::EMERGENCY, "the tracking error is too large"); - } - 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 - trajectory_follower::LongitudinalOutput output; - output.control_cmd = cmd_msg; - output.control_cmd_horizon.controls.push_back(cmd_msg); - output.control_cmd_horizon.time_step_ms = 0.0; - return output; - } - // update control state updateControlState(control_data); @@ -491,23 +467,6 @@ PidLongitudinalController::ControlData PidLongitudinalController::getControlData const auto nearest_point = current_interpolated_pose.first; auto target_point = current_interpolated_pose.first; - // check if the deviation is worth emergency - m_diagnostic_data.trans_deviation = - autoware::universe_utils::calcDistance2d(current_interpolated_pose.first, current_pose); - const bool is_dist_deviation_large = - m_state_transition_params.emergency_state_traj_trans_dev < m_diagnostic_data.trans_deviation; - m_diagnostic_data.rot_deviation = std::abs(autoware::universe_utils::normalizeRadian( - tf2::getYaw(current_interpolated_pose.first.pose.orientation) - - tf2::getYaw(current_pose.orientation))); - const bool is_yaw_deviation_large = - m_state_transition_params.emergency_state_traj_rot_dev < m_diagnostic_data.rot_deviation; - - if (is_dist_deviation_large || is_yaw_deviation_large) { - // return here if nearest index is not found - control_data.is_far_from_trajectory = true; - return control_data; - } - // Delay compensation - Calculate the distance we got, predicted velocity and predicted // acceleration after delay control_data.state_after_delay = @@ -1250,23 +1209,7 @@ void PidLongitudinalController::checkControlState( msg = "emergency occurred due to "; } - if ( - m_state_transition_params.emergency_state_traj_trans_dev < m_diagnostic_data.trans_deviation) { - msg += "translation deviation"; - } - - if (m_state_transition_params.emergency_state_traj_rot_dev < m_diagnostic_data.rot_deviation) { - msg += "rotation deviation"; - } - stat.add("control_state", static_cast(m_control_state)); - stat.addf( - "translation deviation threshold", "%lf", - m_state_transition_params.emergency_state_traj_trans_dev); - stat.addf("translation deviation", "%lf", m_diagnostic_data.trans_deviation); - stat.addf( - "rotation deviation threshold", "%lf", m_state_transition_params.emergency_state_traj_rot_dev); - stat.addf("rotation deviation", "%lf", m_diagnostic_data.rot_deviation); stat.summary(level, msg); } diff --git a/control/autoware_trajectory_follower_node/test/test_controller_node.cpp b/control/autoware_trajectory_follower_node/test/test_controller_node.cpp index 0b1dac644a8ab..982af104538b5 100644 --- a/control/autoware_trajectory_follower_node/test/test_controller_node.cpp +++ b/control/autoware_trajectory_follower_node/test/test_controller_node.cpp @@ -510,34 +510,6 @@ TEST_F(FakeNodeFixture, longitudinal_reverse) EXPECT_GT(tester.cmd_msg->longitudinal.acceleration, 0.0f); } -TEST_F(FakeNodeFixture, longitudinal_emergency) -{ - const auto node_options = makeNodeOptions(); - ControllerTester tester(this, node_options); - - tester.send_default_transform(); - tester.publish_default_odom(); - tester.publish_autonomous_operation_mode(); - tester.publish_default_steer(); - tester.publish_default_acc(); - - // Publish trajectory starting away from the current ego pose - Trajectory traj; - traj.header.stamp = tester.node->now(); - traj.header.frame_id = "map"; - traj.points.push_back(make_traj_point(10.0, 0.0, 1.0f)); - traj.points.push_back(make_traj_point(50.0, 0.0, 1.0f)); - traj.points.push_back(make_traj_point(100.0, 0.0, 1.0f)); - tester.traj_pub->publish(traj); - - test_utils::waitForMessage(tester.node, this, tester.received_control_command); - - ASSERT_TRUE(tester.received_control_command); - // Emergencies (e.g., far from trajectory) produces braking command (0 vel, negative accel) - EXPECT_DOUBLE_EQ(tester.cmd_msg->longitudinal.velocity, 0.0f); - EXPECT_LT(tester.cmd_msg->longitudinal.acceleration, 0.0f); -} - TEST_F(FakeNodeFixture, longitudinal_not_check_steer_converged) { const auto node_options = makeNodeOptions(); From f87d7327169e9ec0b1d50de5038175688e102bd0 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 19 Dec 2024 13:23:47 +0900 Subject: [PATCH 047/334] feat(pid_longitudinal_controller): add virtual wall for dry steering and emergency (#9685) * feat(pid_longitudinal_controller): add virtual wall for dry steering and emergency Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../pid_longitudinal_controller.hpp | 7 ++--- .../src/pid_longitudinal_controller.cpp | 26 +++++++++++-------- 2 files changed, 17 insertions(+), 16 deletions(-) diff --git a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp index 1fe78852047c6..8796664947a5a 100644 --- a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp +++ b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp @@ -50,11 +50,8 @@ namespace autoware::motion::control::pid_longitudinal_controller { -using autoware::universe_utils::createDefaultMarker; -using autoware::universe_utils::createMarkerColor; -using autoware::universe_utils::createMarkerScale; using autoware_adapi_v1_msgs::msg::OperationModeState; -using visualization_msgs::msg::Marker; +using visualization_msgs::msg::MarkerArray; namespace trajectory_follower = ::autoware::motion::control::trajectory_follower; @@ -103,7 +100,7 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro // ros variables rclcpp::Publisher::SharedPtr m_pub_slope; rclcpp::Publisher::SharedPtr m_pub_debug; - rclcpp::Publisher::SharedPtr m_pub_stop_reason_marker; + rclcpp::Publisher::SharedPtr m_pub_virtual_wall_marker; rclcpp::Node::OnSetParametersCallbackHandle::SharedPtr m_set_param_res; rcl_interfaces::msg::SetParametersResult paramCallback( diff --git a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp index 54a5702f333a0..be969e5a4af10 100644 --- a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp +++ b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp @@ -14,6 +14,7 @@ #include "autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp" +#include "autoware/motion_utils/marker/marker_helper.hpp" #include "autoware/motion_utils/trajectory/trajectory.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" #include "autoware/universe_utils/math/normalization.hpp" @@ -215,7 +216,7 @@ PidLongitudinalController::PidLongitudinalController( "~/output/slope_angle", rclcpp::QoS{1}); m_pub_debug = node.create_publisher( "~/output/longitudinal_diagnostic", rclcpp::QoS{1}); - m_pub_stop_reason_marker = node.create_publisher("~/output/stop_reason", rclcpp::QoS{1}); + m_pub_virtual_wall_marker = node.create_publisher("~/virtual_wall", 1); // set parameter callback m_set_param_res = node.add_on_set_parameters_callback( @@ -521,8 +522,8 @@ PidLongitudinalController::ControlData PidLongitudinalController::getControlData // distance to stopline control_data.stop_dist = longitudinal_utils::calcStopDistance( - control_data.interpolated_traj.points.at(control_data.nearest_idx).pose, - control_data.interpolated_traj, m_ego_nearest_dist_threshold, m_ego_nearest_yaw_threshold); + current_pose, control_data.interpolated_traj, m_ego_nearest_dist_threshold, + m_ego_nearest_yaw_threshold); // pitch // NOTE: getPitchByTraj() calculates the pitch angle as defined in @@ -576,6 +577,11 @@ PidLongitudinalController::Motion PidLongitudinalController::calcEmergencyCtrlCm longitudinal_utils::applyDiffLimitFilter(raw_ctrl_cmd.acc, m_prev_raw_ctrl_cmd.acc, dt, p.jerk); m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_JERK_LIMITED, raw_ctrl_cmd.acc); + const auto virtual_wall_marker = autoware::motion_utils::createStopVirtualWallMarker( + m_current_kinematic_state.pose.pose, "velocity control\n (emergency)", clock_->now(), 0, + m_wheel_base + m_front_overhang); + m_pub_virtual_wall_marker->publish(virtual_wall_marker); + return raw_ctrl_cmd; } @@ -740,14 +746,12 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d } // publish debug marker - auto marker = createDefaultMarker( - "map", clock_->now(), "stop_reason", 0, Marker::TEXT_VIEW_FACING, - createMarkerScale(0.0, 0.0, 1.0), createMarkerColor(1.0, 1.0, 1.0, 0.999)); - marker.pose = autoware::universe_utils::calcOffsetPose( - m_current_kinematic_state.pose.pose, m_wheel_base + m_front_overhang, - m_vehicle_width / 2 + 2.0, 1.5); - marker.text = "steering not\nconverged"; - m_pub_stop_reason_marker->publish(marker); + if (is_under_control) { + const auto virtual_wall_marker = autoware::motion_utils::createStopVirtualWallMarker( + m_current_kinematic_state.pose.pose, "velocity control\n(steering not converged)", + clock_->now(), 0, m_wheel_base + m_front_overhang); + m_pub_virtual_wall_marker->publish(virtual_wall_marker); + } // keep STOPPED return; From eef298badcd9e7a2504f088729aa6b80bfc4f454 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 19 Dec 2024 13:25:00 +0900 Subject: [PATCH 048/334] feat(mpc_lateral_controller): remove trans/rot deviation validation since the control_validator has the same feature (#9684) Signed-off-by: Takayuki Murooka --- .../autoware_mpc_lateral_controller/README.md | 12 +++--- .../autoware/mpc_lateral_controller/mpc.hpp | 6 +-- .../lateral_controller_defaults.param.yaml | 2 - .../src/mpc.cpp | 11 ------ .../src/mpc_lateral_controller.cpp | 2 - .../test/test_mpc.cpp | 37 ------------------- 6 files changed, 7 insertions(+), 63 deletions(-) diff --git a/control/autoware_mpc_lateral_controller/README.md b/control/autoware_mpc_lateral_controller/README.md index 7585e7db140b3..a4b2fa3045a74 100644 --- a/control/autoware_mpc_lateral_controller/README.md +++ b/control/autoware_mpc_lateral_controller/README.md @@ -95,13 +95,11 @@ AutonomouStuff Lexus RX 450h for under 40 km/h driving. #### System -| Name | Type | Description | Default value | -| :------------------------ | :------ | :-------------------------------------------------------------------------- | :------------ | -| traj_resample_dist | double | distance of waypoints in resampling [m] | 0.1 | -| use_steer_prediction | boolean | flag for using steer prediction (do not use steer measurement) | false | -| admissible_position_error | double | stop vehicle when following position error is larger than this value [m] | 5.0 | -| admissible_yaw_error_rad | double | stop vehicle when following yaw angle error is larger than this value [rad] | 1.57 | -| use_delayed_initial_state | boolean | flag to use x0_delayed as initial state for predicted trajectory | true | +| Name | Type | Description | Default value | +| :------------------------ | :------ | :--------------------------------------------------------------- | :------------ | +| traj_resample_dist | double | distance of waypoints in resampling [m] | 0.1 | +| use_steer_prediction | boolean | flag for using steer prediction (do not use steer measurement) | false | +| use_delayed_initial_state | boolean | flag to use x0_delayed as initial state for predicted trajectory | true | #### Path Smoothing diff --git a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc.hpp b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc.hpp index 81c8b71683092..4c8d5df2c22a7 100644 --- a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc.hpp +++ b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc.hpp @@ -421,10 +421,8 @@ class MPC double m_raw_steer_cmd_prev = 0.0; // Previous MPC raw output. /* Parameters for control */ - double m_admissible_position_error; // Threshold for lateral error to trigger stop command [m]. - double m_admissible_yaw_error_rad; // Threshold for yaw error to trigger stop command [rad]. - double m_steer_lim; // Steering command limit [rad]. - double m_ctrl_period; // Control frequency [s]. + double m_steer_lim; // Steering command limit [rad]. + double m_ctrl_period; // Control frequency [s]. //!< @brief steering rate limit list depending on curvature [/m], [rad/s] std::vector> m_steer_rate_lim_map_by_curvature{}; diff --git a/control/autoware_mpc_lateral_controller/param/lateral_controller_defaults.param.yaml b/control/autoware_mpc_lateral_controller/param/lateral_controller_defaults.param.yaml index b358e95f86f99..1d30a28d05cb8 100644 --- a/control/autoware_mpc_lateral_controller/param/lateral_controller_defaults.param.yaml +++ b/control/autoware_mpc_lateral_controller/param/lateral_controller_defaults.param.yaml @@ -3,8 +3,6 @@ # -- system -- 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 - admissible_yaw_error_rad: 1.57 # stop mpc calculation when error is larger than the following value use_delayed_initial_state: true # flag to use x0_delayed as initial state for predicted trajectory # -- path smoothing -- diff --git a/control/autoware_mpc_lateral_controller/src/mpc.cpp b/control/autoware_mpc_lateral_controller/src/mpc.cpp index 4c3c8bec9b12e..49bf90b89bc90 100644 --- a/control/autoware_mpc_lateral_controller/src/mpc.cpp +++ b/control/autoware_mpc_lateral_controller/src/mpc.cpp @@ -307,17 +307,6 @@ std::pair MPC::getData( // get predicted steer data.predicted_steer = m_steering_predictor->calcSteerPrediction(); - // check error limit - const double dist_err = calcDistance2d(current_pose, data.nearest_pose); - if (dist_err > m_admissible_position_error) { - return {ResultWithReason{false, "too large position error"}, MPCData{}}; - } - - // check yaw error limit - if (std::fabs(data.yaw_err) > m_admissible_yaw_error_rad) { - return {ResultWithReason{false, "too large yaw error"}, MPCData{}}; - } - // check trajectory time length const double max_prediction_time = m_param.min_prediction_length / static_cast(m_param.prediction_horizon - 1); diff --git a/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp b/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp index 76e5b4737e418..11f4ab4fa233b 100644 --- a/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp +++ b/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp @@ -57,8 +57,6 @@ MpcLateralController::MpcLateralController( p_filt.traj_resample_dist = dp_double("traj_resample_dist"); p_filt.extend_trajectory_for_end_yaw_control = dp_bool("extend_trajectory_for_end_yaw_control"); - m_mpc->m_admissible_position_error = dp_double("admissible_position_error"); - m_mpc->m_admissible_yaw_error_rad = dp_double("admissible_yaw_error_rad"); m_mpc->m_use_steer_prediction = dp_bool("use_steer_prediction"); m_mpc->m_param.steer_tau = dp_double("vehicle_model_steer_tau"); diff --git a/control/autoware_mpc_lateral_controller/test/test_mpc.cpp b/control/autoware_mpc_lateral_controller/test/test_mpc.cpp index ccc91d0e7751b..9c30369305f6e 100644 --- a/control/autoware_mpc_lateral_controller/test/test_mpc.cpp +++ b/control/autoware_mpc_lateral_controller/test/test_mpc.cpp @@ -96,8 +96,6 @@ class MPCTest : public ::testing::Test double error_deriv_lpf_cutoff_hz = 5.0; // Test Parameters - double admissible_position_error = 5.0; - double admissible_yaw_error_rad = M_PI_2; double steer_lim = 0.610865; // 35 degrees double steer_rate_lim = 2.61799; // 150 degrees double ctrl_period = 0.03; @@ -162,8 +160,6 @@ class MPCTest : public ::testing::Test void initializeMPC(mpc_lateral_controller::MPC & mpc) { mpc.m_param = param; - mpc.m_admissible_position_error = admissible_position_error; - mpc.m_admissible_yaw_error_rad = admissible_yaw_error_rad; mpc.m_steer_lim = steer_lim; mpc.m_steer_rate_lim_map_by_curvature.emplace_back(0.0, steer_rate_lim); mpc.m_steer_rate_lim_map_by_velocity.emplace_back(0.0, steer_rate_lim); @@ -480,37 +476,4 @@ TEST_F(MPCTest, MultiSolveWithBuffer) EXPECT_EQ(ctrl_cmd_horizon.controls.front().steering_tire_angle, 0.0f); EXPECT_EQ(ctrl_cmd_horizon.controls.front().steering_tire_rotation_rate, 0.0f); } - -TEST_F(MPCTest, FailureCases) -{ - auto node = rclcpp::Node("mpc_test_node", rclcpp::NodeOptions{}); - auto mpc = std::make_unique(node); - std::shared_ptr vehicle_model_ptr = - std::make_shared(wheelbase, steer_limit, steer_tau); - mpc->setVehicleModel(vehicle_model_ptr); - std::shared_ptr qpsolver_ptr = std::make_shared(); - mpc->setQPSolver(qpsolver_ptr); - - // Init parameters and reference trajectory - initializeMPC(*mpc); - - // Calculate MPC with a pose too far from the trajectory - Pose pose_far; - pose_far.position.x = pose_zero.position.x - admissible_position_error - 1.0; - pose_far.position.y = pose_zero.position.y - admissible_position_error - 1.0; - Lateral ctrl_cmd; - Trajectory pred_traj; - Float32MultiArrayStamped diag; - LateralHorizon ctrl_cmd_horizon; - const auto odom = makeOdometry(pose_far, default_velocity); - EXPECT_FALSE( - mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon).result); - - // Calculate MPC with a fast velocity to make the prediction go further than the reference path - EXPECT_FALSE(mpc - ->calculateMPC( - neutral_steer, makeOdometry(pose_far, default_velocity + 10.0), ctrl_cmd, - pred_traj, diag, ctrl_cmd_horizon) - .result); -} } // namespace autoware::motion::control::mpc_lateral_controller From b0625af68899f8989a49e9e699001acccb8a8d0d Mon Sep 17 00:00:00 2001 From: Kazunori-Nakajima <169115284+Kazunori-Nakajima@users.noreply.github.com> Date: Thu, 19 Dec 2024 19:54:04 +0900 Subject: [PATCH 049/334] feat(planning_evaluator): add lateral trajectory displacement metrics (#9674) * feat(planning_evaluator): add nearest pose deviation msg Signed-off-by: Kasunori-Nakajima * update comment contents Signed-off-by: Kasunori-Nakajima * update variable name Signed-off-by: Kasunori-Nakajima * Revert "update variable name" This reverts commit ee427222fcbd2a18ffbc20fecca3ad557f527e37. Signed-off-by: Kasunori-Nakajima * move lateral_trajectory_displacement position Signed-off-by: Kasunori-Nakajima * prev.dist -> prev_lateral_deviation Signed-off-by: Kasunori-Nakajima --------- Signed-off-by: Kasunori-Nakajima --- .../config/planning_evaluator.param.yaml | 1 + .../metrics/deviation_metrics.hpp | 10 ++++++++++ .../planning_evaluator/metrics/metric.hpp | 4 ++++ .../autoware_planning_evaluator.schema.json | 1 + .../src/metrics/deviation_metrics.cpp | 18 ++++++++++++++++++ .../src/metrics_calculator.cpp | 2 ++ 6 files changed, 36 insertions(+) diff --git a/evaluator/autoware_planning_evaluator/config/planning_evaluator.param.yaml b/evaluator/autoware_planning_evaluator/config/planning_evaluator.param.yaml index 14c1bcc6beea4..e00851de63b9c 100644 --- a/evaluator/autoware_planning_evaluator/config/planning_evaluator.param.yaml +++ b/evaluator/autoware_planning_evaluator/config/planning_evaluator.param.yaml @@ -14,6 +14,7 @@ - lateral_deviation - yaw_deviation - velocity_deviation + - lateral_trajectory_displacement - stability - stability_frechet - obstacle_distance diff --git a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/deviation_metrics.hpp b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/deviation_metrics.hpp index 59866c96ad702..0e08398ffa87e 100644 --- a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/deviation_metrics.hpp +++ b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/deviation_metrics.hpp @@ -38,6 +38,16 @@ using geometry_msgs::msg::Pose; */ Accumulator calcLateralDeviation(const Trajectory & ref, const Trajectory & traj); +/** + * @brief calculate lateral trajectory displacement from the previous trajectory and the trajectory + * @param [in] prev previous trajectory + * @param [in] traj input trajectory + * @param [in] base_pose base pose + * @return calculated statistics + */ +Accumulator calcLateralTrajectoryDisplacement( + const Trajectory & prev, const Trajectory & traj, const Pose & base_pose); + /** * @brief calculate yaw deviation of the given trajectory from the reference trajectory * @param [in] ref reference trajectory diff --git a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/metric.hpp b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/metric.hpp index c0313ed0727dd..13dad65b239b1 100644 --- a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/metric.hpp +++ b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/metric.hpp @@ -37,6 +37,7 @@ enum class Metric { lateral_deviation, yaw_deviation, velocity_deviation, + lateral_trajectory_displacement, stability, stability_frechet, obstacle_distance, @@ -62,6 +63,7 @@ static const std::unordered_map str_to_metric = { {"lateral_deviation", Metric::lateral_deviation}, {"yaw_deviation", Metric::yaw_deviation}, {"velocity_deviation", Metric::velocity_deviation}, + {"lateral_trajectory_displacement", Metric::lateral_trajectory_displacement}, {"stability", Metric::stability}, {"stability_frechet", Metric::stability_frechet}, {"obstacle_distance", Metric::obstacle_distance}, @@ -82,6 +84,7 @@ static const std::unordered_map metric_to_str = { {Metric::lateral_deviation, "lateral_deviation"}, {Metric::yaw_deviation, "yaw_deviation"}, {Metric::velocity_deviation, "velocity_deviation"}, + {Metric::lateral_trajectory_displacement, "lateral_trajectory_displacement"}, {Metric::stability, "stability"}, {Metric::stability_frechet, "stability_frechet"}, {Metric::obstacle_distance, "obstacle_distance"}, @@ -103,6 +106,7 @@ static const std::unordered_map metric_descriptions = { {Metric::lateral_deviation, "Lateral_deviation[m]"}, {Metric::yaw_deviation, "Yaw_deviation[rad]"}, {Metric::velocity_deviation, "Velocity_deviation[m/s]"}, + {Metric::lateral_trajectory_displacement, "Nearest Pose Lateral Deviation[m]"}, {Metric::stability, "Stability[m]"}, {Metric::stability_frechet, "StabilityFrechet[m]"}, {Metric::obstacle_distance, "Obstacle_distance[m]"}, diff --git a/evaluator/autoware_planning_evaluator/schema/autoware_planning_evaluator.schema.json b/evaluator/autoware_planning_evaluator/schema/autoware_planning_evaluator.schema.json index 1ef3874a0dcbc..263bd374a7e45 100644 --- a/evaluator/autoware_planning_evaluator/schema/autoware_planning_evaluator.schema.json +++ b/evaluator/autoware_planning_evaluator/schema/autoware_planning_evaluator.schema.json @@ -34,6 +34,7 @@ "lateral_deviation", "yaw_deviation", "velocity_deviation", + "lateral_trajectory_displacement", "stability", "stability_frechet", "obstacle_distance", diff --git a/evaluator/autoware_planning_evaluator/src/metrics/deviation_metrics.cpp b/evaluator/autoware_planning_evaluator/src/metrics/deviation_metrics.cpp index 7e2217a49ef87..ffb56baf29f17 100644 --- a/evaluator/autoware_planning_evaluator/src/metrics/deviation_metrics.cpp +++ b/evaluator/autoware_planning_evaluator/src/metrics/deviation_metrics.cpp @@ -45,6 +45,24 @@ Accumulator calcLateralDeviation(const Trajectory & ref, const Trajector return stat; } +Accumulator calcLateralTrajectoryDisplacement( + const Trajectory & prev, const Trajectory & traj, const Pose & ego_pose) +{ + Accumulator stat; + + if (prev.points.empty() || traj.points.empty()) { + return stat; + } + + const auto prev_lateral_deviation = + autoware::motion_utils::calcLateralOffset(prev.points, ego_pose.position); + const auto traj_lateral_deviation = + autoware::motion_utils::calcLateralOffset(traj.points, ego_pose.position); + const auto lateral_trajectory_displacement = traj_lateral_deviation - prev_lateral_deviation; + stat.add(lateral_trajectory_displacement); + return stat; +} + Accumulator calcYawDeviation(const Trajectory & ref, const Trajectory & traj) { Accumulator stat; diff --git a/evaluator/autoware_planning_evaluator/src/metrics_calculator.cpp b/evaluator/autoware_planning_evaluator/src/metrics_calculator.cpp index 6e057bcc9fc3d..b7676c2fdab6c 100644 --- a/evaluator/autoware_planning_evaluator/src/metrics_calculator.cpp +++ b/evaluator/autoware_planning_evaluator/src/metrics_calculator.cpp @@ -49,6 +49,8 @@ std::optional> MetricsCalculator::calculate( return metrics::calcYawDeviation(reference_trajectory_, traj); case Metric::velocity_deviation: return metrics::calcVelocityDeviation(reference_trajectory_, traj); + case Metric::lateral_trajectory_displacement: + return metrics::calcLateralTrajectoryDisplacement(previous_trajectory_, traj, ego_pose_); case Metric::stability_frechet: return metrics::calcFrechetDistance( getLookaheadTrajectory( From 00df6b94d3e6cbaff910c79c7bdb6cf32723c3da Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 19 Dec 2024 20:34:32 +0900 Subject: [PATCH 050/334] feat(behavior_velocity_planner): remove unnecessary tier4_api_msgs (#9692) Signed-off-by: Takayuki Murooka --- .../autoware_behavior_velocity_crosswalk_module/package.xml | 1 - .../autoware_behavior_velocity_crosswalk_module/src/manager.hpp | 1 - .../src/scene_crosswalk.hpp | 1 - .../src/manager.hpp | 1 - .../autoware_behavior_velocity_planner/package.xml | 1 - .../autoware_behavior_velocity_planner/src/node.hpp | 2 -- .../autoware/behavior_velocity_planner_common/planner_data.hpp | 2 -- .../autoware_behavior_velocity_planner_common/package.xml | 1 - 8 files changed, 10 deletions(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml index 6b939a7dd0be9..699f80ec8356e 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml @@ -41,7 +41,6 @@ pluginlib rclcpp sensor_msgs - tier4_api_msgs tier4_debug_msgs visualization_msgs diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.hpp index 693f6c27a380d..d6f6ddfb7b6ad 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.hpp @@ -23,7 +23,6 @@ #include #include -#include #include #include diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index 8577ed1669b48..9b771c0d503a4 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -57,7 +57,6 @@ using autoware_perception_msgs::msg::PredictedObject; using autoware_perception_msgs::msg::PredictedObjects; using autoware_perception_msgs::msg::TrafficLightElement; using lanelet::autoware::Crosswalk; -using tier4_api_msgs::msg::CrosswalkStatus; using tier4_planning_msgs::msg::PathWithLaneId; namespace diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.hpp index 8189cbe7bc5d7..80c87e55c6696 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.hpp @@ -24,7 +24,6 @@ #include #include -#include #include #include diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml index 8ba8272712364..e051374ed3dda 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml @@ -56,7 +56,6 @@ tf2_eigen tf2_geometry_msgs tf2_ros - tier4_api_msgs tier4_planning_msgs tier4_v2x_msgs visualization_msgs diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.hpp index e260f582aae60..4efb58e38b74f 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.hpp @@ -31,8 +31,6 @@ #include #include #include -#include -#include #include #include #include diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/planner_data.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/planner_data.hpp index 309ba33a3498a..983aaec2acf4f 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/planner_data.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/planner_data.hpp @@ -29,8 +29,6 @@ #include #include #include -#include -#include #include #include diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml index 77b26aac09161..6d94e20cfdb1b 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml @@ -44,7 +44,6 @@ tf2_eigen tf2_geometry_msgs tf2_ros - tier4_api_msgs tier4_planning_msgs tier4_v2x_msgs visualization_msgs From 3abb7bcde406869f684894e55bd42a7525e9848d Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 19 Dec 2024 21:51:18 +0900 Subject: [PATCH 051/334] feat: update autoware_internal_msgs version in build_depends.repos (#9695) feat: update autoware_internal_tools version in build_depends.repos Signed-off-by: Takayuki Murooka --- build_depends.repos | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/build_depends.repos b/build_depends.repos index 4db947b7c26a8..7e547be7409cf 100644 --- a/build_depends.repos +++ b/build_depends.repos @@ -32,7 +32,7 @@ repositories: core/autoware_internal_msgs: type: git url: https://github.com/autowarefoundation/autoware_internal_msgs.git - version: 1.1.0 + version: 1.2.0 # universe universe/external/tier4_autoware_msgs: type: git From 6ed5634bb53029f9a5cc4c039d3ab2ce1f00a826 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 19 Dec 2024 21:53:11 +0900 Subject: [PATCH 052/334] feat(motion_velocity_planner): remove unnecessary tier4_api_msgs and tier4_v2x_msgs (#9691) * feat(motion_velocity_planner): remove unnecessary tier4_api_msgs and tier4_v2x_msgs Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../planner_data.hpp | 4 ---- .../README.md | 21 +++++++++---------- .../launch/motion_velocity_planner.launch.xml | 1 - .../src/node.cpp | 3 --- .../src/node.hpp | 3 --- .../test/src/test_node_interface.cpp | 2 -- 6 files changed, 10 insertions(+), 24 deletions(-) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp index a96587c4465d6..a5f9badd9f4f7 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp @@ -31,10 +31,7 @@ #include #include #include -#include -#include #include -#include #include #include @@ -76,7 +73,6 @@ struct PlannerData std::map traffic_light_id_map_raw_; std::map traffic_light_id_map_last_observed_; std::optional external_velocity_limit; - tier4_v2x_msgs::msg::VirtualTrafficLightStateArray virtual_traffic_light_states; // velocity smoother std::shared_ptr velocity_smoother_; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/README.md b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/README.md index 494446828e134..01062f81e77a2 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/README.md +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/README.md @@ -17,17 +17,16 @@ This means that to stop before a wall, a stop point is inserted in the trajector ## Input topics -| Name | Type | Description | -| -------------------------------------- | ----------------------------------------------------- | ----------------------------- | -| `~/input/trajectory` | autoware_planning_msgs::msg::Trajectory | input trajectory | -| `~/input/vector_map` | autoware_map_msgs::msg::LaneletMapBin | vector map | -| `~/input/vehicle_odometry` | nav_msgs::msg::Odometry | vehicle position and velocity | -| `~/input/accel` | geometry_msgs::msg::AccelWithCovarianceStamped | vehicle acceleration | -| `~/input/dynamic_objects` | autoware_perception_msgs::msg::PredictedObjects | dynamic objects | -| `~/input/no_ground_pointcloud` | sensor_msgs::msg::PointCloud2 | obstacle pointcloud | -| `~/input/traffic_signals` | autoware_perception_msgs::msg::TrafficLightGroupArray | traffic light states | -| `~/input/virtual_traffic_light_states` | tier4_v2x_msgs::msg::VirtualTrafficLightStateArray | virtual traffic light states | -| `~/input/occupancy_grid` | nav_msgs::msg::OccupancyGrid | occupancy grid | +| Name | Type | Description | +| ------------------------------ | ----------------------------------------------------- | ----------------------------- | +| `~/input/trajectory` | autoware_planning_msgs::msg::Trajectory | input trajectory | +| `~/input/vector_map` | autoware_map_msgs::msg::LaneletMapBin | vector map | +| `~/input/vehicle_odometry` | nav_msgs::msg::Odometry | vehicle position and velocity | +| `~/input/accel` | geometry_msgs::msg::AccelWithCovarianceStamped | vehicle acceleration | +| `~/input/dynamic_objects` | autoware_perception_msgs::msg::PredictedObjects | dynamic objects | +| `~/input/no_ground_pointcloud` | sensor_msgs::msg::PointCloud2 | obstacle pointcloud | +| `~/input/traffic_signals` | autoware_perception_msgs::msg::TrafficLightGroupArray | traffic light states | +| `~/input/occupancy_grid` | nav_msgs::msg::OccupancyGrid | occupancy grid | ## Output topics diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/launch/motion_velocity_planner.launch.xml b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/launch/motion_velocity_planner.launch.xml index 3732d86ef380a..963394323caeb 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/launch/motion_velocity_planner.launch.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/launch/motion_velocity_planner.launch.xml @@ -24,7 +24,6 @@ - diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp index 96865fec1c197..586d27f2c9614 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp @@ -185,9 +185,6 @@ bool MotionVelocityPlannerNode::update_planner_data( // optional data const auto traffic_signals_ptr = sub_traffic_signals_.takeData(); if (traffic_signals_ptr) process_traffic_signals(traffic_signals_ptr); - const auto virtual_traffic_light_states_ptr = sub_virtual_traffic_light_states_.takeData(); - if (virtual_traffic_light_states_ptr) - planner_data_.virtual_traffic_light_states = *virtual_traffic_light_states_ptr; processing_times["update_planner_data.traffic_lights"] = sw.toc(true); return is_ready; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp index 757be518e018a..6e33b89e026c3 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp @@ -80,9 +80,6 @@ class MotionVelocityPlannerNode : public rclcpp::Node autoware::universe_utils::InterProcessPollingSubscriber< autoware_perception_msgs::msg::TrafficLightGroupArray> sub_traffic_signals_{this, "~/input/traffic_signals"}; - autoware::universe_utils::InterProcessPollingSubscriber< - tier4_v2x_msgs::msg::VirtualTrafficLightStateArray> - sub_virtual_traffic_light_states_{this, "~/input/virtual_traffic_light_states"}; rclcpp::Subscription::SharedPtr sub_lanelet_map_; void on_trajectory( diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/test/src/test_node_interface.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/test/src/test_node_interface.cpp index 44ff7820c1566..89a732ead861b 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/test/src/test_node_interface.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/test/src/test_node_interface.cpp @@ -101,8 +101,6 @@ void publishMandatoryTopics( test_manager->publishMap(test_target_node, "motion_velocity_planner_node/input/vector_map"); test_manager->publishTrafficSignals( test_target_node, "motion_velocity_planner_node/input/traffic_signals"); - test_manager->publishVirtualTrafficLightState( - test_target_node, "motion_velocity_planner_node/input/virtual_traffic_light_states"); test_manager->publishOccupancyGrid( test_target_node, "motion_velocity_planner_node/input/occupancy_grid"); } From 067ee7a282853a8610d67d2cc75cb0002c77af38 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 20 Dec 2024 08:12:51 +0900 Subject: [PATCH 053/334] feat(motion_utils): add planning factor interface (#9676) * feat(motion_utils): add planning factor interface Signed-off-by: satoshi-ota * fix: use extern template Signed-off-by: satoshi-ota * fix: define function in header Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../factor/planning_factor_interface.hpp | 240 ++++++++++++++++++ .../src/factor/planing_factor_interface.cpp | 47 ++++ 2 files changed, 287 insertions(+) create mode 100644 common/autoware_motion_utils/include/autoware/motion_utils/factor/planning_factor_interface.hpp create mode 100644 common/autoware_motion_utils/src/factor/planing_factor_interface.cpp diff --git a/common/autoware_motion_utils/include/autoware/motion_utils/factor/planning_factor_interface.hpp b/common/autoware_motion_utils/include/autoware/motion_utils/factor/planning_factor_interface.hpp new file mode 100644 index 0000000000000..7b720c69c6701 --- /dev/null +++ b/common/autoware_motion_utils/include/autoware/motion_utils/factor/planning_factor_interface.hpp @@ -0,0 +1,240 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__MOTION_UTILS__FACTOR__PLANNING_FACTOR_INTERFACE_HPP_ +#define AUTOWARE__MOTION_UTILS__FACTOR__PLANNING_FACTOR_INTERFACE_HPP_ + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +namespace autoware::motion_utils +{ + +using geometry_msgs::msg::Pose; +using tier4_planning_msgs::msg::ControlPoint; +using tier4_planning_msgs::msg::PlanningFactor; +using tier4_planning_msgs::msg::PlanningFactorArray; +using tier4_planning_msgs::msg::SafetyFactorArray; + +class PlanningFactorInterface +{ +public: + PlanningFactorInterface(rclcpp::Node * node, const std::string & name) + : name_{name}, + pub_factors_{ + node->create_publisher("/planning/planning_factors/" + name, 1)}, + clock_{node->get_clock()} + { + } + + /** + * @brief factor setter for single control point. + * + * @param path points. + * @param ego current pose. + * @param control point pose. (e.g. stop or slow down point pose) + * @param behavior of this planning factor. + * @param safety factor. + * @param driving direction. + * @param target velocity of the control point. + * @param shift length of the control point. + * @param detail information. + */ + template + void add( + const std::vector & points, const Pose & ego_pose, const Pose & control_point_pose, + const uint16_t behavior, const SafetyFactorArray & safety_factors, + const bool is_driving_forward = true, const double velocity = 0.0, + const double shift_length = 0.0, const std::string & detail = "") + { + const auto distance = static_cast(autoware::motion_utils::calcSignedArcLength( + points, ego_pose.position, control_point_pose.position)); + add( + distance, control_point_pose, behavior, safety_factors, is_driving_forward, velocity, + shift_length, detail); + } + + /** + * @brief factor setter for two control points (section). + * + * @param path points. + * @param ego current pose. + * @param control section start pose. (e.g. lane change start point pose) + * @param control section end pose. (e.g. lane change end point pose) + * @param behavior of this planning factor. + * @param safety factor. + * @param driving direction. + * @param target velocity of the control point. + * @param shift length of the control point. + * @param detail information. + */ + template + void add( + const std::vector & points, const Pose & ego_pose, const Pose & start_pose, + const Pose & end_pose, const uint16_t behavior, const SafetyFactorArray & safety_factors, + const bool is_driving_forward = true, const double velocity = 0.0, + const double shift_length = 0.0, const std::string & detail = "") + { + const auto start_distance = static_cast( + autoware::motion_utils::calcSignedArcLength(points, ego_pose.position, start_pose.position)); + const auto end_distance = static_cast( + autoware::motion_utils::calcSignedArcLength(points, ego_pose.position, end_pose.position)); + add( + start_distance, end_distance, start_pose, end_pose, behavior, safety_factors, + is_driving_forward, velocity, shift_length, detail); + } + + /** + * @brief factor setter for single control point. + * + * @param distance to control point. + * @param control point pose. (e.g. stop point pose) + * @param behavior of this planning factor. + * @param safety factor. + * @param driving direction. + * @param target velocity of the control point. + * @param shift length of the control point. + * @param detail information. + */ + void add( + const double distance, const Pose & control_point_pose, const uint16_t behavior, + const SafetyFactorArray & safety_factors, const bool is_driving_forward = true, + const double velocity = 0.0, const double shift_length = 0.0, const std::string & detail = "") + { + const auto control_point = tier4_planning_msgs::build() + .pose(control_point_pose) + .velocity(velocity) + .shift_length(shift_length) + .distance(distance); + + const auto factor = tier4_planning_msgs::build() + .module(name_) + .is_driving_forward(is_driving_forward) + .control_points({control_point}) + .behavior(behavior) + .detail(detail) + .safety_factors(safety_factors); + + factors_.push_back(factor); + } + + /** + * @brief factor setter for two control points (section). + * + * @param distance to control section start point. + * @param distance to control section end point. + * @param control section start pose. (e.g. lane change start point pose) + * @param control section end pose. (e.g. lane change end point pose) + * @param behavior of this planning factor. + * @param safety factor. + * @param driving direction. + * @param target velocity of the control point. + * @param shift length of the control point. + * @param detail information. + */ + void add( + const double start_distance, const double end_distance, const Pose & start_pose, + const Pose & end_pose, const uint16_t behavior, const SafetyFactorArray & safety_factors, + const bool is_driving_forward = true, const double velocity = 0.0, + const double shift_length = 0.0, const std::string & detail = "") + { + const auto control_start_point = tier4_planning_msgs::build() + .pose(start_pose) + .velocity(velocity) + .shift_length(shift_length) + .distance(start_distance); + + const auto control_end_point = tier4_planning_msgs::build() + .pose(end_pose) + .velocity(velocity) + .shift_length(shift_length) + .distance(end_distance); + + const auto factor = tier4_planning_msgs::build() + .module(name_) + .is_driving_forward(is_driving_forward) + .control_points({control_start_point, control_end_point}) + .behavior(behavior) + .detail(detail) + .safety_factors(safety_factors); + + factors_.push_back(factor); + } + + /** + * @brief publish planning factors. + */ + void publish() + { + PlanningFactorArray msg; + msg.header.frame_id = "map"; + msg.header.stamp = clock_->now(); + msg.factors = factors_; + + pub_factors_->publish(msg); + + factors_.clear(); + } + +private: + std::string name_; + + rclcpp::Publisher::SharedPtr pub_factors_; + + rclcpp::Clock::SharedPtr clock_; + + std::vector factors_; +}; + +extern template void PlanningFactorInterface::add( + const std::vector &, const Pose &, const Pose &, + const uint16_t behavior, const SafetyFactorArray &, const bool, const double, const double, + const std::string &); +extern template void PlanningFactorInterface::add( + const std::vector &, const Pose &, const Pose &, + const uint16_t behavior, const SafetyFactorArray &, const bool, const double, const double, + const std::string &); +extern template void PlanningFactorInterface::add( + const std::vector &, const Pose &, const Pose &, + const uint16_t behavior, const SafetyFactorArray &, const bool, const double, const double, + const std::string &); + +extern template void PlanningFactorInterface::add( + const std::vector &, const Pose &, const Pose &, + const Pose &, const uint16_t behavior, const SafetyFactorArray &, const bool, const double, + const double, const std::string &); +extern template void PlanningFactorInterface::add( + const std::vector &, const Pose &, const Pose &, + const Pose &, const uint16_t behavior, const SafetyFactorArray &, const bool, const double, + const double, const std::string &); +extern template void PlanningFactorInterface::add( + const std::vector &, const Pose &, const Pose &, + const Pose &, const uint16_t behavior, const SafetyFactorArray &, const bool, const double, + const double, const std::string &); + +} // namespace autoware::motion_utils + +#endif // AUTOWARE__MOTION_UTILS__FACTOR__PLANNING_FACTOR_INTERFACE_HPP_ diff --git a/common/autoware_motion_utils/src/factor/planing_factor_interface.cpp b/common/autoware_motion_utils/src/factor/planing_factor_interface.cpp new file mode 100644 index 0000000000000..d09355b4003ae --- /dev/null +++ b/common/autoware_motion_utils/src/factor/planing_factor_interface.cpp @@ -0,0 +1,47 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include +#include + +namespace autoware::motion_utils +{ +template void PlanningFactorInterface::add( + const std::vector &, const Pose &, const Pose &, + const uint16_t behavior, const SafetyFactorArray &, const bool, const double, const double, + const std::string &); +template void PlanningFactorInterface::add( + const std::vector &, const Pose &, const Pose &, + const uint16_t behavior, const SafetyFactorArray &, const bool, const double, const double, + const std::string &); +template void PlanningFactorInterface::add( + const std::vector &, const Pose &, const Pose &, + const uint16_t behavior, const SafetyFactorArray &, const bool, const double, const double, + const std::string &); + +template void PlanningFactorInterface::add( + const std::vector &, const Pose &, const Pose &, + const Pose &, const uint16_t behavior, const SafetyFactorArray &, const bool, const double, + const double, const std::string &); +template void PlanningFactorInterface::add( + const std::vector &, const Pose &, const Pose &, + const Pose &, const uint16_t behavior, const SafetyFactorArray &, const bool, const double, + const double, const std::string &); +template void PlanningFactorInterface::add( + const std::vector &, const Pose &, const Pose &, + const Pose &, const uint16_t behavior, const SafetyFactorArray &, const bool, const double, + const double, const std::string &); +} // namespace autoware::motion_utils From 160e47bf7cb9c9a5d194afcdf3f5d13754f18670 Mon Sep 17 00:00:00 2001 From: mkquda <168697710+mkquda@users.noreply.github.com> Date: Fri, 20 Dec 2024 10:38:09 +0900 Subject: [PATCH 054/334] fix(mpc_lateral_controller): prevent unstable steering command while stopped (#9690) * modify logic of function isStoppedState Signed-off-by: mohammad alqudah * use a constant distance margin instead of wheelbase length Signed-off-by: mohammad alqudah * add comment to implementation Signed-off-by: mohammad alqudah --------- Signed-off-by: mohammad alqudah --- .../src/mpc_lateral_controller.cpp | 39 ++++++++++++------- 1 file changed, 24 insertions(+), 15 deletions(-) diff --git a/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp b/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp index 11f4ab4fa233b..86d0c0143ed34 100644 --- a/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp +++ b/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp @@ -432,11 +432,18 @@ Lateral MpcLateralController::getInitialControlCommand() const bool MpcLateralController::isStoppedState() const { + const double current_vel = m_current_kinematic_state.twist.twist.linear.x; // If the nearest index is not found, return false - if (m_current_trajectory.points.empty()) { + if ( + m_current_trajectory.points.empty() || std::fabs(current_vel) > m_stop_state_entry_ego_speed) { return false; } + const auto latest_published_cmd = m_ctrl_cmd_prev; // use prev_cmd as a latest published command + if (m_keep_steer_control_until_converged && !isSteerConverged(latest_published_cmd)) { + return false; // not stopState: keep control + } + // 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 @@ -445,21 +452,23 @@ bool MpcLateralController::isStoppedState() const m_current_trajectory.points, m_current_kinematic_state.pose.pose, m_ego_nearest_dist_threshold, m_ego_nearest_yaw_threshold); - const double current_vel = m_current_kinematic_state.twist.twist.linear.x; - const double target_vel = m_current_trajectory.points.at(nearest).longitudinal_velocity_mps; - - const auto latest_published_cmd = m_ctrl_cmd_prev; // use prev_cmd as a latest published command - if (m_keep_steer_control_until_converged && !isSteerConverged(latest_published_cmd)) { - return false; // not stopState: keep control - } + // It is possible that stop is executed earlier than stop point, and velocity controller + // will not start when the distance from ego to stop point is less than 0.5 meter. + // So we use a distance margin to ensure we can detect stopped state. + static constexpr double distance_margin = 1.0; + const double target_vel = std::invoke([&]() -> double { + auto min_vel = m_current_trajectory.points.at(nearest).longitudinal_velocity_mps; + auto covered_distance = 0.0; + for (auto i = nearest + 1; i < m_current_trajectory.points.size(); ++i) { + min_vel = std::min(min_vel, m_current_trajectory.points.at(i).longitudinal_velocity_mps); + covered_distance += autoware::universe_utils::calcDistance2d( + m_current_trajectory.points.at(i - 1).pose, m_current_trajectory.points.at(i).pose); + if (covered_distance > distance_margin) break; + } + return min_vel; + }); - 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; - } + return std::fabs(target_vel) < m_stop_state_entry_target_speed; } Lateral MpcLateralController::createCtrlCmdMsg(const Lateral & ctrl_cmd) From e5243e473e98689532661c4add09d32ca275dae4 Mon Sep 17 00:00:00 2001 From: iwatake Date: Fri, 20 Dec 2024 15:00:10 +0900 Subject: [PATCH 055/334] feat(system_monitor): check UDP network errors (#9538) * feat(system_monitor): generalize logic for /proc/net/snmp Signed-off-by: takeshi.iwanari * feat(system_monitor): add UDP buf errors check Signed-off-by: takeshi.iwanari * fix calculation for errors per unit time at the first time Signed-off-by: takeshi.iwanari * style(pre-commit): autofix * organize code Signed-off-by: takeshi.iwanari * style(pre-commit): autofix * fix warnings Signed-off-by: takeshi.iwanari * remove unnecessary fmt::format Signed-off-by: takeshi.iwanari * organize code for metrics from /proc/net/snmp Signed-off-by: takeshi.iwanari * style(pre-commit): autofix * separate ROS 2 parameters from constructor Signed-off-by: takeshi.iwanari * suppress log Signed-off-by: takeshi.iwanari * style(pre-commit): autofix * fix bugprone-fold-init-type Signed-off-by: takeshi.iwanari * dummy commit to kick workflows Signed-off-by: takeshi.iwanari --------- Signed-off-by: takeshi.iwanari Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: ito-san <57388357+ito-san@users.noreply.github.com> --- system/system_monitor/README.md | 1 + .../config/net_monitor.param.yaml | 2 + system/system_monitor/docs/ros_parameters.md | 2 + .../system_monitor/docs/topics_net_monitor.md | 20 ++ .../net_monitor/net_monitor.hpp | 118 +++++-- .../src/net_monitor/net_monitor.cpp | 330 +++++++++++------- 6 files changed, 333 insertions(+), 140 deletions(-) diff --git a/system/system_monitor/README.md b/system/system_monitor/README.md index 6203ad45d4b3a..d00c57c895279 100644 --- a/system/system_monitor/README.md +++ b/system/system_monitor/README.md @@ -77,6 +77,7 @@ Every topic is published in 1 minute interval. | | Network Usage | ✓ | ✓ | ✓ | Notification of usage only, normally error not generated. | | | Network CRC Error | ✓ | ✓ | ✓ | Warning occurs when the number of CRC errors in the period reaches the threshold value. The number of CRC errors that occur is the same as the value that can be confirmed with the ip command. | | | IP Packet Reassembles Failed | ✓ | ✓ | ✓ | | +| | UDP Buf Errors | ✓ | ✓ | ✓ | | | NTP Monitor | NTP Offset | ✓ | ✓ | ✓ | | | Process Monitor | Tasks Summary | ✓ | ✓ | ✓ | | | | High-load Proc[0-9] | ✓ | ✓ | ✓ | | diff --git a/system/system_monitor/config/net_monitor.param.yaml b/system/system_monitor/config/net_monitor.param.yaml index 7a1e5aeff2db1..b366e26395641 100644 --- a/system/system_monitor/config/net_monitor.param.yaml +++ b/system/system_monitor/config/net_monitor.param.yaml @@ -7,3 +7,5 @@ crc_error_count_threshold: 1 reassembles_failed_check_duration: 1 reassembles_failed_check_count: 1 + udp_buf_errors_check_duration: 1 + udp_buf_errors_check_count: 1 diff --git a/system/system_monitor/docs/ros_parameters.md b/system/system_monitor/docs/ros_parameters.md index 1d081d513c85c..8ec952e60e242 100644 --- a/system/system_monitor/docs/ros_parameters.md +++ b/system/system_monitor/docs/ros_parameters.md @@ -69,6 +69,8 @@ net_monitor: | crc_error_count_threshold | int | n/a | 1 | Generates warning when count of CRC errors during CRC error check duration reaches a specified value or higher. | | reassembles_failed_check_duration | int | sec | 1 | IP packet reassembles failed check duration. | | reassembles_failed_check_count | int | n/a | 1 | Generates warning when count of IP packet reassembles failed during IP packet reassembles failed check duration reaches a specified value or higher. | +| udp_buf_errors_check_duration | int | sec | 1 | UDP buf errors check duration. | +| udp_buf_errors_check_count | int | n/a | 1 | Generates warning when count of UDP buf errors during udp_buf_errors_check_duration reaches a specified value or higher. | ## NTP Monitor diff --git a/system/system_monitor/docs/topics_net_monitor.md b/system/system_monitor/docs/topics_net_monitor.md index edb067c0a5be7..84afb250929b8 100644 --- a/system/system_monitor/docs/topics_net_monitor.md +++ b/system/system_monitor/docs/topics_net_monitor.md @@ -106,3 +106,23 @@ | --------------------------------------- | --------------- | | total packet reassembles failed | 0 | | packet reassembles failed per unit time | 0 | + +## UDP Buf Errors + +/diagnostics/net_monitor: UDP Buf Errors + +[summary] + +| level | message | +| ----- | -------------- | +| OK | OK | +| WARN | UDP buf errors | + +[values] + +| key | value (example) | +| -------------------------------- | --------------- | +| total UDP rcv buf errors | 0 | +| UDP rcv buf errors per unit time | 0 | +| total UDP snd buf errors | 0 | +| UDP snd buf errors per unit time | 0 | diff --git a/system/system_monitor/include/system_monitor/net_monitor/net_monitor.hpp b/system/system_monitor/include/system_monitor/net_monitor/net_monitor.hpp index 5aa2cc9790143..77536c4a60615 100644 --- a/system/system_monitor/include/system_monitor/net_monitor/net_monitor.hpp +++ b/system/system_monitor/include/system_monitor/net_monitor/net_monitor.hpp @@ -81,6 +81,93 @@ struct CrcErrors unsigned int last_rx_crc_errors{0}; //!< @brief rx_crc_error at the time of the last monitoring }; +/** + * @brief /proc/net/snmp information + */ +class NetSnmp +{ +public: + enum class Result { + OK, + CHECK_WARNING, + READ_ERROR, + }; + + /** + * @brief Constructor + * @param [in] node node using this class. + */ + explicit NetSnmp(rclcpp::Node * node); + + /** + * @brief Constructor + */ + NetSnmp() = delete; + + /** + * @brief Copy constructor + */ + NetSnmp(const NetSnmp &) = delete; + + /** + * @brief Copy assignment operator + */ + NetSnmp & operator=(const NetSnmp &) = delete; + + /** + * @brief Move constructor + */ + NetSnmp(const NetSnmp &&) = delete; + + /** + * @brief Move assignment operator + */ + NetSnmp & operator=(const NetSnmp &&) = delete; + + /** + * @brief Set parameters for check + * @param [in] check_duration the value for check_duration + * @param [in] check_count the value for check_count + */ + void set_check_parameters(unsigned int check_duration, unsigned int check_count); + + /** + * @brief Find index in `/proc/net/snmp` + * @param [in] protocol Protocol name (the first column string). e.g. "Ip:" or "Udp:" + * @param [in] metrics Metrics name. e.g. "ReasmFails" + */ + void find_index(const std::string & protocol, const std::string & metrics); + + /** + * @brief Check metrics + * @param [out] current_value the value read from snmp + * @param [out] value_per_unit_time the increase of the value during the duration + * @return the result of check + */ + Result check_metrics(uint64_t & current_value, uint64_t & value_per_unit_time); + +private: + /** + * @brief Read value from `/proc/net/snmp` + * @param [in] index_row row in `/proc/net/snmp` + * @param [in] index_col col in `/proc/net/snmp` + * @param [out] output_value retrieved value + * @return execution result + */ + bool read_value_from_proc( + unsigned int index_row, unsigned int index_col, uint64_t & output_value); + + rclcpp::Logger logger_; //!< @brief logger gotten from user node + unsigned int check_duration_; //!< @brief check duration + unsigned int check_count_; //!< @brief check count threshold + unsigned int index_row_; //!< @brief index for the target metrics in /proc/net/snmp + unsigned int index_col_; //!< @brief index for the target metrics in /proc/net/snmp + uint64_t current_value_; //!< @brief the value read from snmp + uint64_t last_value_; //!< @brief the value read from snmp at the last monitoring + uint64_t value_per_unit_time_; //!< @brief the increase of the value during the duration + std::deque queue_; //!< @brief queue that holds the delta of the value +}; + namespace local = boost::asio::local; class NetMonitor : public rclcpp::Node @@ -150,6 +237,12 @@ class NetMonitor : public rclcpp::Node */ void check_reassembles_failed(diagnostic_updater::DiagnosticStatusWrapper & status); + /** + * @brief Check UDP buf errors + * @param [out] status diagnostic message passed directly to diagnostic publish calls + */ + void check_udp_buf_errors(diagnostic_updater::DiagnosticStatusWrapper & status); + /** * @brief Timer callback */ @@ -273,18 +366,6 @@ class NetMonitor : public rclcpp::Node */ void close_connection(); - /** - * @brief Get column index of IP packet reassembles failed from `/proc/net/snmp` - */ - void get_reassembles_failed_column_index(); - - /** - * @brief get IP packet reassembles failed - * @param [out] reassembles_failed IP packet reassembles failed - * @return execution result - */ - bool get_reassembles_failed(uint64_t & reassembles_failed); - diagnostic_updater::Updater updater_; //!< @brief Updater class which advertises to /diagnostics rclcpp::TimerBase::SharedPtr timer_; //!< @brief timer to get Network information @@ -307,16 +388,9 @@ class NetMonitor : public rclcpp::Node unsigned int crc_error_check_duration_; //!< @brief CRC error check duration unsigned int crc_error_count_threshold_; //!< @brief CRC error count threshold - std::deque - reassembles_failed_queue_; //!< @brief queue that holds count of IP packet reassembles failed - uint64_t last_reassembles_failed_; //!< @brief IP packet reassembles failed at the time of the - //!< last monitoring - unsigned int - reassembles_failed_check_duration_; //!< @brief IP packet reassembles failed check duration - unsigned int - reassembles_failed_check_count_; //!< @brief IP packet reassembles failed check count threshold - unsigned int reassembles_failed_column_index_; //!< @brief column index of IP Reassembles failed - //!< in /proc/net/snmp + NetSnmp reassembles_failed_info_; //!< @brief information of IP packet reassembles failed + NetSnmp udp_rcvbuf_errors_info_; //!< @brief information of UDP rcv buf errors + NetSnmp udp_sndbuf_errors_info_; //!< @brief information of UDP snd buf errors /** * @brief Network connection status messages diff --git a/system/system_monitor/src/net_monitor/net_monitor.cpp b/system/system_monitor/src/net_monitor/net_monitor.cpp index d99150f0b3037..fd00d7f7b895b 100644 --- a/system/system_monitor/src/net_monitor/net_monitor.cpp +++ b/system/system_monitor/src/net_monitor/net_monitor.cpp @@ -28,6 +28,7 @@ #include #include +#include #include #include @@ -51,11 +52,9 @@ NetMonitor::NetMonitor(const rclcpp::NodeOptions & options) socket_path_(declare_parameter("socket_path", traffic_reader_service::socket_path)), crc_error_check_duration_(declare_parameter("crc_error_check_duration", 1)), crc_error_count_threshold_(declare_parameter("crc_error_count_threshold", 1)), - last_reassembles_failed_(0), - reassembles_failed_check_duration_( - declare_parameter("reassembles_failed_check_duration", 1)), - reassembles_failed_check_count_(declare_parameter("reassembles_failed_check_count", 1)), - reassembles_failed_column_index_(0) + reassembles_failed_info_(this), + udp_rcvbuf_errors_info_(this), + udp_sndbuf_errors_info_(this) { if (monitor_program_.empty()) { monitor_program_ = "*"; @@ -68,6 +67,7 @@ NetMonitor::NetMonitor(const rclcpp::NodeOptions & options) updater_.add("Network Traffic", this, &NetMonitor::monitor_traffic); updater_.add("Network CRC Error", this, &NetMonitor::check_crc_error); updater_.add("IP Packet Reassembles Failed", this, &NetMonitor::check_reassembles_failed); + updater_.add("UDP Buf Errors", this, &NetMonitor::check_udp_buf_errors); nl80211_.init(); @@ -83,8 +83,21 @@ NetMonitor::NetMonitor(const rclcpp::NodeOptions & options) using namespace std::literals::chrono_literals; timer_ = rclcpp::create_timer(this, get_clock(), 1s, std::bind(&NetMonitor::on_timer, this)); - // Get column index of IP packet reassembles failed from `/proc/net/snmp` - get_reassembles_failed_column_index(); + // Initialize information for `/proc/net/snmp` + int reassembles_failed_check_duration = + declare_parameter("reassembles_failed_check_duration", 1); + int reassembles_failed_check_count = declare_parameter("reassembles_failed_check_count", 1); + int udp_buf_errors_check_duration = declare_parameter("udp_buf_errors_check_duration", 1); + int udp_buf_errors_check_count = declare_parameter("udp_buf_errors_check_count", 1); + reassembles_failed_info_.set_check_parameters( + reassembles_failed_check_duration, reassembles_failed_check_count); + udp_rcvbuf_errors_info_.set_check_parameters( + udp_buf_errors_check_duration, udp_buf_errors_check_count); + udp_sndbuf_errors_info_.set_check_parameters( + udp_buf_errors_check_duration, udp_buf_errors_check_count); + reassembles_failed_info_.find_index("Ip:", "ReasmFails"); + udp_rcvbuf_errors_info_.find_index("Udp:", "RcvbufErrors"); + udp_sndbuf_errors_info_.find_index("Udp:", "SndbufErrors"); // Send request to start nethogs if (enable_traffic_monitor_) { @@ -292,41 +305,66 @@ void NetMonitor::check_reassembles_failed(diagnostic_updater::DiagnosticStatusWr // Remember start time to measure elapsed time const auto t_start = SystemMonitorUtility::startMeasurement(); - int whole_level = DiagStatus::OK; - std::string error_message; uint64_t total_reassembles_failed = 0; + uint64_t unit_reassembles_failed = 0; + NetSnmp::Result ret = + reassembles_failed_info_.check_metrics(total_reassembles_failed, unit_reassembles_failed); + status.add("total packet reassembles failed", total_reassembles_failed); + status.add("packet reassembles failed per unit time", unit_reassembles_failed); - if (get_reassembles_failed(total_reassembles_failed)) { - reassembles_failed_queue_.push_back(total_reassembles_failed - last_reassembles_failed_); - while (reassembles_failed_queue_.size() > reassembles_failed_check_duration_) { - reassembles_failed_queue_.pop_front(); - } + int whole_level = DiagStatus::OK; + std::string error_message = "OK"; + switch (ret) { + case NetSnmp::Result::OK: + default: + break; + case NetSnmp::Result::CHECK_WARNING: + whole_level = DiagStatus::WARN; + error_message = "reassembles failed"; + break; + case NetSnmp::Result::READ_ERROR: + whole_level = DiagStatus::ERROR; + error_message = "failed to read /proc/net/snmp"; + break; + } - uint64_t unit_reassembles_failed = 0; - for (auto reassembles_failed : reassembles_failed_queue_) { - unit_reassembles_failed += reassembles_failed; - } + status.summary(whole_level, error_message); - status.add(fmt::format("total packet reassembles failed"), total_reassembles_failed); - status.add(fmt::format("packet reassembles failed per unit time"), unit_reassembles_failed); + // Measure elapsed time since start time and report + SystemMonitorUtility::stopMeasurement(t_start, status); +} - if (unit_reassembles_failed >= reassembles_failed_check_count_) { - whole_level = std::max(whole_level, static_cast(DiagStatus::WARN)); - error_message = "reassembles failed"; - } +void NetMonitor::check_udp_buf_errors(diagnostic_updater::DiagnosticStatusWrapper & status) +{ + // Remember start time to measure elapsed time + const auto t_start = SystemMonitorUtility::startMeasurement(); - last_reassembles_failed_ = total_reassembles_failed; - } else { - reassembles_failed_queue_.push_back(0); - whole_level = std::max(whole_level, static_cast(DiagStatus::ERROR)); + uint64_t total_udp_rcvbuf_errors = 0; + uint64_t unit_udp_rcvbuf_errors = 0; + NetSnmp::Result ret_rcv = + udp_rcvbuf_errors_info_.check_metrics(total_udp_rcvbuf_errors, unit_udp_rcvbuf_errors); + status.add("total UDP rcv buf errors", total_udp_rcvbuf_errors); + status.add("UDP rcv buf errors per unit time", unit_udp_rcvbuf_errors); + + uint64_t total_udp_sndbuf_errors = 0; + uint64_t unit_udp_sndbuf_errors = 0; + NetSnmp::Result ret_snd = + udp_sndbuf_errors_info_.check_metrics(total_udp_sndbuf_errors, unit_udp_sndbuf_errors); + status.add("total UDP snd buf errors", total_udp_sndbuf_errors); + status.add("UDP snd buf errors per unit time", unit_udp_sndbuf_errors); + + int whole_level = DiagStatus::OK; + std::string error_message = "OK"; + if (ret_rcv == NetSnmp::Result::READ_ERROR || ret_snd == NetSnmp::Result::READ_ERROR) { + whole_level = DiagStatus::ERROR; error_message = "failed to read /proc/net/snmp"; + } else if ( + ret_rcv == NetSnmp::Result::CHECK_WARNING || ret_snd == NetSnmp::Result::CHECK_WARNING) { + whole_level = DiagStatus::WARN; + error_message = "UDP buf errors"; } - if (!error_message.empty()) { - status.summary(whole_level, error_message); - } else { - status.summary(whole_level, "OK"); - } + status.summary(whole_level, error_message); // Measure elapsed time since start time and report SystemMonitorUtility::stopMeasurement(t_start, status); @@ -544,90 +582,6 @@ void NetMonitor::update_crc_error(NetworkInfomation & network, const struct rtnl crc_errors.last_rx_crc_errors = stats->rx_crc_errors; } -void NetMonitor::get_reassembles_failed_column_index() -{ - std::ifstream ifs("/proc/net/snmp"); - if (!ifs) { - RCLCPP_WARN(get_logger(), "Failed to open /proc/net/snmp."); - return; - } - - // Find column index of 'ReasmFails' - std::string line; - if (!std::getline(ifs, line)) { - RCLCPP_WARN(get_logger(), "Failed to get header of /proc/net/snmp."); - return; - } - - // /proc/net/snmp - // Ip: Forwarding DefaultTTL InReceives ... ReasmTimeout ReasmReqds ReasmOKs ReasmFails ... - // Ip: 2 64 5636471397 ... 135 2303339 216166 270 .. - std::vector header_list; - boost::split(header_list, line, boost::is_space()); - - if (header_list.empty()) { - RCLCPP_WARN(get_logger(), "Failed to get header list of /proc/net/snmp."); - return; - } - if (header_list[0] != "Ip:") { - RCLCPP_WARN( - get_logger(), "Header column is invalid in /proc/net/snmp. %s", header_list[0].c_str()); - return; - } - - int index = 0; - for (const auto & header : header_list) { - if (header == "ReasmFails") { - reassembles_failed_column_index_ = index; - break; - } - ++index; - } -} - -bool NetMonitor::get_reassembles_failed(uint64_t & reassembles_failed) -{ - if (reassembles_failed_column_index_ == 0) { - RCLCPP_WARN(get_logger(), "Column index is invalid. : %d", reassembles_failed_column_index_); - return false; - } - - std::ifstream ifs("/proc/net/snmp"); - if (!ifs) { - RCLCPP_WARN(get_logger(), "Failed to open /proc/net/snmp."); - return false; - } - - std::string line; - - // Skip header row - if (!std::getline(ifs, line)) { - RCLCPP_WARN(get_logger(), "Failed to get header of /proc/net/snmp."); - return false; - } - - // Find a value of 'ReasmFails' - if (!std::getline(ifs, line)) { - RCLCPP_WARN(get_logger(), "Failed to get a line of /proc/net/snmp."); - return false; - } - - std::vector value_list; - boost::split(value_list, line, boost::is_space()); - - if (reassembles_failed_column_index_ >= value_list.size()) { - RCLCPP_WARN( - get_logger(), - "There are not enough columns for reassembles failed column index. : columns=%d index=%d", - static_cast(value_list.size()), reassembles_failed_column_index_); - return false; - } - - reassembles_failed = std::stoull(value_list[reassembles_failed_column_index_]); - - return true; -} - void NetMonitor::send_start_nethogs_request() { // Connect to boot/shutdown service @@ -701,7 +655,7 @@ bool NetMonitor::connect_service() socket_->connect(endpoint, error_code); if (error_code) { - RCLCPP_ERROR(get_logger(), "Failed to connect socket. %s", error_code.message().c_str()); + RCLCPP_ERROR_ONCE(get_logger(), "Failed to connect socket. %s", error_code.message().c_str()); return false; } @@ -782,5 +736,145 @@ void NetMonitor::close_connection() socket_->close(); } +NetSnmp::NetSnmp(rclcpp::Node * node) +: logger_(node->get_logger().get_child("net_snmp")), + check_duration_(1), + check_count_(1), + index_row_(0), + index_col_(0), + current_value_(0), + last_value_(0), + value_per_unit_time_(0), + queue_() +{ +} + +void NetSnmp::set_check_parameters(unsigned int check_duration, unsigned int check_count) +{ + check_duration_ = check_duration; + check_count_ = check_count; +} + +void NetSnmp::find_index(const std::string & protocol, const std::string & metrics) +{ + // /proc/net/snmp + // Ip: Forwarding DefaultTTL InReceives ... ReasmTimeout ReasmReqds ReasmOKs ReasmFails ... + // Ip: 2 64 5636471397 ... 135 2303339 216166 270 .. + std::ifstream ifs("/proc/net/snmp"); + if (!ifs) { + RCLCPP_WARN(logger_, "Failed to open /proc/net/snmp."); + index_row_ = index_col_ = 0; + return; + } + + std::vector target_header_list; + std::string line; + while (std::getline(ifs, line)) { + std::vector header_list; + boost::split(header_list, line, boost::is_space()); + if (header_list.empty()) continue; + if (header_list[0] == protocol) { + target_header_list = header_list; + break; + } + ++index_row_; + } + + ++index_row_; // The values are placed in the row following the header + + for (const auto & header : target_header_list) { + if (header == metrics) { + return; + } + ++index_col_; + } + + RCLCPP_WARN(logger_, "Failed to get header of /proc/net/snmp."); + index_row_ = index_col_ = 0; + return; +} + +NetSnmp::Result NetSnmp::check_metrics(uint64_t & current_value, uint64_t & value_per_unit_time) +{ + if (!read_value_from_proc(index_row_, index_col_, current_value_)) { + queue_.push_back(0); + current_value = value_per_unit_time = 0; + return Result::READ_ERROR; + } + + if (queue_.empty()) { + last_value_ = current_value_; + } + queue_.push_back(current_value_ - last_value_); + last_value_ = current_value_; + while (queue_.size() > check_duration_) { + queue_.pop_front(); + } + + value_per_unit_time_ = std::accumulate(queue_.begin(), queue_.end(), static_cast(0)); + + current_value = current_value_; + value_per_unit_time = value_per_unit_time_; + + if (value_per_unit_time_ >= check_count_) { + return Result::CHECK_WARNING; + } else { + return Result::OK; + } +} + +bool NetSnmp::read_value_from_proc( + unsigned int index_row, unsigned int index_col, uint64_t & output_value) +{ + if (index_row == 0 && index_col == 0) { + RCLCPP_WARN_ONCE(logger_, "index is invalid. : %u, %u", index_row, index_col); + return false; + } + + std::ifstream ifs("/proc/net/snmp"); + if (!ifs) { + RCLCPP_WARN_ONCE(logger_, "Failed to open /proc/net/snmp."); + return false; + } + + std::string target_line; + std::string line; + for (unsigned int row_index = 0; std::getline(ifs, line); ++row_index) { + if (row_index == index_row) { + target_line = line; + break; + } + } + + if (target_line.empty()) { + RCLCPP_WARN_ONCE(logger_, "Failed to get a line of /proc/net/snmp."); + return false; + } + + std::vector value_list; + boost::split(value_list, target_line, boost::is_space()); + if (index_col >= value_list.size()) { + RCLCPP_WARN_ONCE( + logger_, "There are not enough columns for the column index. : column size=%lu index=%u, %u", + value_list.size(), index_row, index_col); + return false; + } + + std::string value_str = value_list[index_col]; + if (value_str.empty()) { + RCLCPP_WARN_ONCE(logger_, "The value is empty. : index=%u, %u", index_row, index_col); + return false; + } + + if (value_str[0] == '-') { + RCLCPP_WARN_ONCE(logger_, "The value is minus. : %s", value_str.c_str()); + output_value = 0; + return false; + } else { + output_value = std::stoull(value_str); + return true; + } +} + #include RCLCPP_COMPONENTS_REGISTER_NODE(NetMonitor) From 0b2bbe8ea75ebb81bb9ac8a1f8ad3c9be3fc453d Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Fri, 20 Dec 2024 15:09:47 +0900 Subject: [PATCH 056/334] fix(autoware_tensorrt_common): fix bugprone-integer-division (#9660) fix: bugprone-error Signed-off-by: kobayu858 --- .../src/tensorrt_common.cpp | 16 ++++++++++------ 1 file changed, 10 insertions(+), 6 deletions(-) diff --git a/perception/autoware_tensorrt_common/src/tensorrt_common.cpp b/perception/autoware_tensorrt_common/src/tensorrt_common.cpp index 897010d22bb4b..990433ee277a0 100644 --- a/perception/autoware_tensorrt_common/src/tensorrt_common.cpp +++ b/perception/autoware_tensorrt_common/src/tensorrt_common.cpp @@ -311,12 +311,13 @@ void TrtCommon::printNetworkInfo(const std::string & onnx_file_path) int groups = conv->getNbGroups(); int stride = s_dims.d[0]; int num_weights = (dim_in.d[1] / groups) * dim_out.d[1] * k_dims.d[0] * k_dims.d[1]; - float gflops = (2 * num_weights) * (dim_in.d[3] / stride * dim_in.d[2] / stride / 1e9); - ; + float gflops = (2.0 * num_weights) * (static_cast(dim_in.d[3]) / stride * + static_cast(dim_in.d[2]) / stride / 1e9); total_gflops += gflops; total_params += num_weights; std::cout << "L" << i << " [conv " << k_dims.d[0] << "x" << k_dims.d[1] << " (" << groups - << ") " << "/" << s_dims.d[0] << "] " << dim_in.d[3] << "x" << dim_in.d[2] << "x" + << ") " + << "/" << s_dims.d[0] << "] " << dim_in.d[3] << "x" << dim_in.d[2] << "x" << dim_in.d[1] << " -> " << dim_out.d[3] << "x" << dim_out.d[2] << "x" << dim_out.d[1]; std::cout << " weights:" << num_weights; @@ -336,8 +337,10 @@ void TrtCommon::printNetworkInfo(const std::string & onnx_file_path) } else if (p_type == nvinfer1::PoolingType::kMAX_AVERAGE_BLEND) { std::cout << "max avg blend "; } - float gflops = dim_in.d[1] * dim_window.d[0] / dim_stride.d[0] * dim_window.d[1] / - dim_stride.d[1] * dim_in.d[2] * dim_in.d[3] / 1e9; + float gflops = static_cast(dim_in.d[1]) * + (static_cast(dim_window.d[0]) / static_cast(dim_stride.d[0])) * + (static_cast(dim_window.d[1]) / static_cast(dim_stride.d[1])) * + static_cast(dim_in.d[2]) * static_cast(dim_in.d[3]) / 1e9; total_gflops += gflops; std::cout << "pool " << dim_window.d[0] << "x" << dim_window.d[1] << "]"; std::cout << " GFLOPs:" << gflops; @@ -381,7 +384,8 @@ bool TrtCommon::buildEngineFromOnnx( if (num_available_dla > 0) { std::cout << "###" << num_available_dla << " DLAs are supported! ###" << std::endl; } else { - std::cout << "###Warning : " << "No DLA is supported! ###" << std::endl; + std::cout << "###Warning : " + << "No DLA is supported! ###" << std::endl; } config->setDefaultDeviceType(nvinfer1::DeviceType::kDLA); config->setDLACore(build_config_->dla_core_id); From a88e90eb46a130d9b7b447f4c893929b93c08cc8 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Fri, 20 Dec 2024 15:10:09 +0900 Subject: [PATCH 057/334] fix(autoware_freespace_planning_algorithms): fix bugprone-errors (#9670) * fix: bugprone-error Signed-off-by: kobayu858 * fix: bugprone-error Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../src/abstract_algorithm.cpp | 2 +- .../autoware_freespace_planning_algorithms/src/astar_search.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/autoware_freespace_planning_algorithms/src/abstract_algorithm.cpp b/planning/autoware_freespace_planning_algorithms/src/abstract_algorithm.cpp index 56d6526e26272..255288603016b 100644 --- a/planning/autoware_freespace_planning_algorithms/src/abstract_algorithm.cpp +++ b/planning/autoware_freespace_planning_algorithms/src/abstract_algorithm.cpp @@ -115,7 +115,7 @@ void AbstractPlanningAlgorithm::setMap(const nav_msgs::msg::OccupancyGrid & cost std::vector is_obstacle_table; is_obstacle_table.resize(nb_of_cells); for (uint32_t i = 0; i < nb_of_cells; ++i) { - const int cost = costmap_.data[i]; + const int cost = costmap_.data[i]; // NOLINT if (cost < 0 || planner_common_param_.obstacle_threshold <= cost) { is_obstacle_table[i] = true; } diff --git a/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp b/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp index 0a17b112eed6f..c9f4b46dab737 100644 --- a/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp +++ b/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp @@ -388,7 +388,7 @@ double AstarSearch::getExpansionDistance(const AstarNode & current_node) const double AstarSearch::getSteeringCost(const int steering_index) const { return planner_common_param_.curve_weight * - (abs(steering_index) / planner_common_param_.turning_steps); + (static_cast(abs(steering_index)) / planner_common_param_.turning_steps); } double AstarSearch::getSteeringChangeCost( From 857aa711ceb03af0ce4089bf7317e8e43ba3acf6 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Fri, 20 Dec 2024 16:16:50 +0900 Subject: [PATCH 058/334] fix(autoware_path_smoother): fix bugprone-branch-clone (#9697) * fix: bugprone-error Signed-off-by: kobayu858 * fix: bugprone-error Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- planning/autoware_path_smoother/src/elastic_band.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/planning/autoware_path_smoother/src/elastic_band.cpp b/planning/autoware_path_smoother/src/elastic_band.cpp index 20786b7b3601e..8c751e698c8fb 100644 --- a/planning/autoware_path_smoother/src/elastic_band.cpp +++ b/planning/autoware_path_smoother/src/elastic_band.cpp @@ -53,9 +53,7 @@ Eigen::SparseMatrix makePMatrix(const int num_points) assign_value_to_triplet_vec(r, c, 6.0); } } else if (std::abs(c - r) == 1) { - if (r == 0 || r == num_points - 1) { - assign_value_to_triplet_vec(r, c, -2.0); - } else if (c == 0 || c == num_points - 1) { + if (r == 0 || r == num_points - 1 || c == 0 || c == num_points - 1) { assign_value_to_triplet_vec(r, c, -2.0); } else { assign_value_to_triplet_vec(r, c, -4.0); From a7314b681a014289818a42c04597c89a149f7bd1 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Fri, 20 Dec 2024 17:26:42 +0900 Subject: [PATCH 059/334] fix(autoware_behavior_path_planner_common): fix bugprone-errors (#9700) fix: bugprone-error Signed-off-by: kobayu858 --- .../drivable_area_expansion/static_drivable_area.cpp | 10 ++++------ .../occupancy_grid_based_collision_detector.cpp | 2 +- 2 files changed, 5 insertions(+), 7 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp index 0768c620dd054..3b272fd8c6722 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp @@ -1127,9 +1127,7 @@ std::vector getBoundWithHatchedRoadMarkings( get_corresponding_polygon_index(*current_polygon, bound_point.id())); } } else { - if (!polygon) { - will_close_polygon = true; - } else if (polygon.value().id() != current_polygon.value().id()) { + if (!polygon || polygon.value().id() != current_polygon.value().id()) { will_close_polygon = true; } else { current_polygon_border_indices.push_back( @@ -1496,9 +1494,9 @@ std::vector postProcess( [](const lanelet::ConstLineString3d & points, std::vector & bound) { for (const auto & bound_p : points) { const auto cp = lanelet::utils::conversion::toGeomMsgPt(bound_p); - if (bound.empty()) { - bound.push_back(cp); - } else if (autoware::universe_utils::calcDistance2d(cp, bound.back()) > overlap_threshold) { + if ( + bound.empty() || + autoware::universe_utils::calcDistance2d(cp, bound.back()) > overlap_threshold) { bound.push_back(cp); } } diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp index e65c67065bc54..33f46420ad537 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp @@ -80,7 +80,7 @@ void OccupancyGridBasedCollisionDetector::setMap(const nav_msgs::msg::OccupancyG for (uint32_t i = 0; i < height; i++) { is_obstacle_table.at(i).resize(width); for (uint32_t j = 0; j < width; j++) { - const int cost = costmap_.data[i * width + j]; + const int cost = costmap_.data[i * width + j]; // NOLINT if (cost < 0 || param_.obstacle_threshold <= cost) { is_obstacle_table[i][j] = true; From 4c03b8d4c2471c13698de1cd43f66cf406f8a114 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Fri, 20 Dec 2024 19:32:34 +0900 Subject: [PATCH 060/334] feat(pid_longitudinal_controller): add new slope compensation mode trajectory_goal_adaptive (#9705) Signed-off-by: yuki-takagi-66 --- .../README.md | 2 ++ ...are_pid_longitudinal_controller.param.yaml | 2 +- .../pid_longitudinal_controller.hpp | 7 ++++- .../src/pid_longitudinal_controller.cpp | 31 +++++++++++++------ 4 files changed, 30 insertions(+), 12 deletions(-) diff --git a/control/autoware_pid_longitudinal_controller/README.md b/control/autoware_pid_longitudinal_controller/README.md index b147b3b795391..aba0f36f04d65 100644 --- a/control/autoware_pid_longitudinal_controller/README.md +++ b/control/autoware_pid_longitudinal_controller/README.md @@ -68,6 +68,8 @@ There are two sources of the slope information, which can be switched by a param - Cons: z-coordinates of high-precision map is needed. - Cons: Does not support free space planning (for now) +We also offer the options to switch between these, depending on driving conditions. + **Notation:** This function works correctly only in a vehicle system that does not have acceleration feedback in the low-level control system. This compensation adds gravity correction to the target acceleration, resulting in an output value that is no longer equal to the target acceleration that the autonomous driving system desires. Therefore, it conflicts with the role of the acceleration feedback in the low-level controller. diff --git a/control/autoware_pid_longitudinal_controller/config/autoware_pid_longitudinal_controller.param.yaml b/control/autoware_pid_longitudinal_controller/config/autoware_pid_longitudinal_controller.param.yaml index bd905cf9be0f1..ec6a6f11b437d 100644 --- a/control/autoware_pid_longitudinal_controller/config/autoware_pid_longitudinal_controller.param.yaml +++ b/control/autoware_pid_longitudinal_controller/config/autoware_pid_longitudinal_controller.param.yaml @@ -74,7 +74,7 @@ # slope compensation lpf_pitch_gain: 0.95 - slope_source: "raw_pitch" # raw_pitch, trajectory_pitch or trajectory_adaptive + slope_source: "trajectory_goal_adaptive" # raw_pitch, trajectory_pitch, trajectory_adaptive or trajectory_goal_adaptive adaptive_trajectory_velocity_th: 1.0 max_pitch_rad: 0.1 min_pitch_rad: -0.1 diff --git a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp index 8796664947a5a..1d03d1b339af6 100644 --- a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp +++ b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp @@ -204,7 +204,12 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro double m_max_acc_cmd_diff; // slope compensation - enum class SlopeSource { RAW_PITCH = 0, TRAJECTORY_PITCH, TRAJECTORY_ADAPTIVE }; + enum class SlopeSource { + RAW_PITCH = 0, + TRAJECTORY_PITCH, + TRAJECTORY_ADAPTIVE, + TRAJECTORY_GOAL_ADAPTIVE + }; SlopeSource m_slope_source{SlopeSource::RAW_PITCH}; double m_adaptive_trajectory_velocity_th; std::shared_ptr m_lpf_pitch{nullptr}; diff --git a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp index be969e5a4af10..ec95ce656fa6f 100644 --- a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp +++ b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp @@ -196,6 +196,8 @@ PidLongitudinalController::PidLongitudinalController( m_slope_source = SlopeSource::TRAJECTORY_PITCH; } else if (slope_source == "trajectory_adaptive") { m_slope_source = SlopeSource::TRAJECTORY_ADAPTIVE; + } else if (slope_source == "trajectory_goal_adaptive") { + m_slope_source = SlopeSource::TRAJECTORY_GOAL_ADAPTIVE; } else { RCLCPP_ERROR(logger_, "Slope source is not valid. Using raw_pitch option as default"); m_slope_source = SlopeSource::RAW_PITCH; @@ -529,21 +531,30 @@ PidLongitudinalController::ControlData PidLongitudinalController::getControlData // NOTE: getPitchByTraj() calculates the pitch angle as defined in // ../media/slope_definition.drawio.svg while getPitchByPose() is not, so `raw_pitch` is reversed const double raw_pitch = (-1.0) * longitudinal_utils::getPitchByPose(current_pose.orientation); + m_lpf_pitch->filter(raw_pitch); const double traj_pitch = longitudinal_utils::getPitchByTraj( control_data.interpolated_traj, control_data.target_idx, m_wheel_base); if (m_slope_source == SlopeSource::RAW_PITCH) { - control_data.slope_angle = m_lpf_pitch->filter(raw_pitch); + control_data.slope_angle = m_lpf_pitch->getValue(); } else if (m_slope_source == SlopeSource::TRAJECTORY_PITCH) { control_data.slope_angle = traj_pitch; - } else if (m_slope_source == SlopeSource::TRAJECTORY_ADAPTIVE) { + } else if ( + m_slope_source == SlopeSource::TRAJECTORY_ADAPTIVE || + m_slope_source == SlopeSource::TRAJECTORY_GOAL_ADAPTIVE) { // if velocity is high, use target idx for slope, otherwise, use raw_pitch - if (control_data.current_motion.vel > m_adaptive_trajectory_velocity_th) { - control_data.slope_angle = traj_pitch; - m_lpf_pitch->filter(raw_pitch); - } else { - control_data.slope_angle = m_lpf_pitch->filter(raw_pitch); - } + const bool is_vel_slow = control_data.current_motion.vel < m_adaptive_trajectory_velocity_th && + m_slope_source == SlopeSource::TRAJECTORY_ADAPTIVE; + + const double goal_dist = autoware::motion_utils::calcSignedArcLength( + control_data.interpolated_traj.points, current_pose.position, + control_data.interpolated_traj.points.size() - 1); + const bool is_close_to_trajectory_end = + goal_dist < m_wheel_base && m_slope_source == SlopeSource::TRAJECTORY_GOAL_ADAPTIVE; + + control_data.slope_angle = + (is_close_to_trajectory_end || is_vel_slow) ? m_lpf_pitch->getValue() : traj_pitch; + if (m_previous_slope_angle.has_value()) { constexpr double gravity_const = 9.8; control_data.slope_angle = std::clamp( @@ -551,13 +562,13 @@ PidLongitudinalController::ControlData PidLongitudinalController::getControlData m_previous_slope_angle.value() + m_min_jerk * control_data.dt / gravity_const, m_previous_slope_angle.value() + m_max_jerk * control_data.dt / gravity_const); } + m_previous_slope_angle = control_data.slope_angle; } else { RCLCPP_ERROR_THROTTLE( logger_, *clock_, 3000, "Slope source is not valid. Using raw_pitch option as default"); - control_data.slope_angle = m_lpf_pitch->filter(raw_pitch); + control_data.slope_angle = m_lpf_pitch->getValue(); } - m_previous_slope_angle = control_data.slope_angle; updatePitchDebugValues(control_data.slope_angle, traj_pitch, raw_pitch, m_lpf_pitch->getValue()); return control_data; From 5ac48238d6e27f890d5c0ffb2528ec81a9ffe1d8 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Fri, 20 Dec 2024 20:40:00 +0900 Subject: [PATCH 061/334] feat(pid_longitudinal_controller): update plotjuggler settings (#9703) Signed-off-by: yuki-takagi-66 --- .../plot_juggler_trajectory_follower.xml | 184 +++++++++++------- 1 file changed, 110 insertions(+), 74 deletions(-) diff --git a/control/autoware_trajectory_follower_node/config/plot_juggler_trajectory_follower.xml b/control/autoware_trajectory_follower_node/config/plot_juggler_trajectory_follower.xml index 0de08076b8c06..38fc5b9ba54da 100644 --- a/control/autoware_trajectory_follower_node/config/plot_juggler_trajectory_follower.xml +++ b/control/autoware_trajectory_follower_node/config/plot_juggler_trajectory_follower.xml @@ -1,130 +1,130 @@ - - + + - - + + - - + + - + - + - + - + - + - + - + - - + + - + - + - - + + - + - + - + - - + + - + - + - + - + - - + + - + - + - - + + @@ -133,114 +133,150 @@ - + - + - - + + - + - + - + - + - - + + - - - - - - + - + + + + + + + + + + + - + - + - + - + - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - + - + - + - + - + - - + + - + + + + + + @@ -255,10 +291,10 @@ - + - + @@ -268,13 +304,13 @@ - + - + - - - + + + @@ -286,7 +322,7 @@ - + From ddfacd3243e2c9fd83884cd55cfe208951e6d327 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 20 Dec 2024 21:46:20 +0900 Subject: [PATCH 062/334] chore(trajectory_follower_node): fix typos (#9707) Signed-off-by: kosuke55 --- .../config/plot_juggler_trajectory_follower.xml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/control/autoware_trajectory_follower_node/config/plot_juggler_trajectory_follower.xml b/control/autoware_trajectory_follower_node/config/plot_juggler_trajectory_follower.xml index 38fc5b9ba54da..fda7e1f3906e0 100644 --- a/control/autoware_trajectory_follower_node/config/plot_juggler_trajectory_follower.xml +++ b/control/autoware_trajectory_follower_node/config/plot_juggler_trajectory_follower.xml @@ -228,7 +228,7 @@ - + @@ -294,7 +294,7 @@ - + @@ -304,7 +304,7 @@ - + @@ -322,7 +322,7 @@ - + From 4d529ba4d4edf4ef0258bd73d55241b7c966fe37 Mon Sep 17 00:00:00 2001 From: Autumn60 <37181352+Autumn60@users.noreply.github.com> Date: Sat, 21 Dec 2024 22:54:13 +0900 Subject: [PATCH 063/334] chore(autoware_mpc_lateral_controller): fix formula description in vehicle_model_bicycle_kinematics.hpp (#8971) fix formula description in vehicle_model_bicycle_kinematics.hpp Signed-off-by: Autumn60 --- .../vehicle_model/vehicle_model_bicycle_kinematics.hpp | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp index d638142daa844..015b4e6fad4d6 100644 --- a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp +++ b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp @@ -14,6 +14,7 @@ /* * Representation + * k : reference curvature (input) * e : lateral error * th : heading angle error * steer : steering angle @@ -32,10 +33,12 @@ * dx3/dt = -(x3 - u) / tau * * Linearized model around reference point (v = v_r, th = th_r, steer = steer_r) - * [0, vr, 0] [ 0] [ 0] - * dx/dt = [0, 0, vr/W/cos(steer_r)^2] * x + [ 0] * u + [-vr*steer_r/W/cos(steer_r)^2] - * [0, 0, 1/tau] [1/tau] [ 0] + * [0, vr, 0] [ 0] [ 0] + * dx/dt = [0, 0, B] * x + [ 0] * u + [-vr*k + A - B*steer_r] + * [0, 0, -1/tau] [1/tau] [ 0] * + * where A = vr*tan(steer_r)/W + * B = vr/(W*cos(steer_r)^2) (partial derivative of A with respect to steer_r) */ #ifndef AUTOWARE__MPC_LATERAL_CONTROLLER__VEHICLE_MODEL__VEHICLE_MODEL_BICYCLE_KINEMATICS_HPP_ From b107ac7bc94b3d88e2873ecbc57aa1cde3375eb5 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Sun, 22 Dec 2024 01:36:19 +0900 Subject: [PATCH 064/334] feat(raw_vehicle_cmd_converter): add vehicle adaptor (#8782) * feat(raw_vehicle_cmd_converter): add vehicle adaptor Signed-off-by: kosuke55 sub operation status Signed-off-by: kosuke55 * feat(raw_vehicle_cmd_converter): publish vehicle adaptor output Signed-off-by: kosuke55 * use control horizon Signed-off-by: kosuke55 * revert carla Signed-off-by: kosuke55 * update docs Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../CMakeLists.txt | 8 ++- .../README.md | 14 +++++ .../node.hpp | 17 +++++- .../vehicle_adaptor/vehicle_adaptor.hpp | 50 ++++++++++++++++ .../launch/raw_vehicle_converter.launch.xml | 6 ++ .../package.xml | 1 + .../raw_vehicle_cmd_converter.schema.json | 5 ++ .../src/node.cpp | 58 +++++++++++++------ .../src/vehicle_adaptor/vehicle_adaptor.cpp | 32 ++++++++++ 9 files changed, 169 insertions(+), 22 deletions(-) create mode 100644 vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/vehicle_adaptor/vehicle_adaptor.hpp create mode 100644 vehicle/autoware_raw_vehicle_cmd_converter/src/vehicle_adaptor/vehicle_adaptor.cpp diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/CMakeLists.txt b/vehicle/autoware_raw_vehicle_cmd_converter/CMakeLists.txt index 9e5b7439e1de2..909dd336bd282 100644 --- a/vehicle/autoware_raw_vehicle_cmd_converter/CMakeLists.txt +++ b/vehicle/autoware_raw_vehicle_cmd_converter/CMakeLists.txt @@ -13,11 +13,15 @@ ament_auto_add_library(actuation_map_converter SHARED src/vgr.cpp ) +ament_auto_add_library(vehicle_adaptor SHARED + src/vehicle_adaptor/vehicle_adaptor.cpp +) + ament_auto_add_library(autoware_raw_vehicle_cmd_converter_node_component SHARED src/node.cpp ) -target_link_libraries(autoware_raw_vehicle_cmd_converter_node_component actuation_map_converter) +target_link_libraries(autoware_raw_vehicle_cmd_converter_node_component actuation_map_converter vehicle_adaptor) rclcpp_components_register_node(autoware_raw_vehicle_cmd_converter_node_component PLUGIN "autoware::raw_vehicle_cmd_converter::RawVehicleCommandConverterNode" @@ -30,7 +34,7 @@ if(BUILD_TESTING) ) set(TEST_RAW_VEHICLE_CMD_CONVERTER_EXE test_autoware_raw_vehicle_cmd_converter) 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 autoware_raw_vehicle_cmd_converter_node_component) + target_link_libraries(${TEST_RAW_VEHICLE_CMD_CONVERTER_EXE} actuation_map_converter vehicle_adaptor autoware_raw_vehicle_cmd_converter_node_component) endif() ament_auto_package(INSTALL_TO_SHARE diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/README.md b/vehicle/autoware_raw_vehicle_cmd_converter/README.md index 1df083f5c5370..a4d72a684e7d3 100644 --- a/vehicle/autoware_raw_vehicle_cmd_converter/README.md +++ b/vehicle/autoware_raw_vehicle_cmd_converter/README.md @@ -45,6 +45,12 @@ vgr_coef_c: 0.042 When `convert_steer_cmd_method: "vgr"` is selected, the node receives the control command from the controller as the desired tire angle and calculates the desired steering angle to output. Also, when `convert_actuation_to_steering_status: true`, this node receives the `actuation_status` topic and calculates the steer tire angle from the `steer_wheel_angle` and publishes it. +### Vehicle Adaptor + +**Under development** +A feature that compensates for control commands according to the dynamic characteristics of the vehicle. +This feature works when `use_vehicle_adaptor: true` is set and requires `control_horizon` to be enabled, so you need to set `enable_control_cmd_horizon_pub: true` in the trajectory_follower node. + ## Input topics | Name | Type | Description | @@ -54,6 +60,14 @@ Also, when `convert_actuation_to_steering_status: true`, this node receives the | `~/input/odometry` | navigation_msgs::Odometry | twist topic in odometry is used. | | `~/input/actuation_status` | tier4_vehicle_msgs::msg::ActuationStatus | actuation status is assumed to receive the same type of status as sent to the vehicle side. For example, if throttle/brake pedal/steer_wheel_angle is sent, the same type of status is received. In the case of steer_wheel_angle, it is used to calculate steer_tire_angle and VGR in this node. | +Input topics when vehicle_adaptor is enabled + +| Name | Type | Description | +| ------------------------------ | ----------------------------------------------- | ----------------------- | +| `~/input/accel` | geometry_msgs::msg::AccelWithCovarianceStamped; | acceleration status | +| `~/input/operation_mode_state` | autoware_adapi_v1_msgs::msg::OperationModeState | operation mode status | +| `~/input/control_horizon` | autoware_control_msgs::msg::ControlHorizon | control horizon command | + ## Output topics | Name | Type | Description | diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/node.hpp b/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/node.hpp index b5e13985c036e..8f8e543dc680e 100644 --- a/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/node.hpp +++ b/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/node.hpp @@ -21,10 +21,12 @@ #include "autoware_raw_vehicle_cmd_converter/brake_map.hpp" #include "autoware_raw_vehicle_cmd_converter/pid.hpp" #include "autoware_raw_vehicle_cmd_converter/steer_map.hpp" +#include "autoware_raw_vehicle_cmd_converter/vehicle_adaptor/vehicle_adaptor.hpp" #include "autoware_raw_vehicle_cmd_converter/vgr.hpp" #include +#include #include #include #include @@ -46,7 +48,8 @@ using tier4_vehicle_msgs::msg::ActuationStatusStamped; using TwistStamped = geometry_msgs::msg::TwistStamped; using Odometry = nav_msgs::msg::Odometry; using Steering = autoware_vehicle_msgs::msg::SteeringReport; - +using autoware_adapi_v1_msgs::msg::OperationModeState; +using geometry_msgs::msg::AccelWithCovarianceStamped; class DebugValues { public: @@ -79,6 +82,7 @@ class RawVehicleCommandConverterNode : public rclcpp::Node //!< @brief topic publisher for low level vehicle command rclcpp::Publisher::SharedPtr pub_actuation_cmd_; rclcpp::Publisher::SharedPtr pub_steering_status_; + rclcpp::Publisher::SharedPtr pub_compensated_control_cmd_; //!< @brief subscriber for vehicle command rclcpp::Subscription::SharedPtr sub_control_cmd_; rclcpp::Subscription::SharedPtr sub_actuation_status_; @@ -86,17 +90,27 @@ class RawVehicleCommandConverterNode : public rclcpp::Node // polling subscribers autoware::universe_utils::InterProcessPollingSubscriber sub_odometry_{ this, "~/input/odometry"}; + // polling subscribers for vehicle_adaptor + autoware::universe_utils::InterProcessPollingSubscriber sub_accel_{ + this, "~/input/accel"}; + autoware::universe_utils::InterProcessPollingSubscriber sub_operation_mode_{ + this, "~/input/operation_mode_state"}; + // control_horizon is an experimental topic, but vehicle_adaptor uses it to improve performance, + autoware::universe_utils::InterProcessPollingSubscriber sub_control_horizon_{ + this, "~/input/control_horizon"}; rclcpp::TimerBase::SharedPtr timer_; std::unique_ptr current_twist_ptr_; // [m/s] std::unique_ptr current_steer_ptr_; ActuationStatusStamped::ConstSharedPtr actuation_status_ptr_; + Odometry::ConstSharedPtr current_odometry_; Control::ConstSharedPtr control_cmd_ptr_; AccelMap accel_map_; BrakeMap brake_map_; SteerMap steer_map_; VGR vgr_; + VehicleAdaptor vehicle_adaptor_; // TODO(tanaka): consider accel/brake pid too PIDController steer_pid_; bool ff_map_initialized_; @@ -112,6 +126,7 @@ class RawVehicleCommandConverterNode : public rclcpp::Node bool convert_brake_cmd_; //!< @brief use brake or not std::optional convert_steer_cmd_method_{std::nullopt}; //!< @brief method to convert bool need_to_subscribe_actuation_status_{false}; + bool use_vehicle_adaptor_{false}; rclcpp::Time prev_time_steer_calculation_{0, 0, RCL_ROS_TIME}; // Whether to subscribe to actuation_status and calculate and publish steering_status diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/vehicle_adaptor/vehicle_adaptor.hpp b/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/vehicle_adaptor/vehicle_adaptor.hpp new file mode 100644 index 0000000000000..595cddd29817f --- /dev/null +++ b/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/vehicle_adaptor/vehicle_adaptor.hpp @@ -0,0 +1,50 @@ +// Copyright 2024 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 AUTOWARE_RAW_VEHICLE_CMD_CONVERTER__VEHICLE_ADAPTOR__VEHICLE_ADAPTOR_HPP_ +#define AUTOWARE_RAW_VEHICLE_CMD_CONVERTER__VEHICLE_ADAPTOR__VEHICLE_ADAPTOR_HPP_ + +#include +#include +#include +#include +#include +#include + +namespace autoware::raw_vehicle_cmd_converter +{ + +using autoware_adapi_v1_msgs::msg::OperationModeState; +using autoware_control_msgs::msg::Control; +using autoware_control_msgs::msg::ControlHorizon; +using autoware_vehicle_msgs::msg::SteeringReport; +using geometry_msgs::msg::AccelWithCovarianceStamped; +using nav_msgs::msg::Odometry; + +class VehicleAdaptor +{ +public: + VehicleAdaptor() = default; + Control compensate( + const Control & input_control_cmd, [[maybe_unused]] const Odometry & odometry, + [[maybe_unused]] const AccelWithCovarianceStamped & accel, + [[maybe_unused]] const double steering, + [[maybe_unused]] const OperationModeState & operation_mode, + [[maybe_unused]] const ControlHorizon & control_horizon); + +private: +}; +} // namespace autoware::raw_vehicle_cmd_converter + +#endif // AUTOWARE_RAW_VEHICLE_CMD_CONVERTER__VEHICLE_ADAPTOR__VEHICLE_ADAPTOR_HPP_ diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/launch/raw_vehicle_converter.launch.xml b/vehicle/autoware_raw_vehicle_cmd_converter/launch/raw_vehicle_converter.launch.xml index 441d924a0e6c3..dc96533c505cd 100644 --- a/vehicle/autoware_raw_vehicle_cmd_converter/launch/raw_vehicle_converter.launch.xml +++ b/vehicle/autoware_raw_vehicle_cmd_converter/launch/raw_vehicle_converter.launch.xml @@ -2,8 +2,11 @@ + + + @@ -13,8 +16,11 @@ + + + diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/package.xml b/vehicle/autoware_raw_vehicle_cmd_converter/package.xml index 468e039312520..ff00f09a7efd8 100644 --- a/vehicle/autoware_raw_vehicle_cmd_converter/package.xml +++ b/vehicle/autoware_raw_vehicle_cmd_converter/package.xml @@ -21,6 +21,7 @@ ament_cmake_auto autoware_cmake + autoware_adapi_v1_msgs autoware_control_msgs autoware_interpolation autoware_vehicle_msgs diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/schema/raw_vehicle_cmd_converter.schema.json b/vehicle/autoware_raw_vehicle_cmd_converter/schema/raw_vehicle_cmd_converter.schema.json index 30642663a39f5..84bc78e1e7ace 100644 --- a/vehicle/autoware_raw_vehicle_cmd_converter/schema/raw_vehicle_cmd_converter.schema.json +++ b/vehicle/autoware_raw_vehicle_cmd_converter/schema/raw_vehicle_cmd_converter.schema.json @@ -180,6 +180,11 @@ "type": "boolean", "default": "true", "description": "convert actuation to steering status or not. Whether to subscribe to actuation_status and calculate and publish steering_status For example, receive the steering wheel angle and calculate the steering wheel angle based on the gear ratio. If false, the vehicle interface must publish steering_status." + }, + "use_vehicle_adaptor": { + "type": "boolean", + "default": "false", + "description": "flag to enable feature that compensates control commands according to vehicle dynamics." } }, "required": [ diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp b/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp index e4cdbe60fd4cd..7624705b15b37 100644 --- a/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp +++ b/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp @@ -40,6 +40,8 @@ RawVehicleCommandConverterNode::RawVehicleCommandConverterNode( // for steering steer controller use_steer_ff_ = declare_parameter("use_steer_ff"); use_steer_fb_ = declare_parameter("use_steer_fb"); + use_vehicle_adaptor_ = declare_parameter("use_vehicle_adaptor", false); + if (convert_accel_cmd_) { if (!accel_map_.readAccelMapFromCSV(csv_path_accel_map, true)) { throw std::invalid_argument("Accel map is invalid."); @@ -116,15 +118,21 @@ RawVehicleCommandConverterNode::RawVehicleCommandConverterNode( debug_pub_steer_pid_ = create_publisher( "/vehicle/raw_vehicle_cmd_converter/debug/steer_pid", 1); + if (use_vehicle_adaptor_) { + pub_compensated_control_cmd_ = create_publisher( + "/vehicle/raw_vehicle_cmd_converter/debug/compensated_control_cmd", 1); + } + logger_configure_ = std::make_unique(this); } void RawVehicleCommandConverterNode::publishActuationCmd() { - if (!current_twist_ptr_ || !control_cmd_ptr_ || !current_steer_ptr_) { + /* check if all necessary data is available */ + if (!current_odometry_ || !control_cmd_ptr_ || !current_steer_ptr_) { RCLCPP_WARN_EXPRESSION( get_logger(), is_debugging_, "some pointers are null: %s, %s, %s", - !current_twist_ptr_ ? "twist" : "", !control_cmd_ptr_ ? "cmd" : "", + !current_odometry_ ? "odometry" : "", !control_cmd_ptr_ ? "cmd" : "", !current_steer_ptr_ ? "steer" : ""); return; } @@ -136,14 +144,34 @@ void RawVehicleCommandConverterNode::publishActuationCmd() } } + /* compensate control command if vehicle adaptor is enabled */ + Control control_cmd = *control_cmd_ptr_; + if (use_vehicle_adaptor_) { + const auto current_accel = sub_accel_.takeData(); + const auto current_operation_mode = sub_operation_mode_.takeData(); + const auto control_horizon = sub_control_horizon_.takeData(); + if (!current_accel || !current_operation_mode || !control_horizon) { + RCLCPP_WARN_EXPRESSION( + get_logger(), is_debugging_, "some pointers are null: %s, %s %s", + !current_accel ? "accel" : "", !current_operation_mode ? "operation_mode" : "", + !control_horizon ? "control_horizon" : ""); + return; + } + control_cmd = vehicle_adaptor_.compensate( + *control_cmd_ptr_, *current_odometry_, *current_accel, *current_steer_ptr_, + *current_operation_mode, *control_horizon); + pub_compensated_control_cmd_->publish(control_cmd); + } + + /* calculate actuation command */ double desired_accel_cmd = 0.0; double desired_brake_cmd = 0.0; double desired_steer_cmd = 0.0; ActuationCommandStamped actuation_cmd; - const double acc = control_cmd_ptr_->longitudinal.acceleration; - const double vel = current_twist_ptr_->twist.linear.x; - const double steer = control_cmd_ptr_->lateral.steering_tire_angle; - const double steer_rate = control_cmd_ptr_->lateral.steering_tire_rotation_rate; + const double acc = control_cmd.longitudinal.acceleration; + const double vel = current_odometry_->twist.twist.linear.x; + const double steer = control_cmd.lateral.steering_tire_angle; + const double steer_rate = control_cmd.lateral.steering_tire_rotation_rate; bool accel_cmd_is_zero = true; if (convert_accel_cmd_) { desired_accel_cmd = calculateAccelMap(vel, acc, accel_cmd_is_zero); @@ -173,7 +201,7 @@ void RawVehicleCommandConverterNode::publishActuationCmd() desired_steer_cmd = calculateSteerFromMap(vel, steer, steer_rate); } actuation_cmd.header.frame_id = "base_link"; - actuation_cmd.header.stamp = control_cmd_ptr_->stamp; + actuation_cmd.header.stamp = control_cmd.stamp; actuation_cmd.actuation.accel_cmd = desired_accel_cmd; actuation_cmd.actuation.brake_cmd = desired_brake_cmd; actuation_cmd.actuation.steer_cmd = desired_steer_cmd; @@ -252,12 +280,7 @@ double RawVehicleCommandConverterNode::calculateBrakeMap( void RawVehicleCommandConverterNode::onControlCmd(const Control::ConstSharedPtr msg) { - const auto odometry_msg = sub_odometry_.takeData(); - if (odometry_msg) { - current_twist_ptr_ = std::make_unique(); - current_twist_ptr_->header = odometry_msg->header; - current_twist_ptr_->twist = odometry_msg->twist.twist; - } + current_odometry_ = sub_odometry_.takeData(); control_cmd_ptr_ = msg; publishActuationCmd(); } @@ -277,14 +300,11 @@ void RawVehicleCommandConverterNode::onActuationStatus( } // calculate steering status from actuation status - const auto odometry_msg = sub_odometry_.takeData(); - if (odometry_msg) { + current_odometry_ = sub_odometry_.takeData(); + if (current_odometry_) { if (convert_steer_cmd_method_.value() == "vgr") { - current_twist_ptr_ = std::make_unique(); - current_twist_ptr_->header = odometry_msg->header; - current_twist_ptr_->twist = odometry_msg->twist.twist; current_steer_ptr_ = std::make_unique(vgr_.calculateSteeringTireState( - current_twist_ptr_->twist.linear.x, actuation_status_ptr_->status.steer_status)); + current_odometry_->twist.twist.linear.x, actuation_status_ptr_->status.steer_status)); Steering steering_msg{}; steering_msg.steering_tire_angle = *current_steer_ptr_; pub_steering_status_->publish(steering_msg); diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/src/vehicle_adaptor/vehicle_adaptor.cpp b/vehicle/autoware_raw_vehicle_cmd_converter/src/vehicle_adaptor/vehicle_adaptor.cpp new file mode 100644 index 0000000000000..7bc9076ae944b --- /dev/null +++ b/vehicle/autoware_raw_vehicle_cmd_converter/src/vehicle_adaptor/vehicle_adaptor.cpp @@ -0,0 +1,32 @@ +// Copyright 2024 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 "autoware_raw_vehicle_cmd_converter/vehicle_adaptor/vehicle_adaptor.hpp" + +#include + +namespace autoware::raw_vehicle_cmd_converter +{ +Control VehicleAdaptor::compensate( + const Control & input_control_cmd, [[maybe_unused]] const Odometry & odometry, + [[maybe_unused]] const AccelWithCovarianceStamped & accel, [[maybe_unused]] const double steering, + [[maybe_unused]] const OperationModeState & operation_mode, + [[maybe_unused]] const ControlHorizon & control_horizon) +{ + // TODO(someone): implement the control command compensation + Control output_control_cmd = input_control_cmd; + std::cerr << "vehicle adaptor: compensate control command" << std::endl; + return output_control_cmd; +} +} // namespace autoware::raw_vehicle_cmd_converter From 29d14e36b2e081f35015fa2c729492cb00a7729b Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Mon, 23 Dec 2024 11:12:54 +0900 Subject: [PATCH 065/334] fix(autoware_bytetrack): fix bugprone-reserved-identifier (#9647) fix: bugprone-reserved-identifier Signed-off-by: kobayu858 --- .../autoware_bytetrack/lib/src/lapjv.cpp | 20 +++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/perception/autoware_bytetrack/lib/src/lapjv.cpp b/perception/autoware_bytetrack/lib/src/lapjv.cpp index 1b8b39ccbb9f7..8949c199f9b21 100644 --- a/perception/autoware_bytetrack/lib/src/lapjv.cpp +++ b/perception/autoware_bytetrack/lib/src/lapjv.cpp @@ -44,7 +44,7 @@ /** Column-reduction and reduction transfer for a dense cost matrix. */ -int_t _ccrrt_dense( +int_t ccrrt_dense( const uint_t n, cost_t * cost[], int_t * free_rows, int_t * x, int_t * y, cost_t * v) { int_t n_free_rows; @@ -108,7 +108,7 @@ int_t _ccrrt_dense( /** Augmenting row reduction for a dense cost matrix. */ -int_t _carr_dense( +int_t carr_dense( const uint_t n, cost_t * cost[], const uint_t n_free_rows, int_t * free_rows, int_t * x, int_t * y, cost_t * v) { @@ -181,7 +181,7 @@ int_t _carr_dense( /** Find columns with minimum d[j] and put them on the SCAN list. */ -uint_t _find_dense( +uint_t find_dense( const uint_t n, uint_t lo, const cost_t * d, int_t * cols, [[maybe_unused]] int_t * y) { uint_t hi = lo + 1; @@ -202,7 +202,7 @@ uint_t _find_dense( // Scan all columns in TODO starting from arbitrary column in SCAN // and try to decrease d of the TODO columns using the SCAN column. -int_t _scan_dense( +int_t scan_dense( const uint_t n, cost_t * cost[], uint_t * plo, uint_t * phi, cost_t * d, int_t * cols, int_t * pred, const int_t * y, const cost_t * v) { @@ -267,7 +267,7 @@ int_t find_path_dense( if (lo == hi) { PRINTF("%d..%d -> find\n", lo, hi); n_ready = lo; - hi = _find_dense(n, lo, d, cols, y); + hi = find_dense(n, lo, d, cols, y); PRINTF("check %d..%d\n", lo, hi); PRINT_INDEX_ARRAY(cols, n); for (uint_t k = lo; k < hi; k++) { @@ -279,7 +279,7 @@ int_t find_path_dense( } if (final_j == -1) { PRINTF("%d..%d -> scan\n", lo, hi); - final_j = _scan_dense(n, cost, &lo, &hi, d, cols, pred, y, v); + final_j = scan_dense(n, cost, &lo, &hi, d, cols, pred, y, v); PRINT_COST_ARRAY(d, n); PRINT_INDEX_ARRAY(cols, n); PRINT_INDEX_ARRAY(pred, n); @@ -304,7 +304,7 @@ int_t find_path_dense( /** Augment for a dense cost matrix. */ -int_t _ca_dense( +int_t ca_dense( const uint_t n, cost_t * cost[], const uint_t n_free_rows, int_t * free_rows, int_t * x, int_t * y, cost_t * v) { @@ -348,14 +348,14 @@ int lapjv_internal(const uint_t n, cost_t * cost[], int_t * x, int_t * y) NEW(free_rows, int_t, n); NEW(v, cost_t, n); - ret = _ccrrt_dense(n, cost, free_rows, x, y, v); + ret = ccrrt_dense(n, cost, free_rows, x, y, v); int i = 0; while (ret > 0 && i < 2) { - ret = _carr_dense(n, cost, ret, free_rows, x, y, v); + ret = carr_dense(n, cost, ret, free_rows, x, y, v); i++; } if (ret > 0) { - ret = _ca_dense(n, cost, ret, free_rows, x, y, v); + ret = ca_dense(n, cost, ret, free_rows, x, y, v); } FREE(v); FREE(free_rows); From 6a749f9f4ae0d2fffc750973c10a66f21ff89c66 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Mon, 23 Dec 2024 12:47:15 +0900 Subject: [PATCH 066/334] fix(autoware_motion_utils): remove clang compiler error (#9713) Signed-off-by: veqcc --- .../test/src/trajectory/benchmark_calcLateralOffset.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/common/autoware_motion_utils/test/src/trajectory/benchmark_calcLateralOffset.cpp b/common/autoware_motion_utils/test/src/trajectory/benchmark_calcLateralOffset.cpp index dc828e885af64..d00053a7b4ff6 100644 --- a/common/autoware_motion_utils/test/src/trajectory/benchmark_calcLateralOffset.cpp +++ b/common/autoware_motion_utils/test/src/trajectory/benchmark_calcLateralOffset.cpp @@ -26,8 +26,6 @@ using autoware::universe_utils::createPoint; using autoware::universe_utils::createQuaternionFromRPY; using autoware_planning_msgs::msg::Trajectory; -constexpr double epsilon = 1e-6; - geometry_msgs::msg::Pose createPose( double x, double y, double z, double roll, double pitch, double yaw) { From 8949358d6b4939711c4202656243cae3e4b74f5e Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 23 Dec 2024 13:07:02 +0900 Subject: [PATCH 067/334] fix(raw_veihicle_converter): fix too long line (#9716) Signed-off-by: kosuke55 --- .../autoware_raw_vehicle_cmd_converter/CMakeLists.txt | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/CMakeLists.txt b/vehicle/autoware_raw_vehicle_cmd_converter/CMakeLists.txt index 909dd336bd282..0d5b6734418c4 100644 --- a/vehicle/autoware_raw_vehicle_cmd_converter/CMakeLists.txt +++ b/vehicle/autoware_raw_vehicle_cmd_converter/CMakeLists.txt @@ -21,7 +21,10 @@ ament_auto_add_library(autoware_raw_vehicle_cmd_converter_node_component SHARED src/node.cpp ) -target_link_libraries(autoware_raw_vehicle_cmd_converter_node_component actuation_map_converter vehicle_adaptor) +target_link_libraries(autoware_raw_vehicle_cmd_converter_node_component + actuation_map_converter + vehicle_adaptor +) rclcpp_components_register_node(autoware_raw_vehicle_cmd_converter_node_component PLUGIN "autoware::raw_vehicle_cmd_converter::RawVehicleCommandConverterNode" @@ -34,7 +37,11 @@ if(BUILD_TESTING) ) set(TEST_RAW_VEHICLE_CMD_CONVERTER_EXE test_autoware_raw_vehicle_cmd_converter) 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 vehicle_adaptor autoware_raw_vehicle_cmd_converter_node_component) + target_link_libraries(${TEST_RAW_VEHICLE_CMD_CONVERTER_EXE} + actuation_map_converter + vehicle_adaptor + autoware_raw_vehicle_cmd_converter_node_component + ) endif() ament_auto_package(INSTALL_TO_SHARE From 9bc173c4f207d10615dfd979dad5180ac22f0571 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Mon, 23 Dec 2024 15:41:19 +0900 Subject: [PATCH 068/334] fix(autoware_universe_utils): fix bug in test (#9710) Signed-off-by: veqcc --- .../test/src/math/test_trigonometry.cpp | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/common/autoware_universe_utils/test/src/math/test_trigonometry.cpp b/common/autoware_universe_utils/test/src/math/test_trigonometry.cpp index df05b698693d6..5c8f96ddee67f 100644 --- a/common/autoware_universe_utils/test/src/math/test_trigonometry.cpp +++ b/common/autoware_universe_utils/test/src/math/test_trigonometry.cpp @@ -18,6 +18,7 @@ #include #include +#include TEST(trigonometry, sin) { @@ -60,11 +61,15 @@ float normalize_angle(double angle) TEST(trigonometry, opencv_fast_atan2) { + std::random_device rd; + std::mt19937 gen(rd()); + + // Generate random x and y between -10.0 and 10.0 as float + std::uniform_real_distribution dis(-10.0f, 10.0f); + for (int i = 0; i < 100; ++i) { - // Generate random x and y between -10 and 10 - std::srand(0); - float x = static_cast(std::rand()) / RAND_MAX * 20.0 - 10.0; - float y = static_cast(std::rand()) / RAND_MAX * 20.0 - 10.0; + const float x = dis(gen); + const float y = dis(gen); float fast_atan = autoware::universe_utils::opencv_fast_atan2(y, x); float std_atan = normalize_angle(std::atan2(y, x)); From dc5120b1c6d05275024c2727d46549be0603df1c Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Mon, 23 Dec 2024 16:00:57 +0900 Subject: [PATCH 069/334] fix(autoware_behavior_velocity_run_out_module): fix bugprone-branch-clone (#9715) fix: bugprone-error Signed-off-by: kobayu858 --- .../autoware_behavior_velocity_run_out_module/src/scene.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp index a32a65a0d8909..efc2d458ae2a7 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp @@ -811,7 +811,7 @@ void RunOutModule::insertVelocityForState( // insert velocity for each state switch (state) { - case State::GO: { + case State::GO: { // NOLINT insertStoppingVelocity(target_obstacle, current_pose, current_vel, current_acc, output_path); break; } From ffbddad7cb3274ab9bb430477413370f08b26c3e Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Mon, 23 Dec 2024 10:15:24 +0300 Subject: [PATCH 070/334] chore: sync files (#9708) Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> Co-authored-by: github-actions --- .pre-commit-config-optional.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.pre-commit-config-optional.yaml b/.pre-commit-config-optional.yaml index 56000d93a8af5..ff325af5e8774 100644 --- a/.pre-commit-config-optional.yaml +++ b/.pre-commit-config-optional.yaml @@ -4,7 +4,7 @@ repos: - repo: https://github.com/tcort/markdown-link-check - rev: v3.13.6 + rev: v3.12.2 hooks: - id: markdown-link-check args: [--quiet, --config=.markdown-link-check.json] From e2a5eeedef043a1377cc76318fd9800c10566fe4 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Mon, 23 Dec 2024 16:36:37 +0900 Subject: [PATCH 071/334] fix(autoware_image_transport_decompressor): fix bugprone-branch-clone (#9724) fix: bugprone-error Signed-off-by: kobayu858 --- .../src/image_transport_decompressor.cpp | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/sensing/autoware_image_transport_decompressor/src/image_transport_decompressor.cpp b/sensing/autoware_image_transport_decompressor/src/image_transport_decompressor.cpp index b1971f892a352..045d1ea564fe6 100644 --- a/sensing/autoware_image_transport_decompressor/src/image_transport_decompressor.cpp +++ b/sensing/autoware_image_transport_decompressor/src/image_transport_decompressor.cpp @@ -107,13 +107,12 @@ void ImageTransportDecompressor::onCompressedImage( } } else { std::string image_encoding; - if (encoding_ == std::string("default")) { - image_encoding = input_compressed_image_msg->format.substr(0, split_pos); - } else if (encoding_ == std::string("rgb8")) { + if (encoding_ == std::string("rgb8")) { image_encoding = "rgb8"; } else if (encoding_ == std::string("bgr8")) { image_encoding = "bgr8"; } else { + // default encoding image_encoding = input_compressed_image_msg->format.substr(0, split_pos); } From 07db1839a94e535e6395c989450f172f61e1b833 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Mon, 23 Dec 2024 16:47:46 +0900 Subject: [PATCH 072/334] fix(autoware_interpolation): remove clang compiler error (#9711) Signed-off-by: veqcc --- .../test/src/test_interpolation_utils.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/common/autoware_interpolation/test/src/test_interpolation_utils.cpp b/common/autoware_interpolation/test/src/test_interpolation_utils.cpp index 2aa41b6fdef00..9131b458dd68b 100644 --- a/common/autoware_interpolation/test/src/test_interpolation_utils.cpp +++ b/common/autoware_interpolation/test/src/test_interpolation_utils.cpp @@ -18,8 +18,6 @@ #include -constexpr double epsilon = 1e-6; - TEST(interpolation_utils, isIncreasing) { // empty From 3bb2df2ebcd2fbf17de50396cb6f04f67f924c29 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Mon, 23 Dec 2024 18:01:31 +0900 Subject: [PATCH 073/334] fix(autoware_planning_evaluator): fix bugprone-exception-escape (#9730) fix: bugprone-exception-escape Signed-off-by: kobayu858 --- .../src/motion_evaluator_node.cpp | 80 ++++++++++--------- .../src/planning_evaluator_node.cpp | 79 +++++++++--------- 2 files changed, 86 insertions(+), 73 deletions(-) diff --git a/evaluator/autoware_planning_evaluator/src/motion_evaluator_node.cpp b/evaluator/autoware_planning_evaluator/src/motion_evaluator_node.cpp index ac6f35179f771..d43aed1ec5687 100644 --- a/evaluator/autoware_planning_evaluator/src/motion_evaluator_node.cpp +++ b/evaluator/autoware_planning_evaluator/src/motion_evaluator_node.cpp @@ -19,6 +19,7 @@ #include #include #include +#include #include #include #include @@ -50,47 +51,52 @@ MotionEvaluatorNode::~MotionEvaluatorNode() if (!output_metrics_) { return; } - - // generate json data - using json = nlohmann::json; - json j; - for (Metric metric : metrics_) { - const std::string base_name = metric_to_str.at(metric) + "/"; - const auto & stat = metrics_calculator_.calculate(metric, accumulated_trajectory_); - if (stat) { - j[base_name + "min"] = stat->min(); - j[base_name + "max"] = stat->max(); - j[base_name + "mean"] = stat->mean(); + try { + // generate json data + using json = nlohmann::json; + json j; + for (Metric metric : metrics_) { + const std::string base_name = metric_to_str.at(metric) + "/"; + const auto & stat = metrics_calculator_.calculate(metric, accumulated_trajectory_); + if (stat) { + j[base_name + "min"] = stat->min(); + j[base_name + "max"] = stat->max(); + j[base_name + "mean"] = stat->mean(); + } } - } - // get output folder - const std::string output_folder_str = - rclcpp::get_logging_directory().string() + "/autoware_metrics"; - if (!std::filesystem::exists(output_folder_str)) { - if (!std::filesystem::create_directories(output_folder_str)) { - RCLCPP_ERROR( - this->get_logger(), "Failed to create directories: %s", output_folder_str.c_str()); - return; + // get output folder + const std::string output_folder_str = + rclcpp::get_logging_directory().string() + "/autoware_metrics"; + if (!std::filesystem::exists(output_folder_str)) { + if (!std::filesystem::create_directories(output_folder_str)) { + RCLCPP_ERROR( + this->get_logger(), "Failed to create directories: %s", output_folder_str.c_str()); + return; + } } - } - // get time stamp - std::time_t now_time_t = std::chrono::system_clock::to_time_t(std::chrono::system_clock::now()); - std::tm * local_time = std::localtime(&now_time_t); - std::ostringstream oss; - oss << std::put_time(local_time, "%Y-%m-%d-%H-%M-%S"); - std::string cur_time_str = oss.str(); - - // Write metrics .json to file - const std::string output_file_str = - output_folder_str + "/autoware_motion_evaluator-" + cur_time_str + ".json"; - std::ofstream f(output_file_str); - if (f.is_open()) { - f << j.dump(4); - f.close(); - } else { - RCLCPP_ERROR(this->get_logger(), "Failed to open file: %s", output_file_str.c_str()); + // get time stamp + std::time_t now_time_t = std::chrono::system_clock::to_time_t(std::chrono::system_clock::now()); + std::tm * local_time = std::localtime(&now_time_t); + std::ostringstream oss; + oss << std::put_time(local_time, "%Y-%m-%d-%H-%M-%S"); + std::string cur_time_str = oss.str(); + + // Write metrics .json to file + const std::string output_file_str = + output_folder_str + "/autoware_motion_evaluator-" + cur_time_str + ".json"; + std::ofstream f(output_file_str); + if (f.is_open()) { + f << j.dump(4); + f.close(); + } else { + RCLCPP_ERROR(this->get_logger(), "Failed to open file: %s", output_file_str.c_str()); + } + } catch (const std::exception & e) { + std::cerr << "Exception in MotionEvaluatorNode destructor: " << e.what() << std::endl; + } catch (...) { + std::cerr << "Unknown exception in MotionEvaluatorNode destructor" << std::endl; } } diff --git a/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp b/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp index a61e56cd532ad..9318ec1db4234 100644 --- a/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp +++ b/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp @@ -25,6 +25,7 @@ #include #include #include +#include #include #include #include @@ -74,45 +75,51 @@ PlanningEvaluatorNode::~PlanningEvaluatorNode() return; } - // generate json data - using json = nlohmann::json; - json j; - for (Metric metric : metrics_) { - const std::string base_name = metric_to_str.at(metric) + "/"; - j[base_name + "min"] = metric_accumulators_[static_cast(metric)][0].min(); - j[base_name + "max"] = metric_accumulators_[static_cast(metric)][1].max(); - j[base_name + "mean"] = metric_accumulators_[static_cast(metric)][2].mean(); - j[base_name + "count"] = metric_accumulators_[static_cast(metric)][2].count(); - j[base_name + "description"] = metric_descriptions.at(metric); - } + try { + // generate json data + using json = nlohmann::json; + json j; + for (Metric metric : metrics_) { + const std::string base_name = metric_to_str.at(metric) + "/"; + j[base_name + "min"] = metric_accumulators_[static_cast(metric)][0].min(); + j[base_name + "max"] = metric_accumulators_[static_cast(metric)][1].max(); + j[base_name + "mean"] = metric_accumulators_[static_cast(metric)][2].mean(); + j[base_name + "count"] = metric_accumulators_[static_cast(metric)][2].count(); + j[base_name + "description"] = metric_descriptions.at(metric); + } - // get output folder - const std::string output_folder_str = - rclcpp::get_logging_directory().string() + "/autoware_metrics"; - if (!std::filesystem::exists(output_folder_str)) { - if (!std::filesystem::create_directories(output_folder_str)) { - RCLCPP_ERROR( - this->get_logger(), "Failed to create directories: %s", output_folder_str.c_str()); - return; + // get output folder + const std::string output_folder_str = + rclcpp::get_logging_directory().string() + "/autoware_metrics"; + if (!std::filesystem::exists(output_folder_str)) { + if (!std::filesystem::create_directories(output_folder_str)) { + RCLCPP_ERROR( + this->get_logger(), "Failed to create directories: %s", output_folder_str.c_str()); + return; + } } - } - // get time stamp - std::time_t now_time_t = std::chrono::system_clock::to_time_t(std::chrono::system_clock::now()); - std::tm * local_time = std::localtime(&now_time_t); - std::ostringstream oss; - oss << std::put_time(local_time, "%Y-%m-%d-%H-%M-%S"); - std::string cur_time_str = oss.str(); - - // Write metrics .json to file - const std::string output_file_str = - output_folder_str + "/autoware_planning_evaluator-" + cur_time_str + ".json"; - std::ofstream f(output_file_str); - if (f.is_open()) { - f << j.dump(4); - f.close(); - } else { - RCLCPP_ERROR(this->get_logger(), "Failed to open file: %s", output_file_str.c_str()); + // get time stamp + std::time_t now_time_t = std::chrono::system_clock::to_time_t(std::chrono::system_clock::now()); + std::tm * local_time = std::localtime(&now_time_t); + std::ostringstream oss; + oss << std::put_time(local_time, "%Y-%m-%d-%H-%M-%S"); + std::string cur_time_str = oss.str(); + + // Write metrics .json to file + const std::string output_file_str = + output_folder_str + "/autoware_planning_evaluator-" + cur_time_str + ".json"; + std::ofstream f(output_file_str); + if (f.is_open()) { + f << j.dump(4); + f.close(); + } else { + RCLCPP_ERROR(this->get_logger(), "Failed to open file: %s", output_file_str.c_str()); + } + } catch (const std::exception & e) { + std::cerr << "Exception in MotionEvaluatorNode destructor: " << e.what() << std::endl; + } catch (...) { + std::cerr << "Unknown exception in MotionEvaluatorNode destructor" << std::endl; } } From 97bc5a7d31574c1384ed3bae07910ab1ed0bcdeb Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> Date: Mon, 23 Dec 2024 18:24:08 +0900 Subject: [PATCH 074/334] feat(planning_evaluator): add evaluation feature of trajectory lateral displacement (#9718) * feat(planning_evaluator): add evaluation feature of trajectory lateral displacement Signed-off-by: Kyoichi Sugahara * feat(metrics_calculator): implement lookahead trajectory calculation and remove deprecated method Signed-off-by: Kyoichi Sugahara * fix(planning_evaluator): rename lateral_trajectory_displacement to trajectory_lateral_displacement for consistency Signed-off-by: Kyoichi Sugahara --------- Signed-off-by: Kyoichi Sugahara --- .../autoware_planning_evaluator/README.md | 1 + .../config/planning_evaluator.param.yaml | 3 +- .../planning_evaluator/metrics/metric.hpp | 4 ++ .../metrics/metrics_utils.hpp | 24 +++++++++ .../metrics/stability_metrics.hpp | 18 +++++++ .../planning_evaluator/metrics_calculator.hpp | 15 ++---- .../planning_evaluator/parameters.hpp | 1 + .../src/metrics/metrics_utils.cpp | 49 +++++++++++++++++ .../src/metrics/stability_metrics.cpp | 44 +++++++++++++++ .../src/metrics_calculator.cpp | 54 ++++++------------- .../src/planning_evaluator_node.cpp | 4 +- 11 files changed, 164 insertions(+), 53 deletions(-) diff --git a/evaluator/autoware_planning_evaluator/README.md b/evaluator/autoware_planning_evaluator/README.md index 4fcdf4d7e55fd..b9dd3201a2541 100644 --- a/evaluator/autoware_planning_evaluator/README.md +++ b/evaluator/autoware_planning_evaluator/README.md @@ -13,6 +13,7 @@ Metrics are calculated using the following information: - the previous trajectory `T(-1)`. - the _reference_ trajectory assumed to be used as the reference to plan `T(0)`. - the current ego pose. +- the current ego odometry. - the set of objects in the environment. These information are maintained by an instance of class `MetricsCalculator` diff --git a/evaluator/autoware_planning_evaluator/config/planning_evaluator.param.yaml b/evaluator/autoware_planning_evaluator/config/planning_evaluator.param.yaml index e00851de63b9c..73c1f3dfded09 100644 --- a/evaluator/autoware_planning_evaluator/config/planning_evaluator.param.yaml +++ b/evaluator/autoware_planning_evaluator/config/planning_evaluator.param.yaml @@ -14,7 +14,7 @@ - lateral_deviation - yaw_deviation - velocity_deviation - - lateral_trajectory_displacement + - trajectory_lateral_displacement - stability - stability_frechet - obstacle_distance @@ -25,6 +25,7 @@ trajectory: min_point_dist_m: 0.1 # [m] minimum distance between two successive points to use for angle calculation + evaluation_time_s: 5.0 # [s] time duration for trajectory evaluation in seconds lookahead: max_dist_m: 5.0 # [m] maximum distance from ego along the trajectory to use for calculation max_time_s: 3.0 # [s] maximum time ahead of ego along the trajectory to use for calculation diff --git a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/metric.hpp b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/metric.hpp index 13dad65b239b1..22b365881ce28 100644 --- a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/metric.hpp +++ b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/metric.hpp @@ -40,6 +40,7 @@ enum class Metric { lateral_trajectory_displacement, stability, stability_frechet, + trajectory_lateral_displacement, obstacle_distance, obstacle_ttc, modified_goal_longitudinal_deviation, @@ -66,6 +67,7 @@ static const std::unordered_map str_to_metric = { {"lateral_trajectory_displacement", Metric::lateral_trajectory_displacement}, {"stability", Metric::stability}, {"stability_frechet", Metric::stability_frechet}, + {"trajectory_lateral_displacement", Metric::trajectory_lateral_displacement}, {"obstacle_distance", Metric::obstacle_distance}, {"obstacle_ttc", Metric::obstacle_ttc}, {"modified_goal_longitudinal_deviation", Metric::modified_goal_longitudinal_deviation}, @@ -87,6 +89,7 @@ static const std::unordered_map metric_to_str = { {Metric::lateral_trajectory_displacement, "lateral_trajectory_displacement"}, {Metric::stability, "stability"}, {Metric::stability_frechet, "stability_frechet"}, + {Metric::trajectory_lateral_displacement, "trajectory_lateral_displacement"}, {Metric::obstacle_distance, "obstacle_distance"}, {Metric::obstacle_ttc, "obstacle_ttc"}, {Metric::modified_goal_longitudinal_deviation, "modified_goal_longitudinal_deviation"}, @@ -109,6 +112,7 @@ static const std::unordered_map metric_descriptions = { {Metric::lateral_trajectory_displacement, "Nearest Pose Lateral Deviation[m]"}, {Metric::stability, "Stability[m]"}, {Metric::stability_frechet, "StabilityFrechet[m]"}, + {Metric::trajectory_lateral_displacement, "Trajectory_lateral_displacement[m]"}, {Metric::obstacle_distance, "Obstacle_distance[m]"}, {Metric::obstacle_ttc, "Obstacle_time_to_collision[s]"}, {Metric::modified_goal_longitudinal_deviation, "Modified_goal_longitudinal_deviation[m]"}, diff --git a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/metrics_utils.hpp b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/metrics_utils.hpp index 0006e49c3338a..9f2b99007af7d 100644 --- a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/metrics_utils.hpp +++ b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/metrics_utils.hpp @@ -25,6 +25,7 @@ namespace metrics namespace utils { using autoware_planning_msgs::msg::Trajectory; +using geometry_msgs::msg::Pose; /** * @brief find the index in the trajectory at the given distance of the given index @@ -35,6 +36,29 @@ using autoware_planning_msgs::msg::Trajectory; */ size_t getIndexAfterDistance(const Trajectory & traj, const size_t curr_id, const double distance); +/** + * @brief trim a trajectory from the current ego pose to some fixed time or distance + * @param [in] traj input trajectory to trim + * @param [in] max_dist_m [m] maximum distance ahead of the ego pose + * @param [in] max_time_s [s] maximum time ahead of the ego pose + * @return sub-trajectory starting from the ego pose and of maximum length max_dist_m, maximum + * duration max_time_s + */ +Trajectory get_lookahead_trajectory( + const Trajectory & traj, const Pose & ego_pose, const double max_dist_m, const double max_time_s); + +/** + * @brief calculate the total distance from ego position to the end of trajectory + * @details finds the nearest point to ego position on the trajectory and calculates + * the cumulative distance by summing up the distances between consecutive points + * from that position to the end of the trajectory. + * + * @param [in] traj input trajectory to calculate distance along + * @param [in] ego_pose current ego vehicle pose + * @return total distance from ego position to trajectory end in meters + */ +double calc_lookahead_trajectory_distance(const Trajectory & traj, const Pose & ego_pose); + } // namespace utils } // namespace metrics } // namespace planning_diagnostics diff --git a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/stability_metrics.hpp b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/stability_metrics.hpp index 38f388feeadda..69df00b26551b 100644 --- a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/stability_metrics.hpp +++ b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/stability_metrics.hpp @@ -18,6 +18,7 @@ #include "autoware/universe_utils/math/accumulator.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" +#include namespace planning_diagnostics { @@ -42,6 +43,23 @@ Accumulator calcFrechetDistance(const Trajectory & traj1, const Trajecto */ Accumulator calcLateralDistance(const Trajectory & traj1, const Trajectory & traj2); +/** + * @brief calculate the total lateral displacement between two trajectories + * @details Evaluates the cumulative absolute lateral displacement by sampling points + * along the first trajectory and measuring their offset from the second trajectory. + * The evaluation section length is determined by the ego vehicle's velocity and + * the specified evaluation time. + * + * @param traj1 first trajectory to compare + * @param traj2 second trajectory to compare against + * @param [in] ego_odom current ego vehicle odometry containing pose and velocity + * @param [in] trajectory_eval_time_s time duration for trajectory evaluation in seconds + * @return statistical accumulator containing the total lateral displacement + */ +Accumulator calcTrajectoryLateralDisplacement( + const Trajectory traj1, const Trajectory traj2, const nav_msgs::msg::Odometry & ego_odom, + const double trajectory_eval_time_s); + } // namespace metrics } // namespace planning_diagnostics diff --git a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics_calculator.hpp b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics_calculator.hpp index 97d23cad10af2..fe9d9eaf4278b 100644 --- a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics_calculator.hpp +++ b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics_calculator.hpp @@ -23,6 +23,7 @@ #include "autoware_planning_msgs/msg/trajectory.hpp" #include "autoware_planning_msgs/msg/trajectory_point.hpp" #include "geometry_msgs/msg/pose.hpp" +#include #include @@ -74,7 +75,7 @@ class MetricsCalculator * @brief set the ego pose * @param [in] traj input previous trajectory */ - void setEgoPose(const geometry_msgs::msg::Pose & pose); + void setEgoPose(const nav_msgs::msg::Odometry & ego_odometry); /** * @brief get the ego pose @@ -83,23 +84,13 @@ class MetricsCalculator Pose getEgoPose(); private: - /** - * @brief trim a trajectory from the current ego pose to some fixed time or distance - * @param [in] traj input trajectory to trim - * @param [in] max_dist_m [m] maximum distance ahead of the ego pose - * @param [in] max_time_s [s] maximum time ahead of the ego pose - * @return sub-trajectory starting from the ego pose and of maximum length max_dist_m, maximum - * duration max_time_s - */ - Trajectory getLookaheadTrajectory( - const Trajectory & traj, const double max_dist_m, const double max_time_s) const; - Trajectory reference_trajectory_; Trajectory reference_trajectory_lookahead_; Trajectory previous_trajectory_; Trajectory previous_trajectory_lookahead_; PredictedObjects dynamic_objects_; geometry_msgs::msg::Pose ego_pose_; + nav_msgs::msg::Odometry ego_odometry_; PoseWithUuidStamped modified_goal_; }; // class MetricsCalculator diff --git a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/parameters.hpp b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/parameters.hpp index cd894fecc2331..94920195ee89c 100644 --- a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/parameters.hpp +++ b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/parameters.hpp @@ -31,6 +31,7 @@ struct Parameters struct { double min_point_dist_m = 0.1; + double evaluation_time_s = 5.0; struct { double max_dist_m = 5.0; diff --git a/evaluator/autoware_planning_evaluator/src/metrics/metrics_utils.cpp b/evaluator/autoware_planning_evaluator/src/metrics/metrics_utils.cpp index 669afdd7229b0..7451264f037a6 100644 --- a/evaluator/autoware_planning_evaluator/src/metrics/metrics_utils.cpp +++ b/evaluator/autoware_planning_evaluator/src/metrics/metrics_utils.cpp @@ -12,8 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "autoware/motion_utils/trajectory/trajectory.hpp" #include "autoware/planning_evaluator/metrics/trajectory_metrics.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" + namespace planning_diagnostics { namespace metrics @@ -23,6 +25,7 @@ namespace utils using autoware::universe_utils::calcDistance2d; using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; +using geometry_msgs::msg::Pose; size_t getIndexAfterDistance(const Trajectory & traj, const size_t curr_id, const double distance) { @@ -41,6 +44,52 @@ size_t getIndexAfterDistance(const Trajectory & traj, const size_t curr_id, cons return target_id; } +Trajectory get_lookahead_trajectory( + const Trajectory & traj, const Pose & ego_pose, const double max_dist_m, const double max_time_s) +{ + if (traj.points.empty()) { + return traj; + } + + const auto ego_index = + autoware::motion_utils::findNearestSegmentIndex(traj.points, ego_pose.position); + Trajectory lookahead_traj; + lookahead_traj.header = traj.header; + double dist = 0.0; + double time = 0.0; + auto curr_point_it = std::next(traj.points.begin(), ego_index); + auto prev_point_it = curr_point_it; + while (curr_point_it != traj.points.end() && dist <= max_dist_m && time <= max_time_s) { + lookahead_traj.points.push_back(*curr_point_it); + const auto d = autoware::universe_utils::calcDistance2d( + prev_point_it->pose.position, curr_point_it->pose.position); + dist += d; + if (prev_point_it->longitudinal_velocity_mps != 0.0) { + time += d / std::abs(prev_point_it->longitudinal_velocity_mps); + } + prev_point_it = curr_point_it; + ++curr_point_it; + } + return lookahead_traj; +} + +double calc_lookahead_trajectory_distance(const Trajectory & traj, const Pose & ego_pose) +{ + const auto ego_index = + autoware::motion_utils::findNearestSegmentIndex(traj.points, ego_pose.position); + double dist = 0.0; + auto curr_point_it = std::next(traj.points.begin(), ego_index); + auto prev_point_it = curr_point_it; + for (size_t i = 0; i < traj.points.size(); ++i) { + const auto d = autoware::universe_utils::calcDistance2d( + prev_point_it->pose.position, curr_point_it->pose.position); + dist += d; + prev_point_it = curr_point_it; + ++curr_point_it; + } + + return dist; +} } // namespace utils } // namespace metrics } // namespace planning_diagnostics diff --git a/evaluator/autoware_planning_evaluator/src/metrics/stability_metrics.cpp b/evaluator/autoware_planning_evaluator/src/metrics/stability_metrics.cpp index e6ede0d07b9b3..b99a4ebd20050 100644 --- a/evaluator/autoware_planning_evaluator/src/metrics/stability_metrics.cpp +++ b/evaluator/autoware_planning_evaluator/src/metrics/stability_metrics.cpp @@ -14,7 +14,9 @@ #include "autoware/planning_evaluator/metrics/stability_metrics.hpp" +#include "autoware/motion_utils/resample/resample.hpp" #include "autoware/motion_utils/trajectory/trajectory.hpp" +#include "autoware/planning_evaluator/metrics/metrics_utils.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" #include @@ -96,5 +98,47 @@ Accumulator calcLateralDistance(const Trajectory & traj1, const Trajecto return stat; } +Accumulator calcTrajectoryLateralDisplacement( + const Trajectory traj1, const Trajectory traj2, const nav_msgs::msg::Odometry & ego_odom, + const double trajectory_eval_time_s) +{ + Accumulator stat; + + if (traj1.points.empty() || traj2.points.empty()) { + return stat; + } + + const double ego_velocity = + std::hypot(ego_odom.twist.twist.linear.x, ego_odom.twist.twist.linear.y); + + const double evaluation_section_length = trajectory_eval_time_s * std::abs(ego_velocity); + + const double traj1_lookahead_distance = + utils::calc_lookahead_trajectory_distance(traj1, ego_odom.pose.pose); + const double traj2_lookahead_distance = + utils::calc_lookahead_trajectory_distance(traj2, ego_odom.pose.pose); + + if ( + traj1_lookahead_distance < evaluation_section_length || + traj2_lookahead_distance < evaluation_section_length) { + return stat; + } + + constexpr double num_evaluation_points = 10.0; + const double interval = evaluation_section_length / num_evaluation_points; + + const auto resampled_traj1 = autoware::motion_utils::resampleTrajectory( + utils::get_lookahead_trajectory( + traj1, ego_odom.pose.pose, evaluation_section_length, trajectory_eval_time_s), + interval); + + for (const auto & point : resampled_traj1.points) { + const auto p0 = autoware::universe_utils::getPoint(point); + const double dist = autoware::motion_utils::calcLateralOffset(traj2.points, p0); + stat.add(std::abs(dist)); + } + return stat; +} + } // namespace metrics } // namespace planning_diagnostics diff --git a/evaluator/autoware_planning_evaluator/src/metrics_calculator.cpp b/evaluator/autoware_planning_evaluator/src/metrics_calculator.cpp index b7676c2fdab6c..201fbcba0e9f7 100644 --- a/evaluator/autoware_planning_evaluator/src/metrics_calculator.cpp +++ b/evaluator/autoware_planning_evaluator/src/metrics_calculator.cpp @@ -16,6 +16,7 @@ #include "autoware/motion_utils/trajectory/trajectory.hpp" #include "autoware/planning_evaluator/metrics/deviation_metrics.hpp" +#include "autoware/planning_evaluator/metrics/metrics_utils.hpp" #include "autoware/planning_evaluator/metrics/obstacle_metrics.hpp" #include "autoware/planning_evaluator/metrics/stability_metrics.hpp" #include "autoware/planning_evaluator/metrics/trajectory_metrics.hpp" @@ -53,20 +54,23 @@ std::optional> MetricsCalculator::calculate( return metrics::calcLateralTrajectoryDisplacement(previous_trajectory_, traj, ego_pose_); case Metric::stability_frechet: return metrics::calcFrechetDistance( - getLookaheadTrajectory( - previous_trajectory_, parameters.trajectory.lookahead.max_dist_m, + metrics::utils::get_lookahead_trajectory( + previous_trajectory_, ego_pose_, parameters.trajectory.lookahead.max_dist_m, parameters.trajectory.lookahead.max_time_s), - getLookaheadTrajectory( - traj, parameters.trajectory.lookahead.max_dist_m, + metrics::utils::get_lookahead_trajectory( + traj, ego_pose_, parameters.trajectory.lookahead.max_dist_m, parameters.trajectory.lookahead.max_time_s)); case Metric::stability: return metrics::calcLateralDistance( - getLookaheadTrajectory( - previous_trajectory_, parameters.trajectory.lookahead.max_dist_m, + metrics::utils::get_lookahead_trajectory( + previous_trajectory_, ego_pose_, parameters.trajectory.lookahead.max_dist_m, parameters.trajectory.lookahead.max_time_s), - getLookaheadTrajectory( - traj, parameters.trajectory.lookahead.max_dist_m, + metrics::utils::get_lookahead_trajectory( + traj, ego_pose_, parameters.trajectory.lookahead.max_dist_m, parameters.trajectory.lookahead.max_time_s)); + case Metric::trajectory_lateral_displacement: + return metrics::calcTrajectoryLateralDisplacement( + previous_trajectory_, traj, ego_odometry_, parameters.trajectory.evaluation_time_s); case Metric::obstacle_distance: return metrics::calcDistanceToObstacle(dynamic_objects_, traj); case Metric::obstacle_ttc: @@ -107,9 +111,10 @@ void MetricsCalculator::setPredictedObjects(const PredictedObjects & objects) dynamic_objects_ = objects; } -void MetricsCalculator::setEgoPose(const geometry_msgs::msg::Pose & pose) +void MetricsCalculator::setEgoPose(const nav_msgs::msg::Odometry & ego_odometry) { - ego_pose_ = pose; + ego_pose_ = ego_odometry.pose.pose; + ego_odometry_ = ego_odometry; } Pose MetricsCalculator::getEgoPose() @@ -117,33 +122,4 @@ Pose MetricsCalculator::getEgoPose() return ego_pose_; } -Trajectory MetricsCalculator::getLookaheadTrajectory( - const Trajectory & traj, const double max_dist_m, const double max_time_s) const -{ - if (traj.points.empty()) { - return traj; - } - - const auto ego_index = - autoware::motion_utils::findNearestSegmentIndex(traj.points, ego_pose_.position); - Trajectory lookahead_traj; - lookahead_traj.header = traj.header; - double dist = 0.0; - double time = 0.0; - auto curr_point_it = std::next(traj.points.begin(), ego_index); - auto prev_point_it = curr_point_it; - while (curr_point_it != traj.points.end() && dist <= max_dist_m && time <= max_time_s) { - lookahead_traj.points.push_back(*curr_point_it); - const auto d = autoware::universe_utils::calcDistance2d( - prev_point_it->pose.position, curr_point_it->pose.position); - dist += d; - if (prev_point_it->longitudinal_velocity_mps != 0.0) { - time += d / std::abs(prev_point_it->longitudinal_velocity_mps); - } - prev_point_it = curr_point_it; - ++curr_point_it; - } - return lookahead_traj; -} - } // namespace planning_diagnostics diff --git a/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp b/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp index 9318ec1db4234..5889f15e48390 100644 --- a/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp +++ b/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp @@ -51,6 +51,8 @@ PlanningEvaluatorNode::PlanningEvaluatorNode(const rclcpp::NodeOptions & node_op declare_parameter("trajectory.lookahead.max_dist_m"); metrics_calculator_.parameters.trajectory.lookahead.max_time_s = declare_parameter("trajectory.lookahead.max_time_s"); + metrics_calculator_.parameters.trajectory.evaluation_time_s = + declare_parameter("trajectory.evaluation_time_s"); metrics_calculator_.parameters.obstacle.dist_thr_m = declare_parameter("obstacle.dist_thr_m"); @@ -350,7 +352,7 @@ void PlanningEvaluatorNode::onModifiedGoal( void PlanningEvaluatorNode::onOdometry(const Odometry::ConstSharedPtr odometry_msg) { if (!odometry_msg) return; - metrics_calculator_.setEgoPose(odometry_msg->pose.pose); + metrics_calculator_.setEgoPose(*odometry_msg); { getRouteData(); if (route_handler_.isHandlerReady() && odometry_msg) { From 4045fb31d1edeebea6aafb74cf3229f8c73d44af Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Mon, 23 Dec 2024 21:37:57 +0900 Subject: [PATCH 075/334] fix(autoware_image_diagnostics): fix bugprone-branch-clone (#9723) fix: bugprone-error Signed-off-by: kobayu858 --- .../src/image_diagnostics_node.cpp | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/sensing/autoware_image_diagnostics/src/image_diagnostics_node.cpp b/sensing/autoware_image_diagnostics/src/image_diagnostics_node.cpp index 681e9ae70a89c..1625cba5b72aa 100644 --- a/sensing/autoware_image_diagnostics/src/image_diagnostics_node.cpp +++ b/sensing/autoware_image_diagnostics/src/image_diagnostics_node.cpp @@ -171,11 +171,9 @@ void ImageDiagNode::ImageChecker(const sensor_msgs::msg::Image::ConstSharedPtr i cv::rectangle( diag_block_image, cv::Point(x, y), cv::Point(x + block_size_h, y + block_size_v), state_color_map_["BLOCKAGE"], -1, cv::LINE_AA); - } else if (region_state_vec[j] == Image_State::LOW_VIS) { - cv::rectangle( - diag_block_image, cv::Point(x, y), cv::Point(x + block_size_h, y + block_size_v), - state_color_map_["BACKLIGHT"], -1, cv::LINE_AA); - } else if (region_state_vec[j] == Image_State::BACKLIGHT) { + } else if ( + region_state_vec[j] == Image_State::LOW_VIS || + region_state_vec[j] == Image_State::BACKLIGHT) { cv::rectangle( diag_block_image, cv::Point(x, y), cv::Point(x + block_size_h, y + block_size_v), state_color_map_["BACKLIGHT"], -1, cv::LINE_AA); From 308eefb1c75335d831104721a4a0ea6c0fd3d6f8 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Tue, 24 Dec 2024 08:48:02 +0900 Subject: [PATCH 076/334] refactor(autoware_multi_object_tracker): define a new internal object class (#9706) * feat: Add dynamic_object.hpp to object_model directory Signed-off-by: Taekjin LEE * chore: Update autoware_perception_msgs include statements in association.hpp and dynamic_object.hpp Signed-off-by: Taekjin LEE * fix: replace object message type to the DynamicObject type Signed-off-by: Taekjin LEE * chore: Update autoware_perception_msgs include statements in association.hpp and dynamic_object.hpp Signed-off-by: Taekjin LEE * chore: add channel index to the DynamicObjects Signed-off-by: Taekjin LEE * Revert "chore: add channel index to the DynamicObjects" This reverts commit c7e73f08a8d17b5b085dd330dbf187aabbec6879. Signed-off-by: Taekjin LEE * fix: replace trackedobject in the process Signed-off-by: Taekjin LEE * fix: Replace transformObjects with shapes::transformObjects for object transformation Signed-off-by: Taekjin LEE * chore: add channel index to the DynamicObjects Signed-off-by: Taekjin LEE * feat: separate shape related functions Signed-off-by: Taekjin LEE * chore: clean up utils.hpp Signed-off-by: Taekjin LEE * chore: Update function signatures to use DynamicObjectList instead of DynamicObjects Signed-off-by: Taekjin LEE * chore: Add channel index to DynamicObject and DynamicObjectList Signed-off-by: Taekjin LEE * chore: Refactor processor and debugger classes to remove channel_index parameter Signed-off-by: Taekjin LEE * chore: Refactor multiple_vehicle_tracker.cpp and debugger.cpp Signed-off-by: Taekjin LEE * Refactor object tracker classes to remove self_transform parameter Signed-off-by: Taekjin LEE * Refactor object tracker classes to use shapes namespace for shape-related functions Signed-off-by: Taekjin LEE * Refactor object tracker classes to use types.hpp for object model types Signed-off-by: Taekjin LEE * Refactor object tracker classes to remove unused utils.hpp Signed-off-by: Taekjin LEE * Refactor object tracker classes to use types.hpp for object model types Signed-off-by: Taekjin LEE * chore: rename to types.cpp Signed-off-by: Taekjin LEE * rename getDynamicObject to toDynamicObject Signed-off-by: Taekjin LEE * Update perception/autoware_multi_object_tracker/lib/object_model/shapes.cpp Co-authored-by: Yukihiro Saito --------- Signed-off-by: Taekjin LEE Co-authored-by: Yukihiro Saito --- .../CMakeLists.txt | 2 + .../association/association.hpp | 4 +- .../object_model/shapes.hpp | 57 ++++ .../object_model/types.hpp | 88 ++++++ .../tracker/model/bicycle_tracker.hpp | 24 +- .../model/multiple_vehicle_tracker.hpp | 13 +- .../tracker/model/pass_through_tracker.hpp | 18 +- .../model/pedestrian_and_bicycle_tracker.hpp | 14 +- .../tracker/model/pedestrian_tracker.hpp | 24 +- .../tracker/model/tracker_base.hpp | 18 +- .../tracker/model/unknown_tracker.hpp | 25 +- .../tracker/model/vehicle_tracker.hpp | 25 +- .../uncertainty/uncertainty_processor.hpp | 11 +- .../lib/association/association.cpp | 17 +- .../utils.hpp => lib/object_model/shapes.cpp} | 297 +++++++++++------- .../lib/object_model/types.cpp | 101 ++++++ .../lib/tracker/model/bicycle_tracker.cpp | 41 ++- .../model/multiple_vehicle_tracker.cpp | 18 +- .../tracker/model/pass_through_tracker.cpp | 18 +- .../model/pedestrian_and_bicycle_tracker.cpp | 14 +- .../lib/tracker/model/pedestrian_tracker.cpp | 39 +-- .../lib/tracker/model/tracker_base.cpp | 10 +- .../lib/tracker/model/unknown_tracker.cpp | 36 +-- .../lib/tracker/model/vehicle_tracker.cpp | 50 ++- .../motion_model/bicycle_motion_model.cpp | 7 +- .../motion_model/ctrv_motion_model.cpp | 7 +- .../tracker/motion_model/cv_motion_model.cpp | 7 +- .../lib/uncertainty/uncertainty_processor.cpp | 18 +- .../src/debugger/debug_object.cpp | 7 +- .../src/debugger/debug_object.hpp | 3 +- .../src/debugger/debugger.cpp | 6 +- .../src/debugger/debugger.hpp | 3 +- .../src/multi_object_tracker_node.cpp | 35 +-- .../src/multi_object_tracker_node.hpp | 12 +- .../src/processor/input_manager.cpp | 28 +- .../src/processor/input_manager.hpp | 12 +- .../src/processor/processor.cpp | 66 ++-- .../src/processor/processor.hpp | 13 +- 38 files changed, 723 insertions(+), 465 deletions(-) create mode 100644 perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/object_model/shapes.hpp create mode 100644 perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/object_model/types.hpp rename perception/autoware_multi_object_tracker/{include/autoware/multi_object_tracker/utils/utils.hpp => lib/object_model/shapes.cpp} (59%) create mode 100644 perception/autoware_multi_object_tracker/lib/object_model/types.cpp diff --git a/perception/autoware_multi_object_tracker/CMakeLists.txt b/perception/autoware_multi_object_tracker/CMakeLists.txt index 298b6605192a5..fcea50235bf0d 100644 --- a/perception/autoware_multi_object_tracker/CMakeLists.txt +++ b/perception/autoware_multi_object_tracker/CMakeLists.txt @@ -30,6 +30,8 @@ set(${PROJECT_NAME}_src set(${PROJECT_NAME}_lib lib/association/association.cpp lib/association/mu_successive_shortest_path/mu_ssp.cpp + lib/object_model/types.cpp + lib/object_model/shapes.cpp lib/tracker/motion_model/motion_model_base.cpp lib/tracker/motion_model/bicycle_motion_model.cpp # cspell: ignore ctrv diff --git a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/association/association.hpp b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/association/association.hpp index 2c12341d0aa67..b92e17987eb5f 100644 --- a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/association/association.hpp +++ b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/association/association.hpp @@ -27,7 +27,7 @@ #include #include -#include "autoware_perception_msgs/msg/detected_objects.hpp" +#include #include #include @@ -58,7 +58,7 @@ class DataAssociation const Eigen::MatrixXd & src, std::unordered_map & direct_assignment, std::unordered_map & reverse_assignment); Eigen::MatrixXd calcScoreMatrix( - const autoware_perception_msgs::msg::DetectedObjects & measurements, + const types::DynamicObjectList & measurements, const std::list> & trackers); virtual ~DataAssociation() {} }; diff --git a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/object_model/shapes.hpp b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/object_model/shapes.hpp new file mode 100644 index 0000000000000..d399f356136fc --- /dev/null +++ b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/object_model/shapes.hpp @@ -0,0 +1,57 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// +// Author: v1.0 Taekjin Lee + +#ifndef AUTOWARE__MULTI_OBJECT_TRACKER__OBJECT_MODEL__SHAPES_HPP_ +#define AUTOWARE__MULTI_OBJECT_TRACKER__OBJECT_MODEL__SHAPES_HPP_ + +#include "autoware/multi_object_tracker/object_model/types.hpp" + +#include + +#include + +#include + +namespace autoware::multi_object_tracker +{ +namespace shapes +{ +bool transformObjects( + const types::DynamicObjectList & input_msg, const std::string & target_frame_id, + const tf2_ros::Buffer & tf_buffer, types::DynamicObjectList & output_msg); + +double get2dIoU( + const types::DynamicObject & source_object, const types::DynamicObject & target_object, + const double min_union_area = 0.01); + +bool convertConvexHullToBoundingBox( + const types::DynamicObject & input_object, types::DynamicObject & output_object); + +bool getMeasurementYaw( + const types::DynamicObject & object, const double & predicted_yaw, double & measurement_yaw); + +int getNearestCornerOrSurface( + const double x, const double y, const double yaw, const double width, const double length, + const geometry_msgs::msg::Transform & self_transform); + +void calcAnchorPointOffset( + const double w, const double l, const int indx, const types::DynamicObject & input_object, + const double & yaw, types::DynamicObject & offset_object, Eigen::Vector2d & tracking_offset); +} // namespace shapes +} // namespace autoware::multi_object_tracker + +#endif // AUTOWARE__MULTI_OBJECT_TRACKER__OBJECT_MODEL__SHAPES_HPP_ diff --git a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/object_model/types.hpp b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/object_model/types.hpp new file mode 100644 index 0000000000000..7dab840aac481 --- /dev/null +++ b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/object_model/types.hpp @@ -0,0 +1,88 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// +// Author: v1.0 Taekjin Lee + +#ifndef AUTOWARE__MULTI_OBJECT_TRACKER__OBJECT_MODEL__TYPES_HPP_ +#define AUTOWARE__MULTI_OBJECT_TRACKER__OBJECT_MODEL__TYPES_HPP_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include + +namespace autoware::multi_object_tracker +{ +namespace types +{ +enum OrientationAvailability : uint8_t { + UNAVAILABLE = 0, + SIGN_UNKNOWN = 1, + AVAILABLE = 2, +}; + +struct ObjectKinematics +{ + geometry_msgs::msg::PoseWithCovariance pose_with_covariance; + geometry_msgs::msg::TwistWithCovariance twist_with_covariance; + bool has_position_covariance = false; + OrientationAvailability orientation_availability; + bool has_twist = false; + bool has_twist_covariance = false; +}; + +struct DynamicObject +{ + unique_identifier_msgs::msg::UUID object_id = unique_identifier_msgs::msg::UUID(); + uint channel_index; + float existence_probability; + std::vector classification; + ObjectKinematics kinematics; + autoware_perception_msgs::msg::Shape shape; +}; + +struct DynamicObjectList +{ + std_msgs::msg::Header header; + uint channel_index; + std::vector objects; +}; + +DynamicObject toDynamicObject( + const autoware_perception_msgs::msg::DetectedObject & det_object, const uint channel_index = 0); + +DynamicObjectList toDynamicObjectList( + const autoware_perception_msgs::msg::DetectedObjects & det_objects, const uint channel_index = 0); + +autoware_perception_msgs::msg::TrackedObject toTrackedObjectMsg(const DynamicObject & dyn_object); + +} // namespace types + +} // namespace autoware::multi_object_tracker + +#endif // AUTOWARE__MULTI_OBJECT_TRACKER__OBJECT_MODEL__TYPES_HPP_ diff --git a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/bicycle_tracker.hpp b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/bicycle_tracker.hpp index 8501c68b0cf23..ad3667eb240c0 100644 --- a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/bicycle_tracker.hpp +++ b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/bicycle_tracker.hpp @@ -19,18 +19,20 @@ #ifndef AUTOWARE__MULTI_OBJECT_TRACKER__TRACKER__MODEL__BICYCLE_TRACKER_HPP_ #define AUTOWARE__MULTI_OBJECT_TRACKER__TRACKER__MODEL__BICYCLE_TRACKER_HPP_ -#include "autoware/kalman_filter/kalman_filter.hpp" #include "autoware/multi_object_tracker/object_model/object_model.hpp" +#include "autoware/multi_object_tracker/object_model/types.hpp" #include "autoware/multi_object_tracker/tracker/model/tracker_base.hpp" #include "autoware/multi_object_tracker/tracker/motion_model/bicycle_motion_model.hpp" +#include + namespace autoware::multi_object_tracker { class BicycleTracker : public Tracker { private: - autoware_perception_msgs::msg::DetectedObject object_; + types::DynamicObject object_; rclcpp::Logger logger_; object_model::ObjectModel object_model_ = object_model::bicycle; @@ -50,23 +52,19 @@ class BicycleTracker : public Tracker public: BicycleTracker( - const rclcpp::Time & time, const autoware_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & self_transform, const size_t channel_size, - const uint & channel_index); + const rclcpp::Time & time, const types::DynamicObject & object, const size_t channel_size); bool predict(const rclcpp::Time & time) override; bool measure( - const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, + const types::DynamicObject & object, const rclcpp::Time & time, const geometry_msgs::msg::Transform & self_transform) override; - bool measureWithPose(const autoware_perception_msgs::msg::DetectedObject & object); - bool measureWithShape(const autoware_perception_msgs::msg::DetectedObject & object); - bool getTrackedObject( - const rclcpp::Time & time, - autoware_perception_msgs::msg::TrackedObject & object) const override; + bool measureWithPose(const types::DynamicObject & object); + bool measureWithShape(const types::DynamicObject & object); + bool getTrackedObject(const rclcpp::Time & time, types::DynamicObject & object) const override; private: - autoware_perception_msgs::msg::DetectedObject getUpdatingObject( - const autoware_perception_msgs::msg::DetectedObject & object, + types::DynamicObject getUpdatingObject( + const types::DynamicObject & object, const geometry_msgs::msg::Transform & self_transform) const; }; diff --git a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/multiple_vehicle_tracker.hpp b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/multiple_vehicle_tracker.hpp index 8b4fa1babf652..b9e026bf3c009 100644 --- a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/multiple_vehicle_tracker.hpp +++ b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/multiple_vehicle_tracker.hpp @@ -19,10 +19,11 @@ #ifndef AUTOWARE__MULTI_OBJECT_TRACKER__TRACKER__MODEL__MULTIPLE_VEHICLE_TRACKER_HPP_ #define AUTOWARE__MULTI_OBJECT_TRACKER__TRACKER__MODEL__MULTIPLE_VEHICLE_TRACKER_HPP_ -#include "autoware/kalman_filter/kalman_filter.hpp" +#include "autoware/multi_object_tracker/object_model/types.hpp" #include "autoware/multi_object_tracker/tracker/model/tracker_base.hpp" #include "autoware/multi_object_tracker/tracker/model/vehicle_tracker.hpp" +#include #include namespace autoware::multi_object_tracker @@ -36,17 +37,13 @@ class MultipleVehicleTracker : public Tracker public: MultipleVehicleTracker( - const rclcpp::Time & time, const autoware_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & self_transform, const size_t channel_size, - const uint & channel_index); + const rclcpp::Time & time, const types::DynamicObject & object, const size_t channel_size); bool predict(const rclcpp::Time & time) override; bool measure( - const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, + const types::DynamicObject & object, const rclcpp::Time & time, const geometry_msgs::msg::Transform & self_transform) override; - bool getTrackedObject( - const rclcpp::Time & time, - autoware_perception_msgs::msg::TrackedObject & object) const override; + bool getTrackedObject(const rclcpp::Time & time, types::DynamicObject & object) const override; virtual ~MultipleVehicleTracker() {} }; diff --git a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/pass_through_tracker.hpp b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/pass_through_tracker.hpp index 45cd0f31a4e85..6230ba6e3b0f4 100644 --- a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/pass_through_tracker.hpp +++ b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/pass_through_tracker.hpp @@ -19,32 +19,30 @@ #ifndef AUTOWARE__MULTI_OBJECT_TRACKER__TRACKER__MODEL__PASS_THROUGH_TRACKER_HPP_ #define AUTOWARE__MULTI_OBJECT_TRACKER__TRACKER__MODEL__PASS_THROUGH_TRACKER_HPP_ -#include "autoware/kalman_filter/kalman_filter.hpp" +#include "autoware/multi_object_tracker/object_model/types.hpp" #include "tracker_base.hpp" +#include + namespace autoware::multi_object_tracker { class PassThroughTracker : public Tracker { private: - autoware_perception_msgs::msg::DetectedObject object_; - autoware_perception_msgs::msg::DetectedObject prev_observed_object_; + types::DynamicObject object_; + types::DynamicObject prev_observed_object_; rclcpp::Logger logger_; rclcpp::Time last_update_time_; public: PassThroughTracker( - const rclcpp::Time & time, const autoware_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & self_transform, const size_t channel_size, - const uint & channel_index); + const rclcpp::Time & time, const types::DynamicObject & object, const size_t channel_size); bool predict(const rclcpp::Time & time) override; bool measure( - const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, + const types::DynamicObject & object, const rclcpp::Time & time, const geometry_msgs::msg::Transform & self_transform) override; - bool getTrackedObject( - const rclcpp::Time & time, - autoware_perception_msgs::msg::TrackedObject & object) const override; + bool getTrackedObject(const rclcpp::Time & time, types::DynamicObject & object) const override; }; } // namespace autoware::multi_object_tracker diff --git a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/pedestrian_and_bicycle_tracker.hpp b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/pedestrian_and_bicycle_tracker.hpp index 4287e0f99d5ee..8a4bfc59d37ac 100644 --- a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/pedestrian_and_bicycle_tracker.hpp +++ b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/pedestrian_and_bicycle_tracker.hpp @@ -19,11 +19,13 @@ #ifndef AUTOWARE__MULTI_OBJECT_TRACKER__TRACKER__MODEL__PEDESTRIAN_AND_BICYCLE_TRACKER_HPP_ #define AUTOWARE__MULTI_OBJECT_TRACKER__TRACKER__MODEL__PEDESTRIAN_AND_BICYCLE_TRACKER_HPP_ -#include "autoware/kalman_filter/kalman_filter.hpp" +#include "autoware/multi_object_tracker/object_model/types.hpp" #include "autoware/multi_object_tracker/tracker/model/bicycle_tracker.hpp" #include "autoware/multi_object_tracker/tracker/model/pedestrian_tracker.hpp" #include "autoware/multi_object_tracker/tracker/model/tracker_base.hpp" +#include + namespace autoware::multi_object_tracker { @@ -35,17 +37,13 @@ class PedestrianAndBicycleTracker : public Tracker public: PedestrianAndBicycleTracker( - const rclcpp::Time & time, const autoware_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & self_transform, const size_t channel_size, - const uint & channel_index); + const rclcpp::Time & time, const types::DynamicObject & object, const size_t channel_size); bool predict(const rclcpp::Time & time) override; bool measure( - const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, + const types::DynamicObject & object, const rclcpp::Time & time, const geometry_msgs::msg::Transform & self_transform) override; - bool getTrackedObject( - const rclcpp::Time & time, - autoware_perception_msgs::msg::TrackedObject & object) const override; + bool getTrackedObject(const rclcpp::Time & time, types::DynamicObject & object) const override; virtual ~PedestrianAndBicycleTracker() {} }; diff --git a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/pedestrian_tracker.hpp b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/pedestrian_tracker.hpp index f20b38f73e95f..5a2acc50a8249 100644 --- a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/pedestrian_tracker.hpp +++ b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/pedestrian_tracker.hpp @@ -19,18 +19,20 @@ #ifndef AUTOWARE__MULTI_OBJECT_TRACKER__TRACKER__MODEL__PEDESTRIAN_TRACKER_HPP_ #define AUTOWARE__MULTI_OBJECT_TRACKER__TRACKER__MODEL__PEDESTRIAN_TRACKER_HPP_ -#include "autoware/kalman_filter/kalman_filter.hpp" #include "autoware/multi_object_tracker/object_model/object_model.hpp" +#include "autoware/multi_object_tracker/object_model/types.hpp" #include "autoware/multi_object_tracker/tracker/model/tracker_base.hpp" #include "autoware/multi_object_tracker/tracker/motion_model/ctrv_motion_model.hpp" +#include + namespace autoware::multi_object_tracker { class PedestrianTracker : public Tracker { private: - autoware_perception_msgs::msg::DetectedObject object_; + types::DynamicObject object_; rclcpp::Logger logger_; object_model::ObjectModel object_model_ = object_model::pedestrian; @@ -56,23 +58,19 @@ class PedestrianTracker : public Tracker public: PedestrianTracker( - const rclcpp::Time & time, const autoware_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & self_transform, const size_t channel_size, - const uint & channel_index); + const rclcpp::Time & time, const types::DynamicObject & object, const size_t channel_size); bool predict(const rclcpp::Time & time) override; bool measure( - const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, + const types::DynamicObject & object, const rclcpp::Time & time, const geometry_msgs::msg::Transform & self_transform) override; - bool measureWithPose(const autoware_perception_msgs::msg::DetectedObject & object); - bool measureWithShape(const autoware_perception_msgs::msg::DetectedObject & object); - bool getTrackedObject( - const rclcpp::Time & time, - autoware_perception_msgs::msg::TrackedObject & object) const override; + bool measureWithPose(const types::DynamicObject & object); + bool measureWithShape(const types::DynamicObject & object); + bool getTrackedObject(const rclcpp::Time & time, types::DynamicObject & object) const override; private: - autoware_perception_msgs::msg::DetectedObject getUpdatingObject( - const autoware_perception_msgs::msg::DetectedObject & object, + types::DynamicObject getUpdatingObject( + const types::DynamicObject & object, const geometry_msgs::msg::Transform & self_transform) const; }; diff --git a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/tracker_base.hpp b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/tracker_base.hpp index 0b9ea9c44a6cf..ac5527fca6400 100644 --- a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/tracker_base.hpp +++ b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/tracker_base.hpp @@ -20,14 +20,14 @@ #define AUTOWARE__MULTI_OBJECT_TRACKER__TRACKER__MODEL__TRACKER_BASE_HPP_ #define EIGEN_MPL2_ONLY -#include "autoware/multi_object_tracker/utils/utils.hpp" -#include "autoware/object_recognition_utils/object_recognition_utils.hpp" +#include "autoware/multi_object_tracker/object_model/types.hpp" #include +#include #include -#include "autoware_perception_msgs/msg/detected_object.hpp" -#include "autoware_perception_msgs/msg/tracked_object.hpp" +#include +#include #include #include @@ -67,9 +67,8 @@ class Tracker return existence_vector.size() > 0; } bool updateWithMeasurement( - const autoware_perception_msgs::msg::DetectedObject & object, - const rclcpp::Time & measurement_time, const geometry_msgs::msg::Transform & self_transform, - const uint & channel_index); + const types::DynamicObject & object, const rclcpp::Time & measurement_time, + const geometry_msgs::msg::Transform & self_transform); bool updateWithoutMeasurement(const rclcpp::Time & now); // classification @@ -108,12 +107,11 @@ class Tracker protected: virtual bool measure( - const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, + const types::DynamicObject & object, const rclcpp::Time & time, const geometry_msgs::msg::Transform & self_transform) = 0; public: - virtual bool getTrackedObject( - const rclcpp::Time & time, autoware_perception_msgs::msg::TrackedObject & object) const = 0; + virtual bool getTrackedObject(const rclcpp::Time & time, types::DynamicObject & object) const = 0; virtual bool predict(const rclcpp::Time & time) = 0; }; diff --git a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/unknown_tracker.hpp b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/unknown_tracker.hpp index 9f128c864ad6c..075db6b8a9d69 100644 --- a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/unknown_tracker.hpp +++ b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/unknown_tracker.hpp @@ -19,17 +19,19 @@ #ifndef AUTOWARE__MULTI_OBJECT_TRACKER__TRACKER__MODEL__UNKNOWN_TRACKER_HPP_ #define AUTOWARE__MULTI_OBJECT_TRACKER__TRACKER__MODEL__UNKNOWN_TRACKER_HPP_ -#include "autoware/kalman_filter/kalman_filter.hpp" +#include "autoware/multi_object_tracker/object_model/types.hpp" #include "autoware/multi_object_tracker/tracker/model/tracker_base.hpp" #include "autoware/multi_object_tracker/tracker/motion_model/cv_motion_model.hpp" +#include + namespace autoware::multi_object_tracker { class UnknownTracker : public Tracker { private: - autoware_perception_msgs::msg::DetectedObject object_; + types::DynamicObject object_; rclcpp::Logger logger_; struct EkfParams @@ -47,22 +49,17 @@ class UnknownTracker : public Tracker public: UnknownTracker( - const rclcpp::Time & time, const autoware_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & self_transform, const size_t channel_size, - const uint & channel_index); + const rclcpp::Time & time, const types::DynamicObject & object, const size_t channel_size); bool predict(const rclcpp::Time & time) override; bool measure( - const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, + const types::DynamicObject & object, const rclcpp::Time & time, const geometry_msgs::msg::Transform & self_transform) override; - autoware_perception_msgs::msg::DetectedObject getUpdatingObject( - const autoware_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & self_transform); - bool measureWithPose(const autoware_perception_msgs::msg::DetectedObject & object); - bool measureWithShape(const autoware_perception_msgs::msg::DetectedObject & object); - bool getTrackedObject( - const rclcpp::Time & time, - autoware_perception_msgs::msg::TrackedObject & object) const override; + types::DynamicObject getUpdatingObject( + const types::DynamicObject & object, const geometry_msgs::msg::Transform & self_transform); + bool measureWithPose(const types::DynamicObject & object); + bool measureWithShape(const types::DynamicObject & object); + bool getTrackedObject(const rclcpp::Time & time, types::DynamicObject & object) const override; }; } // namespace autoware::multi_object_tracker diff --git a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/vehicle_tracker.hpp b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/vehicle_tracker.hpp index f3708fd1ff905..f50d117acc081 100644 --- a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/vehicle_tracker.hpp +++ b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/vehicle_tracker.hpp @@ -19,11 +19,13 @@ #ifndef AUTOWARE__MULTI_OBJECT_TRACKER__TRACKER__MODEL__VEHICLE_TRACKER_HPP_ #define AUTOWARE__MULTI_OBJECT_TRACKER__TRACKER__MODEL__VEHICLE_TRACKER_HPP_ -#include "autoware/kalman_filter/kalman_filter.hpp" #include "autoware/multi_object_tracker/object_model/object_model.hpp" +#include "autoware/multi_object_tracker/object_model/types.hpp" #include "autoware/multi_object_tracker/tracker/model/tracker_base.hpp" #include "autoware/multi_object_tracker/tracker/motion_model/bicycle_motion_model.hpp" +#include + namespace autoware::multi_object_tracker { @@ -35,7 +37,7 @@ class VehicleTracker : public Tracker double velocity_deviation_threshold_; - autoware_perception_msgs::msg::DetectedObject object_; + types::DynamicObject object_; double z_; struct BoundingBox @@ -53,24 +55,19 @@ class VehicleTracker : public Tracker public: VehicleTracker( const object_model::ObjectModel & object_model, const rclcpp::Time & time, - const autoware_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & self_transform, const size_t channel_size, - const uint & channel_index); + const types::DynamicObject & object, const size_t channel_size); bool predict(const rclcpp::Time & time) override; bool measure( - const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, + const types::DynamicObject & object, const rclcpp::Time & time, const geometry_msgs::msg::Transform & self_transform) override; - bool measureWithPose(const autoware_perception_msgs::msg::DetectedObject & object); - bool measureWithShape(const autoware_perception_msgs::msg::DetectedObject & object); - bool getTrackedObject( - const rclcpp::Time & time, - autoware_perception_msgs::msg::TrackedObject & object) const override; + bool measureWithPose(const types::DynamicObject & object); + bool measureWithShape(const types::DynamicObject & object); + bool getTrackedObject(const rclcpp::Time & time, types::DynamicObject & object) const override; private: - autoware_perception_msgs::msg::DetectedObject getUpdatingObject( - const autoware_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & self_transform); + types::DynamicObject getUpdatingObject( + const types::DynamicObject & object, const geometry_msgs::msg::Transform & self_transform); }; } // namespace autoware::multi_object_tracker diff --git a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/uncertainty/uncertainty_processor.hpp b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/uncertainty/uncertainty_processor.hpp index 12bd865795b85..44ad012a5f428 100644 --- a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/uncertainty/uncertainty_processor.hpp +++ b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/uncertainty/uncertainty_processor.hpp @@ -19,6 +19,7 @@ #define AUTOWARE__MULTI_OBJECT_TRACKER__UNCERTAINTY__UNCERTAINTY_PROCESSOR_HPP_ #include "autoware/multi_object_tracker/object_model/object_model.hpp" +#include "autoware/multi_object_tracker/object_model/types.hpp" #include @@ -32,21 +33,19 @@ namespace uncertainty { using autoware::multi_object_tracker::object_model::ObjectModel; -using autoware_perception_msgs::msg::DetectedObject; -using autoware_perception_msgs::msg::DetectedObjects; using autoware_perception_msgs::msg::ObjectClassification; using nav_msgs::msg::Odometry; ObjectModel decodeObjectModel(const ObjectClassification & object_class); -DetectedObjects modelUncertainty(const DetectedObjects & detected_objects); +types::DynamicObjectList modelUncertainty(const types::DynamicObjectList & detected_objects); object_model::StateCovariance covarianceFromObjectClass( - const DetectedObject & detected_object, const ObjectClassification & object_class); + const types::DynamicObject & detected_object, const ObjectClassification & object_class); -void normalizeUncertainty(DetectedObjects & detected_objects); +void normalizeUncertainty(types::DynamicObjectList & detected_objects); -void addOdometryUncertainty(const Odometry & odometry, DetectedObjects & detected_objects); +void addOdometryUncertainty(const Odometry & odometry, types::DynamicObjectList & detected_objects); } // namespace uncertainty } // namespace autoware::multi_object_tracker diff --git a/perception/autoware_multi_object_tracker/lib/association/association.cpp b/perception/autoware_multi_object_tracker/lib/association/association.cpp index 0c809ee5f086d..d74d87489f8db 100644 --- a/perception/autoware_multi_object_tracker/lib/association/association.cpp +++ b/perception/autoware_multi_object_tracker/lib/association/association.cpp @@ -15,8 +15,10 @@ #include "autoware/multi_object_tracker/association/association.hpp" #include "autoware/multi_object_tracker/association/solver/gnn_solver.hpp" -#include "autoware/multi_object_tracker/utils/utils.hpp" -#include "autoware/object_recognition_utils/object_recognition_utils.hpp" +#include "autoware/multi_object_tracker/object_model/shapes.hpp" +#include "autoware/multi_object_tracker/object_model/types.hpp" + +#include #include #include @@ -150,7 +152,7 @@ void DataAssociation::assign( } Eigen::MatrixXd DataAssociation::calcScoreMatrix( - const autoware_perception_msgs::msg::DetectedObjects & measurements, + const types::DynamicObjectList & measurements, const std::list> & trackers) { Eigen::MatrixXd score_matrix = @@ -162,14 +164,13 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix( for (size_t measurement_idx = 0; measurement_idx < measurements.objects.size(); ++measurement_idx) { - const autoware_perception_msgs::msg::DetectedObject & measurement_object = - measurements.objects.at(measurement_idx); + const types::DynamicObject & measurement_object = measurements.objects.at(measurement_idx); const std::uint8_t measurement_label = autoware::object_recognition_utils::getHighestProbLabel(measurement_object.classification); double score = 0.0; if (can_assign_matrix_(tracker_label, measurement_label)) { - autoware_perception_msgs::msg::TrackedObject tracked_object; + types::DynamicObject tracked_object; (*tracker_itr)->getTrackedObject(measurements.header.stamp, tracked_object); const double max_dist = max_dist_matrix_(tracker_label, measurement_label); @@ -210,8 +211,8 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix( if (passed_gate) { const double min_iou = min_iou_matrix_(tracker_label, measurement_label); const double min_union_iou_area = 1e-2; - const double iou = autoware::object_recognition_utils::get2dIoU( - measurement_object, tracked_object, min_union_iou_area); + const double iou = + shapes::get2dIoU(measurement_object, tracked_object, min_union_iou_area); if (iou < min_iou) passed_gate = false; } diff --git a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/utils/utils.hpp b/perception/autoware_multi_object_tracker/lib/object_model/shapes.cpp similarity index 59% rename from perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/utils/utils.hpp rename to perception/autoware_multi_object_tracker/lib/object_model/shapes.cpp index 833f768e171f4..2ce23e5df814e 100644 --- a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/utils/utils.hpp +++ b/perception/autoware_multi_object_tracker/lib/object_model/shapes.cpp @@ -1,4 +1,4 @@ -// Copyright 2020 Tier IV, Inc. +// Copyright 2024 Tier IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -13,31 +13,198 @@ // limitations under the License. // // -// Author: v1.0 Yukihiro Saito -// +// Author: v1.0 Yukihiro Saito, Taekjin Lee -#ifndef AUTOWARE__MULTI_OBJECT_TRACKER__UTILS__UTILS_HPP_ -#define AUTOWARE__MULTI_OBJECT_TRACKER__UTILS__UTILS_HPP_ +#include "autoware/multi_object_tracker/object_model/shapes.hpp" -#include #include +#include +#include + +#include +#include -#include "autoware_perception_msgs/msg/detected_object.hpp" -#include "autoware_perception_msgs/msg/shape.hpp" -#include "autoware_perception_msgs/msg/tracked_object.hpp" -#include -#include -#include +#include #include +#include #include -#include -#include +#include #include -namespace utils +namespace autoware::multi_object_tracker +{ +namespace shapes +{ +inline boost::optional getTransform( + const tf2_ros::Buffer & tf_buffer, const std::string & source_frame_id, + const std::string & target_frame_id, const rclcpp::Time & time) +{ + try { + geometry_msgs::msg::TransformStamped self_transform_stamped; + self_transform_stamped = tf_buffer.lookupTransform( + target_frame_id, source_frame_id, time, rclcpp::Duration::from_seconds(0.5)); + return self_transform_stamped.transform; + } catch (tf2::TransformException & ex) { + RCLCPP_WARN_STREAM(rclcpp::get_logger("multi_object_tracker"), ex.what()); + return boost::none; + } +} + +bool transformObjects( + const types::DynamicObjectList & input_msg, const std::string & target_frame_id, + const tf2_ros::Buffer & tf_buffer, types::DynamicObjectList & output_msg) +{ + output_msg = input_msg; + + // transform to world coordinate + if (input_msg.header.frame_id != target_frame_id) { + output_msg.header.frame_id = target_frame_id; + tf2::Transform tf_target2objects_world; + tf2::Transform tf_target2objects; + tf2::Transform tf_objects_world2objects; + { + const auto ros_target2objects_world = + getTransform(tf_buffer, input_msg.header.frame_id, target_frame_id, input_msg.header.stamp); + if (!ros_target2objects_world) { + return false; + } + tf2::fromMsg(*ros_target2objects_world, tf_target2objects_world); + } + for (auto & object : output_msg.objects) { + auto & pose_with_cov = object.kinematics.pose_with_covariance; + tf2::fromMsg(pose_with_cov.pose, tf_objects_world2objects); + tf_target2objects = tf_target2objects_world * tf_objects_world2objects; + // transform pose, frame difference and object pose + tf2::toMsg(tf_target2objects, pose_with_cov.pose); + // transform covariance, only the frame difference + pose_with_cov.covariance = + tf2::transformCovariance(pose_with_cov.covariance, tf_target2objects_world); + } + } + return true; +} + +inline double getSumArea(const std::vector & polygons) +{ + return std::accumulate( + polygons.begin(), polygons.end(), 0.0, [](double acc, autoware::universe_utils::Polygon2d p) { + return acc + boost::geometry::area(p); + }); +} + +inline double getIntersectionArea( + const autoware::universe_utils::Polygon2d & source_polygon, + const autoware::universe_utils::Polygon2d & target_polygon) +{ + std::vector intersection_polygons; + boost::geometry::intersection(source_polygon, target_polygon, intersection_polygons); + return getSumArea(intersection_polygons); +} + +inline double getUnionArea( + const autoware::universe_utils::Polygon2d & source_polygon, + const autoware::universe_utils::Polygon2d & target_polygon) +{ + std::vector union_polygons; + boost::geometry::union_(source_polygon, target_polygon, union_polygons); + return getSumArea(union_polygons); +} + +double get2dIoU( + const types::DynamicObject & source_object, const types::DynamicObject & target_object, + const double min_union_area) { + static const double MIN_AREA = 1e-6; + + const auto source_polygon = autoware::universe_utils::toPolygon2d( + source_object.kinematics.pose_with_covariance.pose, source_object.shape); + if (boost::geometry::area(source_polygon) < MIN_AREA) return 0.0; + const auto target_polygon = autoware::universe_utils::toPolygon2d( + target_object.kinematics.pose_with_covariance.pose, target_object.shape); + if (boost::geometry::area(target_polygon) < MIN_AREA) return 0.0; + + const double intersection_area = getIntersectionArea(source_polygon, target_polygon); + if (intersection_area < MIN_AREA) return 0.0; + const double union_area = getUnionArea(source_polygon, target_polygon); + + const double iou = + union_area < min_union_area ? 0.0 : std::min(1.0, intersection_area / union_area); + return iou; +} + +/** + * @brief convert convex hull shape object to bounding box object + * @param input_object: input convex hull objects + * @param output_object: output bounding box objects + */ +bool convertConvexHullToBoundingBox( + const types::DynamicObject & input_object, types::DynamicObject & output_object) +{ + // check footprint size + if (input_object.shape.footprint.points.size() < 3) { + return false; + } + + // look for bounding box boundary + float max_x = 0; + float max_y = 0; + float min_x = 0; + float min_y = 0; + float max_z = 0; + for (const auto & point : input_object.shape.footprint.points) { + max_x = std::max(max_x, point.x); + max_y = std::max(max_y, point.y); + min_x = std::min(min_x, point.x); + min_y = std::min(min_y, point.y); + max_z = std::max(max_z, point.z); + } + + // calc new center + const Eigen::Vector2d center{ + input_object.kinematics.pose_with_covariance.pose.position.x, + input_object.kinematics.pose_with_covariance.pose.position.y}; + const auto yaw = tf2::getYaw(input_object.kinematics.pose_with_covariance.pose.orientation); + const Eigen::Matrix2d R_inv = Eigen::Rotation2Dd(-yaw).toRotationMatrix(); + const Eigen::Vector2d new_local_center{(max_x + min_x) / 2.0, (max_y + min_y) / 2.0}; + const Eigen::Vector2d new_center = center + R_inv.transpose() * new_local_center; + + // set output parameters + output_object = input_object; + output_object.kinematics.pose_with_covariance.pose.position.x = new_center.x(); + output_object.kinematics.pose_with_covariance.pose.position.y = new_center.y(); + + output_object.shape.type = autoware_perception_msgs::msg::Shape::BOUNDING_BOX; + output_object.shape.dimensions.x = max_x - min_x; + output_object.shape.dimensions.y = max_y - min_y; + output_object.shape.dimensions.z = max_z; + + return true; +} + +bool getMeasurementYaw( + const types::DynamicObject & object, const double & predicted_yaw, double & measurement_yaw) +{ + measurement_yaw = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); + + // check orientation sign is known or not, and fix the limiting delta yaw + double limiting_delta_yaw = M_PI_2; + if (object.kinematics.orientation_availability == types::OrientationAvailability::AVAILABLE) { + limiting_delta_yaw = M_PI; + } + // limiting delta yaw, even the availability is unknown + while (std::fabs(predicted_yaw - measurement_yaw) > limiting_delta_yaw) { + if (measurement_yaw < predicted_yaw) { + measurement_yaw += 2 * limiting_delta_yaw; + } else { + measurement_yaw -= 2 * limiting_delta_yaw; + } + } + // return false if the orientation is unknown + return object.kinematics.orientation_availability != types::OrientationAvailability::UNAVAILABLE; +} + enum BBOX_IDX { FRONT_SURFACE = 0, RIGHT_SURFACE = 1, @@ -51,17 +218,6 @@ enum BBOX_IDX { INVALID = -1 }; -/** - * @brief check if object label belongs to "large vehicle" - * @param label: input object label - * @return True if object label means large vehicle - */ -inline bool isLargeVehicleLabel(const uint8_t label) -{ - using Label = autoware_perception_msgs::msg::ObjectClassification; - return label == Label::BUS || label == Label::TRUCK || label == Label::TRAILER; -} - /** * @brief Determine the Nearest Corner or Surface of detected object observed from ego vehicle * @@ -73,7 +229,7 @@ inline bool isLargeVehicleLabel(const uint8_t label) * @param self_transform: Ego vehicle position in map frame * @return int index */ -inline int getNearestCornerOrSurface( +int getNearestCornerOrSurface( const double x, const double y, const double yaw, const double width, const double length, const geometry_msgs::msg::Transform & self_transform) { @@ -171,10 +327,9 @@ inline Eigen::Vector2d calcOffsetVectorFromShapeChange( * @param offset_object: output tracking measurement to feed ekf * @return nearest corner index(int) */ -inline void calcAnchorPointOffset( - const double w, const double l, const int indx, - const autoware_perception_msgs::msg::DetectedObject & input_object, const double & yaw, - autoware_perception_msgs::msg::DetectedObject & offset_object, Eigen::Vector2d & tracking_offset) +void calcAnchorPointOffset( + const double w, const double l, const int indx, const types::DynamicObject & input_object, + const double & yaw, types::DynamicObject & offset_object, Eigen::Vector2d & tracking_offset) { // copy value offset_object = input_object; @@ -198,82 +353,6 @@ inline void calcAnchorPointOffset( offset_object.kinematics.pose_with_covariance.pose.position.y += rotated_offset.y(); } -/** - * @brief convert convex hull shape object to bounding box object - * @param input_object: input convex hull objects - * @param output_object: output bounding box objects - */ -inline bool convertConvexHullToBoundingBox( - const autoware_perception_msgs::msg::DetectedObject & input_object, - autoware_perception_msgs::msg::DetectedObject & output_object) -{ - // check footprint size - if (input_object.shape.footprint.points.size() < 3) { - return false; - } - - // look for bounding box boundary - float max_x = 0; - float max_y = 0; - float min_x = 0; - float min_y = 0; - float max_z = 0; - for (const auto & point : input_object.shape.footprint.points) { - max_x = std::max(max_x, point.x); - max_y = std::max(max_y, point.y); - min_x = std::min(min_x, point.x); - min_y = std::min(min_y, point.y); - max_z = std::max(max_z, point.z); - } - - // calc new center - const Eigen::Vector2d center{ - input_object.kinematics.pose_with_covariance.pose.position.x, - input_object.kinematics.pose_with_covariance.pose.position.y}; - const auto yaw = tf2::getYaw(input_object.kinematics.pose_with_covariance.pose.orientation); - const Eigen::Matrix2d R_inv = Eigen::Rotation2Dd(-yaw).toRotationMatrix(); - const Eigen::Vector2d new_local_center{(max_x + min_x) / 2.0, (max_y + min_y) / 2.0}; - const Eigen::Vector2d new_center = center + R_inv.transpose() * new_local_center; - - // set output parameters - output_object = input_object; - output_object.kinematics.pose_with_covariance.pose.position.x = new_center.x(); - output_object.kinematics.pose_with_covariance.pose.position.y = new_center.y(); - - output_object.shape.type = autoware_perception_msgs::msg::Shape::BOUNDING_BOX; - output_object.shape.dimensions.x = max_x - min_x; - output_object.shape.dimensions.y = max_y - min_y; - output_object.shape.dimensions.z = max_z; - - return true; -} - -inline bool getMeasurementYaw( - const autoware_perception_msgs::msg::DetectedObject & object, const double & predicted_yaw, - double & measurement_yaw) -{ - measurement_yaw = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); - - // check orientation sign is known or not, and fix the limiting delta yaw - double limiting_delta_yaw = M_PI_2; - if ( - object.kinematics.orientation_availability == - autoware_perception_msgs::msg::DetectedObjectKinematics::AVAILABLE) { - limiting_delta_yaw = M_PI; - } - // limiting delta yaw, even the availability is unknown - while (std::fabs(predicted_yaw - measurement_yaw) > limiting_delta_yaw) { - if (measurement_yaw < predicted_yaw) { - measurement_yaw += 2 * limiting_delta_yaw; - } else { - measurement_yaw -= 2 * limiting_delta_yaw; - } - } - // return false if the orientation is unknown - return object.kinematics.orientation_availability != - autoware_perception_msgs::msg::DetectedObjectKinematics::UNAVAILABLE; -} - -} // namespace utils +} // namespace shapes -#endif // AUTOWARE__MULTI_OBJECT_TRACKER__UTILS__UTILS_HPP_ +} // namespace autoware::multi_object_tracker diff --git a/perception/autoware_multi_object_tracker/lib/object_model/types.cpp b/perception/autoware_multi_object_tracker/lib/object_model/types.cpp new file mode 100644 index 0000000000000..671d5313d0ff8 --- /dev/null +++ b/perception/autoware_multi_object_tracker/lib/object_model/types.cpp @@ -0,0 +1,101 @@ +// Copyright 2024 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// +// Author: v1.0 Taekjin Lee + +#include "autoware/multi_object_tracker/object_model/types.hpp" + +#include + +namespace autoware::multi_object_tracker +{ + +namespace types +{ + +DynamicObject toDynamicObject( + const autoware_perception_msgs::msg::DetectedObject & det_object, const uint channel_index) +{ + DynamicObject dynamic_object; + dynamic_object.channel_index = channel_index; + dynamic_object.existence_probability = det_object.existence_probability; + dynamic_object.classification = det_object.classification; + + dynamic_object.kinematics.pose_with_covariance = det_object.kinematics.pose_with_covariance; + dynamic_object.kinematics.twist_with_covariance = det_object.kinematics.twist_with_covariance; + dynamic_object.kinematics.has_position_covariance = det_object.kinematics.has_position_covariance; + if ( + det_object.kinematics.orientation_availability == + autoware_perception_msgs::msg::DetectedObjectKinematics::UNAVAILABLE) { + dynamic_object.kinematics.orientation_availability = OrientationAvailability::UNAVAILABLE; + } else if ( + det_object.kinematics.orientation_availability == + autoware_perception_msgs::msg::DetectedObjectKinematics::SIGN_UNKNOWN) { + dynamic_object.kinematics.orientation_availability = OrientationAvailability::SIGN_UNKNOWN; + } else if ( + det_object.kinematics.orientation_availability == + autoware_perception_msgs::msg::DetectedObjectKinematics::AVAILABLE) { + dynamic_object.kinematics.orientation_availability = OrientationAvailability::AVAILABLE; + } + dynamic_object.kinematics.has_twist = det_object.kinematics.has_twist; + dynamic_object.kinematics.has_twist_covariance = det_object.kinematics.has_twist_covariance; + + dynamic_object.shape = det_object.shape; + + return dynamic_object; +} + +DynamicObjectList toDynamicObjectList( + const autoware_perception_msgs::msg::DetectedObjects & det_objects, const uint channel_index) +{ + DynamicObjectList dynamic_objects; + dynamic_objects.header = det_objects.header; + dynamic_objects.channel_index = channel_index; + dynamic_objects.objects.reserve(det_objects.objects.size()); + for (const auto & det_object : det_objects.objects) { + dynamic_objects.objects.emplace_back(toDynamicObject(det_object, channel_index)); + } + return dynamic_objects; +} + +autoware_perception_msgs::msg::TrackedObject toTrackedObjectMsg(const DynamicObject & dyn_object) +{ + autoware_perception_msgs::msg::TrackedObject tracked_object; + tracked_object.object_id = dyn_object.object_id; + tracked_object.existence_probability = dyn_object.existence_probability; + tracked_object.classification = dyn_object.classification; + + tracked_object.kinematics.pose_with_covariance = dyn_object.kinematics.pose_with_covariance; + tracked_object.kinematics.twist_with_covariance = dyn_object.kinematics.twist_with_covariance; + if (dyn_object.kinematics.orientation_availability == OrientationAvailability::UNAVAILABLE) { + tracked_object.kinematics.orientation_availability = + autoware_perception_msgs::msg::TrackedObjectKinematics::UNAVAILABLE; + } else if ( + dyn_object.kinematics.orientation_availability == OrientationAvailability::SIGN_UNKNOWN) { + tracked_object.kinematics.orientation_availability = + autoware_perception_msgs::msg::TrackedObjectKinematics::SIGN_UNKNOWN; + } else if (dyn_object.kinematics.orientation_availability == OrientationAvailability::AVAILABLE) { + tracked_object.kinematics.orientation_availability = + autoware_perception_msgs::msg::TrackedObjectKinematics::AVAILABLE; + } + tracked_object.kinematics.is_stationary = false; + + tracked_object.shape = dyn_object.shape; + + return tracked_object; +} +} // namespace types + +} // namespace autoware::multi_object_tracker diff --git a/perception/autoware_multi_object_tracker/lib/tracker/model/bicycle_tracker.cpp b/perception/autoware_multi_object_tracker/lib/tracker/model/bicycle_tracker.cpp index 69a9edd9c9d9e..e0380a7c33e77 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/model/bicycle_tracker.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/model/bicycle_tracker.cpp @@ -19,15 +19,15 @@ #include "autoware/multi_object_tracker/tracker/model/bicycle_tracker.hpp" -#include "autoware/multi_object_tracker/utils/utils.hpp" -#include "autoware/object_recognition_utils/object_recognition_utils.hpp" -#include "autoware/universe_utils/geometry/boost_polygon_utils.hpp" -#include "autoware/universe_utils/math/normalization.hpp" -#include "autoware/universe_utils/math/unit_conversion.hpp" -#include "autoware/universe_utils/ros/msg_covariance.hpp" +#include "autoware/multi_object_tracker/object_model/shapes.hpp" #include #include +#include +#include +#include +#include +#include #include #include @@ -46,9 +46,7 @@ namespace autoware::multi_object_tracker using Label = autoware_perception_msgs::msg::ObjectClassification; BicycleTracker::BicycleTracker( - const rclcpp::Time & time, const autoware_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & /*self_transform*/, const size_t channel_size, - const uint & channel_index) + const rclcpp::Time & time, const types::DynamicObject & object, const size_t channel_size) : Tracker(time, object.classification, channel_size), logger_(rclcpp::get_logger("BicycleTracker")), z_(object.kinematics.pose_with_covariance.pose.position.z) @@ -56,7 +54,7 @@ BicycleTracker::BicycleTracker( object_ = object; // initialize existence probability - initializeExistenceProbabilities(channel_index, object.existence_probability); + initializeExistenceProbabilities(object.channel_index, object.existence_probability); // OBJECT SHAPE MODEL if (object.shape.type == autoware_perception_msgs::msg::Shape::BOUNDING_BOX) { @@ -148,16 +146,16 @@ bool BicycleTracker::predict(const rclcpp::Time & time) return motion_model_.predictState(time); } -autoware_perception_msgs::msg::DetectedObject BicycleTracker::getUpdatingObject( - const autoware_perception_msgs::msg::DetectedObject & object, +types::DynamicObject BicycleTracker::getUpdatingObject( + const types::DynamicObject & object, const geometry_msgs::msg::Transform & /*self_transform*/) const { - autoware_perception_msgs::msg::DetectedObject updating_object = object; + types::DynamicObject updating_object = object; // OBJECT SHAPE MODEL // convert to bounding box if input is convex shape if (object.shape.type != autoware_perception_msgs::msg::Shape::BOUNDING_BOX) { - if (!utils::convertConvexHullToBoundingBox(object, updating_object)) { + if (!shapes::convertConvexHullToBoundingBox(object, updating_object)) { updating_object = object; } } @@ -165,12 +163,12 @@ autoware_perception_msgs::msg::DetectedObject BicycleTracker::getUpdatingObject( return updating_object; } -bool BicycleTracker::measureWithPose(const autoware_perception_msgs::msg::DetectedObject & object) +bool BicycleTracker::measureWithPose(const types::DynamicObject & object) { // get measurement yaw angle to update const double tracked_yaw = motion_model_.getStateElement(IDX::YAW); double measurement_yaw = 0.0; - bool is_yaw_available = utils::getMeasurementYaw(object, tracked_yaw, measurement_yaw); + bool is_yaw_available = shapes::getMeasurementYaw(object, tracked_yaw, measurement_yaw); // update bool is_updated = false; @@ -196,7 +194,7 @@ bool BicycleTracker::measureWithPose(const autoware_perception_msgs::msg::Detect return is_updated; } -bool BicycleTracker::measureWithShape(const autoware_perception_msgs::msg::DetectedObject & object) +bool BicycleTracker::measureWithShape(const types::DynamicObject & object) { if (object.shape.type != autoware_perception_msgs::msg::Shape::BOUNDING_BOX) { // do not update shape if the input is not a bounding box @@ -235,7 +233,7 @@ bool BicycleTracker::measureWithShape(const autoware_perception_msgs::msg::Detec } bool BicycleTracker::measure( - const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, + const types::DynamicObject & object, const rclcpp::Time & time, const geometry_msgs::msg::Transform & self_transform) { // keep the latest input object @@ -260,8 +258,7 @@ bool BicycleTracker::measure( } // update object - const autoware_perception_msgs::msg::DetectedObject updating_object = - getUpdatingObject(object, self_transform); + const types::DynamicObject updating_object = getUpdatingObject(object, self_transform); measureWithPose(updating_object); measureWithShape(updating_object); @@ -269,9 +266,9 @@ bool BicycleTracker::measure( } bool BicycleTracker::getTrackedObject( - const rclcpp::Time & time, autoware_perception_msgs::msg::TrackedObject & object) const + const rclcpp::Time & time, types::DynamicObject & object) const { - object = autoware::object_recognition_utils::toTrackedObject(object_); + object = object_; object.object_id = getUUID(); object.classification = getClassification(); diff --git a/perception/autoware_multi_object_tracker/lib/tracker/model/multiple_vehicle_tracker.cpp b/perception/autoware_multi_object_tracker/lib/tracker/model/multiple_vehicle_tracker.cpp index ff06544bd509c..9f249ab3bc7bc 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/model/multiple_vehicle_tracker.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/model/multiple_vehicle_tracker.cpp @@ -26,17 +26,13 @@ namespace autoware::multi_object_tracker using Label = autoware_perception_msgs::msg::ObjectClassification; MultipleVehicleTracker::MultipleVehicleTracker( - const rclcpp::Time & time, const autoware_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & self_transform, const size_t channel_size, - const uint & channel_index) + const rclcpp::Time & time, const types::DynamicObject & object, const size_t channel_size) : Tracker(time, object.classification, channel_size), - normal_vehicle_tracker_( - object_model::normal_vehicle, time, object, self_transform, channel_size, channel_index), - big_vehicle_tracker_( - object_model::big_vehicle, time, object, self_transform, channel_size, channel_index) + normal_vehicle_tracker_(object_model::normal_vehicle, time, object, channel_size), + big_vehicle_tracker_(object_model::big_vehicle, time, object, channel_size) { // initialize existence probability - initializeExistenceProbabilities(channel_index, object.existence_probability); + initializeExistenceProbabilities(object.channel_index, object.existence_probability); } bool MultipleVehicleTracker::predict(const rclcpp::Time & time) @@ -47,7 +43,7 @@ bool MultipleVehicleTracker::predict(const rclcpp::Time & time) } bool MultipleVehicleTracker::measure( - const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, + const types::DynamicObject & object, const rclcpp::Time & time, const geometry_msgs::msg::Transform & self_transform) { big_vehicle_tracker_.measure(object, time, self_transform); @@ -60,14 +56,14 @@ bool MultipleVehicleTracker::measure( } bool MultipleVehicleTracker::getTrackedObject( - const rclcpp::Time & time, autoware_perception_msgs::msg::TrackedObject & object) const + const rclcpp::Time & time, types::DynamicObject & object) const { using Label = autoware_perception_msgs::msg::ObjectClassification; const uint8_t label = getHighestProbLabel(); if (label == Label::CAR) { normal_vehicle_tracker_.getTrackedObject(time, object); - } else if (utils::isLargeVehicleLabel(label)) { + } else if (label == Label::BUS || label == Label::TRUCK || label == Label::TRAILER) { big_vehicle_tracker_.getTrackedObject(time, object); } object.object_id = getUUID(); diff --git a/perception/autoware_multi_object_tracker/lib/tracker/model/pass_through_tracker.cpp b/perception/autoware_multi_object_tracker/lib/tracker/model/pass_through_tracker.cpp index f66e616241ae0..45b3b067e2848 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/model/pass_through_tracker.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/model/pass_through_tracker.cpp @@ -18,12 +18,10 @@ #define EIGEN_MPL2_ONLY #include "autoware/multi_object_tracker/tracker/model/pass_through_tracker.hpp" -#include "autoware/multi_object_tracker/utils/utils.hpp" -#include "autoware/object_recognition_utils/object_recognition_utils.hpp" -#include "autoware/universe_utils/ros/msg_covariance.hpp" - #include #include +#include +#include #include #include @@ -40,9 +38,7 @@ namespace autoware::multi_object_tracker { PassThroughTracker::PassThroughTracker( - const rclcpp::Time & time, const autoware_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & /*self_transform*/, const size_t channel_size, - const uint & channel_index) + const rclcpp::Time & time, const types::DynamicObject & object, const size_t channel_size) : Tracker(time, object.classification, channel_size), logger_(rclcpp::get_logger("PassThroughTracker")), last_update_time_(time) @@ -51,7 +47,7 @@ PassThroughTracker::PassThroughTracker( prev_observed_object_ = object; // initialize existence probability - initializeExistenceProbabilities(channel_index, object.existence_probability); + initializeExistenceProbabilities(object.channel_index, object.existence_probability); } bool PassThroughTracker::predict(const rclcpp::Time & time) @@ -66,7 +62,7 @@ bool PassThroughTracker::predict(const rclcpp::Time & time) } bool PassThroughTracker::measure( - const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, + const types::DynamicObject & object, const rclcpp::Time & time, const geometry_msgs::msg::Transform & self_transform) { prev_observed_object_ = object_; @@ -88,10 +84,10 @@ bool PassThroughTracker::measure( } bool PassThroughTracker::getTrackedObject( - const rclcpp::Time & time, autoware_perception_msgs::msg::TrackedObject & object) const + const rclcpp::Time & time, types::DynamicObject & object) const { using autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; - object = autoware::object_recognition_utils::toTrackedObject(object_); + object = object_; object.object_id = getUUID(); object.classification = getClassification(); object.kinematics.pose_with_covariance.covariance[XYZRPY_COV_IDX::X_X] = 0.0; diff --git a/perception/autoware_multi_object_tracker/lib/tracker/model/pedestrian_and_bicycle_tracker.cpp b/perception/autoware_multi_object_tracker/lib/tracker/model/pedestrian_and_bicycle_tracker.cpp index 1b8018351f5a5..21ce949231062 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/model/pedestrian_and_bicycle_tracker.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/model/pedestrian_and_bicycle_tracker.cpp @@ -24,15 +24,13 @@ namespace autoware::multi_object_tracker using Label = autoware_perception_msgs::msg::ObjectClassification; PedestrianAndBicycleTracker::PedestrianAndBicycleTracker( - const rclcpp::Time & time, const autoware_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & self_transform, const size_t channel_size, - const uint & channel_index) + const rclcpp::Time & time, const types::DynamicObject & object, const size_t channel_size) : Tracker(time, object.classification, channel_size), - pedestrian_tracker_(time, object, self_transform, channel_size, channel_index), - bicycle_tracker_(time, object, self_transform, channel_size, channel_index) + pedestrian_tracker_(time, object, channel_size), + bicycle_tracker_(time, object, channel_size) { // initialize existence probability - initializeExistenceProbabilities(channel_index, object.existence_probability); + initializeExistenceProbabilities(object.channel_index, object.existence_probability); } bool PedestrianAndBicycleTracker::predict(const rclcpp::Time & time) @@ -43,7 +41,7 @@ bool PedestrianAndBicycleTracker::predict(const rclcpp::Time & time) } bool PedestrianAndBicycleTracker::measure( - const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, + const types::DynamicObject & object, const rclcpp::Time & time, const geometry_msgs::msg::Transform & self_transform) { pedestrian_tracker_.measure(object, time, self_transform); @@ -56,7 +54,7 @@ bool PedestrianAndBicycleTracker::measure( } bool PedestrianAndBicycleTracker::getTrackedObject( - const rclcpp::Time & time, autoware_perception_msgs::msg::TrackedObject & object) const + const rclcpp::Time & time, types::DynamicObject & object) const { using Label = autoware_perception_msgs::msg::ObjectClassification; const uint8_t label = getHighestProbLabel(); diff --git a/perception/autoware_multi_object_tracker/lib/tracker/model/pedestrian_tracker.cpp b/perception/autoware_multi_object_tracker/lib/tracker/model/pedestrian_tracker.cpp index 2135514df8485..bc53689739439 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/model/pedestrian_tracker.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/model/pedestrian_tracker.cpp @@ -19,15 +19,13 @@ #include "autoware/multi_object_tracker/tracker/model/pedestrian_tracker.hpp" -#include "autoware/multi_object_tracker/utils/utils.hpp" -#include "autoware/object_recognition_utils/object_recognition_utils.hpp" -#include "autoware/universe_utils/geometry/boost_polygon_utils.hpp" -#include "autoware/universe_utils/math/normalization.hpp" -#include "autoware/universe_utils/math/unit_conversion.hpp" -#include "autoware/universe_utils/ros/msg_covariance.hpp" - #include #include +#include +#include +#include +#include +#include #include #include @@ -46,9 +44,7 @@ namespace autoware::multi_object_tracker using Label = autoware_perception_msgs::msg::ObjectClassification; PedestrianTracker::PedestrianTracker( - const rclcpp::Time & time, const autoware_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & /*self_transform*/, const size_t channel_size, - const uint & channel_index) + const rclcpp::Time & time, const types::DynamicObject & object, const size_t channel_size) : Tracker(time, object.classification, channel_size), logger_(rclcpp::get_logger("PedestrianTracker")), z_(object.kinematics.pose_with_covariance.pose.position.z) @@ -56,7 +52,7 @@ PedestrianTracker::PedestrianTracker( object_ = object; // initialize existence probability - initializeExistenceProbabilities(channel_index, object.existence_probability); + initializeExistenceProbabilities(object.channel_index, object.existence_probability); // OBJECT SHAPE MODEL bounding_box_ = { @@ -148,17 +144,16 @@ bool PedestrianTracker::predict(const rclcpp::Time & time) return motion_model_.predictState(time); } -autoware_perception_msgs::msg::DetectedObject PedestrianTracker::getUpdatingObject( - const autoware_perception_msgs::msg::DetectedObject & object, +types::DynamicObject PedestrianTracker::getUpdatingObject( + const types::DynamicObject & object, const geometry_msgs::msg::Transform & /*self_transform*/) const { - autoware_perception_msgs::msg::DetectedObject updating_object = object; + types::DynamicObject updating_object = object; return updating_object; } -bool PedestrianTracker::measureWithPose( - const autoware_perception_msgs::msg::DetectedObject & object) +bool PedestrianTracker::measureWithPose(const types::DynamicObject & object) { // update motion model bool is_updated = false; @@ -178,8 +173,7 @@ bool PedestrianTracker::measureWithPose( return is_updated; } -bool PedestrianTracker::measureWithShape( - const autoware_perception_msgs::msg::DetectedObject & object) +bool PedestrianTracker::measureWithShape(const types::DynamicObject & object) { constexpr double gain = 0.1; constexpr double gain_inv = 1.0 - gain; @@ -235,7 +229,7 @@ bool PedestrianTracker::measureWithShape( } bool PedestrianTracker::measure( - const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, + const types::DynamicObject & object, const rclcpp::Time & time, const geometry_msgs::msg::Transform & self_transform) { // keep the latest input object @@ -259,8 +253,7 @@ bool PedestrianTracker::measure( } // update object - const autoware_perception_msgs::msg::DetectedObject updating_object = - getUpdatingObject(object, self_transform); + const types::DynamicObject updating_object = getUpdatingObject(object, self_transform); measureWithPose(updating_object); measureWithShape(updating_object); @@ -269,9 +262,9 @@ bool PedestrianTracker::measure( } bool PedestrianTracker::getTrackedObject( - const rclcpp::Time & time, autoware_perception_msgs::msg::TrackedObject & object) const + const rclcpp::Time & time, types::DynamicObject & object) const { - object = autoware::object_recognition_utils::toTrackedObject(object_); + object = object_; object.object_id = getUUID(); object.classification = getClassification(); diff --git a/perception/autoware_multi_object_tracker/lib/tracker/model/tracker_base.cpp b/perception/autoware_multi_object_tracker/lib/tracker/model/tracker_base.cpp index 24e2b0c9f5acf..31ad1bf94cadd 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/model/tracker_base.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/model/tracker_base.cpp @@ -16,8 +16,6 @@ #include "autoware/multi_object_tracker/tracker/model/tracker_base.hpp" -#include "autoware/multi_object_tracker/utils/utils.hpp" - #include #include #include @@ -81,9 +79,8 @@ void Tracker::initializeExistenceProbabilities( } bool Tracker::updateWithMeasurement( - const autoware_perception_msgs::msg::DetectedObject & object, - const rclcpp::Time & measurement_time, const geometry_msgs::msg::Transform & self_transform, - const uint & channel_index) + const types::DynamicObject & object, const rclcpp::Time & measurement_time, + const geometry_msgs::msg::Transform & self_transform) { // Update existence probability { @@ -97,6 +94,7 @@ bool Tracker::updateWithMeasurement( constexpr float probability_false_detection = 0.2; // update measured channel probability without decay + const uint channel_index = object.channel_index; existence_probabilities_[channel_index] = updateProbability( existence_probabilities_[channel_index], probability_true_detection, probability_false_detection); @@ -202,7 +200,7 @@ void Tracker::updateClassification( geometry_msgs::msg::PoseWithCovariance Tracker::getPoseWithCovariance( const rclcpp::Time & time) const { - autoware_perception_msgs::msg::TrackedObject object; + types::DynamicObject object; getTrackedObject(time, object); return object.kinematics.pose_with_covariance; } diff --git a/perception/autoware_multi_object_tracker/lib/tracker/model/unknown_tracker.cpp b/perception/autoware_multi_object_tracker/lib/tracker/model/unknown_tracker.cpp index 2805e43b88323..ed01165ed8176 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/model/unknown_tracker.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/model/unknown_tracker.cpp @@ -15,14 +15,13 @@ #include "autoware/multi_object_tracker/tracker/model/unknown_tracker.hpp" -#include "autoware/multi_object_tracker/utils/utils.hpp" -#include "autoware/universe_utils/geometry/boost_polygon_utils.hpp" -#include "autoware/universe_utils/math/normalization.hpp" -#include "autoware/universe_utils/math/unit_conversion.hpp" -#include "autoware/universe_utils/ros/msg_covariance.hpp" - #include #include +#include +#include +#include +#include +#include #include #include @@ -34,15 +33,12 @@ #else #include #endif -#include "autoware/object_recognition_utils/object_recognition_utils.hpp" namespace autoware::multi_object_tracker { UnknownTracker::UnknownTracker( - const rclcpp::Time & time, const autoware_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & /*self_transform*/, const size_t channel_size, - const uint & channel_index) + const rclcpp::Time & time, const types::DynamicObject & object, const size_t channel_size) : Tracker(time, object.classification, channel_size), logger_(rclcpp::get_logger("UnknownTracker")), z_(object.kinematics.pose_with_covariance.pose.position.z) @@ -50,7 +46,7 @@ UnknownTracker::UnknownTracker( object_ = object; // initialize existence probability - initializeExistenceProbabilities(channel_index, object.existence_probability); + initializeExistenceProbabilities(object.channel_index, object.existence_probability); // initialize params // measurement noise covariance @@ -142,11 +138,10 @@ bool UnknownTracker::predict(const rclcpp::Time & time) return motion_model_.predictState(time); } -autoware_perception_msgs::msg::DetectedObject UnknownTracker::getUpdatingObject( - const autoware_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & /*self_transform*/) +types::DynamicObject UnknownTracker::getUpdatingObject( + const types::DynamicObject & object, const geometry_msgs::msg::Transform & /*self_transform*/) { - autoware_perception_msgs::msg::DetectedObject updating_object = object; + types::DynamicObject updating_object = object; // UNCERTAINTY MODEL if (!object.kinematics.has_position_covariance) { @@ -169,7 +164,7 @@ autoware_perception_msgs::msg::DetectedObject UnknownTracker::getUpdatingObject( return updating_object; } -bool UnknownTracker::measureWithPose(const autoware_perception_msgs::msg::DetectedObject & object) +bool UnknownTracker::measureWithPose(const types::DynamicObject & object) { // update motion model bool is_updated = false; @@ -190,7 +185,7 @@ bool UnknownTracker::measureWithPose(const autoware_perception_msgs::msg::Detect } bool UnknownTracker::measure( - const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, + const types::DynamicObject & object, const rclcpp::Time & time, const geometry_msgs::msg::Transform & self_transform) { // keep the latest input object @@ -207,17 +202,16 @@ bool UnknownTracker::measure( } // update object - const autoware_perception_msgs::msg::DetectedObject updating_object = - getUpdatingObject(object, self_transform); + const types::DynamicObject updating_object = getUpdatingObject(object, self_transform); measureWithPose(updating_object); return true; } bool UnknownTracker::getTrackedObject( - const rclcpp::Time & time, autoware_perception_msgs::msg::TrackedObject & object) const + const rclcpp::Time & time, types::DynamicObject & object) const { - object = autoware::object_recognition_utils::toTrackedObject(object_); + object = object_; object.object_id = getUUID(); object.classification = getClassification(); diff --git a/perception/autoware_multi_object_tracker/lib/tracker/model/vehicle_tracker.cpp b/perception/autoware_multi_object_tracker/lib/tracker/model/vehicle_tracker.cpp index 2d1f48a3ad5ee..749640ce4324a 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/model/vehicle_tracker.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/model/vehicle_tracker.cpp @@ -19,15 +19,15 @@ #include "autoware/multi_object_tracker/tracker/model/vehicle_tracker.hpp" -#include "autoware/multi_object_tracker/utils/utils.hpp" -#include "autoware/object_recognition_utils/object_recognition_utils.hpp" -#include "autoware/universe_utils/geometry/boost_polygon_utils.hpp" -#include "autoware/universe_utils/math/normalization.hpp" -#include "autoware/universe_utils/math/unit_conversion.hpp" -#include "autoware/universe_utils/ros/msg_covariance.hpp" +#include "autoware/multi_object_tracker/object_model/shapes.hpp" #include #include +#include +#include +#include +#include +#include #include #include @@ -47,9 +47,7 @@ using Label = autoware_perception_msgs::msg::ObjectClassification; VehicleTracker::VehicleTracker( const object_model::ObjectModel & object_model, const rclcpp::Time & time, - const autoware_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & /*self_transform*/, const size_t channel_size, - const uint & channel_index) + const types::DynamicObject & object, const size_t channel_size) : Tracker(time, object.classification, channel_size), object_model_(object_model), logger_(rclcpp::get_logger("VehicleTracker")), @@ -59,7 +57,7 @@ VehicleTracker::VehicleTracker( object_ = object; // initialize existence probability - initializeExistenceProbabilities(channel_index, object.existence_probability); + initializeExistenceProbabilities(object.channel_index, object.existence_probability); // velocity deviation threshold // if the predicted velocity is close to the observed velocity, @@ -71,8 +69,8 @@ VehicleTracker::VehicleTracker( bounding_box_ = { object.shape.dimensions.x, object.shape.dimensions.y, object.shape.dimensions.z}; } else { - autoware_perception_msgs::msg::DetectedObject bbox_object; - if (!utils::convertConvexHullToBoundingBox(object, bbox_object)) { + types::DynamicObject bbox_object; + if (!shapes::convertConvexHullToBoundingBox(object, bbox_object)) { RCLCPP_WARN( logger_, "VehicleTracker::VehicleTracker: Failed to convert convex hull to bounding " @@ -167,17 +165,16 @@ bool VehicleTracker::predict(const rclcpp::Time & time) return motion_model_.predictState(time); } -autoware_perception_msgs::msg::DetectedObject VehicleTracker::getUpdatingObject( - const autoware_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & self_transform) +types::DynamicObject VehicleTracker::getUpdatingObject( + const types::DynamicObject & object, const geometry_msgs::msg::Transform & self_transform) { - autoware_perception_msgs::msg::DetectedObject updating_object = object; + types::DynamicObject updating_object = object; // OBJECT SHAPE MODEL // convert to bounding box if input is convex shape - autoware_perception_msgs::msg::DetectedObject bbox_object = object; + types::DynamicObject bbox_object = object; if (object.shape.type != autoware_perception_msgs::msg::Shape::BOUNDING_BOX) { - if (!utils::convertConvexHullToBoundingBox(object, bbox_object)) { + if (!shapes::convertConvexHullToBoundingBox(object, bbox_object)) { RCLCPP_WARN( logger_, "VehicleTracker::getUpdatingObject: Failed to convert convex hull to bounding box."); @@ -191,16 +188,16 @@ autoware_perception_msgs::msg::DetectedObject VehicleTracker::getUpdatingObject( const double tracked_yaw = motion_model_.getStateElement(IDX::YAW); // get offset measurement - const int nearest_corner_index = utils::getNearestCornerOrSurface( + const int nearest_corner_index = shapes::getNearestCornerOrSurface( tracked_x, tracked_y, tracked_yaw, bounding_box_.width, bounding_box_.length, self_transform); - utils::calcAnchorPointOffset( + shapes::calcAnchorPointOffset( bounding_box_.width, bounding_box_.length, nearest_corner_index, bbox_object, tracked_yaw, updating_object, tracking_offset_); return updating_object; } -bool VehicleTracker::measureWithPose(const autoware_perception_msgs::msg::DetectedObject & object) +bool VehicleTracker::measureWithPose(const types::DynamicObject & object) { // current (predicted) state const double tracked_vel = motion_model_.getStateElement(IDX::VEL); @@ -242,7 +239,7 @@ bool VehicleTracker::measureWithPose(const autoware_perception_msgs::msg::Detect return is_updated; } -bool VehicleTracker::measureWithShape(const autoware_perception_msgs::msg::DetectedObject & object) +bool VehicleTracker::measureWithShape(const types::DynamicObject & object) { if (object.shape.type != autoware_perception_msgs::msg::Shape::BOUNDING_BOX) { // do not update shape if the input is not a bounding box @@ -295,7 +292,7 @@ bool VehicleTracker::measureWithShape(const autoware_perception_msgs::msg::Detec } bool VehicleTracker::measure( - const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, + const types::DynamicObject & object, const rclcpp::Time & time, const geometry_msgs::msg::Transform & self_transform) { // keep the latest input object @@ -320,8 +317,7 @@ bool VehicleTracker::measure( } // update object - const autoware_perception_msgs::msg::DetectedObject updating_object = - getUpdatingObject(object, self_transform); + const types::DynamicObject updating_object = getUpdatingObject(object, self_transform); measureWithPose(updating_object); measureWithShape(updating_object); @@ -329,9 +325,9 @@ bool VehicleTracker::measure( } bool VehicleTracker::getTrackedObject( - const rclcpp::Time & time, autoware_perception_msgs::msg::TrackedObject & object) const + const rclcpp::Time & time, types::DynamicObject & object) const { - object = autoware::object_recognition_utils::toTrackedObject(object_); + object = object_; object.object_id = getUUID(); object.classification = getClassification(); diff --git a/perception/autoware_multi_object_tracker/lib/tracker/motion_model/bicycle_motion_model.cpp b/perception/autoware_multi_object_tracker/lib/tracker/motion_model/bicycle_motion_model.cpp index c65efffe99a47..1e71bf8548b33 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/motion_model/bicycle_motion_model.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/motion_model/bicycle_motion_model.cpp @@ -20,13 +20,12 @@ #include "autoware/multi_object_tracker/tracker/motion_model/bicycle_motion_model.hpp" #include "autoware/multi_object_tracker/tracker/motion_model/motion_model_base.hpp" -#include "autoware/multi_object_tracker/utils/utils.hpp" -#include "autoware/universe_utils/math/normalization.hpp" -#include "autoware/universe_utils/math/unit_conversion.hpp" -#include "autoware/universe_utils/ros/msg_covariance.hpp" #include #include +#include +#include +#include #include diff --git a/perception/autoware_multi_object_tracker/lib/tracker/motion_model/ctrv_motion_model.cpp b/perception/autoware_multi_object_tracker/lib/tracker/motion_model/ctrv_motion_model.cpp index 700800e94ecd5..e10fbca073047 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/motion_model/ctrv_motion_model.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/motion_model/ctrv_motion_model.cpp @@ -20,13 +20,12 @@ #include "autoware/multi_object_tracker/tracker/motion_model/ctrv_motion_model.hpp" #include "autoware/multi_object_tracker/tracker/motion_model/motion_model_base.hpp" -#include "autoware/multi_object_tracker/utils/utils.hpp" -#include "autoware/universe_utils/math/normalization.hpp" -#include "autoware/universe_utils/math/unit_conversion.hpp" -#include "autoware/universe_utils/ros/msg_covariance.hpp" #include #include +#include +#include +#include namespace autoware::multi_object_tracker { diff --git a/perception/autoware_multi_object_tracker/lib/tracker/motion_model/cv_motion_model.cpp b/perception/autoware_multi_object_tracker/lib/tracker/motion_model/cv_motion_model.cpp index e139419197d79..fd3b03da398e1 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/motion_model/cv_motion_model.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/motion_model/cv_motion_model.cpp @@ -20,13 +20,12 @@ #include "autoware/multi_object_tracker/tracker/motion_model/cv_motion_model.hpp" #include "autoware/multi_object_tracker/tracker/motion_model/motion_model_base.hpp" -#include "autoware/multi_object_tracker/utils/utils.hpp" -#include "autoware/universe_utils/math/normalization.hpp" -#include "autoware/universe_utils/math/unit_conversion.hpp" -#include "autoware/universe_utils/ros/msg_covariance.hpp" #include #include +#include +#include +#include #include diff --git a/perception/autoware_multi_object_tracker/lib/uncertainty/uncertainty_processor.cpp b/perception/autoware_multi_object_tracker/lib/uncertainty/uncertainty_processor.cpp index ddfdc7ef7cb10..36d48d35f74b7 100644 --- a/perception/autoware_multi_object_tracker/lib/uncertainty/uncertainty_processor.cpp +++ b/perception/autoware_multi_object_tracker/lib/uncertainty/uncertainty_processor.cpp @@ -55,10 +55,10 @@ object_model::StateCovariance covarianceFromObjectClass(const ObjectClassificati return obj_class_model.measurement_covariance; } -DetectedObject modelUncertaintyByClass( - const DetectedObject & object, const ObjectClassification & object_class) +types::DynamicObject modelUncertaintyByClass( + const types::DynamicObject & object, const ObjectClassification & object_class) { - DetectedObject updating_object = object; + types::DynamicObject updating_object = object; // measurement noise covariance const object_model::StateCovariance measurement_covariance = @@ -87,8 +87,7 @@ DetectedObject modelUncertaintyByClass( pose_cov[XYZRPY_COV_IDX::YAW_Y] = 0.0; // yaw - y pose_cov[XYZRPY_COV_IDX::YAW_YAW] = measurement_covariance.yaw; // yaw - yaw const bool is_yaw_available = - object.kinematics.orientation_availability != - autoware_perception_msgs::msg::DetectedObjectKinematics::UNAVAILABLE; + object.kinematics.orientation_availability != types::OrientationAvailability::UNAVAILABLE; if (!is_yaw_available) { pose_cov[XYZRPY_COV_IDX::YAW_YAW] *= 1e3; // yaw is not available, multiply large value } @@ -103,10 +102,11 @@ DetectedObject modelUncertaintyByClass( return updating_object; } -DetectedObjects modelUncertainty(const DetectedObjects & detected_objects) +types::DynamicObjectList modelUncertainty(const types::DynamicObjectList & detected_objects) { - DetectedObjects updating_objects; + types::DynamicObjectList updating_objects; updating_objects.header = detected_objects.header; + updating_objects.channel_index = detected_objects.channel_index; for (const auto & object : detected_objects.objects) { if (object.kinematics.has_position_covariance) { updating_objects.objects.push_back(object); @@ -119,7 +119,7 @@ DetectedObjects modelUncertainty(const DetectedObjects & detected_objects) return updating_objects; } -void normalizeUncertainty(DetectedObjects & detected_objects) +void normalizeUncertainty(types::DynamicObjectList & detected_objects) { constexpr double min_cov_dist = 1e-4; constexpr double min_cov_rad = 1e-6; @@ -140,7 +140,7 @@ void normalizeUncertainty(DetectedObjects & detected_objects) } } -void addOdometryUncertainty(const Odometry & odometry, DetectedObjects & detected_objects) +void addOdometryUncertainty(const Odometry & odometry, types::DynamicObjectList & detected_objects) { const auto & odom_pose = odometry.pose.pose; const auto & odom_pose_cov = odometry.pose.covariance; diff --git a/perception/autoware_multi_object_tracker/src/debugger/debug_object.cpp b/perception/autoware_multi_object_tracker/src/debugger/debug_object.cpp index bc27525d85f55..6a1703e029920 100644 --- a/perception/autoware_multi_object_tracker/src/debugger/debug_object.cpp +++ b/perception/autoware_multi_object_tracker/src/debugger/debug_object.cpp @@ -80,8 +80,7 @@ void TrackerObjectDebugger::reset() void TrackerObjectDebugger::collect( const rclcpp::Time & message_time, const std::list> & list_tracker, - const uint & channel_index, - const autoware_perception_msgs::msg::DetectedObjects & detected_objects, + const types::DynamicObjectList & detected_objects, const std::unordered_map & direct_assignment, const std::unordered_map & /*reverse_assignment*/) { @@ -94,13 +93,13 @@ void TrackerObjectDebugger::collect( ++tracker_itr, ++tracker_idx) { ObjectData object_data; object_data.time = message_time; - object_data.channel_id = channel_index; - autoware_perception_msgs::msg::TrackedObject tracked_object; + types::DynamicObject tracked_object; (*(tracker_itr))->getTrackedObject(message_time, tracked_object); object_data.uuid = uuidToBoostUuid(tracked_object.object_id); object_data.uuid_int = uuidToInt(object_data.uuid); object_data.uuid_str = uuidToString(tracked_object.object_id); + object_data.channel_id = tracked_object.channel_index; // tracker bool is_associated = false; diff --git a/perception/autoware_multi_object_tracker/src/debugger/debug_object.hpp b/perception/autoware_multi_object_tracker/src/debugger/debug_object.hpp index e564afc9fd9d0..d507a0350bbb8 100644 --- a/perception/autoware_multi_object_tracker/src/debugger/debug_object.hpp +++ b/perception/autoware_multi_object_tracker/src/debugger/debug_object.hpp @@ -88,8 +88,7 @@ class TrackerObjectDebugger } void collect( const rclcpp::Time & message_time, const std::list> & list_tracker, - const uint & channel_index, - const autoware_perception_msgs::msg::DetectedObjects & detected_objects, + const types::DynamicObjectList & detected_objects, const std::unordered_map & direct_assignment, const std::unordered_map & reverse_assignment); diff --git a/perception/autoware_multi_object_tracker/src/debugger/debugger.cpp b/perception/autoware_multi_object_tracker/src/debugger/debugger.cpp index 9d830bb9e5b81..3eebb3c11ee3e 100644 --- a/perception/autoware_multi_object_tracker/src/debugger/debugger.cpp +++ b/perception/autoware_multi_object_tracker/src/debugger/debugger.cpp @@ -185,15 +185,13 @@ void TrackerDebugger::endPublishTime(const rclcpp::Time & now, const rclcpp::Tim void TrackerDebugger::collectObjectInfo( const rclcpp::Time & message_time, const std::list> & list_tracker, - const uint & channel_index, - const autoware_perception_msgs::msg::DetectedObjects & detected_objects, + const types::DynamicObjectList & detected_objects, const std::unordered_map & direct_assignment, const std::unordered_map & reverse_assignment) { if (!debug_settings_.publish_debug_markers) return; object_debugger_.collect( - message_time, list_tracker, channel_index, detected_objects, direct_assignment, - reverse_assignment); + message_time, list_tracker, detected_objects, direct_assignment, reverse_assignment); } // ObjectDebugger diff --git a/perception/autoware_multi_object_tracker/src/debugger/debugger.hpp b/perception/autoware_multi_object_tracker/src/debugger/debugger.hpp index 2c05da0c999e2..3df901a63505c 100644 --- a/perception/autoware_multi_object_tracker/src/debugger/debugger.hpp +++ b/perception/autoware_multi_object_tracker/src/debugger/debugger.hpp @@ -101,8 +101,7 @@ class TrackerDebugger } void collectObjectInfo( const rclcpp::Time & message_time, const std::list> & list_tracker, - const uint & channel_index, - const autoware_perception_msgs::msg::DetectedObjects & detected_objects, + const types::DynamicObjectList & detected_objects, const std::unordered_map & direct_assignment, const std::unordered_map & reverse_assignment); void publishObjectsMarkers(); diff --git a/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp b/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp index d2d2d3e087c4e..333b301ce9fcf 100644 --- a/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp +++ b/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp @@ -17,8 +17,8 @@ #include "multi_object_tracker_node.hpp" +#include "autoware/multi_object_tracker/object_model/shapes.hpp" #include "autoware/multi_object_tracker/uncertainty/uncertainty_processor.hpp" -#include "autoware/multi_object_tracker/utils/utils.hpp" #include #include @@ -95,7 +95,8 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) get_parameter("selected_input_channels").as_string_array(); // ROS interface - Publisher - tracked_objects_pub_ = create_publisher("output", rclcpp::QoS{1}); + tracked_objects_pub_ = + create_publisher("output", rclcpp::QoS{1}); // ROS interface - Input channels // Get input channels @@ -239,18 +240,18 @@ void MultiObjectTracker::onTrigger() // process start last_updated_time_ = current_time; - const rclcpp::Time latest_time(objects_list.back().second.header.stamp); + const rclcpp::Time latest_time(objects_list.back().header.stamp); debugger_->startMeasurementTime(this->now(), latest_time); - // run process for each DetectedObjects + // run process for each DynamicObject for (const auto & objects_data : objects_list) { - runProcess(objects_data.second, objects_data.first); + runProcess(objects_data); } // process end debugger_->endMeasurementTime(this->now()); // Publish without delay compensation if (!publish_timer_) { - const auto latest_object_time = rclcpp::Time(objects_list.back().second.header.stamp); + const auto latest_object_time = rclcpp::Time(objects_list.back().header.stamp); checkAndPublish(latest_object_time); } } @@ -278,8 +279,7 @@ void MultiObjectTracker::onTimer() if (should_publish) checkAndPublish(current_time); } -void MultiObjectTracker::runProcess( - const DetectedObjects & input_objects, const uint & channel_index) +void MultiObjectTracker::runProcess(const types::DynamicObjectList & input_objects) { // Get the time of the measurement const rclcpp::Time measurement_time = @@ -293,9 +293,8 @@ void MultiObjectTracker::runProcess( } // Transform the objects to the world frame - DetectedObjects transformed_objects; - if (!autoware::object_recognition_utils::transformObjects( - input_objects, world_frame_id_, tf_buffer_, transformed_objects)) { + types::DynamicObjectList transformed_objects; + if (!shapes::transformObjects(input_objects, world_frame_id_, tf_buffer_, transformed_objects)) { return; } @@ -350,19 +349,19 @@ void MultiObjectTracker::runProcess( // Collect debug information - tracker list, existence probabilities, association results debugger_->collectObjectInfo( - measurement_time, processor_->getListTracker(), channel_index, transformed_objects, - direct_assignment, reverse_assignment); + measurement_time, processor_->getListTracker(), transformed_objects, direct_assignment, + reverse_assignment); } /* tracker update */ - processor_->update(transformed_objects, *self_transform, direct_assignment, channel_index); + processor_->update(transformed_objects, *self_transform, direct_assignment); /* tracker pruning */ processor_->prune(measurement_time); /* spawn new tracker */ - if (input_manager_->isChannelSpawnEnabled(channel_index)) { - processor_->spawn(transformed_objects, *self_transform, reverse_assignment, channel_index); + if (input_manager_->isChannelSpawnEnabled(input_objects.channel_index)) { + processor_->spawn(transformed_objects, reverse_assignment); } } @@ -387,7 +386,7 @@ void MultiObjectTracker::publish(const rclcpp::Time & time) const return; } // Create output msg - TrackedObjects output_msg, tentative_objects_msg; + autoware_perception_msgs::msg::TrackedObjects output_msg; output_msg.header.frame_id = world_frame_id_; processor_->getTrackedObjects(time, output_msg); @@ -399,7 +398,7 @@ void MultiObjectTracker::publish(const rclcpp::Time & time) const debugger_->endPublishTime(this->now(), time); if (debugger_->shouldPublishTentativeObjects()) { - TrackedObjects tentative_output_msg; + autoware_perception_msgs::msg::TrackedObjects tentative_output_msg; tentative_output_msg.header.frame_id = world_frame_id_; processor_->getTentativeObjects(time, tentative_output_msg); debugger_->publishTentativeObjects(tentative_output_msg); diff --git a/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.hpp b/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.hpp index 79a8c1b98dcca..0472d67617f7f 100644 --- a/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.hpp +++ b/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.hpp @@ -20,6 +20,7 @@ #define MULTI_OBJECT_TRACKER_NODE_HPP_ #include "autoware/multi_object_tracker/association/association.hpp" +#include "autoware/multi_object_tracker/object_model/types.hpp" #include "autoware/multi_object_tracker/tracker/model/tracker_base.hpp" #include "debugger/debugger.hpp" #include "processor/input_manager.hpp" @@ -55,10 +56,6 @@ namespace autoware::multi_object_tracker { -using DetectedObject = autoware_perception_msgs::msg::DetectedObject; -using DetectedObjects = autoware_perception_msgs::msg::DetectedObjects; -using TrackedObjects = autoware_perception_msgs::msg::TrackedObjects; - class MultiObjectTracker : public rclcpp::Node { public: @@ -66,8 +63,9 @@ class MultiObjectTracker : public rclcpp::Node private: // ROS interface - rclcpp::Publisher::SharedPtr tracked_objects_pub_; - rclcpp::Subscription::SharedPtr detected_object_sub_; + rclcpp::Publisher::SharedPtr tracked_objects_pub_; + rclcpp::Subscription::SharedPtr + detected_object_sub_; tf2_ros::Buffer tf_buffer_; tf2_ros::TransformListener tf_listener_; @@ -100,7 +98,7 @@ class MultiObjectTracker : public rclcpp::Node void onTrigger(); // publish processes - void runProcess(const DetectedObjects & input_objects, const uint & channel_index); + void runProcess(const types::DynamicObjectList & input_objects); void checkAndPublish(const rclcpp::Time & time); void publish(const rclcpp::Time & time) const; inline bool shouldTrackerPublish(const std::shared_ptr tracker) const; diff --git a/perception/autoware_multi_object_tracker/src/processor/input_manager.cpp b/perception/autoware_multi_object_tracker/src/processor/input_manager.cpp index d5b12ed7b2b82..bc461191af271 100644 --- a/perception/autoware_multi_object_tracker/src/processor/input_manager.cpp +++ b/perception/autoware_multi_object_tracker/src/processor/input_manager.cpp @@ -14,6 +14,8 @@ #include "input_manager.hpp" +#include "autoware/multi_object_tracker/object_model/types.hpp" + #include #include @@ -53,10 +55,13 @@ void InputStream::init(const InputChannel & input_channel) void InputStream::onMessage( const autoware_perception_msgs::msg::DetectedObjects::ConstSharedPtr msg) { - const DetectedObjects & objects = *msg; + const autoware_perception_msgs::msg::DetectedObjects & objects = *msg; + + types::DynamicObjectList dynamic_objects = types::toDynamicObjectList(objects, index_); // Model the object uncertainty only if it is not available - DetectedObjects objects_with_uncertainty = uncertainty::modelUncertainty(objects); + types::DynamicObjectList objects_with_uncertainty = + uncertainty::modelUncertainty(dynamic_objects); // Move the objects_with_uncertainty to the objects queue objects_que_.push_back(std::move(objects_with_uncertainty)); @@ -167,8 +172,7 @@ void InputStream::getObjectsOlderThan( // Add the object if the object is older than the specified latest time if (object_time <= object_latest_time) { - std::pair objects_pair(index_, objects); - objects_list.push_back(objects_pair); + objects_list.push_back(objects); } } @@ -216,10 +220,11 @@ void InputManager::init(const std::vector & input_channels) RCLCPP_INFO( node_.get_logger(), "InputManager::init Initializing %s input stream from %s", input_channels[i].long_name.c_str(), input_channels[i].input_topic.c_str()); - std::function func = - std::bind(&InputStream::onMessage, input_streams_.at(i), std::placeholders::_1); - sub_objects_array_.at(i) = node_.create_subscription( - input_channels[i].input_topic, rclcpp::QoS{1}, func); + std::function + func = std::bind(&InputStream::onMessage, input_streams_.at(i), std::placeholders::_1); + sub_objects_array_.at(i) = + node_.create_subscription( + input_channels[i].input_topic, rclcpp::QoS{1}, func); } // Check if any spawn enabled input streams @@ -339,15 +344,14 @@ bool InputManager::getObjects(const rclcpp::Time & now, ObjectsList & objects_li // Sort objects by timestamp std::sort( objects_list.begin(), objects_list.end(), - [](const std::pair & a, const std::pair & b) { - return (rclcpp::Time(a.second.header.stamp) - rclcpp::Time(b.second.header.stamp)).seconds() < - 0; + [](const types::DynamicObjectList & a, const types::DynamicObjectList & b) { + return (rclcpp::Time(a.header.stamp) - rclcpp::Time(b.header.stamp)).seconds() < 0; }); // Update the latest exported object time bool is_any_object = !objects_list.empty(); if (is_any_object) { - latest_exported_object_time_ = rclcpp::Time(objects_list.back().second.header.stamp); + latest_exported_object_time_ = rclcpp::Time(objects_list.back().header.stamp); } else { // check time jump back if (now < latest_exported_object_time_) { diff --git a/perception/autoware_multi_object_tracker/src/processor/input_manager.hpp b/perception/autoware_multi_object_tracker/src/processor/input_manager.hpp index 01b3148251743..189d7b7dc48fe 100644 --- a/perception/autoware_multi_object_tracker/src/processor/input_manager.hpp +++ b/perception/autoware_multi_object_tracker/src/processor/input_manager.hpp @@ -15,9 +15,10 @@ #ifndef PROCESSOR__INPUT_MANAGER_HPP_ #define PROCESSOR__INPUT_MANAGER_HPP_ +#include "autoware/multi_object_tracker/object_model/types.hpp" #include "rclcpp/rclcpp.hpp" -#include "autoware_perception_msgs/msg/detected_objects.hpp" +#include #include #include @@ -28,8 +29,7 @@ namespace autoware::multi_object_tracker { -using DetectedObjects = autoware_perception_msgs::msg::DetectedObjects; -using ObjectsList = std::vector>; +using ObjectsList = std::vector; struct InputChannel { @@ -82,11 +82,10 @@ class InputStream bool is_spawn_enabled_{}; size_t que_size_{30}; - std::deque objects_que_; + std::deque objects_que_; std::function func_trigger_; - // bool is_time_initialized_{false}; int initial_count_{0}; double latency_mean_{}; double latency_var_{}; @@ -115,7 +114,8 @@ class InputManager private: rclcpp::Node & node_; - std::vector::SharedPtr> sub_objects_array_{}; + std::vector::SharedPtr> + sub_objects_array_{}; bool is_initialized_{false}; rclcpp::Time latest_exported_object_time_; diff --git a/perception/autoware_multi_object_tracker/src/processor/processor.cpp b/perception/autoware_multi_object_tracker/src/processor/processor.cpp index b3bcd018faf9d..02ad0767dc815 100644 --- a/perception/autoware_multi_object_tracker/src/processor/processor.cpp +++ b/perception/autoware_multi_object_tracker/src/processor/processor.cpp @@ -15,10 +15,13 @@ #include "processor.hpp" #include "autoware/multi_object_tracker/object_model/object_model.hpp" +#include "autoware/multi_object_tracker/object_model/shapes.hpp" +#include "autoware/multi_object_tracker/object_model/types.hpp" #include "autoware/multi_object_tracker/tracker/tracker.hpp" -#include "autoware/object_recognition_utils/object_recognition_utils.hpp" -#include "autoware_perception_msgs/msg/tracked_objects.hpp" +#include + +#include #include #include @@ -44,9 +47,9 @@ void TrackerProcessor::predict(const rclcpp::Time & time) } void TrackerProcessor::update( - const autoware_perception_msgs::msg::DetectedObjects & detected_objects, + const types::DynamicObjectList & detected_objects, const geometry_msgs::msg::Transform & self_transform, - const std::unordered_map & direct_assignment, const uint & channel_index) + const std::unordered_map & direct_assignment) { int tracker_idx = 0; const auto & time = detected_objects.header.stamp; @@ -55,8 +58,7 @@ void TrackerProcessor::update( if (direct_assignment.find(tracker_idx) != direct_assignment.end()) { // found const auto & associated_object = detected_objects.objects.at(direct_assignment.find(tracker_idx)->second); - (*(tracker_itr)) - ->updateWithMeasurement(associated_object, time, self_transform, channel_index); + (*(tracker_itr))->updateWithMeasurement(associated_object, time, self_transform); } else { // not found (*(tracker_itr))->updateWithoutMeasurement(time); } @@ -64,9 +66,8 @@ void TrackerProcessor::update( } void TrackerProcessor::spawn( - const autoware_perception_msgs::msg::DetectedObjects & detected_objects, - const geometry_msgs::msg::Transform & self_transform, - const std::unordered_map & reverse_assignment, const uint & channel_index) + const types::DynamicObjectList & detected_objects, + const std::unordered_map & reverse_assignment) { const auto & time = detected_objects.header.stamp; for (size_t i = 0; i < detected_objects.objects.size(); ++i) { @@ -74,46 +75,36 @@ void TrackerProcessor::spawn( continue; } const auto & new_object = detected_objects.objects.at(i); - std::shared_ptr tracker = - createNewTracker(new_object, time, self_transform, channel_index); + std::shared_ptr tracker = createNewTracker(new_object, time); if (tracker) list_tracker_.push_back(tracker); } } std::shared_ptr TrackerProcessor::createNewTracker( - const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, - const geometry_msgs::msg::Transform & self_transform, const uint & channel_index) const + const types::DynamicObject & object, const rclcpp::Time & time) const { const LabelType label = autoware::object_recognition_utils::getHighestProbLabel(object.classification); if (config_.tracker_map.count(label) != 0) { const auto tracker = config_.tracker_map.at(label); if (tracker == "bicycle_tracker") - return std::make_shared( - time, object, self_transform, config_.channel_size, channel_index); + return std::make_shared(time, object, config_.channel_size); if (tracker == "big_vehicle_tracker") return std::make_shared( - object_model::big_vehicle, time, object, self_transform, config_.channel_size, - channel_index); + object_model::big_vehicle, time, object, config_.channel_size); if (tracker == "multi_vehicle_tracker") - return std::make_shared( - time, object, self_transform, config_.channel_size, channel_index); + return std::make_shared(time, object, config_.channel_size); if (tracker == "normal_vehicle_tracker") return std::make_shared( - object_model::normal_vehicle, time, object, self_transform, config_.channel_size, - channel_index); + object_model::normal_vehicle, time, object, config_.channel_size); if (tracker == "pass_through_tracker") - return std::make_shared( - time, object, self_transform, config_.channel_size, channel_index); + return std::make_shared(time, object, config_.channel_size); if (tracker == "pedestrian_and_bicycle_tracker") - return std::make_shared( - time, object, self_transform, config_.channel_size, channel_index); + return std::make_shared(time, object, config_.channel_size); if (tracker == "pedestrian_tracker") - return std::make_shared( - time, object, self_transform, config_.channel_size, channel_index); + return std::make_shared(time, object, config_.channel_size); } - return std::make_shared( - time, object, self_transform, config_.channel_size, channel_index); + return std::make_shared(time, object, config_.channel_size); } void TrackerProcessor::prune(const rclcpp::Time & time) @@ -143,12 +134,12 @@ void TrackerProcessor::removeOverlappedTracker(const rclcpp::Time & time) { // Iterate through the list of trackers for (auto itr1 = list_tracker_.begin(); itr1 != list_tracker_.end(); ++itr1) { - autoware_perception_msgs::msg::TrackedObject object1; + types::DynamicObject object1; if (!(*itr1)->getTrackedObject(time, object1)) continue; // Compare the current tracker with the remaining trackers for (auto itr2 = std::next(itr1); itr2 != list_tracker_.end(); ++itr2) { - autoware_perception_msgs::msg::TrackedObject object2; + types::DynamicObject object2; if (!(*itr2)->getTrackedObject(time, object2)) continue; // Calculate the distance between the two objects @@ -164,9 +155,8 @@ void TrackerProcessor::removeOverlappedTracker(const rclcpp::Time & time) } // Check the Intersection over Union (IoU) between the two objects - const double min_union_iou_area = 1e-2; - const auto iou = - autoware::object_recognition_utils::get2dIoU(object1, object2, min_union_iou_area); + constexpr double min_union_iou_area = 1e-2; + const auto iou = shapes::get2dIoU(object1, object2, min_union_iou_area); const auto & label1 = (*itr1)->getHighestProbLabel(); const auto & label2 = (*itr2)->getHighestProbLabel(); bool should_delete_tracker1 = false; @@ -225,13 +215,13 @@ void TrackerProcessor::getTrackedObjects( const rclcpp::Time & time, autoware_perception_msgs::msg::TrackedObjects & tracked_objects) const { tracked_objects.header.stamp = time; + types::DynamicObject tracked_object; for (const auto & tracker : list_tracker_) { // Skip if the tracker is not confident if (!isConfidentTracker(tracker)) continue; // Get the tracked object, extrapolated to the given time - autoware_perception_msgs::msg::TrackedObject tracked_object; if (tracker->getTrackedObject(time, tracked_object)) { - tracked_objects.objects.push_back(tracked_object); + tracked_objects.objects.push_back(toTrackedObjectMsg(tracked_object)); } } } @@ -241,11 +231,11 @@ void TrackerProcessor::getTentativeObjects( autoware_perception_msgs::msg::TrackedObjects & tentative_objects) const { tentative_objects.header.stamp = time; + types::DynamicObject tracked_object; for (const auto & tracker : list_tracker_) { if (!isConfidentTracker(tracker)) { - autoware_perception_msgs::msg::TrackedObject tracked_object; if (tracker->getTrackedObject(time, tracked_object)) { - tentative_objects.objects.push_back(tracked_object); + tentative_objects.objects.push_back(toTrackedObjectMsg(tracked_object)); } } } diff --git a/perception/autoware_multi_object_tracker/src/processor/processor.hpp b/perception/autoware_multi_object_tracker/src/processor/processor.hpp index 80ca92bc43671..ad296b1c07d8d 100644 --- a/perception/autoware_multi_object_tracker/src/processor/processor.hpp +++ b/perception/autoware_multi_object_tracker/src/processor/processor.hpp @@ -15,6 +15,7 @@ #ifndef PROCESSOR__PROCESSOR_HPP_ #define PROCESSOR__PROCESSOR_HPP_ +#include "autoware/multi_object_tracker/object_model/types.hpp" #include "autoware/multi_object_tracker/tracker/model/tracker_base.hpp" #include @@ -53,13 +54,12 @@ class TrackerProcessor // tracker processes void predict(const rclcpp::Time & time); void update( - const autoware_perception_msgs::msg::DetectedObjects & detected_objects, + const types::DynamicObjectList & detected_objects, const geometry_msgs::msg::Transform & self_transform, - const std::unordered_map & direct_assignment, const uint & channel_index); + const std::unordered_map & direct_assignment); void spawn( - const autoware_perception_msgs::msg::DetectedObjects & detected_objects, - const geometry_msgs::msg::Transform & self_transform, - const std::unordered_map & reverse_assignment, const uint & channel_index); + const types::DynamicObjectList & detected_objects, + const std::unordered_map & reverse_assignment); void prune(const rclcpp::Time & time); // output @@ -79,8 +79,7 @@ class TrackerProcessor void removeOldTracker(const rclcpp::Time & time); void removeOverlappedTracker(const rclcpp::Time & time); std::shared_ptr createNewTracker( - const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, - const geometry_msgs::msg::Transform & self_transform, const uint & channel_index) const; + const types::DynamicObject & object, const rclcpp::Time & time) const; }; } // namespace autoware::multi_object_tracker From ca3afdd266c15f3669d6f30fd472e2ee72578b74 Mon Sep 17 00:00:00 2001 From: Masaki Baba Date: Tue, 24 Dec 2024 09:03:41 +0900 Subject: [PATCH 077/334] feat(image_projection_based_fusion): add cache for camera projection (#9635) * add camera_projection class and projection cache Signed-off-by: a-maumau * style(pre-commit): autofix * fix FOV filtering Signed-off-by: a-maumau * style(pre-commit): autofix * remove unused includes Signed-off-by: a-maumau * update schema Signed-off-by: a-maumau * fix cpplint error Signed-off-by: a-maumau * apply suggestion: more simple and effcient computation Signed-off-by: a-maumau * correct terminology Signed-off-by: a-maumau * style(pre-commit): autofix * fix comments Signed-off-by: a-maumau * fix var name Signed-off-by: a-maumau Co-authored-by: Taekjin LEE * fix variable names Signed-off-by: a-maumau Co-authored-by: Taekjin LEE * fix variable names Signed-off-by: a-maumau Co-authored-by: Taekjin LEE * fix variable names Signed-off-by: a-maumau Co-authored-by: Taekjin LEE * fix variable names Signed-off-by: a-maumau Co-authored-by: Taekjin LEE * fix variable names Signed-off-by: a-maumau * fix initialization Co-authored-by: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Signed-off-by: a-maumau * add verification to point_project_to_unrectified_image when loading Co-authored-by: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Signed-off-by: a-maumau * chore: add option description to project points to unrectified image Signed-off-by: Taekjin LEE --------- Signed-off-by: a-maumau Signed-off-by: Taekjin LEE Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Taekjin LEE Co-authored-by: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Co-authored-by: Taekjin LEE --- .../CMakeLists.txt | 1 + .../README.md | 6 + .../config/fusion_common.param.yaml | 9 +- .../camera_projection.hpp | 81 ++++++ .../fusion_node.hpp | 11 +- .../pointpainting_fusion/node.hpp | 3 - .../roi_cluster_fusion/node.hpp | 1 - .../roi_detected_object_fusion/node.hpp | 8 +- .../roi_pointcloud_fusion/node.hpp | 3 +- .../segmentation_pointcloud_fusion/node.hpp | 2 +- .../utils/utils.hpp | 4 - .../schema/fusion_common.schema.json | 20 ++ .../src/camera_projection.cpp | 252 ++++++++++++++++++ .../src/fusion_node.cpp | 52 +++- .../src/pointpainting_fusion/node.cpp | 57 ++-- .../src/roi_cluster_fusion/node.cpp | 31 +-- .../src/roi_detected_object_fusion/node.cpp | 39 ++- .../src/roi_pointcloud_fusion/node.cpp | 75 +++--- .../segmentation_pointcloud_fusion/node.cpp | 20 +- .../src/utils/utils.cpp | 14 - 20 files changed, 522 insertions(+), 167 deletions(-) create mode 100644 perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/camera_projection.hpp create mode 100644 perception/autoware_image_projection_based_fusion/src/camera_projection.cpp diff --git a/perception/autoware_image_projection_based_fusion/CMakeLists.txt b/perception/autoware_image_projection_based_fusion/CMakeLists.txt index 73d305d2ab2a8..7c8160d6fe1b7 100644 --- a/perception/autoware_image_projection_based_fusion/CMakeLists.txt +++ b/perception/autoware_image_projection_based_fusion/CMakeLists.txt @@ -16,6 +16,7 @@ endif() # Build non-CUDA dependent nodes ament_auto_add_library(${PROJECT_NAME} SHARED + src/camera_projection.cpp src/fusion_node.cpp src/debugger.cpp src/utils/geometry.cpp diff --git a/perception/autoware_image_projection_based_fusion/README.md b/perception/autoware_image_projection_based_fusion/README.md index c976697b0396d..dcf35e45bbd9d 100644 --- a/perception/autoware_image_projection_based_fusion/README.md +++ b/perception/autoware_image_projection_based_fusion/README.md @@ -66,6 +66,12 @@ ros2 launch autoware_image_projection_based_fusion pointpainting_fusion.launch.x The rclcpp::TimerBase timer could not break a for loop, therefore even if time is out when fusing a roi msg at the middle, the program will run until all msgs are fused. +### Approximate camera projection + +For algorithms like `pointpainting_fusion`, the computation required to project points onto an unrectified (raw) image can be substantial. To address this, an option is provided to reduce the computational load. Set the [`approximate_camera_projection parameter`](config/fusion_common.param.yaml) to `true` for each camera (ROIs). If the corresponding `point_project_to_unrectified_image` parameter is also set to true, the projections will be pre-cached. + +The cached projections are calculated using a grid, with the grid size specified by the `approximation_grid_width_size` and `approximation_grid_height_size` parameters in the [configuration file](config/fusion_common.param.yaml). The centers of the grid are used as the projected points. + ### Detail description of each fusion's algorithm is in the following links | Fusion Name | Description | Detail | diff --git a/perception/autoware_image_projection_based_fusion/config/fusion_common.param.yaml b/perception/autoware_image_projection_based_fusion/config/fusion_common.param.yaml index 347cb57b484e9..86db3bad4f8f8 100644 --- a/perception/autoware_image_projection_based_fusion/config/fusion_common.param.yaml +++ b/perception/autoware_image_projection_based_fusion/config/fusion_common.param.yaml @@ -4,7 +4,8 @@ timeout_ms: 70.0 match_threshold_ms: 50.0 image_buffer_size: 15 - point_project_to_unrectified_image: false + # projection setting for each ROI whether unrectify image + point_project_to_unrectified_image: [false, false, false, false, false, false] debug_mode: false filter_scope_min_x: -100.0 filter_scope_min_y: -100.0 @@ -13,5 +14,11 @@ filter_scope_max_y: 100.0 filter_scope_max_z: 100.0 + # camera cache setting for each ROI + approximate_camera_projection: [true, true, true, true, true, true] + # grid size in pixels + approximation_grid_cell_width: 1.0 + approximation_grid_cell_height: 1.0 + # debug parameters publish_processing_time_detail: false diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/camera_projection.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/camera_projection.hpp new file mode 100644 index 0000000000000..f9b3158b1672a --- /dev/null +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/camera_projection.hpp @@ -0,0 +1,81 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__IMAGE_PROJECTION_BASED_FUSION__CAMERA_PROJECTION_HPP_ +#define AUTOWARE__IMAGE_PROJECTION_BASED_FUSION__CAMERA_PROJECTION_HPP_ + +#define EIGEN_MPL2_ONLY + +#include +#include + +#include + +#include + +#include + +namespace autoware::image_projection_based_fusion +{ +struct PixelPos +{ + float x; + float y; +}; + +class CameraProjection +{ +public: + explicit CameraProjection( + const sensor_msgs::msg::CameraInfo & camera_info, const float grid_cell_width, + const float grid_cell_height, const bool unrectify, const bool use_approximation); + CameraProjection() : cell_width_(1.0), cell_height_(1.0), unrectify_(false) {} + void initialize(); + std::function calcImageProjectedPoint; + sensor_msgs::msg::CameraInfo getCameraInfo(); + bool isOutsideHorizontalView(const float px, const float pz); + bool isOutsideVerticalView(const float py, const float pz); + bool isOutsideFOV(const float px, const float py, const float pz); + +protected: + bool calcRectifiedImageProjectedPoint( + const cv::Point3d & point3d, Eigen::Vector2d & projected_point); + bool calcRawImageProjectedPoint(const cv::Point3d & point3d, Eigen::Vector2d & projected_point); + bool calcRawImageProjectedPointWithApproximation( + const cv::Point3d & point3d, Eigen::Vector2d & projected_point); + void initializeCache(); + + sensor_msgs::msg::CameraInfo camera_info_; + uint32_t image_height_, image_width_; + double tan_h_x_, tan_h_y_; + double fov_left_, fov_right_, fov_top_, fov_bottom_; + + uint32_t cache_size_; + float cell_width_; + float cell_height_; + float inv_cell_width_; + float inv_cell_height_; + int grid_width_; + int grid_height_; + + bool unrectify_; + bool use_approximation_; + + std::unique_ptr projection_cache_; + image_geometry::PinholeCameraModel camera_model_; +}; + +} // namespace autoware::image_projection_based_fusion + +#endif // AUTOWARE__IMAGE_PROJECTION_BASED_FUSION__CAMERA_PROJECTION_HPP_ diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp index 04ecf89faa0d4..239d406650ce8 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp @@ -15,6 +15,7 @@ #ifndef AUTOWARE__IMAGE_PROJECTION_BASED_FUSION__FUSION_NODE_HPP_ #define AUTOWARE__IMAGE_PROJECTION_BASED_FUSION__FUSION_NODE_HPP_ +#include #include #include #include @@ -55,6 +56,7 @@ using sensor_msgs::msg::PointCloud2; using tier4_perception_msgs::msg::DetectedObjectsWithFeature; using tier4_perception_msgs::msg::DetectedObjectWithFeature; using PointCloud = pcl::PointCloud; +using autoware::image_projection_based_fusion::CameraProjection; using autoware_perception_msgs::msg::ObjectClassification; template @@ -86,7 +88,7 @@ class FusionNode : public rclcpp::Node virtual void fuseOnSingleImage( const TargetMsg3D & input_msg, const std::size_t image_id, const Msg2D & input_roi_msg, - const sensor_msgs::msg::CameraInfo & camera_info, TargetMsg3D & output_msg) = 0; + TargetMsg3D & output_msg) = 0; // set args if you need virtual void postprocess(TargetMsg3D & output_msg); @@ -100,11 +102,16 @@ class FusionNode : public rclcpp::Node tf2_ros::Buffer tf_buffer_; tf2_ros::TransformListener tf_listener_; - bool point_project_to_unrectified_image_{false}; + std::vector point_project_to_unrectified_image_; // camera_info std::map camera_info_map_; std::vector::SharedPtr> camera_info_subs_; + // camera projection + std::vector camera_projectors_; + std::vector approx_camera_projection_; + float approx_grid_cell_w_size_; + float approx_grid_cell_h_size_; rclcpp::TimerBase::SharedPtr timer_; double timeout_ms_{}; diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/node.hpp index 8c0e2ed78fc6c..cd6cd87976522 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/node.hpp @@ -53,15 +53,12 @@ class PointPaintingFusionNode void fuseOnSingleImage( const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const std::size_t image_id, const DetectedObjectsWithFeature & input_roi_msg, - const sensor_msgs::msg::CameraInfo & camera_info, sensor_msgs::msg::PointCloud2 & painted_pointcloud_msg) override; void postprocess(sensor_msgs::msg::PointCloud2 & painted_pointcloud_msg) override; rclcpp::Publisher::SharedPtr obj_pub_ptr_; - std::vector tan_h_; // horizontal field of view - int omp_num_threads_{1}; float score_threshold_{0.0}; std::vector class_names_; diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_cluster_fusion/node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_cluster_fusion/node.hpp index be05c0a1c4bc6..903b153af0681 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_cluster_fusion/node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_cluster_fusion/node.hpp @@ -38,7 +38,6 @@ class RoiClusterFusionNode void fuseOnSingleImage( const DetectedObjectsWithFeature & input_cluster_msg, const std::size_t image_id, const DetectedObjectsWithFeature & input_roi_msg, - const sensor_msgs::msg::CameraInfo & camera_info, DetectedObjectsWithFeature & output_cluster_msg) override; std::string trust_object_iou_mode_{"iou"}; diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_detected_object_fusion/node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_detected_object_fusion/node.hpp index 7103537ec852d..43ec134168ef9 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_detected_object_fusion/node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_detected_object_fusion/node.hpp @@ -42,13 +42,11 @@ class RoiDetectedObjectFusionNode void fuseOnSingleImage( const DetectedObjects & input_object_msg, const std::size_t image_id, - const DetectedObjectsWithFeature & input_roi_msg, - const sensor_msgs::msg::CameraInfo & camera_info, DetectedObjects & output_object_msg) override; + const DetectedObjectsWithFeature & input_roi_msg, DetectedObjects & output_object_msg) override; std::map generateDetectedObjectRoIs( - const DetectedObjects & input_object_msg, const double image_width, const double image_height, - const Eigen::Affine3d & object2camera_affine, - const image_geometry::PinholeCameraModel & pinhole_camera_model); + const DetectedObjects & input_object_msg, const std::size_t & image_id, + const Eigen::Affine3d & object2camera_affine); void fuseObjectsOnImage( const DetectedObjects & input_object_msg, diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp index 9baf754e224a7..2f2c8222e196f 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp @@ -49,8 +49,7 @@ class RoiPointCloudFusionNode void fuseOnSingleImage( const PointCloud2 & input_pointcloud_msg, const std::size_t image_id, - const DetectedObjectsWithFeature & input_roi_msg, - const sensor_msgs::msg::CameraInfo & camera_info, PointCloud2 & output_pointcloud_msg) override; + const DetectedObjectsWithFeature & input_roi_msg, PointCloud2 & output_pointcloud_msg) override; bool out_of_scope(const DetectedObjectWithFeature & obj) override; }; diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp index 0bec3195bb402..7454cb7bcd173 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp @@ -61,7 +61,7 @@ class SegmentPointCloudFusionNode : public FusionNode getTransformStamped( const tf2_ros::Buffer & tf_buffer, const std::string & target_frame_id, const std::string & source_frame_id, const rclcpp::Time & time); diff --git a/perception/autoware_image_projection_based_fusion/schema/fusion_common.schema.json b/perception/autoware_image_projection_based_fusion/schema/fusion_common.schema.json index 73ee1661adaea..8077f3e2f3e30 100644 --- a/perception/autoware_image_projection_based_fusion/schema/fusion_common.schema.json +++ b/perception/autoware_image_projection_based_fusion/schema/fusion_common.schema.json @@ -31,6 +31,11 @@ "default": 15, "minimum": 1 }, + "point_project_to_unrectified_image": { + "type": "array", + "description": "An array of options indicating whether to project point to unrectified image or not.", + "default": [false, false, false, false, false, false] + }, "debug_mode": { "type": "boolean", "description": "Whether to debug or not.", @@ -65,6 +70,21 @@ "type": "number", "description": "Maximum z position [m].", "default": 100.0 + }, + "approximate_camera_projection": { + "type": "array", + "description": "An array of options indicating whether to use approximated projection for each camera.", + "default": [true, true, true, true, true, true] + }, + "approximation_grid_cell_width": { + "type": "number", + "description": "The width of grid cell used in approximated projection [pixel].", + "default": 1.0 + }, + "approximation_grid_cell_height": { + "type": "number", + "description": "The height of grid cell used in approximated projection [pixel].", + "default": 1.0 } } } diff --git a/perception/autoware_image_projection_based_fusion/src/camera_projection.cpp b/perception/autoware_image_projection_based_fusion/src/camera_projection.cpp new file mode 100644 index 0000000000000..c0a820609a0a7 --- /dev/null +++ b/perception/autoware_image_projection_based_fusion/src/camera_projection.cpp @@ -0,0 +1,252 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/image_projection_based_fusion/camera_projection.hpp" + +#include + +namespace autoware::image_projection_based_fusion +{ +CameraProjection::CameraProjection( + const sensor_msgs::msg::CameraInfo & camera_info, const float grid_cell_width, + const float grid_cell_height, const bool unrectify, const bool use_approximation = false) +: camera_info_(camera_info), + cell_width_(grid_cell_width), + cell_height_(grid_cell_height), + unrectify_(unrectify), + use_approximation_(use_approximation) +{ + if (grid_cell_width <= 0.0 || grid_cell_height <= 0.0) { + throw std::runtime_error("Both grid_cell_width and grid_cell_height must be > 0.0"); + } + + image_width_ = camera_info.width; + image_height_ = camera_info.height; + + // prepare camera model + camera_model_.fromCameraInfo(camera_info); + + // cache settings + inv_cell_width_ = 1 / cell_width_; + inv_cell_height_ = 1 / cell_height_; + grid_width_ = static_cast(std::ceil(image_width_ / cell_width_)); + grid_height_ = static_cast(std::ceil(image_height_ / cell_height_)); + cache_size_ = grid_width_ * grid_height_; + + // compute 3D rays for the image corners and pixels related to optical center + // to find the actual FOV size + // optical centers + const double ocx = static_cast(camera_info.k.at(2)); + const double ocy = static_cast(camera_info.k.at(5)); + // for checking pincushion shape case + const cv::Point3d ray_top_left = camera_model_.projectPixelTo3dRay(cv::Point(0, 0)); + const cv::Point3d ray_top_right = + camera_model_.projectPixelTo3dRay(cv::Point(image_width_ - 1, 0)); + const cv::Point3d ray_bottom_left = + camera_model_.projectPixelTo3dRay(cv::Point(0, image_height_ - 1)); + const cv::Point3d ray_bottom_right = + camera_model_.projectPixelTo3dRay(cv::Point(image_width_ - 1, image_height_ - 1)); + // for checking barrel shape case + const cv::Point3d ray_mid_top = camera_model_.projectPixelTo3dRay(cv::Point(ocx, 0)); + const cv::Point3d ray_mid_left = camera_model_.projectPixelTo3dRay(cv::Point(0, ocy)); + const cv::Point3d ray_mid_right = + camera_model_.projectPixelTo3dRay(cv::Point(image_width_ - 1, ocy)); + const cv::Point3d ray_mid_bottom = + camera_model_.projectPixelTo3dRay(cv::Point(ocx, image_height_ - 1)); + + cv::Point3d x_left = ray_top_left; + cv::Point3d x_right = ray_top_right; + cv::Point3d y_top = ray_top_left; + cv::Point3d y_bottom = ray_bottom_left; + + // check each side of the view + if (ray_bottom_left.x < x_left.x) x_left = ray_bottom_left; + if (ray_mid_left.x < x_left.x) x_left = ray_mid_left; + + if (x_right.x < ray_bottom_right.x) x_right = ray_bottom_right; + if (x_right.x < ray_mid_right.x) x_right = ray_mid_right; + + if (y_top.y < ray_top_right.y) y_top = ray_top_right; + if (y_top.y < ray_mid_top.y) y_top = ray_mid_top; + + if (ray_bottom_left.y < y_bottom.y) y_bottom = ray_bottom_left; + if (ray_mid_bottom.y < y_bottom.y) y_bottom = ray_mid_bottom; + + // set FOV at z = 1.0 + fov_left_ = x_left.x / x_left.z; + fov_right_ = x_right.x / x_right.z; + fov_top_ = y_top.y / y_top.z; + fov_bottom_ = y_bottom.y / y_bottom.z; +} + +void CameraProjection::initialize() +{ + if (unrectify_) { + if (use_approximation_) { + // create the cache with size of grid center + // store only xy position in float to reduce memory consumption + projection_cache_ = std::make_unique(cache_size_); + initializeCache(); + + calcImageProjectedPoint = [this]( + const cv::Point3d & point3d, Eigen::Vector2d & projected_point) { + return this->calcRawImageProjectedPointWithApproximation(point3d, projected_point); + }; + } else { + calcImageProjectedPoint = [this]( + const cv::Point3d & point3d, Eigen::Vector2d & projected_point) { + return this->calcRawImageProjectedPoint(point3d, projected_point); + }; + } + } else { + calcImageProjectedPoint = [this]( + const cv::Point3d & point3d, Eigen::Vector2d & projected_point) { + return this->calcRectifiedImageProjectedPoint(point3d, projected_point); + }; + } +} + +void CameraProjection::initializeCache() +{ + // sample grid cell centers till the camera height, width to precompute the projections + // + // grid cell size + // / + // v + // |---| w + // 0-----------------> + // 0 | . | . | . | + // |___|___|___| + // | . | . | . | + // | ^ + // h | | + // v grid cell center + // + // each pixel will be rounded in these grid cell centers + // edge pixels in right and bottom side in the image will be assign to these centers + // that is the outside of the image + + for (int idx_y = 0; idx_y < grid_height_; idx_y++) { + for (int idx_x = 0; idx_x < grid_width_; idx_x++) { + const uint32_t grid_index = idx_y * grid_width_ + idx_x; + const float px = (idx_x + 0.5f) * cell_width_; + const float py = (idx_y + 0.5f) * cell_height_; + + // precompute projected point + cv::Point2d raw_image_point = camera_model_.unrectifyPoint(cv::Point2d(px, py)); + projection_cache_[grid_index] = + PixelPos{static_cast(raw_image_point.x), static_cast(raw_image_point.y)}; + } + } +} + +/** + * @brief Calculate a projection of 3D point to rectified image plane 2D point. + * @return Return a boolean indicating whether the projected point is on the image plane. + */ +bool CameraProjection::calcRectifiedImageProjectedPoint( + const cv::Point3d & point3d, Eigen::Vector2d & projected_point) +{ + const cv::Point2d rectified_image_point = camera_model_.project3dToPixel(point3d); + + if ( + rectified_image_point.x < 0.0 || rectified_image_point.x >= image_width_ || + rectified_image_point.y < 0.0 || rectified_image_point.y >= image_height_) { + return false; + } else { + projected_point << rectified_image_point.x, rectified_image_point.y; + return true; + } +} + +/** + * @brief Calculate a projection of 3D point to raw image plane 2D point. + * @return Return a boolean indicating whether the projected point is on the image plane. + */ +bool CameraProjection::calcRawImageProjectedPoint( + const cv::Point3d & point3d, Eigen::Vector2d & projected_point) +{ + const cv::Point2d rectified_image_point = camera_model_.project3dToPixel(point3d); + const cv::Point2d raw_image_point = camera_model_.unrectifyPoint(rectified_image_point); + + if ( + rectified_image_point.x < 0.0 || rectified_image_point.x >= image_width_ || + rectified_image_point.y < 0.0 || rectified_image_point.y >= image_height_) { + return false; + } else { + projected_point << raw_image_point.x, raw_image_point.y; + return true; + } +} + +/** + * @brief Calculate a projection of 3D point to raw image plane 2D point with approximation. + * @return Return a boolean indicating whether the projected point is on the image plane. + */ +bool CameraProjection::calcRawImageProjectedPointWithApproximation( + const cv::Point3d & point3d, Eigen::Vector2d & projected_point) +{ + const cv::Point2d rectified_image_point = camera_model_.project3dToPixel(point3d); + + // round to a near grid cell + const int grid_idx_x = static_cast(std::floor(rectified_image_point.x * inv_cell_width_)); + const int grid_idx_y = static_cast(std::floor(rectified_image_point.y * inv_cell_height_)); + + if (grid_idx_x < 0.0 || grid_idx_x >= grid_width_) return false; + if (grid_idx_y < 0.0 || grid_idx_y >= grid_height_) return false; + + const uint32_t grid_index = grid_idx_y * grid_width_ + grid_idx_x; + projected_point << projection_cache_[grid_index].x, projection_cache_[grid_index].y; + + return true; +} + +sensor_msgs::msg::CameraInfo CameraProjection::getCameraInfo() +{ + return camera_info_; +} + +bool CameraProjection::isOutsideHorizontalView(const float px, const float pz) +{ + // assuming the points' origin is centered on the camera + if (pz <= 0.0) return true; + if (px < fov_left_ * pz) return true; + if (px > fov_right_ * pz) return true; + + // inside of the horizontal view + return false; +} + +bool CameraProjection::isOutsideVerticalView(const float py, const float pz) +{ + // assuming the points' origin is centered on the camera + if (pz <= 0.0) return true; + // up in the camera coordinate is negative + if (py < fov_top_ * pz) return true; + if (py > fov_bottom_ * pz) return true; + + // inside of the vertical view + return false; +} + +bool CameraProjection::isOutsideFOV(const float px, const float py, const float pz) +{ + if (isOutsideHorizontalView(px, pz)) return true; + if (isOutsideVerticalView(py, pz)) return true; + + // inside of the FOV + return false; +} + +} // namespace autoware::image_projection_based_fusion diff --git a/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp b/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp index bd4d57e45c582..ea0904215cb86 100644 --- a/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp @@ -18,6 +18,7 @@ #include #include +#include #include @@ -124,6 +125,34 @@ FusionNode::FusionNode( timer_ = rclcpp::create_timer( this, get_clock(), period_ns, std::bind(&FusionNode::timer_callback, this)); + // camera projection settings + camera_projectors_.resize(rois_number_); + point_project_to_unrectified_image_ = + declare_parameter>("point_project_to_unrectified_image"); + + if (rois_number_ > point_project_to_unrectified_image_.size()) { + throw std::runtime_error( + "The number of point_project_to_unrectified_image does not match the number of rois topics."); + } + approx_camera_projection_ = declare_parameter>("approximate_camera_projection"); + if (rois_number_ != approx_camera_projection_.size()) { + const std::size_t current_size = approx_camera_projection_.size(); + RCLCPP_WARN( + this->get_logger(), + "The number of elements in approximate_camera_projection should be the same as in " + "rois_number. " + "It has %zu elements.", + current_size); + if (current_size < rois_number_) { + approx_camera_projection_.resize(rois_number_); + for (std::size_t i = current_size; i < rois_number_; i++) { + approx_camera_projection_.at(i) = true; + } + } + } + approx_grid_cell_w_size_ = declare_parameter("approximation_grid_cell_width"); + approx_grid_cell_h_size_ = declare_parameter("approximation_grid_cell_height"); + // debugger if (declare_parameter("debug_mode", false)) { std::size_t image_buffer_size = @@ -142,9 +171,6 @@ FusionNode::FusionNode( time_keeper_ = std::make_shared(time_keeper); } - point_project_to_unrectified_image_ = - declare_parameter("point_project_to_unrectified_image"); - // initialize debug tool { using autoware::universe_utils::DebugPublisher; @@ -168,7 +194,18 @@ void FusionNode::cameraInfoCallback( const sensor_msgs::msg::CameraInfo::ConstSharedPtr input_camera_info_msg, const std::size_t camera_id) { - camera_info_map_[camera_id] = *input_camera_info_msg; + // create the CameraProjection when the camera info arrives for the first time + // assuming the camera info does not change while the node is running + if ( + camera_info_map_.find(camera_id) == camera_info_map_.end() && + checkCameraInfo(*input_camera_info_msg)) { + camera_projectors_.at(camera_id) = CameraProjection( + *input_camera_info_msg, approx_grid_cell_w_size_, approx_grid_cell_h_size_, + point_project_to_unrectified_image_.at(camera_id), approx_camera_projection_.at(camera_id)); + camera_projectors_.at(camera_id).initialize(); + + camera_info_map_[camera_id] = *input_camera_info_msg; + } } template @@ -273,8 +310,7 @@ void FusionNode::subCallback( } fuseOnSingleImage( - *input_msg, roi_i, *((cached_roi_msgs_.at(roi_i))[matched_stamp]), - camera_info_map_.at(roi_i), *output_msg); + *input_msg, roi_i, *((cached_roi_msgs_.at(roi_i))[matched_stamp]), *output_msg); (cached_roi_msgs_.at(roi_i)).erase(matched_stamp); is_fused_.at(roi_i) = true; @@ -346,9 +382,7 @@ void FusionNode::roiCallback( debugger_->clear(); } - fuseOnSingleImage( - *(cached_msg_.second), roi_i, *input_roi_msg, camera_info_map_.at(roi_i), - *(cached_msg_.second)); + fuseOnSingleImage(*(cached_msg_.second), roi_i, *input_roi_msg, *(cached_msg_.second)); is_fused_.at(roi_i) = true; if (debug_publisher_) { diff --git a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp index 4d12de2685c95..2837bac458541 100644 --- a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp @@ -161,13 +161,6 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt sub_ = this->create_subscription( "~/input/pointcloud", rclcpp::SensorDataQoS().keep_last(3), sub_callback); - tan_h_.resize(rois_number_); - for (std::size_t roi_i = 0; roi_i < rois_number_; ++roi_i) { - auto fx = camera_info_map_[roi_i].k.at(0); - auto x0 = camera_info_map_[roi_i].k.at(2); - tan_h_[roi_i] = x0 / fx; - } - detection_class_remapper_.setParameters( allow_remapping_by_area_matrix, min_area_matrix, max_area_matrix); @@ -260,9 +253,7 @@ void PointPaintingFusionNode::preprocess(sensor_msgs::msg::PointCloud2 & painted void PointPaintingFusionNode::fuseOnSingleImage( __attribute__((unused)) const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, - __attribute__((unused)) const std::size_t image_id, - const DetectedObjectsWithFeature & input_roi_msg, - const sensor_msgs::msg::CameraInfo & camera_info, + const std::size_t image_id, const DetectedObjectsWithFeature & input_roi_msg, sensor_msgs::msg::PointCloud2 & painted_pointcloud_msg) { if (painted_pointcloud_msg.data.empty() || painted_pointcloud_msg.fields.empty()) { @@ -276,8 +267,6 @@ void PointPaintingFusionNode::fuseOnSingleImage( return; } - if (!checkCameraInfo(camera_info)) return; - std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); @@ -312,9 +301,6 @@ void PointPaintingFusionNode::fuseOnSingleImage( .offset; const auto class_offset = painted_pointcloud_msg.fields.at(4).offset; const auto p_step = painted_pointcloud_msg.point_step; - // projection matrix - image_geometry::PinholeCameraModel pinhole_camera_model; - pinhole_camera_model.fromCameraInfo(camera_info); Eigen::Vector3f point_lidar, point_camera; /** dc : don't care @@ -346,24 +332,27 @@ dc | dc dc dc dc ||zc| p_y = point_camera.y(); p_z = point_camera.z(); - if (p_z <= 0.0 || p_x > (tan_h_.at(image_id) * p_z) || p_x < (-tan_h_.at(image_id) * p_z)) { + if (camera_projectors_[image_id].isOutsideHorizontalView(p_x, p_z)) { continue; } + // project - Eigen::Vector2d projected_point = calcRawImageProjectedPoint( - pinhole_camera_model, cv::Point3d(p_x, p_y, p_z), point_project_to_unrectified_image_); - - // iterate 2d bbox - for (const auto & feature_object : objects) { - sensor_msgs::msg::RegionOfInterest roi = feature_object.feature.roi; - // paint current point if it is inside bbox - int label2d = feature_object.object.classification.front().label; - if (!isUnknown(label2d) && isInsideBbox(projected_point.x(), projected_point.y(), roi, 1.0)) { - // cppcheck-suppress invalidPointerCast - auto p_class = reinterpret_cast(&output[stride + class_offset]); - for (const auto & cls : isClassTable_) { - // add up the class values if the point belongs to multiple classes - *p_class = cls.second(label2d) ? (class_index_[cls.first] + *p_class) : *p_class; + Eigen::Vector2d projected_point; + if (camera_projectors_[image_id].calcImageProjectedPoint( + cv::Point3d(p_x, p_y, p_z), projected_point)) { + // iterate 2d bbox + for (const auto & feature_object : objects) { + sensor_msgs::msg::RegionOfInterest roi = feature_object.feature.roi; + // paint current point if it is inside bbox + int label2d = feature_object.object.classification.front().label; + if ( + !isUnknown(label2d) && isInsideBbox(projected_point.x(), projected_point.y(), roi, 1.0)) { + // cppcheck-suppress invalidPointerCast + auto p_class = reinterpret_cast(&output[stride + class_offset]); + for (const auto & cls : isClassTable_) { + // add up the class values if the point belongs to multiple classes + *p_class = cls.second(label2d) ? (class_index_[cls.first] + *p_class) : *p_class; + } } } #if 0 @@ -375,15 +364,15 @@ dc | dc dc dc dc ||zc| } } - for (const auto & feature_object : input_roi_msg.feature_objects) { - debug_image_rois.push_back(feature_object.feature.roi); - } - if (debugger_) { std::unique_ptr inner_st_ptr; if (time_keeper_) inner_st_ptr = std::make_unique("publish debug message", *time_keeper_); + for (const auto & feature_object : input_roi_msg.feature_objects) { + debug_image_rois.push_back(feature_object.feature.roi); + } + debugger_->image_rois_ = debug_image_rois; debugger_->obstacle_points_ = debug_image_points; debugger_->publishImage(image_id, input_roi_msg.header.stamp); diff --git a/perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp index 7520647544684..32db5319bb487 100644 --- a/perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp @@ -95,16 +95,12 @@ void RoiClusterFusionNode::postprocess(DetectedObjectsWithFeature & output_clust void RoiClusterFusionNode::fuseOnSingleImage( const DetectedObjectsWithFeature & input_cluster_msg, const std::size_t image_id, - const DetectedObjectsWithFeature & input_roi_msg, - const sensor_msgs::msg::CameraInfo & camera_info, DetectedObjectsWithFeature & output_cluster_msg) + const DetectedObjectsWithFeature & input_roi_msg, DetectedObjectsWithFeature & output_cluster_msg) { - if (!checkCameraInfo(camera_info)) return; - std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); - image_geometry::PinholeCameraModel pinhole_camera_model; - pinhole_camera_model.fromCameraInfo(camera_info); + const sensor_msgs::msg::CameraInfo & camera_info = camera_projectors_[image_id].getCameraInfo(); // get transform from cluster frame id to camera optical frame id geometry_msgs::msg::TransformStamped transform_stamped; @@ -152,18 +148,17 @@ void RoiClusterFusionNode::fuseOnSingleImage( continue; } - Eigen::Vector2d projected_point = calcRawImageProjectedPoint( - pinhole_camera_model, cv::Point3d(*iter_x, *iter_y, *iter_z), - point_project_to_unrectified_image_); - if ( - 0 <= static_cast(projected_point.x()) && - static_cast(projected_point.x()) <= static_cast(camera_info.width) - 1 && - 0 <= static_cast(projected_point.y()) && - static_cast(projected_point.y()) <= static_cast(camera_info.height) - 1) { - min_x = std::min(static_cast(projected_point.x()), min_x); - min_y = std::min(static_cast(projected_point.y()), min_y); - max_x = std::max(static_cast(projected_point.x()), max_x); - max_y = std::max(static_cast(projected_point.y()), max_y); + Eigen::Vector2d projected_point; + if (camera_projectors_[image_id].calcImageProjectedPoint( + cv::Point3d(*iter_x, *iter_y, *iter_z), projected_point)) { + const int px = static_cast(projected_point.x()); + const int py = static_cast(projected_point.y()); + + min_x = std::min(px, min_x); + min_y = std::min(py, min_y); + max_x = std::max(px, max_x); + max_y = std::max(py, max_y); + projected_points.push_back(projected_point); if (debugger_) debugger_->obstacle_points_.push_back(projected_point); } diff --git a/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp index 035bc259ab73c..7be18d59fdbf1 100644 --- a/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp @@ -84,14 +84,11 @@ void RoiDetectedObjectFusionNode::preprocess(DetectedObjects & output_msg) void RoiDetectedObjectFusionNode::fuseOnSingleImage( const DetectedObjects & input_object_msg, const std::size_t image_id, const DetectedObjectsWithFeature & input_roi_msg, - const sensor_msgs::msg::CameraInfo & camera_info, DetectedObjects & output_object_msg __attribute__((unused))) { std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); - if (!checkCameraInfo(camera_info)) return; - Eigen::Affine3d object2camera_affine; { const auto transform_stamped_optional = getTransformStamped( @@ -103,12 +100,8 @@ void RoiDetectedObjectFusionNode::fuseOnSingleImage( object2camera_affine = transformToEigen(transform_stamped_optional.value().transform); } - image_geometry::PinholeCameraModel pinhole_camera_model; - pinhole_camera_model.fromCameraInfo(camera_info); - - const auto object_roi_map = generateDetectedObjectRoIs( - input_object_msg, static_cast(camera_info.width), - static_cast(camera_info.height), object2camera_affine, pinhole_camera_model); + const auto object_roi_map = + generateDetectedObjectRoIs(input_object_msg, image_id, object2camera_affine); fuseObjectsOnImage(input_object_msg, input_roi_msg.feature_objects, object_roi_map); if (debugger_) { @@ -122,9 +115,8 @@ void RoiDetectedObjectFusionNode::fuseOnSingleImage( std::map RoiDetectedObjectFusionNode::generateDetectedObjectRoIs( - const DetectedObjects & input_object_msg, const double image_width, const double image_height, - const Eigen::Affine3d & object2camera_affine, - const image_geometry::PinholeCameraModel & pinhole_camera_model) + const DetectedObjects & input_object_msg, const std::size_t & image_id, + const Eigen::Affine3d & object2camera_affine) { std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); @@ -139,6 +131,10 @@ RoiDetectedObjectFusionNode::generateDetectedObjectRoIs( return object_roi_map; } const auto & passthrough_object_flags = passthrough_object_flags_map_.at(timestamp_nsec); + const sensor_msgs::msg::CameraInfo & camera_info = camera_projectors_[image_id].getCameraInfo(); + const double image_width = static_cast(camera_info.width); + const double image_height = static_cast(camera_info.height); + for (std::size_t obj_i = 0; obj_i < input_object_msg.objects.size(); ++obj_i) { std::vector vertices_camera_coord; const auto & object = input_object_msg.objects.at(obj_i); @@ -165,18 +161,17 @@ RoiDetectedObjectFusionNode::generateDetectedObjectRoIs( continue; } - Eigen::Vector2d proj_point = calcRawImageProjectedPoint( - pinhole_camera_model, cv::Point3d(point.x(), point.y(), point.z()), - point_project_to_unrectified_image_); + Eigen::Vector2d proj_point; + if (camera_projectors_[image_id].calcImageProjectedPoint( + cv::Point3d(point.x(), point.y(), point.z()), proj_point)) { + const double px = proj_point.x(); + const double py = proj_point.y(); - min_x = std::min(proj_point.x(), min_x); - min_y = std::min(proj_point.y(), min_y); - max_x = std::max(proj_point.x(), max_x); - max_y = std::max(proj_point.y(), max_y); + min_x = std::min(px, min_x); + min_y = std::min(py, min_y); + max_x = std::max(px, max_x); + max_y = std::max(py, max_y); - if ( - proj_point.x() >= 0 && proj_point.x() < image_width && proj_point.y() >= 0 && - proj_point.y() < image_height) { point_on_image_cnt++; if (debugger_) { diff --git a/perception/autoware_image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp index 206a5f77a0235..998072d87774e 100644 --- a/perception/autoware_image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp @@ -86,10 +86,8 @@ void RoiPointCloudFusionNode::postprocess( } } void RoiPointCloudFusionNode::fuseOnSingleImage( - const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, - __attribute__((unused)) const std::size_t image_id, + const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const std::size_t image_id, const DetectedObjectsWithFeature & input_roi_msg, - const sensor_msgs::msg::CameraInfo & camera_info, __attribute__((unused)) sensor_msgs::msg::PointCloud2 & output_pointcloud_msg) { std::unique_ptr st_ptr; @@ -98,7 +96,6 @@ void RoiPointCloudFusionNode::fuseOnSingleImage( if (input_pointcloud_msg.data.empty()) { return; } - if (!checkCameraInfo(camera_info)) return; std::vector output_objs; std::vector debug_image_rois; @@ -122,10 +119,6 @@ void RoiPointCloudFusionNode::fuseOnSingleImage( return; } - // transform pointcloud to camera optical frame id - image_geometry::PinholeCameraModel pinhole_camera_model; - pinhole_camera_model.fromCameraInfo(camera_info); - geometry_msgs::msg::TransformStamped transform_stamped; { const auto transform_stamped_optional = getTransformStamped( @@ -136,10 +129,13 @@ void RoiPointCloudFusionNode::fuseOnSingleImage( } transform_stamped = transform_stamped_optional.value(); } - int point_step = input_pointcloud_msg.point_step; - int x_offset = input_pointcloud_msg.fields[pcl::getFieldIndex(input_pointcloud_msg, "x")].offset; - int y_offset = input_pointcloud_msg.fields[pcl::getFieldIndex(input_pointcloud_msg, "y")].offset; - int z_offset = input_pointcloud_msg.fields[pcl::getFieldIndex(input_pointcloud_msg, "z")].offset; + const int point_step = input_pointcloud_msg.point_step; + const int x_offset = + input_pointcloud_msg.fields[pcl::getFieldIndex(input_pointcloud_msg, "x")].offset; + const int y_offset = + input_pointcloud_msg.fields[pcl::getFieldIndex(input_pointcloud_msg, "y")].offset; + const int z_offset = + input_pointcloud_msg.fields[pcl::getFieldIndex(input_pointcloud_msg, "z")].offset; sensor_msgs::msg::PointCloud2 transformed_cloud; tf2::doTransform(input_pointcloud_msg, transformed_cloud, transform_stamped); @@ -164,33 +160,36 @@ void RoiPointCloudFusionNode::fuseOnSingleImage( if (transformed_z <= 0.0) { continue; } - Eigen::Vector2d projected_point = calcRawImageProjectedPoint( - pinhole_camera_model, cv::Point3d(transformed_x, transformed_y, transformed_z), - point_project_to_unrectified_image_); - for (std::size_t i = 0; i < output_objs.size(); ++i) { - auto & feature_obj = output_objs.at(i); - const auto & check_roi = feature_obj.feature.roi; - auto & cluster = clusters.at(i); - - if ( - clusters_data_size.at(i) >= - static_cast(max_cluster_size_) * static_cast(point_step)) { - continue; - } - if ( - check_roi.x_offset <= projected_point.x() && check_roi.y_offset <= projected_point.y() && - check_roi.x_offset + check_roi.width >= projected_point.x() && - check_roi.y_offset + check_roi.height >= projected_point.y()) { - std::memcpy( - &cluster.data[clusters_data_size.at(i)], &input_pointcloud_msg.data[offset], point_step); - clusters_data_size.at(i) += point_step; + + Eigen::Vector2d projected_point; + if (camera_projectors_[image_id].calcImageProjectedPoint( + cv::Point3d(transformed_x, transformed_y, transformed_z), projected_point)) { + for (std::size_t i = 0; i < output_objs.size(); ++i) { + auto & feature_obj = output_objs.at(i); + const auto & check_roi = feature_obj.feature.roi; + auto & cluster = clusters.at(i); + + const double px = projected_point.x(); + const double py = projected_point.y(); + + if ( + clusters_data_size.at(i) >= + static_cast(max_cluster_size_) * static_cast(point_step)) { + continue; + } + if ( + check_roi.x_offset <= px && check_roi.y_offset <= py && + check_roi.x_offset + check_roi.width >= px && + check_roi.y_offset + check_roi.height >= py) { + std::memcpy( + &cluster.data[clusters_data_size.at(i)], &input_pointcloud_msg.data[offset], + point_step); + clusters_data_size.at(i) += point_step; + } } - } - if (debugger_) { - // add all points inside image to debug - if ( - projected_point.x() > 0 && projected_point.x() < camera_info.width && - projected_point.y() > 0 && projected_point.y() < camera_info.height) { + + if (debugger_) { + // add all points inside image to debug debug_image_points.push_back(projected_point); } } diff --git a/perception/autoware_image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp index afeff213c0afe..486ae291abc6a 100644 --- a/perception/autoware_image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp @@ -87,9 +87,8 @@ void SegmentPointCloudFusionNode::postprocess(PointCloud2 & pointcloud_msg) } void SegmentPointCloudFusionNode::fuseOnSingleImage( - const PointCloud2 & input_pointcloud_msg, __attribute__((unused)) const std::size_t image_id, - [[maybe_unused]] const Image & input_mask, __attribute__((unused)) const CameraInfo & camera_info, - __attribute__((unused)) PointCloud2 & output_cloud) + const PointCloud2 & input_pointcloud_msg, const std::size_t image_id, + [[maybe_unused]] const Image & input_mask, __attribute__((unused)) PointCloud2 & output_cloud) { std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); @@ -97,10 +96,11 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage( if (input_pointcloud_msg.data.empty()) { return; } - if (!checkCameraInfo(camera_info)) return; if (input_mask.height == 0 || input_mask.width == 0) { return; } + + const sensor_msgs::msg::CameraInfo & camera_info = camera_projectors_[image_id].getCameraInfo(); std::vector mask_data(input_mask.data.begin(), input_mask.data.end()); cv::Mat mask = perception_utils::runLengthDecoder(mask_data, input_mask.height, input_mask.width); @@ -115,8 +115,6 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage( const int orig_height = camera_info.height; // resize mask to the same size as the camera image cv::resize(mask, mask, cv::Size(orig_width, orig_height), 0, 0, cv::INTER_NEAREST); - image_geometry::PinholeCameraModel pinhole_camera_model; - pinhole_camera_model.fromCameraInfo(camera_info); geometry_msgs::msg::TransformStamped transform_stamped; // transform pointcloud from frame id to camera optical frame id @@ -151,13 +149,9 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage( continue; } - Eigen::Vector2d projected_point = calcRawImageProjectedPoint( - pinhole_camera_model, cv::Point3d(transformed_x, transformed_y, transformed_z), - point_project_to_unrectified_image_); - - bool is_inside_image = projected_point.x() > 0 && projected_point.x() < camera_info.width && - projected_point.y() > 0 && projected_point.y() < camera_info.height; - if (!is_inside_image) { + Eigen::Vector2d projected_point; + if (!camera_projectors_[image_id].calcImageProjectedPoint( + cv::Point3d(transformed_x, transformed_y, transformed_z), projected_point)) { continue; } diff --git a/perception/autoware_image_projection_based_fusion/src/utils/utils.cpp b/perception/autoware_image_projection_based_fusion/src/utils/utils.cpp index 338a5605e5a79..4456d25b18167 100644 --- a/perception/autoware_image_projection_based_fusion/src/utils/utils.cpp +++ b/perception/autoware_image_projection_based_fusion/src/utils/utils.cpp @@ -44,20 +44,6 @@ bool checkCameraInfo(const sensor_msgs::msg::CameraInfo & camera_info) return true; } -Eigen::Vector2d calcRawImageProjectedPoint( - const image_geometry::PinholeCameraModel & pinhole_camera_model, const cv::Point3d & point3d, - const bool & unrectify) -{ - const cv::Point2d rectified_image_point = pinhole_camera_model.project3dToPixel(point3d); - - if (!unrectify) { - return Eigen::Vector2d(rectified_image_point.x, rectified_image_point.y); - } - const cv::Point2d raw_image_point = pinhole_camera_model.unrectifyPoint(rectified_image_point); - - return Eigen::Vector2d(raw_image_point.x, raw_image_point.y); -} - std::optional getTransformStamped( const tf2_ros::Buffer & tf_buffer, const std::string & target_frame_id, const std::string & source_frame_id, const rclcpp::Time & time) From c16e65695250d6d3708f60689d42cf2658755692 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 24 Dec 2024 09:28:12 +0900 Subject: [PATCH 078/334] feat(motion_planning): use StringStamped in autoware_internal_debug_msgs (#9742) feat(motion planning): use StringStamped in autoware_internal_debug_msgs Signed-off-by: Takayuki Murooka --- .../include/autoware/path_optimizer/type_alias.hpp | 4 ++-- planning/autoware_path_optimizer/package.xml | 1 + .../include/autoware/path_smoother/type_alias.hpp | 4 ++-- planning/autoware_path_smoother/package.xml | 1 + .../include/autoware_path_sampler/type_alias.hpp | 4 ++-- .../sampling_based_planner/autoware_path_sampler/package.xml | 1 + 6 files changed, 9 insertions(+), 6 deletions(-) diff --git a/planning/autoware_path_optimizer/include/autoware/path_optimizer/type_alias.hpp b/planning/autoware_path_optimizer/include/autoware/path_optimizer/type_alias.hpp index 5b16d4d5ba5c6..cf545d1a967e7 100644 --- a/planning/autoware_path_optimizer/include/autoware/path_optimizer/type_alias.hpp +++ b/planning/autoware_path_optimizer/include/autoware/path_optimizer/type_alias.hpp @@ -15,6 +15,7 @@ #ifndef AUTOWARE__PATH_OPTIMIZER__TYPE_ALIAS_HPP_ #define AUTOWARE__PATH_OPTIMIZER__TYPE_ALIAS_HPP_ +#include "autoware_internal_debug_msgs/msg/string_stamped.hpp" #include "autoware_planning_msgs/msg/path.hpp" #include "autoware_planning_msgs/msg/path_point.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" @@ -25,7 +26,6 @@ #include "nav_msgs/msg/odometry.hpp" #include "std_msgs/msg/header.hpp" #include "tier4_debug_msgs/msg/float64_stamped.hpp" -#include "tier4_debug_msgs/msg/string_stamped.hpp" #include "visualization_msgs/msg/marker_array.hpp" namespace autoware::path_optimizer @@ -43,8 +43,8 @@ using nav_msgs::msg::Odometry; using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; // debug +using autoware_internal_debug_msgs::msg::StringStamped; using tier4_debug_msgs::msg::Float64Stamped; -using tier4_debug_msgs::msg::StringStamped; } // namespace autoware::path_optimizer #endif // AUTOWARE__PATH_OPTIMIZER__TYPE_ALIAS_HPP_ diff --git a/planning/autoware_path_optimizer/package.xml b/planning/autoware_path_optimizer/package.xml index eb02db8ea9586..21ce487af6f4c 100644 --- a/planning/autoware_path_optimizer/package.xml +++ b/planning/autoware_path_optimizer/package.xml @@ -14,6 +14,7 @@ ament_cmake_auto autoware_cmake + autoware_internal_debug_msgs autoware_interpolation autoware_motion_utils autoware_osqp_interface diff --git a/planning/autoware_path_smoother/include/autoware/path_smoother/type_alias.hpp b/planning/autoware_path_smoother/include/autoware/path_smoother/type_alias.hpp index 5ec4b21955892..5f79689d20875 100644 --- a/planning/autoware_path_smoother/include/autoware/path_smoother/type_alias.hpp +++ b/planning/autoware_path_smoother/include/autoware/path_smoother/type_alias.hpp @@ -15,6 +15,7 @@ #ifndef AUTOWARE__PATH_SMOOTHER__TYPE_ALIAS_HPP_ #define AUTOWARE__PATH_SMOOTHER__TYPE_ALIAS_HPP_ +#include "autoware_internal_debug_msgs/msg/string_stamped.hpp" #include "autoware_planning_msgs/msg/path.hpp" #include "autoware_planning_msgs/msg/path_point.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" @@ -23,7 +24,6 @@ #include "nav_msgs/msg/odometry.hpp" #include "std_msgs/msg/header.hpp" #include "tier4_debug_msgs/msg/float64_stamped.hpp" -#include "tier4_debug_msgs/msg/string_stamped.hpp" namespace autoware::path_smoother { @@ -37,8 +37,8 @@ using autoware_planning_msgs::msg::TrajectoryPoint; // navigation using nav_msgs::msg::Odometry; // debug +using autoware_internal_debug_msgs::msg::StringStamped; using tier4_debug_msgs::msg::Float64Stamped; -using tier4_debug_msgs::msg::StringStamped; } // namespace autoware::path_smoother #endif // AUTOWARE__PATH_SMOOTHER__TYPE_ALIAS_HPP_ diff --git a/planning/autoware_path_smoother/package.xml b/planning/autoware_path_smoother/package.xml index 3fa7b9fa482ed..58bd970db541e 100644 --- a/planning/autoware_path_smoother/package.xml +++ b/planning/autoware_path_smoother/package.xml @@ -14,6 +14,7 @@ ament_cmake_auto autoware_cmake + autoware_internal_debug_msgs autoware_interpolation autoware_motion_utils autoware_osqp_interface diff --git a/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/type_alias.hpp b/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/type_alias.hpp index 95d833c4df47d..7398e28d18b28 100644 --- a/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/type_alias.hpp +++ b/planning/sampling_based_planner/autoware_path_sampler/include/autoware_path_sampler/type_alias.hpp @@ -15,6 +15,7 @@ #ifndef AUTOWARE_PATH_SAMPLER__TYPE_ALIAS_HPP_ #define AUTOWARE_PATH_SAMPLER__TYPE_ALIAS_HPP_ +#include "autoware_internal_debug_msgs/msg/string_stamped.hpp" #include "autoware_perception_msgs/msg/predicted_objects.hpp" #include "autoware_planning_msgs/msg/path.hpp" #include "autoware_planning_msgs/msg/path_point.hpp" @@ -25,7 +26,6 @@ #include "geometry_msgs/msg/twist.hpp" #include "nav_msgs/msg/odometry.hpp" #include "std_msgs/msg/header.hpp" -#include "tier4_debug_msgs/msg/string_stamped.hpp" #include "visualization_msgs/msg/marker_array.hpp" namespace autoware::path_sampler @@ -45,7 +45,7 @@ using nav_msgs::msg::Odometry; using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; // debug -using tier4_debug_msgs::msg::StringStamped; +using autoware_internal_debug_msgs::msg::StringStamped; } // namespace autoware::path_sampler #endif // AUTOWARE_PATH_SAMPLER__TYPE_ALIAS_HPP_ diff --git a/planning/sampling_based_planner/autoware_path_sampler/package.xml b/planning/sampling_based_planner/autoware_path_sampler/package.xml index 142eafdfa4bfe..a4119b03a2dd7 100644 --- a/planning/sampling_based_planner/autoware_path_sampler/package.xml +++ b/planning/sampling_based_planner/autoware_path_sampler/package.xml @@ -15,6 +15,7 @@ autoware_bezier_sampler autoware_frenet_planner + autoware_internal_debug_msgs autoware_interpolation autoware_motion_utils autoware_perception_msgs From 8865d0f6e2a9d4c26f17761ae4acbb5a6229fd11 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 24 Dec 2024 09:34:01 +0900 Subject: [PATCH 079/334] feat(motion_velocity_planner): use Float64Stamped in autoware_internal_debug_msgs (#9745) Signed-off-by: Takayuki Murooka --- .../src/dynamic_obstacle_stop_module.cpp | 7 ++++--- .../src/obstacle_velocity_limiter_module.cpp | 7 ++++--- .../src/out_of_lane_module.cpp | 7 ++++--- .../plugin_module_interface.hpp | 5 +++-- .../autoware_motion_velocity_planner_common/package.xml | 2 +- .../autoware_motion_velocity_planner_node/package.xml | 2 +- .../autoware_motion_velocity_planner_node/src/node.cpp | 5 +++-- .../autoware_motion_velocity_planner_node/src/node.hpp | 5 +++-- 8 files changed, 23 insertions(+), 17 deletions(-) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp index 12cb59ac46195..40aa985ee42e2 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp @@ -51,8 +51,9 @@ void DynamicObstacleStopModule::init(rclcpp::Node & node, const std::string & mo node.create_publisher("~/" + ns_ + "/virtual_walls", 1); processing_diag_publisher_ = std::make_shared( &node, "~/debug/" + ns_ + "/processing_time_ms_diag"); - processing_time_publisher_ = node.create_publisher( - "~/debug/" + ns_ + "/processing_time_ms", 1); + processing_time_publisher_ = + node.create_publisher( + "~/debug/" + ns_ + "/processing_time_ms", 1); using autoware::universe_utils::getOrDeclareParameter; auto & p = params_; @@ -190,7 +191,7 @@ VelocityPlanningResult DynamicObstacleStopModule::plan( processing_times["collisions"] = collisions_duration_us / 1000; processing_times["Total"] = total_time_us / 1000; processing_diag_publisher_->publish(processing_times); - tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg; processing_time_msg.stamp = clock_->now(); processing_time_msg.data = processing_times["Total"]; processing_time_publisher_->publish(processing_time_msg); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp index 3fa3ec7cbf782..532cc834c19ac 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp @@ -56,8 +56,9 @@ void ObstacleVelocityLimiterModule::init(rclcpp::Node & node, const std::string node.create_publisher("~/" + ns_ + "/virtual_walls", 1); processing_diag_publisher_ = std::make_shared( &node, "~/debug/" + ns_ + "/processing_time_ms_diag"); - processing_time_publisher_ = node.create_publisher( - "~/debug/" + ns_ + "/processing_time_ms", 1); + processing_time_publisher_ = + node.create_publisher( + "~/debug/" + ns_ + "/processing_time_ms", 1); const auto vehicle_info = vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo(); vehicle_lateral_offset_ = static_cast(vehicle_info.max_lateral_offset_m); @@ -236,7 +237,7 @@ VelocityPlanningResult ObstacleVelocityLimiterModule::plan( processing_times["slowdowns"] = slowdowns_us / 1000; processing_times["Total"] = total_us / 1000; processing_diag_publisher_->publish(processing_times); - tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg; processing_time_msg.stamp = clock_->now(); processing_time_msg.data = processing_times["Total"]; processing_time_publisher_->publish(processing_time_msg); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp index 63ca1b5784fe8..bd85546cb6c56 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp @@ -66,8 +66,9 @@ void OutOfLaneModule::init(rclcpp::Node & node, const std::string & module_name) node.create_publisher("~/" + ns_ + "/virtual_walls", 1); processing_diag_publisher_ = std::make_shared( &node, "~/debug/" + ns_ + "/processing_time_ms_diag"); - processing_time_publisher_ = node.create_publisher( - "~/debug/" + ns_ + "/processing_time_ms", 1); + processing_time_publisher_ = + node.create_publisher( + "~/debug/" + ns_ + "/processing_time_ms", 1); } void OutOfLaneModule::init_parameters(rclcpp::Node & node) { @@ -349,7 +350,7 @@ VelocityPlanningResult OutOfLaneModule::plan( processing_times["publish_markers"] = pub_markers_us / 1000; processing_times["Total"] = total_time_us / 1000; processing_diag_publisher_->publish(processing_times); - tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg; processing_time_msg.stamp = clock_->now(); processing_time_msg.data = processing_times["Total"]; processing_time_publisher_->publish(processing_time_msg); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp index 9bd662af697ea..53860c390b4db 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp @@ -22,8 +22,8 @@ #include #include +#include #include -#include #include #include @@ -47,7 +47,8 @@ class PluginModuleInterface rclcpp::Publisher::SharedPtr debug_publisher_; rclcpp::Publisher::SharedPtr virtual_wall_publisher_; std::shared_ptr processing_diag_publisher_; - rclcpp::Publisher::SharedPtr processing_time_publisher_; + rclcpp::Publisher::SharedPtr + processing_time_publisher_; autoware::motion_utils::VirtualWallMarkerCreator virtual_wall_marker_creator{}; }; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml index 3f0c027a5c986..51f4d9d984365 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml @@ -17,6 +17,7 @@ eigen3_cmake_module autoware_behavior_velocity_planner_common + autoware_internal_debug_msgs autoware_motion_utils autoware_perception_msgs autoware_planning_msgs @@ -27,7 +28,6 @@ geometry_msgs libboost-dev rclcpp - tier4_debug_msgs tier4_planning_msgs visualization_msgs diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml index 186140cba6e3c..03a1bec5c6fe5 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml @@ -18,6 +18,7 @@ rosidl_default_generators + autoware_internal_debug_msgs autoware_map_msgs autoware_motion_utils autoware_motion_velocity_planner_common @@ -37,7 +38,6 @@ tf2_eigen tf2_geometry_msgs tf2_ros - tier4_debug_msgs tier4_metric_msgs tier4_planning_msgs visualization_msgs diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp index 586d27f2c9614..9a607ba3b88cf 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp @@ -86,7 +86,8 @@ MotionVelocityPlannerNode::MotionVelocityPlannerNode(const rclcpp::NodeOptions & this->create_publisher( "~/output/velocity_factors", 1); processing_time_publisher_ = - this->create_publisher("~/debug/processing_time_ms", 1); + this->create_publisher( + "~/debug/processing_time_ms", 1); debug_viz_pub_ = this->create_publisher("~/debug/markers", 1); metrics_pub_ = this->create_publisher("~/metrics", 1); @@ -299,7 +300,7 @@ void MotionVelocityPlannerNode::on_trajectory( trajectory_pub_, output_trajectory_msg.header.stamp); processing_times["Total"] = stop_watch.toc("Total"); processing_diag_publisher_.publish(processing_times); - tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg; processing_time_msg.stamp = get_clock()->now(); processing_time_msg.data = processing_times["Total"]; processing_time_publisher_->publish(processing_time_msg); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp index 6e33b89e026c3..18d41f5d7fe5d 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp @@ -25,6 +25,7 @@ #include #include +#include #include #include #include @@ -32,7 +33,6 @@ #include #include #include -#include #include #include @@ -97,7 +97,8 @@ class MotionVelocityPlannerNode : public rclcpp::Node velocity_factor_publisher_; autoware::universe_utils::ProcessingTimePublisher processing_diag_publisher_{ this, "~/debug/processing_time_ms_diag"}; - rclcpp::Publisher::SharedPtr processing_time_publisher_; + rclcpp::Publisher::SharedPtr + processing_time_publisher_; autoware::universe_utils::PublishedTimePublisher published_time_publisher_{this}; rclcpp::Publisher::SharedPtr metrics_pub_; From f16ff531b1e6966b32bf2214228c141dd6bc1ab5 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Tue, 24 Dec 2024 10:10:29 +0900 Subject: [PATCH 080/334] feat(autoware_object_merger, autoware_tracking_object_merger): enable anonymized node names to be configurable (#9733) feat: enable anonymized node names to be configurable Signed-off-by: Taekjin LEE --- .../detection/merger/camera_lidar_merger.launch.xml | 2 ++ .../detection/merger/camera_lidar_radar_merger.launch.xml | 3 +++ .../detection/merger/lidar_merger.launch.xml | 2 ++ .../launch/object_recognition/tracking/tracking.launch.xml | 1 + .../launch/object_association_merger.launch.xml | 3 ++- .../launch/decorative_tracker_merger.launch.xml | 3 ++- 6 files changed, 12 insertions(+), 2 deletions(-) diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/merger/camera_lidar_merger.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/merger/camera_lidar_merger.launch.xml index fcfa9baf4ae20..236fea11d9dda 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/merger/camera_lidar_merger.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/merger/camera_lidar_merger.launch.xml @@ -120,6 +120,7 @@ + @@ -132,6 +133,7 @@ + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/merger/camera_lidar_radar_merger.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/merger/camera_lidar_radar_merger.launch.xml index c289a81c906fe..5da942e8ff8f3 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/merger/camera_lidar_radar_merger.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/merger/camera_lidar_radar_merger.launch.xml @@ -143,6 +143,7 @@ + @@ -155,6 +156,7 @@ + @@ -178,6 +180,7 @@ Control parameter 'use_radar_tracking_fusion' should defined in perception.launch.xml --> + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/merger/lidar_merger.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/merger/lidar_merger.launch.xml index a492e7667c347..4242903c1082d 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/merger/lidar_merger.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/merger/lidar_merger.launch.xml @@ -58,6 +58,7 @@ + @@ -70,6 +71,7 @@ + diff --git a/launch/tier4_perception_launch/launch/object_recognition/tracking/tracking.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/tracking/tracking.launch.xml index ce13a742c6202..1d34dd279b5fa 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/tracking/tracking.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/tracking/tracking.launch.xml @@ -57,6 +57,7 @@ + diff --git a/perception/autoware_object_merger/launch/object_association_merger.launch.xml b/perception/autoware_object_merger/launch/object_association_merger.launch.xml index f3c0e8bd5a829..4747b2af284fc 100644 --- a/perception/autoware_object_merger/launch/object_association_merger.launch.xml +++ b/perception/autoware_object_merger/launch/object_association_merger.launch.xml @@ -1,5 +1,6 @@ + @@ -8,7 +9,7 @@ - + diff --git a/perception/autoware_tracking_object_merger/launch/decorative_tracker_merger.launch.xml b/perception/autoware_tracking_object_merger/launch/decorative_tracker_merger.launch.xml index cd609a0fa612a..e2892bc75dfe0 100644 --- a/perception/autoware_tracking_object_merger/launch/decorative_tracker_merger.launch.xml +++ b/perception/autoware_tracking_object_merger/launch/decorative_tracker_merger.launch.xml @@ -1,5 +1,6 @@ + @@ -7,7 +8,7 @@ - + From 50f7cb08f1fdc2a5a82d44e93b0d299021a03bb6 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 24 Dec 2024 11:30:50 +0900 Subject: [PATCH 081/334] feat(diagnostic_graph_utils): use StringStamped in autoware_internal_debug_msgs (#9741) * feat(diagnostic_graph_utils): use StringStamped in autoware_internal_debug_msgs Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- system/diagnostic_graph_utils/package.xml | 1 + system/diagnostic_graph_utils/src/node/logging.cpp | 6 +++--- system/diagnostic_graph_utils/src/node/logging.hpp | 5 +++-- 3 files changed, 7 insertions(+), 5 deletions(-) diff --git a/system/diagnostic_graph_utils/package.xml b/system/diagnostic_graph_utils/package.xml index 03cf1fa369774..b777ee530ecc9 100644 --- a/system/diagnostic_graph_utils/package.xml +++ b/system/diagnostic_graph_utils/package.xml @@ -10,6 +10,7 @@ ament_cmake_auto autoware_cmake + autoware_internal_debug_msgs diagnostic_msgs rclcpp rclcpp_components diff --git a/system/diagnostic_graph_utils/src/node/logging.cpp b/system/diagnostic_graph_utils/src/node/logging.cpp index 5d360a00aee82..2dfc939469172 100644 --- a/system/diagnostic_graph_utils/src/node/logging.cpp +++ b/system/diagnostic_graph_utils/src/node/logging.cpp @@ -34,7 +34,7 @@ LoggingNode::LoggingNode(const rclcpp::NodeOptions & options) : Node("logging", sub_graph_.register_create_callback(std::bind(&LoggingNode::on_create, this, _1)); sub_graph_.subscribe(*this, 1); - pub_error_graph_text_ = create_publisher( + pub_error_graph_text_ = create_publisher( "~/debug/error_graph_text", rclcpp::QoS(1)); const auto period = rclcpp::Rate(declare_parameter("show_rate")).period(); @@ -68,12 +68,12 @@ void LoggingNode::on_timer() RCLCPP_WARN_STREAM(get_logger(), prefix_message << std::endl << dump_text_.str()); } - tier4_debug_msgs::msg::StringStamped message; + autoware_internal_debug_msgs::msg::StringStamped message; message.stamp = now(); message.data = dump_text_.str(); pub_error_graph_text_->publish(message); } else { - tier4_debug_msgs::msg::StringStamped message; + autoware_internal_debug_msgs::msg::StringStamped message; message.stamp = now(); pub_error_graph_text_->publish(message); } diff --git a/system/diagnostic_graph_utils/src/node/logging.hpp b/system/diagnostic_graph_utils/src/node/logging.hpp index 17d33499a1513..81acfcd2ad82f 100644 --- a/system/diagnostic_graph_utils/src/node/logging.hpp +++ b/system/diagnostic_graph_utils/src/node/logging.hpp @@ -19,7 +19,7 @@ #include -#include "tier4_debug_msgs/msg/string_stamped.hpp" +#include "autoware_internal_debug_msgs/msg/string_stamped.hpp" #include #include @@ -37,7 +37,8 @@ class LoggingNode : public rclcpp::Node void on_timer(); void dump_unit(DiagUnit * unit, int depth, const std::string & indent); DiagGraphSubscription sub_graph_; - rclcpp::Publisher::SharedPtr pub_error_graph_text_; + rclcpp::Publisher::SharedPtr + pub_error_graph_text_; rclcpp::TimerBase::SharedPtr timer_; DiagUnit * root_unit_; From 38bd911d7adbc4148d63d3d2497ba5abbb3f04b1 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 24 Dec 2024 11:31:34 +0900 Subject: [PATCH 082/334] feat(velocity_smoother): use autoware internal Stamped messages (#9749) * feat(velocity_smoother): use autoware internal Stamped messages Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../include/autoware/velocity_smoother/node.hpp | 8 ++++---- planning/autoware_velocity_smoother/package.xml | 2 +- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp index 069363d2f65e0..fc0066b1a84f3 100644 --- a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp +++ b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp @@ -39,12 +39,12 @@ #include #include "autoware_adapi_v1_msgs/msg/operation_mode_state.hpp" +#include "autoware_internal_debug_msgs/msg/float32_stamped.hpp" +#include "autoware_internal_debug_msgs/msg/float64_stamped.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" #include "autoware_planning_msgs/msg/trajectory_point.hpp" #include "geometry_msgs/msg/accel_with_covariance_stamped.hpp" #include "nav_msgs/msg/odometry.hpp" -#include "tier4_debug_msgs/msg/float32_stamped.hpp" // temporary -#include "tier4_debug_msgs/msg/float64_stamped.hpp" // temporary #include "tier4_planning_msgs/msg/stop_speed_exceeded.hpp" // temporary #include "tier4_planning_msgs/msg/velocity_limit.hpp" // temporary #include "visualization_msgs/msg/marker_array.hpp" @@ -62,12 +62,12 @@ using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; using TrajectoryPoints = std::vector; using autoware_adapi_v1_msgs::msg::OperationModeState; +using autoware_internal_debug_msgs::msg::Float32Stamped; +using autoware_internal_debug_msgs::msg::Float64Stamped; using geometry_msgs::msg::AccelWithCovarianceStamped; using geometry_msgs::msg::Pose; using geometry_msgs::msg::PoseStamped; using nav_msgs::msg::Odometry; -using tier4_debug_msgs::msg::Float32Stamped; // temporary -using tier4_debug_msgs::msg::Float64Stamped; // temporary using tier4_planning_msgs::msg::StopSpeedExceeded; // temporary using tier4_planning_msgs::msg::VelocityLimit; // temporary using visualization_msgs::msg::MarkerArray; diff --git a/planning/autoware_velocity_smoother/package.xml b/planning/autoware_velocity_smoother/package.xml index 96462602d8da0..3d1252ff0b7a6 100644 --- a/planning/autoware_velocity_smoother/package.xml +++ b/planning/autoware_velocity_smoother/package.xml @@ -21,6 +21,7 @@ autoware_cmake eigen3_cmake_module + autoware_internal_debug_msgs autoware_interpolation autoware_motion_utils autoware_osqp_interface @@ -34,7 +35,6 @@ rclcpp tf2 tf2_ros - tier4_debug_msgs tier4_planning_msgs ament_cmake_ros From daa8a154a06677d830e06c22c3760449c47dadda Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 24 Dec 2024 12:21:53 +0900 Subject: [PATCH 083/334] fix(lane_change): fix prepare length too short at low speed (RT1-8909) (#9735) fix prepare length too short at low speed (RT1-8909) Signed-off-by: Zulfaqar Azmi --- .../src/utils/calculation.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp index 3ba11d62a2be7..550c0fa290a99 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp @@ -417,7 +417,7 @@ double calc_actual_prepare_duration( if (max_acc < eps) { return params.max_prepare_duration; } - return (min_lc_velocity - current_velocity) / max_acc; + return std::max((min_lc_velocity - current_velocity) / max_acc, params.min_prepare_duration); }); return std::max(params.max_prepare_duration - active_signal_duration, min_prepare_duration); From 5fa0141664553017980dfc7673c5faa323d7a4c7 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 24 Dec 2024 13:05:22 +0900 Subject: [PATCH 084/334] refactor(lane_change): separate path-related function to utils/path (#9633) * refactor(lane_change): separate path-related function to utils/path Signed-off-by: Zulfaqar Azmi * remove old terminal lane change computation Signed-off-by: Zulfaqar Azmi * doxygen comments Signed-off-by: Zulfaqar Azmi * remove frenet planner header Signed-off-by: Zulfaqar Azmi * minor refactoring by throwing instead Signed-off-by: Zulfaqar Azmi * minor refactoring Signed-off-by: Zulfaqar Azmi * fix docstring and remove redundant argument Signed-off-by: Zulfaqar Azmi * get logger in header Signed-off-by: Zulfaqar Azmi * add docstring Signed-off-by: Zulfaqar Azmi * rename function is_colliding Signed-off-by: Zulfaqar Azmi * Fix failing test Signed-off-by: Zulfaqar Azmi * fix for failing scenario caused by prepare velocity Signed-off-by: Zulfaqar Azmi * fix error message Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Zulfaqar Azmi --- .../CMakeLists.txt | 1 + .../base_class.hpp | 5 - .../scene.hpp | 48 +- .../structs/data.hpp | 2 + .../utils/path.hpp | 102 ++++ .../utils/utils.hpp | 95 ++-- .../src/scene.cpp | 438 +++--------------- .../src/utils/path.cpp | 292 ++++++++++++ .../src/utils/utils.cpp | 244 ++-------- .../test/test_lane_change_scene.cpp | 1 + 10 files changed, 561 insertions(+), 667 deletions(-) create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/path.cpp diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/CMakeLists.txt b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/CMakeLists.txt index d1b6bfed868f0..0d56a28aaf450 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/CMakeLists.txt +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/CMakeLists.txt @@ -12,6 +12,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/utils/calculation.cpp src/utils/markers.cpp src/utils/utils.cpp + src/utils/path.cpp ) if(BUILD_TESTING) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/base_class.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/base_class.hpp index 5317b94db2d6b..ce2552a41d380 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/base_class.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/base_class.hpp @@ -102,8 +102,6 @@ class LaneChangeBase virtual LaneChangePath getLaneChangePath() const = 0; - virtual BehaviorModuleOutput getTerminalLaneChangePath() const = 0; - virtual bool isEgoOnPreparePhase() const = 0; virtual bool isRequiredStop(const bool is_trailing_object) = 0; @@ -235,9 +233,6 @@ class LaneChangeBase protected: virtual int getNumToPreferredLane(const lanelet::ConstLanelet & lane) const = 0; - virtual bool get_prepare_segment( - PathWithLaneId & prepare_segment, const double prepare_length) const = 0; - virtual bool isValidPath(const PathWithLaneId & path) const = 0; virtual bool isAbleToStopSafely() const = 0; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp index 9bf66722dcec2..6367caaea6829 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp @@ -64,8 +64,6 @@ class NormalLaneChange : public LaneChangeBase LaneChangePath getLaneChangePath() const override; - BehaviorModuleOutput getTerminalLaneChangePath() const override; - BehaviorModuleOutput generateOutput() override; void extendOutputDrivableArea(BehaviorModuleOutput & output) const override; @@ -128,14 +126,6 @@ class NormalLaneChange : public LaneChangeBase void filterOncomingObjects(PredictedObjects & objects) const; - bool get_prepare_segment( - PathWithLaneId & prepare_segment, const double prepare_length) const override; - - PathWithLaneId getTargetSegment( - const lanelet::ConstLanelets & target_lanes, const Pose & lane_changing_start_pose, - const double target_lane_length, const double lane_changing_length, - const double lane_changing_velocity, const double buffer_for_next_lane_change) const; - std::vector get_prepare_metrics() const; std::vector get_lane_changing_metrics( const PathWithLaneId & prep_segment, const LaneChangePhaseMetrics & prep_metrics, @@ -143,32 +133,19 @@ class NormalLaneChange : public LaneChangeBase bool get_lane_change_paths(LaneChangePaths & candidate_paths) const; - LaneChangePath get_candidate_path( - const LaneChangePhaseMetrics & prep_metrics, const LaneChangePhaseMetrics & lc_metrics, - const PathWithLaneId & prep_segment, const std::vector> & sorted_lane_ids, - const Pose & lc_start_pose, const double shift_length) const; - bool check_candidate_path_safety( const LaneChangePath & candidate_path, const lane_change::TargetObjects & target_objects) const; - std::optional calcTerminalLaneChangePath( - const lanelet::ConstLanelets & current_lanes, - const lanelet::ConstLanelets & target_lanes) const; - bool isValidPath(const PathWithLaneId & path) const override; PathSafetyStatus isLaneChangePathSafe( const LaneChangePath & lane_change_path, + const std::vector> & ego_predicted_paths, const lane_change::TargetObjects & collision_check_objects, const utils::path_safety_checker::RSSparams & rss_params, - const size_t deceleration_sampling_num, CollisionCheckDebugMap & debug_data) const; - - bool has_collision_with_decel_patterns( - const LaneChangePath & lane_change_path, const ExtendedPredictedObjects & objects, - const size_t deceleration_sampling_num, const RSSparams & rss_param, - const bool check_prepare_phase, CollisionCheckDebugMap & debug_data) const; + CollisionCheckDebugMap & debug_data) const; - bool is_collided( + bool is_colliding( const LaneChangePath & lane_change_path, const ExtendedPredictedObject & obj, const std::vector & ego_predicted_path, const RSSparams & selected_rss_param, const bool check_prepare_phase, @@ -178,24 +155,6 @@ class NormalLaneChange : public LaneChangeBase bool is_ego_stuck() const; - /** - * @brief Checks if the given pose is a valid starting point for a lane change. - * - * This function determines whether the given pose (position) of the vehicle is within - * the area of either the target neighbor lane or the target lane itself. It uses geometric - * checks to see if the start point of the lane change is covered by the polygons representing - * these lanes. - * - * @param common_data_ptr Shared pointer to a CommonData structure, which should include: - * - Non-null `lanes_polygon_ptr` that contains the polygon data for lanes. - * @param pose The current pose of the vehicle - * - * @return `true` if the pose is within either the target neighbor lane or the target lane; - * `false` otherwise. - */ - bool is_valid_start_point( - const lane_change::CommonDataPtr & common_data_ptr, const Pose & pose) const; - bool check_prepare_phase() const; void set_stop_pose(const double arc_length_to_stop_pose, PathWithLaneId & path); @@ -213,7 +172,6 @@ class NormalLaneChange : public LaneChangeBase std::vector path_after_intersection_; double stop_time_{0.0}; - static constexpr double floating_err_th{1e-3}; }; } // namespace autoware::behavior_path_planner #endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__SCENE_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp index 4dcb1c7b685d0..5f36be806bba4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp @@ -160,6 +160,8 @@ struct TargetObjects : leading(std::move(leading)), trailing(std::move(trailing)) { } + + [[nodiscard]] bool empty() const { return leading.empty() && trailing.empty(); } }; enum class ModuleType { diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp new file mode 100644 index 0000000000000..dcc327b4793e1 --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp @@ -0,0 +1,102 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PATH_HPP_ +#define AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PATH_HPP_ + +#include "autoware/behavior_path_lane_change_module/structs/data.hpp" +#include "autoware/behavior_path_lane_change_module/structs/path.hpp" + +#include + +#include + +namespace autoware::behavior_path_planner::utils::lane_change +{ +using behavior_path_planner::LaneChangePath; +using behavior_path_planner::lane_change::CommonDataPtr; + +/** + * @brief Generates a prepare segment for a lane change maneuver. + * + * This function generates the "prepare segment" of the path by trimming it to the specified length, + * adjusting longitudinal velocity for acceleration or deceleration, and ensuring the starting point + * meets necessary constraints for a lane change. + * + * @param common_data_ptr Shared pointer to CommonData containing current and target lane + * information, vehicle parameters, and ego state. + * @param prev_module_path The input path from the previous module, which will be used + * as the base for the prepare segment. + * @param prep_metric Preparation metrics containing desired length and velocity for the segment. + * @param prepare_segment Output parameter where the resulting prepare segment path will be stored. + * + * @throws std::logic_error If the lane change start point is behind the target lanelet or + * if lane information is invalid. + * + * @return true if the prepare segment is successfully generated, false otherwise. + */ +bool get_prepare_segment( + const CommonDataPtr & common_data_ptr, const PathWithLaneId & prev_module_path, + const LaneChangePhaseMetrics prep_metric, PathWithLaneId & prepare_segment); + +/** + * @brief Generates the candidate path for a lane change maneuver. + * + * This function calculates the candidate lane change path based on the provided preparation + * and lane change metrics. It resamples the target lane reference path, determines the start + * and end poses for the lane change, and constructs the shift line required for the maneuver. + * The function ensures that the resulting path satisfies length and distance constraints. + * + * @param common_data_ptr Shared pointer to CommonData containing route, lane, and transient data. + * @param prep_metric Metrics for the preparation phase, including path length and velocity. + * @param lc_metric Metrics for the lane change phase, including path length and velocity. + * @param prep_segment The path segment prepared before initiating the lane change. + * @param sorted_lane_ids A vector of sorted lane IDs used for updating lane information in the + * path. + * @param lc_start_pose The pose where the lane change begins. + * @param shift_length The lateral distance to shift during the lane change maneuver. + * + * @throws std::logic_error If the target lane reference path is empty, candidate path generation + * fails, or the resulting path length exceeds terminal constraints. + * + * @return LaneChangePath The constructed candidate lane change path. + */ +LaneChangePath get_candidate_path( + const CommonDataPtr & common_data_ptr, const LaneChangePhaseMetrics & prep_metric, + const LaneChangePhaseMetrics & lc_metric, const PathWithLaneId & prep_segment, + const std::vector> & sorted_lane_ids, const double shift_length); + +/** + * @brief Constructs a candidate path for a lane change maneuver. + * + * This function generates a candidate lane change path by shifting the target lane's reference path + * and combining it with the prepare segment. It verifies the path's validity by checking the yaw + * difference, adjusting longitudinal velocity, and updating lane IDs based on the provided lane + * sorting information. + * + * @param lane_change_info Information about the lane change, including shift line and target + * velocity. + * @param prepare_segment The path segment leading up to the lane change. + * @param target_lane_reference_path The reference path of the target lane. + * @param sorted_lane_ids A vector of sorted lane IDs used to update the candidate path's lane IDs. + * + * @return std::optional The constructed candidate path if valid, or std::nullopt + * if the path fails any constraints. + */ +LaneChangePath construct_candidate_path( + const LaneChangeInfo & lane_change_info, const PathWithLaneId & prepare_segment, + const PathWithLaneId & target_lane_reference_path, + const std::vector> & sorted_lane_ids); +} // namespace autoware::behavior_path_planner::utils::lane_change +#endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PATH_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp index 0adb9409fb4b0..69362994dbbac 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp @@ -52,6 +52,7 @@ using autoware_perception_msgs::msg::PredictedObjects; using autoware_perception_msgs::msg::PredictedPath; using behavior_path_planner::lane_change::CommonDataPtr; using behavior_path_planner::lane_change::LanesPolygon; +using behavior_path_planner::lane_change::LCParamPtr; using behavior_path_planner::lane_change::ModuleType; using behavior_path_planner::lane_change::PathSafetyStatus; using behavior_path_planner::lane_change::TargetLaneLeadingObjects; @@ -61,12 +62,11 @@ using geometry_msgs::msg::Twist; using path_safety_checker::CollisionCheckDebugMap; using tier4_planning_msgs::msg::PathWithLaneId; -bool is_mandatory_lane_change(const ModuleType lc_type); +rclcpp::Logger get_logger(); -double calcLaneChangeResampleInterval( - const double lane_changing_length, const double lane_changing_velocity); +bool is_mandatory_lane_change(const ModuleType lc_type); -void setPrepareVelocity( +void set_prepare_velocity( PathWithLaneId & prepare_segment, const double current_velocity, const double prepare_velocity); std::vector replaceWithSortedIds( @@ -79,27 +79,10 @@ lanelet::ConstLanelets get_target_neighbor_lanes( const RouteHandler & route_handler, const lanelet::ConstLanelets & current_lanes, const LaneChangeModuleType & type); -bool isPathInLanelets( - const PathWithLaneId & path, const lanelet::ConstLanelets & current_lanes, - const lanelet::ConstLanelets & target_lanes); - bool path_footprint_exceeds_target_lane_bound( const CommonDataPtr & common_data_ptr, const PathWithLaneId & path, const VehicleInfo & ego_info, const double margin = 0.1); -std::optional construct_candidate_path( - const CommonDataPtr & common_data_ptr, const LaneChangeInfo & lane_change_info, - const PathWithLaneId & prepare_segment, const PathWithLaneId & target_lane_reference_path, - const std::vector> & sorted_lane_ids); - -ShiftLine get_lane_changing_shift_line( - const Pose & lane_changing_start_pose, const Pose & lane_changing_end_pose, - const PathWithLaneId & reference_path, const double shift_length); - -PathWithLaneId get_reference_path_from_target_Lane( - const CommonDataPtr & common_data_ptr, const Pose & lane_changing_start_pose, - const double lane_changing_length, const double resample_interval); - std::vector generateDrivableLanes( const std::vector & original_drivable_lanes, const RouteHandler & route_handler, const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & lane_change_lanes); @@ -141,8 +124,8 @@ bool isParkedObject( * If the parameter delay_lc_param.check_only_parked_vehicle is set to True, only objects * which pass isParkedObject() check will be considered. * - * @param common_data_ptr Shared pointer to CommonData that holds necessary lanes info, parameters, - * and transient data. + * @param common_data_ptr Shared pointer to CommonData that holds necessary lanes info, + * parameters, and transient data. * @param lane_change_path Candidate lane change path to apply checks on. * @param target_objects Relevant objects to consider for delay LC checks (assumed to only include * target lane leading static objects). @@ -202,8 +185,8 @@ rclcpp::Logger getLogger(const std::string & type); * The footprint is determined by the vehicle's pose and its dimensions, including the distance * from the base to the front and rear ends of the vehicle, as well as its width. * - * @param common_data_ptr Shared pointer to CommonData that holds necessary ego vehicle's dimensions - * and pose information. + * @param common_data_ptr Shared pointer to CommonData that holds necessary ego vehicle's + * dimensions and pose information. * * @return Polygon2d A polygon representing the current 2D footprint of the ego vehicle. */ @@ -233,15 +216,15 @@ bool is_within_intersection( /** * @brief Determines if a polygon is within lanes designated for turning. * - * Checks if a polygon overlaps with lanelets tagged for turning directions (excluding 'straight'). - * It evaluates the lanelet's 'turn_direction' attribute and determines overlap with the lanelet's - * area. + * Checks if a polygon overlaps with lanelets tagged for turning directions (excluding + * 'straight'). It evaluates the lanelet's 'turn_direction' attribute and determines overlap with + * the lanelet's area. * * @param lanelet Lanelet representing the road segment whose turn direction is to be evaluated. * @param polygon The polygon to be checked for its presence within turn direction lanes. * - * @return bool True if the polygon is within a lane designated for turning, false if it is within a - * straight lane or no turn direction is specified. + * @return bool True if the polygon is within a lane designated for turning, false if it is within + * a straight lane or no turn direction is specified. */ bool is_within_turn_direction_lanes( const lanelet::ConstLanelet & lanelet, const Polygon2d & polygon); @@ -276,8 +259,8 @@ double get_distance_to_next_regulatory_element( * * @param common_data_ptr Pointer to the common data structure containing parameters for lane * change. - * @param filtered_objects A collection of objects filtered by lanes, including those in the current - * lane. + * @param filtered_objects A collection of objects filtered by lanes, including those in the + * current lane. * @param dist_to_target_lane_start The distance to the start of the target lane from the ego * vehicle. * @param path The current path of the ego vehicle, containing path points and lane information. @@ -297,8 +280,8 @@ double get_min_dist_to_current_lanes_obj( * * @param common_data_ptr Pointer to the common data structure containing parameters for the lane * change. - * @param filtered_objects A collection of objects filtered by lanes, including those in the target - * lane. + * @param filtered_objects A collection of objects filtered by lanes, including those in the + * target lane. * @param stop_arc_length The arc length at which the ego vehicle is expected to stop. * @param path The current path of the ego vehicle, containing path points and lane information. * @return true if there is an object in the target lane that influences the stop point decision; @@ -365,14 +348,15 @@ bool has_overtaking_turn_lane_object( * * @param common_data_ptr Shared pointer to CommonData containing information about current lanes, * vehicle dimensions, lane polygons, and behavior parameters. - * @param object An extended predicted object representing a potential obstacle in the environment. + * @param object An extended predicted object representing a potential obstacle in the + * environment. * @param dist_ego_to_current_lanes_center Distance from the ego vehicle to the center of the * current lanes. * @param ahead_of_ego Boolean flag indicating if the object is ahead of the ego vehicle. - * @param before_terminal Boolean flag indicating if the ego vehicle is before the terminal point of - * the lane. - * @param leading_objects Reference to a structure for storing leading objects (stopped, moving, or - * outside boundaries). + * @param before_terminal Boolean flag indicating if the ego vehicle is before the terminal point + * of the lane. + * @param leading_objects Reference to a structure for storing leading objects (stopped, moving, + * or outside boundaries). * @param trailing_objects Reference to a collection for storing trailing objects. * * @return true if the object is classified as either leading or trailing, false otherwise. @@ -415,5 +399,38 @@ std::vector get_preceding_lanes(const CommonDataPtr & co */ bool object_path_overlaps_lanes( const ExtendedPredictedObject & object, const lanelet::BasicPolygon2d & lanes_polygon); + +/** + * @brief Converts a lane change path into multiple predicted paths with varying acceleration + * profiles. + * + * This function generates a set of predicted paths for the ego vehicle during a lane change, + * using different acceleration values within the specified range. It accounts for deceleration + * sampling if the global minimum acceleration differs from the lane-changing acceleration. + * + * @param common_data_ptr Shared pointer to CommonData containing parameters and state information. + * @param lane_change_path The lane change path used to generate predicted paths. + * @param deceleration_sampling_num Number of samples for deceleration profiles to generate paths. + * + * @return std::vector> A collection of predicted paths, where + * each path is represented as a series of poses with associated velocity. + */ +std::vector> convert_to_predicted_paths( + const CommonDataPtr & common_data_ptr, const LaneChangePath & lane_change_path, + const size_t deceleration_sampling_num); + +/** + * @brief Validates whether a given pose is a valid starting point for a lane change. + * + * This function checks if the specified pose lies within the polygons representing + * the target lane or its neighboring areas. This ensures that the starting point is + * appropriately positioned for initiating a lane change, even if previous paths were adjusted. + * + * @param common_data_ptr Shared pointer to CommonData containing lane polygon information. + * @param pose The pose to validate as a potential lane change starting point. + * + * @return true if the pose is within the target or target neighbor polygons, false otherwise. + */ +bool is_valid_start_point(const lane_change::CommonDataPtr & common_data_ptr, const Pose & pose); } // namespace autoware::behavior_path_planner::utils::lane_change #endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__UTILS_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index a1c2d8467d1fc..f8a200a9685a7 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -15,6 +15,7 @@ #include "autoware/behavior_path_lane_change_module/scene.hpp" #include "autoware/behavior_path_lane_change_module/utils/calculation.hpp" +#include "autoware/behavior_path_lane_change_module/utils/path.hpp" #include "autoware/behavior_path_lane_change_module/utils/utils.hpp" #include "autoware/behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" #include "autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" @@ -31,9 +32,9 @@ #include #include #include -#include -#include -#include +#include +#include +#include #include #include @@ -379,48 +380,6 @@ LaneChangePath NormalLaneChange::getLaneChangePath() const return status_.lane_change_path; } -BehaviorModuleOutput NormalLaneChange::getTerminalLaneChangePath() const -{ - auto output = prev_module_output_; - - if (isAbortState() && abort_path_) { - output.path = abort_path_->path; - extendOutputDrivableArea(output); - const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path.points); - output.turn_signal_info = planner_data_->turn_signal_decider.overwrite_turn_signal( - output.path, getEgoPose(), current_seg_idx, prev_module_output_.turn_signal_info, - output.turn_signal_info, planner_data_->parameters.ego_nearest_dist_threshold, - planner_data_->parameters.ego_nearest_yaw_threshold); - return output; - } - - const auto & current_lanes = get_current_lanes(); - if (current_lanes.empty()) { - RCLCPP_DEBUG(logger_, "Current lanes not found. Returning previous module's path as output."); - return prev_module_output_; - } - - const auto terminal_path = - calcTerminalLaneChangePath(current_lanes, get_lane_change_lanes(current_lanes)); - if (!terminal_path) { - RCLCPP_DEBUG(logger_, "Terminal path not found. Returning previous module's path as output."); - return prev_module_output_; - } - - output.path = terminal_path->path; - output.turn_signal_info = updateOutputTurnSignal(); - - extendOutputDrivableArea(output); - - const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path.points); - output.turn_signal_info = planner_data_->turn_signal_decider.overwrite_turn_signal( - output.path, getEgoPose(), current_seg_idx, prev_module_output_.turn_signal_info, - output.turn_signal_info, planner_data_->parameters.ego_nearest_dist_threshold, - planner_data_->parameters.ego_nearest_yaw_threshold); - - return output; -} - BehaviorModuleOutput NormalLaneChange::generateOutput() { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); @@ -922,43 +881,6 @@ int NormalLaneChange::getNumToPreferredLane(const lanelet::ConstLanelet & lane) return std::abs(getRouteHandler()->getNumLaneToPreferredLane(lane, get_opposite_direction)); } -bool NormalLaneChange::get_prepare_segment( - PathWithLaneId & prepare_segment, const double prepare_length) const -{ - const auto & current_lanes = common_data_ptr_->lanes_ptr->current; - const auto & target_lanes = common_data_ptr_->lanes_ptr->target; - const auto backward_path_length = common_data_ptr_->bpp_param_ptr->backward_path_length; - - if (current_lanes.empty() || target_lanes.empty()) { - return false; - } - - prepare_segment = prev_module_output_.path; - const size_t current_seg_idx = - autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( - prepare_segment.points, getEgoPose(), 3.0, 1.0); - utils::clipPathLength(prepare_segment, current_seg_idx, prepare_length, backward_path_length); - - if (prepare_segment.points.empty()) return false; - - const auto & lc_start_pose = prepare_segment.points.back().point.pose; - - // TODO(Quda, Azu): Is it possible to remove these checks if we ensure prepare segment length is - // larger than distance to target lane start - if (!is_valid_start_point(common_data_ptr_, lc_start_pose)) return false; - - // lane changing start is at the end of prepare segment - const auto target_length_from_lane_change_start_pose = - utils::getArcLengthToTargetLanelet(current_lanes, target_lanes.front(), lc_start_pose); - - // Check if the lane changing start point is not on the lanes next to target lanes, - if (target_length_from_lane_change_start_pose > std::numeric_limits::epsilon()) { - throw std::logic_error("lane change start is behind target lanelet!"); - } - - return true; -} - lane_change::TargetObjects NormalLaneChange::get_target_objects( const FilteredLanesObjects & filtered_objects, [[maybe_unused]] const lanelet::ConstLanelets & current_lanes) const @@ -1107,41 +1029,6 @@ void NormalLaneChange::filterOncomingObjects(PredictedObjects & objects) const }); } -PathWithLaneId NormalLaneChange::getTargetSegment( - const lanelet::ConstLanelets & target_lanes, const Pose & lane_changing_start_pose, - const double target_lane_length, const double lane_changing_length, - const double lane_changing_velocity, const double buffer_for_next_lane_change) const -{ - const auto & route_handler = *getRouteHandler(); - const auto forward_path_length = planner_data_->parameters.forward_path_length; - - const double s_start = std::invoke([&lane_changing_start_pose, &target_lanes, - &lane_changing_length, &target_lane_length, - &buffer_for_next_lane_change]() { - const auto arc_to_start_pose = - lanelet::utils::getArcCoordinates(target_lanes, lane_changing_start_pose); - const double dist_from_front_target_lanelet = arc_to_start_pose.length + lane_changing_length; - const double end_of_lane_dist_without_buffer = target_lane_length - buffer_for_next_lane_change; - return std::min(dist_from_front_target_lanelet, end_of_lane_dist_without_buffer); - }); - - const double s_end = std::invoke( - [&s_start, &forward_path_length, &target_lane_length, &buffer_for_next_lane_change]() { - const double dist_from_start = s_start + forward_path_length; - const double dist_from_end = target_lane_length - buffer_for_next_lane_change; - return std::max( - std::min(dist_from_start, dist_from_end), s_start + std::numeric_limits::epsilon()); - }); - - PathWithLaneId target_segment = route_handler.getCenterLinePath(target_lanes, s_start, s_end); - for (auto & point : target_segment.points) { - point.point.longitudinal_velocity_mps = - std::min(point.point.longitudinal_velocity_mps, static_cast(lane_changing_velocity)); - } - - return target_segment; -} - std::vector NormalLaneChange::get_prepare_metrics() const { const auto & current_lanes = common_data_ptr_->lanes_ptr->current; @@ -1199,7 +1086,6 @@ bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths) const auto & current_lanes = get_current_lanes(); const auto & target_lanes = get_target_lanes(); - const auto current_velocity = getEgoVelocity(); const auto sorted_lane_ids = utils::lane_change::get_sorted_lane_ids(common_data_ptr_); const auto target_objects = get_target_objects(filtered_objects_, current_lanes); @@ -1239,7 +1125,8 @@ bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths) PathWithLaneId prepare_segment; try { - if (!get_prepare_segment(prepare_segment, prep_metric.length)) { + if (!utils::lane_change::get_prepare_segment( + common_data_ptr_, prev_module_output_.path, prep_metric, prepare_segment)) { debug_print("Reject: failed to get valid prepare segment!"); continue; } @@ -1258,7 +1145,10 @@ bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths) const auto lane_changing_metrics = get_lane_changing_metrics( prepare_segment, prep_metric, shift_length, dist_to_next_regulatory_element); - utils::lane_change::setPrepareVelocity(prepare_segment, current_velocity, prep_metric.velocity); + // set_prepare_velocity must only be called after computing lane change metrics, as lane change + // metrics rely on the prepare segment's original velocity as max_path_velocity. + utils::lane_change::set_prepare_velocity( + prepare_segment, common_data_ptr_->get_ego_speed(), prep_metric.velocity); for (const auto & lc_metric : lane_changing_metrics) { const auto debug_print_lat = [&](const std::string & s) { @@ -1274,9 +1164,8 @@ bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths) LaneChangePath candidate_path; try { - candidate_path = get_candidate_path( - prep_metric, lc_metric, prepare_segment, sorted_lane_ids, lane_changing_start_pose, - shift_length); + candidate_path = utils::lane_change::get_candidate_path( + common_data_ptr_, prep_metric, lc_metric, prepare_segment, sorted_lane_ids, shift_length); } catch (const std::exception & e) { debug_print_lat(std::string("Reject: ") + e.what()); continue; @@ -1302,52 +1191,6 @@ bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths) return false; } -LaneChangePath NormalLaneChange::get_candidate_path( - const LaneChangePhaseMetrics & prep_metrics, const LaneChangePhaseMetrics & lc_metrics, - const PathWithLaneId & prep_segment, const std::vector> & sorted_lane_ids, - const Pose & lc_start_pose, const double shift_length) const -{ - const auto & route_handler = *getRouteHandler(); - const auto & target_lanes = common_data_ptr_->lanes_ptr->target; - - const auto resample_interval = - utils::lane_change::calcLaneChangeResampleInterval(lc_metrics.length, prep_metrics.velocity); - const auto target_lane_reference_path = utils::lane_change::get_reference_path_from_target_Lane( - common_data_ptr_, lc_start_pose, lc_metrics.length, resample_interval); - - if (target_lane_reference_path.points.empty()) { - throw std::logic_error("target_lane_reference_path is empty!"); - } - - const auto lc_end_pose = std::invoke([&]() { - const auto dist_to_lc_start = - lanelet::utils::getArcCoordinates(target_lanes, lc_start_pose).length; - const auto dist_to_lc_end = dist_to_lc_start + lc_metrics.length; - return route_handler.get_pose_from_2d_arc_length(target_lanes, dist_to_lc_end); - }); - - const auto shift_line = utils::lane_change::get_lane_changing_shift_line( - lc_start_pose, lc_end_pose, target_lane_reference_path, shift_length); - - LaneChangeInfo lane_change_info{prep_metrics, lc_metrics, lc_start_pose, lc_end_pose, shift_line}; - - const auto candidate_path = utils::lane_change::construct_candidate_path( - common_data_ptr_, lane_change_info, prep_segment, target_lane_reference_path, sorted_lane_ids); - - if (!candidate_path) { - throw std::logic_error("failed to generate candidate path!"); - } - - if ( - candidate_path.value().info.length.sum() + - common_data_ptr_->transient_data.next_dist_buffer.min > - common_data_ptr_->transient_data.dist_to_terminal_end) { - throw std::logic_error("invalid candidate path length!"); - } - - return *candidate_path; -} - bool NormalLaneChange::check_candidate_path_safety( const LaneChangePath & candidate_path, const lane_change::TargetObjects & target_objects) const { @@ -1377,147 +1220,30 @@ bool NormalLaneChange::check_candidate_path_safety( throw std::logic_error("Path footprint exceeds target lane boundary. Skip lane change."); } + if ((target_objects.empty()) || candidate_path.path.points.empty()) { + RCLCPP_DEBUG(logger_, "There is nothing to check."); + return true; + } + constexpr size_t decel_sampling_num = 1; + const auto ego_predicted_paths = utils::lane_change::convert_to_predicted_paths( + common_data_ptr_, candidate_path, decel_sampling_num); + const auto safety_check_with_normal_rss = isLaneChangePathSafe( - candidate_path, target_objects, common_data_ptr_->lc_param_ptr->safety.rss_params, - decel_sampling_num, lane_change_debug_.collision_check_objects); + candidate_path, ego_predicted_paths, target_objects, + common_data_ptr_->lc_param_ptr->safety.rss_params, lane_change_debug_.collision_check_objects); if (!safety_check_with_normal_rss.is_safe && is_stuck) { const auto safety_check_with_stuck_rss = isLaneChangePathSafe( - candidate_path, target_objects, common_data_ptr_->lc_param_ptr->safety.rss_params_for_stuck, - decel_sampling_num, lane_change_debug_.collision_check_objects); + candidate_path, ego_predicted_paths, target_objects, + common_data_ptr_->lc_param_ptr->safety.rss_params_for_stuck, + lane_change_debug_.collision_check_objects); return safety_check_with_stuck_rss.is_safe; } return safety_check_with_normal_rss.is_safe; } -std::optional NormalLaneChange::calcTerminalLaneChangePath( - const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes) const -{ - const auto is_empty = [&](const auto & data, const auto & s) { - if (!data.empty()) return false; - RCLCPP_WARN(logger_, "%s is empty. Not expected.", s); - return true; - }; - - const auto target_lane_neighbors_polygon_2d = - common_data_ptr_->lanes_polygon_ptr->target_neighbor; - if ( - is_empty(current_lanes, "current_lanes") || is_empty(target_lanes, "target_lanes") || - is_empty(target_lane_neighbors_polygon_2d, "target_lane_neighbors_polygon_2d")) { - return {}; - } - - const auto & route_handler = *getRouteHandler(); - - const auto minimum_lane_changing_velocity = - lane_change_parameters_->trajectory.min_lane_changing_velocity; - - const auto is_goal_in_route = route_handler.isInGoalRouteSection(target_lanes.back()); - - const auto current_min_dist_buffer = common_data_ptr_->transient_data.current_dist_buffer.min; - const auto next_min_dist_buffer = common_data_ptr_->transient_data.next_dist_buffer.min; - - const auto sorted_lane_ids = utils::lane_change::get_sorted_lane_ids(common_data_ptr_); - - // lane changing start getEgoPose() is at the end of prepare segment - const auto current_lane_terminal_point = - lanelet::utils::conversion::toGeomMsgPt(current_lanes.back().centerline3d().back()); - - double distance_to_terminal_from_goal = 0; - if (is_goal_in_route) { - distance_to_terminal_from_goal = - utils::getDistanceToEndOfLane(route_handler.getGoalPose(), current_lanes); - } - - const auto lane_changing_start_pose = autoware::motion_utils::calcLongitudinalOffsetPose( - prev_module_output_.path.points, current_lane_terminal_point, - -(current_min_dist_buffer + next_min_dist_buffer + distance_to_terminal_from_goal)); - - if (!lane_changing_start_pose) { - RCLCPP_DEBUG(logger_, "Reject: lane changing start pose not found!!!"); - return {}; - } - - const auto target_length_from_lane_change_start_pose = utils::getArcLengthToTargetLanelet( - current_lanes, target_lanes.front(), lane_changing_start_pose.value()); - - // Check if the lane changing start point is not on the lanes next to target lanes, - if (target_length_from_lane_change_start_pose > 0.0) { - RCLCPP_DEBUG(logger_, "lane change start getEgoPose() is behind target lanelet!"); - return {}; - } - - const auto shift_length = lanelet::utils::getLateralDistanceToClosestLanelet( - target_lanes, lane_changing_start_pose.value()); - - const auto [min_lateral_acc, max_lateral_acc] = - lane_change_parameters_->trajectory.lat_acc_map.find(minimum_lane_changing_velocity); - - const auto lane_changing_time = autoware::motion_utils::calc_shift_time_from_jerk( - shift_length, lane_change_parameters_->trajectory.lateral_jerk, max_lateral_acc); - - const auto target_lane_length = common_data_ptr_->transient_data.target_lane_length; - const auto target_segment = getTargetSegment( - target_lanes, lane_changing_start_pose.value(), target_lane_length, current_min_dist_buffer, - minimum_lane_changing_velocity, next_min_dist_buffer); - - if (target_segment.points.empty()) { - RCLCPP_DEBUG(logger_, "Reject: target segment is empty!! something wrong..."); - return {}; - } - - LaneChangeInfo lane_change_info; - lane_change_info.longitudinal_acceleration = LaneChangePhaseInfo{0.0, 0.0}; - lane_change_info.duration = LaneChangePhaseInfo{0.0, lane_changing_time}; - lane_change_info.velocity = - LaneChangePhaseInfo{minimum_lane_changing_velocity, minimum_lane_changing_velocity}; - lane_change_info.length = LaneChangePhaseInfo{0.0, current_min_dist_buffer}; - lane_change_info.lane_changing_start = lane_changing_start_pose.value(); - lane_change_info.lane_changing_end = target_segment.points.front().point.pose; - lane_change_info.lateral_acceleration = max_lateral_acc; - lane_change_info.terminal_lane_changing_velocity = minimum_lane_changing_velocity; - - if (!is_valid_start_point(common_data_ptr_, lane_changing_start_pose.value())) { - RCLCPP_DEBUG( - logger_, - "Reject: lane changing points are not inside of the target preferred lanes or its " - "neighbors"); - return {}; - } - - const auto resample_interval = utils::lane_change::calcLaneChangeResampleInterval( - current_min_dist_buffer, minimum_lane_changing_velocity); - const auto target_lane_reference_path = utils::lane_change::get_reference_path_from_target_Lane( - common_data_ptr_, lane_changing_start_pose.value(), current_min_dist_buffer, resample_interval); - - if (target_lane_reference_path.points.empty()) { - RCLCPP_DEBUG(logger_, "Reject: target_lane_reference_path is empty!!"); - return {}; - } - - lane_change_info.shift_line = utils::lane_change::get_lane_changing_shift_line( - lane_changing_start_pose.value(), target_segment.points.front().point.pose, - target_lane_reference_path, shift_length); - - auto reference_segment = prev_module_output_.path; - const double length_to_lane_changing_start = autoware::motion_utils::calcSignedArcLength( - reference_segment.points, reference_segment.points.front().point.pose.position, - lane_changing_start_pose->position); - utils::clipPathLength(reference_segment, 0, length_to_lane_changing_start, 0.0); - // remove terminal points because utils::clipPathLength() calculates extra long path - reference_segment.points.pop_back(); - reference_segment.points.back().point.longitudinal_velocity_mps = - static_cast(minimum_lane_changing_velocity); - - const auto terminal_lane_change_path = utils::lane_change::construct_candidate_path( - common_data_ptr_, lane_change_info, reference_segment, target_lane_reference_path, - sorted_lane_ids); - - return terminal_lane_change_path; -} - PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const { const auto & path = status_.lane_change_path; @@ -1545,9 +1271,13 @@ PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const return {false, false}; } + const auto decel_sampling_num = + static_cast(lane_change_parameters_->cancel.deceleration_sampling_num); + const auto ego_predicted_paths = + utils::lane_change::convert_to_predicted_paths(common_data_ptr_, path, decel_sampling_num); const auto safety_status = isLaneChangePathSafe( - path, target_objects, lane_change_parameters_->safety.rss_params_for_abort, - static_cast(lane_change_parameters_->cancel.deceleration_sampling_num), debug_data); + path, ego_predicted_paths, target_objects, lane_change_parameters_->safety.rss_params_for_abort, + debug_data); { // only for debug purpose lane_change_debug_.collision_check_objects.clear(); @@ -1779,103 +1509,57 @@ bool NormalLaneChange::calcAbortPath() PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( const LaneChangePath & lane_change_path, + const std::vector> & ego_predicted_paths, const lane_change::TargetObjects & collision_check_objects, - const utils::path_safety_checker::RSSparams & rss_params, const size_t deceleration_sampling_num, + const utils::path_safety_checker::RSSparams & rss_params, CollisionCheckDebugMap & debug_data) const { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); constexpr auto is_safe = true; constexpr auto is_object_behind_ego = true; - if (collision_check_objects.leading.empty() && collision_check_objects.trailing.empty()) { - RCLCPP_DEBUG(logger_, "There is nothing to check."); - return {is_safe, !is_object_behind_ego}; - } - const auto is_check_prepare_phase = check_prepare_phase(); - const auto all_decel_pattern_has_collision = - [&](const utils::path_safety_checker::ExtendedPredictedObjects & objects) -> bool { - return has_collision_with_decel_patterns( - lane_change_path, objects, deceleration_sampling_num, rss_params, is_check_prepare_phase, - debug_data); + const auto all_paths_collide = [&](const auto & objects) { + const auto stopped_obj_vel_th = lane_change_parameters_->safety.th_stopped_object_velocity; + return ranges::all_of(ego_predicted_paths, [&](const auto & ego_predicted_path) { + const auto check_for_collision = [&](const auto & object) { + const auto selected_rss_param = (object.initial_twist.linear.x <= stopped_obj_vel_th) + ? lane_change_parameters_->safety.rss_params_for_parked + : rss_params; + return is_colliding( + lane_change_path, object, ego_predicted_path, selected_rss_param, is_check_prepare_phase, + debug_data); + }; + return ranges::any_of(objects, check_for_collision); + }); }; - if (all_decel_pattern_has_collision(collision_check_objects.trailing)) { + if (all_paths_collide(collision_check_objects.trailing)) { return {!is_safe, is_object_behind_ego}; } - if (all_decel_pattern_has_collision(collision_check_objects.leading)) { + if (all_paths_collide(collision_check_objects.leading)) { return {!is_safe, !is_object_behind_ego}; } return {is_safe, !is_object_behind_ego}; } -bool NormalLaneChange::has_collision_with_decel_patterns( - const LaneChangePath & lane_change_path, const ExtendedPredictedObjects & objects, - const size_t deceleration_sampling_num, const RSSparams & rss_param, - const bool check_prepare_phase, CollisionCheckDebugMap & debug_data) const -{ - if (objects.empty()) { - return false; - } - - const auto & path = lane_change_path.path; - - if (path.points.empty()) { - return false; - } - - const auto bpp_param = *common_data_ptr_->bpp_param_ptr; - const auto global_min_acc = bpp_param.min_acc; - const auto lane_changing_acc = lane_change_path.info.longitudinal_acceleration.lane_changing; - - const auto min_acc = std::min(lane_changing_acc, global_min_acc); - const auto sampling_num = - std::abs(min_acc - lane_changing_acc) > floating_err_th ? deceleration_sampling_num : 1; - const auto acc_resolution = (min_acc - lane_changing_acc) / static_cast(sampling_num); - - std::vector acceleration_values(sampling_num); - std::iota(acceleration_values.begin(), acceleration_values.end(), 0); - - std::transform( - acceleration_values.begin(), acceleration_values.end(), acceleration_values.begin(), - [&](double n) { return lane_changing_acc + n * acc_resolution; }); - - const auto stopped_obj_vel_th = lane_change_parameters_->safety.th_stopped_object_velocity; - const auto all_collided = std::all_of( - acceleration_values.begin(), acceleration_values.end(), [&](const auto acceleration) { - const auto ego_predicted_path = utils::lane_change::convert_to_predicted_path( - common_data_ptr_, lane_change_path, acceleration); - - return std::any_of(objects.begin(), objects.end(), [&](const auto & obj) { - const auto selected_rss_param = (obj.initial_twist.linear.x <= stopped_obj_vel_th) - ? lane_change_parameters_->safety.rss_params_for_parked - : rss_param; - return is_collided( - lane_change_path, obj, ego_predicted_path, selected_rss_param, check_prepare_phase, - debug_data); - }); - }); - - return all_collided; -} - -bool NormalLaneChange::is_collided( +bool NormalLaneChange::is_colliding( const LaneChangePath & lane_change_path, const ExtendedPredictedObject & obj, const std::vector & ego_predicted_path, const RSSparams & selected_rss_param, const bool check_prepare_phase, CollisionCheckDebugMap & debug_data) const { - constexpr auto is_collided{true}; + constexpr auto is_colliding{true}; if (lane_change_path.path.points.empty()) { - return !is_collided; + return !is_colliding; } if (ego_predicted_path.empty()) { - return !is_collided; + return !is_colliding; } const auto & lanes_polygon_ptr = common_data_ptr_->lanes_polygon_ptr; @@ -1883,7 +1567,7 @@ bool NormalLaneChange::is_collided( const auto & expanded_target_polygon = lanes_polygon_ptr->target; if (current_polygon.empty() || expanded_target_polygon.empty()) { - return !is_collided; + return !is_colliding; } constexpr auto is_safe{true}; @@ -1934,10 +1618,10 @@ bool NormalLaneChange::is_collided( utils::path_safety_checker::updateCollisionCheckDebugMap( debug_data, current_debug_data, !is_safe); - return is_collided; + return is_colliding; } utils::path_safety_checker::updateCollisionCheckDebugMap(debug_data, current_debug_data, is_safe); - return !is_collided; + return !is_colliding; } double NormalLaneChange::get_max_velocity_for_safety_check() const @@ -2004,18 +1688,6 @@ bool NormalLaneChange::is_ego_stuck() const return has_object_blocking; } -bool NormalLaneChange::is_valid_start_point( - const lane_change::CommonDataPtr & common_data_ptr, const Pose & pose) const -{ - const lanelet::BasicPoint2d lc_start_point(pose.position.x, pose.position.y); - - const auto & target_neighbor_poly = common_data_ptr->lanes_polygon_ptr->target_neighbor; - const auto & target_lane_poly = common_data_ptr_->lanes_polygon_ptr->target; - - return boost::geometry::covered_by(lc_start_point, target_neighbor_poly) || - boost::geometry::covered_by(lc_start_point, target_lane_poly); -} - void NormalLaneChange::set_stop_pose(const double arc_length_to_stop_pose, PathWithLaneId & path) { const auto stop_point = utils::insertStopPoint(arc_length_to_stop_pose, path); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/path.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/path.cpp new file mode 100644 index 0000000000000..d7303d7d1df2d --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/path.cpp @@ -0,0 +1,292 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/behavior_path_lane_change_module/utils/path.hpp" + +#include "autoware/behavior_path_lane_change_module/structs/data.hpp" +#include "autoware/behavior_path_lane_change_module/utils/utils.hpp" +#include "autoware/behavior_path_planner_common/utils/path_utils.hpp" +#include "autoware/behavior_path_planner_common/utils/utils.hpp" + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +namespace +{ +using autoware::behavior_path_planner::LaneChangeInfo; +using autoware::behavior_path_planner::PathPointWithLaneId; +using autoware::behavior_path_planner::PathShifter; +using autoware::behavior_path_planner::PathWithLaneId; +using autoware::behavior_path_planner::ShiftedPath; +using autoware::behavior_path_planner::lane_change::CommonDataPtr; +using autoware::behavior_path_planner::lane_change::LCParamPtr; + +using autoware::behavior_path_planner::LaneChangePhaseMetrics; +using autoware::behavior_path_planner::ShiftLine; +using geometry_msgs::msg::Pose; + +double calc_resample_interval( + const double lane_changing_length, const double lane_changing_velocity) +{ + constexpr auto min_resampling_points{30.0}; + constexpr auto resampling_dt{0.2}; + return std::max( + lane_changing_length / min_resampling_points, lane_changing_velocity * resampling_dt); +} + +PathWithLaneId get_reference_path_from_target_Lane( + const CommonDataPtr & common_data_ptr, const Pose & lane_changing_start_pose, + const double lane_changing_length, const double resample_interval) +{ + const auto & route_handler = *common_data_ptr->route_handler_ptr; + const auto & target_lanes = common_data_ptr->lanes_ptr->target; + const auto target_lane_length = common_data_ptr->transient_data.target_lane_length; + const auto is_goal_in_route = common_data_ptr->lanes_ptr->target_lane_in_goal_section; + const auto next_lc_buffer = common_data_ptr->transient_data.next_dist_buffer.min; + const auto forward_path_length = common_data_ptr->bpp_param_ptr->forward_path_length; + + const auto lane_change_start_arc_position = + lanelet::utils::getArcCoordinates(target_lanes, lane_changing_start_pose); + + const double s_start = lane_change_start_arc_position.length; + const double s_end = std::invoke([&]() { + const auto dist_from_lc_start = s_start + lane_changing_length + forward_path_length; + if (is_goal_in_route) { + const double s_goal = + lanelet::utils::getArcCoordinates(target_lanes, route_handler.getGoalPose()).length - + next_lc_buffer; + return std::min(dist_from_lc_start, s_goal); + } + return std::min(dist_from_lc_start, target_lane_length - next_lc_buffer); + }); + + constexpr double epsilon = 1e-4; + if (s_end - s_start + epsilon < lane_changing_length) { + return PathWithLaneId(); + } + + const auto lane_changing_reference_path = + route_handler.getCenterLinePath(target_lanes, s_start, s_end); + + return autoware::behavior_path_planner::utils::resamplePathWithSpline( + lane_changing_reference_path, resample_interval, true, {0.0, lane_changing_length}); +} + +ShiftLine get_lane_changing_shift_line( + const Pose & lane_changing_start_pose, const Pose & lane_changing_end_pose, + const PathWithLaneId & reference_path, const double shift_length) +{ + ShiftLine shift_line; + shift_line.end_shift_length = shift_length; + shift_line.start = lane_changing_start_pose; + shift_line.end = lane_changing_end_pose; + shift_line.start_idx = autoware::motion_utils::findNearestIndex( + reference_path.points, lane_changing_start_pose.position); + shift_line.end_idx = autoware::motion_utils::findNearestIndex( + reference_path.points, lane_changing_end_pose.position); + + return shift_line; +} + +ShiftedPath get_shifted_path( + const PathWithLaneId & target_lane_reference_path, const LaneChangeInfo & lane_change_info) +{ + const auto longitudinal_acceleration = lane_change_info.longitudinal_acceleration; + + PathShifter path_shifter; + path_shifter.setPath(target_lane_reference_path); + path_shifter.addShiftLine(lane_change_info.shift_line); + path_shifter.setLongitudinalAcceleration(longitudinal_acceleration.lane_changing); + const auto initial_lane_changing_velocity = lane_change_info.velocity.lane_changing; + path_shifter.setVelocity(initial_lane_changing_velocity); + path_shifter.setLateralAccelerationLimit(std::abs(lane_change_info.lateral_acceleration)); + + constexpr auto offset_back = false; + ShiftedPath shifted_path; + [[maybe_unused]] const auto success = path_shifter.generate(&shifted_path, offset_back); + return shifted_path; +} + +std::optional exceed_yaw_threshold( + const PathWithLaneId & prepare_segment, const PathWithLaneId & lane_changing_segment, + const double yaw_th_rad) +{ + const auto & prepare = prepare_segment.points; + const auto & lane_changing = lane_changing_segment.points; + + if (prepare.size() <= 1 || lane_changing.size() <= 1) { + return std::nullopt; + } + + const auto & p1 = std::prev(prepare.end() - 1)->point.pose; + const auto & p2 = std::next(lane_changing.begin())->point.pose; + const auto yaw_diff_rad = std::abs(autoware::universe_utils::normalizeRadian( + tf2::getYaw(p1.orientation) - tf2::getYaw(p2.orientation))); + if (yaw_diff_rad > yaw_th_rad) { + return yaw_diff_rad; + } + return std::nullopt; +} +}; // namespace + +namespace autoware::behavior_path_planner::utils::lane_change +{ +using behavior_path_planner::lane_change::CommonDataPtr; + +bool get_prepare_segment( + const CommonDataPtr & common_data_ptr, const PathWithLaneId & prev_module_path, + const LaneChangePhaseMetrics prep_metric, PathWithLaneId & prepare_segment) +{ + const auto & current_lanes = common_data_ptr->lanes_ptr->current; + const auto & target_lanes = common_data_ptr->lanes_ptr->target; + const auto backward_path_length = common_data_ptr->bpp_param_ptr->backward_path_length; + + if (current_lanes.empty() || target_lanes.empty()) { + throw std::logic_error("Empty lanes!"); + } + + prepare_segment = prev_module_path; + const size_t current_seg_idx = + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + prepare_segment.points, common_data_ptr->get_ego_pose(), 3.0, 1.0); + utils::clipPathLength(prepare_segment, current_seg_idx, prep_metric.length, backward_path_length); + + if (prepare_segment.points.empty()) return false; + + const auto & lc_start_pose = prepare_segment.points.back().point.pose; + + // TODO(Quda, Azu): Is it possible to remove these checks if we ensure prepare segment length is + // larger than distance to target lane start + if (!is_valid_start_point(common_data_ptr, lc_start_pose)) return false; + + // lane changing start is at the end of prepare segment + const auto target_length_from_lane_change_start_pose = + utils::getArcLengthToTargetLanelet(current_lanes, target_lanes.front(), lc_start_pose); + + // Check if the lane changing start point is not on the lanes next to target lanes, + if (target_length_from_lane_change_start_pose > std::numeric_limits::epsilon()) { + throw std::logic_error("lane change start is behind target lanelet!"); + } + + return true; +} + +LaneChangePath get_candidate_path( + const CommonDataPtr & common_data_ptr, const LaneChangePhaseMetrics & prep_metric, + const LaneChangePhaseMetrics & lc_metric, const PathWithLaneId & prep_segment, + const std::vector> & sorted_lane_ids, const double shift_length) +{ + const auto & route_handler = *common_data_ptr->route_handler_ptr; + const auto & target_lanes = common_data_ptr->lanes_ptr->target; + + const auto resample_interval = calc_resample_interval(lc_metric.length, prep_metric.velocity); + + if (prep_segment.points.empty()) { + throw std::logic_error("Empty prepare segment!"); + } + + const auto & lc_start_pose = prep_segment.points.back().point.pose; + const auto target_lane_reference_path = get_reference_path_from_target_Lane( + common_data_ptr, lc_start_pose, lc_metric.length, resample_interval); + + if (target_lane_reference_path.points.empty()) { + throw std::logic_error("Empty target reference!"); + } + + const auto lc_end_pose = std::invoke([&]() { + const auto dist_to_lc_start = + lanelet::utils::getArcCoordinates(target_lanes, lc_start_pose).length; + const auto dist_to_lc_end = dist_to_lc_start + lc_metric.length; + return route_handler.get_pose_from_2d_arc_length(target_lanes, dist_to_lc_end); + }); + + const auto shift_line = get_lane_changing_shift_line( + lc_start_pose, lc_end_pose, target_lane_reference_path, shift_length); + + LaneChangeInfo lane_change_info{prep_metric, lc_metric, lc_start_pose, lc_end_pose, shift_line}; + + if ( + lane_change_info.length.sum() + common_data_ptr->transient_data.next_dist_buffer.min > + common_data_ptr->transient_data.dist_to_terminal_end) { + throw std::logic_error("invalid candidate path length!"); + } + + return utils::lane_change::construct_candidate_path( + lane_change_info, prep_segment, target_lane_reference_path, sorted_lane_ids); +} + +LaneChangePath construct_candidate_path( + const LaneChangeInfo & lane_change_info, const PathWithLaneId & prepare_segment, + const PathWithLaneId & target_lane_reference_path, + const std::vector> & sorted_lane_ids) +{ + const auto & shift_line = lane_change_info.shift_line; + const auto terminal_lane_changing_velocity = lane_change_info.terminal_lane_changing_velocity; + + auto shifted_path = get_shifted_path(target_lane_reference_path, lane_change_info); + + if (shifted_path.path.points.empty()) { + throw std::logic_error("Failed to generate shifted path."); + } + + if (shifted_path.path.points.size() < shift_line.end_idx + 1) { + throw std::logic_error("Path points are removed by PathShifter."); + } + + const auto lc_end_idx_opt = autoware::motion_utils::findNearestIndex( + shifted_path.path.points, lane_change_info.lane_changing_end); + + if (!lc_end_idx_opt) { + throw std::logic_error("Lane change end idx not found on target path."); + } + + for (size_t i = 0; i < shifted_path.path.points.size(); ++i) { + auto & point = shifted_path.path.points.at(i); + if (i < *lc_end_idx_opt) { + point.lane_ids = replaceWithSortedIds(point.lane_ids, sorted_lane_ids); + point.point.longitudinal_velocity_mps = std::min( + point.point.longitudinal_velocity_mps, static_cast(terminal_lane_changing_velocity)); + continue; + } + const auto nearest_idx = + autoware::motion_utils::findNearestIndex(target_lane_reference_path.points, point.point.pose); + point.lane_ids = target_lane_reference_path.points.at(*nearest_idx).lane_ids; + } + + constexpr auto yaw_diff_th = autoware::universe_utils::deg2rad(5.0); + if ( + const auto yaw_diff_opt = + exceed_yaw_threshold(prepare_segment, shifted_path.path, yaw_diff_th)) { + std::stringstream err_msg; + err_msg << "Excessive yaw difference " << yaw_diff_opt.value() << " which exceeds the " + << yaw_diff_th << " radian threshold."; + throw std::logic_error(err_msg.str()); + } + + LaneChangePath candidate_path; + candidate_path.path = utils::combinePath(prepare_segment, shifted_path.path); + candidate_path.shifted_path = shifted_path; + candidate_path.info = lane_change_info; + + return candidate_path; +} +} // namespace autoware::behavior_path_planner::utils::lane_change diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp index 2b1c744a926e3..147ef3856ac4e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp @@ -19,7 +19,6 @@ #include "autoware/behavior_path_planner_common/parameters.hpp" #include "autoware/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp" #include "autoware/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" -#include "autoware/behavior_path_planner_common/utils/path_utils.hpp" #include "autoware/behavior_path_planner_common/utils/traffic_light_utils.hpp" #include "autoware/behavior_path_planner_common/utils/utils.hpp" #include "autoware/object_recognition_utils/predicted_path_utils.hpp" @@ -29,15 +28,14 @@ #include #include #include -#include #include +#include #include #include #include -#include -#include -#include -#include +#include +#include +#include #include #include #include @@ -72,7 +70,6 @@ using autoware_perception_msgs::msg::PredictedObjects; using geometry_msgs::msg::Pose; using tier4_planning_msgs::msg::PathWithLaneId; -using lanelet::ArcCoordinates; using tier4_planning_msgs::msg::PathPointWithLaneId; rclcpp::Logger get_logger() @@ -88,29 +85,20 @@ bool is_mandatory_lane_change(const ModuleType lc_type) lc_type == LaneChangeModuleType::AVOIDANCE_BY_LANE_CHANGE; } -double calcLaneChangeResampleInterval( - const double lane_changing_length, const double lane_changing_velocity) -{ - constexpr auto min_resampling_points{30.0}; - constexpr auto resampling_dt{0.2}; - return std::max( - lane_changing_length / min_resampling_points, lane_changing_velocity * resampling_dt); -} - -void setPrepareVelocity( +void set_prepare_velocity( PathWithLaneId & prepare_segment, const double current_velocity, const double prepare_velocity) { - if (current_velocity < prepare_velocity) { - // acceleration - for (auto & point : prepare_segment.points) { - point.point.longitudinal_velocity_mps = - std::min(point.point.longitudinal_velocity_mps, static_cast(prepare_velocity)); - } - } else { + if (current_velocity >= prepare_velocity) { // deceleration prepare_segment.points.back().point.longitudinal_velocity_mps = std::min( prepare_segment.points.back().point.longitudinal_velocity_mps, static_cast(prepare_velocity)); + return; + } + // acceleration + for (auto & point : prepare_segment.points) { + point.point.longitudinal_velocity_mps = + std::min(point.point.longitudinal_velocity_mps, static_cast(prepare_velocity)); } } @@ -132,34 +120,9 @@ lanelet::ConstLanelets get_target_neighbor_lanes( } } } - return neighbor_lanes; } -bool isPathInLanelets( - const PathWithLaneId & path, const lanelet::ConstLanelets & current_lanes, - const lanelet::ConstLanelets & target_lanes) -{ - const auto current_lane_poly = - lanelet::utils::getPolygonFromArcLength(current_lanes, 0, std::numeric_limits::max()); - const auto target_lane_poly = - lanelet::utils::getPolygonFromArcLength(target_lanes, 0, std::numeric_limits::max()); - const auto current_lane_poly_2d = lanelet::utils::to2D(current_lane_poly).basicPolygon(); - const auto target_lane_poly_2d = lanelet::utils::to2D(target_lane_poly).basicPolygon(); - for (const auto & pt : path.points) { - const lanelet::BasicPoint2d ll_pt(pt.point.pose.position.x, pt.point.pose.position.y); - const auto is_in_current = boost::geometry::covered_by(ll_pt, current_lane_poly_2d); - if (is_in_current) { - continue; - } - const auto is_in_target = boost::geometry::covered_by(ll_pt, target_lane_poly_2d); - if (!is_in_target) { - return false; - } - } - return true; -} - bool path_footprint_exceeds_target_lane_bound( const CommonDataPtr & common_data_ptr, const PathWithLaneId & path, const VehicleInfo & ego_info, const double margin) @@ -190,152 +153,6 @@ bool path_footprint_exceeds_target_lane_bound( return false; } -std::optional construct_candidate_path( - const CommonDataPtr & common_data_ptr, const LaneChangeInfo & lane_change_info, - const PathWithLaneId & prepare_segment, const PathWithLaneId & target_lane_reference_path, - const std::vector> & sorted_lane_ids) -{ - const auto & shift_line = lane_change_info.shift_line; - const auto terminal_lane_changing_velocity = lane_change_info.terminal_lane_changing_velocity; - const auto longitudinal_acceleration = lane_change_info.longitudinal_acceleration; - const auto lane_change_velocity = lane_change_info.velocity; - - PathShifter path_shifter; - path_shifter.setPath(target_lane_reference_path); - path_shifter.addShiftLine(shift_line); - path_shifter.setLongitudinalAcceleration(longitudinal_acceleration.lane_changing); - ShiftedPath shifted_path; - - // offset front side - bool offset_back = false; - - const auto initial_lane_changing_velocity = lane_change_velocity.lane_changing; - path_shifter.setVelocity(initial_lane_changing_velocity); - path_shifter.setLateralAccelerationLimit(std::abs(lane_change_info.lateral_acceleration)); - - if (!path_shifter.generate(&shifted_path, offset_back)) { - RCLCPP_DEBUG(get_logger(), "Failed to generate shifted path."); - } - - // TODO(Zulfaqar Azmi): have to think of a more feasible solution for points being remove by path - // shifter. - if (shifted_path.path.points.size() < shift_line.end_idx + 1) { - RCLCPP_DEBUG(get_logger(), "Path points are removed by PathShifter."); - return std::nullopt; - } - - LaneChangePath candidate_path; - candidate_path.info = lane_change_info; - - const auto lane_change_end_idx = autoware::motion_utils::findNearestIndex( - shifted_path.path.points, candidate_path.info.lane_changing_end); - - if (!lane_change_end_idx) { - RCLCPP_DEBUG(get_logger(), "Lane change end idx not found on target path."); - return std::nullopt; - } - - for (size_t i = 0; i < shifted_path.path.points.size(); ++i) { - auto & point = shifted_path.path.points.at(i); - if (i < *lane_change_end_idx) { - point.lane_ids = replaceWithSortedIds(point.lane_ids, sorted_lane_ids); - point.point.longitudinal_velocity_mps = std::min( - point.point.longitudinal_velocity_mps, static_cast(terminal_lane_changing_velocity)); - continue; - } - const auto nearest_idx = - autoware::motion_utils::findNearestIndex(target_lane_reference_path.points, point.point.pose); - point.lane_ids = target_lane_reference_path.points.at(*nearest_idx).lane_ids; - } - - // TODO(Yutaka Shimizu): remove this flag after make the isPathInLanelets faster - const bool enable_path_check_in_lanelet = false; - - // check candidate path is in lanelet - const auto & current_lanes = common_data_ptr->lanes_ptr->current; - const auto & target_lanes = common_data_ptr->lanes_ptr->target; - if ( - enable_path_check_in_lanelet && - !isPathInLanelets(shifted_path.path, current_lanes, target_lanes)) { - return std::nullopt; - } - - if (prepare_segment.points.size() > 1 && shifted_path.path.points.size() > 1) { - const auto & prepare_segment_second_last_point = - std::prev(prepare_segment.points.end() - 1)->point.pose; - const auto & lane_change_start_from_shifted = - std::next(shifted_path.path.points.begin())->point.pose; - const auto yaw_diff2 = std::abs(autoware::universe_utils::normalizeRadian( - tf2::getYaw(prepare_segment_second_last_point.orientation) - - tf2::getYaw(lane_change_start_from_shifted.orientation))); - if (yaw_diff2 > autoware::universe_utils::deg2rad(5.0)) { - RCLCPP_DEBUG( - get_logger(), "Excessive yaw difference %.3f which exceeds the 5 degrees threshold.", - autoware::universe_utils::rad2deg(yaw_diff2)); - return std::nullopt; - } - } - - candidate_path.path = utils::combinePath(prepare_segment, shifted_path.path); - candidate_path.shifted_path = shifted_path; - - return std::optional{candidate_path}; -} - -PathWithLaneId get_reference_path_from_target_Lane( - const CommonDataPtr & common_data_ptr, const Pose & lane_changing_start_pose, - const double lane_changing_length, const double resample_interval) -{ - const auto & route_handler = *common_data_ptr->route_handler_ptr; - const auto & target_lanes = common_data_ptr->lanes_ptr->target; - const auto target_lane_length = common_data_ptr->transient_data.target_lane_length; - const auto is_goal_in_route = common_data_ptr->lanes_ptr->target_lane_in_goal_section; - const auto next_lc_buffer = common_data_ptr->transient_data.next_dist_buffer.min; - const auto forward_path_length = common_data_ptr->bpp_param_ptr->forward_path_length; - - const ArcCoordinates lane_change_start_arc_position = - lanelet::utils::getArcCoordinates(target_lanes, lane_changing_start_pose); - - const double s_start = lane_change_start_arc_position.length; - const double s_end = std::invoke([&]() { - const auto dist_from_lc_start = s_start + lane_changing_length + forward_path_length; - if (is_goal_in_route) { - const double s_goal = - lanelet::utils::getArcCoordinates(target_lanes, route_handler.getGoalPose()).length - - next_lc_buffer; - return std::min(dist_from_lc_start, s_goal); - } - return std::min(dist_from_lc_start, target_lane_length - next_lc_buffer); - }); - - constexpr double epsilon = 1e-4; - if (s_end - s_start + epsilon < lane_changing_length) { - return PathWithLaneId(); - } - - const auto lane_changing_reference_path = - route_handler.getCenterLinePath(target_lanes, s_start, s_end); - - return utils::resamplePathWithSpline( - lane_changing_reference_path, resample_interval, true, {0.0, lane_changing_length}); -} - -ShiftLine get_lane_changing_shift_line( - const Pose & lane_changing_start_pose, const Pose & lane_changing_end_pose, - const PathWithLaneId & reference_path, const double shift_length) -{ - ShiftLine shift_line; - shift_line.end_shift_length = shift_length; - shift_line.start = lane_changing_start_pose; - shift_line.end = lane_changing_end_pose; - shift_line.start_idx = autoware::motion_utils::findNearestIndex( - reference_path.points, lane_changing_start_pose.position); - shift_line.end_idx = autoware::motion_utils::findNearestIndex( - reference_path.points, lane_changing_end_pose.position); - - return shift_line; -} - std::vector generateDrivableLanes( const RouteHandler & route_handler, const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & lane_change_lanes) @@ -631,6 +448,7 @@ std::vector convert_to_predicted_path( const auto & lc_param_ptr = common_data_ptr->lc_param_ptr; const auto resolution = lc_param_ptr->safety.collision_check.prediction_time_resolution; std::vector predicted_path; + predicted_path.reserve(static_cast(std::ceil(duration / resolution))); // prepare segment for (double t = 0.0; t < prepare_time; t += resolution) { @@ -647,6 +465,7 @@ std::vector convert_to_predicted_path( initial_velocity + prepare_acc * prepare_time, 0.0, lane_change_path.info.velocity.prepare); const auto offset = initial_velocity * prepare_time + 0.5 * prepare_acc * prepare_time * prepare_time; + for (double t = prepare_time; t < duration; t += resolution) { const auto delta_t = t - prepare_time; const auto velocity = std::clamp( @@ -1294,4 +1113,39 @@ bool object_path_overlaps_lanes( return !boost::geometry::disjoint(path, lanes_polygon); }); } + +std::vector> convert_to_predicted_paths( + const CommonDataPtr & common_data_ptr, const LaneChangePath & lane_change_path, + const size_t deceleration_sampling_num) +{ + static constexpr double floating_err_th{1e-3}; + const auto bpp_param = *common_data_ptr->bpp_param_ptr; + const auto global_min_acc = bpp_param.min_acc; + const auto lane_changing_acc = lane_change_path.info.longitudinal_acceleration.lane_changing; + + const auto min_acc = std::min(lane_changing_acc, global_min_acc); + const auto sampling_num = + std::abs(min_acc - lane_changing_acc) > floating_err_th ? deceleration_sampling_num : 1; + const auto acc_resolution = (min_acc - lane_changing_acc) / static_cast(sampling_num); + + const auto ego_predicted_path = [&](size_t n) { + auto acc = lane_changing_acc + static_cast(n) * acc_resolution; + return utils::lane_change::convert_to_predicted_path(common_data_ptr, lane_change_path, acc); + }; + + return ranges::views::iota(0UL, sampling_num) | ranges::views::transform(ego_predicted_path) | + ranges::to(); +} + +bool is_valid_start_point(const lane_change::CommonDataPtr & common_data_ptr, const Pose & pose) +{ + const lanelet::BasicPoint2d lc_start_point(pose.position.x, pose.position.y); + + const auto & target_neighbor_poly = common_data_ptr->lanes_polygon_ptr->target_neighbor; + const auto & target_lane_poly = common_data_ptr->lanes_polygon_ptr->target; + + // Check the target lane because the previous approved path might be shifted by avoidance module + return boost::geometry::covered_by(lc_start_point, target_neighbor_poly) || + boost::geometry::covered_by(lc_start_point, target_lane_poly); +} } // namespace autoware::behavior_path_planner::utils::lane_change diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp index 96b24d5aa9a9e..114a38a77876c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp @@ -258,6 +258,7 @@ TEST_F(TestNormalLaneChange, testGetPathWhenValid) constexpr auto is_approved = true; ego_pose_ = autoware::test_utils::createPose(1.0, 1.75, 0.0, 0.0, 0.0, 0.0); planner_data_->self_odometry = set_odometry(ego_pose_); + normal_lane_change_->setData(planner_data_); set_previous_approved_path(); normal_lane_change_->update_lanes(!is_approved); normal_lane_change_->update_filtered_objects(); From 57f38b756e88e079702aa73925f0f73ae1163a30 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Tue, 24 Dec 2024 13:34:47 +0900 Subject: [PATCH 085/334] fix(autoware_pointcloud_preprocessor): remove unused function mask() (#9751) Signed-off-by: Ryuta Kambe --- .../src/downsample_filter/robin_hood.h | 6 ------ 1 file changed, 6 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/robin_hood.h b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/robin_hood.h index 55307a2aa5552..0748516665e40 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/robin_hood.h +++ b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/robin_hood.h @@ -2189,12 +2189,6 @@ class Table return 0 == mNumElements; } - ROBIN_HOOD(NODISCARD) size_t mask() const noexcept - { - ROBIN_HOOD_TRACE(this) - return mMask; - } - ROBIN_HOOD(NODISCARD) size_t calcMaxNumElementsAllowed(size_t maxElements) const noexcept { if (ROBIN_HOOD_LIKELY(maxElements <= (std::numeric_limits::max)() / 100)) { From f2a41290ee07bdcb8b970fc7eaa53e52c77c7edc Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> Date: Tue, 24 Dec 2024 15:48:48 +0900 Subject: [PATCH 086/334] refactor(autoware_behavior_path_start_planner_module): add data_structs.cpp and init method for StartPlannerParameters (#9736) feat(autoware_behavior_path_start_planner_module): add data_structs.cpp and init method for StartPlannerParameters Signed-off-by: Kyoichi Sugahara --- .../CMakeLists.txt | 1 + .../data_structs.hpp | 1 + .../src/data_structs.cpp | 340 ++++++++++++++++++ .../src/manager.cpp | 308 +--------------- 4 files changed, 346 insertions(+), 304 deletions(-) create mode 100644 planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/data_structs.cpp diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/CMakeLists.txt b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/CMakeLists.txt index 3fa8ad7218fa2..e28339fb51a6c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/CMakeLists.txt +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/CMakeLists.txt @@ -12,6 +12,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/freespace_pull_out.cpp src/geometric_pull_out.cpp src/shift_pull_out.cpp + src/data_structs.cpp src/util.cpp ) diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/data_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/data_structs.hpp index 9c439e9b3b921..5d8331318484d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/data_structs.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/data_structs.hpp @@ -97,6 +97,7 @@ struct StartPlannerDebugData struct StartPlannerParameters { + static StartPlannerParameters init(rclcpp::Node & node); double th_arrived_distance{0.0}; double th_stopped_velocity{0.0}; double th_stopped_time{0.0}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/data_structs.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/data_structs.cpp new file mode 100644 index 0000000000000..f613b9345ce42 --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/data_structs.cpp @@ -0,0 +1,340 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/behavior_path_start_planner_module/data_structs.hpp" + +#include "autoware/behavior_path_start_planner_module/manager.hpp" + +#include +#include + +#include + +namespace autoware::behavior_path_planner +{ + +StartPlannerParameters StartPlannerParameters::init(rclcpp::Node & node) +{ + using autoware::universe_utils::getOrDeclareParameter; + StartPlannerParameters p; + { + const std::string ns = "start_planner."; + + p.th_arrived_distance = getOrDeclareParameter(node, ns + "th_arrived_distance"); + p.th_stopped_velocity = getOrDeclareParameter(node, ns + "th_stopped_velocity"); + p.th_stopped_time = getOrDeclareParameter(node, ns + "th_stopped_time"); + p.prepare_time_before_start = + getOrDeclareParameter(node, ns + "prepare_time_before_start"); + p.th_distance_to_middle_of_the_road = + getOrDeclareParameter(node, ns + "th_distance_to_middle_of_the_road"); + p.skip_rear_vehicle_check = getOrDeclareParameter(node, ns + "skip_rear_vehicle_check"); + p.extra_width_margin_for_rear_obstacle = + getOrDeclareParameter(node, ns + "extra_width_margin_for_rear_obstacle"); + p.collision_check_margins = + getOrDeclareParameter>(node, ns + "collision_check_margins"); + p.collision_check_margin_from_front_object = + getOrDeclareParameter(node, ns + "collision_check_margin_from_front_object"); + p.th_moving_object_velocity = + getOrDeclareParameter(node, ns + "th_moving_object_velocity"); + p.center_line_path_interval = + getOrDeclareParameter(node, ns + "center_line_path_interval"); + // shift pull out + p.enable_shift_pull_out = getOrDeclareParameter(node, ns + "enable_shift_pull_out"); + p.check_shift_path_lane_departure = + getOrDeclareParameter(node, ns + "check_shift_path_lane_departure"); + p.allow_check_shift_path_lane_departure_override = + getOrDeclareParameter(node, ns + "allow_check_shift_path_lane_departure_override"); + p.shift_collision_check_distance_from_end = + getOrDeclareParameter(node, ns + "shift_collision_check_distance_from_end"); + p.minimum_shift_pull_out_distance = + getOrDeclareParameter(node, ns + "minimum_shift_pull_out_distance"); + p.lateral_acceleration_sampling_num = + getOrDeclareParameter(node, ns + "lateral_acceleration_sampling_num"); + p.lateral_jerk = getOrDeclareParameter(node, ns + "lateral_jerk"); + p.maximum_lateral_acc = getOrDeclareParameter(node, ns + "maximum_lateral_acc"); + p.minimum_lateral_acc = getOrDeclareParameter(node, ns + "minimum_lateral_acc"); + p.maximum_curvature = getOrDeclareParameter(node, ns + "maximum_curvature"); + p.end_pose_curvature_threshold = + getOrDeclareParameter(node, ns + "end_pose_curvature_threshold"); + p.maximum_longitudinal_deviation = + getOrDeclareParameter(node, ns + "maximum_longitudinal_deviation"); + // geometric pull out + p.enable_geometric_pull_out = + getOrDeclareParameter(node, ns + "enable_geometric_pull_out"); + p.geometric_collision_check_distance_from_end = + getOrDeclareParameter(node, ns + "geometric_collision_check_distance_from_end"); + p.divide_pull_out_path = getOrDeclareParameter(node, ns + "divide_pull_out_path"); + p.parallel_parking_parameters.pull_out_velocity = + getOrDeclareParameter(node, ns + "geometric_pull_out_velocity"); + p.parallel_parking_parameters.pull_out_arc_path_interval = + getOrDeclareParameter(node, ns + "arc_path_interval"); + p.parallel_parking_parameters.pull_out_lane_departure_margin = + getOrDeclareParameter(node, ns + "lane_departure_margin"); + p.lane_departure_check_expansion_margin = + getOrDeclareParameter(node, ns + "lane_departure_check_expansion_margin"); + p.parallel_parking_parameters.pull_out_max_steer_angle = + getOrDeclareParameter(node, ns + "pull_out_max_steer_angle"); // 15deg + p.parallel_parking_parameters.center_line_path_interval = + p.center_line_path_interval; // for geometric parallel parking + // search start pose backward + p.search_priority = getOrDeclareParameter( + node, + ns + "search_priority"); // "efficient_path" or "short_back_distance" + p.enable_back = getOrDeclareParameter(node, ns + "enable_back"); + p.backward_velocity = getOrDeclareParameter(node, ns + "backward_velocity"); + p.max_back_distance = getOrDeclareParameter(node, ns + "max_back_distance"); + p.backward_search_resolution = + getOrDeclareParameter(node, ns + "backward_search_resolution"); + p.backward_path_update_duration = + getOrDeclareParameter(node, ns + "backward_path_update_duration"); + p.ignore_distance_from_lane_end = + getOrDeclareParameter(node, ns + "ignore_distance_from_lane_end"); + // stop condition + p.maximum_deceleration_for_stop = + getOrDeclareParameter(node, ns + "stop_condition.maximum_deceleration_for_stop"); + p.maximum_jerk_for_stop = + getOrDeclareParameter(node, ns + "stop_condition.maximum_jerk_for_stop"); + } + { + const std::string ns = "start_planner.object_types_to_check_for_path_generation."; + p.object_types_to_check_for_path_generation.check_car = + getOrDeclareParameter(node, ns + "check_car"); + p.object_types_to_check_for_path_generation.check_truck = + getOrDeclareParameter(node, ns + "check_truck"); + p.object_types_to_check_for_path_generation.check_bus = + getOrDeclareParameter(node, ns + "check_bus"); + p.object_types_to_check_for_path_generation.check_trailer = + getOrDeclareParameter(node, ns + "check_trailer"); + p.object_types_to_check_for_path_generation.check_unknown = + getOrDeclareParameter(node, ns + "check_unknown"); + p.object_types_to_check_for_path_generation.check_bicycle = + getOrDeclareParameter(node, ns + "check_bicycle"); + p.object_types_to_check_for_path_generation.check_motorcycle = + getOrDeclareParameter(node, ns + "check_motorcycle"); + p.object_types_to_check_for_path_generation.check_pedestrian = + getOrDeclareParameter(node, ns + "check_pedestrian"); + } + // freespace planner general params + { + const std::string ns = "start_planner.freespace_planner."; + p.enable_freespace_planner = getOrDeclareParameter(node, ns + "enable_freespace_planner"); + p.freespace_planner_algorithm = + getOrDeclareParameter(node, ns + "freespace_planner_algorithm"); + p.end_pose_search_start_distance = + getOrDeclareParameter(node, ns + "end_pose_search_start_distance"); + p.end_pose_search_end_distance = + getOrDeclareParameter(node, ns + "end_pose_search_end_distance"); + p.end_pose_search_interval = + getOrDeclareParameter(node, ns + "end_pose_search_interval"); + p.freespace_planner_velocity = getOrDeclareParameter(node, ns + "velocity"); + p.vehicle_shape_margin = getOrDeclareParameter(node, ns + "vehicle_shape_margin"); + p.freespace_planner_common_parameters.time_limit = + getOrDeclareParameter(node, ns + "time_limit"); + p.freespace_planner_common_parameters.max_turning_ratio = + getOrDeclareParameter(node, ns + "max_turning_ratio"); + p.freespace_planner_common_parameters.turning_steps = + getOrDeclareParameter(node, ns + "turning_steps"); + } + // freespace planner search config + { + const std::string ns = "start_planner.freespace_planner.search_configs."; + p.freespace_planner_common_parameters.theta_size = + getOrDeclareParameter(node, ns + "theta_size"); + p.freespace_planner_common_parameters.angle_goal_range = + getOrDeclareParameter(node, ns + "angle_goal_range"); + p.freespace_planner_common_parameters.curve_weight = + getOrDeclareParameter(node, ns + "curve_weight"); + p.freespace_planner_common_parameters.reverse_weight = + getOrDeclareParameter(node, ns + "reverse_weight"); + p.freespace_planner_common_parameters.lateral_goal_range = + getOrDeclareParameter(node, ns + "lateral_goal_range"); + p.freespace_planner_common_parameters.longitudinal_goal_range = + getOrDeclareParameter(node, ns + "longitudinal_goal_range"); + } + // freespace planner costmap configs + { + const std::string ns = "start_planner.freespace_planner.costmap_configs."; + p.freespace_planner_common_parameters.obstacle_threshold = + getOrDeclareParameter(node, ns + "obstacle_threshold"); + } + // freespace planner astar + { + const std::string ns = "start_planner.freespace_planner.astar."; + p.astar_parameters.search_method = + getOrDeclareParameter(node, ns + "search_method"); + p.astar_parameters.only_behind_solutions = + getOrDeclareParameter(node, ns + "only_behind_solutions"); + p.astar_parameters.use_back = getOrDeclareParameter(node, ns + "use_back"); + p.astar_parameters.distance_heuristic_weight = + getOrDeclareParameter(node, ns + "distance_heuristic_weight"); + } + // freespace planner rrtstar + { + const std::string ns = "start_planner.freespace_planner.rrtstar."; + p.rrt_star_parameters.enable_update = getOrDeclareParameter(node, ns + "enable_update"); + p.rrt_star_parameters.use_informed_sampling = + getOrDeclareParameter(node, ns + "use_informed_sampling"); + p.rrt_star_parameters.max_planning_time = + getOrDeclareParameter(node, ns + "max_planning_time"); + p.rrt_star_parameters.neighbor_radius = + getOrDeclareParameter(node, ns + "neighbor_radius"); + p.rrt_star_parameters.margin = getOrDeclareParameter(node, ns + "margin"); + } + + const std::string base_ns = "start_planner.path_safety_check."; + // EgoPredictedPath + { + const std::string ego_path_ns = base_ns + "ego_predicted_path."; + p.ego_predicted_path_params.min_velocity = + getOrDeclareParameter(node, ego_path_ns + "min_velocity"); + p.ego_predicted_path_params.acceleration = + getOrDeclareParameter(node, ego_path_ns + "min_acceleration"); + p.ego_predicted_path_params.time_horizon_for_front_object = + getOrDeclareParameter(node, ego_path_ns + "time_horizon_for_front_object"); + p.ego_predicted_path_params.time_horizon_for_rear_object = + getOrDeclareParameter(node, ego_path_ns + "time_horizon_for_rear_object"); + p.ego_predicted_path_params.time_resolution = + getOrDeclareParameter(node, ego_path_ns + "time_resolution"); + p.ego_predicted_path_params.delay_until_departure = + getOrDeclareParameter(node, ego_path_ns + "delay_until_departure"); + } + // ObjectFilteringParams + const std::string obj_filter_ns = base_ns + "target_filtering."; + { + p.objects_filtering_params.safety_check_time_horizon = + getOrDeclareParameter(node, obj_filter_ns + "safety_check_time_horizon"); + p.objects_filtering_params.safety_check_time_resolution = + getOrDeclareParameter(node, obj_filter_ns + "safety_check_time_resolution"); + p.objects_filtering_params.object_check_forward_distance = + getOrDeclareParameter(node, obj_filter_ns + "object_check_forward_distance"); + p.objects_filtering_params.object_check_backward_distance = + getOrDeclareParameter(node, obj_filter_ns + "object_check_backward_distance"); + p.objects_filtering_params.ignore_object_velocity_threshold = + getOrDeclareParameter(node, obj_filter_ns + "ignore_object_velocity_threshold"); + p.objects_filtering_params.include_opposite_lane = + getOrDeclareParameter(node, obj_filter_ns + "include_opposite_lane"); + p.objects_filtering_params.invert_opposite_lane = + getOrDeclareParameter(node, obj_filter_ns + "invert_opposite_lane"); + p.objects_filtering_params.check_all_predicted_path = + getOrDeclareParameter(node, obj_filter_ns + "check_all_predicted_path"); + p.objects_filtering_params.use_all_predicted_path = + getOrDeclareParameter(node, obj_filter_ns + "use_all_predicted_path"); + p.objects_filtering_params.use_predicted_path_outside_lanelet = + getOrDeclareParameter(node, obj_filter_ns + "use_predicted_path_outside_lanelet"); + } + // ObjectTypesToCheck + { + const std::string obj_types_ns = obj_filter_ns + "object_types_to_check."; + p.objects_filtering_params.object_types_to_check.check_car = + getOrDeclareParameter(node, obj_types_ns + "check_car"); + p.objects_filtering_params.object_types_to_check.check_truck = + getOrDeclareParameter(node, obj_types_ns + "check_truck"); + p.objects_filtering_params.object_types_to_check.check_bus = + getOrDeclareParameter(node, obj_types_ns + "check_bus"); + p.objects_filtering_params.object_types_to_check.check_trailer = + getOrDeclareParameter(node, obj_types_ns + "check_trailer"); + p.objects_filtering_params.object_types_to_check.check_unknown = + getOrDeclareParameter(node, obj_types_ns + "check_unknown"); + p.objects_filtering_params.object_types_to_check.check_bicycle = + getOrDeclareParameter(node, obj_types_ns + "check_bicycle"); + p.objects_filtering_params.object_types_to_check.check_motorcycle = + getOrDeclareParameter(node, obj_types_ns + "check_motorcycle"); + p.objects_filtering_params.object_types_to_check.check_pedestrian = + getOrDeclareParameter(node, obj_types_ns + "check_pedestrian"); + } + // ObjectLaneConfiguration + { + const std::string obj_lane_ns = obj_filter_ns + "object_lane_configuration."; + p.objects_filtering_params.object_lane_configuration.check_current_lane = + getOrDeclareParameter(node, obj_lane_ns + "check_current_lane"); + p.objects_filtering_params.object_lane_configuration.check_right_lane = + getOrDeclareParameter(node, obj_lane_ns + "check_right_side_lane"); + p.objects_filtering_params.object_lane_configuration.check_left_lane = + getOrDeclareParameter(node, obj_lane_ns + "check_left_side_lane"); + p.objects_filtering_params.object_lane_configuration.check_shoulder_lane = + getOrDeclareParameter(node, obj_lane_ns + "check_shoulder_lane"); + p.objects_filtering_params.object_lane_configuration.check_other_lane = + getOrDeclareParameter(node, obj_lane_ns + "check_other_lane"); + } + // SafetyCheckParams + const std::string safety_check_ns = base_ns + "safety_check_params."; + { + p.safety_check_params.enable_safety_check = + getOrDeclareParameter(node, safety_check_ns + "enable_safety_check"); + p.safety_check_params.hysteresis_factor_expand_rate = + getOrDeclareParameter(node, safety_check_ns + "hysteresis_factor_expand_rate"); + p.safety_check_params.backward_path_length = + getOrDeclareParameter(node, safety_check_ns + "backward_path_length"); + p.safety_check_params.forward_path_length = + getOrDeclareParameter(node, safety_check_ns + "forward_path_length"); + p.safety_check_params.publish_debug_marker = + getOrDeclareParameter(node, safety_check_ns + "publish_debug_marker"); + p.safety_check_params.collision_check_yaw_diff_threshold = + getOrDeclareParameter(node, safety_check_ns + "collision_check_yaw_diff_threshold"); + } + // RSSparams + { + const std::string rss_ns = safety_check_ns + "rss_params."; + p.safety_check_params.rss_params.rear_vehicle_reaction_time = + getOrDeclareParameter(node, rss_ns + "rear_vehicle_reaction_time"); + p.safety_check_params.rss_params.rear_vehicle_safety_time_margin = + getOrDeclareParameter(node, rss_ns + "rear_vehicle_safety_time_margin"); + p.safety_check_params.rss_params.lateral_distance_max_threshold = + getOrDeclareParameter(node, rss_ns + "lateral_distance_max_threshold"); + p.safety_check_params.rss_params.longitudinal_distance_min_threshold = + getOrDeclareParameter(node, rss_ns + "longitudinal_distance_min_threshold"); + p.safety_check_params.rss_params.longitudinal_velocity_delta_time = + getOrDeclareParameter(node, rss_ns + "longitudinal_velocity_delta_time"); + p.safety_check_params.rss_params.extended_polygon_policy = + getOrDeclareParameter(node, rss_ns + "extended_polygon_policy"); + } + // surround moving obstacle check + { + const std::string surround_moving_obstacle_check_ns = + "start_planner.surround_moving_obstacle_check."; + p.search_radius = + getOrDeclareParameter(node, surround_moving_obstacle_check_ns + "search_radius"); + p.th_moving_obstacle_velocity = getOrDeclareParameter( + node, surround_moving_obstacle_check_ns + "th_moving_obstacle_velocity"); + // ObjectTypesToCheck + { + const std::string obj_types_ns = surround_moving_obstacle_check_ns + "object_types_to_check."; + p.surround_moving_obstacles_type_to_check.check_car = + getOrDeclareParameter(node, obj_types_ns + "check_car"); + p.surround_moving_obstacles_type_to_check.check_truck = + getOrDeclareParameter(node, obj_types_ns + "check_truck"); + p.surround_moving_obstacles_type_to_check.check_bus = + getOrDeclareParameter(node, obj_types_ns + "check_bus"); + p.surround_moving_obstacles_type_to_check.check_trailer = + getOrDeclareParameter(node, obj_types_ns + "check_trailer"); + p.surround_moving_obstacles_type_to_check.check_unknown = + getOrDeclareParameter(node, obj_types_ns + "check_unknown"); + p.surround_moving_obstacles_type_to_check.check_bicycle = + getOrDeclareParameter(node, obj_types_ns + "check_bicycle"); + p.surround_moving_obstacles_type_to_check.check_motorcycle = + getOrDeclareParameter(node, obj_types_ns + "check_motorcycle"); + p.surround_moving_obstacles_type_to_check.check_pedestrian = + getOrDeclareParameter(node, obj_types_ns + "check_pedestrian"); + } + } + + // debug + { + const std::string debug_ns = "start_planner.debug."; + p.print_debug_info = getOrDeclareParameter(node, debug_ns + "print_debug_info"); + } + + return p; +} +} // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/manager.cpp index f5739ce322248..9ea51d56ee1cc 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/manager.cpp @@ -29,318 +29,18 @@ void StartPlannerModuleManager::init(rclcpp::Node * node) // init manager interface initInterface(node, {""}); - StartPlannerParameters p; - - { - const std::string ns = "start_planner."; - - p.th_arrived_distance = node->declare_parameter(ns + "th_arrived_distance"); - p.th_stopped_velocity = node->declare_parameter(ns + "th_stopped_velocity"); - p.th_stopped_time = node->declare_parameter(ns + "th_stopped_time"); - p.prepare_time_before_start = node->declare_parameter(ns + "prepare_time_before_start"); - p.th_distance_to_middle_of_the_road = - node->declare_parameter(ns + "th_distance_to_middle_of_the_road"); - p.skip_rear_vehicle_check = node->declare_parameter(ns + "skip_rear_vehicle_check"); - p.extra_width_margin_for_rear_obstacle = - node->declare_parameter(ns + "extra_width_margin_for_rear_obstacle"); - p.collision_check_margins = - node->declare_parameter>(ns + "collision_check_margins"); - p.collision_check_margin_from_front_object = - node->declare_parameter(ns + "collision_check_margin_from_front_object"); - p.th_moving_object_velocity = node->declare_parameter(ns + "th_moving_object_velocity"); - p.center_line_path_interval = node->declare_parameter(ns + "center_line_path_interval"); - // shift pull out - p.enable_shift_pull_out = node->declare_parameter(ns + "enable_shift_pull_out"); - p.check_shift_path_lane_departure = - node->declare_parameter(ns + "check_shift_path_lane_departure"); - p.allow_check_shift_path_lane_departure_override = - node->declare_parameter(ns + "allow_check_shift_path_lane_departure_override"); - p.shift_collision_check_distance_from_end = - node->declare_parameter(ns + "shift_collision_check_distance_from_end"); - p.minimum_shift_pull_out_distance = - node->declare_parameter(ns + "minimum_shift_pull_out_distance"); - p.lateral_acceleration_sampling_num = - node->declare_parameter(ns + "lateral_acceleration_sampling_num"); - p.lateral_jerk = node->declare_parameter(ns + "lateral_jerk"); - p.maximum_lateral_acc = node->declare_parameter(ns + "maximum_lateral_acc"); - p.minimum_lateral_acc = node->declare_parameter(ns + "minimum_lateral_acc"); - p.maximum_curvature = node->declare_parameter(ns + "maximum_curvature"); - p.end_pose_curvature_threshold = - node->declare_parameter(ns + "end_pose_curvature_threshold"); - p.maximum_longitudinal_deviation = - node->declare_parameter(ns + "maximum_longitudinal_deviation"); - // geometric pull out - p.enable_geometric_pull_out = node->declare_parameter(ns + "enable_geometric_pull_out"); - p.geometric_collision_check_distance_from_end = - node->declare_parameter(ns + "geometric_collision_check_distance_from_end"); - p.divide_pull_out_path = node->declare_parameter(ns + "divide_pull_out_path"); - p.parallel_parking_parameters.pull_out_velocity = - node->declare_parameter(ns + "geometric_pull_out_velocity"); - p.parallel_parking_parameters.pull_out_arc_path_interval = - node->declare_parameter(ns + "arc_path_interval"); - p.parallel_parking_parameters.pull_out_lane_departure_margin = - node->declare_parameter(ns + "lane_departure_margin"); - p.lane_departure_check_expansion_margin = - node->declare_parameter(ns + "lane_departure_check_expansion_margin"); - p.parallel_parking_parameters.pull_out_max_steer_angle = - node->declare_parameter(ns + "pull_out_max_steer_angle"); // 15deg - p.parallel_parking_parameters.center_line_path_interval = - p.center_line_path_interval; // for geometric parallel parking - // search start pose backward - p.search_priority = node->declare_parameter( - ns + "search_priority"); // "efficient_path" or "short_back_distance" - p.enable_back = node->declare_parameter(ns + "enable_back"); - p.backward_velocity = node->declare_parameter(ns + "backward_velocity"); - p.max_back_distance = node->declare_parameter(ns + "max_back_distance"); - p.backward_search_resolution = - node->declare_parameter(ns + "backward_search_resolution"); - p.backward_path_update_duration = - node->declare_parameter(ns + "backward_path_update_duration"); - p.ignore_distance_from_lane_end = - node->declare_parameter(ns + "ignore_distance_from_lane_end"); - // stop condition - p.maximum_deceleration_for_stop = - node->declare_parameter(ns + "stop_condition.maximum_deceleration_for_stop"); - p.maximum_jerk_for_stop = - node->declare_parameter(ns + "stop_condition.maximum_jerk_for_stop"); - } - { - const std::string ns = "start_planner.object_types_to_check_for_path_generation."; - p.object_types_to_check_for_path_generation.check_car = - node->declare_parameter(ns + "check_car"); - p.object_types_to_check_for_path_generation.check_truck = - node->declare_parameter(ns + "check_truck"); - p.object_types_to_check_for_path_generation.check_bus = - node->declare_parameter(ns + "check_bus"); - p.object_types_to_check_for_path_generation.check_trailer = - node->declare_parameter(ns + "check_trailer"); - p.object_types_to_check_for_path_generation.check_unknown = - node->declare_parameter(ns + "check_unknown"); - p.object_types_to_check_for_path_generation.check_bicycle = - node->declare_parameter(ns + "check_bicycle"); - p.object_types_to_check_for_path_generation.check_motorcycle = - node->declare_parameter(ns + "check_motorcycle"); - p.object_types_to_check_for_path_generation.check_pedestrian = - node->declare_parameter(ns + "check_pedestrian"); - } - // freespace planner general params - { - const std::string ns = "start_planner.freespace_planner."; - p.enable_freespace_planner = node->declare_parameter(ns + "enable_freespace_planner"); - p.freespace_planner_algorithm = - node->declare_parameter(ns + "freespace_planner_algorithm"); - p.end_pose_search_start_distance = - node->declare_parameter(ns + "end_pose_search_start_distance"); - p.end_pose_search_end_distance = - node->declare_parameter(ns + "end_pose_search_end_distance"); - p.end_pose_search_interval = node->declare_parameter(ns + "end_pose_search_interval"); - p.freespace_planner_velocity = node->declare_parameter(ns + "velocity"); - p.vehicle_shape_margin = node->declare_parameter(ns + "vehicle_shape_margin"); - p.freespace_planner_common_parameters.time_limit = - node->declare_parameter(ns + "time_limit"); - p.freespace_planner_common_parameters.max_turning_ratio = - node->declare_parameter(ns + "max_turning_ratio"); - p.freespace_planner_common_parameters.turning_steps = - node->declare_parameter(ns + "turning_steps"); - } - // freespace planner search config - { - const std::string ns = "start_planner.freespace_planner.search_configs."; - p.freespace_planner_common_parameters.theta_size = - node->declare_parameter(ns + "theta_size"); - p.freespace_planner_common_parameters.angle_goal_range = - node->declare_parameter(ns + "angle_goal_range"); - p.freespace_planner_common_parameters.curve_weight = - node->declare_parameter(ns + "curve_weight"); - p.freespace_planner_common_parameters.reverse_weight = - node->declare_parameter(ns + "reverse_weight"); - p.freespace_planner_common_parameters.lateral_goal_range = - node->declare_parameter(ns + "lateral_goal_range"); - p.freespace_planner_common_parameters.longitudinal_goal_range = - node->declare_parameter(ns + "longitudinal_goal_range"); - } - // freespace planner costmap configs - { - const std::string ns = "start_planner.freespace_planner.costmap_configs."; - p.freespace_planner_common_parameters.obstacle_threshold = - node->declare_parameter(ns + "obstacle_threshold"); - } - // freespace planner astar - { - const std::string ns = "start_planner.freespace_planner.astar."; - p.astar_parameters.search_method = node->declare_parameter(ns + "search_method"); - p.astar_parameters.only_behind_solutions = - node->declare_parameter(ns + "only_behind_solutions"); - p.astar_parameters.use_back = node->declare_parameter(ns + "use_back"); - p.astar_parameters.distance_heuristic_weight = - node->declare_parameter(ns + "distance_heuristic_weight"); - } - // freespace planner rrtstar - { - const std::string ns = "start_planner.freespace_planner.rrtstar."; - p.rrt_star_parameters.enable_update = node->declare_parameter(ns + "enable_update"); - p.rrt_star_parameters.use_informed_sampling = - node->declare_parameter(ns + "use_informed_sampling"); - p.rrt_star_parameters.max_planning_time = - node->declare_parameter(ns + "max_planning_time"); - p.rrt_star_parameters.neighbor_radius = node->declare_parameter(ns + "neighbor_radius"); - p.rrt_star_parameters.margin = node->declare_parameter(ns + "margin"); - } - - const std::string base_ns = "start_planner.path_safety_check."; - // EgoPredictedPath - { - const std::string ego_path_ns = base_ns + "ego_predicted_path."; - p.ego_predicted_path_params.min_velocity = - node->declare_parameter(ego_path_ns + "min_velocity"); - p.ego_predicted_path_params.acceleration = - node->declare_parameter(ego_path_ns + "min_acceleration"); - p.ego_predicted_path_params.time_horizon_for_front_object = - node->declare_parameter(ego_path_ns + "time_horizon_for_front_object"); - p.ego_predicted_path_params.time_horizon_for_rear_object = - node->declare_parameter(ego_path_ns + "time_horizon_for_rear_object"); - p.ego_predicted_path_params.time_resolution = - node->declare_parameter(ego_path_ns + "time_resolution"); - p.ego_predicted_path_params.delay_until_departure = - node->declare_parameter(ego_path_ns + "delay_until_departure"); - } - // ObjectFilteringParams - const std::string obj_filter_ns = base_ns + "target_filtering."; - { - p.objects_filtering_params.safety_check_time_horizon = - node->declare_parameter(obj_filter_ns + "safety_check_time_horizon"); - p.objects_filtering_params.safety_check_time_resolution = - node->declare_parameter(obj_filter_ns + "safety_check_time_resolution"); - p.objects_filtering_params.object_check_forward_distance = - node->declare_parameter(obj_filter_ns + "object_check_forward_distance"); - p.objects_filtering_params.object_check_backward_distance = - node->declare_parameter(obj_filter_ns + "object_check_backward_distance"); - p.objects_filtering_params.ignore_object_velocity_threshold = - node->declare_parameter(obj_filter_ns + "ignore_object_velocity_threshold"); - p.objects_filtering_params.include_opposite_lane = - node->declare_parameter(obj_filter_ns + "include_opposite_lane"); - p.objects_filtering_params.invert_opposite_lane = - node->declare_parameter(obj_filter_ns + "invert_opposite_lane"); - p.objects_filtering_params.check_all_predicted_path = - node->declare_parameter(obj_filter_ns + "check_all_predicted_path"); - p.objects_filtering_params.use_all_predicted_path = - node->declare_parameter(obj_filter_ns + "use_all_predicted_path"); - p.objects_filtering_params.use_predicted_path_outside_lanelet = - node->declare_parameter(obj_filter_ns + "use_predicted_path_outside_lanelet"); - } - // ObjectTypesToCheck - { - const std::string obj_types_ns = obj_filter_ns + "object_types_to_check."; - p.objects_filtering_params.object_types_to_check.check_car = - node->declare_parameter(obj_types_ns + "check_car"); - p.objects_filtering_params.object_types_to_check.check_truck = - node->declare_parameter(obj_types_ns + "check_truck"); - p.objects_filtering_params.object_types_to_check.check_bus = - node->declare_parameter(obj_types_ns + "check_bus"); - p.objects_filtering_params.object_types_to_check.check_trailer = - node->declare_parameter(obj_types_ns + "check_trailer"); - p.objects_filtering_params.object_types_to_check.check_unknown = - node->declare_parameter(obj_types_ns + "check_unknown"); - p.objects_filtering_params.object_types_to_check.check_bicycle = - node->declare_parameter(obj_types_ns + "check_bicycle"); - p.objects_filtering_params.object_types_to_check.check_motorcycle = - node->declare_parameter(obj_types_ns + "check_motorcycle"); - p.objects_filtering_params.object_types_to_check.check_pedestrian = - node->declare_parameter(obj_types_ns + "check_pedestrian"); - } - // ObjectLaneConfiguration - { - const std::string obj_lane_ns = obj_filter_ns + "object_lane_configuration."; - p.objects_filtering_params.object_lane_configuration.check_current_lane = - node->declare_parameter(obj_lane_ns + "check_current_lane"); - p.objects_filtering_params.object_lane_configuration.check_right_lane = - node->declare_parameter(obj_lane_ns + "check_right_side_lane"); - p.objects_filtering_params.object_lane_configuration.check_left_lane = - node->declare_parameter(obj_lane_ns + "check_left_side_lane"); - p.objects_filtering_params.object_lane_configuration.check_shoulder_lane = - node->declare_parameter(obj_lane_ns + "check_shoulder_lane"); - p.objects_filtering_params.object_lane_configuration.check_other_lane = - node->declare_parameter(obj_lane_ns + "check_other_lane"); - } - // SafetyCheckParams - const std::string safety_check_ns = base_ns + "safety_check_params."; - { - p.safety_check_params.enable_safety_check = - node->declare_parameter(safety_check_ns + "enable_safety_check"); - p.safety_check_params.hysteresis_factor_expand_rate = - node->declare_parameter(safety_check_ns + "hysteresis_factor_expand_rate"); - p.safety_check_params.backward_path_length = - node->declare_parameter(safety_check_ns + "backward_path_length"); - p.safety_check_params.forward_path_length = - node->declare_parameter(safety_check_ns + "forward_path_length"); - p.safety_check_params.publish_debug_marker = - node->declare_parameter(safety_check_ns + "publish_debug_marker"); - p.safety_check_params.collision_check_yaw_diff_threshold = - node->declare_parameter(safety_check_ns + "collision_check_yaw_diff_threshold"); - } - // RSSparams - { - const std::string rss_ns = safety_check_ns + "rss_params."; - p.safety_check_params.rss_params.rear_vehicle_reaction_time = - node->declare_parameter(rss_ns + "rear_vehicle_reaction_time"); - p.safety_check_params.rss_params.rear_vehicle_safety_time_margin = - node->declare_parameter(rss_ns + "rear_vehicle_safety_time_margin"); - p.safety_check_params.rss_params.lateral_distance_max_threshold = - node->declare_parameter(rss_ns + "lateral_distance_max_threshold"); - p.safety_check_params.rss_params.longitudinal_distance_min_threshold = - node->declare_parameter(rss_ns + "longitudinal_distance_min_threshold"); - p.safety_check_params.rss_params.longitudinal_velocity_delta_time = - node->declare_parameter(rss_ns + "longitudinal_velocity_delta_time"); - p.safety_check_params.rss_params.extended_polygon_policy = - node->declare_parameter(rss_ns + "extended_polygon_policy"); - } - // surround moving obstacle check - { - const std::string surround_moving_obstacle_check_ns = - "start_planner.surround_moving_obstacle_check."; - p.search_radius = - node->declare_parameter(surround_moving_obstacle_check_ns + "search_radius"); - p.th_moving_obstacle_velocity = node->declare_parameter( - surround_moving_obstacle_check_ns + "th_moving_obstacle_velocity"); - // ObjectTypesToCheck - { - const std::string obj_types_ns = surround_moving_obstacle_check_ns + "object_types_to_check."; - p.surround_moving_obstacles_type_to_check.check_car = - node->declare_parameter(obj_types_ns + "check_car"); - p.surround_moving_obstacles_type_to_check.check_truck = - node->declare_parameter(obj_types_ns + "check_truck"); - p.surround_moving_obstacles_type_to_check.check_bus = - node->declare_parameter(obj_types_ns + "check_bus"); - p.surround_moving_obstacles_type_to_check.check_trailer = - node->declare_parameter(obj_types_ns + "check_trailer"); - p.surround_moving_obstacles_type_to_check.check_unknown = - node->declare_parameter(obj_types_ns + "check_unknown"); - p.surround_moving_obstacles_type_to_check.check_bicycle = - node->declare_parameter(obj_types_ns + "check_bicycle"); - p.surround_moving_obstacles_type_to_check.check_motorcycle = - node->declare_parameter(obj_types_ns + "check_motorcycle"); - p.surround_moving_obstacles_type_to_check.check_pedestrian = - node->declare_parameter(obj_types_ns + "check_pedestrian"); - } - } - - // debug - { - const std::string debug_ns = "start_planner.debug."; - p.print_debug_info = node->declare_parameter(debug_ns + "print_debug_info"); - } - + StartPlannerParameters parameters = StartPlannerParameters::init(*node); // validation of parameters - if (p.lateral_acceleration_sampling_num < 1) { + if (parameters.lateral_acceleration_sampling_num < 1) { RCLCPP_FATAL_STREAM( node->get_logger().get_child(name()), "lateral_acceleration_sampling_num must be positive integer. Given parameter: " - << p.lateral_acceleration_sampling_num << std::endl + << parameters.lateral_acceleration_sampling_num << std::endl << "Terminating the program..."); exit(EXIT_FAILURE); } - parameters_ = std::make_shared(p); + parameters_ = std::make_shared(parameters); } void StartPlannerModuleManager::updateModuleParams( From a5aeb82f54a945ae249f8305b0d23f1b790f1a54 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Tue, 24 Dec 2024 16:12:19 +0900 Subject: [PATCH 087/334] fix(diagnostic_graph_aggregator): remove unused message alias (#8722) feat(diagnostic_graph_aggregator): remove unused message alias --- system/diagnostic_graph_aggregator/test/src/test2.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/system/diagnostic_graph_aggregator/test/src/test2.cpp b/system/diagnostic_graph_aggregator/test/src/test2.cpp index 4a0199a89f37e..169e3017f8cd4 100644 --- a/system/diagnostic_graph_aggregator/test/src/test2.cpp +++ b/system/diagnostic_graph_aggregator/test/src/test2.cpp @@ -29,7 +29,6 @@ using namespace diagnostic_graph_aggregator; // NOLINT(build/namespaces) using diagnostic_msgs::msg::DiagnosticArray; using diagnostic_msgs::msg::DiagnosticStatus; -using tier4_system_msgs::msg::DiagnosticGraph; constexpr auto OK = DiagnosticStatus::OK; constexpr auto WARN = DiagnosticStatus::WARN; From 3dc9605d9354260ae540d161094044c56f6c98f0 Mon Sep 17 00:00:00 2001 From: Masato Saeki <78376491+MasatoSaeki@users.noreply.github.com> Date: Tue, 24 Dec 2024 16:45:47 +0900 Subject: [PATCH 088/334] feat(autoware_traffic_light_arbiter): add current time validation (#9747) * add current time validation Signed-off-by: MasatoSaeki * style(pre-commit): autofix * change ros parameter name Signed-off-by: MasatoSaeki * style(pre-commit): autofix * add validation with absolute function Signed-off-by: MasatoSaeki * add timestamp of topic in test Signed-off-by: MasatoSaeki * fix ci error Signed-off-by: MasatoSaeki --------- Signed-off-by: MasatoSaeki Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../autoware_traffic_light_arbiter/README.md | 5 +++-- .../config/traffic_light_arbiter.param.yaml | 1 + .../traffic_light_arbiter.hpp | 1 + .../src/traffic_light_arbiter.cpp | 19 +++++++++++++++++-- .../test/test_node.cpp | 10 ++++++++++ 5 files changed, 32 insertions(+), 4 deletions(-) diff --git a/perception/autoware_traffic_light_arbiter/README.md b/perception/autoware_traffic_light_arbiter/README.md index 619154e1e183b..f27afab62818e 100644 --- a/perception/autoware_traffic_light_arbiter/README.md +++ b/perception/autoware_traffic_light_arbiter/README.md @@ -43,7 +43,8 @@ The table below outlines how the matching process determines the output based on | Name | Type | Default Value | Description | | --------------------------- | ------ | ------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | -| `external_time_tolerance` | double | 5.0 | The duration in seconds an external message is considered valid for merging | -| `perception_time_tolerance` | double | 1.0 | The duration in seconds a perception message is considered valid for merging | +| `external_delay_tolerance` | double | 5.0 | The duration in seconds an external message is considered valid for merging in comparison with current time | +| `external_time_tolerance` | double | 5.0 | The duration in seconds an external message is considered valid for merging in comparison with a timestamp of perception message | +| `perception_time_tolerance` | double | 1.0 | The duration in seconds a perception message is considered valid for merging in comparison with a timestamp of external message | | `external_priority` | bool | false | Whether or not externals signals take precedence over perception-based ones. If false, the merging uses confidence as a criteria | | `enable_signal_matching` | bool | false | Decide whether to validate the match between perception signals and external signals. If set to true, verify that the colors match and only publish them if they are identical | diff --git a/perception/autoware_traffic_light_arbiter/config/traffic_light_arbiter.param.yaml b/perception/autoware_traffic_light_arbiter/config/traffic_light_arbiter.param.yaml index dfe12ff352f16..36e1b8593bebc 100644 --- a/perception/autoware_traffic_light_arbiter/config/traffic_light_arbiter.param.yaml +++ b/perception/autoware_traffic_light_arbiter/config/traffic_light_arbiter.param.yaml @@ -1,5 +1,6 @@ /**: ros__parameters: + external_delay_tolerance: 5.0 external_time_tolerance: 5.0 perception_time_tolerance: 1.0 external_priority: false diff --git a/perception/autoware_traffic_light_arbiter/include/autoware/traffic_light_arbiter/traffic_light_arbiter.hpp b/perception/autoware_traffic_light_arbiter/include/autoware/traffic_light_arbiter/traffic_light_arbiter.hpp index ccd928d52b367..916bd04a6bdd0 100644 --- a/perception/autoware_traffic_light_arbiter/include/autoware/traffic_light_arbiter/traffic_light_arbiter.hpp +++ b/perception/autoware_traffic_light_arbiter/include/autoware/traffic_light_arbiter/traffic_light_arbiter.hpp @@ -51,6 +51,7 @@ class TrafficLightArbiter : public rclcpp::Node std::unique_ptr> map_regulatory_elements_set_; + double external_delay_tolerance_; double external_time_tolerance_; double perception_time_tolerance_; bool external_priority_; diff --git a/perception/autoware_traffic_light_arbiter/src/traffic_light_arbiter.cpp b/perception/autoware_traffic_light_arbiter/src/traffic_light_arbiter.cpp index e71629fa5dd28..8ce002780813f 100644 --- a/perception/autoware_traffic_light_arbiter/src/traffic_light_arbiter.cpp +++ b/perception/autoware_traffic_light_arbiter/src/traffic_light_arbiter.cpp @@ -20,6 +20,7 @@ #include #include +#include #include #include #include @@ -70,6 +71,7 @@ namespace autoware TrafficLightArbiter::TrafficLightArbiter(const rclcpp::NodeOptions & options) : Node("traffic_light_arbiter", options) { + external_delay_tolerance_ = this->declare_parameter("external_delay_tolerance", 5.0); external_time_tolerance_ = this->declare_parameter("external_time_tolerance", 5.0); perception_time_tolerance_ = this->declare_parameter("perception_time_tolerance", 1.0); external_priority_ = this->declare_parameter("external_priority", false); @@ -119,7 +121,7 @@ void TrafficLightArbiter::onPerceptionMsg(const TrafficSignalArray::ConstSharedP latest_perception_msg_ = *msg; if ( - (rclcpp::Time(msg->stamp) - rclcpp::Time(latest_external_msg_.stamp)).seconds() > + std::abs((rclcpp::Time(msg->stamp) - rclcpp::Time(latest_external_msg_.stamp)).seconds()) > external_time_tolerance_) { latest_external_msg_.traffic_light_groups.clear(); } @@ -129,10 +131,16 @@ void TrafficLightArbiter::onPerceptionMsg(const TrafficSignalArray::ConstSharedP void TrafficLightArbiter::onExternalMsg(const TrafficSignalArray::ConstSharedPtr msg) { + if (std::abs((this->now() - rclcpp::Time(msg->stamp)).seconds()) > external_delay_tolerance_) { + RCLCPP_WARN_THROTTLE( + get_logger(), *get_clock(), 5000, "Received outdated V2X traffic signal messages"); + return; + } + latest_external_msg_ = *msg; if ( - (rclcpp::Time(msg->stamp) - rclcpp::Time(latest_perception_msg_.stamp)).seconds() > + std::abs((rclcpp::Time(msg->stamp) - rclcpp::Time(latest_perception_msg_.stamp)).seconds()) > perception_time_tolerance_) { latest_perception_msg_.traffic_light_groups.clear(); } @@ -229,6 +237,13 @@ void TrafficLightArbiter::arbitrateAndPublish(const builtin_interfaces::msg::Tim } pub_->publish(output_signals_msg); + + const auto latest_time = + std::max(rclcpp::Time(latest_perception_msg_.stamp), rclcpp::Time(latest_external_msg_.stamp)); + if (rclcpp::Time(output_signals_msg.stamp) < latest_time) { + RCLCPP_WARN_THROTTLE( + get_logger(), *get_clock(), 5000, "Published traffic signal messages are not latest"); + } } } // namespace autoware diff --git a/perception/autoware_traffic_light_arbiter/test/test_node.cpp b/perception/autoware_traffic_light_arbiter/test/test_node.cpp index f993ad7cec84d..44b3ca7925fd0 100644 --- a/perception/autoware_traffic_light_arbiter/test/test_node.cpp +++ b/perception/autoware_traffic_light_arbiter/test/test_node.cpp @@ -196,6 +196,9 @@ TEST(TrafficLightArbiterTest, testTrafficSignalOnlyPerceptionMsg) }; test_manager->set_subscriber(output_topic, callback); + // stamp preparation + perception_msg.stamp = test_target_node->now(); + test_manager->test_pub_msg( test_target_node, input_map_topic, vector_map_msg, rclcpp::QoS(1).transient_local()); test_manager->test_pub_msg( @@ -229,6 +232,9 @@ TEST(TrafficLightArbiterTest, testTrafficSignalOnlyExternalMsg) }; test_manager->set_subscriber(output_topic, callback); + // stamp preparation + external_msg.stamp = test_target_node->now(); + test_manager->test_pub_msg( test_target_node, input_map_topic, vector_map_msg, rclcpp::QoS(1).transient_local()); test_manager->test_pub_msg( @@ -268,6 +274,10 @@ TEST(TrafficLightArbiterTest, testTrafficSignalBothMsg) }; test_manager->set_subscriber(output_topic, callback); + // stamp preparation + external_msg.stamp = test_target_node->now(); + perception_msg.stamp = test_target_node->now(); + test_manager->test_pub_msg( test_target_node, input_map_topic, vector_map_msg, rclcpp::QoS(1).transient_local()); test_manager->test_pub_msg( From e60245b2b47d69e795e399a04e1f447a2cdc7042 Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Tue, 24 Dec 2024 17:06:03 +0900 Subject: [PATCH 089/334] fix(autoware_pointcloud_preprocessor): fix image display in distortion corrector (#9761) fix: fix image display Signed-off-by: vividf --- .../docs/distortion-corrector.md | 13 +++---------- 1 file changed, 3 insertions(+), 10 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/docs/distortion-corrector.md b/sensing/autoware_pointcloud_preprocessor/docs/distortion-corrector.md index 75cdccc4453ba..032798e9db125 100644 --- a/sensing/autoware_pointcloud_preprocessor/docs/distortion-corrector.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/distortion-corrector.md @@ -55,16 +55,9 @@ ros2 launch autoware_pointcloud_preprocessor distortion_corrector.launch.xml - `hesai`: (x: 90 degrees, y: 0 degrees) - `others`: (x: 0 degrees, y: 90 degrees) and (x: 270 degrees, y: 0 degrees) - - - - - - - - - -
velodyne azimuth coordinatehesai azimuth coordinate

Velodyne azimuth coordinate

Hesai azimuth coordinate

+| ![Velodyne Azimuth Coordinate](./image/velodyne.drawio.png) | ![Hesai Azimuth Coordinate](./image/hesai.drawio.png) | +| :---------------------------------------------------------: | :---------------------------------------------------: | +| **Velodyne azimuth coordinate** | **Hesai azimuth coordinate** | ## References/External links From f3a258ca04dc0dde9fbb629d05c8c3e12c38e24b Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 24 Dec 2024 17:07:43 +0900 Subject: [PATCH 090/334] fix(lane_change): add metrics to valid paths visualization (#9737) * fix(lane_change): add metrics to valid paths visualization Signed-off-by: Zulfaqar Azmi * fix cpp-check error Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Zulfaqar Azmi --- .../utils/markers.hpp | 2 +- .../src/utils/markers.cpp | 60 +++++++++++++++---- 2 files changed, 51 insertions(+), 11 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/markers.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/markers.hpp index 4c2712f053b13..059db8e38300f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/markers.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/markers.hpp @@ -35,7 +35,7 @@ using autoware::behavior_path_planner::lane_change::Debug; using autoware::behavior_path_planner::utils::path_safety_checker::ExtendedPredictedObjects; using visualization_msgs::msg::MarkerArray; MarkerArray showAllValidLaneChangePath( - const std::vector & lanes, std::string && ns); + const std::vector & lane_change_paths, std::string && ns); MarkerArray createLaneChangingVirtualWallMarker( const geometry_msgs::msg::Pose & lane_changing_pose, const std::string & module_name, const rclcpp::Time & now, const std::string & ns); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp index c7514fea01535..3277b8f031486 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp @@ -38,34 +38,74 @@ using autoware::universe_utils::createDefaultMarker; using autoware::universe_utils::createMarkerScale; using geometry_msgs::msg::Point; -MarkerArray showAllValidLaneChangePath(const std::vector & lanes, std::string && ns) +MarkerArray showAllValidLaneChangePath( + const std::vector & lane_change_paths, std::string && ns) { - if (lanes.empty()) { + if (lane_change_paths.empty()) { return MarkerArray{}; } MarkerArray marker_array; - int32_t id{0}; const auto current_time{rclcpp::Clock{RCL_ROS_TIME}.now()}; const auto colors = colors::colors_list(); - const auto loop_size = std::min(lanes.size(), colors.size()); + const auto loop_size = std::min(lane_change_paths.size(), colors.size()); marker_array.markers.reserve(loop_size); + const auto info_prep_to_string = + [](const autoware::behavior_path_planner::lane_change::Info & info) -> std::string { + std::ostringstream ss_text; + ss_text << std::setprecision(3) << "vel: " << info.velocity.prepare + << "[m/s] | lon_acc: " << info.longitudinal_acceleration.prepare + << "[m/s2] | t: " << info.duration.prepare << "[s] | L: " << info.length.prepare + << "[m]"; + return ss_text.str(); + }; + + const auto info_lc_to_string = + [](const autoware::behavior_path_planner::lane_change::Info & info) -> std::string { + std::ostringstream ss_text; + ss_text << std::setprecision(3) << "vel: " << info.velocity.lane_changing + << "[m/s] | lon_acc: " << info.longitudinal_acceleration.lane_changing + << "[m/s2] | lat_acc: " << info.lateral_acceleration + << "[m/s2] | t: " << info.duration.lane_changing + << "[s] | L: " << info.length.lane_changing << "[m]"; + return ss_text.str(); + }; + for (std::size_t idx = 0; idx < loop_size; ++idx) { - if (lanes.at(idx).path.points.empty()) { + int32_t id{0}; + const auto & lc_path = lane_change_paths.at(idx); + if (lc_path.path.points.empty()) { continue; } - + std::string ns_with_idx = ns + "[" + std::to_string(idx) + "]"; const auto & color = colors.at(idx); - Marker marker = createDefaultMarker( - "map", current_time, ns, ++id, Marker::LINE_STRIP, createMarkerScale(0.1, 0.1, 0.0), color); - marker.points.reserve(lanes.at(idx).path.points.size()); + const auto & points = lc_path.path.points; + auto marker = createDefaultMarker( + "map", current_time, ns_with_idx, ++id, Marker::LINE_STRIP, createMarkerScale(0.1, 0.1, 0.0), + color); + marker.points.reserve(points.size()); - for (const auto & point : lanes.at(idx).path.points) { + for (const auto & point : points) { marker.points.push_back(point.point.pose.position); } + auto text_marker = createDefaultMarker( + "map", current_time, ns_with_idx, ++id, visualization_msgs::msg::Marker::TEXT_VIEW_FACING, + createMarkerScale(0.1, 0.1, 0.8), colors::yellow()); + const auto prep_idx = points.size() / 4; + text_marker.pose = points.at(prep_idx).point.pose; + text_marker.pose.position.z += 2.0; + text_marker.text = info_prep_to_string(lc_path.info); + marker_array.markers.push_back(text_marker); + + const auto lc_idx = points.size() / 2; + text_marker.id = ++id; + text_marker.pose = points.at(lc_idx).point.pose; + text_marker.text = info_lc_to_string(lc_path.info); + marker_array.markers.push_back(text_marker); + marker_array.markers.push_back(marker); } return marker_array; From a499a0a0ed7933b6e4cca5a40a9ad9ad70a27c3c Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 24 Dec 2024 17:23:30 +0900 Subject: [PATCH 091/334] fix(autoware_tensorrt_classifier): fix bugprone-exception-escape (#9732) fix: bugprone-error Signed-off-by: kobayu858 --- .../src/tensorrt_classifier.cpp | 12 +++++++++--- 1 file changed, 9 insertions(+), 3 deletions(-) diff --git a/perception/autoware_tensorrt_classifier/src/tensorrt_classifier.cpp b/perception/autoware_tensorrt_classifier/src/tensorrt_classifier.cpp index b24e4fe56e8b8..4aa008e42c966 100644 --- a/perception/autoware_tensorrt_classifier/src/tensorrt_classifier.cpp +++ b/perception/autoware_tensorrt_classifier/src/tensorrt_classifier.cpp @@ -193,9 +193,15 @@ TrtClassifier::TrtClassifier( TrtClassifier::~TrtClassifier() { - if (m_cuda) { - if (h_img_) CHECK_CUDA_ERROR(cudaFreeHost(h_img_)); - if (d_img_) CHECK_CUDA_ERROR(cudaFree(d_img_)); + try { + if (m_cuda) { + if (h_img_) CHECK_CUDA_ERROR(cudaFreeHost(h_img_)); + if (d_img_) CHECK_CUDA_ERROR(cudaFree(d_img_)); + } + } catch (const std::exception & e) { + std::cerr << "Exception in TrtClassifier destructor: " << e.what() << std::endl; + } catch (...) { + std::cerr << "Unknown exception in TrtClassifier destructor" << std::endl; } } From 72bc2dcf8aaa79247b3aa6dab09dd900764c44fd Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 24 Dec 2024 17:25:54 +0900 Subject: [PATCH 092/334] fix(autoware_tensorrt_yolox): fix bugprone-exception-escape (#9734) * fix: bugprone-error Signed-off-by: kobayu858 * fix: fmt Signed-off-by: kobayu858 * fix: fmt Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../src/tensorrt_yolox.cpp | 24 ++++++++++++------- 1 file changed, 15 insertions(+), 9 deletions(-) diff --git a/perception/autoware_tensorrt_yolox/src/tensorrt_yolox.cpp b/perception/autoware_tensorrt_yolox/src/tensorrt_yolox.cpp index 06540f2b7cd19..7e2e327bf6f5e 100644 --- a/perception/autoware_tensorrt_yolox/src/tensorrt_yolox.cpp +++ b/perception/autoware_tensorrt_yolox/src/tensorrt_yolox.cpp @@ -341,16 +341,22 @@ TrtYoloX::TrtYoloX( TrtYoloX::~TrtYoloX() { - if (use_gpu_preprocess_) { - if (image_buf_h_) { - image_buf_h_.reset(); - } - if (image_buf_d_) { - image_buf_d_.reset(); - } - if (argmax_buf_d_) { - argmax_buf_d_.reset(); + try { + if (use_gpu_preprocess_) { + if (image_buf_h_) { + image_buf_h_.reset(); + } + if (image_buf_d_) { + image_buf_d_.reset(); + } + if (argmax_buf_d_) { + argmax_buf_d_.reset(); + } } + } catch (const std::exception & e) { + std::cerr << "Exception in TrtYoloX destructor: " << e.what() << std::endl; + } catch (...) { + std::cerr << "Unknown exception in TrtYoloX destructor" << std::endl; } } From 3402b6a7c80326967b9b5a61f079d28cf7d26232 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 24 Dec 2024 17:29:16 +0900 Subject: [PATCH 093/334] fix(autoware_behavior_path_static_obstacle_avoidance_module): fix bugprone-branch-clone (#9701) fix: bugprone-error Signed-off-by: kobayu858 --- .../src/scene.cpp | 6 +----- .../src/shift_line_generator.cpp | 4 +--- 2 files changed, 2 insertions(+), 8 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp index be4ce4a125c68..48729c9c4fa0c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp @@ -233,11 +233,7 @@ void StaticObstacleAvoidanceModule::fillFundamentalData( std::for_each( data.current_lanelets.begin(), data.current_lanelets.end(), [&](const auto & lanelet) { - if (!not_use_adjacent_lane) { - data.drivable_lanes.push_back( - utils::static_obstacle_avoidance::generateExpandedDrivableLanes( - lanelet, planner_data_, parameters_)); - } else if (red_signal_lane_itr->id() != lanelet.id()) { + if (!not_use_adjacent_lane || red_signal_lane_itr->id() != lanelet.id()) { data.drivable_lanes.push_back( utils::static_obstacle_avoidance::generateExpandedDrivableLanes( lanelet, planner_data_, parameters_)); diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp index 744af35641a59..2aba986ab680d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp @@ -264,9 +264,7 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( AvoidOutlines outlines; for (auto & o : data.target_objects) { if (!o.avoid_margin.has_value()) { - if (!data.red_signal_lane.has_value()) { - o.info = ObjectInfo::INSUFFICIENT_DRIVABLE_SPACE; - } else if (data.red_signal_lane.value().id() == o.overhang_lanelet.id()) { + if (data.red_signal_lane.value().id() == o.overhang_lanelet.id()) { o.info = ObjectInfo::LIMIT_DRIVABLE_SPACE_TEMPORARY; } else { o.info = ObjectInfo::INSUFFICIENT_DRIVABLE_SPACE; From c476676c39612ebc36a20072415125571598abb2 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 24 Dec 2024 17:30:25 +0900 Subject: [PATCH 094/334] fix(autoware_default_adapi): fix bugprone-branch-clone (#9726) fix: bugprone-error Signed-off-by: kobayu858 --- system/autoware_default_adapi/src/utils/route_conversion.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/system/autoware_default_adapi/src/utils/route_conversion.cpp b/system/autoware_default_adapi/src/utils/route_conversion.cpp index e8a748d52edee..25e8204770f8a 100644 --- a/system/autoware_default_adapi/src/utils/route_conversion.cpp +++ b/system/autoware_default_adapi/src/utils/route_conversion.cpp @@ -115,13 +115,13 @@ ExternalState convert_state(const InternalState & internal) const auto convert = [](InternalState::_state_type state) { switch(state) { // TODO(Takagi, Isamu): Add adapi state. - case InternalState::INITIALIZING: return ExternalState::UNSET; + case InternalState::INITIALIZING: return ExternalState::UNSET; // NOLINT case InternalState::UNSET: return ExternalState::UNSET; case InternalState::ROUTING: return ExternalState::UNSET; case InternalState::SET: return ExternalState::SET; case InternalState::REROUTING: return ExternalState::CHANGING; case InternalState::ARRIVED: return ExternalState::ARRIVED; - case InternalState::ABORTED: return ExternalState::SET; + case InternalState::ABORTED: return ExternalState::SET; // NOLINT case InternalState::INTERRUPTED: return ExternalState::SET; default: return ExternalState::UNKNOWN; } From 46586531056e780748a545c362403b36c9307b3e Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 24 Dec 2024 19:21:25 +0900 Subject: [PATCH 095/334] fix(autoware_route_handler): fix bugprone-exception-escape (#9738) * fix: bugprone-error Signed-off-by: kobayu858 * fix: add include Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../src/route_handler.cpp | 97 +++++++++++-------- 1 file changed, 57 insertions(+), 40 deletions(-) diff --git a/planning/autoware_route_handler/src/route_handler.cpp b/planning/autoware_route_handler/src/route_handler.cpp index 01e52d85f01c3..89930fd4a23a9 100644 --- a/planning/autoware_route_handler/src/route_handler.cpp +++ b/planning/autoware_route_handler/src/route_handler.cpp @@ -36,6 +36,7 @@ #include #include +#include #include #include #include @@ -1163,32 +1164,40 @@ lanelet::ConstLanelets RouteHandler::getAllLeftSharedLinestringLanelets( const bool & invert_opposite) const noexcept { lanelet::ConstLanelets linestring_shared; - auto lanelet_at_left = getLeftLanelet(lane); - auto lanelet_at_left_opposite = getLeftOppositeLanelets(lane); - while (lanelet_at_left) { - linestring_shared.push_back(lanelet_at_left.value()); - lanelet_at_left = getLeftLanelet(lanelet_at_left.value()); - if (!lanelet_at_left) { - break; + try { + auto lanelet_at_left = getLeftLanelet(lane); + auto lanelet_at_left_opposite = getLeftOppositeLanelets(lane); + while (lanelet_at_left) { + linestring_shared.push_back(lanelet_at_left.value()); + lanelet_at_left = getLeftLanelet(lanelet_at_left.value()); + if (!lanelet_at_left) { + break; + } + lanelet_at_left_opposite = getLeftOppositeLanelets(lanelet_at_left.value()); } - lanelet_at_left_opposite = getLeftOppositeLanelets(lanelet_at_left.value()); - } - if (!lanelet_at_left_opposite.empty() && include_opposite) { - if (invert_opposite) { - linestring_shared.push_back(lanelet_at_left_opposite.front().invert()); - } else { - linestring_shared.push_back(lanelet_at_left_opposite.front()); - } - auto lanelet_at_right = getRightLanelet(lanelet_at_left_opposite.front()); - while (lanelet_at_right) { + if (!lanelet_at_left_opposite.empty() && include_opposite) { if (invert_opposite) { - linestring_shared.push_back(lanelet_at_right.value().invert()); + linestring_shared.push_back(lanelet_at_left_opposite.front().invert()); } else { - linestring_shared.push_back(lanelet_at_right.value()); + linestring_shared.push_back(lanelet_at_left_opposite.front()); + } + auto lanelet_at_right = getRightLanelet(lanelet_at_left_opposite.front()); + while (lanelet_at_right) { + if (invert_opposite) { + linestring_shared.push_back(lanelet_at_right.value().invert()); + } else { + linestring_shared.push_back(lanelet_at_right.value()); + } + lanelet_at_right = getRightLanelet(lanelet_at_right.value()); } - lanelet_at_right = getRightLanelet(lanelet_at_right.value()); } + } catch (const std::exception & e) { + std::cerr << "Exception in getAllLeftSharedLinestringLanelets: " << e.what() << std::endl; + return {}; + } catch (...) { + std::cerr << "Unknown exception in getAllLeftSharedLinestringLanelets" << std::endl; + return {}; } return linestring_shared; } @@ -1198,32 +1207,40 @@ lanelet::ConstLanelets RouteHandler::getAllRightSharedLinestringLanelets( const bool & invert_opposite) const noexcept { lanelet::ConstLanelets linestring_shared; - auto lanelet_at_right = getRightLanelet(lane); - auto lanelet_at_right_opposite = getRightOppositeLanelets(lane); - while (lanelet_at_right) { - linestring_shared.push_back(lanelet_at_right.value()); - lanelet_at_right = getRightLanelet(lanelet_at_right.value()); - if (!lanelet_at_right) { - break; + try { + auto lanelet_at_right = getRightLanelet(lane); + auto lanelet_at_right_opposite = getRightOppositeLanelets(lane); + while (lanelet_at_right) { + linestring_shared.push_back(lanelet_at_right.value()); + lanelet_at_right = getRightLanelet(lanelet_at_right.value()); + if (!lanelet_at_right) { + break; + } + lanelet_at_right_opposite = getRightOppositeLanelets(lanelet_at_right.value()); } - lanelet_at_right_opposite = getRightOppositeLanelets(lanelet_at_right.value()); - } - if (!lanelet_at_right_opposite.empty() && include_opposite) { - if (invert_opposite) { - linestring_shared.push_back(lanelet_at_right_opposite.front().invert()); - } else { - linestring_shared.push_back(lanelet_at_right_opposite.front()); - } - auto lanelet_at_left = getLeftLanelet(lanelet_at_right_opposite.front()); - while (lanelet_at_left) { + if (!lanelet_at_right_opposite.empty() && include_opposite) { if (invert_opposite) { - linestring_shared.push_back(lanelet_at_left.value().invert()); + linestring_shared.push_back(lanelet_at_right_opposite.front().invert()); } else { - linestring_shared.push_back(lanelet_at_left.value()); + linestring_shared.push_back(lanelet_at_right_opposite.front()); + } + auto lanelet_at_left = getLeftLanelet(lanelet_at_right_opposite.front()); + while (lanelet_at_left) { + if (invert_opposite) { + linestring_shared.push_back(lanelet_at_left.value().invert()); + } else { + linestring_shared.push_back(lanelet_at_left.value()); + } + lanelet_at_left = getLeftLanelet(lanelet_at_left.value()); } - lanelet_at_left = getLeftLanelet(lanelet_at_left.value()); } + } catch (const std::exception & e) { + std::cerr << "Exception in getAllRightSharedLinestringLanelets: " << e.what() << std::endl; + return {}; + } catch (...) { + std::cerr << "Unknown exception in getAllRightSharedLinestringLanelets" << std::endl; + return {}; } return linestring_shared; } From 7102a48c93ff9616e62722cb46761266900d220d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Tue, 24 Dec 2024 13:31:06 +0300 Subject: [PATCH 096/334] ci: introduce build-test-tidy-pr (#9709) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../build-and-test-differential/action.yaml | 111 --------- .github/labeler.yaml | 3 - .../build-and-test-differential.yaml | 219 ++++++------------ .github/workflows/build-test-tidy-pr.yaml | 76 ++++++ .../workflows/clang-tidy-differential.yaml | 75 ++++++ 5 files changed, 227 insertions(+), 257 deletions(-) delete mode 100644 .github/actions/build-and-test-differential/action.yaml create mode 100644 .github/workflows/build-test-tidy-pr.yaml create mode 100644 .github/workflows/clang-tidy-differential.yaml diff --git a/.github/actions/build-and-test-differential/action.yaml b/.github/actions/build-and-test-differential/action.yaml deleted file mode 100644 index 89893e9f55fb5..0000000000000 --- a/.github/actions/build-and-test-differential/action.yaml +++ /dev/null @@ -1,111 +0,0 @@ -name: build-and-test-differential -description: "" - -inputs: - rosdistro: - description: "" - required: true - container: - description: "" - required: true - container-suffix: - description: "" - required: true - runner: - description: "" - required: true - build-depends-repos: - description: "" - required: true - build-pre-command: - description: "" - required: true - codecov-token: - description: "" - required: true - -runs: - using: composite - steps: - - name: Show disk space before the tasks - run: df -h - shell: bash - - - name: Show machine specs - run: lscpu && free -h - shell: bash - - - name: Remove exec_depend - uses: autowarefoundation/autoware-github-actions/remove-exec-depend@v1 - - - name: Get modified packages - id: get-modified-packages - uses: autowarefoundation/autoware-github-actions/get-modified-packages@v1 - - - name: Create ccache directory - run: | - mkdir -p ${CCACHE_DIR} - du -sh ${CCACHE_DIR} && ccache -s - shell: bash - - - name: Attempt to restore ccache - uses: actions/cache/restore@v4 - with: - path: | - /root/.ccache - key: ccache-main-${{ runner.arch }}-${{ inputs.rosdistro }}-${{ github.event.pull_request.base.sha }} - restore-keys: | - ccache-main-${{ runner.arch }}-${{ inputs.rosdistro }}- - - - name: Show ccache stats before build and reset stats - run: | - du -sh ${CCACHE_DIR} && ccache -s - ccache --zero-stats - shell: bash - - - name: Export CUDA state as a variable for adding to cache key - run: | - build_type_cuda_state=nocuda - if [[ "${{ inputs.container-suffix }}" == "-cuda" ]]; then - build_type_cuda_state=cuda - fi - echo "BUILD_TYPE_CUDA_STATE=$build_type_cuda_state" >> "${GITHUB_ENV}" - echo "::notice::BUILD_TYPE_CUDA_STATE=$build_type_cuda_state" - shell: bash - - - name: Build - if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }} - uses: autowarefoundation/autoware-github-actions/colcon-build@v1 - with: - rosdistro: ${{ inputs.rosdistro }} - target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} - build-depends-repos: ${{ inputs.build-depends-repos }} - cache-key-element: ${{ env.BUILD_TYPE_CUDA_STATE }} - build-pre-command: ${{ inputs.build-pre-command }} - - - name: Show ccache stats after build - run: du -sh ${CCACHE_DIR} && ccache -s - shell: bash - - - name: Test - id: test - if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }} - uses: autowarefoundation/autoware-github-actions/colcon-test@v1 - with: - rosdistro: ${{ inputs.rosdistro }} - target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} - build-depends-repos: ${{ inputs.build-depends-repos }} - - - name: Upload coverage to CodeCov - if: ${{ steps.test.outputs.coverage-report-files != '' }} - uses: codecov/codecov-action@v4 - with: - files: ${{ steps.test.outputs.coverage-report-files }} - fail_ci_if_error: false - verbose: true - flags: differential - token: ${{ inputs.codecov-token }} - - - name: Show disk space after the tasks - run: df -h - shell: bash diff --git a/.github/labeler.yaml b/.github/labeler.yaml index 115f75197f41a..47f8737ebbf39 100644 --- a/.github/labeler.yaml +++ b/.github/labeler.yaml @@ -39,6 +39,3 @@ - tools/**/* "component:vehicle": - vehicle/**/* -"tag:require-cuda-build-and-test": - - perception/**/* - - sensing/**/* diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index f62904b03c6e4..0925cb0f53930 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -1,57 +1,35 @@ name: build-and-test-differential on: - pull_request: - types: - - opened - - synchronize - - reopened - - labeled - -concurrency: - group: ${{ github.workflow }}-${{ github.event.pull_request.number || github.run_id }} - cancel-in-progress: true + workflow_call: + inputs: + container: + required: true + type: string + runner: + default: ubuntu-24.04 + required: false + type: string + rosdistro: + default: humble + required: false + type: string + container-suffix: + required: false + default: "" + type: string + secrets: + codecov-token: + required: true env: CC: /usr/lib/ccache/gcc CXX: /usr/lib/ccache/g++ jobs: - make-sure-label-is-present: - uses: autowarefoundation/autoware-github-actions/.github/workflows/make-sure-label-is-present.yaml@v1 - with: - label: tag:run-build-and-test-differential - - make-sure-require-cuda-label-is-present: - uses: autowarefoundation/autoware-github-actions/.github/workflows/make-sure-label-is-present.yaml@v1 - with: - label: tag:require-cuda-build-and-test - - prepare-build-and-test-differential: - runs-on: ubuntu-latest - needs: [make-sure-label-is-present, make-sure-require-cuda-label-is-present] - outputs: - cuda_build: ${{ steps.check-if-cuda-build-is-required.outputs.cuda_build }} - steps: - - name: Check if cuda-build is required - id: check-if-cuda-build-is-required - run: | - if ${{ needs.make-sure-require-cuda-label-is-present.outputs.result == 'true' }}; then - echo "cuda-build is required" - echo "cuda_build=true" >> $GITHUB_OUTPUT - else - echo "cuda-build is not required" - echo "cuda_build=false" >> $GITHUB_OUTPUT - fi - shell: bash - - name: Fail if the tag:run-build-and-test-differential is missing - if: ${{ needs.make-sure-label-is-present.outputs.result != 'true' }} - run: exit 1 - build-and-test-differential: - runs-on: ubuntu-latest - container: ghcr.io/autowarefoundation/autoware:universe-devel - needs: prepare-build-and-test-differential + runs-on: ${{ inputs.runner }} + container: ${{ inputs.container }}${{ inputs.container-suffix }} steps: - name: Set PR fetch depth run: echo "PR_FETCH_DEPTH=$(( ${{ github.event.pull_request.commits }} + 1 ))" >> "${GITHUB_ENV}" @@ -63,61 +41,13 @@ jobs: ref: ${{ github.event.pull_request.head.sha }} fetch-depth: ${{ env.PR_FETCH_DEPTH }} - - name: Run build-and-test-differential action - uses: ./.github/actions/build-and-test-differential - with: - rosdistro: humble - container: ghcr.io/autowarefoundation/autoware:universe-devel - container-suffix: "" - runner: ubuntu-latest - build-depends-repos: build_depends.repos - build-pre-command: "" - codecov-token: ${{ secrets.CODECOV_TOKEN }} - - build-and-test-differential-cuda: - runs-on: codebuild-autoware-us-east-1-${{ github.run_id }}-${{ github.run_attempt }}-ubuntu-7.0-large - container: ghcr.io/autowarefoundation/autoware:universe-devel-cuda - needs: prepare-build-and-test-differential - if: ${{ needs.prepare-build-and-test-differential.outputs.cuda_build == 'true' }} - steps: - - name: Set PR fetch depth - run: echo "PR_FETCH_DEPTH=$(( ${{ github.event.pull_request.commits }} + 1 ))" >> "${GITHUB_ENV}" - shell: bash - - - name: Checkout PR branch and all PR commits - uses: actions/checkout@v4 - with: - ref: ${{ github.event.pull_request.head.sha }} - fetch-depth: ${{ env.PR_FETCH_DEPTH }} - - - name: Run build-and-test-differential action - uses: ./.github/actions/build-and-test-differential - with: - rosdistro: humble - container: ghcr.io/autowarefoundation/autoware:universe-devel - container-suffix: -cuda - runner: codebuild-autoware-us-east-1-${{ github.run_id }}-${{ github.run_attempt }}-ubuntu-7.0-large - build-depends-repos: build_depends.repos - build-pre-command: taskset --cpu-list 0-5 - codecov-token: ${{ secrets.CODECOV_TOKEN }} - - clang-tidy-differential: - needs: [build-and-test-differential, prepare-build-and-test-differential] - if: ${{ needs.prepare-build-and-test-differential.outputs.cuda_build == 'false' }} - runs-on: ubuntu-latest - container: ghcr.io/autowarefoundation/autoware:universe-devel - steps: - - name: Set PR fetch depth - run: echo "PR_FETCH_DEPTH=$(( ${{ github.event.pull_request.commits }} + 1 ))" >> "${GITHUB_ENV}" - - - name: Checkout PR branch and all PR commits - uses: actions/checkout@v4 - with: - ref: ${{ github.event.pull_request.head.sha }} - fetch-depth: ${{ env.PR_FETCH_DEPTH }} - - name: Show disk space before the tasks run: df -h + shell: bash + + - name: Show machine specs + run: lscpu && free -h + shell: bash - name: Remove exec_depend uses: autowarefoundation/autoware-github-actions/remove-exec-depend@v1 @@ -126,66 +56,69 @@ jobs: id: get-modified-packages uses: autowarefoundation/autoware-github-actions/get-modified-packages@v1 - - name: Get changed files (existing files only) - id: get-changed-files + - name: Create ccache directory run: | - echo "changed-files=$(git diff --name-only "origin/${{ github.base_ref }}"...HEAD | grep -E '\.(cpp|hpp)$' | while read -r file; do [ -e "$file" ] && echo -n "$file "; done)" >> $GITHUB_OUTPUT + mkdir -p ${CCACHE_DIR} + du -sh ${CCACHE_DIR} && ccache -s shell: bash - - name: Run clang-tidy - if: ${{ steps.get-changed-files.outputs.changed-files != '' }} - uses: autowarefoundation/autoware-github-actions/clang-tidy@v1 + - name: Attempt to restore ccache + uses: actions/cache/restore@v4 with: - rosdistro: humble - target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} - clang-tidy-config-url: https://raw.githubusercontent.com/autowarefoundation/autoware/main/.clang-tidy-ci - clang-tidy-ignore-path: .clang-tidy-ignore - build-depends-repos: build_depends.repos - cache-key-element: cuda + path: | + /root/.ccache + key: ccache-main-${{ runner.arch }}-${{ inputs.rosdistro }}-${{ github.event.pull_request.base.sha }} + restore-keys: | + ccache-main-${{ runner.arch }}-${{ inputs.rosdistro }}- - - name: Show disk space after the tasks - run: df -h + - name: Show ccache stats before build and reset stats + run: | + du -sh ${CCACHE_DIR} && ccache -s + ccache --zero-stats + shell: bash - clang-tidy-differential-cuda: - needs: build-and-test-differential-cuda - runs-on: codebuild-autoware-us-east-1-${{ github.run_id }}-${{ github.run_attempt }}-ubuntu-7.0-large - container: ghcr.io/autowarefoundation/autoware:universe-devel-cuda - steps: - - name: Set PR fetch depth - run: echo "PR_FETCH_DEPTH=$(( ${{ github.event.pull_request.commits }} + 1 ))" >> "${GITHUB_ENV}" + - name: Export CUDA state as a variable for adding to cache key + run: | + build_type_cuda_state=nocuda + if [[ "${{ inputs.container-suffix }}" == "-cuda" ]]; then + build_type_cuda_state=cuda + fi + echo "BUILD_TYPE_CUDA_STATE=$build_type_cuda_state" >> "${GITHUB_ENV}" + echo "::notice::BUILD_TYPE_CUDA_STATE=$build_type_cuda_state" + shell: bash - - name: Checkout PR branch and all PR commits - uses: actions/checkout@v4 + - name: Build + if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }} + uses: autowarefoundation/autoware-github-actions/colcon-build@v1 with: - ref: ${{ github.event.pull_request.head.sha }} - fetch-depth: ${{ env.PR_FETCH_DEPTH }} - - - name: Show disk space before the tasks - run: df -h - - - name: Remove exec_depend - uses: autowarefoundation/autoware-github-actions/remove-exec-depend@v1 - - - name: Get modified packages - id: get-modified-packages - uses: autowarefoundation/autoware-github-actions/get-modified-packages@v1 + rosdistro: ${{ inputs.rosdistro }} + target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} + build-depends-repos: build_depends.repos + cache-key-element: ${{ env.BUILD_TYPE_CUDA_STATE }} - - name: Get changed files (existing files only) - id: get-changed-files - run: | - echo "changed-files=$(git diff --name-only "origin/${{ github.base_ref }}"...HEAD | grep -E '\.(cpp|hpp)$' | while read -r file; do [ -e "$file" ] && echo -n "$file "; done)" >> $GITHUB_OUTPUT + - name: Show ccache stats after build + run: du -sh ${CCACHE_DIR} && ccache -s shell: bash - - name: Run clang-tidy - if: ${{ steps.get-changed-files.outputs.changed-files != '' }} - uses: autowarefoundation/autoware-github-actions/clang-tidy@v1 + - name: Test + id: test + if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }} + uses: autowarefoundation/autoware-github-actions/colcon-test@v1 with: - rosdistro: humble + rosdistro: ${{ inputs.rosdistro }} target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} - clang-tidy-config-url: https://raw.githubusercontent.com/autowarefoundation/autoware/main/.clang-tidy-ci - clang-tidy-ignore-path: .clang-tidy-ignore build-depends-repos: build_depends.repos - cache-key-element: cuda + + - name: Upload coverage to CodeCov + if: ${{ steps.test.outputs.coverage-report-files != '' }} + uses: codecov/codecov-action@v4 + with: + files: ${{ steps.test.outputs.coverage-report-files }} + fail_ci_if_error: false + verbose: true + flags: differential${{ inputs.container-suffix }} + token: ${{ secrets.codecov-token }} - name: Show disk space after the tasks run: df -h + shell: bash diff --git a/.github/workflows/build-test-tidy-pr.yaml b/.github/workflows/build-test-tidy-pr.yaml new file mode 100644 index 0000000000000..df2eff132eb05 --- /dev/null +++ b/.github/workflows/build-test-tidy-pr.yaml @@ -0,0 +1,76 @@ +name: build-test-tidy-pr + +on: + pull_request: + types: + - opened + - synchronize + - reopened + - labeled + +concurrency: + group: ${{ github.workflow }}-${{ github.event.pull_request.number || github.run_id }} + cancel-in-progress: true + +jobs: + require-label: + uses: autowarefoundation/autoware-github-actions/.github/workflows/require-label.yaml@v1 + with: + label: run:build-and-test-differential + + check-if-cuda-job-is-needed: + needs: require-label + runs-on: ubuntu-latest + outputs: + cuda_job_is_needed: ${{ steps.check.outputs.any_changed }} + steps: + - uses: actions/checkout@v4 + + - name: Check if relevant files changed + id: check + uses: tj-actions/changed-files@v45 + with: + files: | + perception/** + sensing/** + + - name: Output result + run: | + echo "CUDA job needed: ${{ steps.check.outputs.any_changed }}" + shell: bash + + build-and-test-differential: + needs: + - require-label + uses: ./.github/workflows/build-and-test-differential.yaml + with: + container: ghcr.io/autowarefoundation/autoware:universe-devel + secrets: + codecov-token: ${{ secrets.CODECOV_TOKEN }} + + build-and-test-differential-cuda: + needs: check-if-cuda-job-is-needed + if: ${{ needs.check-if-cuda-job-is-needed.outputs.cuda_job_is_needed == 'true' }} + uses: ./.github/workflows/build-and-test-differential.yaml + with: + container: ghcr.io/autowarefoundation/autoware:universe-devel + container-suffix: -cuda + secrets: + codecov-token: ${{ secrets.CODECOV_TOKEN }} + + clang-tidy-differential: + needs: + - check-if-cuda-job-is-needed + - build-and-test-differential + if: ${{ needs.check-if-cuda-job-is-needed.outputs.cuda_job_is_needed == 'false' }} + uses: ./.github/workflows/clang-tidy-differential.yaml + with: + container: ghcr.io/autowarefoundation/autoware:universe-devel + + clang-tidy-differential-cuda: + needs: + - build-and-test-differential-cuda + uses: ./.github/workflows/clang-tidy-differential.yaml + with: + container: ghcr.io/autowarefoundation/autoware:universe-devel + container-suffix: -cuda diff --git a/.github/workflows/clang-tidy-differential.yaml b/.github/workflows/clang-tidy-differential.yaml new file mode 100644 index 0000000000000..51e0a8408468c --- /dev/null +++ b/.github/workflows/clang-tidy-differential.yaml @@ -0,0 +1,75 @@ +name: clang-tidy-differential + +on: + workflow_call: + inputs: + container: + required: true + type: string + container-suffix: + required: false + default: "" + type: string + runner: + default: ubuntu-24.04 + required: false + type: string + +jobs: + clang-tidy-differential: + runs-on: ${{ inputs.runner }} + container: ${{ inputs.container }}${{ inputs.container-suffix }} + steps: + - name: Set PR fetch depth + run: echo "PR_FETCH_DEPTH=$(( ${{ github.event.pull_request.commits }} + 1 ))" >> "${GITHUB_ENV}" + + - name: Checkout PR branch and all PR commits + uses: actions/checkout@v4 + with: + ref: ${{ github.event.pull_request.head.sha }} + fetch-depth: ${{ env.PR_FETCH_DEPTH }} + + - name: Show machine specs + run: lscpu && free -h + shell: bash + + - name: Show disk space before the tasks + run: df -h + shell: bash + + - name: Remove exec_depend + uses: autowarefoundation/autoware-github-actions/remove-exec-depend@v1 + + - name: Get modified packages + id: get-modified-packages + uses: autowarefoundation/autoware-github-actions/get-modified-packages@v1 + + - name: Get changed files (existing files only) + id: get-changed-files + run: | + echo "changed-files=$(git diff --name-only "origin/${{ github.base_ref }}"...HEAD | grep -E '\.(cpp|hpp)$' | while read -r file; do [ -e "$file" ] && echo -n "$file "; done)" >> $GITHUB_OUTPUT + shell: bash + + - name: Export CUDA state as a variable for adding to cache key + run: | + build_type_cuda_state=nocuda + if [[ "${{ inputs.container-suffix }}" == "-cuda" ]]; then + build_type_cuda_state=cuda + fi + echo "BUILD_TYPE_CUDA_STATE=$build_type_cuda_state" >> "${GITHUB_ENV}" + echo "::notice::BUILD_TYPE_CUDA_STATE=$build_type_cuda_state" + shell: bash + + - name: Run clang-tidy + if: ${{ steps.get-changed-files.outputs.changed-files != '' }} + uses: autowarefoundation/autoware-github-actions/clang-tidy@v1 + with: + rosdistro: humble + target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} + clang-tidy-config-url: https://raw.githubusercontent.com/autowarefoundation/autoware/main/.clang-tidy-ci + clang-tidy-ignore-path: .clang-tidy-ignore + build-depends-repos: build_depends.repos + cache-key-element: ${{ env.BUILD_TYPE_CUDA_STATE }} + + - name: Show disk space after the tasks + run: df -h From 24bcd0e8b9a0a5541af9c95450d0ce2f7a402abc Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 24 Dec 2024 20:57:04 +0900 Subject: [PATCH 097/334] feat(motion_velocity_planner): remove unnecessary tier4_planning_msgs dependency (#9757) * feat(motion_velocity_planner): remove unnecessary tier4_planning_msgs dependency Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../package.xml | 1 - .../package.xml | 1 - .../autoware_motion_velocity_out_of_lane_module/package.xml | 1 - .../src/out_of_lane_module.hpp | 2 -- .../autoware/motion_velocity_planner_common/planner_data.hpp | 2 -- .../autoware_motion_velocity_planner_common/package.xml | 1 - .../autoware_motion_velocity_planner_node/package.xml | 1 - .../autoware_motion_velocity_planner_node/src/node.cpp | 5 ----- 8 files changed, 14 deletions(-) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/package.xml index eef7b6af1f9af..1063abfb61bbb 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/package.xml @@ -24,7 +24,6 @@ pluginlib rclcpp tf2 - tier4_planning_msgs visualization_msgs ament_cmake_ros diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/package.xml index 68e2ead5a5ec7..e608e158b3ffe 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/package.xml @@ -33,7 +33,6 @@ sensor_msgs tf2_eigen tf2_geometry_msgs - tier4_planning_msgs visualization_msgs ament_cmake_ros diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml index 857716819d8cc..f0f663355821c 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml @@ -29,7 +29,6 @@ pluginlib rclcpp tf2 - tier4_planning_msgs visualization_msgs ament_cmake_ros diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp index c39c6e17101c5..72f20f1c63d96 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp @@ -24,8 +24,6 @@ #include #include -#include -#include #include diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp index a5f9badd9f4f7..9ef3bf5c7f756 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp @@ -31,7 +31,6 @@ #include #include #include -#include #include #include @@ -72,7 +71,6 @@ struct PlannerData // last observed infomation for UNKNOWN std::map traffic_light_id_map_raw_; std::map traffic_light_id_map_last_observed_; - std::optional external_velocity_limit; // velocity smoother std::shared_ptr velocity_smoother_; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml index 51f4d9d984365..2fc682e695f6b 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml @@ -28,7 +28,6 @@ geometry_msgs libboost-dev rclcpp - tier4_planning_msgs visualization_msgs ament_cmake_ros diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml index 03a1bec5c6fe5..07b719689f51f 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml @@ -39,7 +39,6 @@ tf2_geometry_msgs tf2_ros tier4_metric_msgs - tier4_planning_msgs visualization_msgs rosidl_default_runtime diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp index 9a607ba3b88cf..cefc84836beda 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp @@ -357,7 +357,6 @@ autoware::motion_velocity_planner::TrajectoryPoints MotionVelocityPlannerNode::s const geometry_msgs::msg::Pose current_pose = planner_data.current_odometry.pose.pose; const double v0 = planner_data.current_odometry.twist.twist.linear.x; const double a0 = planner_data.current_acceleration.accel.accel.linear.x; - const auto & external_v_limit = planner_data.external_velocity_limit; const auto & smoother = planner_data.velocity_smoother_; const auto traj_lateral_acc_filtered = @@ -382,10 +381,6 @@ autoware::motion_velocity_planner::TrajectoryPoints MotionVelocityPlannerNode::s if (!smoother->apply(v0, a0, clipped, traj_smoothed, debug_trajectories, false)) { RCLCPP_ERROR(get_logger(), "failed to smooth"); } - if (external_v_limit) { - autoware::velocity_smoother::trajectory_utils::applyMaximumVelocityLimit( - 0LU, traj_smoothed.size(), external_v_limit->max_velocity, traj_smoothed); - } return traj_smoothed; } From 421ec7d67b5624720d8dc33aa1fba04c6c5a06ef Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Tue, 24 Dec 2024 20:07:25 +0300 Subject: [PATCH 098/334] ci(build-test-tidy): introduce success condition jobs (#9769) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../actions/evaluate-job-result/action.yaml | 45 ++++++++++++++ .github/workflows/build-test-tidy-pr.yaml | 61 +++++++++++++++++++ 2 files changed, 106 insertions(+) create mode 100644 .github/actions/evaluate-job-result/action.yaml diff --git a/.github/actions/evaluate-job-result/action.yaml b/.github/actions/evaluate-job-result/action.yaml new file mode 100644 index 0000000000000..c5c013080fd27 --- /dev/null +++ b/.github/actions/evaluate-job-result/action.yaml @@ -0,0 +1,45 @@ +name: Evaluate Job Result +description: Evaluates the result of a job and updates the summary. +inputs: + job_result: + description: Result of the job to evaluate (e.g., success, failure, skipped) + required: true + type: string + job_name: + description: Name of the job to evaluate + required: true + type: string + expected_results: + description: Comma-separated list of acceptable results (e.g., success,skipped) + required: true + type: string +outputs: + failed: + description: Indicates if the job failed + value: ${{ steps.evaluate.outputs.failed }} + +runs: + using: composite + steps: + - name: Evaluate Job Result + id: evaluate + run: | + JOB_RESULT="${{ inputs.job_result }}" + IFS=',' read -ra EXPECTED <<< "${{ inputs.expected_results }}" + FAILED=false + + for RESULT in "${EXPECTED[@]}"; do + if [[ "$JOB_RESULT" == "$RESULT" ]]; then + echo "- **${{ inputs.job_name }}:** "$JOB_RESULT" ✅" >> "$GITHUB_STEP_SUMMARY" + echo "failed=false" >> "$GITHUB_OUTPUT" + exit 0 + fi + done + + # If no expected result matched + echo "::error::${{ inputs.job_name }} failed. ❌" + echo "- **${{ inputs.job_name }}:** failed ❌" >> "$GITHUB_STEP_SUMMARY" + echo "failed=true" >> "$GITHUB_OUTPUT" + + exit 1 + shell: bash diff --git a/.github/workflows/build-test-tidy-pr.yaml b/.github/workflows/build-test-tidy-pr.yaml index df2eff132eb05..d1ea9b2d0f79d 100644 --- a/.github/workflows/build-test-tidy-pr.yaml +++ b/.github/workflows/build-test-tidy-pr.yaml @@ -58,6 +58,34 @@ jobs: secrets: codecov-token: ${{ secrets.CODECOV_TOKEN }} + build-test-pr: + needs: + - build-and-test-differential + - build-and-test-differential-cuda + if: ${{ always() }} + runs-on: ubuntu-latest + steps: + - uses: actions/checkout@v4 + + - name: Initialize Summary + run: echo "### Build Test PR Results" > $GITHUB_STEP_SUMMARY + shell: bash + + - name: Evaluate build-and-test-differential + uses: ./.github/actions/evaluate-job-result + with: + job_result: ${{ needs.build-and-test-differential.result }} + job_name: build-and-test-differential + expected_results: success + + - name: Evaluate build-and-test-differential-cuda + if: ${{ always() }} + uses: ./.github/actions/evaluate-job-result + with: + job_result: ${{ needs.build-and-test-differential-cuda.result }} + job_name: build-and-test-differential-cuda + expected_results: success,skipped + clang-tidy-differential: needs: - check-if-cuda-job-is-needed @@ -74,3 +102,36 @@ jobs: with: container: ghcr.io/autowarefoundation/autoware:universe-devel container-suffix: -cuda + + clang-tidy-pr: + needs: + - clang-tidy-differential + - clang-tidy-differential-cuda + if: ${{ always() }} + runs-on: ubuntu-latest + steps: + - name: Initialize Summary + run: echo "### Clang Tidy PR Results" > $GITHUB_STEP_SUMMARY + shell: bash + + - name: Check clang-tidy success + if: ${{ needs.clang-tidy-differential.result == 'success' || needs.clang-tidy-differential-cuda.result == 'success' }} + run: | + echo "✅ Either one of the following has succeeded:" >> $GITHUB_STEP_SUMMARY + + - name: Fail if conditions not met + if: ${{ !(needs.clang-tidy-differential.result == 'success' || needs.clang-tidy-differential-cuda.result == 'success') }} + run: | + echo "::error::❌ Either one of the following should have succeeded:" + echo "::error::clang-tidy-differential: ${{ needs.clang-tidy-differential.result }}" + echo "::error::clang-tidy-differential-cuda: ${{ needs.clang-tidy-differential-cuda.result }}" + + echo "❌ Either one of the following should have succeeded:" >> $GITHUB_STEP_SUMMARY + + exit 1 + + - name: Print the results + if: ${{ always() }} + run: | + echo "- **clang-tidy-differential:** ${{ needs.clang-tidy-differential.result }}" >> $GITHUB_STEP_SUMMARY + echo "- **clang-tidy-differential-cuda:** ${{ needs.clang-tidy-differential-cuda.result }}" >> $GITHUB_STEP_SUMMARY From 16d5cb1888d17ec750bb50f08f02bbd71d985c9c Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Wed, 25 Dec 2024 12:10:15 +0900 Subject: [PATCH 099/334] feat!: move diagnostics_module from localization_util to unverse_utils (#9714) * feat!: move diagnostics_module from localization_util to unverse_utils Signed-off-by: kminoda * remove diagnostics module from localization_util Signed-off-by: kminoda * style(pre-commit): autofix * minor fix in pose_initializer Signed-off-by: kminoda * add test Signed-off-by: kminoda * style(pre-commit): autofix * remove unnecessary declaration Signed-off-by: kminoda * module -> interface Signed-off-by: kminoda * remove unnecessary equal expression Signed-off-by: kminoda * revert the remove of template function Signed-off-by: kminoda * style(pre-commit): autofix * use overload instead Signed-off-by: kminoda * include what you use -- test_diagnostics_interface.cpp Signed-off-by: kminoda --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- common/autoware_universe_utils/CMakeLists.txt | 1 + .../ros/diagnostics_interface.hpp | 23 +-- .../src/ros/diagnostics_interface.cpp | 24 ++- .../src/ros/test_diagnostics_interface.cpp | 179 ++++++++++++++++++ .../src/gyro_odometer_core.cpp | 2 +- .../src/gyro_odometer_core.hpp | 4 +- .../src/lidar_marker_localizer.cpp | 42 ++-- .../src/lidar_marker_localizer.hpp | 4 +- .../CHANGELOG.rst | 4 +- .../src/localization_error_monitor.cpp | 2 +- .../src/localization_error_monitor.hpp | 4 +- .../autoware_localization_util/CMakeLists.txt | 1 - .../ndt_scan_matcher/map_update_module.hpp | 12 +- .../ndt_scan_matcher_core.hpp | 14 +- .../src/map_update_module.cpp | 10 +- .../src/ndt_scan_matcher_core.cpp | 14 +- .../autoware_pose_initializer/package.xml | 1 - .../src/pose_initializer_core.cpp | 2 +- .../src/pose_initializer_core.hpp | 5 +- 19 files changed, 261 insertions(+), 87 deletions(-) rename localization/autoware_localization_util/include/autoware/localization_util/diagnostics_module.hpp => common/autoware_universe_utils/include/autoware/universe_utils/ros/diagnostics_interface.hpp (70%) rename localization/autoware_localization_util/src/diagnostics_module.cpp => common/autoware_universe_utils/src/ros/diagnostics_interface.cpp (76%) create mode 100644 common/autoware_universe_utils/test/src/ros/test_diagnostics_interface.cpp diff --git a/common/autoware_universe_utils/CMakeLists.txt b/common/autoware_universe_utils/CMakeLists.txt index f295662e69091..72486b5de8818 100644 --- a/common/autoware_universe_utils/CMakeLists.txt +++ b/common/autoware_universe_utils/CMakeLists.txt @@ -21,6 +21,7 @@ ament_auto_add_library(autoware_universe_utils SHARED src/geometry/sat_2d.cpp src/math/sin_table.cpp src/math/trigonometry.cpp + src/ros/diagnostics_interface.cpp src/ros/msg_operation.cpp src/ros/marker_helper.cpp src/ros/logger_level_configure.cpp diff --git a/localization/autoware_localization_util/include/autoware/localization_util/diagnostics_module.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/ros/diagnostics_interface.hpp similarity index 70% rename from localization/autoware_localization_util/include/autoware/localization_util/diagnostics_module.hpp rename to common/autoware_universe_utils/include/autoware/universe_utils/ros/diagnostics_interface.hpp index 8c19c94127630..120aed7c7548e 100644 --- a/localization/autoware_localization_util/include/autoware/localization_util/diagnostics_module.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/ros/diagnostics_interface.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__LOCALIZATION_UTIL__DIAGNOSTICS_MODULE_HPP_ -#define AUTOWARE__LOCALIZATION_UTIL__DIAGNOSTICS_MODULE_HPP_ +#ifndef AUTOWARE__UNIVERSE_UTILS__ROS__DIAGNOSTICS_INTERFACE_HPP_ +#define AUTOWARE__UNIVERSE_UTILS__ROS__DIAGNOSTICS_INTERFACE_HPP_ #include @@ -22,16 +22,18 @@ #include #include -namespace autoware::localization_util +namespace autoware::universe_utils { -class DiagnosticsModule +class DiagnosticInterface { public: - DiagnosticsModule(rclcpp::Node * node, const std::string & diagnostic_name); + DiagnosticInterface(rclcpp::Node * node, const std::string & diagnostic_name); void clear(); void add_key_value(const diagnostic_msgs::msg::KeyValue & key_value_msg); template void add_key_value(const std::string & key, const T & value); + void add_key_value(const std::string & key, const std::string & value); + void add_key_value(const std::string & key, bool value); void update_level_and_message(const int8_t level, const std::string & message); void publish(const rclcpp::Time & publish_time_stamp); @@ -46,7 +48,7 @@ class DiagnosticsModule }; template -void DiagnosticsModule::add_key_value(const std::string & key, const T & value) +void DiagnosticInterface::add_key_value(const std::string & key, const T & value) { diagnostic_msgs::msg::KeyValue key_value; key_value.key = key; @@ -54,11 +56,6 @@ void DiagnosticsModule::add_key_value(const std::string & key, const T & value) add_key_value(key_value); } -template <> -void DiagnosticsModule::add_key_value(const std::string & key, const std::string & value); -template <> -void DiagnosticsModule::add_key_value(const std::string & key, const bool & value); +} // namespace autoware::universe_utils -} // namespace autoware::localization_util - -#endif // AUTOWARE__LOCALIZATION_UTIL__DIAGNOSTICS_MODULE_HPP_ +#endif // AUTOWARE__UNIVERSE_UTILS__ROS__DIAGNOSTICS_INTERFACE_HPP_ diff --git a/localization/autoware_localization_util/src/diagnostics_module.cpp b/common/autoware_universe_utils/src/ros/diagnostics_interface.cpp similarity index 76% rename from localization/autoware_localization_util/src/diagnostics_module.cpp rename to common/autoware_universe_utils/src/ros/diagnostics_interface.cpp index 2b68dbf4f5890..978af27f202d4 100644 --- a/localization/autoware_localization_util/src/diagnostics_module.cpp +++ b/common/autoware_universe_utils/src/ros/diagnostics_interface.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware/localization_util/diagnostics_module.hpp" +#include "autoware/universe_utils/ros/diagnostics_interface.hpp" #include @@ -21,9 +21,9 @@ #include #include -namespace autoware::localization_util +namespace autoware::universe_utils { -DiagnosticsModule::DiagnosticsModule(rclcpp::Node * node, const std::string & diagnostic_name) +DiagnosticInterface::DiagnosticInterface(rclcpp::Node * node, const std::string & diagnostic_name) : clock_(node->get_clock()) { diagnostics_pub_ = @@ -34,7 +34,7 @@ DiagnosticsModule::DiagnosticsModule(rclcpp::Node * node, const std::string & di diagnostics_status_msg_.hardware_id = node->get_name(); } -void DiagnosticsModule::clear() +void DiagnosticInterface::clear() { diagnostics_status_msg_.values.clear(); diagnostics_status_msg_.values.shrink_to_fit(); @@ -43,7 +43,7 @@ void DiagnosticsModule::clear() diagnostics_status_msg_.message = ""; } -void DiagnosticsModule::add_key_value(const diagnostic_msgs::msg::KeyValue & key_value_msg) +void DiagnosticInterface::add_key_value(const diagnostic_msgs::msg::KeyValue & key_value_msg) { auto it = std::find_if( std::begin(diagnostics_status_msg_.values), std::end(diagnostics_status_msg_.values), @@ -56,8 +56,7 @@ void DiagnosticsModule::add_key_value(const diagnostic_msgs::msg::KeyValue & key } } -template <> -void DiagnosticsModule::add_key_value(const std::string & key, const std::string & value) +void DiagnosticInterface::add_key_value(const std::string & key, const std::string & value) { diagnostic_msgs::msg::KeyValue key_value; key_value.key = key; @@ -65,8 +64,7 @@ void DiagnosticsModule::add_key_value(const std::string & key, const std::string add_key_value(key_value); } -template <> -void DiagnosticsModule::add_key_value(const std::string & key, const bool & value) +void DiagnosticInterface::add_key_value(const std::string & key, bool value) { diagnostic_msgs::msg::KeyValue key_value; key_value.key = key; @@ -74,7 +72,7 @@ void DiagnosticsModule::add_key_value(const std::string & key, const bool & valu add_key_value(key_value); } -void DiagnosticsModule::update_level_and_message(const int8_t level, const std::string & message) +void DiagnosticInterface::update_level_and_message(const int8_t level, const std::string & message) { if ((level > diagnostic_msgs::msg::DiagnosticStatus::OK)) { if (!diagnostics_status_msg_.message.empty()) { @@ -87,12 +85,12 @@ void DiagnosticsModule::update_level_and_message(const int8_t level, const std:: } } -void DiagnosticsModule::publish(const rclcpp::Time & publish_time_stamp) +void DiagnosticInterface::publish(const rclcpp::Time & publish_time_stamp) { diagnostics_pub_->publish(create_diagnostics_array(publish_time_stamp)); } -diagnostic_msgs::msg::DiagnosticArray DiagnosticsModule::create_diagnostics_array( +diagnostic_msgs::msg::DiagnosticArray DiagnosticInterface::create_diagnostics_array( const rclcpp::Time & publish_time_stamp) const { diagnostic_msgs::msg::DiagnosticArray diagnostics_msg; @@ -105,4 +103,4 @@ diagnostic_msgs::msg::DiagnosticArray DiagnosticsModule::create_diagnostics_arra return diagnostics_msg; } -} // namespace autoware::localization_util +} // namespace autoware::universe_utils diff --git a/common/autoware_universe_utils/test/src/ros/test_diagnostics_interface.cpp b/common/autoware_universe_utils/test/src/ros/test_diagnostics_interface.cpp new file mode 100644 index 0000000000000..a0683694cc2b7 --- /dev/null +++ b/common/autoware_universe_utils/test/src/ros/test_diagnostics_interface.cpp @@ -0,0 +1,179 @@ +// Copyright 2024 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/universe_utils/ros/diagnostics_interface.hpp" + +#include + +#include +#include +#include + +#include + +#include +#include + +using autoware::universe_utils::DiagnosticInterface; + +class TestDiagnosticInterface : public ::testing::Test +{ +protected: + void SetUp() override + { + // Create a test node + node_ = std::make_shared("test_diagnostics_interface"); + } + + // Automatically destroyed at the end of each test + std::shared_ptr node_; +}; + +/* + * Test clear(): + * Verify that calling clear() resets DiagnosticStatus values, level, and message. + */ +TEST_F(TestDiagnosticInterface, ClearTest) +{ + DiagnosticInterface module(node_.get(), "test_diagnostic"); + + // Add some key-value pairs and update level/message + module.add_key_value("param1", 42); + module.update_level_and_message( + diagnostic_msgs::msg::DiagnosticStatus::WARN, "Something is not OK"); + + // Call clear() + module.clear(); + + // After calling clear(), publish and check the contents of the message + diagnostic_msgs::msg::DiagnosticArray::ConstSharedPtr received_msg; + auto sub = node_->create_subscription( + "/diagnostics", 10, + [&](diagnostic_msgs::msg::DiagnosticArray::ConstSharedPtr msg) { received_msg = msg; }); + + // Publish the message + module.publish(node_->now()); + + // Spin to allow the subscriber to receive messages + rclcpp::spin_some(node_); + + ASSERT_NE(nullptr, received_msg); + ASSERT_FALSE(received_msg->status.empty()); + const auto & status = received_msg->status.front(); + + // After clear(), key-value pairs should be empty + EXPECT_TRUE(status.values.empty()); + + // After clear(), level should be OK (=0) + EXPECT_EQ(status.level, diagnostic_msgs::msg::DiagnosticStatus::OK); + + // After clear(), message is empty internally, + // but "OK" is set during publishing when level == OK + EXPECT_EQ(status.message, "OK"); +} + +/* + * Test add_key_value(): + * Verify that adding the same key updates its value instead of adding a duplicate. + */ +TEST_F(TestDiagnosticInterface, AddKeyValueTest) +{ + DiagnosticInterface module(node_.get(), "test_diagnostic"); + + // Call the template version of add_key_value() with different types + module.add_key_value("string_key", std::string("initial_value")); + module.add_key_value("int_key", 123); + module.add_key_value("bool_key", true); + + // Overwrite the value for "string_key" + module.add_key_value("string_key", std::string("updated_value")); + + // Capture the published message to verify its contents + diagnostic_msgs::msg::DiagnosticArray::ConstSharedPtr received_msg; + auto sub = node_->create_subscription( + "/diagnostics", 10, + [&](diagnostic_msgs::msg::DiagnosticArray::ConstSharedPtr msg) { received_msg = msg; }); + module.publish(node_->now()); + rclcpp::spin_some(node_); + + ASSERT_NE(nullptr, received_msg); + ASSERT_FALSE(received_msg->status.empty()); + const auto & status = received_msg->status.front(); + + // Expect 3 key-value pairs + ASSERT_EQ(status.values.size(), 3U); + + // Helper lambda to find a value by key + auto find_value = [&](const std::string & key) -> std::string { + for (const auto & kv : status.values) { + if (kv.key == key) { + return kv.value; + } + } + return ""; + }; + + EXPECT_EQ(find_value("string_key"), "updated_value"); + EXPECT_EQ(find_value("int_key"), "123"); + EXPECT_EQ(find_value("bool_key"), "True"); + + // Status level should still be OK + EXPECT_EQ(status.level, diagnostic_msgs::msg::DiagnosticStatus::OK); + // Message should be "OK" + EXPECT_EQ(status.message, "OK"); +} + +/* + * Test update_level_and_message(): + * Verify that the level is updated to the highest severity and + * that messages are concatenated if level > OK. + */ +TEST_F(TestDiagnosticInterface, UpdateLevelAndMessageTest) +{ + DiagnosticInterface module(node_.get(), "test_diagnostic"); + + // Initial status is level=OK(0), message="" + module.update_level_and_message(diagnostic_msgs::msg::DiagnosticStatus::OK, "Initial OK"); + // Update to WARN (1) + module.update_level_and_message(diagnostic_msgs::msg::DiagnosticStatus::WARN, "Low battery"); + // Update to ERROR (2) + module.update_level_and_message(diagnostic_msgs::msg::DiagnosticStatus::ERROR, "Sensor failure"); + // Another WARN (1) after ERROR should not downgrade the overall level + module.update_level_and_message( + diagnostic_msgs::msg::DiagnosticStatus::WARN, "Should not override error"); + + diagnostic_msgs::msg::DiagnosticArray::ConstSharedPtr received_msg; + auto sub = node_->create_subscription( + "/diagnostics", 10, + [&](diagnostic_msgs::msg::DiagnosticArray::ConstSharedPtr msg) { received_msg = msg; }); + + module.publish(node_->now()); + rclcpp::spin_some(node_); + + ASSERT_NE(nullptr, received_msg); + ASSERT_FALSE(received_msg->status.empty()); + const auto & status = received_msg->status.front(); + + // Final level should be ERROR (2) + EXPECT_EQ(status.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR); + + // The message should contain all parts that were added when level > OK. + // Thus, we expect something like: + // "Low battery; Sensor failure; Should not override error" + const std::string & final_message = status.message; + EXPECT_FALSE(final_message.find("Initial OK") != std::string::npos); + EXPECT_TRUE(final_message.find("Low battery") != std::string::npos); + EXPECT_TRUE(final_message.find("Sensor failure") != std::string::npos); + EXPECT_TRUE(final_message.find("Should not override error") != std::string::npos); +} diff --git a/localization/autoware_gyro_odometer/src/gyro_odometer_core.cpp b/localization/autoware_gyro_odometer/src/gyro_odometer_core.cpp index 9511f168f346f..d52fb5e798b58 100644 --- a/localization/autoware_gyro_odometer/src/gyro_odometer_core.cpp +++ b/localization/autoware_gyro_odometer/src/gyro_odometer_core.cpp @@ -73,7 +73,7 @@ GyroOdometerNode::GyroOdometerNode(const rclcpp::NodeOptions & node_options) "twist_with_covariance", rclcpp::QoS{10}); diagnostics_ = - std::make_unique(this, "gyro_odometer_status"); + std::make_unique(this, "gyro_odometer_status"); // TODO(YamatoAndo) createTimer } diff --git a/localization/autoware_gyro_odometer/src/gyro_odometer_core.hpp b/localization/autoware_gyro_odometer/src/gyro_odometer_core.hpp index 036b3d7cab527..70334738e9ce3 100644 --- a/localization/autoware_gyro_odometer/src/gyro_odometer_core.hpp +++ b/localization/autoware_gyro_odometer/src/gyro_odometer_core.hpp @@ -15,7 +15,7 @@ #ifndef GYRO_ODOMETER_CORE_HPP_ #define GYRO_ODOMETER_CORE_HPP_ -#include "autoware/localization_util/diagnostics_module.hpp" +#include "autoware/universe_utils/ros/diagnostics_interface.hpp" #include "autoware/universe_utils/ros/logger_level_configure.hpp" #include "autoware/universe_utils/ros/msg_covariance.hpp" #include "autoware/universe_utils/ros/transform_listener.hpp" @@ -80,7 +80,7 @@ class GyroOdometerNode : public rclcpp::Node std::deque vehicle_twist_queue_; std::deque gyro_queue_; - std::unique_ptr diagnostics_; + std::unique_ptr diagnostics_; }; } // namespace autoware::gyro_odometer diff --git a/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.cpp b/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.cpp index 2faf2d19168a5..bc7dbbcfc9ca1 100644 --- a/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.cpp +++ b/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.cpp @@ -124,22 +124,22 @@ LidarMarkerLocalizer::LidarMarkerLocalizer(const rclcpp::NodeOptions & node_opti tf_buffer_ = std::make_shared(this->get_clock()); tf_listener_ = std::make_shared(*tf_buffer_, this, false); - diagnostics_module_.reset( - new autoware::localization_util::DiagnosticsModule(this, "marker_detection_status")); + diagnostics_interface_.reset( + new autoware::universe_utils::DiagnosticInterface(this, "marker_detection_status")); } void LidarMarkerLocalizer::initialize_diagnostics() { - diagnostics_module_->clear(); - diagnostics_module_->add_key_value("is_received_map", false); - diagnostics_module_->add_key_value("is_received_self_pose", false); - diagnostics_module_->add_key_value("detect_marker_num", 0); - diagnostics_module_->add_key_value("distance_self_pose_to_nearest_marker", 0.0); - diagnostics_module_->add_key_value( + diagnostics_interface_->clear(); + diagnostics_interface_->add_key_value("is_received_map", false); + diagnostics_interface_->add_key_value("is_received_self_pose", false); + diagnostics_interface_->add_key_value("detect_marker_num", 0); + diagnostics_interface_->add_key_value("distance_self_pose_to_nearest_marker", 0.0); + diagnostics_interface_->add_key_value( "limit_distance_from_self_pose_to_nearest_marker", param_.limit_distance_from_self_pose_to_nearest_marker); - diagnostics_module_->add_key_value("distance_lanelet2_marker_to_detected_marker", 0.0); - diagnostics_module_->add_key_value( + diagnostics_interface_->add_key_value("distance_lanelet2_marker_to_detected_marker", 0.0); + diagnostics_interface_->add_key_value( "limit_distance_from_lanelet2_marker_to_detected_marker", param_.limit_distance_from_self_pose_to_marker); } @@ -176,7 +176,7 @@ void LidarMarkerLocalizer::points_callback(const PointCloud2::ConstSharedPtr & p main_process(points_msg_ptr); - diagnostics_module_->publish(sensor_ros_time); + diagnostics_interface_->publish(sensor_ros_time); } void LidarMarkerLocalizer::main_process(const PointCloud2::ConstSharedPtr & points_msg_ptr) @@ -186,13 +186,13 @@ void LidarMarkerLocalizer::main_process(const PointCloud2::ConstSharedPtr & poin // (1) check if the map have be received const std::vector map_landmarks = landmark_manager_.get_landmarks(); const bool is_received_map = !map_landmarks.empty(); - diagnostics_module_->add_key_value("is_received_map", is_received_map); + diagnostics_interface_->add_key_value("is_received_map", is_received_map); if (!is_received_map) { std::stringstream message; message << "Not receive the landmark information. Please check if the vector map is being " << "published and if the landmark information is correctly specified."; RCLCPP_INFO_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1000, message.str()); - diagnostics_module_->update_level_and_message( + diagnostics_interface_->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); return; } @@ -202,13 +202,13 @@ void LidarMarkerLocalizer::main_process(const PointCloud2::ConstSharedPtr & poin interpolate_result = ekf_pose_buffer_->interpolate(sensor_ros_time); const bool is_received_self_pose = interpolate_result != std::nullopt; - diagnostics_module_->add_key_value("is_received_self_pose", is_received_self_pose); + diagnostics_interface_->add_key_value("is_received_self_pose", is_received_self_pose); if (!is_received_self_pose) { std::stringstream message; message << "Could not get self_pose. Please check if the self pose is being published and if " << "the timestamp of the self pose is correctly specified"; RCLCPP_INFO_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1000, message.str()); - diagnostics_module_->update_level_and_message( + diagnostics_interface_->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); return; } @@ -221,7 +221,7 @@ void LidarMarkerLocalizer::main_process(const PointCloud2::ConstSharedPtr & poin detect_landmarks(points_msg_ptr); const bool is_detected_marker = !detected_landmarks.empty(); - diagnostics_module_->add_key_value("detect_marker_num", detected_landmarks.size()); + diagnostics_interface_->add_key_value("detect_marker_num", detected_landmarks.size()); // (4) check distance to the nearest marker const landmark_manager::Landmark nearest_marker = get_nearest_landmark(self_pose, map_landmarks); @@ -230,7 +230,7 @@ void LidarMarkerLocalizer::main_process(const PointCloud2::ConstSharedPtr & poin const double distance_from_self_pose_to_nearest_marker = std::abs(nearest_marker_pose_on_base_link.position.x); - diagnostics_module_->add_key_value( + diagnostics_interface_->add_key_value( "distance_self_pose_to_nearest_marker", distance_from_self_pose_to_nearest_marker); const bool is_exist_marker_within_self_pose = @@ -242,14 +242,14 @@ void LidarMarkerLocalizer::main_process(const PointCloud2::ConstSharedPtr & poin std::stringstream message; message << "Could not detect marker, because the distance from self_pose to nearest_marker " << "is too far (" << distance_from_self_pose_to_nearest_marker << " [m])."; - diagnostics_module_->update_level_and_message( + diagnostics_interface_->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::OK, message.str()); } else { std::stringstream message; message << "Could not detect marker, although the distance from self_pose to nearest_marker " << "is near (" << distance_from_self_pose_to_nearest_marker << " [m])."; RCLCPP_INFO_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1000, message.str()); - diagnostics_module_->update_level_and_message( + diagnostics_interface_->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); } return; @@ -279,13 +279,13 @@ void LidarMarkerLocalizer::main_process(const PointCloud2::ConstSharedPtr & poin const bool is_exist_marker_within_lanelet2_map = diff_norm < param_.limit_distance_from_self_pose_to_marker; - diagnostics_module_->add_key_value("distance_lanelet2_marker_to_detected_marker", diff_norm); + diagnostics_interface_->add_key_value("distance_lanelet2_marker_to_detected_marker", diff_norm); if (!is_exist_marker_within_lanelet2_map) { std::stringstream message; message << "The distance from lanelet2 to the detect marker is too far(" << diff_norm << " [m]). The limit is " << param_.limit_distance_from_self_pose_to_marker << "."; RCLCPP_INFO_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1000, message.str()); - diagnostics_module_->update_level_and_message( + diagnostics_interface_->update_level_and_message( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); return; } diff --git a/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.hpp b/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.hpp index d1482c6912592..1b5672cff9d04 100644 --- a/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.hpp +++ b/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.hpp @@ -15,8 +15,8 @@ #ifndef LIDAR_MARKER_LOCALIZER_HPP_ #define LIDAR_MARKER_LOCALIZER_HPP_ -#include "autoware/localization_util/diagnostics_module.hpp" #include "autoware/localization_util/smart_pose_buffer.hpp" +#include "autoware/universe_utils/ros/diagnostics_interface.hpp" #include @@ -134,7 +134,7 @@ class LidarMarkerLocalizer : public rclcpp::Node rclcpp::Publisher::SharedPtr pub_debug_pose_with_covariance_; rclcpp::Publisher::SharedPtr pub_marker_pointcloud_; - std::shared_ptr diagnostics_module_; + std::shared_ptr diagnostics_interface_; Param param_; bool is_activated_; diff --git a/localization/autoware_localization_error_monitor/CHANGELOG.rst b/localization/autoware_localization_error_monitor/CHANGELOG.rst index e9583916e2e8f..69833a04a8d3a 100644 --- a/localization/autoware_localization_error_monitor/CHANGELOG.rst +++ b/localization/autoware_localization_error_monitor/CHANGELOG.rst @@ -43,8 +43,8 @@ Changelog for package autoware_localization_error_monitor * unify package.xml version to 0.37.0 * refactor(localization_util)!: prefix package and namespace with autoware (`#8922 `_) add autoware prefix to localization_util -* fix(localization_error_monitor, system diag): fix to use diagnostics_module in localization_util (`#8543 `_) - * fix(localization_error_monitor): fix to use diagnostics_module in localization_util +* fix(localization_error_monitor, system diag): fix to use diagnostics_interface in localization_util (`#8543 `_) + * fix(localization_error_monitor): fix to use diagnostics_interface in localization_util * fix: update media * fix: update component name * fix: rename include file diff --git a/localization/autoware_localization_error_monitor/src/localization_error_monitor.cpp b/localization/autoware_localization_error_monitor/src/localization_error_monitor.cpp index 63edbe5f6a9c7..5ebcd105d57ba 100644 --- a/localization/autoware_localization_error_monitor/src/localization_error_monitor.cpp +++ b/localization/autoware_localization_error_monitor/src/localization_error_monitor.cpp @@ -59,7 +59,7 @@ LocalizationErrorMonitor::LocalizationErrorMonitor(const rclcpp::NodeOptions & o logger_configure_ = std::make_unique(this); diagnostics_error_monitor_ = - std::make_unique(this, "ellipse_error_status"); + std::make_unique(this, "ellipse_error_status"); } void LocalizationErrorMonitor::on_odom(nav_msgs::msg::Odometry::ConstSharedPtr input_msg) diff --git a/localization/autoware_localization_error_monitor/src/localization_error_monitor.hpp b/localization/autoware_localization_error_monitor/src/localization_error_monitor.hpp index 7b26573964b38..b38958c420b19 100644 --- a/localization/autoware_localization_error_monitor/src/localization_error_monitor.hpp +++ b/localization/autoware_localization_error_monitor/src/localization_error_monitor.hpp @@ -16,7 +16,7 @@ #define LOCALIZATION_ERROR_MONITOR_HPP_ #include "autoware/localization_util/covariance_ellipse.hpp" -#include "autoware/localization_util/diagnostics_module.hpp" +#include "autoware/universe_utils/ros/diagnostics_interface.hpp" #include #include @@ -39,7 +39,7 @@ class LocalizationErrorMonitor : public rclcpp::Node std::unique_ptr logger_configure_; - std::unique_ptr diagnostics_error_monitor_; + std::unique_ptr diagnostics_error_monitor_; double scale_; double error_ellipse_size_; diff --git a/localization/autoware_localization_util/CMakeLists.txt b/localization/autoware_localization_util/CMakeLists.txt index dd18f3cbad932..de62633124f3d 100644 --- a/localization/autoware_localization_util/CMakeLists.txt +++ b/localization/autoware_localization_util/CMakeLists.txt @@ -6,7 +6,6 @@ autoware_package() ament_auto_add_library(${PROJECT_NAME} SHARED src/util_func.cpp - src/diagnostics_module.cpp src/smart_pose_buffer.cpp src/tree_structured_parzen_estimator.cpp src/covariance_ellipse.cpp diff --git a/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/map_update_module.hpp b/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/map_update_module.hpp index d2dce42e3923e..bf8fce2b302c0 100644 --- a/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/map_update_module.hpp +++ b/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/map_update_module.hpp @@ -15,8 +15,8 @@ #ifndef AUTOWARE__NDT_SCAN_MATCHER__MAP_UPDATE_MODULE_HPP_ #define AUTOWARE__NDT_SCAN_MATCHER__MAP_UPDATE_MODULE_HPP_ -#include "autoware/localization_util/diagnostics_module.hpp" #include "autoware/localization_util/util_func.hpp" +#include "autoware/universe_utils/ros/diagnostics_interface.hpp" #include "hyper_parameters.hpp" #include "ndt_omp/multigrid_ndt_omp.h" #include "particle.hpp" @@ -42,7 +42,7 @@ namespace autoware::ndt_scan_matcher { -using DiagnosticsModule = autoware::localization_util::DiagnosticsModule; +using DiagnosticInterface = autoware::universe_utils::DiagnosticInterface; class MapUpdateModule { @@ -63,19 +63,19 @@ class MapUpdateModule void callback_timer( const bool is_activated, const std::optional & position, - std::unique_ptr & diagnostics_ptr); + std::unique_ptr & diagnostics_ptr); [[nodiscard]] bool should_update_map( const geometry_msgs::msg::Point & position, - std::unique_ptr & diagnostics_ptr); + std::unique_ptr & diagnostics_ptr); void update_map( const geometry_msgs::msg::Point & position, - std::unique_ptr & diagnostics_ptr); + std::unique_ptr & diagnostics_ptr); // Update the specified NDT bool update_ndt( const geometry_msgs::msg::Point & position, NdtType & ndt, - std::unique_ptr & diagnostics_ptr); + std::unique_ptr & diagnostics_ptr); void publish_partial_pcd_map(); rclcpp::Publisher::SharedPtr loaded_pcd_pub_; diff --git a/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_scan_matcher_core.hpp b/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_scan_matcher_core.hpp index 22b6bfb2ff740..25b7417ffbe3c 100644 --- a/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_scan_matcher_core.hpp +++ b/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_scan_matcher_core.hpp @@ -17,8 +17,8 @@ #define FMT_HEADER_ONLY -#include "autoware/localization_util/diagnostics_module.hpp" #include "autoware/localization_util/smart_pose_buffer.hpp" +#include "autoware/universe_utils/ros/diagnostics_interface.hpp" #include "hyper_parameters.hpp" #include "map_update_module.hpp" #include "ndt_omp/multigrid_ndt_omp.h" @@ -211,12 +211,12 @@ class NDTScanMatcher : public rclcpp::Node std::unique_ptr regularization_pose_buffer_; std::atomic is_activated_; - std::unique_ptr diagnostics_scan_points_; - std::unique_ptr diagnostics_initial_pose_; - std::unique_ptr diagnostics_regularization_pose_; - std::unique_ptr diagnostics_map_update_; - std::unique_ptr diagnostics_ndt_align_; - std::unique_ptr diagnostics_trigger_node_; + std::unique_ptr diagnostics_scan_points_; + std::unique_ptr diagnostics_initial_pose_; + std::unique_ptr diagnostics_regularization_pose_; + std::unique_ptr diagnostics_map_update_; + std::unique_ptr diagnostics_ndt_align_; + std::unique_ptr diagnostics_trigger_node_; std::unique_ptr map_update_module_; std::unique_ptr logger_configure_; diff --git a/localization/autoware_ndt_scan_matcher/src/map_update_module.cpp b/localization/autoware_ndt_scan_matcher/src/map_update_module.cpp index 25b51b55aebd7..eea0b8f3d06c4 100644 --- a/localization/autoware_ndt_scan_matcher/src/map_update_module.cpp +++ b/localization/autoware_ndt_scan_matcher/src/map_update_module.cpp @@ -56,7 +56,7 @@ MapUpdateModule::MapUpdateModule( void MapUpdateModule::callback_timer( const bool is_activated, const std::optional & position, - std::unique_ptr & diagnostics_ptr) + std::unique_ptr & diagnostics_ptr) { // check is_activated diagnostics_ptr->add_key_value("is_activated", is_activated); @@ -86,7 +86,8 @@ void MapUpdateModule::callback_timer( } bool MapUpdateModule::should_update_map( - const geometry_msgs::msg::Point & position, std::unique_ptr & diagnostics_ptr) + const geometry_msgs::msg::Point & position, + std::unique_ptr & diagnostics_ptr) { last_update_position_mtx_.lock(); @@ -141,7 +142,8 @@ bool MapUpdateModule::out_of_map_range(const geometry_msgs::msg::Point & positio } void MapUpdateModule::update_map( - const geometry_msgs::msg::Point & position, std::unique_ptr & diagnostics_ptr) + const geometry_msgs::msg::Point & position, + std::unique_ptr & diagnostics_ptr) { diagnostics_ptr->add_key_value("is_need_rebuild", need_rebuild_); @@ -229,7 +231,7 @@ void MapUpdateModule::update_map( bool MapUpdateModule::update_ndt( const geometry_msgs::msg::Point & position, NdtType & ndt, - std::unique_ptr & diagnostics_ptr) + std::unique_ptr & diagnostics_ptr) { diagnostics_ptr->add_key_value("maps_size_before", ndt.getCurrentMapIDs().size()); diff --git a/localization/autoware_ndt_scan_matcher/src/ndt_scan_matcher_core.cpp b/localization/autoware_ndt_scan_matcher/src/ndt_scan_matcher_core.cpp index a1871023d525b..cef8724423bed 100644 --- a/localization/autoware_ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/autoware_ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -49,9 +49,9 @@ using autoware::localization_util::matrix4f_to_pose; using autoware::localization_util::point_to_vector3d; using autoware::localization_util::pose_to_matrix4f; -using autoware::localization_util::DiagnosticsModule; using autoware::localization_util::SmartPoseBuffer; using autoware::localization_util::TreeStructuredParzenEstimator; +using autoware::universe_utils::DiagnosticInterface; tier4_debug_msgs::msg::Float32Stamped make_float32_stamped( const builtin_interfaces::msg::Time & stamp, const float data) @@ -141,7 +141,7 @@ NDTScanMatcher::NDTScanMatcher(const rclcpp::NodeOptions & options) std::make_unique(this->get_logger(), value_as_unlimited, value_as_unlimited); diagnostics_regularization_pose_ = - std::make_unique(this, "regularization_pose_subscriber_status"); + std::make_unique(this, "regularization_pose_subscriber_status"); } sensor_aligned_pose_pub_ = @@ -209,13 +209,13 @@ NDTScanMatcher::NDTScanMatcher(const rclcpp::NodeOptions & options) map_update_module_ = std::make_unique(this, &ndt_ptr_mtx_, ndt_ptr_, param_.dynamic_map_loading); - diagnostics_scan_points_ = std::make_unique(this, "scan_matching_status"); + diagnostics_scan_points_ = std::make_unique(this, "scan_matching_status"); diagnostics_initial_pose_ = - std::make_unique(this, "initial_pose_subscriber_status"); - diagnostics_map_update_ = std::make_unique(this, "map_update_status"); - diagnostics_ndt_align_ = std::make_unique(this, "ndt_align_service_status"); + std::make_unique(this, "initial_pose_subscriber_status"); + diagnostics_map_update_ = std::make_unique(this, "map_update_status"); + diagnostics_ndt_align_ = std::make_unique(this, "ndt_align_service_status"); diagnostics_trigger_node_ = - std::make_unique(this, "trigger_node_service_status"); + std::make_unique(this, "trigger_node_service_status"); logger_configure_ = std::make_unique(this); } diff --git a/localization/autoware_pose_initializer/package.xml b/localization/autoware_pose_initializer/package.xml index eeeb46a8db3e5..de3ecd880ea45 100644 --- a/localization/autoware_pose_initializer/package.xml +++ b/localization/autoware_pose_initializer/package.xml @@ -21,7 +21,6 @@ autoware_component_interface_specs autoware_component_interface_utils - autoware_localization_util autoware_map_height_fitter autoware_motion_utils autoware_universe_utils diff --git a/localization/autoware_pose_initializer/src/pose_initializer_core.cpp b/localization/autoware_pose_initializer/src/pose_initializer_core.cpp index 5e9c68d2acc80..67d5c447c09b6 100644 --- a/localization/autoware_pose_initializer/src/pose_initializer_core.cpp +++ b/localization/autoware_pose_initializer/src/pose_initializer_core.cpp @@ -40,7 +40,7 @@ PoseInitializer::PoseInitializer(const rclcpp::NodeOptions & options) output_pose_covariance_ = get_covariance_parameter(this, "output_pose_covariance"); gnss_particle_covariance_ = get_covariance_parameter(this, "gnss_particle_covariance"); - diagnostics_pose_reliable_ = std::make_unique( + diagnostics_pose_reliable_ = std::make_unique( this, "pose_initializer_status"); if (declare_parameter("ekf_enabled")) { diff --git a/localization/autoware_pose_initializer/src/pose_initializer_core.hpp b/localization/autoware_pose_initializer/src/pose_initializer_core.hpp index 28d2eae08c3f1..5305bcc3ad347 100644 --- a/localization/autoware_pose_initializer/src/pose_initializer_core.hpp +++ b/localization/autoware_pose_initializer/src/pose_initializer_core.hpp @@ -15,10 +15,9 @@ #ifndef POSE_INITIALIZER_CORE_HPP_ #define POSE_INITIALIZER_CORE_HPP_ -#include "autoware/localization_util/diagnostics_module.hpp" - #include #include +#include #include #include @@ -61,7 +60,7 @@ class PoseInitializer : public rclcpp::Node std::unique_ptr ekf_localization_trigger_; std::unique_ptr ndt_localization_trigger_; std::unique_ptr logger_configure_; - std::unique_ptr diagnostics_pose_reliable_; + std::unique_ptr diagnostics_pose_reliable_; double stop_check_duration_; void change_node_trigger(bool flag, bool need_spin = false); From 3d53032a827477c9c2cb83e80be3222e1d64bf03 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Wed, 25 Dec 2024 12:38:28 +0900 Subject: [PATCH 100/334] chore(autoware_multi_object_tracker): fix autoware univserse documentation page (#9772) * feat: Add descriptions for confidence thresholds in multi_object_tracker_node schema Signed-off-by: Taekjin LEE * feat: Update multi_object_tracker_node schema with confidence threshold descriptions Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE --- perception/autoware_multi_object_tracker/README.md | 5 +++++ .../schema/multi_object_tracker_node.schema.json | 11 +++++++++-- 2 files changed, 14 insertions(+), 2 deletions(-) diff --git a/perception/autoware_multi_object_tracker/README.md b/perception/autoware_multi_object_tracker/README.md index afb1598645733..3f83817f6509f 100644 --- a/perception/autoware_multi_object_tracker/README.md +++ b/perception/autoware_multi_object_tracker/README.md @@ -69,7 +69,12 @@ Multiple inputs are pre-defined in the input channel parameters (described below ### Core Parameters +- Node + {{ json_to_markdown("perception/autoware_multi_object_tracker/schema/multi_object_tracker_node.schema.json") }} + +- Association + {{ json_to_markdown("perception/autoware_multi_object_tracker/schema/data_association_matrix.schema.json") }} #### Simulation parameters diff --git a/perception/autoware_multi_object_tracker/schema/multi_object_tracker_node.schema.json b/perception/autoware_multi_object_tracker/schema/multi_object_tracker_node.schema.json index f32db284c1738..d3bca273da803 100644 --- a/perception/autoware_multi_object_tracker/schema/multi_object_tracker_node.schema.json +++ b/perception/autoware_multi_object_tracker/schema/multi_object_tracker_node.schema.json @@ -86,38 +86,45 @@ "properties": { "UNKNOWN": { "type": "number", + "description": "Number of measurements to consider tracker as confident for unknown object classes.", "default": 3 }, "CAR": { "type": "number", + "description": "Number of measurements to consider tracker as confident for car object classes.", "default": 3 }, "TRUCK": { "type": "number", + "description": "Number of measurements to consider tracker as confident for truck object classes.", "default": 3 }, "BUS": { "type": "number", + "description": "Number of measurements to consider tracker as confident for bus object classes.", "default": 3 }, "TRAILER": { "type": "number", + "description": "Number of measurements to consider tracker as confident for trailer object classes.", "default": 3 }, "MOTORBIKE": { "type": "number", + "description": "Number of measurements to consider tracker as confident for motorbike object classes.", "default": 3 }, "BICYCLE": { "type": "number", + "description": "Number of measurements to consider tracker as confident for bicycle object classes.", "default": 3 }, "PEDESTRIAN": { "type": "number", + "description": "Number of measurements to consider tracker as confident for pedestrian object classes.", "default": 3 } - }, - "description": "Number of measurements to consider tracker as confident for different object classes." + } }, "publish_processing_time": { "type": "boolean", From b764c57c89182bbf631c51bec10cc0826dcc13fd Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 25 Dec 2024 13:58:37 +0900 Subject: [PATCH 101/334] feat(behavior_path_planner): use autoware internal stamped messages (#9750) * feat(behavior_path_planner): use autoware internal stamped messages Signed-off-by: Takayuki Murooka * fix universe_utils Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../universe_utils/ros/debug_traits.hpp | 62 +++++++++++++++++++ common/autoware_universe_utils/package.xml | 1 + .../behavior_path_planner/planner_manager.hpp | 6 +- .../package.xml | 1 + 4 files changed, 68 insertions(+), 2 deletions(-) diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/ros/debug_traits.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/ros/debug_traits.hpp index 8420f930e0ce9..5878641676d9f 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/ros/debug_traits.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/ros/debug_traits.hpp @@ -15,6 +15,16 @@ #ifndef AUTOWARE__UNIVERSE_UTILS__ROS__DEBUG_TRAITS_HPP_ #define AUTOWARE__UNIVERSE_UTILS__ROS__DEBUG_TRAITS_HPP_ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #include #include #include @@ -84,6 +94,58 @@ template <> struct is_debug_message : std::true_type { }; + +template <> +struct is_debug_message : std::true_type +{ +}; + +template <> +struct is_debug_message +: std::true_type +{ +}; + +template <> +struct is_debug_message : std::true_type +{ +}; + +template <> +struct is_debug_message +: std::true_type +{ +}; + +template <> +struct is_debug_message : std::true_type +{ +}; + +template <> +struct is_debug_message : std::true_type +{ +}; + +template <> +struct is_debug_message : std::true_type +{ +}; + +template <> +struct is_debug_message : std::true_type +{ +}; + +template <> +struct is_debug_message : std::true_type +{ +}; + +template <> +struct is_debug_message : std::true_type +{ +}; } // namespace autoware::universe_utils::debug_traits #endif // AUTOWARE__UNIVERSE_UTILS__ROS__DEBUG_TRAITS_HPP_ diff --git a/common/autoware_universe_utils/package.xml b/common/autoware_universe_utils/package.xml index d04e1a57e78ab..0e7b892a8c689 100644 --- a/common/autoware_universe_utils/package.xml +++ b/common/autoware_universe_utils/package.xml @@ -12,6 +12,7 @@ ament_cmake_auto autoware_cmake + autoware_internal_debug_msgs autoware_internal_msgs autoware_perception_msgs autoware_planning_msgs diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/planner_manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/planner_manager.hpp index 3bed1e6a88bd8..741202590779c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/planner_manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/planner_manager.hpp @@ -25,6 +25,8 @@ #include #include +#include +#include #include #include @@ -44,8 +46,8 @@ using tier4_planning_msgs::msg::PathWithLaneId; using SceneModulePtr = std::shared_ptr; using SceneModuleManagerPtr = std::shared_ptr; using DebugPublisher = autoware::universe_utils::DebugPublisher; -using DebugDoubleMsg = tier4_debug_msgs::msg::Float64Stamped; -using DebugStringMsg = tier4_debug_msgs::msg::StringStamped; +using DebugDoubleMsg = autoware_internal_debug_msgs::msg::Float64Stamped; +using DebugStringMsg = autoware_internal_debug_msgs::msg::StringStamped; struct SceneModuleUpdateInfo { diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/package.xml b/planning/behavior_path_planner/autoware_behavior_path_planner/package.xml index 6141480d1597a..7b7e2438a3fd6 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/package.xml @@ -40,6 +40,7 @@ autoware_behavior_path_planner_common autoware_freespace_planning_algorithms autoware_frenet_planner + autoware_internal_debug_msgs autoware_interpolation autoware_lane_departure_checker autoware_lanelet2_extension From fe597e2a5118f267260785bd4fc68c9648d31835 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 25 Dec 2024 15:10:41 +0900 Subject: [PATCH 102/334] fix(autoware_motion_velocity_obstacle_velocity_limiter_module): fix bugprone-exception-escape (#9779) * fix: bugprone-error Signed-off-by: kobayu858 * fix: cppcheck Signed-off-by: kobayu858 * fix: cpplint Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../collision_checker_benchmark.cpp | 85 ++++++++++--------- 1 file changed, 47 insertions(+), 38 deletions(-) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/benchmarks/collision_checker_benchmark.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/benchmarks/collision_checker_benchmark.cpp index 79b817c51169c..1d980e220ccef 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/benchmarks/collision_checker_benchmark.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/benchmarks/collision_checker_benchmark.cpp @@ -16,6 +16,7 @@ #include "../src/types.hpp" #include +#include #include #include @@ -55,45 +56,53 @@ polygon_t random_polygon() int main() { - Obstacles obstacles; - std::vector polygons; - polygons.reserve(100); - for (auto i = 0; i < 100; ++i) { - polygons.push_back(random_polygon()); - } - for (auto nb_lines = 1lu; nb_lines < 1000lu; nb_lines += 10) { - obstacles.lines.push_back(random_line()); - obstacles.points.clear(); - for (auto nb_points = 1lu; nb_points < 1000lu; nb_points += 10) { - obstacles.points.push_back(random_point()); - const auto rtt_constr_start = std::chrono::system_clock::now(); - CollisionChecker rtree_collision_checker(obstacles, 0, 0); - const auto rtt_constr_end = std::chrono::system_clock::now(); - const auto naive_constr_start = std::chrono::system_clock::now(); - CollisionChecker naive_collision_checker(obstacles, nb_points + 1, nb_lines * 100); - const auto naive_constr_end = std::chrono::system_clock::now(); - const auto rtt_check_start = std::chrono::system_clock::now(); - for (const auto & polygon : polygons) - // cppcheck-suppress unreadVariable - const auto rtree_result = rtree_collision_checker.intersections(polygon); - const auto rtt_check_end = std::chrono::system_clock::now(); - const auto naive_check_start = std::chrono::system_clock::now(); - for (const auto & polygon : polygons) - // cppcheck-suppress unreadVariable - const auto naive_result = naive_collision_checker.intersections(polygon); - const auto naive_check_end = std::chrono::system_clock::now(); - const auto rtt_constr_time = - std::chrono::duration_cast(rtt_constr_end - rtt_constr_start); - const auto naive_constr_time = - std::chrono::duration_cast(naive_constr_end - naive_constr_start); - const auto rtt_check_time = - std::chrono::duration_cast(rtt_check_end - rtt_check_start); - const auto naive_check_time = - std::chrono::duration_cast(naive_check_end - naive_check_start); - std::printf( - "%lu, %lu, %ld, %ld, %ld, %ld\n", nb_lines, nb_points, rtt_constr_time.count(), - rtt_check_time.count(), naive_constr_time.count(), naive_check_time.count()); + try { + Obstacles obstacles; + std::vector polygons; + polygons.reserve(100); + for (auto i = 0; i < 100; ++i) { + polygons.push_back(random_polygon()); + } + for (auto nb_lines = 1lu; nb_lines < 1000lu; nb_lines += 10) { + obstacles.lines.push_back(random_line()); + obstacles.points.clear(); + for (auto nb_points = 1lu; nb_points < 1000lu; nb_points += 10) { + obstacles.points.push_back(random_point()); + const auto rtt_constr_start = std::chrono::system_clock::now(); + CollisionChecker rtree_collision_checker(obstacles, 0, 0); + const auto rtt_constr_end = std::chrono::system_clock::now(); + const auto naive_constr_start = std::chrono::system_clock::now(); + CollisionChecker naive_collision_checker(obstacles, nb_points + 1, nb_lines * 100); + const auto naive_constr_end = std::chrono::system_clock::now(); + const auto rtt_check_start = std::chrono::system_clock::now(); + for (const auto & polygon : polygons) + // cppcheck-suppress unreadVariable + const auto rtree_result = rtree_collision_checker.intersections(polygon); + const auto rtt_check_end = std::chrono::system_clock::now(); + const auto naive_check_start = std::chrono::system_clock::now(); + for (const auto & polygon : polygons) + // cppcheck-suppress unreadVariable + const auto naive_result = naive_collision_checker.intersections(polygon); + const auto naive_check_end = std::chrono::system_clock::now(); + const auto rtt_constr_time = + std::chrono::duration_cast(rtt_constr_end - rtt_constr_start); + const auto naive_constr_time = std::chrono::duration_cast( + naive_constr_end - naive_constr_start); + const auto rtt_check_time = + std::chrono::duration_cast(rtt_check_end - rtt_check_start); + const auto naive_check_time = + std::chrono::duration_cast(naive_check_end - naive_check_start); + std::printf( + "%lu, %lu, %ld, %ld, %ld, %ld\n", nb_lines, nb_points, rtt_constr_time.count(), + rtt_check_time.count(), naive_constr_time.count(), naive_check_time.count()); + } } + } catch (const std::exception & e) { + std::cerr << "Exception in main(): " << e.what() << std::endl; + return {}; + } catch (...) { + std::cerr << "Unknown exception in main()" << std::endl; + return {}; } return 0; } From d0c39d38cbf9d6f352f352aef41dc3f7b3590e1f Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 25 Dec 2024 15:12:44 +0900 Subject: [PATCH 103/334] fix(autoware_processing_time_checker): fix bugprone-exception-escape (#9780) * fix: bugprone-error Signed-off-by: kobayu858 * fix: cpplint Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../src/processing_time_checker.cpp | 79 ++++++++++--------- 1 file changed, 43 insertions(+), 36 deletions(-) diff --git a/system/autoware_processing_time_checker/src/processing_time_checker.cpp b/system/autoware_processing_time_checker/src/processing_time_checker.cpp index 1e3f04af8fa89..5455cdab422d5 100644 --- a/system/autoware_processing_time_checker/src/processing_time_checker.cpp +++ b/system/autoware_processing_time_checker/src/processing_time_checker.cpp @@ -20,6 +20,7 @@ #include #include #include +#include #include #include @@ -103,45 +104,51 @@ ProcessingTimeChecker::~ProcessingTimeChecker() return; } - // generate json data - nlohmann::json j; - for (const auto & accumulator_iterator : processing_time_accumulator_map_) { - const auto module_name = accumulator_iterator.first; - const auto processing_time_accumulator = accumulator_iterator.second; - j[module_name + "/min"] = processing_time_accumulator.min(); - j[module_name + "/max"] = processing_time_accumulator.max(); - j[module_name + "/mean"] = processing_time_accumulator.mean(); - j[module_name + "/count"] = processing_time_accumulator.count(); - j[module_name + "/description"] = "processing time of " + module_name + "[ms]"; - } + try { + // generate json data + nlohmann::json j; + for (const auto & accumulator_iterator : processing_time_accumulator_map_) { + const auto module_name = accumulator_iterator.first; + const auto processing_time_accumulator = accumulator_iterator.second; + j[module_name + "/min"] = processing_time_accumulator.min(); + j[module_name + "/max"] = processing_time_accumulator.max(); + j[module_name + "/mean"] = processing_time_accumulator.mean(); + j[module_name + "/count"] = processing_time_accumulator.count(); + j[module_name + "/description"] = "processing time of " + module_name + "[ms]"; + } - // get output folder - const std::string output_folder_str = - rclcpp::get_logging_directory().string() + "/autoware_metrics"; - if (!std::filesystem::exists(output_folder_str)) { - if (!std::filesystem::create_directories(output_folder_str)) { - RCLCPP_ERROR( - this->get_logger(), "Failed to create directories: %s", output_folder_str.c_str()); - return; + // get output folder + const std::string output_folder_str = + rclcpp::get_logging_directory().string() + "/autoware_metrics"; + if (!std::filesystem::exists(output_folder_str)) { + if (!std::filesystem::create_directories(output_folder_str)) { + RCLCPP_ERROR( + this->get_logger(), "Failed to create directories: %s", output_folder_str.c_str()); + return; + } } - } - // get time stamp - std::time_t now_time_t = std::chrono::system_clock::to_time_t(std::chrono::system_clock::now()); - std::tm * local_time = std::localtime(&now_time_t); - std::ostringstream oss; - oss << std::put_time(local_time, "%Y-%m-%d-%H-%M-%S"); - std::string cur_time_str = oss.str(); - - // Write metrics .json to file - const std::string output_file_str = - output_folder_str + "/autoware_processing_time_checker-" + cur_time_str + ".json"; - std::ofstream f(output_file_str); - if (f.is_open()) { - f << j.dump(4); - f.close(); - } else { - RCLCPP_ERROR(this->get_logger(), "Failed to open file: %s", output_file_str.c_str()); + // get time stamp + std::time_t now_time_t = std::chrono::system_clock::to_time_t(std::chrono::system_clock::now()); + std::tm * local_time = std::localtime(&now_time_t); + std::ostringstream oss; + oss << std::put_time(local_time, "%Y-%m-%d-%H-%M-%S"); + std::string cur_time_str = oss.str(); + + // Write metrics .json to file + const std::string output_file_str = + output_folder_str + "/autoware_processing_time_checker-" + cur_time_str + ".json"; + std::ofstream f(output_file_str); + if (f.is_open()) { + f << j.dump(4); + f.close(); + } else { + RCLCPP_ERROR(this->get_logger(), "Failed to open file: %s", output_file_str.c_str()); + } + } catch (const std::exception & e) { + std::cerr << "Exception in ProcessingTimeChecker: " << e.what() << std::endl; + } catch (...) { + std::cerr << "Unknown exception in ProcessingTimeChecker" << std::endl; } } From c11d613278ab3c7f7cfe014a6dcaf1ac1d4954ae Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 25 Dec 2024 15:18:21 +0900 Subject: [PATCH 104/334] fix(autoware_objects_of_interest_marker_interface): fix bugprone-branch-clone (#9671) Signed-off-by: kobayu858 --- .../src/objects_of_interest_marker_interface.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/autoware_objects_of_interest_marker_interface/src/objects_of_interest_marker_interface.cpp b/planning/autoware_objects_of_interest_marker_interface/src/objects_of_interest_marker_interface.cpp index cbdb2542b97e7..e18190a8bf9e7 100644 --- a/planning/autoware_objects_of_interest_marker_interface/src/objects_of_interest_marker_interface.cpp +++ b/planning/autoware_objects_of_interest_marker_interface/src/objects_of_interest_marker_interface.cpp @@ -76,14 +76,14 @@ ColorRGBA ObjectsOfInterestMarkerInterface::getColor( const ColorName & color_name, const float alpha) { switch (color_name) { + case ColorName::GRAY: + return coloring::getGray(alpha); case ColorName::GREEN: return coloring::getGreen(alpha); case ColorName::AMBER: return coloring::getAmber(alpha); case ColorName::RED: return coloring::getRed(alpha); - case ColorName::GRAY: - return coloring::getGray(alpha); default: return coloring::getGray(alpha); } From d2a9531b4a86be0ae10b8207a6c615aca575b105 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> Date: Wed, 25 Dec 2024 15:23:50 +0900 Subject: [PATCH 105/334] test(autoware_behavior_path_start_planner_module): add unit tests for shift shift pull out planner (#9776) feat(behavior_path_planner): add unit tests for ShiftPullOut path planning Signed-off-by: kyoichi-sugahara --- .../autoware_planning_test_manager_utils.hpp | 6 +- .../shift_pull_out.hpp | 2 + .../test/test_shift_pull_out.cpp | 179 ++++++++++++++++++ 3 files changed, 184 insertions(+), 3 deletions(-) create mode 100644 planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_shift_pull_out.cpp diff --git a/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager_utils.hpp b/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager_utils.hpp index 5081b14dda63b..8a075594ebd3a 100644 --- a/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager_utils.hpp +++ b/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager_utils.hpp @@ -35,7 +35,7 @@ using geometry_msgs::msg::Pose; using nav_msgs::msg::Odometry; using RouteSections = std::vector; -Pose createPoseFromLaneID( +inline Pose createPoseFromLaneID( const lanelet::Id & lane_id, const std::string & package_name = "autoware_test_utils", const std::string & map_filename = "lanelet2_map.osm") { @@ -70,7 +70,7 @@ Pose createPoseFromLaneID( // Function to create a route from given start and goal lanelet ids // start pose and goal pose are set to the middle of the lanelet -LaneletRoute makeBehaviorRouteFromLaneId( +inline LaneletRoute makeBehaviorRouteFromLaneId( const int & start_lane_id, const int & goal_lane_id, const std::string & package_name = "autoware_test_utils", const std::string & map_filename = "lanelet2_map.osm") @@ -119,7 +119,7 @@ LaneletRoute makeBehaviorRouteFromLaneId( return route; } -Odometry makeInitialPoseFromLaneId(const lanelet::Id & lane_id) +inline Odometry makeInitialPoseFromLaneId(const lanelet::Id & lane_id) { Odometry current_odometry; current_odometry.pose.pose = createPoseFromLaneID(lane_id); diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/shift_pull_out.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/shift_pull_out.hpp index d1b4c9dabdd7f..5b4f78b252d22 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/shift_pull_out.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/shift_pull_out.hpp @@ -56,6 +56,8 @@ class ShiftPullOut : public PullOutPlannerBase std::shared_ptr lane_departure_checker_; + friend class TestShiftPullOut; + private: // Calculate longitudinal distance based on the acceleration limit, curvature limit, and the // minimum distance requirement. diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_shift_pull_out.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_shift_pull_out.cpp new file mode 100644 index 0000000000000..156cf62f9ac4a --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_shift_pull_out.cpp @@ -0,0 +1,179 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include + +using autoware::behavior_path_planner::ShiftPullOut; +using autoware::behavior_path_planner::StartPlannerParameters; +using autoware::lane_departure_checker::LaneDepartureChecker; +using autoware::test_utils::get_absolute_path_to_config; +using autoware_planning_msgs::msg::LaneletRoute; +using RouteSections = std::vector; +using autoware_planning_test_manager::utils::makeBehaviorRouteFromLaneId; + +namespace autoware::behavior_path_planner +{ + +class TestShiftPullOut : public ::testing::Test +{ +public: + std::optional call_plan( + const Pose & start_pose, const Pose & goal_pose, PlannerDebugData & planner_debug_data) + { + return shift_pull_out_->plan(start_pose, goal_pose, planner_debug_data); + } + +protected: + void SetUp() override + { + rclcpp::init(0, nullptr); + node_ = rclcpp::Node::make_shared("shift_pull_out", make_node_options()); + + initialize_lane_departure_checker(); + initialize_shift_pull_out_planner(); + } + + void TearDown() override { rclcpp::shutdown(); } + + PlannerData make_planner_data( + const Pose & start_pose, const int route_start_lane_id, const int route_goal_lane_id) + { + PlannerData planner_data; + planner_data.init_parameters(*node_); + + // Load a sample lanelet map and create a route handler + const auto shoulder_map_path = autoware::test_utils::get_absolute_path_to_lanelet_map( + "autoware_test_utils", "road_shoulder/lanelet2_map.osm"); + const auto map_bin_msg = autoware::test_utils::make_map_bin_msg(shoulder_map_path, 0.5); + auto route_handler = std::make_shared(map_bin_msg); + + // Set up current odometry at start pose + auto odometry = std::make_shared(); + odometry->pose.pose = start_pose; + odometry->header.frame_id = "map"; + planner_data.self_odometry = odometry; + + // Setup route + const auto route = makeBehaviorRouteFromLaneId( + route_start_lane_id, route_goal_lane_id, "autoware_test_utils", + "road_shoulder/lanelet2_map.osm"); + route_handler->setRoute(route); + + // Update planner data with the route handler + planner_data.route_handler = route_handler; + + return planner_data; + } + + // Member variables + std::shared_ptr node_; + std::shared_ptr shift_pull_out_; + std::shared_ptr lane_departure_checker_; + +private: + rclcpp::NodeOptions make_node_options() const + { + // Load common configuration files + auto node_options = rclcpp::NodeOptions{}; + + const auto common_param_path = + get_absolute_path_to_config("autoware_test_utils", "test_common.param.yaml"); + const auto nearest_search_param_path = + get_absolute_path_to_config("autoware_test_utils", "test_nearest_search.param.yaml"); + const auto vehicle_info_param_path = + get_absolute_path_to_config("autoware_test_utils", "test_vehicle_info.param.yaml"); + const auto behavior_path_planner_param_path = get_absolute_path_to_config( + "autoware_behavior_path_planner", "behavior_path_planner.param.yaml"); + const auto drivable_area_expansion_param_path = get_absolute_path_to_config( + "autoware_behavior_path_planner", "drivable_area_expansion.param.yaml"); + const auto scene_module_manager_param_path = get_absolute_path_to_config( + "autoware_behavior_path_planner", "scene_module_manager.param.yaml"); + const auto start_planner_param_path = get_absolute_path_to_config( + "autoware_behavior_path_start_planner_module", "start_planner.param.yaml"); + + autoware::test_utils::updateNodeOptions( + node_options, {common_param_path, nearest_search_param_path, vehicle_info_param_path, + behavior_path_planner_param_path, drivable_area_expansion_param_path, + scene_module_manager_param_path, start_planner_param_path}); + + return node_options; + } + + void initialize_lane_departure_checker() + { + const auto vehicle_info = + autoware::vehicle_info_utils::VehicleInfoUtils(*node_).getVehicleInfo(); + lane_departure_checker_ = std::make_shared(); + lane_departure_checker_->setVehicleInfo(vehicle_info); + + autoware::lane_departure_checker::Param lane_departure_checker_params{}; + lane_departure_checker_->setParam(lane_departure_checker_params); + } + + void initialize_shift_pull_out_planner() + { + auto parameters = StartPlannerParameters::init(*node_); + + auto time_keeper = std::make_shared(); + shift_pull_out_ = + std::make_shared(*node_, parameters, lane_departure_checker_, time_keeper); + } +}; + +TEST_F(TestShiftPullOut, GenerateValidShiftPullOutPath) +{ + const auto start_pose = + geometry_msgs::build() + .position(geometry_msgs::build().x(362.181).y(362.164).z(100.000)) + .orientation( + geometry_msgs::build().x(0.0).y(0.0).z(0.709650).w( + 0.704554)); + + const auto goal_pose = + geometry_msgs::build() + .position(geometry_msgs::build().x(365.658).y(507.253).z(100.000)) + .orientation( + geometry_msgs::build().x(0.0).y(0.0).z(0.705897).w( + 0.708314)); + const auto planner_data = make_planner_data(start_pose, 4619, 4635); + + shift_pull_out_->setPlannerData(std::make_shared(planner_data)); + + // Plan the pull out path + PlannerDebugData debug_data; + auto result = call_plan(start_pose, goal_pose, debug_data); + + // Assert that a valid shift pull out path is generated + ASSERT_TRUE(result.has_value()) << "shift pull out path generation failed."; + EXPECT_EQ(result->partial_paths.size(), 1UL) + << "Generated shift pull out path does not have the expected number of partial paths."; + EXPECT_EQ(debug_data.conditions_evaluation.back(), "success") + << "shift pull out path planning did not succeed."; +} + +} // namespace autoware::behavior_path_planner From e0531b8e5dbd14c8b9c9fb22e487fd81c311d89c Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Wed, 25 Dec 2024 15:28:30 +0900 Subject: [PATCH 106/334] feat(autoware_default_adapi): release adapi v1.6.0 (#9704) * feat: reject clearing route during autonomous mode Signed-off-by: Takagi, Isamu * feat: modify check and relay door service Signed-off-by: Takagi, Isamu * fix door condition Signed-off-by: Takagi, Isamu * fix error and add option Signed-off-by: Takagi, Isamu * update v1.6.0 Signed-off-by: Takagi, Isamu --------- Signed-off-by: Takagi, Isamu --- .../include/autoware/adapi_specs/vehicle.hpp | 2 +- .../config/default_adapi.param.yaml | 4 ++ .../launch/test_default_adapi.launch.xml | 5 ++ .../autoware_default_adapi/src/interface.cpp | 2 +- system/autoware_default_adapi/src/routing.cpp | 11 ++++- system/autoware_default_adapi/src/routing.hpp | 1 + .../src/vehicle_door.cpp | 46 ++++++++++++++++--- .../src/vehicle_door.hpp | 37 +++++++++++---- .../test/node/interface_version.py | 2 +- 9 files changed, 90 insertions(+), 20 deletions(-) create mode 100644 system/autoware_default_adapi/launch/test_default_adapi.launch.xml diff --git a/common/autoware_adapi_specs/include/autoware/adapi_specs/vehicle.hpp b/common/autoware_adapi_specs/include/autoware/adapi_specs/vehicle.hpp index a7568d54b5e1a..dc907b6610cde 100644 --- a/common/autoware_adapi_specs/include/autoware/adapi_specs/vehicle.hpp +++ b/common/autoware_adapi_specs/include/autoware/adapi_specs/vehicle.hpp @@ -41,7 +41,7 @@ struct VehicleStatus using Message = autoware_adapi_v1_msgs::msg::VehicleStatus; static constexpr char name[] = "/api/vehicle/status"; static constexpr size_t depth = 1; - static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE; + static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT; static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE; }; diff --git a/system/autoware_default_adapi/config/default_adapi.param.yaml b/system/autoware_default_adapi/config/default_adapi.param.yaml index ddbf103878953..f2782e313e785 100644 --- a/system/autoware_default_adapi/config/default_adapi.param.yaml +++ b/system/autoware_default_adapi/config/default_adapi.param.yaml @@ -6,3 +6,7 @@ ros__parameters: require_accept_start: false stop_check_duration: 1.0 + +/adapi/node/vehicle_door: + ros__parameters: + check_autoware_control: true diff --git a/system/autoware_default_adapi/launch/test_default_adapi.launch.xml b/system/autoware_default_adapi/launch/test_default_adapi.launch.xml new file mode 100644 index 0000000000000..3a00beeb623d4 --- /dev/null +++ b/system/autoware_default_adapi/launch/test_default_adapi.launch.xml @@ -0,0 +1,5 @@ + + + + + diff --git a/system/autoware_default_adapi/src/interface.cpp b/system/autoware_default_adapi/src/interface.cpp index fb924f06f42ea..6535dcfca30fd 100644 --- a/system/autoware_default_adapi/src/interface.cpp +++ b/system/autoware_default_adapi/src/interface.cpp @@ -21,7 +21,7 @@ InterfaceNode::InterfaceNode(const rclcpp::NodeOptions & options) : Node("interf { const auto on_interface_version = [](auto, auto res) { res->major = 1; - res->minor = 5; + res->minor = 6; res->patch = 0; }; diff --git a/system/autoware_default_adapi/src/routing.cpp b/system/autoware_default_adapi/src/routing.cpp index 4eaa98376b147..93f31ff693344 100644 --- a/system/autoware_default_adapi/src/routing.cpp +++ b/system/autoware_default_adapi/src/routing.cpp @@ -68,6 +68,7 @@ RoutingNode::RoutingNode(const rclcpp::NodeOptions & options) : Node("routing", adaptor.init_cli(cli_operation_mode_, group_cli_); adaptor.init_sub(sub_operation_mode_, this, &RoutingNode::on_operation_mode); + is_autoware_control_ = false; is_auto_mode_ = false; state_.state = State::Message::UNKNOWN; } @@ -85,6 +86,7 @@ void RoutingNode::change_stop_mode() void RoutingNode::on_operation_mode(const OperationModeState::Message::ConstSharedPtr msg) { + is_autoware_control_ = msg->is_autoware_control_enabled; is_auto_mode_ = msg->mode == OperationModeState::Message::AUTONOMOUS; } @@ -119,7 +121,14 @@ void RoutingNode::on_clear_route( const autoware::adapi_specs::routing::ClearRoute::Service::Request::SharedPtr req, const autoware::adapi_specs::routing::ClearRoute::Service::Response::SharedPtr res) { - change_stop_mode(); + // For safety, do not clear the route while it is in use. + // https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-interfaces/ad-api/list/api/routing/clear_route/ + if (is_auto_mode_ && is_autoware_control_) { + res->status.success = false; + res->status.code = ResponseStatus::UNKNOWN; + res->status.message = "The route cannot be cleared while it is in use."; + return; + } res->status = conversion::convert_call(cli_clear_route_, req); } diff --git a/system/autoware_default_adapi/src/routing.hpp b/system/autoware_default_adapi/src/routing.hpp index 10eed606a5f6b..f37b8a978a235 100644 --- a/system/autoware_default_adapi/src/routing.hpp +++ b/system/autoware_default_adapi/src/routing.hpp @@ -52,6 +52,7 @@ class RoutingNode : public rclcpp::Node Cli cli_clear_route_; Cli cli_operation_mode_; Sub sub_operation_mode_; + bool is_autoware_control_; bool is_auto_mode_; State::Message state_; diff --git a/system/autoware_default_adapi/src/vehicle_door.cpp b/system/autoware_default_adapi/src/vehicle_door.cpp index 23588bdf4597a..d3ad5d8ddccee 100644 --- a/system/autoware_default_adapi/src/vehicle_door.cpp +++ b/system/autoware_default_adapi/src/vehicle_door.cpp @@ -24,18 +24,50 @@ VehicleDoorNode::VehicleDoorNode(const rclcpp::NodeOptions & options) { const auto adaptor = autoware::component_interface_utils::NodeAdaptor(this); group_cli_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); - adaptor.relay_service(cli_command_, srv_command_, group_cli_, 3.0); - adaptor.relay_service(cli_layout_, srv_layout_, group_cli_, 3.0); + adaptor.relay_service(cli_layout_, srv_layout_, group_cli_); + adaptor.init_cli(cli_command_, group_cli_); + adaptor.init_srv(srv_command_, this, &VehicleDoorNode::on_command); adaptor.init_pub(pub_status_); adaptor.init_sub(sub_status_, this, &VehicleDoorNode::on_status); + adaptor.init_sub(sub_operation_mode_, this, &VehicleDoorNode::on_operation_mode); + + check_autoware_control_ = declare_parameter("check_autoware_control"); + is_autoware_control_ = false; + is_stop_mode_ = false; +} + +void VehicleDoorNode::on_operation_mode(const OperationModeState::Message::ConstSharedPtr msg) +{ + is_autoware_control_ = msg->is_autoware_control_enabled; + is_stop_mode_ = msg->mode == OperationModeState::Message::STOP; +} +void VehicleDoorNode::on_status(InternalDoorStatus::Message::ConstSharedPtr msg) +{ + utils::notify(pub_status_, status_, *msg, utils::ignore_stamp); } -void VehicleDoorNode::on_status( - autoware::component_interface_specs::vehicle::DoorStatus::Message::ConstSharedPtr msg) +void VehicleDoorNode::on_command( + const ExternalDoorCommand::Service::Request::SharedPtr req, + const ExternalDoorCommand::Service::Response::SharedPtr res) { - utils::notify( - pub_status_, status_, *msg, - utils::ignore_stamp); + // For safety, do not open the door if the vehicle is not stopped. + // https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-interfaces/ad-api/list/api/vehicle/doors/command/ + if (!is_stop_mode_ || (!is_autoware_control_ && check_autoware_control_)) { + bool is_open = false; + for (const auto & door : req->doors) { + if (door.command == autoware_adapi_v1_msgs::msg::DoorCommand::OPEN) { + is_open = true; + break; + } + } + if (is_open) { + res->status.success = false; + res->status.code = autoware_adapi_v1_msgs::msg::ResponseStatus::UNKNOWN; + res->status.message = "Doors cannot be opened if the vehicle is not stopped."; + return; + } + } + autoware::component_interface_utils::status::copy(cli_command_->call(req), res); } } // namespace autoware::default_adapi diff --git a/system/autoware_default_adapi/src/vehicle_door.hpp b/system/autoware_default_adapi/src/vehicle_door.hpp index 50312a38a4cb7..a75232a2b2c74 100644 --- a/system/autoware_default_adapi/src/vehicle_door.hpp +++ b/system/autoware_default_adapi/src/vehicle_door.hpp @@ -16,7 +16,9 @@ #define VEHICLE_DOOR_HPP_ #include +#include #include +#include #include #include @@ -33,16 +35,33 @@ class VehicleDoorNode : public rclcpp::Node explicit VehicleDoorNode(const rclcpp::NodeOptions & options); private: - void on_status( - autoware::component_interface_specs::vehicle::DoorStatus::Message::ConstSharedPtr msg); + using OperationModeState = autoware::component_interface_specs::system::OperationModeState; + using InternalDoorStatus = autoware::component_interface_specs::vehicle::DoorStatus; + using InternalDoorLayout = autoware::component_interface_specs::vehicle::DoorLayout; + using InternalDoorCommand = autoware::component_interface_specs::vehicle::DoorCommand; + using ExternalDoorStatus = autoware::adapi_specs::vehicle::DoorStatus; + using ExternalDoorLayout = autoware::adapi_specs::vehicle::DoorLayout; + using ExternalDoorCommand = autoware::adapi_specs::vehicle::DoorCommand; + + void on_operation_mode(const OperationModeState::Message::ConstSharedPtr msg); + void on_status(InternalDoorStatus::Message::ConstSharedPtr msg); + void on_command( + const ExternalDoorCommand::Service::Request::SharedPtr req, + const ExternalDoorCommand::Service::Response::SharedPtr res); + rclcpp::CallbackGroup::SharedPtr group_cli_; - Srv srv_command_; - Srv srv_layout_; - Pub pub_status_; - Cli cli_command_; - Cli cli_layout_; - Sub sub_status_; - std::optional status_; + Srv srv_command_; + Srv srv_layout_; + Pub pub_status_; + Cli cli_command_; + Cli cli_layout_; + Sub sub_status_; + std::optional status_; + + bool check_autoware_control_; + bool is_autoware_control_; + bool is_stop_mode_; + Sub sub_operation_mode_; }; } // namespace autoware::default_adapi diff --git a/system/autoware_default_adapi/test/node/interface_version.py b/system/autoware_default_adapi/test/node/interface_version.py index c91889149cb0e..8db70ca5cba9a 100644 --- a/system/autoware_default_adapi/test/node/interface_version.py +++ b/system/autoware_default_adapi/test/node/interface_version.py @@ -30,7 +30,7 @@ if response.major != 1: exit(1) -if response.minor != 5: +if response.minor != 6: exit(1) if response.patch != 0: exit(1) From 2579f3c436a8fb07bd4a12a685af22bb00397659 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 25 Dec 2024 15:58:42 +0900 Subject: [PATCH 107/334] feat(behavior_velocity_planner): use XXXStamped in autoware_internal_debug_msgs (#9744) * feat(behavior_velocity_planner): use XXXStamped in autoware_internal_debug_msgs Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../package.xml | 2 +- .../scripts/time_to_collision_plotter.py | 2 +- .../src/scene_crosswalk.cpp | 8 ++++---- .../src/scene_crosswalk.hpp | 5 +++-- .../package.xml | 1 + .../scripts/ttc.py | 2 +- .../src/scene_intersection.cpp | 11 ++++++----- .../src/scene_intersection.hpp | 12 +++++++----- .../src/scene_intersection_collision.cpp | 4 ++-- .../scene_module_interface.hpp | 4 ++-- .../package.xml | 1 + .../package.xml | 1 + .../src/debug.cpp | 2 +- .../src/debug.hpp | 8 ++++---- .../src/scene.hpp | 2 +- .../src/utils.hpp | 4 ++-- 16 files changed, 38 insertions(+), 31 deletions(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml index 699f80ec8356e..08bd8f91c7d71 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml @@ -23,6 +23,7 @@ autoware_behavior_velocity_planner_common autoware_grid_map_utils + autoware_internal_debug_msgs autoware_interpolation autoware_lanelet2_extension autoware_motion_utils @@ -41,7 +42,6 @@ pluginlib rclcpp sensor_msgs - tier4_debug_msgs visualization_msgs ament_cmake_ros diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/scripts/time_to_collision_plotter.py b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/scripts/time_to_collision_plotter.py index 8a9de1a563249..5b13b6f5752d3 100755 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/scripts/time_to_collision_plotter.py +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/scripts/time_to_collision_plotter.py @@ -19,10 +19,10 @@ from copy import deepcopy from ament_index_python.packages import get_package_share_directory +from autoware_internal_debug_msgs.msg import StringStamped import matplotlib.pyplot as plt import rclpy from rclpy.node import Node -from tier4_debug_msgs.msg import StringStamped import yaml diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 1bea0626b0b2f..07b2f1deff0c7 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -153,11 +153,11 @@ StopFactor createStopFactor( return stop_factor; } -tier4_debug_msgs::msg::StringStamped createStringStampedMessage( +autoware_internal_debug_msgs::msg::StringStamped createStringStampedMessage( const rclcpp::Time & now, const int64_t module_id_, const std::vector> & collision_points) { - tier4_debug_msgs::msg::StringStamped msg; + autoware_internal_debug_msgs::msg::StringStamped msg; msg.stamp = now; for (const auto & collision_point : collision_points) { std::stringstream ss; @@ -199,8 +199,8 @@ CrosswalkModule::CrosswalkModule( road_ = lanelet_map_ptr->laneletLayer.get(lane_id); - collision_info_pub_ = - node.create_publisher("~/debug/collision_info", 1); + collision_info_pub_ = node.create_publisher( + "~/debug/collision_info", 1); } bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index 9b771c0d503a4..b3fbc2f6cfaba 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -23,9 +23,9 @@ #include #include +#include #include #include -#include #include #include @@ -456,7 +456,8 @@ class CrosswalkModule : public SceneModuleInterface const int64_t module_id_; - rclcpp::Publisher::SharedPtr collision_info_pub_; + rclcpp::Publisher::SharedPtr + collision_info_pub_; lanelet::ConstLanelet crosswalk_; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml index b056f71614da3..7a64d1d6638ff 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml @@ -20,6 +20,7 @@ autoware_cmake autoware_behavior_velocity_planner_common + autoware_internal_debug_msgs autoware_interpolation autoware_lanelet2_extension autoware_motion_utils diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/scripts/ttc.py b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/scripts/ttc.py index 1eb6ae1ffafc1..c1bed003ea3a9 100755 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/scripts/ttc.py +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/scripts/ttc.py @@ -22,13 +22,13 @@ import time from PIL import Image +from autoware_internal_debug_msgs.msg import Float64MultiArrayStamped import imageio import matplotlib import matplotlib.pyplot as plt import numpy as np import rclpy from rclpy.node import Node -from tier4_debug_msgs.msg import Float64MultiArrayStamped matplotlib.use("TKAgg") diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp index 6f7841ebb0bbb..7c492a9dd42bf 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -88,10 +88,11 @@ IntersectionModule::IntersectionModule( static_occlusion_timeout_state_machine_.setState(StateMachine::State::STOP); } - ego_ttc_pub_ = node.create_publisher( + ego_ttc_pub_ = node.create_publisher( "~/debug/intersection/ego_ttc", 1); - object_ttc_pub_ = node.create_publisher( - "~/debug/intersection/object_ttc", 1); + object_ttc_pub_ = + node.create_publisher( + "~/debug/intersection/object_ttc", 1); } bool IntersectionModule::modifyPathVelocity(PathWithLaneId * path) @@ -231,7 +232,7 @@ DecisionResult IntersectionModule::modifyPathVelocityDetail(PathWithLaneId * pat // calculate the expected vehicle speed and obtain the spatiotemporal profile of ego to the // exit of intersection // ========================================================================================== - tier4_debug_msgs::msg::Float64MultiArrayStamped ego_ttc_time_array; + autoware_internal_debug_msgs::msg::Float64MultiArrayStamped ego_ttc_time_array; const auto time_distance_array = calcIntersectionPassingTime(*path, is_prioritized, intersection_stoplines, &ego_ttc_time_array); @@ -240,7 +241,7 @@ DecisionResult IntersectionModule::modifyPathVelocityDetail(PathWithLaneId * pat // passed each pass judge line for the first time, save current collision status for late // diagnosis // ========================================================================================== - tier4_debug_msgs::msg::Float64MultiArrayStamped object_ttc_time_array; + autoware_internal_debug_msgs::msg::Float64MultiArrayStamped object_ttc_time_array; updateObjectInfoManagerCollision( path_lanelets, time_distance_array, traffic_prioritized_level, safely_passed_1st_judge_line, safely_passed_2nd_judge_line, &object_ttc_time_array); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp index b718dd84d33af..164df7588bd68 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -27,7 +27,7 @@ #include #include -#include +#include #include #include @@ -748,7 +748,7 @@ class IntersectionModule : public SceneModuleInterface const PathLanelets & path_lanelets, const TimeDistanceArray & time_distance_array, const TrafficPrioritizedLevel & traffic_prioritized_level, const bool passed_1st_judge_line_first_time, const bool passed_2nd_judge_line_first_time, - tier4_debug_msgs::msg::Float64MultiArrayStamped * object_ttc_time_array); + autoware_internal_debug_msgs::msg::Float64MultiArrayStamped * object_ttc_time_array); void cutPredictPathWithinDuration( const builtin_interfaces::msg::Time & object_stamp, const double time_thr, @@ -809,13 +809,15 @@ class IntersectionModule : public SceneModuleInterface TimeDistanceArray calcIntersectionPassingTime( const tier4_planning_msgs::msg::PathWithLaneId & path, const bool is_prioritized, const IntersectionStopLines & intersection_stoplines, - tier4_debug_msgs::msg::Float64MultiArrayStamped * ego_ttc_array) const; + autoware_internal_debug_msgs::msg::Float64MultiArrayStamped * ego_ttc_array) const; /** @} */ mutable DebugData debug_data_; mutable InternalDebugData internal_debug_data_{}; - rclcpp::Publisher::SharedPtr ego_ttc_pub_; - rclcpp::Publisher::SharedPtr object_ttc_pub_; + rclcpp::Publisher::SharedPtr + ego_ttc_pub_; + rclcpp::Publisher::SharedPtr + object_ttc_pub_; }; } // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_collision.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_collision.cpp index 5a66bec15bab1..5103cd6cc46e4 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_collision.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_collision.cpp @@ -152,7 +152,7 @@ void IntersectionModule::updateObjectInfoManagerCollision( const IntersectionModule::TimeDistanceArray & time_distance_array, const IntersectionModule::TrafficPrioritizedLevel & traffic_prioritized_level, const bool passed_1st_judge_line_first_time, const bool passed_2nd_judge_line_first_time, - tier4_debug_msgs::msg::Float64MultiArrayStamped * object_ttc_time_array) + autoware_internal_debug_msgs::msg::Float64MultiArrayStamped * object_ttc_time_array) { const auto & intersection_lanelets = intersection_lanelets_.value(); @@ -815,7 +815,7 @@ std::optional IntersectionModule::checkAngleForTargetLanelets( IntersectionModule::TimeDistanceArray IntersectionModule::calcIntersectionPassingTime( const tier4_planning_msgs::msg::PathWithLaneId & path, const bool is_prioritized, const IntersectionStopLines & intersection_stoplines, - tier4_debug_msgs::msg::Float64MultiArrayStamped * ego_ttc_array) const + autoware_internal_debug_msgs::msg::Float64MultiArrayStamped * ego_ttc_array) const { const double intersection_velocity = planner_param_.collision_detection.velocity_profile.default_velocity; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp index fadda66f12562..4e898d9d28715 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp @@ -27,8 +27,8 @@ #include #include +#include #include -#include #include #include #include @@ -57,8 +57,8 @@ using autoware::objects_of_interest_marker_interface::ObjectsOfInterestMarkerInt using autoware::rtc_interface::RTCInterface; using autoware::universe_utils::DebugPublisher; using autoware::universe_utils::getOrDeclareParameter; +using autoware_internal_debug_msgs::msg::Float64Stamped; using builtin_interfaces::msg::Time; -using tier4_debug_msgs::msg::Float64Stamped; using tier4_planning_msgs::msg::PathWithLaneId; using tier4_rtc_msgs::msg::Module; using tier4_rtc_msgs::msg::State; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml index 6d94e20cfdb1b..a0b54cb879cab 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml @@ -20,6 +20,7 @@ eigen3_cmake_module autoware_adapi_v1_msgs + autoware_internal_debug_msgs autoware_interpolation autoware_lanelet2_extension autoware_map_msgs diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/package.xml index 90e1d32198854..b3ced8b2e9b9f 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/package.xml @@ -21,6 +21,7 @@ autoware_behavior_velocity_crosswalk_module autoware_behavior_velocity_planner_common + autoware_internal_debug_msgs autoware_motion_utils autoware_object_recognition_utils autoware_perception_msgs diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/debug.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/debug.cpp index 2823648e184d3..3f4b9f330e2d0 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/debug.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/debug.cpp @@ -316,7 +316,7 @@ void RunOutDebug::setAccelReason(const AccelReason & accel_reason) void RunOutDebug::publishDebugValue() { // publish debug values - tier4_debug_msgs::msg::Float32MultiArrayStamped debug_msg{}; + autoware_internal_debug_msgs::msg::Float32MultiArrayStamped debug_msg{}; debug_msg.stamp = node_.now(); for (const auto & v : debug_values_.getValues()) { debug_msg.data.push_back(v); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/debug.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/debug.hpp index 3e913f57f30c0..1ffa826c4d1d1 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/debug.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/debug.hpp @@ -18,17 +18,17 @@ #include -#include -#include +#include +#include #include #include #include namespace autoware::behavior_velocity_planner { +using autoware_internal_debug_msgs::msg::Float32MultiArrayStamped; +using autoware_internal_debug_msgs::msg::Int32Stamped; using sensor_msgs::msg::PointCloud2; -using tier4_debug_msgs::msg::Float32MultiArrayStamped; -using tier4_debug_msgs::msg::Int32Stamped; class DebugValues { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.hpp index 3673a215bb749..83123c71f461e 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.hpp @@ -32,10 +32,10 @@ namespace autoware::behavior_velocity_planner { +using autoware_internal_debug_msgs::msg::Float32Stamped; using autoware_perception_msgs::msg::PredictedObjects; using run_out_utils::PlannerParam; using run_out_utils::PoseWithRange; -using tier4_debug_msgs::msg::Float32Stamped; using tier4_planning_msgs::msg::PathPointWithLaneId; using tier4_planning_msgs::msg::PathWithLaneId; using BasicPolygons2d = std::vector; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/utils.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/utils.hpp index 1f948cc7faaa1..c48e4f867fac0 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/utils.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/utils.hpp @@ -21,10 +21,10 @@ #include #include +#include #include #include #include -#include #include #include @@ -39,11 +39,11 @@ using autoware::universe_utils::LineString2d; using autoware::universe_utils::Point2d; using autoware::universe_utils::Polygon2d; using autoware::vehicle_info_utils::VehicleInfo; +using autoware_internal_debug_msgs::msg::Float32Stamped; using autoware_perception_msgs::msg::ObjectClassification; using autoware_perception_msgs::msg::PredictedObjects; using autoware_perception_msgs::msg::Shape; using autoware_planning_msgs::msg::PathPoint; -using tier4_debug_msgs::msg::Float32Stamped; using tier4_planning_msgs::msg::PathWithLaneId; using PathPointsWithLaneId = std::vector; struct CommonParam From a7655bca2cebeccc37c638d464f367a712560015 Mon Sep 17 00:00:00 2001 From: mkquda <168697710+mkquda@users.noreply.github.com> Date: Wed, 25 Dec 2024 16:40:57 +0900 Subject: [PATCH 108/334] feat(lane_change): add info text to virtual wall (#9783) * specify reason for lane change stop line Signed-off-by: mohammad alqudah * add stop reason for incoming rear object Signed-off-by: mohammad alqudah --------- Signed-off-by: mohammad alqudah --- .../base_class.hpp | 6 ++++-- .../scene.hpp | 4 +++- .../src/interface.cpp | 8 ++------ .../src/scene.cpp | 20 ++++++++++--------- 4 files changed, 20 insertions(+), 18 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/base_class.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/base_class.hpp index ce2552a41d380..1061e07e516a2 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/base_class.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/base_class.hpp @@ -18,6 +18,7 @@ #include "autoware/behavior_path_lane_change_module/structs/debug.hpp" #include "autoware/behavior_path_lane_change_module/structs/path.hpp" #include "autoware/behavior_path_lane_change_module/utils/utils.hpp" +#include "autoware/behavior_path_planner_common/data_manager.hpp" #include "autoware/behavior_path_planner_common/interface/scene_module_interface.hpp" #include "autoware/behavior_path_planner_common/turn_signal_decider.hpp" #include "autoware/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" @@ -38,6 +39,7 @@ class TestNormalLaneChange; namespace autoware::behavior_path_planner { +using autoware::behavior_path_planner::PoseWithDetailOpt; using autoware::route_handler::Direction; using autoware::universe_utils::StopWatch; using geometry_msgs::msg::Point; @@ -222,7 +224,7 @@ class LaneChangeBase return direction_; } - std::optional getStopPose() const { return lane_change_stop_pose_; } + PoseWithDetailOpt getStopPose() const { return lane_change_stop_pose_; } void resetStopPose() { lane_change_stop_pose_ = std::nullopt; } @@ -282,7 +284,7 @@ class LaneChangeBase lane_change::CommonDataPtr common_data_ptr_; FilteredLanesObjects filtered_objects_{}; BehaviorModuleOutput prev_module_output_{}; - std::optional lane_change_stop_pose_{std::nullopt}; + PoseWithDetailOpt lane_change_stop_pose_{std::nullopt}; PathWithLaneId prev_approved_path_; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp index 6367caaea6829..5f1da79bc7ea0 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp @@ -18,6 +18,7 @@ #include "autoware/behavior_path_lane_change_module/structs/data.hpp" #include +#include #include #include @@ -157,7 +158,8 @@ class NormalLaneChange : public LaneChangeBase bool check_prepare_phase() const; - void set_stop_pose(const double arc_length_to_stop_pose, PathWithLaneId & path); + void set_stop_pose( + const double arc_length_to_stop_pose, PathWithLaneId & path, const std::string & reason = ""); void updateStopTime(); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp index d65e51997eb32..f80aad721a07c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp @@ -111,9 +111,7 @@ BehaviorModuleOutput LaneChangeInterface::plan() path_reference_ = std::make_shared(output.reference_path); *prev_approved_path_ = getPreviousModuleOutput().path; - const auto stop_pose_opt = module_type_->getStopPose(); - stop_pose_ = stop_pose_opt.has_value() ? PoseWithDetailOpt(PoseWithDetail(stop_pose_opt.value())) - : PoseWithDetailOpt(); + stop_pose_ = module_type_->getStopPose(); const auto & lane_change_debug = module_type_->getDebugData(); for (const auto & [uuid, data] : lane_change_debug.collision_check_objects_after_approval) { @@ -171,9 +169,7 @@ BehaviorModuleOutput LaneChangeInterface::planWaitingApproval() } path_reference_ = std::make_shared(out.reference_path); - const auto stop_pose_opt = module_type_->getStopPose(); - stop_pose_ = stop_pose_opt.has_value() ? PoseWithDetailOpt(PoseWithDetail(stop_pose_opt.value())) - : PoseWithDetailOpt(); + stop_pose_ = module_type_->getStopPose(); if (!module_type_->isValidPath()) { path_candidate_ = std::make_shared(); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index f8a200a9685a7..7f0e6d7f575f6 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -408,7 +408,7 @@ BehaviorModuleOutput NormalLaneChange::generateOutput() output.path.points, output.path.points.front().point.pose.position, getEgoPosition()); const auto stop_dist = -(current_velocity * current_velocity / (2.0 * planner_data_->parameters.min_acc)); - set_stop_pose(stop_dist + current_dist, output.path); + set_stop_pose(stop_dist + current_dist, output.path, "incoming rear object"); } else { insert_stop_point(get_target_lanes(), output.path); } @@ -471,7 +471,7 @@ void NormalLaneChange::insert_stop_point( if (!is_current_lane) { const auto arc_length_to_stop_pose = motion_utils::calcArcLength(path.points) - common_data_ptr_->transient_data.next_dist_buffer.min; - set_stop_pose(arc_length_to_stop_pose, path); + set_stop_pose(arc_length_to_stop_pose, path, "next lc terminal"); return; } @@ -514,8 +514,9 @@ void NormalLaneChange::insert_stop_point_on_current_lanes(PathWithLaneId & path) const auto dist_to_terminal_stop = std::min(dist_to_terminal_start, distance_to_last_fit_width); + const auto terminal_stop_reason = status_.is_valid_path ? "no safe path" : "no valid path"; if (filtered_objects_.current_lane.empty()) { - set_stop_pose(dist_to_terminal_stop, path); + set_stop_pose(dist_to_terminal_stop, path, terminal_stop_reason); return; } @@ -541,12 +542,12 @@ void NormalLaneChange::insert_stop_point_on_current_lanes(PathWithLaneId & path) const auto stop_arc_length_behind_obj = arc_length_to_current_obj - stop_margin; if (stop_arc_length_behind_obj < dist_to_target_lane_start) { - set_stop_pose(dist_to_target_lane_start, path); + set_stop_pose(dist_to_target_lane_start, path, "maintain distance to front object"); return; } if (stop_arc_length_behind_obj > dist_to_terminal_stop) { - set_stop_pose(dist_to_terminal_stop, path); + set_stop_pose(dist_to_terminal_stop, path, terminal_stop_reason); return; } @@ -562,11 +563,11 @@ void NormalLaneChange::insert_stop_point_on_current_lanes(PathWithLaneId & path) filtered_objects_.target_lane_leading, stop_arc_length_behind_obj, path); if (has_blocking_target_lane_obj || stop_arc_length_behind_obj <= 0.0) { - set_stop_pose(dist_to_terminal_stop, path); + set_stop_pose(dist_to_terminal_stop, path, terminal_stop_reason); return; } - set_stop_pose(stop_arc_length_behind_obj, path); + set_stop_pose(stop_arc_length_behind_obj, path, "maintain distance to front object"); } PathWithLaneId NormalLaneChange::getReferencePath() const @@ -1688,10 +1689,11 @@ bool NormalLaneChange::is_ego_stuck() const return has_object_blocking; } -void NormalLaneChange::set_stop_pose(const double arc_length_to_stop_pose, PathWithLaneId & path) +void NormalLaneChange::set_stop_pose( + const double arc_length_to_stop_pose, PathWithLaneId & path, const std::string & reason) { const auto stop_point = utils::insertStopPoint(arc_length_to_stop_pose, path); - lane_change_stop_pose_ = stop_point.point.pose; + lane_change_stop_pose_ = PoseWithDetailOpt(PoseWithDetail(stop_point.point.pose, reason)); } void NormalLaneChange::updateStopTime() From d4ced2a84c70f9755e78e77746e814bb3291077f Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Wed, 25 Dec 2024 17:02:18 +0900 Subject: [PATCH 109/334] refactor(lane_change): replace sstream to fmt for marker's text (#9775) Signed-off-by: Zulfaqar Azmi --- .../structs/debug.hpp | 4 +- .../package.xml | 1 + .../src/utils/markers.cpp | 54 +++++++------------ 3 files changed, 22 insertions(+), 37 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp index ea9807ad1616f..8738b412e18b9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp @@ -45,7 +45,7 @@ struct Debug double distance_to_end_of_current_lane{std::numeric_limits::max()}; double distance_to_lane_change_finished{std::numeric_limits::max()}; double distance_to_abort_finished{std::numeric_limits::max()}; - bool is_able_to_return_to_current_lane{false}; + bool is_able_to_return_to_current_lane{true}; bool is_stuck{false}; bool is_abort{false}; @@ -69,7 +69,7 @@ struct Debug distance_to_end_of_current_lane = std::numeric_limits::max(); distance_to_lane_change_finished = std::numeric_limits::max(); distance_to_abort_finished = std::numeric_limits::max(); - is_able_to_return_to_current_lane = false; + is_able_to_return_to_current_lane = true; is_stuck = false; is_abort = false; } diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/package.xml index dd4dbe63e41d4..fad98ecf8f8e1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/package.xml @@ -26,6 +26,7 @@ autoware_motion_utils autoware_rtc_interface autoware_universe_utils + fmt pluginlib range-v3 rclcpp diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp index 3277b8f031486..30af582175d14 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp @@ -25,10 +25,11 @@ #include #include +#include + #include #include #include -#include #include #include @@ -52,27 +53,6 @@ MarkerArray showAllValidLaneChangePath( const auto loop_size = std::min(lane_change_paths.size(), colors.size()); marker_array.markers.reserve(loop_size); - const auto info_prep_to_string = - [](const autoware::behavior_path_planner::lane_change::Info & info) -> std::string { - std::ostringstream ss_text; - ss_text << std::setprecision(3) << "vel: " << info.velocity.prepare - << "[m/s] | lon_acc: " << info.longitudinal_acceleration.prepare - << "[m/s2] | t: " << info.duration.prepare << "[s] | L: " << info.length.prepare - << "[m]"; - return ss_text.str(); - }; - - const auto info_lc_to_string = - [](const autoware::behavior_path_planner::lane_change::Info & info) -> std::string { - std::ostringstream ss_text; - ss_text << std::setprecision(3) << "vel: " << info.velocity.lane_changing - << "[m/s] | lon_acc: " << info.longitudinal_acceleration.lane_changing - << "[m/s2] | lat_acc: " << info.lateral_acceleration - << "[m/s2] | t: " << info.duration.lane_changing - << "[s] | L: " << info.length.lane_changing << "[m]"; - return ss_text.str(); - }; - for (std::size_t idx = 0; idx < loop_size; ++idx) { int32_t id{0}; const auto & lc_path = lane_change_paths.at(idx); @@ -91,19 +71,30 @@ MarkerArray showAllValidLaneChangePath( marker.points.push_back(point.point.pose.position); } + const auto & info = lc_path.info; auto text_marker = createDefaultMarker( "map", current_time, ns_with_idx, ++id, visualization_msgs::msg::Marker::TEXT_VIEW_FACING, createMarkerScale(0.1, 0.1, 0.8), colors::yellow()); const auto prep_idx = points.size() / 4; text_marker.pose = points.at(prep_idx).point.pose; text_marker.pose.position.z += 2.0; - text_marker.text = info_prep_to_string(lc_path.info); + text_marker.text = fmt::format( + "vel: {vel:.3f}[m/s] | lon_acc: {lon_acc:.3f}[m/s2] | t: {time:.3f}[s] | L: {length:.3f}[m]", + fmt::arg("vel", info.velocity.prepare), + fmt::arg("lon_acc", info.longitudinal_acceleration.prepare), + fmt::arg("time", info.duration.prepare), fmt::arg("length", info.length.prepare)); marker_array.markers.push_back(text_marker); const auto lc_idx = points.size() / 2; text_marker.id = ++id; text_marker.pose = points.at(lc_idx).point.pose; - text_marker.text = info_lc_to_string(lc_path.info); + text_marker.text = fmt::format( + "vel: {vel:.3f}[m/s] | lon_acc: {lon_acc:.3f}[m/s2] | lat_acc: {lat_acc:.3f}[m/s2] | t: " + "{time:.3f}[s] | L: {length:.3f}[m]", + fmt::arg("vel", info.velocity.lane_changing), + fmt::arg("lon_acc", info.longitudinal_acceleration.lane_changing), + fmt::arg("lat_acc", info.lateral_acceleration), fmt::arg("time", info.duration.lane_changing), + fmt::arg("length", info.length.lane_changing)); marker_array.markers.push_back(text_marker); marker_array.markers.push_back(marker); @@ -186,17 +177,10 @@ MarkerArray showExecutionInfo(const Debug & debug_data, const geometry_msgs::msg safety_check_info_text.pose = ego_pose; safety_check_info_text.pose.position.z += 4.0; - std::ostringstream ss; - - ss << "\nDistToEndOfCurrentLane: " << std::setprecision(5) - << debug_data.distance_to_end_of_current_lane - << "\nDistToLaneChangeFinished: " << debug_data.distance_to_lane_change_finished - << (debug_data.is_stuck ? "\nVehicleStuck" : "") - << (debug_data.is_able_to_return_to_current_lane ? "\nAbleToReturnToCurrentLane" : "") - << (debug_data.is_abort ? "\nAborting" : "") - << "\nDistanceToAbortFinished: " << debug_data.distance_to_abort_finished; - - safety_check_info_text.text = ss.str(); + safety_check_info_text.text = fmt::format( + "{stuck} | {return_lane} | {abort}", fmt::arg("stuck", debug_data.is_stuck ? "is stuck" : ""), + fmt::arg("return_lane", debug_data.is_able_to_return_to_current_lane ? "" : "can't return"), + fmt::arg("abort", debug_data.is_abort ? "aborting" : "")); marker_array.markers.push_back(safety_check_info_text); return marker_array; } From 2465d07acccdeb30d8a561764c1fbd4d238740db Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Wed, 25 Dec 2024 17:33:58 +0900 Subject: [PATCH 110/334] fix(perception): fix perception docs (#9766) * fix: fix perception docs Signed-off-by: vividf * fix: fix missing parameter in schema Signed-off-by: vividf * Update perception/autoware_object_merger/schema/data_association_matrix.schema.json Co-authored-by: Taekjin LEE * Update perception/autoware_object_merger/schema/data_association_matrix.schema.json Co-authored-by: Taekjin LEE * Update perception/autoware_object_merger/schema/data_association_matrix.schema.json Co-authored-by: Taekjin LEE * Update perception/autoware_object_merger/schema/data_association_matrix.schema.json Co-authored-by: Taekjin LEE * style(pre-commit): autofix * chore: seperate paramters for different nodes Signed-off-by: vividf --------- Signed-off-by: vividf Co-authored-by: Taekjin LEE Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- perception/autoware_object_merger/README.md | 8 + .../data_association_matrix.schema.json | 61 +++++- .../object_association_merger.schema.json | 9 +- .../schema/overlapped_judge.schema.json | 33 ++- .../README.md | 2 +- .../README.md | 29 ++- ...chronized_grid_map_fusion_node.schema.json | 196 ++++++++++-------- 7 files changed, 220 insertions(+), 118 deletions(-) diff --git a/perception/autoware_object_merger/README.md b/perception/autoware_object_merger/README.md index c65353efa3a91..a78cd70052707 100644 --- a/perception/autoware_object_merger/README.md +++ b/perception/autoware_object_merger/README.md @@ -25,8 +25,16 @@ The successive shortest path algorithm is used to solve the data association pro ## Parameters +- object association merger + {{ json_to_markdown("perception/autoware_object_merger/schema/object_association_merger.schema.json") }} + +- data association matrix + {{ json_to_markdown("perception/autoware_object_merger/schema/data_association_matrix.schema.json") }} + +- overlapped judge + {{ json_to_markdown("perception/autoware_object_merger/schema/overlapped_judge.schema.json") }} ## Tips diff --git a/perception/autoware_object_merger/schema/data_association_matrix.schema.json b/perception/autoware_object_merger/schema/data_association_matrix.schema.json index 68dc977224ba5..52f6aa3d8c37c 100644 --- a/perception/autoware_object_merger/schema/data_association_matrix.schema.json +++ b/perception/autoware_object_merger/schema/data_association_matrix.schema.json @@ -2,8 +2,8 @@ "$schema": "http://json-schema.org/draft-07/schema#", "title": "Data Association Matrix Parameters", "type": "object", - "properties": { - "ros__parameters": { + "definitions": { + "data_association_matrix": { "type": "object", "properties": { "can_assign_matrix": { @@ -11,31 +11,72 @@ "items": { "type": "number" }, - "description": "Assignment table for data association" + "description": "Assignment table for data association.", + "default": [ + 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 0, 0, 0, 0, 1, 1, 1, 1, 0, 0, 0, 0, 1, 1, 1, 1, + 0, 0, 0, 0, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 0, 0, 0, 0, 0, 1, 1, 1, 0, 0, + 0, 0, 0, 1, 1, 1 + ] }, "max_dist_matrix": { "type": "array", "items": { "type": "number" }, - "description": "Maximum distance table for data association" + "description": "Maximum distance table for data association.", + "default": [ + 4.0, 4.0, 5.0, 5.0, 5.0, 2.0, 2.0, 2.0, 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, 5.0, + 5.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, 5.0, 5.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, 5.0, 5.0, + 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, 2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 3.0, 2.0, 1.0, 1.0, + 1.0, 1.0, 3.0, 3.0, 3.0, 2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0 + ] }, "max_rad_matrix": { "type": "array", "items": { - "type": "number" + "type": "number", + "minimum": 0.0 }, - "description": "Maximum angle table for data association. If value is greater than pi, it will be ignored." + "description": "Maximum angle table for data association. If value is greater than pi, it will be ignored.", + "default": [ + 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 1.047, 1.047, 1.047, 1.047, 3.15, + 3.15, 3.15, 3.15, 1.047, 1.047, 1.047, 1.047, 3.15, 3.15, 3.15, 3.15, 1.047, 1.047, + 1.047, 1.047, 3.15, 3.15, 3.15, 3.15, 1.047, 1.047, 1.047, 1.047, 3.15, 3.15, 3.15, + 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, + 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15 + ] }, "min_iou_matrix": { "type": "array", "items": { - "type": "number" + "type": "number", + "minimum": 0.0 }, - "description": "Minimum IoU threshold matrix for data association. If value is negative, it will be ignored." + "description": "Minimum IoU threshold matrix for data association. If value is negative, it will be ignored.", + "default": [ + 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.3, 0.2, 0.2, 0.2, 0.1, 0.1, 0.1, 0.1, + 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, 0.1, 0.2, + 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, + 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1 + ] + } + }, + "required": ["can_assign_matrix", "max_dist_matrix", "max_rad_matrix", "min_iou_matrix"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/data_association_matrix" } }, - "required": ["can_assign_matrix", "max_dist_matrix", "max_rad_matrix", "min_iou_matrix"] + "required": ["ros__parameters"], + "additionalProperties": false } - } + }, + "required": ["/**"], + "additionalProperties": false } diff --git a/perception/autoware_object_merger/schema/object_association_merger.schema.json b/perception/autoware_object_merger/schema/object_association_merger.schema.json index 11090fab9c7b3..c31cb8866b8cc 100644 --- a/perception/autoware_object_merger/schema/object_association_merger.schema.json +++ b/perception/autoware_object_merger/schema/object_association_merger.schema.json @@ -45,7 +45,8 @@ "remove_overlapped_unknown_objects", "base_link_frame_id", "priority_mode" - ] + ], + "additionalProperties": false } }, "properties": { @@ -56,8 +57,10 @@ "$ref": "#/definitions/object_association_merger" } }, - "required": ["ros__parameters"] + "required": ["ros__parameters"], + "additionalProperties": false } }, - "required": ["/**"] + "required": ["/**"], + "additionalProperties": false } diff --git a/perception/autoware_object_merger/schema/overlapped_judge.schema.json b/perception/autoware_object_merger/schema/overlapped_judge.schema.json index b65464c6201d1..b8ed9f313eb3a 100644 --- a/perception/autoware_object_merger/schema/overlapped_judge.schema.json +++ b/perception/autoware_object_merger/schema/overlapped_judge.schema.json @@ -2,8 +2,8 @@ "$schema": "http://json-schema.org/draft-07/schema#", "title": "Overlapped Judge Parameters", "type": "object", - "properties": { - "ros__parameters": { + "definitions": { + "overlapped_judge": { "type": "object", "properties": { "distance_threshold_list": { @@ -11,17 +11,36 @@ "items": { "type": "number" }, - "description": "Distance threshold for each class used in judging overlap." + "description": "Distance threshold for each class used in judging overlap.", + "default": [9.0, 9.0, 9.0, 9.0, 9.0, 9.0, 9.0, 9.0] }, "generalized_iou_threshold": { "type": "array", "items": { - "type": "number" + "type": "number", + "minimum": -1.0, + "maximum": 1.0 }, - "description": "Generalized IoU threshold for each class." + "description": "Generalized IoU threshold for each class.", + "default": [-0.1, -0.1, -0.1, -0.6, -0.6, -0.1, -0.1, -0.1] + } + }, + "required": ["distance_threshold_list", "generalized_iou_threshold"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/overlapped_judge" } }, - "required": ["distance_threshold_list", "generalized_iou_threshold"] + "required": ["ros__parameters"], + "additionalProperties": false } - } + }, + "required": ["/**"], + "additionalProperties": false } diff --git a/perception/autoware_occupancy_grid_map_outlier_filter/README.md b/perception/autoware_occupancy_grid_map_outlier_filter/README.md index 7de2cc1dce92c..b920aa6908946 100644 --- a/perception/autoware_occupancy_grid_map_outlier_filter/README.md +++ b/perception/autoware_occupancy_grid_map_outlier_filter/README.md @@ -40,7 +40,7 @@ The following video is a sample. Yellow points are high occupancy probability, g ## Parameters -{{ json_to_markdown("perception/occupancy_grid_map_outlier_filter/schema/occupancy_grid_map_outlier_filter.schema.json") }} +{{ json_to_markdown("perception/autoware_occupancy_grid_map_outlier_filter/schema/occupancy_grid_map_outlier_filter.schema.json") }} ## Assumptions / Known limits diff --git a/perception/autoware_probabilistic_occupancy_grid_map/README.md b/perception/autoware_probabilistic_occupancy_grid_map/README.md index 575411bcbd220..3637dcb10daeb 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/README.md +++ b/perception/autoware_probabilistic_occupancy_grid_map/README.md @@ -21,12 +21,29 @@ You may need to choose `scan_origin_frame` and `gridmap_origin_frame` which mean ### Parameters -{{ json_to_markdown("perception/autoware_probabilistic_occupancy_grid_map/schema/binary_bayes_filter_updater.schema.json") }} -{{ json_to_markdown("perception/autoware_probabilistic_occupancy_grid_map/schema/grid_map.schema.json") }} -{{ json_to_markdown("perception/autoware_probabilistic_occupancy_grid_map/schema/laserscan_based_occupancy_grid_map.schema.json") }} -{{ json_to_markdown("perception/autoware_probabilistic_occupancy_grid_map/schema/multi_lidar_pointcloud_based_occupancy_grid_map.schema.json") }} -{{ json_to_markdown("perception/autoware_probabilistic_occupancy_grid_map/schema/pointcloud_based_occupancy_grid_map.schema.json") }} -{{ json_to_markdown("perception/autoware_probabilistic_occupancy_grid_map/schema/synchronized_grid_map_fusion_node.schema.json") }} +- binary bayes filter updater + + {{ json_to_markdown("perception/autoware_probabilistic_occupancy_grid_map/schema/binary_bayes_filter_updater.schema.json") }} + +- grid map + + {{ json_to_markdown("perception/autoware_probabilistic_occupancy_grid_map/schema/grid_map.schema.json") }} + +- laserscan based occupancy grid map + + {{ json_to_markdown("perception/autoware_probabilistic_occupancy_grid_map/schema/laserscan_based_occupancy_grid_map.schema.json") }} + +- multi lidar pointcloud based occupancy grid map + + {{ json_to_markdown("perception/autoware_probabilistic_occupancy_grid_map/schema/multi_lidar_pointcloud_based_occupancy_grid_map.schema.json") }} + +- pointcloud based occupancy grid map + + {{ json_to_markdown("perception/autoware_probabilistic_occupancy_grid_map/schema/pointcloud_based_occupancy_grid_map.schema.json") }} + +- synchronized grid map fusion + + {{ json_to_markdown("perception/autoware_probabilistic_occupancy_grid_map/schema/synchronized_grid_map_fusion_node.schema.json") }} ### Downsample input pointcloud(Optional) diff --git a/perception/autoware_probabilistic_occupancy_grid_map/schema/synchronized_grid_map_fusion_node.schema.json b/perception/autoware_probabilistic_occupancy_grid_map/schema/synchronized_grid_map_fusion_node.schema.json index 14f4305f55de8..de7c1e194ed42 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/schema/synchronized_grid_map_fusion_node.schema.json +++ b/perception/autoware_probabilistic_occupancy_grid_map/schema/synchronized_grid_map_fusion_node.schema.json @@ -2,104 +2,118 @@ "$schema": "http://json-schema.org/draft-07/schema#", "title": "Parameters for Synchronized Grid Map Fusion Node", "type": "object", + "definitions": { + "synchronized_grid_map_fusion": { + "type": "object", + "properties": { + "fusion_input_ogm_topics": { + "type": "array", + "description": "List of fusion input occupancy grid map topics.", + "items": { + "type": "string" + }, + "default": ["topic1", "topic2"] + }, + "input_ogm_reliabilities": { + "type": "array", + "description": "Reliability of each sensor for fusion.", + "items": { + "type": "number", + "minimum": 0.0, + "maximum": 1.0 + }, + "default": [0.8, 0.2] + }, + "fusion_method": { + "type": "string", + "description": "Method for occupancy grid map fusion.", + "enum": ["overwrite", "log-odds", "dempster-shafer"], + "default": "overwrite" + }, + "match_threshold_sec": { + "type": "number", + "description": "Time threshold for matching in seconds.", + "default": 0.01 + }, + "timeout_sec": { + "type": "number", + "description": "Timeout for synchronization in seconds.", + "default": 0.1 + }, + "input_offset_sec": { + "type": "array", + "description": "Offset for each input in seconds.", + "items": { + "type": "number" + }, + "default": [0.0, 0.0] + }, + "map_frame_": { + "type": "string", + "description": "The frame ID of the map.", + "default": "map" + }, + "base_link_frame_": { + "type": "string", + "description": "The frame ID of the base link.", + "default": "base_link" + }, + "grid_map_origin_frame_": { + "type": "string", + "description": "The frame ID of the grid map origin.", + "default": "base_link" + }, + "fusion_map_length_x": { + "type": "number", + "description": "The length of the fusion map in the x direction.", + "default": 100.0 + }, + "fusion_map_length_y": { + "type": "number", + "description": "The length of the fusion map in the y direction.", + "default": 100.0 + }, + "fusion_map_resolution": { + "type": "number", + "description": "The resolution of the fusion map.", + "default": 0.5 + }, + "publish_processing_time_detail": { + "type": "boolean", + "description": "True for showing detail of publish processing time.", + "default": false + } + }, + "required": [ + "fusion_input_ogm_topics", + "input_ogm_reliabilities", + "fusion_method", + "match_threshold_sec", + "timeout_sec", + "input_offset_sec", + "map_frame_", + "base_link_frame_", + "grid_map_origin_frame_", + "fusion_map_length_x", + "fusion_map_length_y", + "fusion_map_resolution", + "publish_processing_time_detail" + ], + "additionalProperties": false + } + }, "properties": { "/**": { "type": "object", "properties": { "ros__parameters": { - "type": "object", - "properties": { - "fusion_input_ogm_topics": { - "type": "array", - "description": "List of fusion input occupancy grid map topics.", - "items": { - "type": "string" - }, - "default": ["topic1", "topic2"] - }, - "input_ogm_reliabilities": { - "type": "array", - "description": "Reliability of each sensor for fusion.", - "items": { - "type": "number", - "minimum": 0.0, - "maximum": 1.0 - }, - "default": [0.8, 0.2] - }, - "fusion_method": { - "type": "string", - "description": "Method for occupancy grid map fusion.", - "enum": ["overwrite", "log-odds", "dempster-shafer"], - "default": "overwrite" - }, - "match_threshold_sec": { - "type": "number", - "description": "Time threshold for matching in seconds.", - "default": 0.01 - }, - "timeout_sec": { - "type": "number", - "description": "Timeout for synchronization in seconds.", - "default": 0.1 - }, - "input_offset_sec": { - "type": "array", - "description": "Offset for each input in seconds.", - "items": { - "type": "number" - }, - "default": [0.0, 0.0] - }, - "map_frame_": { - "type": "string", - "description": "The frame ID of the map.", - "default": "map" - }, - "base_link_frame_": { - "type": "string", - "description": "The frame ID of the base link.", - "default": "base_link" - }, - "grid_map_origin_frame_": { - "type": "string", - "description": "The frame ID of the grid map origin.", - "default": "base_link" - }, - "fusion_map_length_x": { - "type": "number", - "description": "The length of the fusion map in the x direction.", - "default": 100.0 - }, - "fusion_map_length_y": { - "type": "number", - "description": "The length of the fusion map in the y direction.", - "default": 100.0 - }, - "fusion_map_resolution": { - "type": "number", - "description": "The resolution of the fusion map.", - "default": 0.5 - } - }, - "required": [ - "fusion_input_ogm_topics", - "input_ogm_reliabilities", - "fusion_method", - "match_threshold_sec", - "timeout_sec", - "input_offset_sec", - "map_frame_", - "base_link_frame_", - "grid_map_origin_frame_", - "fusion_map_length_x", - "fusion_map_length_y", - "fusion_map_resolution" - ] + "$ref": "#/definitions/synchronized_grid_map_fusion" } }, - "required": ["ros__parameters"] + "required": ["ros__parameters"], + "additionalProperties": false } }, - "required": ["/**"] + "required": ["/**"], + "additionalProperties": false } From aaad09f15b936b475108f9419e1a438629cd68ac Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Wed, 25 Dec 2024 18:05:37 +0900 Subject: [PATCH 111/334] fix(static_avoidance): add optional check (#9782) Signed-off-by: Zulfaqar Azmi --- .../src/shift_line_generator.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp index 2aba986ab680d..52d5ee49c9a68 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp @@ -264,7 +264,9 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( AvoidOutlines outlines; for (auto & o : data.target_objects) { if (!o.avoid_margin.has_value()) { - if (data.red_signal_lane.value().id() == o.overhang_lanelet.id()) { + if ( + data.red_signal_lane.has_value() && + data.red_signal_lane.value().id() == o.overhang_lanelet.id()) { o.info = ObjectInfo::LIMIT_DRIVABLE_SPACE_TEMPORARY; } else { o.info = ObjectInfo::INSUFFICIENT_DRIVABLE_SPACE; From 1586372c7aa9d8e0c4adb7c6cc3ca049c664f98c Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Wed, 25 Dec 2024 18:11:54 +0900 Subject: [PATCH 112/334] fix(autoware_pointcloud_preprocessor): fix autoware pointcloud preprocessor docs (#9765) * fix downsample and passthrough Signed-off-by: vividf * fix: fix blockage-diag docs that page is not shown Signed-off-by: vividf --------- Signed-off-by: vividf --- .../docs/{blockage_diag.md => blockage-diag.md} | 0 .../autoware_pointcloud_preprocessor/docs/downsample-filter.md | 2 +- .../docs/passthrough-filter.md | 3 +-- .../schema/blockage_diag_node.schema.json | 3 ++- .../schema/distortion_corrector_node.schema.json | 2 +- 5 files changed, 5 insertions(+), 5 deletions(-) rename sensing/autoware_pointcloud_preprocessor/docs/{blockage_diag.md => blockage-diag.md} (100%) diff --git a/sensing/autoware_pointcloud_preprocessor/docs/blockage_diag.md b/sensing/autoware_pointcloud_preprocessor/docs/blockage-diag.md similarity index 100% rename from sensing/autoware_pointcloud_preprocessor/docs/blockage_diag.md rename to sensing/autoware_pointcloud_preprocessor/docs/blockage-diag.md diff --git a/sensing/autoware_pointcloud_preprocessor/docs/downsample-filter.md b/sensing/autoware_pointcloud_preprocessor/docs/downsample-filter.md index 92ca1d3b3081c..f237a1871b5e5 100644 --- a/sensing/autoware_pointcloud_preprocessor/docs/downsample-filter.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/downsample-filter.md @@ -48,7 +48,7 @@ These implementations inherit `autoware::pointcloud_preprocessor::Filter` class, ### Pickup Based Voxel Grid Downsample Filter -{{ json_to_markdown("sensing/autoware_pointcloud_preprocessor/schema/pickup_based_voxel_grid_downsample_filter.schema.json") }} +{{ json_to_markdown("sensing/autoware_pointcloud_preprocessor/schema/pickup_based_voxel_grid_downsample_filter_node.schema.json") }} ## Assumptions / Known limits diff --git a/sensing/autoware_pointcloud_preprocessor/docs/passthrough-filter.md b/sensing/autoware_pointcloud_preprocessor/docs/passthrough-filter.md index 58da60c8fe90e..25d2f3d4127a0 100644 --- a/sensing/autoware_pointcloud_preprocessor/docs/passthrough-filter.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/passthrough-filter.md @@ -25,8 +25,7 @@ The `passthrough_filter` is a node that removes points on the outside of a range ### Core Parameters -{{ json_to_markdown("sensing/autoware_pointcloud_preprocessor/schema/passthrough_filter_uint16_node.schema.json -") }} +{{ json_to_markdown("sensing/autoware_pointcloud_preprocessor/schema/passthrough_filter_uint16_node.schema.json") }} ## Assumptions / Known limits diff --git a/sensing/autoware_pointcloud_preprocessor/schema/blockage_diag_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/blockage_diag_node.schema.json index 0e4a02d37bd16..cdca58a6a73f0 100644 --- a/sensing/autoware_pointcloud_preprocessor/schema/blockage_diag_node.schema.json +++ b/sensing/autoware_pointcloud_preprocessor/schema/blockage_diag_node.schema.json @@ -99,7 +99,8 @@ "type": "number", "minimum": 0.0, "maximum": 360.0 - } + }, + "default": [0.0, 360.0] }, "vertical_bins": { "type": "integer", diff --git a/sensing/autoware_pointcloud_preprocessor/schema/distortion_corrector_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/distortion_corrector_node.schema.json index 091695716c610..c59541d1d2fba 100644 --- a/sensing/autoware_pointcloud_preprocessor/schema/distortion_corrector_node.schema.json +++ b/sensing/autoware_pointcloud_preprocessor/schema/distortion_corrector_node.schema.json @@ -29,7 +29,7 @@ "has_static_tf_only": { "type": "boolean", "description": "Flag to indicate if only static TF is used.", - "default": false + "default": "false" } }, "required": [ From 452e076d7659efe19a413da3716979a2c537cf28 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 26 Dec 2024 12:14:56 +0900 Subject: [PATCH 113/334] feat(autoware_overlay_rviz_plugin): add plugin to show string stamped (#9683) * feat(autoware_overlay_rviz_plugin): add plugin to show string stamped Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * better visualization Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka * fix cpp check and typo Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../CMakeLists.txt | 28 +++ .../README.md | 7 + .../package.xml | 30 +++ .../plugins/plugins_description.xml | 5 + .../src/jsk_overlay_utils.cpp | 225 +++++++++++++++++ .../src/jsk_overlay_utils.hpp | 143 +++++++++++ .../src/string_stamped_overlay_display.cpp | 237 ++++++++++++++++++ .../src/string_stamped_overlay_display.hpp | 110 ++++++++ 8 files changed, 785 insertions(+) create mode 100644 visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/CMakeLists.txt create mode 100644 visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/README.md create mode 100644 visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/package.xml create mode 100644 visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/plugins/plugins_description.xml create mode 100644 visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/src/jsk_overlay_utils.cpp create mode 100644 visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/src/jsk_overlay_utils.hpp create mode 100644 visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/src/string_stamped_overlay_display.cpp create mode 100644 visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/src/string_stamped_overlay_display.hpp diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/CMakeLists.txt b/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/CMakeLists.txt new file mode 100644 index 0000000000000..7ff4e19c69419 --- /dev/null +++ b/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/CMakeLists.txt @@ -0,0 +1,28 @@ +cmake_minimum_required(VERSION 3.8) +project(autoware_string_stamped_rviz_plugin) + +# find dependencies +find_package(autoware_cmake REQUIRED) +autoware_package() + +find_package(Qt5 REQUIRED Core Widgets) +set(QT_LIBRARIES Qt5::Widgets) +set(CMAKE_AUTOMOC ON) +set(CMAKE_INCLUDE_CURRENT_DIR ON) +add_definitions(-DQT_NO_KEYWORDS) + +ament_auto_add_library(${PROJECT_NAME} SHARED + DIRECTORY src +) + +target_link_libraries(${PROJECT_NAME} + ${QT_LIBRARIES} +) + +# Export the plugin to be imported by rviz2 +pluginlib_export_plugin_description_file(rviz_common plugins/plugins_description.xml) + +ament_auto_package( + INSTALL_TO_SHARE + plugins +) diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/README.md b/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/README.md new file mode 100644 index 0000000000000..e5add261325f4 --- /dev/null +++ b/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/README.md @@ -0,0 +1,7 @@ +# autoware_string_stamped_rviz_plugin + +Plugin for displaying 2D overlays over the RViz2 3D scene. + +## Purpose + +This plugin displays the ROS message whose topic type is `autoware_internal_debug_msgs::msg::StringStamped` in rviz. diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/package.xml b/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/package.xml new file mode 100644 index 0000000000000..c22bc75f55290 --- /dev/null +++ b/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/package.xml @@ -0,0 +1,30 @@ + + + + autoware_string_stamped_rviz_plugin + 0.39.0 + + RViz2 plugin for 2D overlays in the 3D view. Mainly a port of the JSK overlay plugin + (https://github.com/jsk-ros-pkg/jsk_visualization). + + Takayuki Murooka + Satoshi Ota + + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + + ament_index_cpp + autoware_internal_debug_msgs + rviz_common + rviz_ogre_vendor + rviz_rendering + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/plugins/plugins_description.xml b/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/plugins/plugins_description.xml new file mode 100644 index 0000000000000..302bcc629b892 --- /dev/null +++ b/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/plugins/plugins_description.xml @@ -0,0 +1,5 @@ + + + String stamped overlay plugin for the 3D view. + + diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/src/jsk_overlay_utils.cpp b/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/src/jsk_overlay_utils.cpp new file mode 100644 index 0000000000000..03fd8bca5aee8 --- /dev/null +++ b/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/src/jsk_overlay_utils.cpp @@ -0,0 +1,225 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +// Copyright (c) 2014, JSK Lab +// All rights reserved. +// +// Software License Agreement (BSD License) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of {copyright_holder} nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE.S SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. + +#include "jsk_overlay_utils.hpp" + +#include + +namespace jsk_rviz_plugins +{ +ScopedPixelBuffer::ScopedPixelBuffer(Ogre::HardwarePixelBufferSharedPtr pixel_buffer) +: pixel_buffer_(pixel_buffer) +{ + pixel_buffer_->lock(Ogre::HardwareBuffer::HBL_NORMAL); +} + +ScopedPixelBuffer::~ScopedPixelBuffer() +{ + pixel_buffer_->unlock(); +} + +Ogre::HardwarePixelBufferSharedPtr ScopedPixelBuffer::getPixelBuffer() +{ + return pixel_buffer_; +} + +QImage ScopedPixelBuffer::getQImage(unsigned int width, unsigned int height) +{ + const Ogre::PixelBox & pixelBox = pixel_buffer_->getCurrentLock(); + Ogre::uint8 * pDest = static_cast(pixelBox.data); + memset(pDest, 0, width * height); + return QImage(pDest, width, height, QImage::Format_ARGB32); +} + +QImage ScopedPixelBuffer::getQImage(unsigned int width, unsigned int height, QColor & bg_color) +{ + QImage Hud = getQImage(width, height); + for (unsigned int i = 0; i < width; i++) { + for (unsigned int j = 0; j < height; j++) { + Hud.setPixel(i, j, bg_color.rgba()); + } + } + return Hud; +} + +QImage ScopedPixelBuffer::getQImage(OverlayObject & overlay) +{ + return getQImage(overlay.getTextureWidth(), overlay.getTextureHeight()); +} + +QImage ScopedPixelBuffer::getQImage(OverlayObject & overlay, QColor & bg_color) +{ + return getQImage(overlay.getTextureWidth(), overlay.getTextureHeight(), bg_color); +} + +OverlayObject::OverlayObject( + Ogre::SceneManager * manager, rclcpp::Logger logger, const std::string & name) +: name_(name), logger_(logger) +{ + rviz_rendering::RenderSystem::get()->prepareOverlays(manager); + std::string material_name = name_ + "Material"; + Ogre::OverlayManager * mOverlayMgr = Ogre::OverlayManager::getSingletonPtr(); + overlay_ = mOverlayMgr->create(name_); + panel_ = static_cast( + mOverlayMgr->createOverlayElement("Panel", name_ + "Panel")); + panel_->setMetricsMode(Ogre::GMM_PIXELS); + + panel_material_ = Ogre::MaterialManager::getSingleton().create( + material_name, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME); + panel_->setMaterialName(panel_material_->getName()); + overlay_->add2D(panel_); +} + +OverlayObject::~OverlayObject() +{ + hide(); + panel_material_->unload(); + Ogre::MaterialManager::getSingleton().remove(panel_material_->getName()); + // Ogre::OverlayManager* mOverlayMgr = Ogre::OverlayManager::getSingletonPtr(); + // mOverlayMgr->destroyOverlayElement(panel_); + // delete panel_; + // delete overlay_; +} + +std::string OverlayObject::getName() +{ + return name_; +} + +void OverlayObject::hide() +{ + if (overlay_->isVisible()) { + overlay_->hide(); + } +} + +void OverlayObject::show() +{ + if (!overlay_->isVisible()) { + overlay_->show(); + } +} + +bool OverlayObject::isTextureReady() +{ + return static_cast(texture_); +} + +void OverlayObject::updateTextureSize(unsigned int width, unsigned int height) +{ + const std::string texture_name = name_ + "Texture"; + if (width == 0) { + RCLCPP_WARN(logger_, "width=0 is specified as texture size"); + width = 1; + } + if (height == 0) { + RCLCPP_WARN(logger_, "height=0 is specified as texture size"); + height = 1; + } + if (!isTextureReady() || ((width != texture_->getWidth()) || (height != texture_->getHeight()))) { + if (isTextureReady()) { + Ogre::TextureManager::getSingleton().remove(texture_name); + panel_material_->getTechnique(0)->getPass(0)->removeAllTextureUnitStates(); + } + texture_ = Ogre::TextureManager::getSingleton().createManual( + texture_name, // name + Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, + Ogre::TEX_TYPE_2D, // type + width, height, // width & height of the render window + 0, // number of mipmaps + Ogre::PF_A8R8G8B8, // pixel format chosen to match a format Qt can use + Ogre::TU_DEFAULT // usage + ); + panel_material_->getTechnique(0)->getPass(0)->createTextureUnitState(texture_name); + + panel_material_->getTechnique(0)->getPass(0)->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA); + } +} + +ScopedPixelBuffer OverlayObject::getBuffer() +{ + if (isTextureReady()) { + return ScopedPixelBuffer(texture_->getBuffer()); + } else { + return ScopedPixelBuffer(Ogre::HardwarePixelBufferSharedPtr()); + } +} + +void OverlayObject::setPosition(double left, double top) +{ + panel_->setPosition(left, top); +} + +void OverlayObject::setDimensions(double width, double height) +{ + panel_->setDimensions(width, height); +} + +bool OverlayObject::isVisible() +{ + return overlay_->isVisible(); +} + +unsigned int OverlayObject::getTextureWidth() +{ + if (isTextureReady()) { + return texture_->getWidth(); + } else { + return 0; + } +} + +unsigned int OverlayObject::getTextureHeight() +{ + if (isTextureReady()) { + return texture_->getHeight(); + } else { + return 0; + } +} + +} // namespace jsk_rviz_plugins diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/src/jsk_overlay_utils.hpp b/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/src/jsk_overlay_utils.hpp new file mode 100644 index 0000000000000..e69abed49f371 --- /dev/null +++ b/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/src/jsk_overlay_utils.hpp @@ -0,0 +1,143 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +// Copyright (c) 2014, JSK Lab +// All rights reserved. +// +// Software License Agreement (BSD License) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of {copyright_holder} nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE.S SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. + +#ifndef JSK_OVERLAY_UTILS_HPP_ +#define JSK_OVERLAY_UTILS_HPP_ + +#include +#include +#include +#include +#include +#include + +#include +#include +// see OGRE/OgrePrerequisites.h +// #define OGRE_VERSION +// ((OGRE_VERSION_MAJOR << 16) | (OGRE_VERSION_MINOR << 8) | OGRE_VERSION_PATCH) +#if OGRE_VERSION < ((1 << 16) | (9 << 8) | 0) +#include +#include +#include +#include +#else +#include +#include +#include +#include +#include +#endif + +#include +#include +#include +#include +#include +#include + +namespace jsk_rviz_plugins +{ +class OverlayObject; + +class ScopedPixelBuffer +{ +public: + explicit ScopedPixelBuffer(Ogre::HardwarePixelBufferSharedPtr pixel_buffer); + virtual ~ScopedPixelBuffer(); + virtual Ogre::HardwarePixelBufferSharedPtr getPixelBuffer(); + virtual QImage getQImage(unsigned int width, unsigned int height); + virtual QImage getQImage(OverlayObject & overlay); + virtual QImage getQImage(unsigned int width, unsigned int height, QColor & bg_color); + virtual QImage getQImage(OverlayObject & overlay, QColor & bg_color); + +protected: + Ogre::HardwarePixelBufferSharedPtr pixel_buffer_; + +private: +}; + +// this is a class for put overlay object on rviz 3D panel. +// This class suppose to be instantiated in onInitialize method +// of rviz::Display class. +class OverlayObject +{ +public: + typedef std::shared_ptr Ptr; + + OverlayObject(Ogre::SceneManager * manager, rclcpp::Logger logger, const std::string & name); + virtual ~OverlayObject(); + + virtual std::string getName(); + /*virtual*/ void hide(); // remove "virtual" for cppcheck + virtual void show(); + virtual bool isTextureReady(); + virtual void updateTextureSize(unsigned int width, unsigned int height); + virtual ScopedPixelBuffer getBuffer(); + virtual void setPosition(double left, double top); + virtual void setDimensions(double width, double height); + virtual bool isVisible(); + virtual unsigned int getTextureWidth(); + virtual unsigned int getTextureHeight(); + +protected: + const std::string name_; + rclcpp::Logger logger_; + Ogre::Overlay * overlay_; + Ogre::PanelOverlayElement * panel_; + Ogre::MaterialPtr panel_material_; + Ogre::TexturePtr texture_; + +private: +}; + +// Ogre::Overlay* createOverlay(std::string name); +// Ogre::PanelOverlayElement* createOverlayPanel(Ogre::Overlay* overlay); +// Ogre::MaterialPtr createOverlayMaterial(Ogre::Overlay* overlay); +} // namespace jsk_rviz_plugins + +#endif // JSK_OVERLAY_UTILS_HPP_ diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/src/string_stamped_overlay_display.cpp b/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/src/string_stamped_overlay_display.cpp new file mode 100644 index 0000000000000..d5746e99ff084 --- /dev/null +++ b/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/src/string_stamped_overlay_display.cpp @@ -0,0 +1,237 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +// Copyright (c) 2014, JSK Lab +// All rights reserved. +// +// Software License Agreement (BSD License) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of {copyright_holder} nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE.S SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. + +#include "string_stamped_overlay_display.hpp" + +#include "jsk_overlay_utils.hpp" + +#include +#include + +#include + +#include +#include +#include +#include +#include + +namespace autoware::string_stamped_rviz_plugin +{ +StringStampedOverlayDisplay::StringStampedOverlayDisplay() +{ + const Screen * screen_info = DefaultScreenOfDisplay(XOpenDisplay(NULL)); + + constexpr float hight_4k = 2160.0; + const float scale = static_cast(screen_info->height) / hight_4k; + const auto left = static_cast(std::round(1024 * scale)); + const auto top = static_cast(std::round(128 * scale)); + + property_text_color_ = new rviz_common::properties::ColorProperty( + "Text Color", QColor(25, 255, 240), "text color", this, SLOT(updateVisualization()), this); + property_left_ = new rviz_common::properties::IntProperty( + "Left", left, "Left of the plotter window", this, SLOT(updateVisualization()), this); + property_left_->setMin(0); + property_top_ = new rviz_common::properties::IntProperty( + "Top", top, "Top of the plotter window", this, SLOT(updateVisualization())); + property_top_->setMin(0); + + property_value_height_offset_ = new rviz_common::properties::IntProperty( + "Value height offset", 0, "Height offset of the plotter window", this, + SLOT(updateVisualization())); + property_font_size_ = new rviz_common::properties::IntProperty( + "Font Size", 15, "Font Size", this, SLOT(updateVisualization()), this); + property_font_size_->setMin(1); + property_max_letter_num_ = new rviz_common::properties::IntProperty( + "Max Letter Num", 100, "Max Letter Num", this, SLOT(updateVisualization()), this); + property_max_letter_num_->setMin(10); + + property_last_diag_keep_time_ = new rviz_common::properties::FloatProperty( + "Time To Keep Last Diag", 1.0, "Time To Keep Last Diag", this, SLOT(updateVisualization()), + this); + property_last_diag_keep_time_->setMin(0); + + property_last_diag_erase_time_ = new rviz_common::properties::FloatProperty( + "Time To Erase Last Diag", 2.0, "Time To Erase Last Diag", this, SLOT(updateVisualization()), + this); + property_last_diag_erase_time_->setMin(0.001); +} + +StringStampedOverlayDisplay::~StringStampedOverlayDisplay() +{ + if (initialized()) { + overlay_->hide(); + } +} + +void StringStampedOverlayDisplay::onInitialize() +{ + RTDClass::onInitialize(); + + static int count = 0; + rviz_common::UniformStringStream ss; + ss << "StringOverlayDisplayObject" << count++; + auto logger = context_->getRosNodeAbstraction().lock()->get_raw_node()->get_logger(); + overlay_.reset(new jsk_rviz_plugins::OverlayObject(scene_manager_, logger, ss.str())); + + overlay_->show(); + + const int texture_size = property_font_size_->getInt() * property_max_letter_num_->getInt(); + overlay_->updateTextureSize(texture_size, texture_size); + overlay_->setPosition(property_left_->getInt(), property_top_->getInt()); + overlay_->setDimensions(overlay_->getTextureWidth(), overlay_->getTextureHeight()); +} + +void StringStampedOverlayDisplay::onEnable() +{ + subscribe(); + overlay_->show(); +} + +void StringStampedOverlayDisplay::onDisable() +{ + unsubscribe(); + reset(); + overlay_->hide(); +} + +void StringStampedOverlayDisplay::update(float wall_dt, float ros_dt) +{ + (void)wall_dt; + (void)ros_dt; + + { + std::lock_guard message_lock(mutex_); + if (!last_non_empty_msg_ptr_) { + return; + } + } + + // calculate text and alpha + const auto text_with_alpha = [&]() { + std::lock_guard message_lock(mutex_); + if (last_msg_text_.empty()) { + const auto current_time = context_->getRosNodeAbstraction().lock()->get_raw_node()->now(); + const auto duration = (current_time - last_non_empty_msg_ptr_->stamp).seconds(); + if ( + duration < + property_last_diag_keep_time_->getFloat() + property_last_diag_erase_time_->getFloat()) { + const int dynamic_alpha = static_cast(std::max( + (1.0 - std::max(duration - property_last_diag_keep_time_->getFloat(), 0.0) / + property_last_diag_erase_time_->getFloat()) * + 255, + 0.0)); + return std::make_pair(last_non_empty_msg_ptr_->data, dynamic_alpha); + } + } + return std::make_pair(last_msg_text_, 255); + }(); + + // Display + QColor background_color; + background_color.setAlpha(0); + jsk_rviz_plugins::ScopedPixelBuffer buffer = overlay_->getBuffer(); + QImage hud = buffer.getQImage(*overlay_); + hud.fill(background_color); + + QPainter painter(&hud); + painter.setRenderHint(QPainter::Antialiasing, true); + + const int w = overlay_->getTextureWidth() - line_width_; + const int h = overlay_->getTextureHeight() - line_width_; + + // text + QColor text_color(property_text_color_->getColor()); + text_color.setAlpha(text_with_alpha.second); + painter.setPen(QPen(text_color, static_cast(2), Qt::SolidLine)); + QFont font = painter.font(); + font.setPixelSize(property_font_size_->getInt()); + font.setBold(true); + painter.setFont(font); + + // same as above, but align on right side + painter.drawText( + 0, std::min(property_value_height_offset_->getInt(), h - 1), w, + std::max(h - property_value_height_offset_->getInt(), 1), Qt::AlignLeft | Qt::AlignTop, + text_with_alpha.first.c_str()); + painter.end(); + updateVisualization(); +} + +void StringStampedOverlayDisplay::processMessage( + const autoware_internal_debug_msgs::msg::StringStamped::ConstSharedPtr msg_ptr) +{ + if (!isEnabled()) { + return; + } + + { + std::lock_guard message_lock(mutex_); + last_msg_text_ = msg_ptr->data; + + // keep the non empty last message for visualization + if (!msg_ptr->data.empty()) { + last_non_empty_msg_ptr_ = msg_ptr; + } + } + + queueRender(); +} + +void StringStampedOverlayDisplay::updateVisualization() +{ + const int texture_size = property_font_size_->getInt() * property_max_letter_num_->getInt(); + overlay_->updateTextureSize(texture_size, texture_size); + overlay_->setPosition(property_left_->getInt(), property_top_->getInt()); + overlay_->setDimensions(overlay_->getTextureWidth(), overlay_->getTextureHeight()); +} + +} // namespace autoware::string_stamped_rviz_plugin + +#include +PLUGINLIB_EXPORT_CLASS( + autoware::string_stamped_rviz_plugin::StringStampedOverlayDisplay, rviz_common::Display) diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/src/string_stamped_overlay_display.hpp b/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/src/string_stamped_overlay_display.hpp new file mode 100644 index 0000000000000..6f7cd84b91aaa --- /dev/null +++ b/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/src/string_stamped_overlay_display.hpp @@ -0,0 +1,110 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +// Copyright (c) 2014, JSK Lab +// All rights reserved. +// +// Software License Agreement (BSD License) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of {copyright_holder} nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE.S SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. + +#ifndef STRING_STAMPED_OVERLAY_DISPLAY_HPP_ +#define STRING_STAMPED_OVERLAY_DISPLAY_HPP_ + +#include +#include +#include + +#ifndef Q_MOC_RUN +#include "jsk_overlay_utils.hpp" + +#include +#include +#include +#include + +#endif + +#include + +namespace autoware::string_stamped_rviz_plugin +{ +class StringStampedOverlayDisplay +: public rviz_common::RosTopicDisplay + +{ + Q_OBJECT + +public: + StringStampedOverlayDisplay(); + ~StringStampedOverlayDisplay() override; + + void onInitialize() override; + void onEnable() override; + void onDisable() override; + +private Q_SLOTS: + void updateVisualization(); + +protected: + void update(float wall_dt, float ros_dt) override; + void processMessage( + const autoware_internal_debug_msgs::msg::StringStamped::ConstSharedPtr msg_ptr) override; + jsk_rviz_plugins::OverlayObject::Ptr overlay_; + rviz_common::properties::ColorProperty * property_text_color_; + rviz_common::properties::IntProperty * property_left_; + rviz_common::properties::IntProperty * property_top_; + rviz_common::properties::IntProperty * property_value_height_offset_; + rviz_common::properties::IntProperty * property_font_size_; + rviz_common::properties::IntProperty * property_max_letter_num_; + rviz_common::properties::FloatProperty * property_last_diag_keep_time_; + rviz_common::properties::FloatProperty * property_last_diag_erase_time_; + +private: + static constexpr int line_width_ = 2; + static constexpr int hand_width_ = 4; + + std::mutex mutex_; + std::string last_msg_text_; + autoware_internal_debug_msgs::msg::StringStamped::ConstSharedPtr last_non_empty_msg_ptr_; +}; +} // namespace autoware::string_stamped_rviz_plugin + +#endif // STRING_STAMPED_OVERLAY_DISPLAY_HPP_ From ee93be1fe1ecb1721a3f4dab118d814d1263a193 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 26 Dec 2024 14:35:11 +0900 Subject: [PATCH 114/334] refactor(behavior_velocity_planner): independent of plugin packages (#9760) Signed-off-by: Takayuki Murooka --- .../CMakeLists.txt | 3 +- .../behavior_velocity_planner}/node.hpp | 8 +- .../planner_manager.hpp | 6 +- .../behavior_velocity_planner/test_utils.hpp | 47 ++++++++ .../package.xml | 13 --- .../src/node.cpp | 2 +- .../src/planner_manager.cpp | 2 +- .../test_utils.cpp} | 108 ++++-------------- .../test/test_node_interface.cpp | 61 ++++++++++ 9 files changed, 144 insertions(+), 106 deletions(-) rename planning/behavior_velocity_planner/autoware_behavior_velocity_planner/{src => include/autoware/behavior_velocity_planner}/node.hpp (96%) rename planning/behavior_velocity_planner/autoware_behavior_velocity_planner/{src => include/autoware/behavior_velocity_planner}/planner_manager.hpp (91%) create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_planner/include/autoware/behavior_velocity_planner/test_utils.hpp rename planning/behavior_velocity_planner/autoware_behavior_velocity_planner/{test/src/test_node_interface.cpp => src/test_utils.cpp} (50%) create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_planner/test/test_node_interface.cpp diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/CMakeLists.txt b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/CMakeLists.txt index 37a02b844dfe9..31900a23d00e5 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/CMakeLists.txt +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/CMakeLists.txt @@ -16,6 +16,7 @@ autoware_package() ament_auto_add_library(${PROJECT_NAME}_lib SHARED src/node.cpp src/planner_manager.cpp + src/test_utils.cpp ) rclcpp_components_register_node(${PROJECT_NAME}_lib @@ -34,7 +35,7 @@ endif() if(BUILD_TESTING) ament_add_ros_isolated_gtest(test_${PROJECT_NAME} - test/src/test_node_interface.cpp + test/test_node_interface.cpp ) target_link_libraries(test_${PROJECT_NAME} gtest_main diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/include/autoware/behavior_velocity_planner/node.hpp similarity index 96% rename from planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.hpp rename to planning/behavior_velocity_planner/autoware_behavior_velocity_planner/include/autoware/behavior_velocity_planner/node.hpp index 4efb58e38b74f..4c1f10c355226 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/include/autoware/behavior_velocity_planner/node.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NODE_HPP_ -#define NODE_HPP_ +#ifndef AUTOWARE__BEHAVIOR_VELOCITY_PLANNER__NODE_HPP_ +#define AUTOWARE__BEHAVIOR_VELOCITY_PLANNER__NODE_HPP_ +#include "autoware/behavior_velocity_planner/planner_manager.hpp" #include "autoware/universe_utils/ros/logger_level_configure.hpp" #include "autoware/universe_utils/ros/polling_subscriber.hpp" -#include "planner_manager.hpp" #include #include @@ -150,4 +150,4 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node }; } // namespace autoware::behavior_velocity_planner -#endif // NODE_HPP_ +#endif // AUTOWARE__BEHAVIOR_VELOCITY_PLANNER__NODE_HPP_ diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/planner_manager.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/include/autoware/behavior_velocity_planner/planner_manager.hpp similarity index 91% rename from planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/planner_manager.hpp rename to planning/behavior_velocity_planner/autoware_behavior_velocity_planner/include/autoware/behavior_velocity_planner/planner_manager.hpp index fddd658cef06e..9bd423ecfef21 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/planner_manager.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/include/autoware/behavior_velocity_planner/planner_manager.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PLANNER_MANAGER_HPP_ -#define PLANNER_MANAGER_HPP_ +#ifndef AUTOWARE__BEHAVIOR_VELOCITY_PLANNER__PLANNER_MANAGER_HPP_ +#define AUTOWARE__BEHAVIOR_VELOCITY_PLANNER__PLANNER_MANAGER_HPP_ #include #include @@ -57,4 +57,4 @@ class BehaviorVelocityPlannerManager }; } // namespace autoware::behavior_velocity_planner -#endif // PLANNER_MANAGER_HPP_ +#endif // AUTOWARE__BEHAVIOR_VELOCITY_PLANNER__PLANNER_MANAGER_HPP_ diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/include/autoware/behavior_velocity_planner/test_utils.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/include/autoware/behavior_velocity_planner/test_utils.hpp new file mode 100644 index 0000000000000..f34182e77e6f1 --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/include/autoware/behavior_velocity_planner/test_utils.hpp @@ -0,0 +1,47 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__BEHAVIOR_VELOCITY_PLANNER__TEST_UTILS_HPP_ +#define AUTOWARE__BEHAVIOR_VELOCITY_PLANNER__TEST_UTILS_HPP_ + +#include "autoware/behavior_velocity_planner/node.hpp" + +#include + +#include +#include +#include + +namespace autoware::behavior_velocity_planner +{ +using autoware::behavior_velocity_planner::BehaviorVelocityPlannerNode; +using autoware::planning_test_manager::PlanningInterfaceTestManager; + +struct PluginInfo +{ + std::string module_name; // e.g. crosswalk + std::string plugin_name; // e.g. autoware::behavior_velocity_planner::CrosswalkModulePlugin +}; + +std::shared_ptr generateTestManager(); + +std::shared_ptr generateNode( + const std::vector & plugin_info_vec); + +void publishMandatoryTopics( + std::shared_ptr test_manager, + std::shared_ptr test_target_node); +} // namespace autoware::behavior_velocity_planner + +#endif // AUTOWARE__BEHAVIOR_VELOCITY_PLANNER__TEST_UTILS_HPP_ diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml index e051374ed3dda..04b4cf0328fd1 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml @@ -64,19 +64,6 @@ ament_cmake_ros ament_lint_auto - autoware_behavior_velocity_blind_spot_module - autoware_behavior_velocity_crosswalk_module - autoware_behavior_velocity_detection_area_module - autoware_behavior_velocity_intersection_module - autoware_behavior_velocity_no_drivable_lane_module - autoware_behavior_velocity_no_stopping_area_module - autoware_behavior_velocity_occlusion_spot_module - autoware_behavior_velocity_run_out_module - autoware_behavior_velocity_speed_bump_module - autoware_behavior_velocity_stop_line_module - autoware_behavior_velocity_traffic_light_module - autoware_behavior_velocity_virtual_traffic_light_module - autoware_behavior_velocity_walkway_module autoware_lint_common diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp index d78bc883e6b35..5f78e4c670b49 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "node.hpp" +#include "autoware/behavior_velocity_planner/node.hpp" #include #include diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/planner_manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/planner_manager.cpp index 4820c340058ff..45ee83260d53a 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/planner_manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/planner_manager.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "planner_manager.hpp" +#include "autoware/behavior_velocity_planner/planner_manager.hpp" #include #include diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/test_utils.cpp similarity index 50% rename from planning/behavior_velocity_planner/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp rename to planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/test_utils.cpp index fe79450d0def8..ee1bb8f89fc46 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/test_utils.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 Tier IV, Inc. +// Copyright 2024 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,22 +12,18 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "node.hpp" +#include "autoware/behavior_velocity_planner/test_utils.hpp" #include #include #include -#include - -#include #include #include #include -using autoware::behavior_velocity_planner::BehaviorVelocityPlannerNode; -using autoware::planning_test_manager::PlanningInterfaceTestManager; - +namespace autoware::behavior_velocity_planner +{ std::shared_ptr generateTestManager() { auto test_manager = std::make_shared(); @@ -45,7 +41,8 @@ std::shared_ptr generateTestManager() return test_manager; } -std::shared_ptr generateNode() +std::shared_ptr generateNode( + const std::vector & plugin_info_vec) { auto node_options = rclcpp::NodeOptions{}; @@ -64,49 +61,29 @@ std::shared_ptr generateNode() return package_path + "/config/" + module + ".param.yaml"; }; - std::vector module_names; - module_names.emplace_back("autoware::behavior_velocity_planner::CrosswalkModulePlugin"); - module_names.emplace_back("autoware::behavior_velocity_planner::WalkwayModulePlugin"); - module_names.emplace_back("autoware::behavior_velocity_planner::TrafficLightModulePlugin"); - module_names.emplace_back("autoware::behavior_velocity_planner::IntersectionModulePlugin"); - module_names.emplace_back("autoware::behavior_velocity_planner::MergeFromPrivateModulePlugin"); - module_names.emplace_back("autoware::behavior_velocity_planner::BlindSpotModulePlugin"); - module_names.emplace_back("autoware::behavior_velocity_planner::DetectionAreaModulePlugin"); - module_names.emplace_back("autoware::behavior_velocity_planner::VirtualTrafficLightModulePlugin"); - module_names.emplace_back("autoware::behavior_velocity_planner::NoStoppingAreaModulePlugin"); - module_names.emplace_back("autoware::behavior_velocity_planner::StopLineModulePlugin"); - module_names.emplace_back("autoware::behavior_velocity_planner::OcclusionSpotModulePlugin"); - module_names.emplace_back("autoware::behavior_velocity_planner::RunOutModulePlugin"); - module_names.emplace_back("autoware::behavior_velocity_planner::SpeedBumpModulePlugin"); - module_names.emplace_back("autoware::behavior_velocity_planner::NoDrivableLaneModulePlugin"); + std::vector plugin_names; + for (const auto & plugin_info : plugin_info_vec) { + plugin_names.emplace_back(plugin_info.plugin_name); + } std::vector params; - params.emplace_back("launch_modules", module_names); + params.emplace_back("launch_modules", plugin_names); params.emplace_back("is_simulation", false); node_options.parameter_overrides(params); - autoware::test_utils::updateNodeOptions( - node_options, - {autoware_test_utils_dir + "/config/test_common.param.yaml", - autoware_test_utils_dir + "/config/test_nearest_search.param.yaml", - autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", - velocity_smoother_dir + "/config/default_velocity_smoother.param.yaml", - velocity_smoother_dir + "/config/Analytical.param.yaml", - behavior_velocity_planner_common_dir + "/config/behavior_velocity_planner_common.param.yaml", - behavior_velocity_planner_dir + "/config/behavior_velocity_planner.param.yaml", - get_behavior_velocity_module_config("blind_spot"), - get_behavior_velocity_module_config("crosswalk"), - get_behavior_velocity_module_config("walkway"), - get_behavior_velocity_module_config("detection_area"), - get_behavior_velocity_module_config("intersection"), - get_behavior_velocity_module_config("no_stopping_area"), - get_behavior_velocity_module_config("occlusion_spot"), - get_behavior_velocity_module_config("run_out"), - get_behavior_velocity_module_config("speed_bump"), - get_behavior_velocity_module_config("stop_line"), - get_behavior_velocity_module_config("traffic_light"), - get_behavior_velocity_module_config("virtual_traffic_light"), - get_behavior_velocity_module_config("no_drivable_lane")}); + auto yaml_files = std::vector{ + autoware_test_utils_dir + "/config/test_common.param.yaml", + autoware_test_utils_dir + "/config/test_nearest_search.param.yaml", + autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", + velocity_smoother_dir + "/config/default_velocity_smoother.param.yaml", + velocity_smoother_dir + "/config/Analytical.param.yaml", + behavior_velocity_planner_common_dir + "/config/behavior_velocity_planner_common.param.yaml", + behavior_velocity_planner_dir + "/config/behavior_velocity_planner.param.yaml"}; + for (const auto & plugin_info : plugin_info_vec) { + yaml_files.push_back(get_behavior_velocity_module_config(plugin_info.module_name)); + } + + autoware::test_utils::updateNodeOptions(node_options, yaml_files); // TODO(Takagi, Isamu): set launch_modules // TODO(Kyoichi Sugahara) set to true launch_virtual_traffic_light @@ -141,39 +118,4 @@ void publishMandatoryTopics( test_manager->publishOccupancyGrid( test_target_node, "behavior_velocity_planner_node/input/occupancy_grid"); } - -TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID) -{ - rclcpp::init(0, nullptr); - auto test_manager = generateTestManager(); - auto test_target_node = generateNode(); - - publishMandatoryTopics(test_manager, test_target_node); - - // test with nominal path_with_lane_id - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); - EXPECT_GE(test_manager->getReceivedTopicNum(), 1); - - // test with empty path_with_lane_id - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalPathWithLaneId(test_target_node)); - rclcpp::shutdown(); -} - -TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) -{ - rclcpp::init(0, nullptr); - - auto test_manager = generateTestManager(); - auto test_target_node = generateNode(); - publishMandatoryTopics(test_manager, test_target_node); - - // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); - - // make sure behavior_path_planner is running - EXPECT_GE(test_manager->getReceivedTopicNum(), 1); - - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testOffTrackFromPathWithLaneId(test_target_node)); - - rclcpp::shutdown(); -} +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/test/test_node_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/test/test_node_interface.cpp new file mode 100644 index 0000000000000..6e232318c1711 --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/test/test_node_interface.cpp @@ -0,0 +1,61 @@ +// Copyright 2023 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/behavior_velocity_planner/test_utils.hpp" + +#include + +#include +#include +#include +#include + +namespace autoware::behavior_velocity_planner +{ +TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID) +{ + rclcpp::init(0, nullptr); + auto test_manager = autoware::behavior_velocity_planner::generateTestManager(); + auto test_target_node = autoware::behavior_velocity_planner::generateNode({}); + + autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + + // test with nominal path_with_lane_id + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + // test with empty path_with_lane_id + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalPathWithLaneId(test_target_node)); + rclcpp::shutdown(); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) +{ + rclcpp::init(0, nullptr); + + auto test_manager = autoware::behavior_velocity_planner::generateTestManager(); + auto test_target_node = autoware::behavior_velocity_planner::generateNode({}); + autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + + // make sure behavior_path_planner is running + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testOffTrackFromPathWithLaneId(test_target_node)); + + rclcpp::shutdown(); +} +} // namespace autoware::behavior_velocity_planner From ad16612cf12fa7122304eebb9f7c5112fa72cbaa Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 26 Dec 2024 14:45:37 +0900 Subject: [PATCH 115/334] chore(cppcheck): ignore examples/ dir (#9798) Signed-off-by: Mamoru Sobue --- .cppcheck_suppressions | 1 + 1 file changed, 1 insertion(+) diff --git a/.cppcheck_suppressions b/.cppcheck_suppressions index 5e1035de20c64..ab267ec3ac007 100644 --- a/.cppcheck_suppressions +++ b/.cppcheck_suppressions @@ -1,4 +1,5 @@ *:*/test/* +*:*/examples/* checkersReport missingInclude From 0997af503fbcb36a7d5679968eba18659030d144 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> Date: Thu, 26 Dec 2024 16:42:01 +0900 Subject: [PATCH 116/334] fix(autoware_planning_evaluator): rename lateral deviation metrics (#9801) * refactor(planning_evaluator): rename and add lateral trajectory displacement metrics Signed-off-by: kyoichi-sugahara * fix typo Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- .../config/planning_evaluator.param.yaml | 3 ++- .../metrics/deviation_metrics.hpp | 2 +- .../planning_evaluator/metrics/metric.hpp | 16 ++++++++-------- .../metrics/stability_metrics.hpp | 2 +- .../src/metrics/deviation_metrics.cpp | 2 +- .../src/metrics/stability_metrics.cpp | 2 +- .../src/metrics_calculator.cpp | 10 +++++----- 7 files changed, 19 insertions(+), 18 deletions(-) diff --git a/evaluator/autoware_planning_evaluator/config/planning_evaluator.param.yaml b/evaluator/autoware_planning_evaluator/config/planning_evaluator.param.yaml index 73c1f3dfded09..7605ed2a5e859 100644 --- a/evaluator/autoware_planning_evaluator/config/planning_evaluator.param.yaml +++ b/evaluator/autoware_planning_evaluator/config/planning_evaluator.param.yaml @@ -14,7 +14,8 @@ - lateral_deviation - yaw_deviation - velocity_deviation - - trajectory_lateral_displacement + - lateral_trajectory_displacement_local + - lateral_trajectory_displacement_lookahead - stability - stability_frechet - obstacle_distance diff --git a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/deviation_metrics.hpp b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/deviation_metrics.hpp index 0e08398ffa87e..2341ad2bb6ba3 100644 --- a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/deviation_metrics.hpp +++ b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/deviation_metrics.hpp @@ -45,7 +45,7 @@ Accumulator calcLateralDeviation(const Trajectory & ref, const Trajector * @param [in] base_pose base pose * @return calculated statistics */ -Accumulator calcLateralTrajectoryDisplacement( +Accumulator calcLocalLateralTrajectoryDisplacement( const Trajectory & prev, const Trajectory & traj, const Pose & base_pose); /** diff --git a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/metric.hpp b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/metric.hpp index 22b365881ce28..7c207bf6c8f57 100644 --- a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/metric.hpp +++ b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/metric.hpp @@ -37,10 +37,10 @@ enum class Metric { lateral_deviation, yaw_deviation, velocity_deviation, - lateral_trajectory_displacement, + lateral_trajectory_displacement_local, + lateral_trajectory_displacement_lookahead, stability, stability_frechet, - trajectory_lateral_displacement, obstacle_distance, obstacle_ttc, modified_goal_longitudinal_deviation, @@ -64,10 +64,10 @@ static const std::unordered_map str_to_metric = { {"lateral_deviation", Metric::lateral_deviation}, {"yaw_deviation", Metric::yaw_deviation}, {"velocity_deviation", Metric::velocity_deviation}, - {"lateral_trajectory_displacement", Metric::lateral_trajectory_displacement}, + {"lateral_trajectory_displacement_local", Metric::lateral_trajectory_displacement_local}, + {"lateral_trajectory_displacement_lookahead", Metric::lateral_trajectory_displacement_lookahead}, {"stability", Metric::stability}, {"stability_frechet", Metric::stability_frechet}, - {"trajectory_lateral_displacement", Metric::trajectory_lateral_displacement}, {"obstacle_distance", Metric::obstacle_distance}, {"obstacle_ttc", Metric::obstacle_ttc}, {"modified_goal_longitudinal_deviation", Metric::modified_goal_longitudinal_deviation}, @@ -86,10 +86,10 @@ static const std::unordered_map metric_to_str = { {Metric::lateral_deviation, "lateral_deviation"}, {Metric::yaw_deviation, "yaw_deviation"}, {Metric::velocity_deviation, "velocity_deviation"}, - {Metric::lateral_trajectory_displacement, "lateral_trajectory_displacement"}, + {Metric::lateral_trajectory_displacement_local, "lateral_trajectory_displacement_local"}, + {Metric::lateral_trajectory_displacement_lookahead, "lateral_trajectory_displacement_lookahead"}, {Metric::stability, "stability"}, {Metric::stability_frechet, "stability_frechet"}, - {Metric::trajectory_lateral_displacement, "trajectory_lateral_displacement"}, {Metric::obstacle_distance, "obstacle_distance"}, {Metric::obstacle_ttc, "obstacle_ttc"}, {Metric::modified_goal_longitudinal_deviation, "modified_goal_longitudinal_deviation"}, @@ -109,10 +109,10 @@ static const std::unordered_map metric_descriptions = { {Metric::lateral_deviation, "Lateral_deviation[m]"}, {Metric::yaw_deviation, "Yaw_deviation[rad]"}, {Metric::velocity_deviation, "Velocity_deviation[m/s]"}, - {Metric::lateral_trajectory_displacement, "Nearest Pose Lateral Deviation[m]"}, + {Metric::lateral_trajectory_displacement_local, "Nearest Pose Lateral Deviation[m]"}, + {Metric::lateral_trajectory_displacement_lookahead, "Lateral_Offset_Over_Distance_Ahead[m]"}, {Metric::stability, "Stability[m]"}, {Metric::stability_frechet, "StabilityFrechet[m]"}, - {Metric::trajectory_lateral_displacement, "Trajectory_lateral_displacement[m]"}, {Metric::obstacle_distance, "Obstacle_distance[m]"}, {Metric::obstacle_ttc, "Obstacle_time_to_collision[s]"}, {Metric::modified_goal_longitudinal_deviation, "Modified_goal_longitudinal_deviation[m]"}, diff --git a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/stability_metrics.hpp b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/stability_metrics.hpp index 69df00b26551b..1b46fbddfb297 100644 --- a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/stability_metrics.hpp +++ b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/stability_metrics.hpp @@ -56,7 +56,7 @@ Accumulator calcLateralDistance(const Trajectory & traj1, const Trajecto * @param [in] trajectory_eval_time_s time duration for trajectory evaluation in seconds * @return statistical accumulator containing the total lateral displacement */ -Accumulator calcTrajectoryLateralDisplacement( +Accumulator calcLookaheadLateralTrajectoryDisplacement( const Trajectory traj1, const Trajectory traj2, const nav_msgs::msg::Odometry & ego_odom, const double trajectory_eval_time_s); diff --git a/evaluator/autoware_planning_evaluator/src/metrics/deviation_metrics.cpp b/evaluator/autoware_planning_evaluator/src/metrics/deviation_metrics.cpp index ffb56baf29f17..82ba86c65d6af 100644 --- a/evaluator/autoware_planning_evaluator/src/metrics/deviation_metrics.cpp +++ b/evaluator/autoware_planning_evaluator/src/metrics/deviation_metrics.cpp @@ -45,7 +45,7 @@ Accumulator calcLateralDeviation(const Trajectory & ref, const Trajector return stat; } -Accumulator calcLateralTrajectoryDisplacement( +Accumulator calcLocalLateralTrajectoryDisplacement( const Trajectory & prev, const Trajectory & traj, const Pose & ego_pose) { Accumulator stat; diff --git a/evaluator/autoware_planning_evaluator/src/metrics/stability_metrics.cpp b/evaluator/autoware_planning_evaluator/src/metrics/stability_metrics.cpp index b99a4ebd20050..61e18a6ad0b63 100644 --- a/evaluator/autoware_planning_evaluator/src/metrics/stability_metrics.cpp +++ b/evaluator/autoware_planning_evaluator/src/metrics/stability_metrics.cpp @@ -98,7 +98,7 @@ Accumulator calcLateralDistance(const Trajectory & traj1, const Trajecto return stat; } -Accumulator calcTrajectoryLateralDisplacement( +Accumulator calcLookaheadLateralTrajectoryDisplacement( const Trajectory traj1, const Trajectory traj2, const nav_msgs::msg::Odometry & ego_odom, const double trajectory_eval_time_s) { diff --git a/evaluator/autoware_planning_evaluator/src/metrics_calculator.cpp b/evaluator/autoware_planning_evaluator/src/metrics_calculator.cpp index 201fbcba0e9f7..c30420a5632fa 100644 --- a/evaluator/autoware_planning_evaluator/src/metrics_calculator.cpp +++ b/evaluator/autoware_planning_evaluator/src/metrics_calculator.cpp @@ -50,8 +50,11 @@ std::optional> MetricsCalculator::calculate( return metrics::calcYawDeviation(reference_trajectory_, traj); case Metric::velocity_deviation: return metrics::calcVelocityDeviation(reference_trajectory_, traj); - case Metric::lateral_trajectory_displacement: - return metrics::calcLateralTrajectoryDisplacement(previous_trajectory_, traj, ego_pose_); + case Metric::lateral_trajectory_displacement_local: + return metrics::calcLocalLateralTrajectoryDisplacement(previous_trajectory_, traj, ego_pose_); + case Metric::lateral_trajectory_displacement_lookahead: + return metrics::calcLookaheadLateralTrajectoryDisplacement( + previous_trajectory_, traj, ego_odometry_, parameters.trajectory.evaluation_time_s); case Metric::stability_frechet: return metrics::calcFrechetDistance( metrics::utils::get_lookahead_trajectory( @@ -68,9 +71,6 @@ std::optional> MetricsCalculator::calculate( metrics::utils::get_lookahead_trajectory( traj, ego_pose_, parameters.trajectory.lookahead.max_dist_m, parameters.trajectory.lookahead.max_time_s)); - case Metric::trajectory_lateral_displacement: - return metrics::calcTrajectoryLateralDisplacement( - previous_trajectory_, traj, ego_odometry_, parameters.trajectory.evaluation_time_s); case Metric::obstacle_distance: return metrics::calcDistanceToObstacle(dynamic_objects_, traj); case Metric::obstacle_ttc: From 231c341e4bac7061c477f1222eeddd526fbad18c Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 26 Dec 2024 19:48:50 +0900 Subject: [PATCH 117/334] fix(behavior_path_planner): add freespace_planning_algorithms dependency (#9800) --- .../autoware_behavior_path_goal_planner_module/package.xml | 1 + .../autoware_behavior_path_start_planner_module/package.xml | 1 + 2 files changed, 2 insertions(+) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/package.xml index 232c548b28da3..78c4ea7e4c609 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/package.xml @@ -23,6 +23,7 @@ autoware_behavior_path_planner autoware_behavior_path_planner_common autoware_bezier_sampler + autoware_freespace_planning_algorithms autoware_motion_utils autoware_rtc_interface autoware_test_utils diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/package.xml index c7cabb403f164..214731f96cebc 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/package.xml @@ -22,6 +22,7 @@ autoware_behavior_path_planner autoware_behavior_path_planner_common + autoware_freespace_planning_algorithms autoware_motion_utils autoware_rtc_interface autoware_universe_utils From 4ed851f651777e7e241e791ff2cfd76deb3522ba Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 27 Dec 2024 10:16:22 +0900 Subject: [PATCH 118/334] refactor(behavior_velocity_planner_common): add behavior_velocity_rtc_interface and move RTC-related implementation (#9799) * split into planer_common and rtc_interface Signed-off-by: Takayuki Murooka * Update planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp Co-authored-by: Mamoru Sobue * Update planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp Co-authored-by: Mamoru Sobue * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka Co-authored-by: Mamoru Sobue --- .../manager.hpp | 6 +- .../scene.hpp | 4 +- .../package.xml | 1 + .../src/manager.cpp | 2 +- .../src/scene.cpp | 2 +- .../package.xml | 1 + .../src/manager.cpp | 4 +- .../src/manager.hpp | 6 +- .../src/scene_crosswalk.cpp | 2 +- .../src/scene_crosswalk.hpp | 4 +- .../package.xml | 1 + .../src/manager.cpp | 9 +- .../src/manager.hpp | 6 +- .../src/scene.cpp | 2 +- .../src/scene.hpp | 4 +- .../package.xml | 1 + .../src/manager.cpp | 4 +- .../src/manager.hpp | 7 +- .../src/scene_intersection.cpp | 2 +- .../src/scene_intersection.hpp | 4 +- .../src/manager.hpp | 2 +- .../package.xml | 1 + .../src/manager.cpp | 9 +- .../src/manager.hpp | 6 +- .../src/scene_no_stopping_area.cpp | 2 +- .../src/scene_no_stopping_area.hpp | 4 +- .../src/manager.hpp | 2 +- .../README.md | 2 +- .../scene_module_interface.hpp | 229 ++++++++++------- .../package.xml | 1 - .../src/scene_module_interface.cpp | 238 +----------------- .../CMakeLists.txt | 11 + .../README.md | 3 + .../scene_module_interface_with_rtc.hpp | 154 ++++++++++++ .../package.xml | 38 +++ .../src/scene_module_interface_with_rtc.cpp | 140 +++++++++++ .../src/manager.hpp | 2 +- .../src/manager.hpp | 2 +- .../src/manager.hpp | 2 +- .../src/manager.hpp | 2 +- .../package.xml | 1 + .../src/manager.cpp | 4 +- .../src/manager.hpp | 6 +- .../src/scene.cpp | 2 +- .../src/scene.hpp | 4 +- .../src/manager.hpp | 2 +- .../src/manager.hpp | 2 +- 47 files changed, 562 insertions(+), 381 deletions(-) create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/CMakeLists.txt create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/README.md create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/package.xml create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/src/scene_module_interface_with_rtc.cpp diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/manager.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/manager.hpp index f296ad03cbac6..bf01986d5c28f 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/manager.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/manager.hpp @@ -19,7 +19,7 @@ #include #include -#include +#include #include #include @@ -42,8 +42,8 @@ class BlindSpotModuleManager : public SceneModuleManagerInterfaceWithRTC void launchNewModules(const tier4_planning_msgs::msg::PathWithLaneId & path) override; - std::function &)> getModuleExpiredFunction( - const tier4_planning_msgs::msg::PathWithLaneId & path) override; + std::function &)> + getModuleExpiredFunction(const tier4_planning_msgs::msg::PathWithLaneId & path) override; }; class BlindSpotModulePlugin : public PluginWrapper diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/scene.hpp index 1bfa41d86ffbe..50ce8634ec600 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/scene.hpp @@ -16,8 +16,8 @@ #define AUTOWARE__BEHAVIOR_VELOCITY_BLIND_SPOT_MODULE__SCENE_HPP_ #include -#include #include +#include #include #include @@ -59,7 +59,7 @@ struct Safe using BlindSpotDecision = std::variant; -class BlindSpotModule : public SceneModuleInterface +class BlindSpotModule : public SceneModuleInterfaceWithRTC { public: struct DebugData diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml index a2ea4a82a884d..9739370387df7 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml @@ -18,6 +18,7 @@ autoware_cmake autoware_behavior_velocity_planner_common + autoware_behavior_velocity_rtc_interface autoware_lanelet2_extension autoware_motion_utils autoware_perception_msgs diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/manager.cpp index cc63b42df68e4..a1410d2fecfd5 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/manager.cpp @@ -83,7 +83,7 @@ void BlindSpotModuleManager::launchNewModules(const tier4_planning_msgs::msg::Pa } } -std::function &)> +std::function &)> BlindSpotModuleManager::getModuleExpiredFunction( const tier4_planning_msgs::msg::PathWithLaneId & path) { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp index 7697786adb19d..7d1a68c5006a0 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp @@ -41,7 +41,7 @@ BlindSpotModule::BlindSpotModule( const int64_t module_id, const int64_t lane_id, const TurnDirection turn_direction, const std::shared_ptr planner_data, const PlannerParam & planner_param, const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock) -: SceneModuleInterface(module_id, logger, clock), +: SceneModuleInterfaceWithRTC(module_id, logger, clock), lane_id_(lane_id), planner_param_{planner_param}, turn_direction_(turn_direction), diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml index 08bd8f91c7d71..ff01e85aa5456 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml @@ -22,6 +22,7 @@ eigen3_cmake_module autoware_behavior_velocity_planner_common + autoware_behavior_velocity_rtc_interface autoware_grid_map_utils autoware_internal_debug_msgs autoware_interpolation diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.cpp index 8ba05be36ae56..cdaff7225a7d2 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.cpp @@ -216,7 +216,7 @@ void CrosswalkModuleManager::launchNewModules(const PathWithLaneId & path) } } -std::function &)> +std::function &)> CrosswalkModuleManager::getModuleExpiredFunction(const PathWithLaneId & path) { const auto rh = planner_data_->route_handler_; @@ -233,7 +233,7 @@ CrosswalkModuleManager::getModuleExpiredFunction(const PathWithLaneId & path) crosswalk_id_set.insert(crosswalk.first->crosswalkLanelet().id()); } - return [crosswalk_id_set](const std::shared_ptr & scene_module) { + return [crosswalk_id_set](const std::shared_ptr & scene_module) { return crosswalk_id_set.count(scene_module->getModuleId()) == 0; }; } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.hpp index d6f6ddfb7b6ad..091a427e14949 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.hpp @@ -19,7 +19,7 @@ #include #include -#include +#include #include #include @@ -48,8 +48,8 @@ class CrosswalkModuleManager : public SceneModuleManagerInterfaceWithRTC void launchNewModules(const PathWithLaneId & path) override; - std::function &)> getModuleExpiredFunction( - const PathWithLaneId & path) override; + std::function &)> + getModuleExpiredFunction(const PathWithLaneId & path) override; }; class CrosswalkModulePlugin : public PluginWrapper diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 07b2f1deff0c7..64f7e9e14dcd1 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -176,7 +176,7 @@ CrosswalkModule::CrosswalkModule( const std::optional & reg_elem_id, const lanelet::LaneletMapPtr & lanelet_map_ptr, const PlannerParam & planner_param, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock) -: SceneModuleInterface(module_id, logger, clock), +: SceneModuleInterfaceWithRTC(module_id, logger, clock), module_id_(module_id), planner_param_(planner_param), use_regulatory_element_(reg_elem_id) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index b3fbc2f6cfaba..d5a9e463c730b 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -17,7 +17,7 @@ #include "autoware/behavior_velocity_crosswalk_module/util.hpp" -#include +#include #include #include #include @@ -112,7 +112,7 @@ double InterpolateMap( } } // namespace -class CrosswalkModule : public SceneModuleInterface +class CrosswalkModule : public SceneModuleInterfaceWithRTC { public: struct PlannerParam diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/package.xml index ff91cf40a32a6..90aaddf96feef 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/package.xml @@ -18,6 +18,7 @@ eigen3_cmake_module autoware_behavior_velocity_planner_common + autoware_behavior_velocity_rtc_interface autoware_lanelet2_extension autoware_motion_utils autoware_planning_msgs diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/manager.cpp index 3f39696ff6bcc..62f5b88699a37 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/manager.cpp @@ -74,16 +74,17 @@ void DetectionAreaModuleManager::launchNewModules( } } -std::function &)> +std::function &)> DetectionAreaModuleManager::getModuleExpiredFunction( const tier4_planning_msgs::msg::PathWithLaneId & path) { const auto detection_area_id_set = planning_utils::getRegElemIdSetOnPath( path, planner_data_->route_handler_->getLaneletMapPtr(), planner_data_->current_odometry->pose); - return [detection_area_id_set](const std::shared_ptr & scene_module) { - return detection_area_id_set.count(scene_module->getModuleId()) == 0; - }; + return + [detection_area_id_set](const std::shared_ptr & scene_module) { + return detection_area_id_set.count(scene_module->getModuleId()) == 0; + }; } } // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/manager.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/manager.hpp index 7aa60cbbaa18b..1fbcc16461ebc 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/manager.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/manager.hpp @@ -19,7 +19,7 @@ #include #include -#include +#include #include #include @@ -41,8 +41,8 @@ class DetectionAreaModuleManager : public SceneModuleManagerInterfaceWithRTC void launchNewModules(const tier4_planning_msgs::msg::PathWithLaneId & path) override; - std::function &)> getModuleExpiredFunction( - const tier4_planning_msgs::msg::PathWithLaneId & path) override; + std::function &)> + getModuleExpiredFunction(const tier4_planning_msgs::msg::PathWithLaneId & path) override; }; class DetectionAreaModulePlugin : public PluginWrapper diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp index 61b3b185999d8..6d7754624485c 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp @@ -37,7 +37,7 @@ DetectionAreaModule::DetectionAreaModule( const lanelet::autoware::DetectionArea & detection_area_reg_elem, const PlannerParam & planner_param, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock) -: SceneModuleInterface(module_id, logger, clock), +: SceneModuleInterfaceWithRTC(module_id, logger, clock), lane_id_(lane_id), detection_area_reg_elem_(detection_area_reg_elem), state_(State::GO), diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.hpp index 9224cf4624687..bdf2d05a35bcb 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.hpp @@ -23,8 +23,8 @@ #define EIGEN_MPL2_ONLY #include -#include #include +#include #include #include @@ -38,7 +38,7 @@ using PathIndexWithPoint2d = std::pair; // front using PathIndexWithOffset = std::pair; // front index, offset using tier4_planning_msgs::msg::PathWithLaneId; -class DetectionAreaModule : public SceneModuleInterface +class DetectionAreaModule : public SceneModuleInterfaceWithRTC { public: enum class State { GO, STOP }; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml index 7a64d1d6638ff..208e7ed49de71 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml @@ -20,6 +20,7 @@ autoware_cmake autoware_behavior_velocity_planner_common + autoware_behavior_velocity_rtc_interface autoware_internal_debug_msgs autoware_interpolation autoware_lanelet2_extension diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.cpp index 39ed8e80412a6..41bdbe3e43c8b 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.cpp @@ -353,14 +353,14 @@ void IntersectionModuleManager::launchNewModules( } } -std::function &)> +std::function &)> IntersectionModuleManager::getModuleExpiredFunction( const tier4_planning_msgs::msg::PathWithLaneId & path) { const auto lane_set = planning_utils::getLaneletsOnPath( path, planner_data_->route_handler_->getLaneletMapPtr(), planner_data_->current_odometry->pose); - return [lane_set](const std::shared_ptr & scene_module) { + return [lane_set](const std::shared_ptr & scene_module) { const auto intersection_module = std::dynamic_pointer_cast(scene_module); const auto & associative_ids = intersection_module->getAssociativeIds(); for (const auto & lane : lane_set) { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.hpp index 80c87e55c6696..c6f76d7c39640 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.hpp @@ -21,6 +21,7 @@ #include #include #include +#include #include #include @@ -47,8 +48,8 @@ class IntersectionModuleManager : public SceneModuleManagerInterfaceWithRTC void launchNewModules(const tier4_planning_msgs::msg::PathWithLaneId & path) override; - std::function &)> getModuleExpiredFunction( - const tier4_planning_msgs::msg::PathWithLaneId & path) override; + std::function &)> + getModuleExpiredFunction(const tier4_planning_msgs::msg::PathWithLaneId & path) override; bool hasSameParentLaneletAndTurnDirectionWithRegistered(const lanelet::ConstLanelet & lane) const; @@ -63,7 +64,7 @@ class IntersectionModuleManager : public SceneModuleManagerInterfaceWithRTC tl_observation_pub_; }; -class MergeFromPrivateModuleManager : public SceneModuleManagerInterface +class MergeFromPrivateModuleManager : public SceneModuleManagerInterface<> { public: explicit MergeFromPrivateModuleManager(rclcpp::Node & node); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp index 7c492a9dd42bf..e33416860c319 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -53,7 +53,7 @@ IntersectionModule::IntersectionModule( const PlannerParam & planner_param, const std::set & associative_ids, const std::string & turn_direction, const bool has_traffic_light, rclcpp::Node & node, const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock) -: SceneModuleInterface(module_id, logger, clock), +: SceneModuleInterfaceWithRTC(module_id, logger, clock), planner_param_(planner_param), lane_id_(lane_id), associative_ids_(associative_ids), diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp index 164df7588bd68..6c31be2ce83b9 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -22,8 +22,8 @@ #include "object_manager.hpp" #include "result.hpp" -#include #include +#include #include #include @@ -46,7 +46,7 @@ namespace autoware::behavior_velocity_planner { -class IntersectionModule : public SceneModuleInterface +class IntersectionModule : public SceneModuleInterfaceWithRTC { public: struct PlannerParam diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/manager.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/manager.hpp index 545af1576c6a8..bea068f5b9579 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/manager.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/manager.hpp @@ -29,7 +29,7 @@ namespace autoware::behavior_velocity_planner { -class NoDrivableLaneModuleManager : public SceneModuleManagerInterface +class NoDrivableLaneModuleManager : public SceneModuleManagerInterface<> { public: explicit NoDrivableLaneModuleManager(rclcpp::Node & node); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/package.xml index 88fafeb5b90dc..4415eadef62c7 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/package.xml @@ -18,6 +18,7 @@ autoware_cmake autoware_behavior_velocity_planner_common + autoware_behavior_velocity_rtc_interface autoware_interpolation autoware_lanelet2_extension autoware_motion_utils diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/manager.cpp index 9d66aa6672d36..dca2dde33b693 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/manager.cpp @@ -69,16 +69,17 @@ void NoStoppingAreaModuleManager::launchNewModules( } } -std::function &)> +std::function &)> NoStoppingAreaModuleManager::getModuleExpiredFunction( const tier4_planning_msgs::msg::PathWithLaneId & path) { const auto no_stopping_area_id_set = planning_utils::getRegElemIdSetOnPath( path, planner_data_->route_handler_->getLaneletMapPtr(), planner_data_->current_odometry->pose); - return [no_stopping_area_id_set](const std::shared_ptr & scene_module) { - return no_stopping_area_id_set.count(scene_module->getModuleId()) == 0; - }; + return + [no_stopping_area_id_set](const std::shared_ptr & scene_module) { + return no_stopping_area_id_set.count(scene_module->getModuleId()) == 0; + }; } } // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/manager.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/manager.hpp index 7009e94612580..523cbba291632 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/manager.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/manager.hpp @@ -19,7 +19,7 @@ #include #include -#include +#include #include #include @@ -41,8 +41,8 @@ class NoStoppingAreaModuleManager : public SceneModuleManagerInterfaceWithRTC void launchNewModules(const tier4_planning_msgs::msg::PathWithLaneId & path) override; - std::function &)> getModuleExpiredFunction( - const tier4_planning_msgs::msg::PathWithLaneId & path) override; + std::function &)> + getModuleExpiredFunction(const tier4_planning_msgs::msg::PathWithLaneId & path) override; }; class NoStoppingAreaModulePlugin : public PluginWrapper diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp index 3769aed71a1ec..5c79ec69a9d98 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp @@ -41,7 +41,7 @@ NoStoppingAreaModule::NoStoppingAreaModule( const lanelet::autoware::NoStoppingArea & no_stopping_area_reg_elem, const PlannerParam & planner_param, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock) -: SceneModuleInterface(module_id, logger, clock), +: SceneModuleInterfaceWithRTC(module_id, logger, clock), lane_id_(lane_id), no_stopping_area_reg_elem_(no_stopping_area_reg_elem), planner_param_(planner_param), diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.hpp index 51f3a0d261ebd..1eafcf157623d 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.hpp @@ -17,9 +17,9 @@ #include "utils.hpp" -#include #include #include +#include #include #include @@ -31,7 +31,7 @@ namespace autoware::behavior_velocity_planner { -class NoStoppingAreaModule : public SceneModuleInterface +class NoStoppingAreaModule : public SceneModuleInterfaceWithRTC { public: struct PlannerParam diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/manager.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/manager.hpp index 32b1818214952..08c1516dea67a 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/manager.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/manager.hpp @@ -39,7 +39,7 @@ namespace autoware::behavior_velocity_planner { -class OcclusionSpotModuleManager : public SceneModuleManagerInterface +class OcclusionSpotModuleManager : public SceneModuleManagerInterface<> { public: explicit OcclusionSpotModuleManager(rclcpp::Node & node); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/README.md b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/README.md index 2abbb83575af5..c4c8d97b4b390 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/README.md +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/README.md @@ -1,3 +1,3 @@ # Behavior Velocity Planner Common -This package provides common functions as a library, which are used in the `behavior_velocity_planner` node and modules. +This package provides a behavior velocity interface without RTC, and common functions as a library, which are used in the `behavior_velocity_planner` node and modules. diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp index 4e898d9d28715..9dbed9009a93e 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp @@ -16,12 +16,14 @@ #define AUTOWARE__BEHAVIOR_VELOCITY_PLANNER_COMMON__SCENE_MODULE_INTERFACE_HPP_ #include +#include #include #include +#include #include -#include #include #include +#include #include #include @@ -30,7 +32,6 @@ #include #include #include -#include #include #include @@ -54,14 +55,12 @@ using autoware::motion_utils::PlanningBehavior; using autoware::motion_utils::VelocityFactor; using autoware::objects_of_interest_marker_interface::ColorName; using autoware::objects_of_interest_marker_interface::ObjectsOfInterestMarkerInterface; -using autoware::rtc_interface::RTCInterface; using autoware::universe_utils::DebugPublisher; using autoware::universe_utils::getOrDeclareParameter; +using autoware::universe_utils::StopWatch; using autoware_internal_debug_msgs::msg::Float64Stamped; using builtin_interfaces::msg::Time; using tier4_planning_msgs::msg::PathWithLaneId; -using tier4_rtc_msgs::msg::Module; -using tier4_rtc_msgs::msg::State; using unique_identifier_msgs::msg::UUID; struct ObjectOfInterest @@ -114,12 +113,6 @@ class SceneModuleInterface std::shared_ptr getTimeKeeper() { return time_keeper_; } - void setActivation(const bool activated) { activated_ = activated; } - void setRTCEnabled(const bool enable_rtc) { rtc_enabled_ = enable_rtc; } - bool isActivated() const { return activated_; } - bool isSafe() const { return safe_; } - double getDistance() const { return distance_; } - void resetVelocityFactor() { velocity_factor_.reset(); } VelocityFactor getVelocityFactor() const { return velocity_factor_.get(); } std::vector getObjectsOfInterestData() const { return objects_of_interest_; } @@ -127,10 +120,6 @@ class SceneModuleInterface protected: const int64_t module_id_; - bool activated_; - bool safe_; - bool rtc_enabled_; - double distance_; rclcpp::Logger logger_; rclcpp::Clock::SharedPtr clock_; std::shared_ptr planner_data_; @@ -139,16 +128,6 @@ class SceneModuleInterface std::vector objects_of_interest_; mutable std::shared_ptr time_keeper_; - void setSafe(const bool safe) - { - safe_ = safe; - if (!rtc_enabled_) { - syncActivation(); - } - } - void setDistance(const double distance) { distance_ = distance; } - void syncActivation() { setActivation(isSafe()); } - void setObjectsOfInterestData( const geometry_msgs::msg::Pose & pose, const autoware_perception_msgs::msg::Shape & shape, const ColorName & color_name) @@ -160,10 +139,39 @@ class SceneModuleInterface const std::vector & points) const; }; +template class SceneModuleManagerInterface { public: - SceneModuleManagerInterface(rclcpp::Node & node, [[maybe_unused]] const char * module_name); + SceneModuleManagerInterface(rclcpp::Node & node, [[maybe_unused]] const char * module_name) + : node_(node), clock_(node.get_clock()), logger_(node.get_logger()) + { + const auto ns = std::string("~/debug/") + module_name; + pub_debug_ = node.create_publisher(ns, 1); + if (!node.has_parameter("is_publish_debug_path")) { + is_publish_debug_path_ = node.declare_parameter("is_publish_debug_path"); + } else { + is_publish_debug_path_ = node.get_parameter("is_publish_debug_path").as_bool(); + } + if (is_publish_debug_path_) { + pub_debug_path_ = node.create_publisher( + std::string("~/debug/path_with_lane_id/") + module_name, 1); + } + pub_virtual_wall_ = node.create_publisher( + std::string("~/virtual_wall/") + module_name, 5); + pub_velocity_factor_ = node.create_publisher( + std::string("/planning/velocity_factors/") + module_name, 1); + pub_infrastructure_commands_ = + node.create_publisher( + "~/output/infrastructure_commands", 1); + + processing_time_publisher_ = std::make_shared(&node, "~/debug"); + + pub_processing_time_detail_ = node.create_publisher( + "~/debug/processing_time_detail_ms/" + std::string(module_name), 1); + + time_keeper_ = std::make_shared(pub_processing_time_detail_); + } virtual ~SceneModuleManagerInterface() = default; @@ -171,31 +179,111 @@ class SceneModuleManagerInterface void updateSceneModuleInstances( const std::shared_ptr & planner_data, - const tier4_planning_msgs::msg::PathWithLaneId & path); + const tier4_planning_msgs::msg::PathWithLaneId & path) + { + planner_data_ = planner_data; + + launchNewModules(path); + deleteExpiredModules(path); + } virtual void plan(tier4_planning_msgs::msg::PathWithLaneId * path) { modifyPathVelocity(path); } protected: - virtual void modifyPathVelocity(tier4_planning_msgs::msg::PathWithLaneId * path); + virtual void modifyPathVelocity(tier4_planning_msgs::msg::PathWithLaneId * path) + { + universe_utils::ScopedTimeTrack st( + "SceneModuleManagerInterface::modifyPathVelocity", *time_keeper_); + StopWatch stop_watch; + stop_watch.tic("Total"); + visualization_msgs::msg::MarkerArray debug_marker_array; + autoware_adapi_v1_msgs::msg::VelocityFactorArray velocity_factor_array; + velocity_factor_array.header.frame_id = "map"; + velocity_factor_array.header.stamp = clock_->now(); + + tier4_v2x_msgs::msg::InfrastructureCommandArray infrastructure_command_array; + infrastructure_command_array.stamp = clock_->now(); + + for (const auto & scene_module : scene_modules_) { + scene_module->resetVelocityFactor(); + scene_module->setPlannerData(planner_data_); + scene_module->modifyPathVelocity(path); + + // The velocity factor must be called after modifyPathVelocity. + const auto velocity_factor = scene_module->getVelocityFactor(); + if (velocity_factor.behavior != PlanningBehavior::UNKNOWN) { + velocity_factor_array.factors.emplace_back(velocity_factor); + } + + if (const auto command = scene_module->getInfrastructureCommand()) { + infrastructure_command_array.commands.push_back(*command); + } + + for (const auto & marker : scene_module->createDebugMarkerArray().markers) { + debug_marker_array.markers.push_back(marker); + } + + virtual_wall_marker_creator_.add_virtual_walls(scene_module->createVirtualWalls()); + } + + pub_velocity_factor_->publish(velocity_factor_array); + pub_infrastructure_commands_->publish(infrastructure_command_array); + pub_debug_->publish(debug_marker_array); + if (is_publish_debug_path_) { + tier4_planning_msgs::msg::PathWithLaneId debug_path; + debug_path.header = path->header; + debug_path.points = path->points; + pub_debug_path_->publish(debug_path); + } + pub_virtual_wall_->publish(virtual_wall_marker_creator_.create_markers(clock_->now())); + processing_time_publisher_->publish( + std::string(getModuleName()) + "/processing_time_ms", stop_watch.toc("Total")); + } virtual void launchNewModules(const tier4_planning_msgs::msg::PathWithLaneId & path) = 0; - virtual std::function &)> - getModuleExpiredFunction(const tier4_planning_msgs::msg::PathWithLaneId & path) = 0; + virtual std::function &)> getModuleExpiredFunction( + const tier4_planning_msgs::msg::PathWithLaneId & path) = 0; - virtual void deleteExpiredModules(const tier4_planning_msgs::msg::PathWithLaneId & path); + virtual void deleteExpiredModules(const tier4_planning_msgs::msg::PathWithLaneId & path) + { + const auto isModuleExpired = getModuleExpiredFunction(path); + + auto itr = scene_modules_.begin(); + while (itr != scene_modules_.end()) { + if (isModuleExpired(*itr)) { + itr = scene_modules_.erase(itr); + } else { + itr++; + } + } + } bool isModuleRegistered(const int64_t module_id) { return registered_module_id_set_.count(module_id) != 0; } - void registerModule(const std::shared_ptr & scene_module); + void registerModule(const std::shared_ptr & scene_module) + { + RCLCPP_DEBUG( + logger_, "register task: module = %s, id = %lu", getModuleName(), + scene_module->getModuleId()); + registered_module_id_set_.emplace(scene_module->getModuleId()); + scene_module->setTimeKeeper(time_keeper_); + scene_modules_.insert(scene_module); + } size_t findEgoSegmentIndex( - const std::vector & points) const; + const std::vector & points) const + { + const auto & p = planner_data_; + return autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + points, p->current_odometry->pose, p->ego_nearest_dist_threshold, + p->ego_nearest_yaw_threshold); + } - std::set> scene_modules_; + std::set> scene_modules_; std::set registered_module_id_set_; std::shared_ptr planner_data_; @@ -220,66 +308,19 @@ class SceneModuleManagerInterface std::shared_ptr time_keeper_; }; - -class SceneModuleManagerInterfaceWithRTC : public SceneModuleManagerInterface -{ -public: - SceneModuleManagerInterfaceWithRTC( - rclcpp::Node & node, const char * module_name, const bool enable_rtc = true); - - void plan(tier4_planning_msgs::msg::PathWithLaneId * path) override; - -protected: - RTCInterface rtc_interface_; - std::unordered_map map_uuid_; - - ObjectsOfInterestMarkerInterface objects_of_interest_marker_interface_; - - virtual void sendRTC(const Time & stamp); - - virtual void setActivation(); - - void updateRTCStatus( - const UUID & uuid, const bool safe, const uint8_t state, const double distance, - const Time & stamp) - { - rtc_interface_.updateCooperateStatus(uuid, safe, state, distance, distance, stamp); - } - - void removeRTCStatus(const UUID & uuid) { rtc_interface_.removeCooperateStatus(uuid); } - - void publishRTCStatus(const Time & stamp) - { - rtc_interface_.removeExpiredCooperateStatus(); - rtc_interface_.publishCooperateStatus(stamp); - } - - UUID getUUID(const int64_t & module_id) const; - - void generateUUID(const int64_t & module_id); - - void removeUUID(const int64_t & module_id); - - void publishObjectsOfInterestMarker(); - - void deleteExpiredModules(const tier4_planning_msgs::msg::PathWithLaneId & path) override; - - static bool getEnableRTC(rclcpp::Node & node, const std::string & param_name) - { - bool enable_rtc = true; - - try { - enable_rtc = getOrDeclareParameter(node, "enable_all_modules_auto_mode") - ? false - : getOrDeclareParameter(node, param_name); - } catch (const std::exception & e) { - enable_rtc = getOrDeclareParameter(node, param_name); - } - - return enable_rtc; - } -}; - +extern template SceneModuleManagerInterface::SceneModuleManagerInterface( + rclcpp::Node & node, [[maybe_unused]] const char * module_name); +extern template size_t SceneModuleManagerInterface::findEgoSegmentIndex( + const std::vector & points) const; +extern template void SceneModuleManagerInterface::updateSceneModuleInstances( + const std::shared_ptr & planner_data, + const tier4_planning_msgs::msg::PathWithLaneId & path); +extern template void SceneModuleManagerInterface::modifyPathVelocity( + tier4_planning_msgs::msg::PathWithLaneId * path); +extern template void SceneModuleManagerInterface::deleteExpiredModules( + const tier4_planning_msgs::msg::PathWithLaneId & path); +extern template void SceneModuleManagerInterface::registerModule( + const std::shared_ptr & scene_module); } // namespace autoware::behavior_velocity_planner #endif // AUTOWARE__BEHAVIOR_VELOCITY_PLANNER_COMMON__SCENE_MODULE_INTERFACE_HPP_ diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml index a0b54cb879cab..002c3362260cc 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml @@ -29,7 +29,6 @@ autoware_perception_msgs autoware_planning_msgs autoware_route_handler - autoware_rtc_interface autoware_universe_utils autoware_vehicle_info_utils autoware_velocity_smoother diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp index cdfde1ce51205..ffd454012d13e 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp @@ -13,29 +13,20 @@ // limitations under the License. #include -#include #include -#include -#include #include #include #include #include -#include #include namespace autoware::behavior_velocity_planner { -using autoware::universe_utils::StopWatch; - SceneModuleInterface::SceneModuleInterface( const int64_t module_id, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock) : module_id_(module_id), - activated_(false), - safe_(false), - distance_(std::numeric_limits::lowest()), logger_(logger), clock_(clock), time_keeper_(std::shared_ptr()) @@ -50,222 +41,17 @@ size_t SceneModuleInterface::findEgoSegmentIndex( points, p->current_odometry->pose, p->ego_nearest_dist_threshold); } -SceneModuleManagerInterface::SceneModuleManagerInterface( - rclcpp::Node & node, [[maybe_unused]] const char * module_name) -: node_(node), clock_(node.get_clock()), logger_(node.get_logger()) -{ - const auto ns = std::string("~/debug/") + module_name; - pub_debug_ = node.create_publisher(ns, 1); - if (!node.has_parameter("is_publish_debug_path")) { - is_publish_debug_path_ = node.declare_parameter("is_publish_debug_path"); - } else { - is_publish_debug_path_ = node.get_parameter("is_publish_debug_path").as_bool(); - } - if (is_publish_debug_path_) { - pub_debug_path_ = node.create_publisher( - std::string("~/debug/path_with_lane_id/") + module_name, 1); - } - pub_virtual_wall_ = node.create_publisher( - std::string("~/virtual_wall/") + module_name, 5); - pub_velocity_factor_ = node.create_publisher( - std::string("/planning/velocity_factors/") + module_name, 1); - pub_infrastructure_commands_ = - node.create_publisher( - "~/output/infrastructure_commands", 1); - - processing_time_publisher_ = std::make_shared(&node, "~/debug"); - - pub_processing_time_detail_ = node.create_publisher( - "~/debug/processing_time_detail_ms/" + std::string(module_name), 1); - - time_keeper_ = std::make_shared(pub_processing_time_detail_); -} - -size_t SceneModuleManagerInterface::findEgoSegmentIndex( - const std::vector & points) const -{ - const auto & p = planner_data_; - return autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( - points, p->current_odometry->pose, p->ego_nearest_dist_threshold, p->ego_nearest_yaw_threshold); -} - -void SceneModuleManagerInterface::updateSceneModuleInstances( +template SceneModuleManagerInterface::SceneModuleManagerInterface( + rclcpp::Node & node, [[maybe_unused]] const char * module_name); +template size_t SceneModuleManagerInterface::findEgoSegmentIndex( + const std::vector & points) const; +template void SceneModuleManagerInterface::updateSceneModuleInstances( const std::shared_ptr & planner_data, - const tier4_planning_msgs::msg::PathWithLaneId & path) -{ - planner_data_ = planner_data; - - launchNewModules(path); - deleteExpiredModules(path); -} - -void SceneModuleManagerInterface::modifyPathVelocity( - tier4_planning_msgs::msg::PathWithLaneId * path) -{ - universe_utils::ScopedTimeTrack st( - "SceneModuleManagerInterface::modifyPathVelocity", *time_keeper_); - StopWatch stop_watch; - stop_watch.tic("Total"); - visualization_msgs::msg::MarkerArray debug_marker_array; - autoware_adapi_v1_msgs::msg::VelocityFactorArray velocity_factor_array; - velocity_factor_array.header.frame_id = "map"; - velocity_factor_array.header.stamp = clock_->now(); - - tier4_v2x_msgs::msg::InfrastructureCommandArray infrastructure_command_array; - infrastructure_command_array.stamp = clock_->now(); - - for (const auto & scene_module : scene_modules_) { - scene_module->resetVelocityFactor(); - scene_module->setPlannerData(planner_data_); - scene_module->modifyPathVelocity(path); - - // The velocity factor must be called after modifyPathVelocity. - const auto velocity_factor = scene_module->getVelocityFactor(); - if (velocity_factor.behavior != PlanningBehavior::UNKNOWN) { - velocity_factor_array.factors.emplace_back(velocity_factor); - } - - if (const auto command = scene_module->getInfrastructureCommand()) { - infrastructure_command_array.commands.push_back(*command); - } - - for (const auto & marker : scene_module->createDebugMarkerArray().markers) { - debug_marker_array.markers.push_back(marker); - } - - virtual_wall_marker_creator_.add_virtual_walls(scene_module->createVirtualWalls()); - } - - pub_velocity_factor_->publish(velocity_factor_array); - pub_infrastructure_commands_->publish(infrastructure_command_array); - pub_debug_->publish(debug_marker_array); - if (is_publish_debug_path_) { - tier4_planning_msgs::msg::PathWithLaneId debug_path; - debug_path.header = path->header; - debug_path.points = path->points; - pub_debug_path_->publish(debug_path); - } - pub_virtual_wall_->publish(virtual_wall_marker_creator_.create_markers(clock_->now())); - processing_time_publisher_->publish( - std::string(getModuleName()) + "/processing_time_ms", stop_watch.toc("Total")); -} - -void SceneModuleManagerInterface::deleteExpiredModules( - const tier4_planning_msgs::msg::PathWithLaneId & path) -{ - const auto isModuleExpired = getModuleExpiredFunction(path); - - auto itr = scene_modules_.begin(); - while (itr != scene_modules_.end()) { - if (isModuleExpired(*itr)) { - itr = scene_modules_.erase(itr); - } else { - itr++; - } - } -} - -void SceneModuleManagerInterface::registerModule( - const std::shared_ptr & scene_module) -{ - RCLCPP_DEBUG( - logger_, "register task: module = %s, id = %lu", getModuleName(), scene_module->getModuleId()); - registered_module_id_set_.emplace(scene_module->getModuleId()); - scene_module->setTimeKeeper(time_keeper_); - scene_modules_.insert(scene_module); -} - -SceneModuleManagerInterfaceWithRTC::SceneModuleManagerInterfaceWithRTC( - rclcpp::Node & node, const char * module_name, const bool enable_rtc) -: SceneModuleManagerInterface(node, module_name), - rtc_interface_(&node, module_name, enable_rtc), - objects_of_interest_marker_interface_(&node, module_name) -{ -} - -void SceneModuleManagerInterfaceWithRTC::plan(tier4_planning_msgs::msg::PathWithLaneId * path) -{ - setActivation(); - modifyPathVelocity(path); - sendRTC(path->header.stamp); - publishObjectsOfInterestMarker(); -} - -void SceneModuleManagerInterfaceWithRTC::sendRTC(const Time & stamp) -{ - for (const auto & scene_module : scene_modules_) { - const UUID uuid = getUUID(scene_module->getModuleId()); - const auto state = !scene_module->isActivated() && scene_module->isSafe() - ? State::WAITING_FOR_EXECUTION - : State::RUNNING; - updateRTCStatus(uuid, scene_module->isSafe(), state, scene_module->getDistance(), stamp); - } - publishRTCStatus(stamp); -} - -void SceneModuleManagerInterfaceWithRTC::setActivation() -{ - for (const auto & scene_module : scene_modules_) { - const UUID uuid = getUUID(scene_module->getModuleId()); - scene_module->setActivation(rtc_interface_.isActivated(uuid)); - scene_module->setRTCEnabled(rtc_interface_.isRTCEnabled(uuid)); - } -} - -UUID SceneModuleManagerInterfaceWithRTC::getUUID(const int64_t & module_id) const -{ - if (map_uuid_.count(module_id) == 0) { - const UUID uuid; - return uuid; - } - return map_uuid_.at(module_id); -} - -void SceneModuleManagerInterfaceWithRTC::generateUUID(const int64_t & module_id) -{ - map_uuid_.insert({module_id, autoware::universe_utils::generateUUID()}); -} - -void SceneModuleManagerInterfaceWithRTC::removeUUID(const int64_t & module_id) -{ - const auto result = map_uuid_.erase(module_id); - if (result == 0) { - RCLCPP_WARN_STREAM(logger_, "[removeUUID] module_id = " << module_id << " is not registered."); - } -} - -void SceneModuleManagerInterfaceWithRTC::publishObjectsOfInterestMarker() -{ - for (const auto & scene_module : scene_modules_) { - const auto objects = scene_module->getObjectsOfInterestData(); - for (const auto & obj : objects) { - objects_of_interest_marker_interface_.insertObjectData(obj.pose, obj.shape, obj.color); - } - scene_module->clearObjectsOfInterestData(); - } - - objects_of_interest_marker_interface_.publishMarkerArray(); -} - -void SceneModuleManagerInterfaceWithRTC::deleteExpiredModules( - const tier4_planning_msgs::msg::PathWithLaneId & path) -{ - const auto isModuleExpired = getModuleExpiredFunction(path); - - auto itr = scene_modules_.begin(); - while (itr != scene_modules_.end()) { - if (isModuleExpired(*itr)) { - const UUID uuid = getUUID((*itr)->getModuleId()); - updateRTCStatus( - uuid, (*itr)->isSafe(), State::SUCCEEDED, std::numeric_limits::lowest(), - clock_->now()); - removeUUID((*itr)->getModuleId()); - registered_module_id_set_.erase((*itr)->getModuleId()); - itr = scene_modules_.erase(itr); - } else { - itr++; - } - } -} - + const tier4_planning_msgs::msg::PathWithLaneId & path); +template void SceneModuleManagerInterface::modifyPathVelocity( + tier4_planning_msgs::msg::PathWithLaneId * path); +template void SceneModuleManagerInterface::deleteExpiredModules( + const tier4_planning_msgs::msg::PathWithLaneId & path); +template void SceneModuleManagerInterface::registerModule( + const std::shared_ptr & scene_module); } // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/CMakeLists.txt b/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/CMakeLists.txt new file mode 100644 index 0000000000000..2bd9b9b8d20f0 --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/CMakeLists.txt @@ -0,0 +1,11 @@ +cmake_minimum_required(VERSION 3.14) +project(autoware_behavior_velocity_rtc_interface) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/scene_module_interface_with_rtc.cpp +) + +ament_auto_package(INSTALL_TO_SHARE) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/README.md b/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/README.md new file mode 100644 index 0000000000000..79b5a4e3d7b95 --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/README.md @@ -0,0 +1,3 @@ +# Behavior Velocity RTC Interface + +This package provides a behavior velocity interface with RTC, which are used in the `behavior_velocity_planner` node and modules. diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp new file mode 100644 index 0000000000000..4e30ab019aa4e --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp @@ -0,0 +1,154 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__BEHAVIOR_VELOCITY_RTC_INTERFACE__SCENE_MODULE_INTERFACE_WITH_RTC_HPP_ +#define AUTOWARE__BEHAVIOR_VELOCITY_RTC_INTERFACE__SCENE_MODULE_INTERFACE_WITH_RTC_HPP_ + +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +// Debug +#include +#include + +namespace autoware::behavior_velocity_planner +{ + +using autoware::rtc_interface::RTCInterface; +using autoware::universe_utils::getOrDeclareParameter; +using builtin_interfaces::msg::Time; +using tier4_planning_msgs::msg::PathWithLaneId; +using tier4_rtc_msgs::msg::Module; +using tier4_rtc_msgs::msg::State; +using unique_identifier_msgs::msg::UUID; + +class SceneModuleInterfaceWithRTC : public SceneModuleInterface +{ +public: + explicit SceneModuleInterfaceWithRTC( + const int64_t module_id, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock); + virtual ~SceneModuleInterfaceWithRTC() = default; + + void setActivation(const bool activated) { activated_ = activated; } + void setRTCEnabled(const bool enable_rtc) { rtc_enabled_ = enable_rtc; } + bool isActivated() const { return activated_; } + bool isSafe() const { return safe_; } + double getDistance() const { return distance_; } + +protected: + bool activated_; + bool safe_; + bool rtc_enabled_; + double distance_; + + void setSafe(const bool safe) + { + safe_ = safe; + if (!rtc_enabled_) { + syncActivation(); + } + } + void setDistance(const double distance) { distance_ = distance; } + void syncActivation() { setActivation(isSafe()); } +}; + +class SceneModuleManagerInterfaceWithRTC +: public SceneModuleManagerInterface +{ +public: + SceneModuleManagerInterfaceWithRTC( + rclcpp::Node & node, const char * module_name, const bool enable_rtc = true); + + void plan(tier4_planning_msgs::msg::PathWithLaneId * path) override; + +protected: + RTCInterface rtc_interface_; + std::unordered_map map_uuid_; + + ObjectsOfInterestMarkerInterface objects_of_interest_marker_interface_; + + virtual void sendRTC(const Time & stamp); + + virtual void setActivation(); + + void updateRTCStatus( + const UUID & uuid, const bool safe, const uint8_t state, const double distance, + const Time & stamp) + { + rtc_interface_.updateCooperateStatus(uuid, safe, state, distance, distance, stamp); + } + + void removeRTCStatus(const UUID & uuid) { rtc_interface_.removeCooperateStatus(uuid); } + + void publishRTCStatus(const Time & stamp) + { + rtc_interface_.removeExpiredCooperateStatus(); + rtc_interface_.publishCooperateStatus(stamp); + } + + UUID getUUID(const int64_t & module_id) const; + + void generateUUID(const int64_t & module_id); + + void removeUUID(const int64_t & module_id); + + void publishObjectsOfInterestMarker(); + + void deleteExpiredModules(const tier4_planning_msgs::msg::PathWithLaneId & path) override; + + static bool getEnableRTC(rclcpp::Node & node, const std::string & param_name) + { + bool enable_rtc = true; + + try { + enable_rtc = getOrDeclareParameter(node, "enable_all_modules_auto_mode") + ? false + : getOrDeclareParameter(node, param_name); + } catch (const std::exception & e) { + enable_rtc = getOrDeclareParameter(node, param_name); + } + + return enable_rtc; + } +}; + +extern template size_t +SceneModuleManagerInterface::findEgoSegmentIndex( + const std::vector & points) const; +extern template void +SceneModuleManagerInterface::updateSceneModuleInstances( + const std::shared_ptr & planner_data, + const tier4_planning_msgs::msg::PathWithLaneId & path); +extern template void SceneModuleManagerInterface::modifyPathVelocity( + tier4_planning_msgs::msg::PathWithLaneId * path); +extern template void SceneModuleManagerInterface::registerModule( + const std::shared_ptr & scene_module); +} // namespace autoware::behavior_velocity_planner + +#endif // AUTOWARE__BEHAVIOR_VELOCITY_RTC_INTERFACE__SCENE_MODULE_INTERFACE_WITH_RTC_HPP_ diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/package.xml new file mode 100644 index 0000000000000..88b252106a90a --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/package.xml @@ -0,0 +1,38 @@ + + + + autoware_behavior_velocity_rtc_interface + 0.40.0 + The autoware_behavior_velocity_rtc_interface package + + Mamoru Sobue + Takayuki Murooka + Tomoya Kimura + Shumpei Wakabayashi + Takagi, Isamu + Fumiya Watanabe + + Apache License 2.0 + + Takayuki Murooka + + ament_cmake_auto + autoware_cmake + + autoware_behavior_velocity_planner_common + autoware_motion_utils + autoware_planning_msgs + autoware_rtc_interface + autoware_universe_utils + rclcpp + rclcpp_components + tier4_planning_msgs + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/src/scene_module_interface_with_rtc.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/src/scene_module_interface_with_rtc.cpp new file mode 100644 index 0000000000000..abac509fd2b2b --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/src/scene_module_interface_with_rtc.cpp @@ -0,0 +1,140 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +namespace autoware::behavior_velocity_planner +{ + +SceneModuleInterfaceWithRTC::SceneModuleInterfaceWithRTC( + const int64_t module_id, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock) +: SceneModuleInterface(module_id, logger, clock), + activated_(false), + safe_(false), + distance_(std::numeric_limits::lowest()) +{ +} + +SceneModuleManagerInterfaceWithRTC::SceneModuleManagerInterfaceWithRTC( + rclcpp::Node & node, const char * module_name, const bool enable_rtc) +: SceneModuleManagerInterface(node, module_name), + rtc_interface_(&node, module_name, enable_rtc), + objects_of_interest_marker_interface_(&node, module_name) +{ +} + +void SceneModuleManagerInterfaceWithRTC::plan(tier4_planning_msgs::msg::PathWithLaneId * path) +{ + setActivation(); + modifyPathVelocity(path); + sendRTC(path->header.stamp); + publishObjectsOfInterestMarker(); +} + +void SceneModuleManagerInterfaceWithRTC::sendRTC(const Time & stamp) +{ + for (const auto & scene_module : scene_modules_) { + const UUID uuid = getUUID(scene_module->getModuleId()); + const auto state = !scene_module->isActivated() && scene_module->isSafe() + ? State::WAITING_FOR_EXECUTION + : State::RUNNING; + updateRTCStatus(uuid, scene_module->isSafe(), state, scene_module->getDistance(), stamp); + } + publishRTCStatus(stamp); +} + +void SceneModuleManagerInterfaceWithRTC::setActivation() +{ + for (const auto & scene_module : scene_modules_) { + const UUID uuid = getUUID(scene_module->getModuleId()); + scene_module->setActivation(rtc_interface_.isActivated(uuid)); + scene_module->setRTCEnabled(rtc_interface_.isRTCEnabled(uuid)); + } +} + +UUID SceneModuleManagerInterfaceWithRTC::getUUID(const int64_t & module_id) const +{ + if (map_uuid_.count(module_id) == 0) { + const UUID uuid; + return uuid; + } + return map_uuid_.at(module_id); +} + +void SceneModuleManagerInterfaceWithRTC::generateUUID(const int64_t & module_id) +{ + map_uuid_.insert({module_id, autoware::universe_utils::generateUUID()}); +} + +void SceneModuleManagerInterfaceWithRTC::removeUUID(const int64_t & module_id) +{ + const auto result = map_uuid_.erase(module_id); + if (result == 0) { + RCLCPP_WARN_STREAM(logger_, "[removeUUID] module_id = " << module_id << " is not registered."); + } +} + +void SceneModuleManagerInterfaceWithRTC::publishObjectsOfInterestMarker() +{ + for (const auto & scene_module : scene_modules_) { + const auto objects = scene_module->getObjectsOfInterestData(); + for (const auto & obj : objects) { + objects_of_interest_marker_interface_.insertObjectData(obj.pose, obj.shape, obj.color); + } + scene_module->clearObjectsOfInterestData(); + } + + objects_of_interest_marker_interface_.publishMarkerArray(); +} + +void SceneModuleManagerInterfaceWithRTC::deleteExpiredModules( + const tier4_planning_msgs::msg::PathWithLaneId & path) +{ + const auto isModuleExpired = getModuleExpiredFunction(path); + + auto itr = scene_modules_.begin(); + while (itr != scene_modules_.end()) { + if (isModuleExpired(*itr)) { + const UUID uuid = getUUID((*itr)->getModuleId()); + updateRTCStatus( + uuid, (*itr)->isSafe(), State::SUCCEEDED, std::numeric_limits::lowest(), + clock_->now()); + removeUUID((*itr)->getModuleId()); + registered_module_id_set_.erase((*itr)->getModuleId()); + itr = scene_modules_.erase(itr); + } else { + itr++; + } + } +} + +template size_t SceneModuleManagerInterface::findEgoSegmentIndex( + const std::vector & points) const; +template void SceneModuleManagerInterface::updateSceneModuleInstances( + const std::shared_ptr & planner_data, + const tier4_planning_msgs::msg::PathWithLaneId & path); +template void SceneModuleManagerInterface::modifyPathVelocity( + tier4_planning_msgs::msg::PathWithLaneId * path); +template void SceneModuleManagerInterface::registerModule( + const std::shared_ptr & scene_module); +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/manager.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/manager.hpp index 131ba32f32100..068ed81015fb1 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/manager.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/manager.hpp @@ -25,7 +25,7 @@ namespace autoware::behavior_velocity_planner { -class RunOutModuleManager : public SceneModuleManagerInterface +class RunOutModuleManager : public SceneModuleManagerInterface<> { public: explicit RunOutModuleManager(rclcpp::Node & node); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/manager.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/manager.hpp index 950bb8471cc22..f98db8b88b7a9 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/manager.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/manager.hpp @@ -29,7 +29,7 @@ namespace autoware::behavior_velocity_planner { -class SpeedBumpModuleManager : public SceneModuleManagerInterface +class SpeedBumpModuleManager : public SceneModuleManagerInterface<> { public: explicit SpeedBumpModuleManager(rclcpp::Node & node); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/manager.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/manager.hpp index bef8a5eef4ac0..c746e2bf6a314 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/manager.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/manager.hpp @@ -33,7 +33,7 @@ namespace autoware::behavior_velocity_planner { using StopLineWithLaneId = std::pair; -class StopLineModuleManager : public SceneModuleManagerInterface +class StopLineModuleManager : public SceneModuleManagerInterface<> { public: explicit StopLineModuleManager(rclcpp::Node & node); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/manager.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/manager.hpp index a7a0d83be6368..c5b9293fcdcc5 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/manager.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/manager.hpp @@ -38,7 +38,7 @@ namespace autoware::behavior_velocity_planner * @param node A reference to the ROS node. */ class TemplateModuleManager -: public autoware::behavior_velocity_planner::SceneModuleManagerInterface +: public autoware::behavior_velocity_planner::SceneModuleManagerInterface<> { public: explicit TemplateModuleManager(rclcpp::Node & node); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/package.xml index 082973d9431e5..ebc45d372f92d 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/package.xml @@ -20,6 +20,7 @@ autoware_adapi_v1_msgs autoware_behavior_velocity_planner_common + autoware_behavior_velocity_rtc_interface autoware_lanelet2_extension autoware_motion_utils autoware_perception_msgs diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.cpp index b6747724ba6f7..1b66824d04623 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.cpp @@ -123,7 +123,7 @@ void TrafficLightModuleManager::launchNewModules( } } -std::function &)> +std::function &)> TrafficLightModuleManager::getModuleExpiredFunction( const tier4_planning_msgs::msg::PathWithLaneId & path) { @@ -131,7 +131,7 @@ TrafficLightModuleManager::getModuleExpiredFunction( path, planner_data_->route_handler_->getLaneletMapPtr(), planner_data_->current_odometry->pose); return [this, lanelet_id_set]( - [[maybe_unused]] const std::shared_ptr & scene_module) { + [[maybe_unused]] const std::shared_ptr & scene_module) { for (const auto & id : lanelet_id_set) { if (isModuleRegisteredFromExistingAssociatedModule(id)) { return false; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.hpp index eb8ef53ddb604..5ac32d1107880 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.hpp @@ -19,7 +19,7 @@ #include #include -#include +#include #include #include @@ -42,8 +42,8 @@ class TrafficLightModuleManager : public SceneModuleManagerInterfaceWithRTC void launchNewModules(const tier4_planning_msgs::msg::PathWithLaneId & path) override; - std::function &)> getModuleExpiredFunction( - const tier4_planning_msgs::msg::PathWithLaneId & path) override; + std::function &)> + getModuleExpiredFunction(const tier4_planning_msgs::msg::PathWithLaneId & path) override; void modifyPathVelocity(tier4_planning_msgs::msg::PathWithLaneId * path) override; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp index 5eb0d5aa5f267..458d8e1588a5b 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp @@ -44,7 +44,7 @@ TrafficLightModule::TrafficLightModule( const int64_t lane_id, const lanelet::TrafficLight & traffic_light_reg_elem, lanelet::ConstLanelet lane, const PlannerParam & planner_param, const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock) -: SceneModuleInterface(lane_id, logger, clock), +: SceneModuleInterfaceWithRTC(lane_id, logger, clock), lane_id_(lane_id), traffic_light_reg_elem_(traffic_light_reg_elem), lane_(lane), diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.hpp index 8221bb3740273..3af13bc1927ce 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.hpp @@ -23,8 +23,8 @@ #define EIGEN_MPL2_ONLY #include #include -#include #include +#include #include #include @@ -33,7 +33,7 @@ namespace autoware::behavior_velocity_planner { -class TrafficLightModule : public SceneModuleInterface +class TrafficLightModule : public SceneModuleInterfaceWithRTC { public: using TrafficSignal = autoware_perception_msgs::msg::TrafficLightGroup; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/manager.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/manager.hpp index ba5a4b23a6fe0..8e0abc98c90de 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/manager.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/manager.hpp @@ -29,7 +29,7 @@ namespace autoware::behavior_velocity_planner { -class VirtualTrafficLightModuleManager : public SceneModuleManagerInterface +class VirtualTrafficLightModuleManager : public SceneModuleManagerInterface<> { public: explicit VirtualTrafficLightModuleManager(rclcpp::Node & node); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/manager.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/manager.hpp index 85d4495914823..b323d6d201795 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/manager.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/manager.hpp @@ -35,7 +35,7 @@ namespace autoware::behavior_velocity_planner { using tier4_planning_msgs::msg::PathWithLaneId; -class WalkwayModuleManager : public SceneModuleManagerInterface +class WalkwayModuleManager : public SceneModuleManagerInterface<> { public: explicit WalkwayModuleManager(rclcpp::Node & node); From a313653f7b14a40dd0c938b96ea68f9ee1e2fe48 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 27 Dec 2024 10:22:15 +0900 Subject: [PATCH 119/334] feat(build_depends.repos): update version of autoware_internal_msgs (#9806) Signed-off-by: Takayuki Murooka --- build_depends.repos | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/build_depends.repos b/build_depends.repos index 7e547be7409cf..2313a9be487a6 100644 --- a/build_depends.repos +++ b/build_depends.repos @@ -32,7 +32,7 @@ repositories: core/autoware_internal_msgs: type: git url: https://github.com/autowarefoundation/autoware_internal_msgs.git - version: 1.2.0 + version: 1.3.0 # universe universe/external/tier4_autoware_msgs: type: git From 4d1f69d793449c349d6a7befc79120ea6a9f8efa Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Fri, 27 Dec 2024 11:23:07 +0900 Subject: [PATCH 120/334] refactor(autoware_universe_utils): add missing 's' in the class of diagnostics_interface (#9777) Signed-off-by: kminoda --- .../universe_utils/ros/diagnostics_interface.hpp | 6 +++--- .../src/ros/diagnostics_interface.cpp | 16 ++++++++-------- .../test/src/ros/test_diagnostics_interface.cpp | 16 ++++++++-------- .../src/gyro_odometer_core.cpp | 2 +- .../src/gyro_odometer_core.hpp | 2 +- .../src/lidar_marker_localizer.cpp | 2 +- .../src/lidar_marker_localizer.hpp | 2 +- .../src/localization_error_monitor.cpp | 2 +- .../src/localization_error_monitor.hpp | 2 +- .../ndt_scan_matcher/map_update_module.hpp | 10 +++++----- .../ndt_scan_matcher/ndt_scan_matcher_core.hpp | 12 ++++++------ .../src/map_update_module.cpp | 8 ++++---- .../src/ndt_scan_matcher_core.cpp | 14 +++++++------- .../src/pose_initializer_core.cpp | 2 +- .../src/pose_initializer_core.hpp | 2 +- 15 files changed, 49 insertions(+), 49 deletions(-) diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/ros/diagnostics_interface.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/ros/diagnostics_interface.hpp index 120aed7c7548e..db370eb46ef43 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/ros/diagnostics_interface.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/ros/diagnostics_interface.hpp @@ -24,10 +24,10 @@ namespace autoware::universe_utils { -class DiagnosticInterface +class DiagnosticsInterface { public: - DiagnosticInterface(rclcpp::Node * node, const std::string & diagnostic_name); + DiagnosticsInterface(rclcpp::Node * node, const std::string & diagnostic_name); void clear(); void add_key_value(const diagnostic_msgs::msg::KeyValue & key_value_msg); template @@ -48,7 +48,7 @@ class DiagnosticInterface }; template -void DiagnosticInterface::add_key_value(const std::string & key, const T & value) +void DiagnosticsInterface::add_key_value(const std::string & key, const T & value) { diagnostic_msgs::msg::KeyValue key_value; key_value.key = key; diff --git a/common/autoware_universe_utils/src/ros/diagnostics_interface.cpp b/common/autoware_universe_utils/src/ros/diagnostics_interface.cpp index 978af27f202d4..e4d1ec8494113 100644 --- a/common/autoware_universe_utils/src/ros/diagnostics_interface.cpp +++ b/common/autoware_universe_utils/src/ros/diagnostics_interface.cpp @@ -23,7 +23,7 @@ namespace autoware::universe_utils { -DiagnosticInterface::DiagnosticInterface(rclcpp::Node * node, const std::string & diagnostic_name) +DiagnosticsInterface::DiagnosticsInterface(rclcpp::Node * node, const std::string & diagnostic_name) : clock_(node->get_clock()) { diagnostics_pub_ = @@ -34,7 +34,7 @@ DiagnosticInterface::DiagnosticInterface(rclcpp::Node * node, const std::string diagnostics_status_msg_.hardware_id = node->get_name(); } -void DiagnosticInterface::clear() +void DiagnosticsInterface::clear() { diagnostics_status_msg_.values.clear(); diagnostics_status_msg_.values.shrink_to_fit(); @@ -43,7 +43,7 @@ void DiagnosticInterface::clear() diagnostics_status_msg_.message = ""; } -void DiagnosticInterface::add_key_value(const diagnostic_msgs::msg::KeyValue & key_value_msg) +void DiagnosticsInterface::add_key_value(const diagnostic_msgs::msg::KeyValue & key_value_msg) { auto it = std::find_if( std::begin(diagnostics_status_msg_.values), std::end(diagnostics_status_msg_.values), @@ -56,7 +56,7 @@ void DiagnosticInterface::add_key_value(const diagnostic_msgs::msg::KeyValue & k } } -void DiagnosticInterface::add_key_value(const std::string & key, const std::string & value) +void DiagnosticsInterface::add_key_value(const std::string & key, const std::string & value) { diagnostic_msgs::msg::KeyValue key_value; key_value.key = key; @@ -64,7 +64,7 @@ void DiagnosticInterface::add_key_value(const std::string & key, const std::stri add_key_value(key_value); } -void DiagnosticInterface::add_key_value(const std::string & key, bool value) +void DiagnosticsInterface::add_key_value(const std::string & key, bool value) { diagnostic_msgs::msg::KeyValue key_value; key_value.key = key; @@ -72,7 +72,7 @@ void DiagnosticInterface::add_key_value(const std::string & key, bool value) add_key_value(key_value); } -void DiagnosticInterface::update_level_and_message(const int8_t level, const std::string & message) +void DiagnosticsInterface::update_level_and_message(const int8_t level, const std::string & message) { if ((level > diagnostic_msgs::msg::DiagnosticStatus::OK)) { if (!diagnostics_status_msg_.message.empty()) { @@ -85,12 +85,12 @@ void DiagnosticInterface::update_level_and_message(const int8_t level, const std } } -void DiagnosticInterface::publish(const rclcpp::Time & publish_time_stamp) +void DiagnosticsInterface::publish(const rclcpp::Time & publish_time_stamp) { diagnostics_pub_->publish(create_diagnostics_array(publish_time_stamp)); } -diagnostic_msgs::msg::DiagnosticArray DiagnosticInterface::create_diagnostics_array( +diagnostic_msgs::msg::DiagnosticArray DiagnosticsInterface::create_diagnostics_array( const rclcpp::Time & publish_time_stamp) const { diagnostic_msgs::msg::DiagnosticArray diagnostics_msg; diff --git a/common/autoware_universe_utils/test/src/ros/test_diagnostics_interface.cpp b/common/autoware_universe_utils/test/src/ros/test_diagnostics_interface.cpp index a0683694cc2b7..6ec4fccf78b43 100644 --- a/common/autoware_universe_utils/test/src/ros/test_diagnostics_interface.cpp +++ b/common/autoware_universe_utils/test/src/ros/test_diagnostics_interface.cpp @@ -25,9 +25,9 @@ #include #include -using autoware::universe_utils::DiagnosticInterface; +using autoware::universe_utils::DiagnosticsInterface; -class TestDiagnosticInterface : public ::testing::Test +class TestDiagnosticsInterface : public ::testing::Test { protected: void SetUp() override @@ -44,9 +44,9 @@ class TestDiagnosticInterface : public ::testing::Test * Test clear(): * Verify that calling clear() resets DiagnosticStatus values, level, and message. */ -TEST_F(TestDiagnosticInterface, ClearTest) +TEST_F(TestDiagnosticsInterface, ClearTest) { - DiagnosticInterface module(node_.get(), "test_diagnostic"); + DiagnosticsInterface module(node_.get(), "test_diagnostic"); // Add some key-value pairs and update level/message module.add_key_value("param1", 42); @@ -87,9 +87,9 @@ TEST_F(TestDiagnosticInterface, ClearTest) * Test add_key_value(): * Verify that adding the same key updates its value instead of adding a duplicate. */ -TEST_F(TestDiagnosticInterface, AddKeyValueTest) +TEST_F(TestDiagnosticsInterface, AddKeyValueTest) { - DiagnosticInterface module(node_.get(), "test_diagnostic"); + DiagnosticsInterface module(node_.get(), "test_diagnostic"); // Call the template version of add_key_value() with different types module.add_key_value("string_key", std::string("initial_value")); @@ -139,9 +139,9 @@ TEST_F(TestDiagnosticInterface, AddKeyValueTest) * Verify that the level is updated to the highest severity and * that messages are concatenated if level > OK. */ -TEST_F(TestDiagnosticInterface, UpdateLevelAndMessageTest) +TEST_F(TestDiagnosticsInterface, UpdateLevelAndMessageTest) { - DiagnosticInterface module(node_.get(), "test_diagnostic"); + DiagnosticsInterface module(node_.get(), "test_diagnostic"); // Initial status is level=OK(0), message="" module.update_level_and_message(diagnostic_msgs::msg::DiagnosticStatus::OK, "Initial OK"); diff --git a/localization/autoware_gyro_odometer/src/gyro_odometer_core.cpp b/localization/autoware_gyro_odometer/src/gyro_odometer_core.cpp index d52fb5e798b58..0a85f75b74ad7 100644 --- a/localization/autoware_gyro_odometer/src/gyro_odometer_core.cpp +++ b/localization/autoware_gyro_odometer/src/gyro_odometer_core.cpp @@ -73,7 +73,7 @@ GyroOdometerNode::GyroOdometerNode(const rclcpp::NodeOptions & node_options) "twist_with_covariance", rclcpp::QoS{10}); diagnostics_ = - std::make_unique(this, "gyro_odometer_status"); + std::make_unique(this, "gyro_odometer_status"); // TODO(YamatoAndo) createTimer } diff --git a/localization/autoware_gyro_odometer/src/gyro_odometer_core.hpp b/localization/autoware_gyro_odometer/src/gyro_odometer_core.hpp index 70334738e9ce3..b59e6af341ec2 100644 --- a/localization/autoware_gyro_odometer/src/gyro_odometer_core.hpp +++ b/localization/autoware_gyro_odometer/src/gyro_odometer_core.hpp @@ -80,7 +80,7 @@ class GyroOdometerNode : public rclcpp::Node std::deque vehicle_twist_queue_; std::deque gyro_queue_; - std::unique_ptr diagnostics_; + std::unique_ptr diagnostics_; }; } // namespace autoware::gyro_odometer diff --git a/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.cpp b/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.cpp index bc7dbbcfc9ca1..34fc61797231b 100644 --- a/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.cpp +++ b/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.cpp @@ -125,7 +125,7 @@ LidarMarkerLocalizer::LidarMarkerLocalizer(const rclcpp::NodeOptions & node_opti tf_listener_ = std::make_shared(*tf_buffer_, this, false); diagnostics_interface_.reset( - new autoware::universe_utils::DiagnosticInterface(this, "marker_detection_status")); + new autoware::universe_utils::DiagnosticsInterface(this, "marker_detection_status")); } void LidarMarkerLocalizer::initialize_diagnostics() diff --git a/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.hpp b/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.hpp index 1b5672cff9d04..22a0c3f642563 100644 --- a/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.hpp +++ b/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.hpp @@ -134,7 +134,7 @@ class LidarMarkerLocalizer : public rclcpp::Node rclcpp::Publisher::SharedPtr pub_debug_pose_with_covariance_; rclcpp::Publisher::SharedPtr pub_marker_pointcloud_; - std::shared_ptr diagnostics_interface_; + std::shared_ptr diagnostics_interface_; Param param_; bool is_activated_; diff --git a/localization/autoware_localization_error_monitor/src/localization_error_monitor.cpp b/localization/autoware_localization_error_monitor/src/localization_error_monitor.cpp index 5ebcd105d57ba..1f26f6b80aa17 100644 --- a/localization/autoware_localization_error_monitor/src/localization_error_monitor.cpp +++ b/localization/autoware_localization_error_monitor/src/localization_error_monitor.cpp @@ -59,7 +59,7 @@ LocalizationErrorMonitor::LocalizationErrorMonitor(const rclcpp::NodeOptions & o logger_configure_ = std::make_unique(this); diagnostics_error_monitor_ = - std::make_unique(this, "ellipse_error_status"); + std::make_unique(this, "ellipse_error_status"); } void LocalizationErrorMonitor::on_odom(nav_msgs::msg::Odometry::ConstSharedPtr input_msg) diff --git a/localization/autoware_localization_error_monitor/src/localization_error_monitor.hpp b/localization/autoware_localization_error_monitor/src/localization_error_monitor.hpp index b38958c420b19..b7d2454eb9f75 100644 --- a/localization/autoware_localization_error_monitor/src/localization_error_monitor.hpp +++ b/localization/autoware_localization_error_monitor/src/localization_error_monitor.hpp @@ -39,7 +39,7 @@ class LocalizationErrorMonitor : public rclcpp::Node std::unique_ptr logger_configure_; - std::unique_ptr diagnostics_error_monitor_; + std::unique_ptr diagnostics_error_monitor_; double scale_; double error_ellipse_size_; diff --git a/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/map_update_module.hpp b/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/map_update_module.hpp index bf8fce2b302c0..12990259f88cd 100644 --- a/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/map_update_module.hpp +++ b/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/map_update_module.hpp @@ -42,7 +42,7 @@ namespace autoware::ndt_scan_matcher { -using DiagnosticInterface = autoware::universe_utils::DiagnosticInterface; +using DiagnosticsInterface = autoware::universe_utils::DiagnosticsInterface; class MapUpdateModule { @@ -63,19 +63,19 @@ class MapUpdateModule void callback_timer( const bool is_activated, const std::optional & position, - std::unique_ptr & diagnostics_ptr); + std::unique_ptr & diagnostics_ptr); [[nodiscard]] bool should_update_map( const geometry_msgs::msg::Point & position, - std::unique_ptr & diagnostics_ptr); + std::unique_ptr & diagnostics_ptr); void update_map( const geometry_msgs::msg::Point & position, - std::unique_ptr & diagnostics_ptr); + std::unique_ptr & diagnostics_ptr); // Update the specified NDT bool update_ndt( const geometry_msgs::msg::Point & position, NdtType & ndt, - std::unique_ptr & diagnostics_ptr); + std::unique_ptr & diagnostics_ptr); void publish_partial_pcd_map(); rclcpp::Publisher::SharedPtr loaded_pcd_pub_; diff --git a/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_scan_matcher_core.hpp b/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_scan_matcher_core.hpp index 25b7417ffbe3c..e083e6751c3db 100644 --- a/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_scan_matcher_core.hpp +++ b/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_scan_matcher_core.hpp @@ -211,12 +211,12 @@ class NDTScanMatcher : public rclcpp::Node std::unique_ptr regularization_pose_buffer_; std::atomic is_activated_; - std::unique_ptr diagnostics_scan_points_; - std::unique_ptr diagnostics_initial_pose_; - std::unique_ptr diagnostics_regularization_pose_; - std::unique_ptr diagnostics_map_update_; - std::unique_ptr diagnostics_ndt_align_; - std::unique_ptr diagnostics_trigger_node_; + std::unique_ptr diagnostics_scan_points_; + std::unique_ptr diagnostics_initial_pose_; + std::unique_ptr diagnostics_regularization_pose_; + std::unique_ptr diagnostics_map_update_; + std::unique_ptr diagnostics_ndt_align_; + std::unique_ptr diagnostics_trigger_node_; std::unique_ptr map_update_module_; std::unique_ptr logger_configure_; diff --git a/localization/autoware_ndt_scan_matcher/src/map_update_module.cpp b/localization/autoware_ndt_scan_matcher/src/map_update_module.cpp index eea0b8f3d06c4..299d596401b19 100644 --- a/localization/autoware_ndt_scan_matcher/src/map_update_module.cpp +++ b/localization/autoware_ndt_scan_matcher/src/map_update_module.cpp @@ -56,7 +56,7 @@ MapUpdateModule::MapUpdateModule( void MapUpdateModule::callback_timer( const bool is_activated, const std::optional & position, - std::unique_ptr & diagnostics_ptr) + std::unique_ptr & diagnostics_ptr) { // check is_activated diagnostics_ptr->add_key_value("is_activated", is_activated); @@ -87,7 +87,7 @@ void MapUpdateModule::callback_timer( bool MapUpdateModule::should_update_map( const geometry_msgs::msg::Point & position, - std::unique_ptr & diagnostics_ptr) + std::unique_ptr & diagnostics_ptr) { last_update_position_mtx_.lock(); @@ -143,7 +143,7 @@ bool MapUpdateModule::out_of_map_range(const geometry_msgs::msg::Point & positio void MapUpdateModule::update_map( const geometry_msgs::msg::Point & position, - std::unique_ptr & diagnostics_ptr) + std::unique_ptr & diagnostics_ptr) { diagnostics_ptr->add_key_value("is_need_rebuild", need_rebuild_); @@ -231,7 +231,7 @@ void MapUpdateModule::update_map( bool MapUpdateModule::update_ndt( const geometry_msgs::msg::Point & position, NdtType & ndt, - std::unique_ptr & diagnostics_ptr) + std::unique_ptr & diagnostics_ptr) { diagnostics_ptr->add_key_value("maps_size_before", ndt.getCurrentMapIDs().size()); diff --git a/localization/autoware_ndt_scan_matcher/src/ndt_scan_matcher_core.cpp b/localization/autoware_ndt_scan_matcher/src/ndt_scan_matcher_core.cpp index cef8724423bed..d3e1fa5982867 100644 --- a/localization/autoware_ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/autoware_ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -51,7 +51,7 @@ using autoware::localization_util::pose_to_matrix4f; using autoware::localization_util::SmartPoseBuffer; using autoware::localization_util::TreeStructuredParzenEstimator; -using autoware::universe_utils::DiagnosticInterface; +using autoware::universe_utils::DiagnosticsInterface; tier4_debug_msgs::msg::Float32Stamped make_float32_stamped( const builtin_interfaces::msg::Time & stamp, const float data) @@ -141,7 +141,7 @@ NDTScanMatcher::NDTScanMatcher(const rclcpp::NodeOptions & options) std::make_unique(this->get_logger(), value_as_unlimited, value_as_unlimited); diagnostics_regularization_pose_ = - std::make_unique(this, "regularization_pose_subscriber_status"); + std::make_unique(this, "regularization_pose_subscriber_status"); } sensor_aligned_pose_pub_ = @@ -209,13 +209,13 @@ NDTScanMatcher::NDTScanMatcher(const rclcpp::NodeOptions & options) map_update_module_ = std::make_unique(this, &ndt_ptr_mtx_, ndt_ptr_, param_.dynamic_map_loading); - diagnostics_scan_points_ = std::make_unique(this, "scan_matching_status"); + diagnostics_scan_points_ = std::make_unique(this, "scan_matching_status"); diagnostics_initial_pose_ = - std::make_unique(this, "initial_pose_subscriber_status"); - diagnostics_map_update_ = std::make_unique(this, "map_update_status"); - diagnostics_ndt_align_ = std::make_unique(this, "ndt_align_service_status"); + std::make_unique(this, "initial_pose_subscriber_status"); + diagnostics_map_update_ = std::make_unique(this, "map_update_status"); + diagnostics_ndt_align_ = std::make_unique(this, "ndt_align_service_status"); diagnostics_trigger_node_ = - std::make_unique(this, "trigger_node_service_status"); + std::make_unique(this, "trigger_node_service_status"); logger_configure_ = std::make_unique(this); } diff --git a/localization/autoware_pose_initializer/src/pose_initializer_core.cpp b/localization/autoware_pose_initializer/src/pose_initializer_core.cpp index 67d5c447c09b6..5bde25a564f1d 100644 --- a/localization/autoware_pose_initializer/src/pose_initializer_core.cpp +++ b/localization/autoware_pose_initializer/src/pose_initializer_core.cpp @@ -40,7 +40,7 @@ PoseInitializer::PoseInitializer(const rclcpp::NodeOptions & options) output_pose_covariance_ = get_covariance_parameter(this, "output_pose_covariance"); gnss_particle_covariance_ = get_covariance_parameter(this, "gnss_particle_covariance"); - diagnostics_pose_reliable_ = std::make_unique( + diagnostics_pose_reliable_ = std::make_unique( this, "pose_initializer_status"); if (declare_parameter("ekf_enabled")) { diff --git a/localization/autoware_pose_initializer/src/pose_initializer_core.hpp b/localization/autoware_pose_initializer/src/pose_initializer_core.hpp index 5305bcc3ad347..a0c1ed3a86576 100644 --- a/localization/autoware_pose_initializer/src/pose_initializer_core.hpp +++ b/localization/autoware_pose_initializer/src/pose_initializer_core.hpp @@ -60,7 +60,7 @@ class PoseInitializer : public rclcpp::Node std::unique_ptr ekf_localization_trigger_; std::unique_ptr ndt_localization_trigger_; std::unique_ptr logger_configure_; - std::unique_ptr diagnostics_pose_reliable_; + std::unique_ptr diagnostics_pose_reliable_; double stop_check_duration_; void change_node_trigger(bool flag, bool need_spin = false); From 8048b9ef8eb4efa1a6db0351ae6be7acdcc1e3ef Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Fri, 27 Dec 2024 12:03:00 +0900 Subject: [PATCH 121/334] fix(autoware_static_centerline_generator): fix bugprone-exception-escape (#9805) fix:bugprone-error Signed-off-by: kobayu858 --- .../src/main.cpp | 62 +++++++++++-------- 1 file changed, 35 insertions(+), 27 deletions(-) diff --git a/planning/autoware_static_centerline_generator/src/main.cpp b/planning/autoware_static_centerline_generator/src/main.cpp index 811d57c6036ef..71a076ee86fe0 100644 --- a/planning/autoware_static_centerline_generator/src/main.cpp +++ b/planning/autoware_static_centerline_generator/src/main.cpp @@ -14,38 +14,46 @@ #include "static_centerline_generator_node.hpp" +#include #include #include int main(int argc, char * argv[]) { - rclcpp::init(argc, argv); - - // initialize node - rclcpp::NodeOptions node_options; - auto node = - std::make_shared( - node_options); - - // get ros parameter - const auto mode = node->declare_parameter("mode"); - - // process - if (mode == "AUTO") { - node->generate_centerline(); - node->validate(); - node->save_map(); - } else if (mode == "GUI") { - node->generate_centerline(); - } else if (mode == "VMB") { - // Do nothing - } else { - throw std::invalid_argument("The `mode` is invalid."); + try { + rclcpp::init(argc, argv); + + // initialize node + rclcpp::NodeOptions node_options; + auto node = + std::make_shared( + node_options); + + // get ros parameter + const auto mode = node->declare_parameter("mode"); + + // process + if (mode == "AUTO") { + node->generate_centerline(); + node->validate(); + node->save_map(); + } else if (mode == "GUI") { + node->generate_centerline(); + } else if (mode == "VMB") { + // Do nothing + } else { + throw std::invalid_argument("The `mode` is invalid."); + } + + // NOTE: spin node to keep showing debug path/trajectory in rviz with transient local + rclcpp::spin(node); + rclcpp::shutdown(); + } catch (const std::exception & e) { + std::cerr << "Exception in main(): " << e.what() << std::endl; + return {}; + } catch (...) { + std::cerr << "Unknown exception in main()" << std::endl; + return {}; } - - // NOTE: spin node to keep showing debug path/trajectory in rviz with transient local - rclcpp::spin(node); - rclcpp::shutdown(); - return 0; } From 7e3a80c0987c507b789148d3df1073798df5b65d Mon Sep 17 00:00:00 2001 From: mkquda <168697710+mkquda@users.noreply.github.com> Date: Fri, 27 Dec 2024 12:13:25 +0900 Subject: [PATCH 122/334] feat(lane_change): revise current lane objects filtering (#9785) * consider stopped front objects Signed-off-by: mohammad alqudah * simplify computation of dist to front current lane object Signed-off-by: mohammad alqudah * add flag to enable/disable keeping distance from front stopped vehicle Signed-off-by: mohammad alqudah * fix object filtering test Signed-off-by: mohammad alqudah --------- Signed-off-by: mohammad alqudah --- .../README.md | 1 + .../config/lane_change.param.yaml | 1 + .../structs/parameters.hpp | 1 + .../src/manager.cpp | 4 ++++ .../src/scene.cpp | 12 ++++------ .../src/utils/utils.cpp | 22 +++++++++---------- .../test/test_lane_change_scene.cpp | 5 ++--- 7 files changed, 23 insertions(+), 23 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md index 86d8d1c0c1413..5a6c22a731bf9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md @@ -886,6 +886,7 @@ The following parameters are configurable in [lane_change.param.yaml](https://gi | `backward_length_buffer_for_end_of_lane` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change | 3.0 | | `backward_length_buffer_for_blocking_object` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change when there is an object in front | 3.0 | | `backward_length_from_intersection` | [m] | double | Distance threshold from the last intersection to invalidate or cancel the lane change path | 5.0 | +| `enable_stopped_vehicle_buffer` | [-] | bool | If true, will keep enough distance from current lane front stopped object to perform lane change when possible | true | | `trajectory.max_prepare_duration` | [s] | double | The maximum preparation time for the ego vehicle to be ready to perform lane change. | 4.0 | | `trajectory.min_prepare_duration` | [s] | double | The minimum preparation time for the ego vehicle to be ready to perform lane change. | 2.0 | | `trajectory.lateral_jerk` | [m/s3] | double | Lateral jerk value for lane change path generation | 0.5 | diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml index bf892b3058a16..61e41b4ea3ea4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml @@ -5,6 +5,7 @@ backward_length_buffer_for_end_of_lane: 3.0 # [m] backward_length_buffer_for_blocking_object: 3.0 # [m] backward_length_from_intersection: 5.0 # [m] + enable_stopped_vehicle_buffer: true # turn signal min_length_for_turn_signal_activation: 10.0 # [m] diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp index 719bbbbf3057a..94020e8a08279 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp @@ -149,6 +149,7 @@ struct Parameters double backward_length_buffer_for_end_of_lane{0.0}; double backward_length_buffer_for_blocking_object{0.0}; double backward_length_from_intersection{5.0}; + bool enable_stopped_vehicle_buffer{false}; // parked vehicle double object_check_min_road_shoulder_width{0.5}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp index 1bb41069140e7..9f7a811770b5d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp @@ -195,6 +195,8 @@ LCParamPtr LaneChangeModuleManager::set_params(rclcpp::Node * node, const std::s getOrDeclareParameter(*node, parameter("backward_length_buffer_for_blocking_object")); p.backward_length_from_intersection = getOrDeclareParameter(*node, parameter("backward_length_from_intersection")); + p.enable_stopped_vehicle_buffer = + getOrDeclareParameter(*node, parameter("enable_stopped_vehicle_buffer")); if (p.backward_length_buffer_for_end_of_lane < 1.0) { RCLCPP_WARN_STREAM( @@ -305,6 +307,8 @@ void LaneChangeModuleManager::updateModuleParams(const std::vectorbackward_length_buffer_for_blocking_object); updateParam( parameters, ns + "lane_change_finish_judge_buffer", p->lane_change_finish_judge_buffer); + updateParam( + parameters, ns + "enable_stopped_vehicle_buffer", p->enable_stopped_vehicle_buffer); updateParam( parameters, ns + "finish_judge_lateral_threshold", p->th_finish_judge_lateral_diff); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index 7f0e6d7f575f6..e2543c602cbfa 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -515,7 +515,9 @@ void NormalLaneChange::insert_stop_point_on_current_lanes(PathWithLaneId & path) const auto dist_to_terminal_stop = std::min(dist_to_terminal_start, distance_to_last_fit_width); const auto terminal_stop_reason = status_.is_valid_path ? "no safe path" : "no valid path"; - if (filtered_objects_.current_lane.empty()) { + if ( + filtered_objects_.current_lane.empty() || + !lane_change_parameters_->enable_stopped_vehicle_buffer) { set_stop_pose(dist_to_terminal_stop, path, terminal_stop_reason); return; } @@ -948,8 +950,6 @@ FilteredLanesObjects NormalLaneChange::filter_objects() const filtered_objects.target_lane_trailing.reserve(reserve_size); filtered_objects.others.reserve(reserve_size); - const auto stopped_obj_vel_th = lane_change_parameters_->safety.th_stopped_object_velocity; - for (const auto & object : objects.objects) { auto ext_object = utils::lane_change::transform(object, *lane_change_parameters_); const auto & ext_obj_pose = ext_object.initial_pose; @@ -968,12 +968,8 @@ FilteredLanesObjects NormalLaneChange::filter_objects() const continue; } - // TODO(Azu): We have to think about how to remove is_within_vel_th without breaking AW behavior - const auto is_moving = velocity_filter( - ext_object.initial_twist, stopped_obj_vel_th, std::numeric_limits::max()); - if ( - ahead_of_ego && is_moving && is_before_terminal && + ahead_of_ego && is_before_terminal && !boost::geometry::disjoint(ext_object.initial_polygon, lanes_polygon.current)) { // check only the objects that are in front of the ego vehicle filtered_objects.current_lane.push_back(ext_object); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp index 147ef3856ac4e..9360435891632 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp @@ -920,19 +920,17 @@ double get_min_dist_to_current_lanes_obj( continue; } - // calculate distance from path front to the stationary object polygon on the ego lane. - for (const auto & polygon_p : object.initial_polygon.outer()) { - const auto p_fp = autoware::universe_utils::toMsg(polygon_p.to_3d()); - const auto lateral_fp = motion_utils::calcLateralOffset(path_points, p_fp); - - // ignore if the point is not on ego path - if (std::abs(lateral_fp) > (common_data_ptr->bpp_param_ptr->vehicle_width / 2)) { - continue; - } - - const auto current_distance_to_obj = motion_utils::calcSignedArcLength(path_points, 0, p_fp); - min_dist_to_obj = std::min(min_dist_to_obj, current_distance_to_obj); + // check if object is on ego path + const auto obj_half_width = object.shape.dimensions.y / 2; + const auto obj_lat_dist_to_path = + std::abs(motion_utils::calcLateralOffset(path_points, object.initial_pose.position)) - + obj_half_width; + if (obj_lat_dist_to_path > (common_data_ptr->bpp_param_ptr->vehicle_width / 2)) { + continue; } + + min_dist_to_obj = std::min(min_dist_to_obj, dist_to_obj); + break; } return min_dist_to_obj; } diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp index 114a38a77876c..5fb445788672c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp @@ -242,15 +242,14 @@ TEST_F(TestNormalLaneChange, testFilteredObjects) const auto & filtered_objects = get_filtered_objects(); - // Note: There's 1 stopping object in current lanes, however, it was filtered out. const auto filtered_size = filtered_objects.current_lane.size() + filtered_objects.target_lane_leading.size() + filtered_objects.target_lane_trailing.size() + filtered_objects.others.size(); EXPECT_EQ(filtered_size, planner_data_->dynamic_object->objects.size()); - EXPECT_EQ(filtered_objects.current_lane.size(), 0); + EXPECT_EQ(filtered_objects.current_lane.size(), 1); EXPECT_EQ(filtered_objects.target_lane_leading.size(), 2); EXPECT_EQ(filtered_objects.target_lane_trailing.size(), 0); - EXPECT_EQ(filtered_objects.others.size(), 2); + EXPECT_EQ(filtered_objects.others.size(), 1); } TEST_F(TestNormalLaneChange, testGetPathWhenValid) From f211728650c8abcf757fb8088c9b824780b736b6 Mon Sep 17 00:00:00 2001 From: mkquda <168697710+mkquda@users.noreply.github.com> Date: Fri, 27 Dec 2024 15:38:11 +0900 Subject: [PATCH 123/334] feat(lane_change): add text display for candidate path sampling metrics (#9810) * display candidate path sampling metrics on rviz Signed-off-by: mohammad alqudah * rename struct Signed-off-by: mohammad alqudah --------- Signed-off-by: mohammad alqudah --- .../structs/debug.hpp | 12 ++++++ .../src/scene.cpp | 8 +++- .../src/utils/markers.cpp | 42 +++++++++++++++++++ 3 files changed, 61 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp index 8738b412e18b9..90b13f86976b2 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp @@ -25,10 +25,20 @@ #include #include +#include namespace autoware::behavior_path_planner::lane_change { using utils::path_safety_checker::CollisionCheckDebugMap; + +struct MetricsDebug +{ + LaneChangePhaseMetrics prep_metric; + std::vector lc_metrics; + double max_prepare_length; + double max_lane_changing_length; +}; + struct Debug { std::string module_type; @@ -41,6 +51,7 @@ struct Debug lanelet::ConstLanelets current_lanes; lanelet::ConstLanelets target_lanes; lanelet::ConstLanelets target_backward_lanes; + std::vector lane_change_metrics; double collision_check_object_debug_lifetime{0.0}; double distance_to_end_of_current_lane{std::numeric_limits::max()}; double distance_to_lane_change_finished{std::numeric_limits::max()}; @@ -64,6 +75,7 @@ struct Debug current_lanes.clear(); target_lanes.clear(); target_backward_lanes.clear(); + lane_change_metrics.clear(); collision_check_object_debug_lifetime = 0.0; distance_to_end_of_current_lane = std::numeric_limits::max(); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index e2543c602cbfa..fb4f7aeca1525 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -1061,14 +1061,20 @@ std::vector NormalLaneChange::get_lane_changing_metrics( }); const auto max_path_velocity = prep_segment.points.back().point.longitudinal_velocity_mps; - return calculation::calc_shift_phase_metrics( + const auto lc_metrics = calculation::calc_shift_phase_metrics( common_data_ptr_, shift_length, prep_metric.velocity, max_path_velocity, prep_metric.sampled_lon_accel, max_lane_changing_length); + + const auto max_prep_length = common_data_ptr_->transient_data.dist_to_terminal_start; + lane_change_debug_.lane_change_metrics.push_back( + {prep_metric, lc_metrics, max_prep_length, max_lane_changing_length}); + return lc_metrics; } bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths) const { lane_change_debug_.collision_check_objects.clear(); + lane_change_debug_.lane_change_metrics.clear(); if (!common_data_ptr_->is_lanes_available()) { RCLCPP_WARN(logger_, "lanes are not available. Not expected."); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp index 30af582175d14..da9ee52b038c6 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp @@ -16,6 +16,7 @@ #include "autoware/behavior_path_planner_common/marker_utils/utils.hpp" #include +#include #include #include @@ -185,6 +186,46 @@ MarkerArray showExecutionInfo(const Debug & debug_data, const geometry_msgs::msg return marker_array; } +MarkerArray ShowLaneChangeMetricsInfo( + const Debug & debug_data, const geometry_msgs::msg::Pose & pose) +{ + MarkerArray marker_array; + if (debug_data.lane_change_metrics.empty()) { + return marker_array; + } + + auto text_marker = createDefaultMarker( + "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "sampling_metrics", 0, Marker::TEXT_VIEW_FACING, + createMarkerScale(0.6, 0.6, 0.6), colors::yellow()); + text_marker.pose = autoware::universe_utils::calcOffsetPose(pose, 10.0, 15.0, 0.0); + + text_marker.text = fmt::format("{:<12}", "") + fmt::format("{:^18}|", "lat_accel[m/s2]") + + fmt::format("{:^18}|", "lon_accel[m/s2]") + + fmt::format("{:^17}|", "velocity[m/s]") + + fmt::format("{:^15}|", "duration[s]") + fmt::format("{:^15}|", "length[m]") + + fmt::format("{:^20}\n", "max_length_th[m]"); + for (const auto & metrics : debug_data.lane_change_metrics) { + text_marker.text += fmt::format("{:-<170}\n", ""); + const auto & p_m = metrics.prep_metric; + text_marker.text += + fmt::format("{:<17}", "prep_metrics:") + fmt::format("{:^10.3f}", p_m.lat_accel) + + fmt::format("{:^21.3f}", p_m.actual_lon_accel) + fmt::format("{:^12.3f}", p_m.velocity) + + fmt::format("{:^15.3f}", p_m.duration) + fmt::format("{:^15.3f}", p_m.length) + + fmt::format("{:^17.3f}\n", metrics.max_prepare_length); + text_marker.text += fmt::format("{:<20}\n", "lc_metrics:"); + for (const auto lc_m : metrics.lc_metrics) { + text_marker.text += + fmt::format("{:<15}", "") + fmt::format("{:^10.3f}", lc_m.lat_accel) + + fmt::format("{:^21.3f}", lc_m.actual_lon_accel) + fmt::format("{:^12.3f}", lc_m.velocity) + + fmt::format("{:^15.3f}", lc_m.duration) + fmt::format("{:^15.3f}", lc_m.length) + + fmt::format("{:^17.3f}\n", metrics.max_lane_changing_length); + } + } + + marker_array.markers.push_back(text_marker); + return marker_array; +} + MarkerArray createDebugMarkerArray( const Debug & debug_data, const geometry_msgs::msg::Pose & ego_pose) { @@ -212,6 +253,7 @@ MarkerArray createDebugMarkerArray( } add(showExecutionInfo(debug_data, ego_pose)); + add(ShowLaneChangeMetricsInfo(debug_data, ego_pose)); // lanes add(laneletsAsTriangleMarkerArray( From 5de2e4a3123c37390e83bd45a6e11e7755db56b8 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 27 Dec 2024 16:35:02 +0900 Subject: [PATCH 124/334] feat(behavior_velocity_detection_area): use base class without RTC (#9802) * feat(behavior_velocity_detection_area): use base class without RTC Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../config/detection_area.param.yaml | 1 - .../package.xml | 1 - .../src/manager.cpp | 16 +++++----------- .../src/manager.hpp | 8 ++++---- .../src/scene.cpp | 13 ++++--------- .../src/scene.hpp | 4 ++-- 6 files changed, 15 insertions(+), 28 deletions(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/config/detection_area.param.yaml b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/config/detection_area.param.yaml index b49b43794685c..9294795274066 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/config/detection_area.param.yaml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/config/detection_area.param.yaml @@ -8,5 +8,4 @@ state_clear_time: 2.0 hold_stop_margin_distance: 0.0 distance_to_judge_over_stop_line: 0.5 - enable_rtc: false # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval suppress_pass_judge_when_stopping: false diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/package.xml index 90aaddf96feef..ff91cf40a32a6 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/package.xml @@ -18,7 +18,6 @@ eigen3_cmake_module autoware_behavior_velocity_planner_common - autoware_behavior_velocity_rtc_interface autoware_lanelet2_extension autoware_motion_utils autoware_planning_msgs diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/manager.cpp index 62f5b88699a37..fb2c17d9e3745 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/manager.cpp @@ -34,8 +34,7 @@ using autoware::universe_utils::getOrDeclareParameter; using lanelet::autoware::DetectionArea; DetectionAreaModuleManager::DetectionAreaModuleManager(rclcpp::Node & node) -: SceneModuleManagerInterfaceWithRTC( - node, getModuleName(), getEnableRTC(node, std::string(getModuleName()) + ".enable_rtc")) +: SceneModuleManagerInterface(node, getModuleName()) { const std::string ns(DetectionAreaModuleManager::getModuleName()); planner_param_.stop_margin = getOrDeclareParameter(node, ns + ".stop_margin"); @@ -66,25 +65,20 @@ void DetectionAreaModuleManager::launchNewModules( registerModule(std::make_shared( module_id, lane_id, *detection_area_with_lane_id.first, planner_param_, logger_.get_child("detection_area_module"), clock_)); - generateUUID(module_id); - updateRTCStatus( - getUUID(module_id), true, State::WAITING_FOR_EXECUTION, - std::numeric_limits::lowest(), path.header.stamp); } } } -std::function &)> +std::function &)> DetectionAreaModuleManager::getModuleExpiredFunction( const tier4_planning_msgs::msg::PathWithLaneId & path) { const auto detection_area_id_set = planning_utils::getRegElemIdSetOnPath( path, planner_data_->route_handler_->getLaneletMapPtr(), planner_data_->current_odometry->pose); - return - [detection_area_id_set](const std::shared_ptr & scene_module) { - return detection_area_id_set.count(scene_module->getModuleId()) == 0; - }; + return [detection_area_id_set](const std::shared_ptr & scene_module) { + return detection_area_id_set.count(scene_module->getModuleId()) == 0; + }; } } // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/manager.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/manager.hpp index 1fbcc16461ebc..4b34ac4a45298 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/manager.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/manager.hpp @@ -19,7 +19,7 @@ #include #include -#include +#include #include #include @@ -29,7 +29,7 @@ namespace autoware::behavior_velocity_planner { -class DetectionAreaModuleManager : public SceneModuleManagerInterfaceWithRTC +class DetectionAreaModuleManager : public SceneModuleManagerInterface<> { public: explicit DetectionAreaModuleManager(rclcpp::Node & node); @@ -41,8 +41,8 @@ class DetectionAreaModuleManager : public SceneModuleManagerInterfaceWithRTC void launchNewModules(const tier4_planning_msgs::msg::PathWithLaneId & path) override; - std::function &)> - getModuleExpiredFunction(const tier4_planning_msgs::msg::PathWithLaneId & path) override; + std::function &)> getModuleExpiredFunction( + const tier4_planning_msgs::msg::PathWithLaneId & path) override; }; class DetectionAreaModulePlugin : public PluginWrapper diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp index 6d7754624485c..031c45753022e 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp @@ -37,7 +37,7 @@ DetectionAreaModule::DetectionAreaModule( const lanelet::autoware::DetectionArea & detection_area_reg_elem, const PlannerParam & planner_param, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock) -: SceneModuleInterfaceWithRTC(module_id, logger, clock), +: SceneModuleInterface(module_id, logger, clock), lane_id_(lane_id), detection_area_reg_elem_(detection_area_reg_elem), state_(State::GO), @@ -105,12 +105,10 @@ bool DetectionAreaModule::modifyPathVelocity(PathWithLaneId * path) modified_stop_line_seg_idx = current_seg_idx; } - setDistance(stop_dist); - // Check state - setSafe(detection_area::can_clear_stop_state( - last_obstacle_found_time_, clock_->now(), planner_param_.state_clear_time)); - if (isActivated()) { + const bool is_safe = detection_area::can_clear_stop_state( + last_obstacle_found_time_, clock_->now(), planner_param_.state_clear_time); + if (is_safe) { last_obstacle_found_time_ = {}; if (!planner_param_.suppress_pass_judge_when_stopping || !is_stopped) { state_ = State::GO; @@ -139,7 +137,6 @@ bool DetectionAreaModule::modifyPathVelocity(PathWithLaneId * path) dead_line_seg_idx); if (dist_from_ego_to_dead_line < 0.0) { RCLCPP_WARN(logger_, "[detection_area] vehicle is over dead line"); - setSafe(true); return true; } } @@ -152,7 +149,6 @@ bool DetectionAreaModule::modifyPathVelocity(PathWithLaneId * path) if ( state_ != State::STOP && dist_from_ego_to_stop < -planner_param_.distance_to_judge_over_stop_line) { - setSafe(true); return true; } @@ -169,7 +165,6 @@ bool DetectionAreaModule::modifyPathVelocity(PathWithLaneId * path) RCLCPP_WARN_THROTTLE( logger_, *clock_, std::chrono::milliseconds(1000).count(), "[detection_area] vehicle is over stop border"); - setSafe(true); return true; } } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.hpp index bdf2d05a35bcb..9224cf4624687 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.hpp @@ -23,8 +23,8 @@ #define EIGEN_MPL2_ONLY #include +#include #include -#include #include #include @@ -38,7 +38,7 @@ using PathIndexWithPoint2d = std::pair; // front using PathIndexWithOffset = std::pair; // front index, offset using tier4_planning_msgs::msg::PathWithLaneId; -class DetectionAreaModule : public SceneModuleInterfaceWithRTC +class DetectionAreaModule : public SceneModuleInterface { public: enum class State { GO, STOP }; From eaf5ad7a82a527a51775166b0f218f3804e43abd Mon Sep 17 00:00:00 2001 From: Masato Saeki <78376491+MasatoSaeki@users.noreply.github.com> Date: Fri, 27 Dec 2024 16:46:50 +0900 Subject: [PATCH 125/334] feat(autoware_crosswalk_traffic_light_estimator): overwrite invalid detection result (#9667) * add code in order to check invalid detection Signed-off-by: MasatoSaeki * style(pre-commit): autofix --------- Signed-off-by: MasatoSaeki Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../node.hpp | 2 ++ .../src/node.cpp | 21 +++++++++++++++++++ 2 files changed, 23 insertions(+) diff --git a/perception/autoware_crosswalk_traffic_light_estimator/include/autoware_crosswalk_traffic_light_estimator/node.hpp b/perception/autoware_crosswalk_traffic_light_estimator/include/autoware_crosswalk_traffic_light_estimator/node.hpp index 8efb90cc87c89..085e423db38ba 100644 --- a/perception/autoware_crosswalk_traffic_light_estimator/include/autoware_crosswalk_traffic_light_estimator/node.hpp +++ b/perception/autoware_crosswalk_traffic_light_estimator/include/autoware_crosswalk_traffic_light_estimator/node.hpp @@ -97,6 +97,8 @@ class CrosswalkTrafficLightEstimatorNode : public rclcpp::Node void removeDuplicateIds(TrafficSignalArray & signal_array) const; + bool isInvalidDetectionStatus(const TrafficSignal & signal) const; + // Node param bool use_last_detect_color_; double last_detect_color_hold_time_; diff --git a/perception/autoware_crosswalk_traffic_light_estimator/src/node.cpp b/perception/autoware_crosswalk_traffic_light_estimator/src/node.cpp index b0ec4d0e5ffd0..d7cc6c725edfd 100644 --- a/perception/autoware_crosswalk_traffic_light_estimator/src/node.cpp +++ b/perception/autoware_crosswalk_traffic_light_estimator/src/node.cpp @@ -298,6 +298,14 @@ void CrosswalkTrafficLightEstimatorNode::setCrosswalkTrafficSignal( if (valid_id2idx_map.count(id)) { size_t idx = valid_id2idx_map[id]; auto signal = msg.traffic_light_groups[idx]; + if (isInvalidDetectionStatus(signal)) { + TrafficSignalElement output_traffic_signal_element; + output_traffic_signal_element.color = color; + output_traffic_signal_element.shape = TrafficSignalElement::CIRCLE; + output_traffic_signal_element.confidence = 1.0; + output.traffic_light_groups[idx].elements[0] = output_traffic_signal_element; + continue; + } updateFlashingState(signal); // check if it is flashing // update output msg according to flashing and current state output.traffic_light_groups[idx].elements[0].color = updateAndGetColorState(signal); @@ -314,6 +322,19 @@ void CrosswalkTrafficLightEstimatorNode::setCrosswalkTrafficSignal( } } +bool CrosswalkTrafficLightEstimatorNode::isInvalidDetectionStatus( + const TrafficSignal & signal) const +{ + // check occlusion, backlight(shape is unknown) and no detection(shape is circle) + if ( + signal.elements.front().color == TrafficSignalElement::UNKNOWN && + signal.elements.front().confidence == 0.0) { + return true; + } + + return false; +} + void CrosswalkTrafficLightEstimatorNode::updateFlashingState(const TrafficSignal & signal) { const auto id = signal.traffic_light_group_id; From cd06f625c980e57fc21b9cbd246513f6512dae29 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Fri, 27 Dec 2024 08:01:44 +0000 Subject: [PATCH 126/334] chore: update CODEOWNERS (#9808) Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> Co-authored-by: github-actions --- .github/CODEOWNERS | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index cda3c8ceaca89..5bbc4d1c6177b 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -170,6 +170,7 @@ planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_m planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/** shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_planner/autoware_behavior_velocity_planner/** kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp mamoru.sobue@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/** fumiya.watanabe@tier4.jp isamu.takagi@tier4.jp mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp +planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/** fumiya.watanabe@tier4.jp isamu.takagi@tier4.jp mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/** kosuke.takeuchi@tier4.jp makoto.kurihara@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/** mdogru@leodrive.ai shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp yukinari.hisaki.2@tier4.jp zhe.shen@tier4.jp @@ -234,6 +235,7 @@ vehicle/autoware_raw_vehicle_cmd_converter/** kosuke.takeuchi@tier4.jp kyoichi.s vehicle/autoware_steer_offset_estimator/** taiki.tanaka@tier4.jp visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/** ahmed.ebrahim@leodrive.ai visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/** khalil@leodrive.ai +visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/** satoshi.ota@tier4.jp takayuki.murooka@tier4.jp visualization/autoware_perception_rviz_plugin/** opensource@apex.ai shunsuke.miura@tier4.jp taiki.tanaka@tier4.jp takeshi.miura@tier4.jp yoshi.ri@tier4.jp visualization/bag_time_manager_rviz_plugin/** taiki.tanaka@tier4.jp visualization/tier4_adapi_rviz_plugin/** hiroki.ota@tier4.jp isamu.takagi@tier4.jp kosuke.takeuchi@tier4.jp From 75fde99c78aef0ea140154b183fcae05f1639784 Mon Sep 17 00:00:00 2001 From: mkquda <168697710+mkquda@users.noreply.github.com> Date: Fri, 27 Dec 2024 17:27:23 +0900 Subject: [PATCH 127/334] feat(lane_change): implement terminal lane change feature (#9592) * implement function to compute terminal lane change path Signed-off-by: mohammad alqudah * push terminal path to candidate paths if no other valid candidate path is found Signed-off-by: mohammad alqudah * use terminal path in LC interface planWaitingApproval function Signed-off-by: mohammad alqudah * set lane changing longitudinal accel to zero for terminal lc path Signed-off-by: mohammad alqudah * rename function Signed-off-by: mohammad alqudah * chore: rename codeowners file Signed-off-by: tomoya.kimura * remove unused member variable prev_approved_path_ Signed-off-by: mohammad alqudah * refactor stop point insertion for terminal lc path Signed-off-by: mohammad alqudah * add flag to enable/disable terminal path feature Signed-off-by: mohammad alqudah * update README Signed-off-by: mohammad alqudah * add parameter to configure stop point placement Signed-off-by: mohammad alqudah * compute terminal path only when near terminal start Signed-off-by: mohammad alqudah * add option to disable feature near goal Signed-off-by: mohammad alqudah * set default flag value to false Signed-off-by: mohammad alqudah * add documentation for terminal lane change path Signed-off-by: mohammad alqudah * ensure actual prepare duration is always above minimum prepare duration threshold Signed-off-by: mohammad alqudah * explicitly return std::nullopt Signed-off-by: mohammad alqudah * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> * fix assignment Signed-off-by: mohammad alqudah * fix spelling Signed-off-by: mohammad alqudah * fix merge errors Signed-off-by: mohammad alqudah --------- Signed-off-by: mohammad alqudah Signed-off-by: tomoya.kimura Co-authored-by: tomoya.kimura Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> --- .../README.md | 20 ++ .../config/lane_change.param.yaml | 6 + .../images/lane_change-no_terminal_path.png | Bin 0 -> 52805 bytes .../images/lane_change-terminal_path.png | Bin 0 -> 56568 bytes .../base_class.hpp | 7 +- .../interface.hpp | 2 - .../scene.hpp | 11 +- .../structs/data.hpp | 18 ++ .../structs/parameters.hpp | 8 + .../utils/calculation.hpp | 3 + .../utils/path.hpp | 2 +- .../src/interface.cpp | 10 +- .../src/manager.cpp | 7 + .../src/scene.cpp | 186 +++++++++++++++--- .../src/utils/calculation.cpp | 58 ++++-- .../src/utils/path.cpp | 4 +- 16 files changed, 283 insertions(+), 59 deletions(-) create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/lane_change-no_terminal_path.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/lane_change-terminal_path.png diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md index 5a6c22a731bf9..0508dc753a2e8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md @@ -874,6 +874,16 @@ endif @enduml ``` +## Terminal Lane Change Path + +Depending on the space configuration around the Ego vehicle, it is possible that a valid LC path cannot be generated. If that happens, then Ego will get stuck at `terminal_start` and will be not be able to proceed. Therefore we introduced the terminal LC path feature; when ego gets near to the terminal point (dist to `terminal_start` is less than the maximum lane change length) a terminal lane changing path will be computed starting from the terminal start point on the current lane and connects to the target lane. The terminal path only needs to be computed once in each execution of LC module. If no valid candidate paths are found in the path generation process, then the terminal path will be used as a fallback candidate path, the safety of the terminal path is not ensured and therefore it can only be force approved. The following images illustrate the expected behavior without and with the terminal path feature respectively: + +![no terminal path](./images/lane_change-no_terminal_path.png) + +![terminal path](./images/lane_change-terminal_path.png) + +Additionally if terminal path feature is enabled and path is computed, stop point placement can be configured to be at the edge of the current lane instead of at the `terminal_start` position, as indicated by the dashed red line in the image above. + ## Parameters ### Essential lane change parameters @@ -935,6 +945,16 @@ The following parameters are used to judge lane change completion. | `delay_lane_change.min_road_shoulder_width` | [m] | double | Width considered as road shoulder if lane doesn't have road shoulder when checking for parked vehicle | 0.5 | | `delay_lane_change.th_parked_vehicle_shift_ratio` | [-] | double | Stopped vehicles beyond this distance ratio from center line will be considered as parked | 0.6 | +### Terminal Lane Change Path + +The following parameters are used to configure terminal lane change path feature. + +| Name | Unit | Type | Description | Default value | +| :-------------------------------- | ---- | ---- | ------------------------------------------------------------------------- | ------------- | +| `terminal_path.enable` | [-] | bool | Flag to enable/disable terminal path feature | true | +| `terminal_path.disable_near_goal` | [-] | bool | Flag to disable terminal path feature if ego is near goal | true | +| `terminal_path.stop_at_boundary` | [-] | bool | If true, ego will stop at current lane boundary instead of middle of lane | false | + ### Collision checks #### Target Objects diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml index 61e41b4ea3ea4..91b296f8bd40f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml @@ -10,6 +10,12 @@ # turn signal min_length_for_turn_signal_activation: 10.0 # [m] + # terminal path + terminal_path: + enable: true + disable_near_goal: true + stop_at_boundary: false + # trajectory generation trajectory: max_prepare_duration: 4.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/lane_change-no_terminal_path.png b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/lane_change-no_terminal_path.png new file mode 100644 index 0000000000000000000000000000000000000000..2c7b76e1749974c64c7422aa524ed6839e12059b GIT binary patch literal 52805 zcmeEv2S60p+BO)wF=|X=G`7TG7q^0o4VLXNvuv4}-7%JJY%lIEY_Xux#KhR6V#Thp z61$>^iHTjX_Zme|M2!XP{_pHUL}Tu~|Mz|Oe*e8cDY|p!%qj1A`-cL{XJp^#;`iUuLPINW*`jOBr~)lU^8Q*nK9HONg^eZ9K}e4-!`+= z0DlP$I;)d-9pN)8R1aDpswcqQ>oZ`d+V=>aq5;Ls;fiv^bsrvo10n!I*f#mzqm2fWKobvnEiTta76 zTqinh&M>z#X`z3h+~ajSt%ld`2n1ZJukfA9#RNVJbuR!hhyJK5oehSd(S`;}U29=< z6_?cWUX9ym@TM5tX1l>_a4TFIo!McmcouYxtxBhQwxNff8m8TuUZn}3u{)rm9*Jf% zIB+{upbizVV%e1iJW7bd6 zM{{uTW^3WqGU(rs4UaR;t*aE5x3Em8=x_7wEAAB1+<@VRnyj^Awe+!b&|> z*RC| z?0@zQ{%1(U1eZ<_7N~zjctX{|PpVW@fBTt=+94bN_iFyh6{ujb^uJ+$!K%6_O=`A> zJRmMOm|ipZJ;@ra!It9mn7v_lQ|t74op!J&HtGgfqq7>_&NPR<(#q)#shTt!xGR6O zkYF<#DM!`obU~@c;|lv_sb)WA@42B46Dmt7gH|yFo?heCL@^V>mkfa?-5AB-`oRxi zB&LW^1{vV8w1huR7j&_-LR*?9NHc3ha+;3kOiyO&nfd^mi3Hf`I=e0%QCitj1t(lD zAT}C=bdT17aKv^KO)pA_Ne*z}30;~#h@@$m5=U}S>_d17={hFq5SzIS4S_Rdb`C2= zA@+%R2}VT8XD3@^3^7mUgZnO$M>8vh0ye3Vq#|Z9j59?jw~-En`XxeX2EuPkF|#dN z5#mKuUJH!Zm#pHN^g?5dUM2A)C8D7+olrp2BwAxr6%}pMmG)B->GsEsS;vhn(0|?wp zN#q3eBAbU)vU)%}E}bAW7Ndrc0ZmYkM#c51RdT1;!s?;3;}(4)*GUpKheibVEulFx zHH4g|fq4Th=*bqoALu~QCk<7IjnJk^$E4^R8bd&A2K&i{UPH6Qs9Ew@J(3xJ&`78Y z_idA;s|k7V?fvr2Vo`XG&`&Vgg2A;F#zUVO}@G(ybDL6}E~ zwp?q9LgGb~3AAL3)q_|P(on+aMFXq=qEdSi!pKavi2ZttK%-UA{AePJhA4bKO(HE^ zZl?J)JY5=M5ik(kLIC<@hw6sL^(T(5oMj@%kz(v&?l}=z)-}xW$WdB>XiB&ZJVlX6Zkb1HoMw3@%|%h6P?bk zNJdu#(mg8d(Ero6sba|0aZ@P1s7Qwy7c~T5X%E zZBunluR5pqMy|6uZu$?2o0vUb-yi(9h?^?%kkz)S+BQ|&rfS<%ZJYih_nYW%+9vwH z#fDSGn_Sh#soFSI8>edHRBfF8GmX=mNxgp$<5ZD|tTs;7#;MvkRU4;jKwocX7soFYKTc>L4^q*;+XskDm9sXP7_24A_-#ukqeah)?oN|KGRK6G; zoV8XnFpk*44Uj6-rgM-sI5`5Rg(T@32Ii$KA4#~6;3Qb+1enVSrDQ2R6 zCo3@ABgX{8-wJbZkYp@%Nbslo=-Px zXmXp3L2^-=z$V9Vja-Ryl{A4^!qI6uA+oUy3NN7u3M>R)&eYR57LqAulMd2tuzMwh&F0ZENdysb z6O|aACKt)va2hQM7YXcWQ0La!FqTe8isg2Cq7-wvwLE7)vdR4WEz2hsZf$!1&+97b^(H7 z>>$bzNHj_v6V`&Iut}^7LybexNsdqZY41n7ZJH6YNaGyMz@C1ZRW%D2+IijYqQN(JK z>I6Il6%tekWPU_I+6*|FrWLwuu(nQw zZZc~GYM%}cz{zNw6kMsNO9g6%hR^ZnY&M~m&-crf61R@2^Ai{?sHAiK8iGxzVVxD2 z#}8*O2|VBp=xt~WNheKmOpvZnaRY=>z$FM@P@(X+Nud`dMF?G~#8nDdStZkj$}wvI zwd2V;n!uy8$dhow?@%zrY)r*9>ufG1jyc^joa<2F+!UEjLNnO$L|o)_YitsYh7dC` zCMif}y3$Ann<*E{d4x*LLUCM;VJ5no&PDVLnOkZ1r>QYc49pAU$4S%EF`r(9%C!!3 zuz_%)Bwgm#(O7;Aj)Ex(#4X269=XFMM=hjTO_!K48a%`I%hb5btstP3Z%WY;Iwqks ziIpmS3~mv~Gz>wI;Bkeho#RpRNL1(GYH&M;i3+_YoKLEh7ThNz{7wx)^AiqIt;9&0 zo~F0r47vcf=z=N^au@e=oLyUmX0#~PLl5;QLBlO6!1!=Dw|Bl*DKWyu2_jn zLJd&-q+F~>g2~LW*Owgk~ zC5{J_K{6xfXpClEcBCSY(NclPzAtD`c zYLzCpvXfAi#E%9|iMWDemeJTEB~xOS1x-mhLgEFTA=BA87DR|TNR>;C+u2DY@J;-rQlM?l6S zq|A!Z6g<*|1?5VmjZ8DB^m45d_243tLv59)byhVERq6*z2`gJobFn~PXfm3>MA+GC zTp$MCchWG7?N#ywX(XQD)>#BDDV(M@m^mJ>B{4}%xf;hzb`75&P|($EIh^2@F`Ypo zk&}e*$ryFeq|{ir46R7dMj199>5y2GX`r74E<3@usWFC;1@mT6wi2hC6e!_Mms#`# zNtgtn-z_KsGzm(0dJC>m(!3_UzzTLxl8D>&K1_&{B=`&3AmYXtbcF$v2bByzUq%S5 zm`Ea3+sGus!A;Z(a5>ILZDdfd#2FH|nn1-ehbu|Oz;P_7=b-_P6`>1~6I8?z*o}cV#K1Rfj%(H6TJ?^VpGHEc3(2hm55s4=bS zK^R~IZPs*@k1wQV!2SFG^juZEpkGJ>t#}0!X*S;vqC9LPhyhb0k{y%ViKw? z`k;;<9={&+F)Bchz>66+}6L}g0R;c|sR$O@7S z@NEcsiX1luquA3%eoS+CM_Nh`tx+wE3c1x&fXrb2~u1sO!W zU{`~3yECXzngTMF-ltRAthi9-mQg+$Q|?eRa3;yK`jcp=h_EFDpz^L}XCz#W1;7BQVLZ07rrmCRH-iNk{lH@XK%w zN*8EQJMghcpGJUQRuXKkQlJ;e3A$8I05XFBYzV=YXqh_D_Y#(p#&Kexalv14%9&y& zDzKT9e2h-u0te`F@L5f2%I8GE579C83MoNX;#OOV6hm2Bo1UjpN_=`@52haMGRD)h zbSjfgE|9DB43imbK245s?vZ6HtRsgR5K)J?J(aF7fNF5;tM91~HXDgsZrS0mB`*Lmrbv!w1V5s6)@>sxk0E zHFo)6HB+Akv4K;H<0&McgqVXQA=XgfbUjyr`RK_s4-;|VLOEUF0RK&`qnidxRdSmK z>>x(#K?j*LX<`1jO(50_y)2M_iP9lRl49U9*gR0I!z2F(? zgD6h`{+vD;2Y?0*W)dX@1>o`FbTw{uD`|RxhNpMR>^4Hq<4Tkw9G-Vs6+C>f&Y^cI zMXsRE%yH-luLiKw*QiXbe_BNc(r-Kg*x*G+9%2pvN zGN2RTTm#<;V-WkLd_DvGBDDg8wX_Qor9wJSZ9|o$ikkxb5F{-&8rX5V-U=q1&!Wo- zw!`26x#Xjyo&esm;w(7fZ;^ssQrJOXIE+52&}#-;?L|Z;narVg$q5#n;F%n7A2FyB z(zQ%^5&$s33Hs2dBwWd$Bi)#VYbNOuw?csU3^oa63w(0A zUJS7v$UDx!tZX)BC!HwaOUH2u2Ju*oj)%FmnBK1d-(Eq-*$|hcp;op?VP(0K85|d> zw8=1$Kn?t+AqjdCPUo^f$E8RKL7Lu<$_XLM4?5k1Gf}1<;yscWE>{&{q~yI>rZ`MR0&OXz4mkt^qzI6ySf# z7;1MC%_~#z0Z##Jk=`x`KSytaxYI8S>cNL3({v7m0kM}|Ddg~>9}`YHNH5+HiJU#4Z+*fJW7 zi)Lji1#+HVXmS{=Uie>-qEm?j1n3owz)Htel5~Hmf{{uy7lihKsle!UMTCds!N#2?xF% zoWw*;GP_=+wqiaVAvZ%@o-U&q!AF+Jl}s*AZwEU?=;(5Rk%eP=hL&j}G&GQ-ph*G# z7lB$OiF$!ah=VQz`>8}|R2(4>l1kJEK4Va6cRA%EJpy!R6IMB@g_H#a4n!rl5V%PQG}Y*Y5*%VsyNuGExWt_t1dYP*K)g?b z7*L*~U?%vJL$Q(%-hsVxdQT1E-fI_XziRd63|nsi|^;&_&!%FCgKC;6S_4dr){IZ{m;W&2E5Q3Rm$ND7@2u z2_y-f#RBlOD)?!finlMT9Q%%`Kp&}!NCGH`p{M>=5J~72L;hRaoK^5B|1MINrUC#< z2e6J5Ak1GuXGJlXsiA+MN@b(3gJ*d{D3(M8JR)H9y$#ngF%d9F;Z7yKD0QLNcuXO5 z&5AoAs4u%8fNou;XtUE38*K)T@kFQEGyq-sC+?|8tp9V-YnT;CFqKGql{`>|RRH2M z#1^ly%Ks*K4ZRv!tr}Ua8d2l=mdr4tj3urnRT*Hnb-07fTUE5s-S#0uO_K`aTo zoLZhMP0L{0q>vAQsK!kyofgER3jhKl{f{yQ-K&9&jLuH&cH3xD3*RSY(kQ&a3S7}w z<9dat`Nybveur3SqfjqBkhinxEPonl80j-yC-fVIxPwA8)dC(P;2_eFAU}vI`G9gs zpo2N;=3*#CsxGnlIvXvhNkvMc6FlPYx#GyvshSeIY|9p+Baz$aA#-IY3{ zGBE-0Gg+{HVjqk-jFbvlbg5Ei1Z+)MC&Vx1CBT@))OcXCRL6$)0I!n|_Y!EKew0>f z4AffCDc*oOKu06+lgo5MwLRY7=~<9sad=E8jhd3B}CHKd!wM zv2qN>AJQ<&tydd*f5k>KD4ihB6zc3NNeJO|+Qm$hNg7Bnrc`3i+WjU2>{o|zd;h2n zQk){Hf{N=1{bquW2qDPAx>3llbSaM?kScuCyn(k9;M!^g9-w3(h){e*(Ga8=wWt|l zA;qh{(0eW+I#K*=27abw!vefd;hs|RWC1yWwF5Z-+9trWzW>NKz+04T0Y6!+K>q{=;HiQv=wO|w=fiRX>&HZRYBt5=A!J%=?P2XG*#Q0obYOTk zk*f*6(?cNy)68K_<+PAI0ktCbx6%3!ZKZreqbcYWNWo5O{1g)JA1fdRO z-#nvPETm9~Y2op~{wwe#$Sxl+T0v%%2=G0H-irX=T4B{f^8)^}QZh;LCM6pzkkznm z0(p}vjUZ=$!fT;Woz);4Kw~Ha{tbr8m1-8s(*>z=C}YC@5@5fAEb@SMNq$MU}h}X;i0HaNv#f~7&HQKH}$p_tSAkhVIct@tO{s8i<%A;HUcFmj%S00 zquK-M5Q7GWT`Y3~U^VMNqky&mtwL!MDM$fG5m*mCXfrElC>;$}m3qbxnh~so`0X0v zUqwMbm4BH!-8JOCqB0(Nj%RzU_qZv&1n@Mi$!!A=tBW$GCz#kcV8 z8T5^bfkKEsYzNg~0}?>TQ1(Cu{b96_ESp)t z*VL-W!nzvpjzOQoeWM53Wdr|%Z8L)21$1iA+o)2_09`}bM&NHN6ZEqt~x&W0&4RIR}d_$mTs0@6ZH_ED@oCDIknfnLIIn2ERZ5$*8e8{lx_%^ih zx9GTV92nMd)Nh^`+LEy0{YFaCSTG(+pHO8Kg8J)aLX%BH=$-ly(z+Vzyh1=nC`3jo zKO9Cqr=ATXp$k#)_0S;rd|||S#jCtA=v>M>{gcl}<(eyaoRWAzJ_m^gJ_3FOO(CX* zZIP80vSE~@Q+`+?@UMcx$~Mx&_hsPc$iRMCL;8>67foUU%*SX{2Ppmpbal$t3jnVN zDBnp82>KZ1BT#a|lq$HM5dOCXq2$5$79{yMZTj1F9-wpoVWlZ)0_%Z*HV4a0NiSGn z&@)wM0@nzje^cHeczb~P4xS7(>yQWccVG4*aOg>nyigDR(FSO$Dy^uziG{z01kxhGm> zPe3E8b?|7R^)SYMsAZrdBh0B3KKy^PxA6F(hu3=p*#fGA{idu|#r!Jg&8OxK)D8Lh zV8Q-`$^JIp`13p&mGgX^q6oAMo@ywYNl6ve8-?2+`VNGTiW&_(s_gZ8e?qwbYmYPN z3w=!@h59s97$d&wo{T{g+LL*6+vZ=9c&F3efaaw$V=BKKS0(q(s@SikA^exo|S0am9vzfqmvsLpRx=QrN&>sRMDs5gmTWsF|SivB|xqU!uc zb$-KKo!_7$_t&xl)%gu7OH-ZSc>P<3|5%oxI==xg9aeeg^nWwI!C+V5QCGfM$YlRp zPLeBO=;H!0Iaf14=K{8Tz4N$IIW_)cfYg zmGc|($JT7HxBjLsKdpNib>swgN)XZiL!SB^me^#fYEraF)_Cn5@^Vhjpj-A|Gqg+8 zKOXT;p7MioNnLr3@)xa{XFlcZo5?X=pTqI=xgRY2kmbp`H@rP_=AA%3Gp+2_nf1cc zjpHLCYrgf5yQ=x`MQ+%$@PjcCHR`q<@s>XZ)vP<8)A+3qQ>_kd(so4ISJSvn{;G@Q zhzs|pBpLE=oiV+&{ZOBcWo^53NlGo4S0ot|arVPzJ=?u)C{T8zQ)5p=uIUO_y~VX) z>a^)gm$l3lM2sBWK%bf_2?PQ^mn`AdY%G#S=5uavZa-)-QeV%NFP`4(;b)VwYRvH* z^_;)KuCecZ)9Jgh?h|Zc+lnmq{QiU2GXG-oBSt79YnYbFZ~Y~CE=xxI%>mc#@nPE$ z>79Qa{&woZl-2-&D~Av-srT+D?eFFH91$UqTME;uc5fO2dc5xTIv7$$XP(Ez; ztgO!{DtCyFm^)mDPJClkYedCIwEE%7e0r#hton`PhwK+?-t2D+HRCS3Uxdn+w}YnQ zbo`_@n&NhXruJ)=C_=RaBO+$K6Zr;@j$8~KbeJ}8f9TPn&}!MV%%9(Ar|~!Kp&{g( zc_EHjye1;jdvijoZo=1TR`)9?@A&m(G(-d52W>}O-}ySjYCr1Oy?f?~mBfLuA9m57 z?C0F~WvvF+W@qP3FFm(;&ll~xKNvWF`12?3(^tkE7`&%dhh_7I=d?^et#P~7r%stU z^F~Ht6HD6>X#JkkC<4~~oCoCm^q}&~suFdjX~!Pl`v&;n}IP_lKT+zcZ{vilcL471E46 z{?Vht%z=xGw-)Jt8(r_-{er%;^N+9YN5pw=bzGJeTygE%wY^P*tveyJSmM$NCyzc^ zbavC~XE%OZlB8HSukVXTi`1PBFP=TV_u}cD1I^}TMECUFW(_kRo43;2X>Bpr*O;FiJ7Zb zbv>fqptdlV1LpKc?nLMY5Y)Ai12cP{QTO@ElZROh=D4N$j?dI{{ zhl%RVAJ$=MjZlY+De{fa8v9y@8*83iHK1FwIT<^OZ>cYw-C%BawL>y({k*1IZ%kv+ST-RN+n&Zq5z{We-K!?e}pMv3>~nwu;8 zWoNYUm0V#G^{)g%RV=^ z-uw$=*Y*u*i<__j%kou6AS~~qmsLSLhi6; z_9{EAyZ2jz?t5pktq0E@%kkEn-E-uyvNOW6OBosadY7_poZFn;(t9|eNrS_8IWK>1 zz`x`@T)JkhE~;au`{QV&{QFkfm z589ru@J}h>uCQbAgKEBbekbF=p;5K>{hYmH%I@)>9Jp|G4@hSJq4s(C!7P?}O0W9| znd<__mhR7aujext=lO$UhurUX>$hp@^H11gKc1gso)dlJ_uJd<%-T5d)aw4$)EABm zIVV=pTbZBUST?Wo%gw>hb;ri^jFFu*O&Gd*ox9h>2nB-GavwCR0+ijWd};VLVrEXX z``A+C5V@~;pYHVcrA9Aj{P@1lKX0)xyZ^TI?1dA0{8snIx$Jp!(x2Q&{dU5N*?o4( zGEYBxbaf(9yoUKho9E{)m66B#8AmqCxzT zE7p24`F6{=`9Y^r=h`o`6<}`af9c7_}XApBY8CsgCUw)vSzEG z&!fxlTs?gIheg*GjA=b3aaL^kLH;S`Z6c-ZN+LVv%KbJu-pN0G_0^QQb4%5&_C<@@ ze9S3Zvu)g>uMZ!3kHc&2za07a!V#g+cJ?$~ckSCfZDRXAz1rNkcl5VS4~=S=)@}q^ zW|D_BYY*__cF`w1s8Lnh4{a*qMXWAqQl4{b-TtW0voe0?-`|uWVwe0ldLhC{R1?nmH$ zEZ+Bhms4la>k|KNw7?6XA}XHAQOd>~!?m$epNxOC#d{layJWJ!yrIlJq> z5|+<$-1Hu=m(GQjxu5@7dLnS|*oZpF#GCWd=d^s3lDB2ZvW(ci(R*gQz2b1N7scQIwr1CWogSuff9d86sV|7DyT=!1WDP&Ns=Vb%WK>yJX8-n|#5!30 zTlRF!`NDtYs}ng-pO;@cfPjpGTh;k#X+RJoRZi+BB6 zu&#gWtXr*@jhH>3d3Fc(&V^ZJ*)5I=&UTmgXu0}Dk4}D0NE?o=d#n6r4RfDCIp)&o z$A)(>G%!|NQLH~ikW?|w|%*{hc{bL5O(hOsTLT)B0vpzqV!_oF3 zpJ{4S@MO1sy6C5>Vl`<{WZpZ)Q-0Gn_a8$RGN(y750&fR{RMRPWp#Jsp;=LzKm2I_ zQe^hQ1S>z1_D1Mf)yX-7QW{U20?$JiFS4;r^xW`jcKze1_t? zSLE3PdKc{X$tOiK@10$ly&pp1gX8oKcS`#de!wZZwSLLB(nj3lg>3JIlFWg@ef|k8 zdXqWVi<-vwY)&f+iB9~^E)eKtf8ME1Rq6e?^JQPe^P}H&-`_3vlI_uhgh0-_qchJv zFdx$&-#dBf-UCC*r=N4=T{!TYwVM^ja_=W_gMVC*xMbC;RcCjs?zegR;z)7YV9P-(b#)rQQ z%=IUScU{aKa$x_5U6Lb__3N%(2Y(Tr8#hyZl!qlJXU^MbJ%zRo+@f!+PBpBogf{POnOdCqe%kXQ zP~k_x^U<#C`flU{L&ny{C-a?W*6{}nEiC-z>4ql0Nbmi;}Gja&(_Z8uqW~+6>xs9d3cV;^0G83*OTu!b8*3k zMRPtzR}6SQ;l2+oeKg1Ob9(-jJ5UsRJqqe&UcI;?z0K{_E1tTX*i-s0P7yILr>|pL z?MrK(KkRk>hXuBty$(Fxc*Cv_c46=b7q_!lp$N0*l%Bh?%M~wAQCR^a6fMtE1DaZ*4cMvqcw9} zE2dz>upD#zg`(_?)wr`)sd}yZt5qvi*B43W^>HU@G#l?-=rj7qA*Y5eADB0Me4lfh z?B6eJmQlL-*y{YO-b2bBY`-R-$sCeCKKqCyk6hQ|w}K0`505dHd(LiZQGV{ky?FKS zFAi@xaO9H(C-d60_HkOY4mLr}mrMAn>)4P7g5voJ(mkb%G}+A}bH8p?C)oHKXK}`+ z4kNdm{Xw>U_E~?EZ%WoK+LN+ru40oYNtzL9?Qk`JA;a`_A$7DEh^HzS!EM$d&(X;c2LT z(Syz%_wK$`v(0f^jODF6UD`-dxYwT6@s}Q5I(1;xX5({m_+v+>?%gLAHlDiU`O~CJ zFHU&)n7?hnr8XQWr*d!BUWVv}`?YTI`YK74l9 z!TDzk#<%$9RJZxt(w@#~dVsFW{W?@Kp-nz#jz`OJ zJYa`uc*~Vv?+#~7^TTVO3BK{>{V*mur+k1qH@MN%c<8fw9YmMDta0P;+C@|xf8KX# z*u7ti=FQ&u{P4-ug-3*Krk&ixUbvcMH}2l8+xX>8%9EosV|1uH@eT~kJ#}; zzw+Ga?=L4WUq3Xva0xMR@QDFU!& zuWPe)4CF{!&xpg)Z=IIuKFwLjdl~r-6*y_LfB2fX$kBiE?EV?!A*paei>ThwIX|4u za=c?I_@vWk5J3GPZyz#UZ9yHrLw}d`n#Wh8EBK^OFBgxhJ#Xl5^#afCWMn=pS((u} z*Njj9BJBirbUo31dB50uo^{&n{-Yz}TK69CT}bJTr~~PO)@|iAskSTC;Aj#Iz>X^y za))dly3IB-d3Fqv3bwZ7sZYK%Fv7(H}I6XEC`-DIrUyRSLA{eTj~4b zF1!|Lm)89GgZP0b*DpIy*MD<-xuU~^t3Ryld?~P}6+^fC-DAY`%XObmI+hUf1KL9V zt_)fDf%6Y*ptF>u=KIt>|(u7=#~CaA==<{7`VZb~-PQTLWZ=3xJD%?EuiLYqQ#41hdh4plR>zwx?jM@> zg2rt}y!R{ZXuYaN=B|wDbXTLkQ%Am2d+)@)FFJNezxjDNI_q<_TAlT<_=4}!w4cC4 z?}wDs)xwMWzF(qVpPDtT&G9ey@87SF&l`U4anZaai1Q53e)-mYZ(oO|;BW0Th5fA_ z;DPMota(tss_Ea}^lr})1Gf9uKDcv^nBIM0^ca>iTCp^F@_Vg%22YN3Lh^1+-tD*} zcjDGRSum!}^!yHUuc;p=bSus+zxe%^pExEB9R8Spc9XS3xpZ#lF|C6gBfTkg#-)cM z+R+MF)Hzor*;R9TJ9|?8)uGw32gb*qZ|f;KIQihguD%i0INIo9D-0 z%wivy8pxmbvTOPIA=x2Eb2w;^+0N~3t>%*X7q~Z4eYDlV4BP_ zpFLjl{@k9v7zpj^7HYnY@Hd({smN<~(P+BdWw9v4dKRm$aiHQ#R% zZ)M)jEovQjv|vo~cixk?n@W2}b(rJ&a@0q0=L`_?xUqSC?)}qzxI7O8})s(^I1noe{HoMoU#AH zjL5k)-a(s&gI$QcTRo#M{Hlt2Xglc(D)NTp*AyzM%K74J$DURh+uvsF?2Kn(LNa|Kx$~+g=A&Y&vy%_TilA>)NqTn73|BTfa1BPyDVVs@CCp z2Q$*9KeO+gyL8~5Ib}n(zF07LaJj7D!sPr*ai0*zyD#qUYSf-};;uULE7OS;*!eU| zWDf7wg4$6wD6mD6DHldWm}$iXGhlY8^TX}ZgOT~ zEAg2dXM-BisW-Zp%zS9;y+51(-AB7ie^@kO?3Q2lcIlqiHRtnvOUHkL+>g$EAm2J{ z@1)$;@)`2T4Q=*L{Wh%0JJbjSPSh}UivDQdp@)n8^%L6Sk=;kxy6>+qkH2$bcJl#S zl&uD4&-tuX?C=e-C$D~g>eud<+tXHe`*^$(MXuOS3~M*7->`YdXV?1ZWpPT4kRV`@ z{S|)5Ij9VK*8Kd|ty|rvPOn|(939agxis`X(wsANi|y=&eWUL{SjuYDX+z%! zvdk`2>Ti4b?QPdzPTWxvegCi^Z&TcmRmJDCTXbv|QjoBv1}XKVtYDM)wqMn(o0rk5 zYwUu-^&56a!uq1^ik-{m4b}d5{3_$J8t!jIMcD+@?m0N{J2$)lVNCUeejI^>J#`K{suuso1Sn zvjN4{MQMF*b$}_QcFO)@?ZS0yAjUr6EI(J!wcC*;NzL{-jtN?n=4E_gKjKP1Fuhy* zK`(C}=w7&I-tZ|W`aWw53H2rio?oBs?EEq>`qboc$SGT&Eovrb{$L#^C$WzC;`Xi2 z$~Nb%jwuO1g6AHjefQr2J2$NhF*g6%rkIBF_Ka`SJ+J4JV#@*V_J=3?QQB%@OkCoV zEb;ff`qhq_(k#-;nDE(69+d$Sje}rJJ7;;Vs-{d%4tlm_@V)Z9=Z99&S2bEOx zW(`L@zj$&@|1RHmK&CXhm@yDvR{X9ZZ~Xb`*$0+gD=ZXWv2PYH5{zGw`$d}+{~?Un zH>S;S)A00tOEPDTY5rtullZ60lg@;Qwhy8-bWPuluSJ}ax}Z=}qHiBbOuv1;)6C}0 zk8aM$*jkoT^8V5EhPio9ZgzoiVAJ;A*6BkZ7iKPPWxHK-)@IYE%jUSp&KYts;J&qX z58iL-uFl9M(~KS(ZsEIkn-}yprY1c7yFKr(YwGy8xZOnMrp8R3GpVc)0!M(YEK$dUFfgI-j)t`Mp+gGtw5Yy(jC$o!nqP{PGsFVDH{0 z?KJTUWL;M8 zrt4Y?Q#MSnoZGan(|4KC4JGSy%0E+8z6a-c^ z+F#b4+*QCSS+&3afFW1Mo3_=tS7bf4YBFr+d?ArYu0aZuH_CK@!C)4Giq3=`yM1f- zw95Q(Q`7hk<7SNw`9beTLuT3K?i^y|iX8dKQT(tF?QN(`!xQV-jg=9dgl4qz&eWMid!79E$=YD zQRiDzW_NjB=iN#8YBI{u{KFc>$9p@kjHq_UotLJsOpyhux@!jW+5U ztclMJK3r@#F#RZ`Y;PQ2{yocazQ^+MQ6tdKeW!(3RaJhW2;3L}YR_ui zH?&zT>JN^_@m4*_2~}wimFh!z%De66hDh>F$M}dtBS*eoWkmdINwgi{wm;pUbfqez zP->0`Y&)U-F9jiQLQX*6X?rG2e`8RixlsPWE>VZjntTRLc?P`-N5a1*DXE=|dx}uv zbVN32(jE8YJt(qO9oG@y*G2Vy_fVeO$m7(yTv)rP@Qq5ZdHW;3fu>r1{6>|!pJOnj z<y>Y>+zha z)7RWvQloxVf4ZuIZY&x$^6Q2f?TG%KjVmY2hK43uB z-Qe=Zku{GhMtIQRgr2#AwrY4&W=fPax9;L)5k+$zwDbkX$FHlY9q?s4b;G3t{zQdJ zS-o3-MpTcV&-D(5GJ0?tekC#%{PjsS)i$)pr!CQff*R=!mX?n}0<~ zZuI4T5xGP6xC7b?P4DGT_vs&(6)t?ax?fqJGt(AteOf5F(>|A<_jE0P#j%OOj!mn! z9b)*3Kj!C*SQfeA!?;E-hi~a(ZMY=&-9@FP9Uc8{_1jsx;`>{n{k*qKaPiFe^O4?F z3p_~v@1u`QKFf`mn<`{oc>8Ea?yUPutN5aBhrXY3C~AjyulVEDX(a@*ehs|6(7eT8 zGRwmHHRDFCIUBS-FTVBU%#hVx`uFQzZ~mgz@7#LJfI=Mc=rbV7YR%d{gHm>B`(HX! zf8y#o@7!Ef=!?l~Cta2CbLIr~S76=VqA@BMDt>&89W@UpHfr8^*Q`dKU)GG=Fi*pZ z+^|S9sKZ|{!%k1+z#7G>#DNVLWjY5&OV?x^T|e{4+D*TD%=N44_p0Ip- ztpz3Tnyoh`thlP{_He<0p~a)>uI$rzazxyr38tKIs^k@OSNs~;q^>QZm3VLc1!>ba ztm$T7-NjxydoycdL>z6*M-9Un{wll2p>9Wdn~9c3#GM_~BwpC`x1zt2p5H)aG&Lf~ zU)?9E-I^1wW9q*kMccuk)V^K6G_)^;^?aLlshM%TX(ib*{{D1K2ZUdzH% z5%ozpbYNzm_lEX|-kc@$D4GLK;cu&!*Q?rljrJ)x-oBvOhx@i~^%yR04@6q~`)40p z$Zv3L>zw?#ORT5XT<`fw#gN{bu$W&vvWxfRW%bKL(}zYjT)gdi(Sh-`YVC8r+pR(& zL`p#m_byxvdk1yb@61Un(H~jJU*{+#j~(KF*KEwzZQ{~?__3u+Uo1MiIrb9uvH{ZN z#X$Kdg0PY3)O|j4ZudJUR+4>VpzZvz>aFM8ZuyRR38nG5V|V5y{A#-|;PZ#Du~D!& zyob>)?uU0o+rm`+CIL)FZPoyI{pv>4pgz-kIf>2|vh9_;vB8&)uFKN|UT zS#p!->tY(tVfzOZtU9Oa(K|4{_R*)!J{0fT>RF=UcRXY>Nll$p!Wz@Gk$m_HU|_Mz72+h$v~8w+wz`UemxlkQ$t z?>ZS=vgF%4+b6Pb+s>?WU-xf6!Frq*TX)vki)|0b&YL%@Pw$J`K<^5gf3DtnDkAuJ zLgBq%ayle8BW|faeRAo{Q~m6hx7Q79cK^=#=kDI^_V%0AA!>F~S?BC6_O;8>{3liQ zxe+6G)-NU}ZGNxy_EX3TcA}*3lx@?-T>IR1Yt_UXHxG7v+HiTyh}lO+H+<(q%1i3h zeNdx$4`;pDb$acNfd%aj-9iF;$+-Dzo-E1e@GEoC7Z=Efw>q7?6!BzVhyGJWHLTzv zIk7V{;>puCdx_*U~_y;~&+!bt*mg zMb|FTWgCxSnUlVOkJt_0@hrN7a9ywA_r1HPc3S7U*h_KyVe5jA2lT_+NAdYfpUsL{ zP2{b(-LypBp={>iFG_~>wsi`59ubk3YSs8K{@jp~_Tx59fAaB*=XWiGy8d+KDV1t2kns*m9vYcV8NeQY7vf4j8;Toc9xqds_Hb6mI_CK-Q zhK->0wQoK#)Vld3*l-v7$4xQ0w@VIsHW%cloZ8j-MW18V=jZz5jl8Tsf4XwB^L&Gv zF(W2?ASiih&6SqyZ*wE(=#lA9;4RLKl)Lq79+kC~#r|Mf8LMcK6|?Tbj5CK;H|Gr> zH|pXCH!~fdtX<|-P-E=4z-p}G*Y8Cmq**lQ>M zPcv5@4(0m((T0vVEfk@0q)pDTP4=}^qE01@Ey<9{SO;M&sg#bT6ooO9CHtT;WNe+2 zrNWFXGiESI8Dq?mGQ>1|pO-r4{J!7o{QvXET&{Vq_kHf?e(&dg?)&rkJd=RDf%7}W zEqDayPufW!rDOOR-Z!6LD0CVScZgo&;9iAE3$EJHBfV8N16fZS&c)+tvDHhm718uL zj;wDQQ729?v5(qZC~w(DE`2P7FZWhmx&M-Qq??`oXhpXwe&ZNeG;pt9xJ(M!lTOu@ zR_tZGAvX{gu!Wc)Y+$Y(=9qD%bVV z(ZYKu?U2i)bv#cim?S0@h1?ij#%Nh|iE|Yka(9#8?)7AjTZ2g>_FO7!`Z4%e6{^xu zq#M<-<~H^XafJ#O5&M1fN7Wcwyi5qA{O-g&Q&%e2S~vZR>@nns%OIhD?eJA7G;GAI zNWRFZ_wyN4JNnIDh4aX=W^ZDSb_#7rqrS=;I7~Awd9qdB)JZF^_k>p?JQP)*{v}xeFNC~{hV|1ze z>?dCPhu8emtvXuF3^caRjW8hxZ6{|kV}xV1Q3RW749Yd(7ZUI^}vb!n_W1E{0pb#r+%2zw5bJtOTBCiF)a6&K^;^ zSoK3Je&a;k2EOQxC`wc{H4^nORb`8d;r3TN=DjDM{Tn0z52IUfazr;3c~+qj#>FX)!UR4nNKS zFkfFw+^w+V_v}?p>p@X7xzRydZjLL35KOV77poeplFa+Xyc=lTz>AARyncuA(lyw{ zCfw{w{jf{8_UxV*+a~uXZ9v8 zheY5V0Z;6}C?cW zeJmU3L*1LlVd=O58b-O&>8|YI2M`tVR#D&b>os5Y&Kg^iFe!TGgWNNZwoUZi1wFb| z$N}0^Mkda!Huz=_oy^eq4OXx?n(sGMS(ye&c!F@iDI4u%GC36$Xs(^==p9}x7i>vV- zle)LX$Q2`)pZ`h59>`up&nak#1sH|Yi#PKf=Jv>#OlO(gUEf)Gm4po%OtT-*QzN>% z0Ma2zL$nHGbjifaB%VJ$TLQ||uyR+#^Py6zZ|BL+mqNC(vzXBXN7$BgKqQfotguA6 zqZINn)VA{&imHd6FY=Q7tQA9J@0rN#h(ftb;d!_a_yy-F?^^X5QEiCwpZSU+8?k%O z+v^WG>GAhci(C>63qq7XWic_E(G-9!-DiAe>j_CPf!+G9h`FhvnVSl_S5xTAe8h@3 z8pItMG8W$T8Ju_R{3ylzZ46I}59J`2hiInG$(%5lR5L&H5Q~?C8p?NVaPwO#M#-N_ zPfxdwPf}D_s;>@88VKnNq09t@oX=6R%~Nu(*CUyvbah%J46?FlA%+2z(X6q#$Xo$X zgLL|s3F`KE^T0Pey|!{>Jx1u&G<hec3|imHOi zHGzwvTdvvi&boJ|A7S5MXXP3(>aP*&XD1KZM)NwON=11Icd-BqI3*TEkiLR3q)*3h zxw$ajyOffny2;q5L>A>|`!d+DM-E!AvCHCL(1|tCf4rXN<6cH4)|9W|&8FHqk1a^8 z9=F)_57?!7{|LSFO2acvy+az*s-$FgtMTzWj}*5>aKlug3fDAc-B)t!fJIldeq@lg zQo+wrZ%!CZiB|P^o)yQB>D>=gU#)}xMwd-DgFEy*Lmt55PKxjnRq~-4o3n3(t^t zfEbtn-IST~ZYJ2#8YTRLCV!)ap4GsypI5 zhSjTFp_0L<&1xW};grk4p`@*{Bjde{k$|Adjynx2eaUr|7dkA41GsCv*>%;*T{1Y( zokd2~%Zsi(>kyN9&MU61vq(#AZp9q&BoTU;m&flqtjAj-R;%S0(@0?9%)*QhD6HH? zQMOnqC0GF^tAFE)`A5WnIf?7QUA9vz?bOb;Aa;^n)&Gti03_ zacB~<|Ia275oDGs2^YaRihg5s-Zcn&tRDRHr{)Ob} z8ED~}&7n#IIYH~!uZ0+-re}gSRWK6joDD0@Bugc$et&BJUU`w+P+shw( zFi4y3d)Y=*PM^X&iyJ_~A-wJOZ8um!N7AS9kDvu`-r+j)iLl&6Lefow23e? zNhiGP(Q9gdeb2q8KyXr?CIU4OP;=u^(>z+xB96xx_3r!D#kj3|w+WB&Rb0WWjU~UJ zgM4s`Ep0&_%BF(0pvQ{a>Qu@hAgBA+7a$qICkwJ>du+)|M9THKpdCpS>$_-bS;0In zOe*8`F%h2S9n5N9{*QAMreeUYdZZ0qMv{`2OxOF|SN4(#o@5-vb_f=MUwY_mzEPPcwXzC9D zl{hWgD$uiUJ~U!4QZ`hPeW09}8?5MUQu8w_tC%iz?b^PJ$5f-OCoR#|B*Tej>vdHw(DmwZtM<8c>rqMk^LAH z@&GENP4f0#g%yPFZ2siGCqe|9nyPa8+ShwrOJ!W|N=+_P7jug$Z_XXpod|}P2yIR` zr42rF8^aPFPUQ&=oT|0!bQBC75DFO_t zcgI0EAcmASI*3-e5p$Uzg?Q~z^!t=6Y2+O6o z;DitGcU3iu2;#O8rT(0oS=l({o*?Dm+9I9&{FU~a#ZBVNK_EX!#$<3SW4vf;b5uj=ef@ZnpJ2{W@(r+yZuWG5GTk zSN)V|73&6h`#W^ z^9+BlP8#0SE0e3AMxGHdSF@56K-=u7T!kCkL&5|r$uQwxzS*U4z?_xwrh1+*ou4`OFzk|>+*xjb z;Nl*Pl(br)ruh`)(L7uXMjhbLX9|468-|+-k7qEi(~HYVgoiHV5H!4WOc;FPa6`y| zN#*-5Ex(5J2I}0V_D-GOyP4Gr#9FS^K=cU%1Wi z1Ke~tjp&JJs@`H;@cEwQ@Jb~9u?v(Nw|>o&2Emga!~fY_{ike4eOq~Vw}R)@LUhq4 ztZJE4se4e~Cl4t+(x+tGDW@mFHd?t;#9SnNgH~GnW;-c>$?TK)4vD@ve6fipFxtW_ zwvY1`-bkV((4x8ak6>KKt>o4qL$0sA3*{#@HLGlZR(1r>uHu2QT|lN4A9b6v3t}0& z9J>Jcco==ZI@Epw_&K_VFX9*%12bCz!5m)^%qJUsS~7!i>*MCf+`&Y{b$V$NOb0Cm6?_ORp~u9VLAitlf3 zv->1Kok9OS*%rk2AYXkgSD`d{xpO;vug-#pId};ovFEpTaT^+EO4|b+to`#Znf%d< zXm}dhNo6~3a+g292sRIBW4#H8%Xmmxbmpk3-$`YS1NS-GxR#U2WvVLmj~X^U4-!4- zP1|rphm;tf_JW*3QG_4~8B;t$6o84{I{}M$jfI!+*^)u54gSFQ%>wlD z!PoIc>!Ivw>URu{c))seVW>2o7sl_x_V&y)wMZQ_&UPa0MI2x7J1zCC5Qb{@mE{!% zNIu@fpTJr(-M8+`ZIu5lyEre*u6vaG-(Y+2I#yo~m~JnSi`pgzQmOT_K|LNC>Ig9EM;$%$>hGC%BPNw-Hn)tE8w*65rh9Ly@Z}8UI~o8y&;|O&F9~Z zSzYkJw$~sOY@Zr~BVYe>X~pc_vOu>wGt#Z|mu-Jr3H`V0G1$Ie_ZFc3?RxXyWU*ub zj3fWe8-E$_-A$&3Vp0lA#|Y$cAN!+^M96H_^fy@yqDw;x=;Z$4ntu-8ZT0>46^dW3 z?IJwy-|^3@-<=7*JAOL$(VB_b_c`?M!~M@}qa;7dn46&YEBxCdJV0{PR*EG5H%0&b zNnapca=~HGfAi!OprFRK#+|1B+jL9-uO#fvzxr>UOa#|^!aj2J|HXwP1wcc9BR@#| vZqa}FI1h>id1+&p|N0eyzr6c(>le5En*3g^WSpc3_&agb){zf_g+FX9ZWYE|Fg0Uh9r0Q-&gNGlRMD9-F;>H%zHEYZ89pV_DRD}A|fKH zNyL0*L_~!J@OyjZitzWu@l__lKapOgh!?T?P~+PX5tD*GfyU zqd7%wdY6YXdWssMN2E1N(3%ksz0m(-B^0k1E}S|TJq(FtSafG*(d!nfs4dYMqoQ!# zfMCF3le#%EHiGZ@xVMr%9RZO?=Qhh+l+g|yQ-R_sF}Ov2Qo*7I4!3yTCQr#Q#iP;< zDodz%KFsjE5r!$nLK(e9?-oDkbGht3i~GYygUjhO8j7)2{GiU`arr-dY@o|tytv|L z+_3HsdZ!yy?_pZ%F~UOm%tg<3a7N3|M?c9kRJGbO&%<)FG$%>V0o;>wRZ% z@o`@sSBjGgqlO-?2ysU04{Y+DQo_XZx5@QA(Ta>9@nAhbxc>JHRl-l^QoK~s<}uoJ zK1=F{Y^p2fYty^#K9q8QCh@<|ZGUH6E{h!vlpN-l;!#;FW;BDtegCIetd~rpn6`@M|IbVUcuhwm zprk`L-IbS~!#{$>zq24FgIg>*J_h3dAFPUo`7=y0Vm=%IxV{K}|7io1bXbBAq?io; zlLp{+{b&KKV)^@@)&Iu;`sey*fyp8)qLqJyF2aw49Z+ekRab07 zr2a3`FARoI$fJdMk>>g5^~>MX93LqkP(58KS`B`vd}!%kqz#y?usV6C4Op?<|8IRz z#9RLdGyt2;jpla!Kold~m}oAym^(|v<$t~spq0-@<9?)g{%M*2-^i84OZZz{3AUV@ zR^%2(*zV?mTjR5UwVkBX8|}$1ufKpUVNHYNv1TbOxI#Y?hQ5UX*d5F2xQ; z^1B}5?G_X59{F5uXw`Y$Mc%+bOMo_Ic;Nx#OIm5erg#c`O6SwHX2lm>B0_JfsWrk2 zfc1$aB#Tjm4D#4|B9LMTx!HP=Jw+E{Saf0~!@zf?Cb1|M738pFK~Ac{VMvv!Z5+9Z zTl8E|Vls-DUcFPsl{m}{N*o`P6y(Aih7>9!OVP8W&ZLmUFXP9j8d#)LV&Ne=0%s{4 zTz0Zb;+OE_O)|BBlVnvO628I@_uV9)VNr{O98x14D6>dlp2;Gmopj3RUt*MDBm(wi z3&*M#%X~78&kFPPCuw+QN@R+mG*WM30vc{Jh=dGXf-QESs`y!_&!Hm%Ub%yls&`=T z+b#YSEfNSNsnJ*iOBvK7K6{dea+6}EOK#=)jeH+B$$@$eK}N`kkZ!%mA0r7#LNY=d zl)=5^1a62D+r6Zk-4*(A8-(Gxm~?~!V1jye8lGRPQMx2nc2|P~w^9i_7fINiIx*b0 zhS$u}5lV&*)(x;=CRqgmfCCMm6jUWKL7!#=i-vD_4nc_pxR(c`hF6KvtK_r0CL!-& zBr+6@ZI`BM31#Td#}!y4;-WReIH4pf2G=&24~+}@w}~sUu$eFq7)2N|06i4JNM=b2 z!8*dQ<=K)|QlCs6&q%V`yfSNi3QCxKXpkM0X|z5WVPYj&B>~DR)ag}>0GhyN$W(s6 zE`d?hZeav;d_#)NDnw+s+n1ykKtGB=5})TvQWv!+sfDiM{sM%90b?mrP`1AhMjI0L?A7Ir}PM_h-BaSa&#hzbH>tcti^BSEF=Ej+&-v8PaCpb{%^6ktxS ziU;nJrJ!nwNv2}^WtMmv%RvcWkRszlTQK}gK&CbUM74js4rysf!@Kbz)Iwt}J^=k8 zfFYACp{Om)y&*%alWR(eAXR_6wN&xLr3hS^k-BhNV%5)RhHN`r+OgHiWEp!u; z)wMV@P!fBJE%u}SS1TvjCi;8f@-oM%%yBZ6IZkDc6YYrpeFwG7aViM~{O@s`{-B&# z{}P^4u>vjgoXR|>vZ!8JRPUo`XPM{pZ{j&2F~uRff2puu@ort2aw=0!Wy+~cIh84= zf6FZ=CX-XVfAcS;oQf4{nQ|&qPG!oeOgWV)r+-i7#9$X6fcTeEP9+I8W!mYV)J||J z&>v%fOcgDHaV1V(kkp`dgOjww2`D)ACQa2Ln2+w8B;2Vwf(_3|Qz?RDD}A3r>^3-^ z2SI%a8%~4;;Z&cAa^OJ&Vo%ju;nbUoO`mxC`S=Rl9=@-~0x~&f zrhg}?Fx;!eg#>0*rl>}!L^bs35Rr&9;3r2CG2*uo<+)J zVqSt8!&8)Eg$GVmCgNhD0}UBG20O+!h)9Xj!Ay{2ZjYW%C6XbWrx#JUQYdsP`DTG! zj9YO>z((SzMkaDQal%aM#CD4Tk(w#7S%x#ruwGeEhuJ)ogR9U9g)Ehtd5o5usG4Hn0E}Y?W0i(({!p5)m+U7M}xmN)QD>2~mV%sT_8v%whMc>;?{%;3E}G zDx|f!1uCYHg@z;uZZ*qMp&K_KN*jr}c`~tEs#Qx<4GfZrSp^=M6ZPXvH>t#wBxbjh z1{)gGV@j6-ClQqu^=X}EvBGXhC2e-M5tneZR;gDlwyO+;JAgY$jzX=JqBbF_cAz4X z;lp(fUyKTI!^u#yLv1y92odQt2$VRzHaN#CBdr3qUV!3iyObxh+l2l?DN>g??;`kkpAY z?L33c&cW5mGaG0Ug01w18(7 z<_*9ZVge8Pf|MPNA(^CEi3w9x8eWi43wZ?L52;jM4=M7Yq*%sOt8tAAFso*{Q6**z zq7FRCzz}*3R%Iei1e_{F!of5=i^1+z6(lOQ}g6$q1Me5qE&Zw0<2TwV@cL!C(yrnx=wW6te-$oVcH2 zqBey_5Cr_NFal&0!f}EeVPH;5rM6+IC=zgy0yl};%t&I;CzosN3WI=BYn?oa8kdS? zAcHUgZXq1ZkXqmyq`=%_qsS+fIqfM5%*#|@HiW`BQY?WhO$rHPC>-aZEHugJaCv~< zB(f0BGK5H=c@s;=BDHc1m+A!pfh?pHp&FrEZIkj*hbd?jn{|dDH=uB$s22FZV3#7$ zzhAGxRR&Cm%P@0_98-#w0%am;7a|4+WyK&{m?S8cmKpECHFhZ_q!b|Q6lz4Mq689# z7DI)4fr6=Y_?ddASwuRhWK_e0zBo3$h$%AgNrhZ!CuBBBDy#vK**Mlj1mupIk}JhR zo!W{96It#gogGg=5iV1KC_Mkz)W$O4Q2H~V+6rbc!HhYZDDaA=Kj|Fnnug3A9 zI;520Oj4+32~uIcOafC%aT_ksIhBbjn=FWGlpv`nuR*{h39%B9Im`|ebb^r(Cd&n8 z2FQLnf#V+BsuapKcu_}G z8z&LfNCRldoPevi76pSNRw;X1jF52*Hg^(<2+g=v%EK5O7s?V^WDGN3#{yla z7P2X^n+>!l1^vM>Izi&I%n5`I1)Sqd9Ye@4U;#7eA+wASc$7h(*Fb=ru}M4z4aOt| zfgmohr^0+BxWy+nsJJW{CS|DzFQQ^fMPx!(;3Xkn&bLb_IF+vsdi`?TmWuOnQendw zDn4n(LQ1vTPNo<&lv1xoy|~!y)Y_z4gH6jo)zlz4VdH2SZZ_}>L%|T52?s}u3nf7N zE(V5id}_Whg~a1M2CL95hpYgjh3f@f5|hYMYH`f$&t@rs5@(uKDB(+0SSf-e%tDaw zR+Ipkgrt1RitE%2pP3TcK<`Nta0lhbL^w%;y`T@tJQ%`M88Kx@jRXV=LTJOpQn}Vn zCK66wf?kL#aRF*4LzEgvq#iASN)%3aq5{EjEJX3qAlD{i3X_yhQVuc@M;THS{vCwk zN&@6#j0$W$1C9la30@AsN39g1gh7mIzv7=TqA$hFnO>4Pr`-34{VQ zQz?;IwG5C47G;9ZDYM$Okfq^IVz?7$I z6%}9zYDL95hFPK%N!3OT@Ss&mC~!(4$E7?%$g`-_iqu3F2^N4`hFQ%bt(6KH1V!_w zKpvw))Ml_#J_U^%D~~VNNNt1zWCMfLPz+y!f#E`wB2uWe;sGNrm4cmMBN+;?O|)#4 z0A!>i;8J4tWT1bK8uNn;BvX_)PfIfGGQAy7QrMVD6eg4#Yyk(!G?RL}mLn5M1$u;3 zVGLymV+jR%fsoVzttEklDYHw3Dh(c^!i7?;1{WEHq*D#>QD96n;N6TmI7-yU4j9F# z7899yI77%L2vloyN=c>0<=257tFW7xMwp9AW0n|b+eBkdHsDH?QN#|B2-r3RGg*n7 zgK~kAq1D(^Q3fi-5G7wHpn_sVIpF{N?ZlwP4fW z8n=@I*=E3{0m>%z5O!M#(+I`5h9@&(xD$6OV-gwoASHr2DHczQfeos2C%!!MXOraC(H?4tb9wgT&?K;qd7^5o_c+RYc z_2YJ-gcAAK!2eRUQL1_K={nC zu0*ZIELS?sKD_|+7p}(~v=f80Q%UE|`NP zAQuP_u#2=R3~=cXCdfrhzSfSaNewR<=pjT}?F`W4Ov(l-T)<{3369g~1iloYBt-yi z*>E;ws#xWqmsAdr7fzF3F7jDGSNmjQvqIsd+)9GYB=}}0+?N?O@u_;2GLZnCqC?Cq z!Xahhq5z@|fz89>u|OXB)r304%>QM=0exqGV>jJ-$NlC!B1AfO5%*Nqh z4$_4Z{!|>7V&IR(82Fe+k5K^?*!C(W&H=w91+{U+DjVCAgmB%Y+OELFLM_mnjwG0g zIFrW)8J8?4gejB*RT3h00A#uuXQ3<#{5^xsoJ2T$ZoM6K%Q2>h6uT3E&cLcvauga~ zKyT^F(6P`Mz$Z#E-8vl~VOUj71*B&MC(ap_!KGuQ!x}Qm0iguVSXTM6ZIi`GA0x% z^n_2M5~Im72dV>q4*X+<2jpN#C-C6}h9Po|P)0cd3O&otQ7~X$3>!-=RPrg2*=e-- z;Qzv8gGLf0K(6S7HYTo-rjmTA+h7y&WlkYt#Ds%jJhxJ#MYM!jA`{yQ9FwZ#xRPTO z1aM`L>(@F+0u`82RRW<)EiijAG06gd&8xMVT{@f3AtRJ(lEC>%h+PUW$51eq)Iy;) z5upN<22C-FaFt3UVH%irn=&M0<90L!7xQE?KJdN8$JVLMIMD5&L>6jRI4H5!hWQPI z(gJ>Ys)Atx8(FGUvv_>U0eXrsFqJ|R8^X4MgMI4_Fd>gPy z?2xEPDndf1Orx|CxLE`+)fq%m9DGoRf|i}Q)RPnfiGp~+-)Ddis7zL|;sZ%xU&)85 z5GGFvI0l=>s}tD}rPbs|#o&vpr7prLB@&r-LWLXrFfTReJ)g?PjUkbM(_mw!fV~nj zsC+!sA+;)SsVgyrn!%Tx-q!;8*2Saj^nsD_vsv>WM+(F93qN$e|} ziRv&wb|_@cd0ajyC=xEF)R_sT82*??M_D|OK3w#O-$+-BDz1a_Uz=LTWV0a;fKCM{ zNnhw%oElIneW9ebL+R8yqjG4^2SD6AobE4J!z^8;p}3w=afZi#ZDuCx!y*DK=AR_L6hHC-_54pJ zW-^N@{%=uF2?qWZs|NgyY5@?#m(dyW4g zGmzuY(TgxTgSt5HUl>b5bXm`Lr|1!mT@H2_XcG^qc3EXsLl82kneWl4jkc9*xR4srkc{*DjHX!&WHmc%TA-~$2q>fL43IgEE${27BdEW7C zSxC!H3TNCK!1fj}VXp)7w;>;#ZwjGS6TAcal_42JrUoB40mh&!GQfQ_WD3H&L3lSn zj|0y#P`-@52eBmqQ>NC2P?g^Ydp8KmmxSbe8zK>e@3Y}vP_DMIV$a6zh?vfBz~B4QKbclUdYu76XfOto@42*~$5GqpIncOZ(zF53031y~PX;f*7I0yracUxf-ikQ{Do&JC zyNLIb4*1XNE7|jl3EL{_ch|mR8zqLO4|!3Q44*!{Z)j&2)h^&?x@yIHP6+4uJ0vW# zSssixC70B!a0JXo*e58e`|<8+;EiN)sj3>z@NX8#h;Ri8z#CmTf+^<%t4!2o!o-!I}Dz#mJ- z*K%kY4_CIJaSynoc?0MZs*Aw82|QiVUMgK-gkdR?R4yyY7t$DU{28p@Nh|e75>3S{ zt~BDJ=TBGic!vRyKP6Q?!g4oU;e&6oNJMlM6GqYeAnpw`3A`(S8V|rTY8lWyUHwA_ zbZY~wh1Ui2XQO$NrcIhR*ubkrvI+Q2t~LRmK@|@xT@^+Pya6zVHlW{7xLvJfqkKb% zZihA&#Py(d1n?psV5f#kB}KFgd~V}NKsEtRp&tnXeBuq$o*H--cnNAxfc&sA0memR z)ASv(nT&r%--semOyA)OF-ZjYbp-0B#I_jOdm8_nH2)EO|2f5SiYXQa2?Q9>($WcP z>G%PHG=-XgazHxMbyU0#G--OAZ)i zz&mVN&<|Jv$!FCv0m3GL1WoZAkZ^Q=z#S5hzz{vO#6ztY14tB*79dq04@UU zApmJ+0|{kd09NUD0w5VdOGy4)Li~3@FhKh~#riM=_@-%)maAUS5kLblV>Q$sDdJV& zL6F-}hXm*|i1HzV2XdKyM^4i%?D@lQpbr`7HGv7L%!Gi(fM&F`oB&LKRE63n09AmH zEKsBewV(syLB`PfKmp@nj4&@-*g)4bRuo0D8tSEhJcauvFZ9a+`Ul-+0=Wy-Z9s0L zYAph?hSrTh-!>M=brWD8beRqMmj%Q8AA+$$@nJa*eSq8sSrDXk49y=jHVpq=nBf0~ zthN{1NjTT7MYt)3AYH5JLzyiF|5j0y(CZBUrtP{Q?Z1YpjSsdVz%$$iHqJ+FrK%)B zr6>#UU6mwQJJ^zRwIbjYupx_V$3Lr9^d~Z|D3_;5#?im|66j0HfpaA^r?Fu^v^=5P z=n709wu#Jk9YMLMaHS?KJoCPSl8ml4Li^=KRg>s{}hb_3jvkDpt zL8v$coQ2VrEA(aHNJOArgKPv=Nn5M`=t@Lj;XAP6Wc2WFdLm=ysZi6+joJ0N_9P55nw^BQZ)w0vOS~gGCFy7uDzr_Y81EiYS#%ll~8mRy2PY z;lt5@w*cy(ziF*iyuOlk3+QzNbi;N&Xs|!jbow*e_~SZ}l68IvQ5p0MmTI`p9L-hq zXms7La2+{6?KK+tblZo|{h>nEUt63Zf4CZ5GF_^;sK!+3SeQ{4j)nbCl$~NSKF$F^ z*d_JOOGU@n#TjAdQiX((;`5pRGtsespjK&Fd;{vHmBlycN{D6gjk5SgS$yLoTe&R0 zQ5N4Qi*J<0H{SVvW$}&wo>*O3e4`}hQ5N4QU1|HzeAqwkLX^cf{vOQ!==Yb!H~z22 zHxN$oX^oOJQiSy{5#K2L>OPQ<-)u(@ylcS2#=a?^%QAlKK^3fzld@w z4oCj2#4Mweg6~7S{BTmNIM1zAqTh$#kuS={EBSsa(C^3PHW6;|4n)bA{}S|DRvWs^@-MUe%Pjvg%m3fm z@(25_IQO8WpvV8FU6b$!wLLBuls6HyX2gT>^8SCtAKMnu6)$8i%4q-Knebi8qJx4M zj^Z1|FF@%FV^PZ|7pE?dh-e-GVMleK|NV?l>0&Y!jWrcUIf&~D}0 zR-~gRS+!jM=2uqLzmeHv_!s-HMvlr}^fqc&AA{oOQ@oM5Ag;oy=H;X-tNd``h3swN z;hl@89&{oZtc>p4Ug!5}8XRS~+5PgvC*9BP+x}wPQVP6 ze#HH??M}8B9#O7x^FR5kez~Y4b1VPpE&B1y$~EI&{~}%Tmk+?(<^S^L-+fycG4I8> zyGqT=o(=!9lggt$7bmXh9D6x5u4R*!!ygR2pOW|Z2f@Tt%J8Ra24IXhQOkVdr|&wE zTYpuInGg{=kb5-mLGMe`e)xqa>Yl*_NYq>vH?0G9{n6FzqYn-Zg|UaXjO_1iJZLT4 z++61hXHV_0W9y z&Bp)O+m%Pf#gF)As5Wt2-7oS5@qg&>a)rtZ(%RmP2m^Ic?Y)QUYB&G<^y-r*f_3YD zKh>)G_>ZU|u0xfYaZ8Vxj}rjW<|m^nFHkvtz1`(Ql8M_1?d4;dvn$cWwlg8JoVf;b z*(V=U-YuZ0LkG{4r`ww=;Fa3O#pbpjbv5OansIG!?>yEyjKW$ihTmj=yz=I&p`$@J zZe0m4A`@PCy+85B$7G^z6&KO(yPAcQ=oL-g46l6KJ#~HK4=2^UJxpV&zW(hfdKz&W zm^u1sc;r%l{oWxiq6smy`b4^?D=Q)**RR>G4que8&9W9h4}Rf%b!Wwz>sf^bYwT}s zx8(*NeQEXeh##!oV8vdYJv_9{!P%UtF^==ni(6B!ovU3gcXOWC9Uf%>jguQoJf()L zDRz#ye|}TWRC$jURqJ+|+_}%jy(0=<-`F{#ys~fKxfhzqA6>$ht0l{^6>T`SQ{Pvt z)=>QX>w5d|`!BTE)5PDmZ%7!?q+V+EvGkN{){ZQfJCot9`N06uBYF;gzPFESM{9Xf zdUWrV1Je7>OFVjM@zSL^_x+dJ4}1G0eF-|R8xw0jd}909N(nS6eX}eg(wDS_Tc3tj z38l2k+_^R7F17#qK4jS2A!oCOWgT7E0b9QJ+s=LVYfbapcb0c+?_^mF3%gT~u1v`u z->7%5x?`TcsegW>W2!5w0H5BaPaE6m)zh-a)M&Klr~W&(`VQ=$l9~2;zho5|9C|_g z`Dbx^#?LMv7F56X9Ujr`=Jm!kOQZ2KBF@zP#og0~D@Sk0RaSp?=j7Da53&YC@3@B? z-SG9)9qTO@w=N#H0$+pXK4{v_C$4)Sz00D)yn1K12fh1_wZDIE!_;r5w$14>^zpcv zPbWomYjdD+RG3DiX*$#0T2N}S%_j%S<$t+L(NeU(Q82iB{Mq&E*;|$;*1LT=E9>zs zb^CpF;^r7Ox-R#c)x$DndtP47I@{@JgYdO+#(?NW&4wJ&v_1Eb7jb_R<5^1@fWOLN zJwu;2Zt%f+q*u1gVj16T9`r-Tzzr8XcUO7#%=7Q=G33$~@6sX9&zkbCjjp!NdUE;9 zMwyS^JZZgW`-A+uhM_~+Ryxs|LvFOUUphZ^_Il^Vtrr^H8T{hjcUf z-_+t=9$Z-9xtMaA%ca!kKZ_Inwi^wvuS$!!hB4IE-B9gtdLTRFEp1g49 z_ZRxkib+{sOS;i<9-lw#@ozH^47rq6gVo!fldtl67c%c`e*EJc>e1vDnPWeDFDV9n4s_kIccs!&d&HHh z_6wU86>Bu44)i!>Z17;%mB=mmvu)#N9T__PE1>b*BMbA=yJWVj-6Q?P@@bUGl=E%d z`R$(FJ^f;FgWiq{=EgQ4>UCGgG?PwmSY_1^;P}>sPjd#mJvP7;ckgd)4M7f#yan3BpX`MSf?gEIwYrUe_ALy&EI!`WKGfYxAw19eeX~%B+nG5Yzt$O}4zE79X zl=Sp2*<-3tTh(V%!;_Ysp%*=0)W2KrZeFeab?)b!Xs^0{Klp?y$bZ&f-Qb&UCq(n| zFQm+uPTH#_Gp;Xdn_j2dl8(eO{ef2L?4V~EXJN{=$b$TRqGoBWIJT2h#xxzO ziQaY(xtuSKxZkMr=S95Q4|w%KLR|UMMpg4O<+^$CY;osq<%9XP zLKTF<(_dA{o8-U59N6jZ)`O&P-}qXKgkM*C$O)XPl-MhH@8Bp90ee@h+0kZ|yw{e+ z)1r>_s#gEx7qt9aJQEbk*lJxbeqj16Ew}cQ1?lNM`!sFH+C6jMid~O>-8XeYvS!AW zM?c)Vw4+b{Men2`k9JksO&+F&eI%@V$&7vj-*AuS9BR^?Iy9GySbpc91!<{X-B;Uf zps|51)wZ)S`TYL*wy{rhTMQWTcFW@dJ)N85AMAM8t6VO>cP(@8Fdcqi$dnM{S8ZyJ ziwHfrdC>D%P_Mz=&uq8Pu9)#@qh1$OW82OT@Y?ixK2u>@MQ)&SA6-4RB(dJ%a!z@p zMn+@9OIc5UABPOR(3Mt-ikt+ zqNnDWYGJ*zAu8tKC2Z)JjEp5$kIAJD)#TptPu3x-s$(yOq4rMq){2^bXik^IPY3UO zdHHykd(Hj5n3rm==p^Z~>=tN{31<(J)P?-y z>^`n-t4@r3(WAR&ZpUM-yZ$JfXB}cu>>&mWyQn$VYJG0EGyYrG_nza}uHWiixTQzT zpdaR@JwLm9AZW#=;_6|;s^+}moSK)m-!gZ#zn$~y#n`uASDBOS`Qad%v`NiWsrD&QIN4TiCZ_&*z?BUG===Xzkdo4@}e9-w)wl{>emh z{JF!;hCUkc_{GBP(ULWncJynOP3{{0w!nDl!j|2=3vRx7a^rT^Th6k9y~gNoC*{rw zy_i0!_uDfs*Bm1HwXV_gjl02d$N7!>c1D)JK5|%LAM2^*t*^CBnw%KD<<~P4BhDRH zP2L}7<$IrKvh@Yt;KD(hzdZY3kbXmxNZ-oE-0G$EQLE*{FGsFFggzMj;^OX3H-r-! z?)%g>a9UzIZiC#=bOOAdXWk-l%yq@HbV4V>Q3IVGZ-ZuIw~ zY2w=T8Dpfe+QjS%`xj=+7%P4t@5)T3aw$4*X7$m}Ws`be zUmv@>bG2%-4kmN8rjD<7B}UvI(;=laTf`w%UN(u#;+iIY+LXPw`SBagd<`mh$+@S^ zxW4P?q6r;f`JpW@-o8$&nwGs`aL)A3Q(olXUH9eNA=(|G4Ip05SKcXi9v2P;H@d-H z*6B3^F6TryO0gVCD@=Q_@9vr%1K*@Q9a%$q+Iew*<1rEEyrB;Kh!LY|9=Q@c(eAqj zEPfvCOMUjk*`YDY>>Gm1t2oscMzUID#GZ>fa;dAb>IYP{CJw1^B=+gO_Sp}2#10&} z!F0IkmTMc&U(Yz)i*-t0z4O*K&$ir}-*Jm-X~T@~cSP5?Ff5BUDx;3{&sH`AV)=P^ z#X}8y*diQt=SA*t_ABS#A3VN_HLJ>;d9S%=M@F3cw(j{4K+^%7B~k31trtcgik=_q zU#*DWU_H55n=w$isejM2Yty#XsatpYsAELR?JrsiC$gJP$u+hZ{#-eAD|l?&sJhX0 z_8p2oKciK8g@gBQzMPjCb>wlzt-T+Z$8^}>=!D}S2XD-u+xTeft~A@F026D?aZ0geV(0)y$t%I)ZMh4|k+-u`mKXliO+EIBy&l`&oKzPH*Y702u zY^>YwtAvEyR_zB~IRInUXcy^wvuAkScOsCs9)1SvVNs*>2CRX5TVC6fvoK-I_20*J znLcLs#A)D}OjmDAxr;YI%#*hlzJ0y>fT`b{eDKsJKKSz6rg0C?Z(8%R;Kik>p=Wod zRXwt?-?mRSt!=sa<+Vxo?fBK0TLt;2KX)2T<sFFL?bT=a)A_EJqf^&k~;2Y)p!&-niYfiH*7W!zMHum#ZQNKkKl;@x_jt z<|`|8Pj2?yMm^Yn<3{xpr(B(KCT)JXtm}hTuBMmjFMfXS;#S#n$Jv{_8@a1FlU&U= zOza+du%*g^6?L88S--;w3KvGEhbuyeI%eV4v0 zPtF_?IQZ>N!8fNH_xJw5b@`h0_tFg)u5$KlJ3V*(q|?&;^{<3q4?b*f(dc!-u9q2e z2G8nbY4^&LsW?2|ls;{3jo$V*Te4r>%IUo6V%>w26BiHJmtT|D-4-`^TKa+X-U9~q zd@=Xvj9&hWt^GHyijAu2`*Ur`U@_yt6X5Sq=l`+pc#Z z^J~;^zG?K@l)Re1og}Rlg#M0d}>SIQoJ+j z>o;litg5|VZn_)t4bSM-_sZ6$)w0uv-4>jFX0AW9fOC55>OCu-=c?FaKJAhJy)ssC zdP{>Bd!u5p`mfRXT_tVgb91-O-}d_Xv~901UEA7p12dg{=SO6NqU9#R;U--!B_H*k z9TyvT>wesNUFyNv$i@9#ePV0fdO5Ktm$!auL)jT~IbRmI5475p(79o+^fZwi#(nwb z_S0Fb?>=7M^KNf#bjJa+uWjuqJH$;m*Ux+7Xw^r>8Zu>Ik%q(rbFa0@Y`I7NX7JbN zvGu#AXU^DvDpNFUgjY2*=23-Zug~e}*}i?cH)UN$PH^>Ii$}J)?bVz4Gd#bJ`+39J z-)ba2<23r=4l!uM^1S=AMT^eG`j$>5H)mz$HmZ9$jqyv$;HLvKgJTq{?;d@8bdaad z(>993jW+!TP&qvHZQm`O^Pep4O*pHr;ohj4H@o(wF{kJ5y;Tja3X>ks&W0tP?%dxy zE-^@2uTkvq}HFQ?i74y!1LtcK@J<`g~^%_=-RtYN|J6U(Nq-JKErn{N8N?*9F0FD`W~4BTq6jNGvN)2xTR zwmjInE-QBHK5qwN*%#ARsAH-JuT6;Ee`R4p&Y5mi7Npz~2PbORqA_o%SBS_Uj*vw( zc|5Ac@aRI*z7_RWs;e%zznxd%v24xh!pHve8FO1c`z~VZo1<-qM_(Qjv2{qZa=Ghz zMIE`3&Wbv+{pOih^I9E?*?#lU>}yZoT;+^8-FWG(@hO984j2@A+coWAi{YsqhWK7z z+H|3l_fjAs_1>8lDR)kMC)u*ab4qKHOlZitzVmHC-ceDreG5jEH@z`-r z4>DhCd#_tNMEla8UA<|KcH?^G?+wKFy1)K-t5vD@k@9uFKRvg}>*xE&RuimSMYcYh zJcO~e;}m0;-qUBgkN>1LPny%<$dEeg-(++YHw&HssT=(|+CDO+%0#l+s_DNsJV_N= z4*n9oOJO{Yo_%sYW`y>u?1Q2vt18dUzLB2&veon&Yq(eUF&dItw z>~iJw4SfSg1&H&_OQnrJN0c)47Fg}|3$BbjwxQ1^WZod8{MPL~_N>%2+Zq@;rusyW z-cZr!J8+M-d;*=4lbav=WzL2PiyX7ItQQJwTv4CiuYbdL0*cR1_pnQcui~2bD%WEa zBlH5C@5IARdye19Ra!1>-*R9sC$ZsO*3UiO=}O_M{!vGo#;#f1t(-ZFT2?PI>Rwgz zqaKFQdw)`V(eiEK)}<{)=PsWf*}2NRo^hX=KaV;R*`)q#dP47X%!pdeho{EY$sfN( z)GWw{s7ISVF|O(5D^(YR`>{k9+8Q>Cvn$atvu)kQqjpqTkfvLr1Rd5P()P%nnq-Pw z)92RU*edhV+E)KH5@MyyPub;48&u^w#YNm7>VAIjY|G0-pG?RdpPTmjd4n1)515bf z>4?sTW5+HugCKEiLI+{Q2&&$Zi2Pq`=RD6lYZ8Q>d^eD6*GC|a(C9KRgGWb zxX=Obu2p|UhG*vO?`XU*s>=N50T?3h%7C}}6TxSk(|Zdb27s-=pFOP~zw#c$ygd&e zUCrARdxGYblJIiAVuxHHnq(@xQj+K zxzJ*f5kjd%WZD>XWbXW)i-txlY|yPs2TjL0FYb-C`MU<(5K11&s=GcMJ1jxLSM9I( zBX(r|B=&eb)NeBe(9vJxvFrQt<~%w4;#0%x=l4B#560%)N+0Gt@#;!K4atn?emz$7 z{^|1_kAA6|H{-jO6K>A)KG;J04$Fu&{g>UmgEZ+@KK~%syI8qI3VarLb$lAp@cgF@ zyCz=>Jvq2&V6Ev7A1!~_Y1h?ht)78x^t4>VUZPhI+GfmKWRic~v&sUM?)%#b~aa4N`cuin0X*eK)s4eAxR?Cq8>N3fk2&ag&| ztW;yapkDuWy$fD0QrxmEo!2H~Kp-AGh^uFrUn##^z2xF58=)1~>G;=r$LT|7#z%B(*HYRYY+6RSPHSt;Tqyo&H0(N@a39r_ zmNDOqjO$b`m$vOr_S?1}Lha+5&Yv@@z3NBw*;C!9hMpR^mj|RiIMV_G@!vtDTylA6 zL8~2#MO}Z&_wJq0D0cs%+HLki6s^5zVq@m?3r9E`&Tn!xdp?{Fx7Thq?83{eszYD* zF}#`zA>?xAVWY>8wc?szjq){FG>Ziu1odFSVA@Qqa=Jpp#={_j|8i1f=Tf2Bh!I~_ z{q>9Ccx1KoHCfNevpWWFqMa(|mS^~uYlpfo8F+B^{D|9~a+j%o+*{c5$@s=y-Eqso zJ-s#8JMn_&yrWimQeM6BB5AKTSIP(PEL(a#L*D!I`zsDTz_ZUk+?=o+Uq$}-`PLqy z)6xCH4rXDsM!oump5MXNHDN6vGY#{Cmg%6R*}HZQq`>dxp^kO zv~Qhi3mQciEItvl<4LorU#(1HeBk>>M)9eK+gq<&b=jBw!|tz5dmqa$Tsya9(c&C2 zcZ<4bHv>`r_uI#RY>?sSu$%OtzVSUgnq7JEj&==uOlr!J_8(S|a;-i|+XwXq3|ag1 z_Hohdg5T@yzGp7@By_Y=@hJhi=BDGvH}n zII(Th8whDIw+7!l-jf55t)QM~yln(>APYYg%b)MXz6Umh|2n}qcMZbEr`#|WE((DC0hF^Txgj*k$I7-$C(6g~xyN@UHF7e0Fpkn)~UkX2bF&nH}3rPPuz(+VZ?n zwb98=VnAowm_E~M<$$dIyC*d=)o+yJJF%tcy}U3%(v!@JCVn_?e%brx!ZC|g zw+{7Z_p~<&Ti0nT=8XkJjrb&r*Q{OOw~pTHV~IlC+GSqBkcaE5Xm*QtHvIH%`l?9x z<}6!A->-ii`g~l(IeEW3!V+;uYn)a!UxJHg{Ic-vI`F$J{{8KzbT^KrDC*^@40^*r z7JI2({_q~1VVf0c+VH1DV{VeM%h*GW`)~0qNt)B`+}F7I7%qVi9BCN}9fAtQv<1#)KJ-wweFR)h|ziNc%uJBUN5nc07 zg|@eiT)$_58Ytks^556y=g>221NN80hk$sQGJk&bq#pS{z3KK#!u{=cUW2bm?Y*)K zDNHY{lNPs7ix!?-Gyd$6tZvsny%ssR;eye9E}xNf@1@;(LNldDAy!aw7Qk?0?C12> z5ZCwe=f*wU&GnyyD(LvC_nK2nQ;+rcp0}QR(E(cwQbiay44V<{xv4cxTP}UQcJSe* zX92o-;NR{)|Kw(aoK*ACjRPL<>AipQ!h|KT=dnB*!KVEfOlbckXOwjeiu(u6VRk^#|v-ZKCGvp3taKjkeq0 zjP1C8)Zwj1f8En;#?tvijxqKgIy7C>ba0aO^y>S42r$1EEzw8SWK>`W=5O-^XPrIt z-6&t(^>v%}2&ngdIwc|d=Hj_)?>(DTEpq+oA5MILZb`dGd5K;2{REmfPC0V#uxQPf zJvJYD_`{y_AYgms?`;WzyZ+109vRxKyY{YY*xOg0!h#o#SaVW>Q;)3k-a_|1ICFGn zwbjNmkFM^XQ+;UNa^~JC%NmWSQ~aV}AIhZhmKcH4o9YEcEY{nTV_v)@Hm?qzG^Bkq^) zfPD~2LO#hIc{lX@Ui)pS57=A%&VfIU&(9gK*qAe&d4Kil8aph<+nn9zUz3Y8SsQ)Y zcNh2UozXwo`qUV|uSdV-38($1mhheq-dw5n?9Yb+01?lxm0#s%*I2T7^BGN_{M)Aa z-?0w&IDVA5=5Yx5mSr)6b8JS=DF8 zo5JNMSB$)L;gj=AYtZ_j*^&X5GkWJ_Ae9fU+1O=wc67>mPE}rzl6I@v zsWmfB+D`2qT(#c*-j~xhU6*}*=j4h+a5Zmi?EYYK{tK&Gk1RSF7x0u z8S@6CX+Nr8u1x8?|4wt(>kD-p8!{j6X?Q5J_W9m$fFZ5p#?oE_=;QHMf=7Q4Ailjd z&knU$8<;k8Ud5wZ?Fq20u^9IEB(@D8Tc%{*9{J|8wYf-}ZW9~w@A~_B5)yahKQkUk zsIjj?lWyXJyvX+cpFY7e6Kxn>IQq} zjmAGenH$mV%kn($d+3DEg`8TcZK?8jjkk|2S?9QmL$p}@1AAU78RhGj3+Ej6a&OIT z$@O3EoVC6a^Rtfa%H?V#-o{a%shii$v41aGl(FFTr23|n1@`I9qmCT#pp$C@bmA+H z9rywH)~w(wxY8x_B@bV%X_4NkUk7?)E7EA>tFla+vAf+Uyl>qHsz``ulexGSt)hst5a9BGcM0Oe}Dhx%Ci@GU*BA{Sa-kM zAWQj5Deb_mt2zGQ2gc8cb>+s?XcjZwdt^-Qrf0I!&mM{FE%BZ5Zn$%D!VTq}Q>!|H zLHVt1T$Kga_8;C=tMdG~9@EeMB#t-rzMD{)Gh|{)3*W>IoA>N#IsAG3@9&fb9<7Dl zZD7a)<5txYOGh+6m|DFYW1+XEaMz-knsI}pB%Jqpt>_mY_Kus(Yc#mUd?lSQ%o((j68Uva5)ImFAC-r0NHRf>ga8)rD2eyc<^H&-mz zze=m@{6n8>N6o3wGvlyq9axJ$|0)!O+CMLhI?_JoiVp$~rE%2U40DffRO{TxxbMsD z`#Ce?;_ADgJkc~^Osq7PcWcYV)ph3Gu#Y~RdRMotPEDBli1;7JeKhrWh<{hl%RLek z)uE>Nlrg45!$4Zih0(vQ&0p8MzO7pZOhDiM4LyM#FMUlunm}cG0`)7L8$LW?gu2@N zY2UVvX*|EvvP^EIZ+Uv;(`Fw%eh3~P)HI^{q~Wzks5O_lQ!3S{{@{4{*Apz7q(s|?$N%`3vI%($C1D{uZ>yyV%uRro|x_eqW0=Up27#j97&eP=%! zD*V#U^7QGkn#;;X_KwmF%-(el_BRgCeU&w9b+_ydM3>&9zwY({HxyscaMj3*XX<>oiud+u^J!6FBy>(+^YWNt#)OFcmB$ZHZqj{Y_jBJ(__Kb)i&Baf zcy8=pmw(>XIOR;`1+Q;j=nUINQ~&(XV1H}Yp>3&>w zbNGxk+;7*!*MLKEE;v>ArtXhJqiX*A$)nlXuVCwKZJlpI6@8r=?OR(jF0K`J+8@)b zLqM>NwY_Jx@Xkvw(u7a{f6aY)IMi+XH?k&0l8`7#vXq3(5ZM#T64?tGjIGAl2^B4N zvW+qJrR-y0qR754GmLDB!C10}Qtvg?^W69I-0$!G{rURCaX4nK<$GS|`Z+(>SIcu2 zRZwRAwGjOMsGl#?E7Fr)hOQ>r^A>~D*M1Bulu?!c9vj%TXk4;dFfML=k_l~G@^$&d zz<)CR$R;+S1~4WTb}qgN6W%*8=-X%(2(Tq4IQCfJns|`xf3NEQFXN(Q>zNpiTlq0c z@GI-VSZ|kg1j==0=>JXkf1d&mneWz^F+acxa-yvH%Uo5BfkYCtS~}$5L8Xoi>AS3i zkh9aKsAzc#}br#$<~^Wg!zG#0-2<7L?oU3_rI2aVPAO-~&?KA2skJ3+1E5g&pJ z;pA$!->Q0t?PtM*zFcB`XDedA*SIFL5B>%4fhX6gU!yQ;nBhQKw|G^L zMLmPE$Bf7@rAUM?4Hssu+YPmYf3CaiSf;4x7~puzHmBoEc-s-SfqLn15)?lBsoHIB zO^-*T!jYRO`nP%amyr*qkzq(iKkbUxfd%$*lU$&P0F>p`}z0edOb}^z`R94U;s4>Yu>MMK?TMtdO>;gpFV`wkW7YsaCR=Ju(9cv78TBIhVE}D_3sh9ex|3H8%5Ad^J;E{sQ(^}8I}I}`t7sq%=DBZH<1Josaa{;<$=+N0&*N;9Men3>V3ZF&VSi2SQV&z8 z;#9|Q*CMJsGO(1?m_l>%=%0`VxWR&zm8s^FZSR8*O<_8hTSZtfV;LfbM>p#^I5<@3 zeGIg;yg8e+fBTGjb`Vm{@8;+|u@>RHj3QknVFV*+?ppH=!Bn-iBgCL~t)D+OX$Y#@ zQ?IM&-JJ0t-T-`!;6K|>W$Phr7oJvBH*J@&85^s_E_8N8%bLJaGmtgrrKx8uF`gbC zk*8Lz{kop}I&RuGBa09G_JP#8;56f=A}{5gv2m5tt7@dhqDP@S+D|wj@UOX#GaJqQ z; z{xM5!#ztX3(W|#__qBj9pfozM>e^w37GZP~6)wHuOY&}ggPLw%(aF#ex5CADq};Sg zf9a3kwJO8nQ^)XG;%KMY-ZYJm5XH71YWZE!sat&a#=LP5$&ni07DA$@_|Dg%qK@aA zK^Oqd0>Tn2eQo}7Ye)35<&_5gCwFS|?}%Ku{LVl~SmVO@6HOH7ZtwW3b+@xp*p|U& z2wwupM+bdjzx?BUM&r$pjB!}WJ+^Q${F`g7!8vBhJc*}{+G)?$?T2(dB^IVznVIFG zmWSAd;Y`*o_P%cVLdLNI0ACfGs#F$ArV?hZ5+Z zvwr3Gb0uiPPxu&3BhC^y`b=N`ynF7eZ{D17|IZ*#7QJsK8)fd%vhnhrw1DnbEPuunjsO6-JY9dR&Atly{E%3U!1Uk zxQkF^AH2dWOF^#EatVK)PjS6Hthgv!ZT;p=DCSzm1KB|IwONfdrl}_74S7`wdl{GP zhbNd)*uM}*q|c80wqtn;8Y&j~psE4cXwf`3*YGGe^u-+*^Z{&8a}~!hrBr9!&hz-h z8O_boB3+sh-iaKFc6;|Wj;OX=scg;|#}iN-9;LUaR}o(;HfNuBI5mH!88O;%O}E^7 zv^qAIbvOqBv%GQmH+HK}NyuRz*)|?QO+l3CPo5vu%9D)o#c}I5aWUiS? zOQ)LuaSUoQ{_?av`YPhVj>XGgbgmb3TzPCtRNPL%T`)99+_~#RHQNXkWUc)uqjyP6 zwWmtbN*MP{V>)am0oD=`d}!EX%%eC>H!C~97s$*?tu^xGr?_)7-KX-%;p4|KoBpa& z?b>ntX3s66OJ}Rthr3J`k1q%dv$X^=rXvHFyAvcu7&11xwP5P1T=FPvW~r&r@r#ny z+9Wsl^OFQ?aTi=6)Wpw`7GGebK(e`Z$GR4WJr;zK6C4QH^P7HkRAP+DfN-P;6Z}4` zyoYs-9J^PBu)r|lz8b>jyh&@SGKx+*4RdoEXAsuWu~nXY*;3J-Q|?*K*!m7s=S#=C zom`LLb*YttgS&a+DIT{YVqpi72_^*!M9rrNv?fLbfOHt8bBgwb3v zGi+~=w7Bna>0|tyK;F=9V?%G+yYS#*HhpsK?etJJD#%DBGOekJo&Ok(7sugfjuTc-I+tLolyesUwl5Z1JGP>zriuPD66D?qI7$tP) zC_2JQQHwFB)8h@IGtW$7=qSKnPe15+uNJZYU=~oE?DaunW`jP0=IeD-qjBvu#KI3 z(lydfw;4OBbkuh1WRA!TSIx|!2R>=In#1t$r909?B{|x!H?NPkl=@zNlL~jc;!qga zQ$=kM(Ll6!Mu(}OLH0;40_a2iE>f1D44WN4*dTBl(j)nYLNAHj;H1R4Y9*uy53=mq zZ3E!l9Ab-3c}v$bQC{;E@41$9y#N_gc#+A)FbC-xjf}yL+9~2+1kX^0>rZub zXn1tJKXj#f(F#h=Zu}crzJA|1<>|m929JRqVJ*2p;%eUU@-x5rG+z8wt+(_2bgWXr zH=j_EjLCJ~Tfz+ySLM7)_A5t!XDWZ7*&!u?y*n@xp?4;sZ)f*ut;5rvc-BuxD6OI2 zQ#f-Wok6T~9p}-fr&WvcnK%}i>}<|+7lh3l;r)WwCsJ&fkmwd|S0Z6WrN8v!fRsCpsdM7;qb`hUwfZ)Fo>anptxS#Y?mZmffq3(s zq!?3kVQ0mp_F>rc!g*76BVb};4_u=S_-@GprIP>57)O$WGD$CP{`i8+3(?$&k~5PV zz!L(k7?Vq#X4cLpzLS=xaQL>cFH1`505VckBbK84@MsUn;$}a+Q+|83)UTn*sD3$& zXoMG9UrWntbw$`Q4WRQ!hA%@$?zR_$?$T=EEpdXSPtqfqy^NDcewp<3^`(2P%|z-~yAC<3dUigv zD*+S&zNOW#0OL2ej< zbvsK=+YFIdt64i3sMVrvN(9u zX1_qjFG(5nh54x4z3v=;8?eq9H!G(bVI~&2Vs_4^&TYj@>kH{lxNlSG>+5!ay3@Mr z6^bcnovxj^8%DZ<6|EhK4>HLxYFNxymqY_Izhqf21 zms`u1V|=lE2~Frn+x(AiVxYmpU5+tBCoVgO*Zd^Fd#|JnT$?%-&kIPTpR1Bc1(moc z#<8`Fwdc*KnI2bc9W|`B*3{d*uq@GR`z+5W@x;T}3xjXe0Wa`m!F8J~rX9U)>t>wz zCVY+w%iVev+E#TeNK~kpShKcJ7%R-4N|LWeb4z%9J{vFdFg0%~ro49)T!9$%88yec zcM3i}e-scGms-=E)J1B%+nk9Y6j-=kJI3wDdmh>O>#3APlSaII}Q-I^Kq z?+L6qWqMWR#a`TBz9p_^Y{_PM^DO1HeS0wo58WrHRm*KQxl;E~_pscGvtmm2cz>{o zQQsr)`5lTyVrS0Aq>?VUb;&bEG`P`((nWI*3P4AA5yie)9td>`?rr-i&4OadBG1mE z@0|4^98%V<-LIWTR=m2j+3NCFa73nALU$Ey35K7eU}gS+X<)+=S0{CkYWJ0~^$WiQ zLdOwXvdwewVgvt+PM)tXcB9OuzhCu9lhtwX2efg9P!GV;-sz23d(fY$`RKjVW3D*< zs{u9XPx{%Rq)lI8v55IaTf&69t^Thq9TG%<)Z7@b{*Y(4rD^rSk$Ll z+KO7x#gf9C&e7ihg)ULF`(t+)v1xu%X+9!XDyvr}y=AV`)`Q5(V=VM5D+HhT^_p45 zSrYOk(Ei7nUspCInhW4H$X!_7_&u!|xVJEsjc+EIdpCY>bnF$W5=Z}J-*Z%g}F%Q&~fJ5WxvpO(+e-iPLkCl2)~X)jWgVfbO%X=qD5iJpD~aEAgTOx&>3NOtI+VIci<0(^=m;!qWTf>;UM^+H=mVWN?rBOHaG#Tc z>IQGU#Ml^b6N$4RkI%16O2vMk@Fss50NVl$=g&Rl>FBBSS<`Q_haIFc+nYBErR$}& z|2^iDl=&;0O#$#4S%EUpGTig*Za`Q|KZZs?X8QB>y!W8 zXs9|ET^dKaip^Dt4qup2_XFd+KP3_n7D9V5eS+ROq+IH_$<(5B5!>%Fvw{`y^N7u3 zZ1l`m5HG0>$z#$QI&=PPjy{wE@9t&!USceX)p%cgetuAJ2yVU$J{o?>@w%s3Xey*j zrR@G!3&mdcLQ!J#d+qZFbJ4K5;Am-@$l^3GluO@H>(932ovACDMz|P(oDzrrT!sDw zIv>?*H@9l}3VLAf6ckKsq6nrObO;dAN|`#wvZtOm{@_3pu-Xn zhy;jL53IHbbGC{>Z69i6q~jt^kIxXjd~#6*?P>;WvcI*Cn8Y zb~2{nD9mxtP+QYTbKFyA>K|;*-0~MenxVlMzq_!UtPKSWRlW&)ryx)FhP8JtHtiio z;^yYiR-Cw0*4U6P`Cdo(ES0b6)Zj-GDMS2YoK(WDa4V-giK}BrWi6>gW7~Jr-uS7> zl!I6i%f90J9|LR96&qY3>qp^fFgZwS2hf(y>M>8EB%y#xD3?e_~< z=1(pJHAuX({mdy#T)%y>gtM2E{evWIQ>i^VSSrg-tk}!Vu+r+q`wz{CG+F4-5%PMP z{#;dVu>iKZns6U((6*z39mj85)ikLhe9CEi;^X626T9n-hh^D^4uh|gwPFFN_{g5I zswq&)9k4;fg!;-Dz^-E~EVrNAyog$v(G%&QV}``nHj&qPwZD!irMMq1Xk<=tsYVnx zT;c0W5FE~50mWzxIe%`L{IZijLTccV_^~`tiIrJc$#pI0J~F@WPAUBR!1E=t0QnbF zftntjD`&$l6mvvSy$q!*QFbj+?a2Wq=7nS8%q=Y~;WXE%54#fTCHD&}_P9uJ{L=;$ zd3X;~Mx#0ss&mIyV0Q_5BNJY;G5KNs3wdP}Mil7Aj&Rzw-?{-{zs>PDK9EMs)BO11 zp6@EH50=YB>8|O$n3+`4M>uL7*ilr)lHKj%>{RpqGl1TO2I$(vvm5jI$sc7n#0Aj2#=%kz1Wa)0hfUZ?QRM0J#4K2AId%QrQd?K^Ln@>>=B$f?|sS7 zQO)ytyNM7hwHw**1O-$jc^In~H}T%O=H*1nr>=v)58Z!)+zo{Z+khTd<6Zd%7*k5= zRrCwX@*JGR8KiZDbal(pPuDUmZ4acq{jEh;s2!m6rHdF^e0sXGE3XWmPAgWWs7tB8 z^fdDL6&kW4@giv~9-{HX4Kqlc42h@jvJu3~crQ|ib=G|>2faZ_W6&wZx{_Im>KY42 zm~X+Xu$ZDvoF zdXdScSACd6N6#5LY4D9k6LN(5R39xakOn1jT=x+A(I^h>l*Qt)bQP?1mc#;n1B2wY z*@K7V=MUa3SnD-0SZJFoeP?Etlun%CtRCoU32zs63YZrrt_GN`?YzOn^jQSfxQ01_ zEe5pAaW&z};wLMR9O2H3J(6%QzS61)~|+$F7+Vf%twe z_&^>|p{opypQkEubVu!^7CW9wI(IU4c7dX;EK8h@Zrca5_^ixOrM`8c z_f2OSw7#!b{oGv`)|Qp;-Ko~Kw$7B1@+w0s7BlVpRC?;$;GF%QC`17*Dx<;~f|d`) z)%dMc#*UcIZoabOtVr`u6YaRSQjxvBXYoem2H3O?{_7p_ga|6zwR2ZpT0@EmIhcJz<07(0P)$&XTj&LM zoUbt~3gK{TK-}MT|0uu8k@G!T;7&dKdnC@Jp>r(hF1w&xoWIA3KZm-`TV<)Mj?5ll zl=v}tX@o>~#;%rANpHBye_BrqGlD#`@MH{u3CW$sZDjtYfoLX57G_Azz?z21O zH=gJT-$OIx8N+Sfh^K65-d6uX(=q<4gJTM^wmn&7$=^R&Y_hUUCRXf41OMCP2WJ5G zJQ3%&ab3Arly35vu2ZoK!wb*mYpJLOp8h)qyL}Q#quxKHU8GrYfi9jid+2m{0+6;G zDpmlCK-{G0;ODD}t3@Te>D?gwK&w8cQ!ft=!ZjgfA-bFU*(Yx{2m#l*ImlON#n^jL zI$)RAOJeTkvDz+Xdx&T9;59QXfJ%<|8seXQIX9Sh?mPKxas-p{p0zWiQn`}2_8W2I zy1FgnW?9PaaYbF8OCZvGdL1?8bRhc=gTjLRA{brA!=P#Of)@yayMPzMl4vp9q;>?+ z$ED|}V<~;~B)Fi!tab{pvXKrpOsTO-^h!}#?xBfu;(S}IF9MA z?y%Zzn|z)(1AFxk5W>EC1Df(vPPPN@%uMs{`<4N zL16S>zWyKc{69zk``u7BzkS<(?2r5>vwpI6no6$`3nWF^ z2WD&VX0abWEbHoqnEgYuabKo-=fh+4jUC@@#2hTgI@WXkPqWI`gEY3pRB#_{{UVF-0d9jioiM3au06#aBwUqJ| H?gjiG%@K1E literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/base_class.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/base_class.hpp index 1061e07e516a2..43a929591dad1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/base_class.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/base_class.hpp @@ -104,6 +104,8 @@ class LaneChangeBase virtual LaneChangePath getLaneChangePath() const = 0; + virtual BehaviorModuleOutput getTerminalLaneChangePath() const = 0; + virtual bool isEgoOnPreparePhase() const = 0; virtual bool isRequiredStop(const bool is_trailing_object) = 0; @@ -130,7 +132,7 @@ class LaneChangeBase virtual void insert_stop_point( [[maybe_unused]] const lanelet::ConstLanelets & lanelets, - [[maybe_unused]] PathWithLaneId & path) + [[maybe_unused]] PathWithLaneId & path, [[maybe_unused]] const bool is_waiting_approval = false) { } @@ -285,8 +287,7 @@ class LaneChangeBase FilteredLanesObjects filtered_objects_{}; BehaviorModuleOutput prev_module_output_{}; PoseWithDetailOpt lane_change_stop_pose_{std::nullopt}; - - PathWithLaneId prev_approved_path_; + mutable std::optional terminal_lane_change_path_{std::nullopt}; int unsafe_hysteresis_count_{0}; bool is_abort_path_approved_{false}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp index 9d6fbd65acfd8..a69ae0d92647a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp @@ -129,8 +129,6 @@ class LaneChangeInterface : public SceneModuleInterface mutable MarkerArray virtual_wall_marker_; - std::unique_ptr prev_approved_path_; - void clearAbortApproval() { is_abort_path_approved_ = false; } bool is_abort_path_approved_{false}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp index 5f1da79bc7ea0..fe1d18ea6ea0c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp @@ -65,13 +65,18 @@ class NormalLaneChange : public LaneChangeBase LaneChangePath getLaneChangePath() const override; + BehaviorModuleOutput getTerminalLaneChangePath() const override; + BehaviorModuleOutput generateOutput() override; void extendOutputDrivableArea(BehaviorModuleOutput & output) const override; - void insert_stop_point(const lanelet::ConstLanelets & lanelets, PathWithLaneId & path) override; + void insert_stop_point( + const lanelet::ConstLanelets & lanelets, PathWithLaneId & path, + const bool is_waiting_approval = false) override; - void insert_stop_point_on_current_lanes(PathWithLaneId & path); + void insert_stop_point_on_current_lanes( + PathWithLaneId & path, const bool is_waiting_approval = false); PathWithLaneId getReferencePath() const override; @@ -137,6 +142,8 @@ class NormalLaneChange : public LaneChangeBase bool check_candidate_path_safety( const LaneChangePath & candidate_path, const lane_change::TargetObjects & target_objects) const; + std::optional compute_terminal_lane_change_path() const; + bool isValidPath(const PathWithLaneId & path) const override; PathSafetyStatus isLaneChangePathSafe( diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp index 5f36be806bba4..d5bbfe25fe1e9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp @@ -128,6 +128,22 @@ struct Info terminal_lane_changing_velocity = _lc_metrics.velocity; shift_line = _shift_line; } + + void set_prepare(const PhaseMetrics & _prep_metrics) + { + longitudinal_acceleration.prepare = _prep_metrics.actual_lon_accel; + velocity.prepare = _prep_metrics.velocity; + duration.prepare = _prep_metrics.duration; + length.prepare = _prep_metrics.length; + } + + void set_lane_changing(const PhaseMetrics & _lc_metrics) + { + longitudinal_acceleration.lane_changing = _lc_metrics.actual_lon_accel; + velocity.lane_changing = _lc_metrics.velocity; + duration.lane_changing = _lc_metrics.duration; + length.lane_changing = _lc_metrics.length; + } }; struct TargetLaneLeadingObjects @@ -219,6 +235,8 @@ struct TransientData double target_lane_length{std::numeric_limits::min()}; + double dist_to_target_end{std::numeric_limits::max()}; + lanelet::ArcCoordinates current_lanes_ego_arc; // arc coordinates of ego pose along current lanes lanelet::ArcCoordinates target_lanes_ego_arc; // arc coordinates of ego pose along target lanes diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp index 94020e8a08279..b25dbc99189e8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp @@ -137,12 +137,20 @@ struct DelayParameters double th_parked_vehicle_shift_ratio{0.6}; }; +struct TerminalPathParameters +{ + bool enable{false}; + bool disable_near_goal{false}; + bool stop_at_boundary{false}; +}; + struct Parameters { TrajectoryParameters trajectory{}; SafetyParameters safety{}; CancelParameters cancel{}; DelayParameters delay{}; + TerminalPathParameters terminal_path{}; // lane change parameters double backward_lane_length{200.0}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp index eced227a5be32..29a9f258545a2 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp @@ -67,6 +67,9 @@ double calc_dist_to_last_fit_width( const lanelet::ConstLanelets & lanelets, const Pose & src_pose, const BehaviorPathPlannerParameters & bpp_param, const double margin = 0.1); +double calc_dist_to_last_fit_width( + const CommonDataPtr & common_data_ptr, const PathWithLaneId & path, const double margin = 0.1); + /** * @brief Calculates the maximum preparation longitudinal distance for lane change. * diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp index dcc327b4793e1..77ba8fe68a653 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp @@ -48,7 +48,7 @@ using behavior_path_planner::lane_change::CommonDataPtr; */ bool get_prepare_segment( const CommonDataPtr & common_data_ptr, const PathWithLaneId & prev_module_path, - const LaneChangePhaseMetrics prep_metric, PathWithLaneId & prepare_segment); + const double prep_length, PathWithLaneId & prepare_segment); /** * @brief Generates the candidate path for a lane change maneuver. diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp index f80aad721a07c..9f3c6c9ef48bf 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp @@ -43,8 +43,7 @@ LaneChangeInterface::LaneChangeInterface( std::unique_ptr && module_type) : SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT parameters_{std::move(parameters)}, - module_type_{std::move(module_type)}, - prev_approved_path_{std::make_unique()} + module_type_{std::move(module_type)} { module_type_->setTimeKeeper(getTimeKeeper()); logger_ = utils::lane_change::getLogger(module_type_->getModuleTypeStr()); @@ -109,7 +108,6 @@ BehaviorModuleOutput LaneChangeInterface::plan() auto output = module_type_->generateOutput(); path_reference_ = std::make_shared(output.reference_path); - *prev_approved_path_ = getPreviousModuleOutput().path; stop_pose_ = module_type_->getStopPose(); @@ -155,11 +153,9 @@ BehaviorModuleOutput LaneChangeInterface::plan() BehaviorModuleOutput LaneChangeInterface::planWaitingApproval() { - BehaviorModuleOutput out = getPreviousModuleOutput(); + BehaviorModuleOutput out = module_type_->getTerminalLaneChangePath(); - *prev_approved_path_ = out.path; - - module_type_->insert_stop_point(module_type_->get_current_lanes(), out.path); + module_type_->insert_stop_point(module_type_->get_current_lanes(), out.path, true); out.turn_signal_info = module_type_->get_current_turn_signal_info(); const auto & lane_change_debug = module_type_->getDebugData(); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp index 9f7a811770b5d..ec000b8fee97c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp @@ -242,6 +242,13 @@ LCParamPtr LaneChangeModuleManager::set_params(rclcpp::Node * node, const std::s // debug marker p.publish_debug_marker = getOrDeclareParameter(*node, parameter("publish_debug_marker")); + // terminal lane change path + p.terminal_path.enable = getOrDeclareParameter(*node, parameter("terminal_path.enable")); + p.terminal_path.disable_near_goal = + getOrDeclareParameter(*node, parameter("terminal_path.disable_near_goal")); + p.terminal_path.stop_at_boundary = + getOrDeclareParameter(*node, parameter("terminal_path.stop_at_boundary")); + // validation of safety check parameters // if loose check is not enabled, lane change module will keep on chattering and canceling, and // false positive situation might occur diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index fb4f7aeca1525..2719239baaed8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -43,6 +43,7 @@ #include #include #include +#include #include #include #include @@ -169,6 +170,9 @@ void NormalLaneChange::update_transient_data(const bool is_approved) transient_data.dist_to_terminal_start = transient_data.dist_to_terminal_end - transient_data.current_dist_buffer.min; + transient_data.dist_to_target_end = calculation::calc_dist_from_pose_to_terminal_end( + common_data_ptr_, common_data_ptr_->lanes_ptr->target, common_data_ptr_->get_ego_pose()); + transient_data.max_prepare_length = calculation::calc_maximum_prepare_length(common_data_ptr_); transient_data.target_lane_length = @@ -246,6 +250,10 @@ std::pair NormalLaneChange::getSafePath(LaneChangePath & safe_path) bool found_safe_path = get_lane_change_paths(valid_paths); // if no safe path is found and ego is stuck, try to find a path with a small margin + if (valid_paths.empty() && terminal_lane_change_path_) { + valid_paths.push_back(terminal_lane_change_path_.value()); + } + lane_change_debug_.valid_paths = valid_paths; if (valid_paths.empty()) { @@ -380,6 +388,45 @@ LaneChangePath NormalLaneChange::getLaneChangePath() const return status_.lane_change_path; } +BehaviorModuleOutput NormalLaneChange::getTerminalLaneChangePath() const +{ + if ( + !lane_change_parameters_->terminal_path.enable || + !common_data_ptr_->transient_data.is_ego_near_current_terminal_start) { + return prev_module_output_; + } + + const auto is_near_goal = lane_change_parameters_->terminal_path.disable_near_goal && + common_data_ptr_->lanes_ptr->target_lane_in_goal_section && + common_data_ptr_->transient_data.dist_to_target_end < + common_data_ptr_->transient_data.lane_changing_length.max; + if (is_near_goal) { + return prev_module_output_; + } + + const auto & current_lanes = get_current_lanes(); + if (current_lanes.empty()) { + RCLCPP_DEBUG(logger_, "Current lanes not found. Returning previous module's path as output."); + return prev_module_output_; + } + + const auto terminal_lc_path = compute_terminal_lane_change_path(); + + if (!terminal_lc_path) { + RCLCPP_DEBUG(logger_, "Terminal path not found. Returning previous module's path as output."); + return prev_module_output_; + } + + auto output = prev_module_output_; + + output.path = *terminal_lc_path; + output.turn_signal_info = get_current_turn_signal_info(); + + extendOutputDrivableArea(output); + + return output; +} + BehaviorModuleOutput NormalLaneChange::generateOutput() { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); @@ -450,7 +497,7 @@ void NormalLaneChange::extendOutputDrivableArea(BehaviorModuleOutput & output) c } void NormalLaneChange::insert_stop_point( - const lanelet::ConstLanelets & lanelets, PathWithLaneId & path) + const lanelet::ConstLanelets & lanelets, PathWithLaneId & path, const bool is_waiting_approval) { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); if (lanelets.empty()) { @@ -475,44 +522,42 @@ void NormalLaneChange::insert_stop_point( return; } - insert_stop_point_on_current_lanes(path); + insert_stop_point_on_current_lanes(path, is_waiting_approval); } -void NormalLaneChange::insert_stop_point_on_current_lanes(PathWithLaneId & path) +void NormalLaneChange::insert_stop_point_on_current_lanes( + PathWithLaneId & path, const bool is_waiting_approval) { const auto & path_front_pose = path.points.front().point.pose; - const auto & center_line = common_data_ptr_->current_lanes_path.points; - const auto get_arc_length_along_lanelet = [&](const geometry_msgs::msg::Pose & target) { - return motion_utils::calcSignedArcLength( - center_line, path_front_pose.position, target.position); - }; + const auto & ego_pose = common_data_ptr_->get_ego_pose(); + const auto dist_from_path_front = + motion_utils::calcSignedArcLength(path.points, path_front_pose.position, ego_pose.position); const auto & transient_data = common_data_ptr_->transient_data; const auto & lanes_ptr = common_data_ptr_->lanes_ptr; const auto & lc_param_ptr = common_data_ptr_->lc_param_ptr; - const auto dist_to_terminal = std::invoke([&]() -> double { - const auto target_pose = (lanes_ptr->current_lane_in_goal_section) - ? common_data_ptr_->route_handler_ptr->getGoalPose() - : center_line.back().point.pose; - return get_arc_length_along_lanelet(target_pose); - }); - - const auto & bpp_param_ptr = common_data_ptr_->bpp_param_ptr; - const auto min_dist_buffer = transient_data.current_dist_buffer.min; const auto dist_to_terminal_start = - dist_to_terminal - min_dist_buffer - calculation::calc_stopping_distance(lc_param_ptr); + transient_data.dist_to_terminal_start - calculation::calc_stopping_distance(lc_param_ptr); - const auto distance_to_last_fit_width = std::invoke([&]() -> double { + const auto & bpp_param_ptr = common_data_ptr_->bpp_param_ptr; + const auto dist_to_terminal_stop = std::invoke([&]() -> double { const auto & curr_lanes_poly = common_data_ptr_->lanes_polygon_ptr->current; - if (utils::isEgoWithinOriginalLane(curr_lanes_poly, getEgoPose(), *bpp_param_ptr)) { - return utils::lane_change::calculation::calc_dist_to_last_fit_width( - lanes_ptr->current, path.points.front().point.pose, *bpp_param_ptr); + if (!utils::isEgoWithinOriginalLane(curr_lanes_poly, getEgoPose(), *bpp_param_ptr)) { + return dist_from_path_front + dist_to_terminal_start; } - return std::numeric_limits::max(); - }); - const auto dist_to_terminal_stop = std::min(dist_to_terminal_start, distance_to_last_fit_width); + if ( + terminal_lane_change_path_ && is_waiting_approval && + lc_param_ptr->terminal_path.stop_at_boundary) { + return calculation::calc_dist_to_last_fit_width(common_data_ptr_, path); + } + + const auto dist_to_last_fit_width = calculation::calc_dist_to_last_fit_width( + lanes_ptr->current, path.points.front().point.pose, *bpp_param_ptr); + + return std::min(dist_from_path_front + dist_to_terminal_start, dist_to_last_fit_width); + }); const auto terminal_stop_reason = status_.is_valid_path ? "no safe path" : "no valid path"; if ( @@ -522,11 +567,13 @@ void NormalLaneChange::insert_stop_point_on_current_lanes(PathWithLaneId & path) return; } + const auto & center_line = common_data_ptr_->current_lanes_path.points; const auto dist_to_target_lane_start = std::invoke([&]() -> double { const auto & front_lane = lanes_ptr->target_neighbor.front(); const auto target_front = utils::to_geom_msg_pose(front_lane.centerline2d().front(), front_lane); - return get_arc_length_along_lanelet(target_front); + return motion_utils::calcSignedArcLength( + center_line, path_front_pose.position, target_front.position); }); const auto arc_length_to_current_obj = utils::lane_change::get_min_dist_to_current_lanes_obj( @@ -1129,7 +1176,7 @@ bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths) PathWithLaneId prepare_segment; try { if (!utils::lane_change::get_prepare_segment( - common_data_ptr_, prev_module_output_.path, prep_metric, prepare_segment)) { + common_data_ptr_, prev_module_output_.path, prep_metric.length, prepare_segment)) { debug_print("Reject: failed to get valid prepare segment!"); continue; } @@ -1247,6 +1294,91 @@ bool NormalLaneChange::check_candidate_path_safety( return safety_check_with_normal_rss.is_safe; } +std::optional NormalLaneChange::compute_terminal_lane_change_path() const +{ + const auto & transient_data = common_data_ptr_->transient_data; + const auto dist_to_terminal_start = transient_data.dist_to_terminal_start; + const auto min_lc_velocity = lane_change_parameters_->trajectory.min_lane_changing_velocity; + const auto current_velocity = getEgoVelocity(); + + PathWithLaneId prepare_segment; + try { + if (!utils::lane_change::get_prepare_segment( + common_data_ptr_, prev_module_output_.path, dist_to_terminal_start, prepare_segment)) { + RCLCPP_DEBUG(logger_, "failed to get valid prepare segment for terminal LC path"); + return std::nullopt; + } + } catch (const std::exception & e) { + RCLCPP_DEBUG(logger_, "failed to get terminal LC path: %s", e.what()); + return std::nullopt; + } + + // t = 2 * d / (v1 + v2) + const auto duration_to_lc_start = + 2.0 * dist_to_terminal_start / (current_velocity + min_lc_velocity); + const auto lon_accel = std::invoke([&]() -> double { + if (duration_to_lc_start < calculation::eps) { + return 0.0; + } + return std::clamp( + (min_lc_velocity - current_velocity) / duration_to_lc_start, + lane_change_parameters_->trajectory.min_longitudinal_acc, + lane_change_parameters_->trajectory.max_longitudinal_acc); + }); + const auto vel_on_prep = current_velocity + lon_accel * duration_to_lc_start; + const LaneChangePhaseMetrics prep_metric( + duration_to_lc_start, dist_to_terminal_start, vel_on_prep, lon_accel, lon_accel, 0.0); + + if (terminal_lane_change_path_) { + terminal_lane_change_path_->info.set_prepare(prep_metric); + if (prepare_segment.points.empty()) { + terminal_lane_change_path_->path = terminal_lane_change_path_->shifted_path.path; + return terminal_lane_change_path_->path; + } + prepare_segment.points.pop_back(); + terminal_lane_change_path_->path = + utils::combinePath(prepare_segment, terminal_lane_change_path_->shifted_path.path); + return terminal_lane_change_path_->path; + } + + const auto & lane_changing_start_pose = prepare_segment.points.back().point.pose; + const auto & target_lanes = common_data_ptr_->lanes_ptr->target; + const auto shift_length = + lanelet::utils::getLateralDistanceToClosestLanelet(target_lanes, lane_changing_start_pose); + + const auto dist_lc_start_to_end_of_lanes = calculation::calc_dist_from_pose_to_terminal_end( + common_data_ptr_, common_data_ptr_->lanes_ptr->target_neighbor, + prepare_segment.points.back().point.pose); + + const auto max_lane_changing_length = std::invoke([&]() { + double max_length = transient_data.dist_to_terminal_end - prep_metric.length; + return std::min( + max_length, dist_lc_start_to_end_of_lanes - transient_data.next_dist_buffer.min); + }); + + const auto max_path_velocity = prepare_segment.points.back().point.longitudinal_velocity_mps; + constexpr double lane_changing_lon_accel{0.0}; + const auto lane_changing_metrics = calculation::calc_shift_phase_metrics( + common_data_ptr_, shift_length, prep_metric.velocity, max_path_velocity, + lane_changing_lon_accel, max_lane_changing_length); + + const auto sorted_lane_ids = utils::lane_change::get_sorted_lane_ids(common_data_ptr_); + + LaneChangePath candidate_path; + for (const auto & lc_metric : lane_changing_metrics) { + try { + candidate_path = utils::lane_change::get_candidate_path( + common_data_ptr_, prep_metric, lc_metric, prepare_segment, sorted_lane_ids, shift_length); + } catch (const std::exception & e) { + continue; + } + terminal_lane_change_path_ = candidate_path; + return candidate_path.path; + } + + return std::nullopt; +} + PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const { const auto & path = status_.lane_change_path; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp index 550c0fa290a99..a0130fcd27041 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp @@ -58,22 +58,10 @@ double calc_stopping_distance(const LCParamPtr & lc_param_ptr) } double calc_dist_to_last_fit_width( - const lanelet::ConstLanelets & lanelets, const Pose & src_pose, + const lanelet::ConstLanelets & lanelets, const lanelet::BasicPolygon2d & lanelet_polygon, + const universe_utils::LineString2d & line_string, const Pose & src_pose, const BehaviorPathPlannerParameters & bpp_param, const double margin) { - if (lanelets.empty()) return 0.0; - - const auto lane_polygon = lanelets.back().polygon2d().basicPolygon(); - const auto center_line = lanelet::utils::generateFineCenterline(lanelets.back(), 1.0); - - if (center_line.size() <= 1) return 0.0; - - universe_utils::LineString2d line_string; - line_string.reserve(center_line.size() - 1); - std::for_each(center_line.begin() + 1, center_line.end(), [&line_string](const auto & point) { - boost::geometry::append(line_string, universe_utils::Point2d(point.x(), point.y())); - }); - const double buffer_distance = 0.5 * bpp_param.vehicle_width + margin; universe_utils::MultiPolygon2d center_line_polygon; namespace strategy = boost::geometry::strategy::buffer; @@ -85,7 +73,7 @@ double calc_dist_to_last_fit_width( if (center_line_polygon.empty()) return 0.0; std::vector intersection_points; - boost::geometry::intersection(lane_polygon, center_line_polygon, intersection_points); + boost::geometry::intersection(lanelet_polygon, center_line_polygon, intersection_points); if (intersection_points.empty()) { return utils::getDistanceToEndOfLane(src_pose, lanelets); @@ -102,6 +90,46 @@ double calc_dist_to_last_fit_width( return std::max(distance - (bpp_param.base_link2front + margin), 0.0); } +double calc_dist_to_last_fit_width( + const CommonDataPtr & common_data_ptr, const PathWithLaneId & path, const double margin) +{ + const auto & current_lanes = common_data_ptr->lanes_ptr->current; + const auto & current_lanes_polygon = common_data_ptr->lanes_polygon_ptr->current; + const auto & bpp_param = *common_data_ptr->bpp_param_ptr; + + universe_utils::LineString2d line_string; + line_string.reserve(path.points.size() - 1); + std::for_each(path.points.begin() + 1, path.points.end(), [&line_string](const auto & point) { + const auto & position = point.point.pose.position; + boost::geometry::append(line_string, universe_utils::Point2d(position.x, position.y)); + }); + + const auto & src_pose = path.points.front().point.pose; + return calc_dist_to_last_fit_width( + current_lanes, current_lanes_polygon, line_string, src_pose, bpp_param, margin); +} + +double calc_dist_to_last_fit_width( + const lanelet::ConstLanelets & lanelets, const Pose & src_pose, + const BehaviorPathPlannerParameters & bpp_param, const double margin) +{ + if (lanelets.empty()) return 0.0; + + const auto lane_polygon = lanelets.back().polygon2d().basicPolygon(); + const auto center_line = lanelet::utils::generateFineCenterline(lanelets.back(), 1.0); + + if (center_line.size() <= 1) return 0.0; + + universe_utils::LineString2d line_string; + line_string.reserve(center_line.size() - 1); + std::for_each(center_line.begin() + 1, center_line.end(), [&line_string](const auto & point) { + boost::geometry::append(line_string, universe_utils::Point2d(point.x(), point.y())); + }); + + return calc_dist_to_last_fit_width( + lanelets, lane_polygon, line_string, src_pose, bpp_param, margin); +} + double calc_maximum_prepare_length(const CommonDataPtr & common_data_ptr) { const auto max_prepare_duration = common_data_ptr->lc_param_ptr->trajectory.max_prepare_duration; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/path.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/path.cpp index d7303d7d1df2d..44ee1624f0f51 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/path.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/path.cpp @@ -154,7 +154,7 @@ using behavior_path_planner::lane_change::CommonDataPtr; bool get_prepare_segment( const CommonDataPtr & common_data_ptr, const PathWithLaneId & prev_module_path, - const LaneChangePhaseMetrics prep_metric, PathWithLaneId & prepare_segment) + const double prep_length, PathWithLaneId & prepare_segment) { const auto & current_lanes = common_data_ptr->lanes_ptr->current; const auto & target_lanes = common_data_ptr->lanes_ptr->target; @@ -168,7 +168,7 @@ bool get_prepare_segment( const size_t current_seg_idx = autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( prepare_segment.points, common_data_ptr->get_ego_pose(), 3.0, 1.0); - utils::clipPathLength(prepare_segment, current_seg_idx, prep_metric.length, backward_path_length); + utils::clipPathLength(prepare_segment, current_seg_idx, prep_length, backward_path_length); if (prepare_segment.points.empty()) return false; From 203587335202d0c39260b40fae458300929d7a2b Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Fri, 27 Dec 2024 19:24:46 +0900 Subject: [PATCH 128/334] fix(autoware_scenario_selector): fix bugprone-branch-clone (#9699) fix: bugprone-error Signed-off-by: kobayu858 --- planning/autoware_scenario_selector/src/node.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/planning/autoware_scenario_selector/src/node.cpp b/planning/autoware_scenario_selector/src/node.cpp index 4bb64e27368d8..defbde4f6aabc 100644 --- a/planning/autoware_scenario_selector/src/node.cpp +++ b/planning/autoware_scenario_selector/src/node.cpp @@ -156,9 +156,8 @@ std::string ScenarioSelectorNode::selectScenarioByPosition() return tier4_planning_msgs::msg::Scenario::LANEDRIVING; } else if (is_in_parking_lot) { return tier4_planning_msgs::msg::Scenario::PARKING; - } else { - return tier4_planning_msgs::msg::Scenario::LANEDRIVING; } + return tier4_planning_msgs::msg::Scenario::LANEDRIVING; } if (current_scenario_ == tier4_planning_msgs::msg::Scenario::LANEDRIVING) { From 869cf4c435704f704e3d9ebc898d91ba697d2653 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Fri, 27 Dec 2024 19:25:33 +0900 Subject: [PATCH 129/334] fix(autoware_behavior_velocity_intersection_module): fix bugprone-branch-clone (#9702) fix: bugprone-error Signed-off-by: kobayu858 --- .../src/scene_intersection.cpp | 11 ++--------- 1 file changed, 2 insertions(+), 9 deletions(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp index e33416860c319..93a13a4d62737 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -354,9 +354,7 @@ DecisionResult IntersectionModule::modifyPathVelocityDetail(PathWithLaneId * pat (std::fabs(dist_stopline) < planner_param_.common.stopline_overshoot_margin); const bool over_stopline = (dist_stopline < 0.0); const bool is_stopped_duration = planner_data_->isVehicleStopped(duration); - if (over_stopline) { - state_machine.setState(StateMachine::State::GO); - } else if (is_stopped_duration && approached_dist_stopline) { + if (over_stopline || (is_stopped_duration && approached_dist_stopline)) { state_machine.setState(StateMachine::State::GO); } return state_machine.getState() == StateMachine::State::GO; @@ -367,12 +365,7 @@ DecisionResult IntersectionModule::modifyPathVelocityDetail(PathWithLaneId * pat (std::fabs(dist_stopline) < planner_param_.common.stopline_overshoot_margin); const bool over_stopline = (dist_stopline < -planner_param_.common.stopline_overshoot_margin); const bool is_stopped = planner_data_->isVehicleStopped(duration); - if (over_stopline) { - return true; - } else if (is_stopped && approached_dist_stopline) { - return true; - } - return false; + return over_stopline || (is_stopped && approached_dist_stopline); }; const auto occlusion_wo_tl_pass_judge_line_idx = From c8e00409c03555274c6ff26cc438e75144e1dcfd Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Sat, 28 Dec 2024 03:16:48 +0900 Subject: [PATCH 130/334] feat(pointpainting_fusion): enable cloud display on image (#9813) --- .../src/pointpainting_fusion/node.cpp | 90 ++++++++++--------- 1 file changed, 48 insertions(+), 42 deletions(-) diff --git a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp index 2837bac458541..25d9064ddbfc7 100644 --- a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp @@ -316,54 +316,56 @@ dc | dc dc dc dc ||zc| // iterate points // Requires 'OMP_NUM_THREADS=N' omp_set_num_threads(omp_num_threads_); -#pragma omp parallel for - for (int i = 0; i < iterations; i++) { - int stride = p_step * i; - unsigned char * data = &painted_pointcloud_msg.data[0]; - unsigned char * output = &painted_pointcloud_msg.data[0]; - // cppcheck-suppress-begin invalidPointerCast - float p_x = *reinterpret_cast(&data[stride + x_offset]); - float p_y = *reinterpret_cast(&data[stride + y_offset]); - float p_z = *reinterpret_cast(&data[stride + z_offset]); - // cppcheck-suppress-end invalidPointerCast - point_lidar << p_x, p_y, p_z; - point_camera = lidar2cam_affine * point_lidar; - p_x = point_camera.x(); - p_y = point_camera.y(); - p_z = point_camera.z(); - - if (camera_projectors_[image_id].isOutsideHorizontalView(p_x, p_z)) { - continue; - } + std::vector> local_vectors(omp_num_threads_); +#pragma omp parallel + { +#pragma omp for + for (int i = 0; i < iterations; i++) { + int stride = p_step * i; + unsigned char * data = &painted_pointcloud_msg.data[0]; + unsigned char * output = &painted_pointcloud_msg.data[0]; + // cppcheck-suppress-begin invalidPointerCast + float p_x = *reinterpret_cast(&data[stride + x_offset]); + float p_y = *reinterpret_cast(&data[stride + y_offset]); + float p_z = *reinterpret_cast(&data[stride + z_offset]); + // cppcheck-suppress-end invalidPointerCast + point_lidar << p_x, p_y, p_z; + point_camera = lidar2cam_affine * point_lidar; + p_x = point_camera.x(); + p_y = point_camera.y(); + p_z = point_camera.z(); + + if (camera_projectors_[image_id].isOutsideHorizontalView(p_x, p_z)) { + continue; + } - // project - Eigen::Vector2d projected_point; - if (camera_projectors_[image_id].calcImageProjectedPoint( - cv::Point3d(p_x, p_y, p_z), projected_point)) { - // iterate 2d bbox - for (const auto & feature_object : objects) { - sensor_msgs::msg::RegionOfInterest roi = feature_object.feature.roi; - // paint current point if it is inside bbox - int label2d = feature_object.object.classification.front().label; - if ( - !isUnknown(label2d) && isInsideBbox(projected_point.x(), projected_point.y(), roi, 1.0)) { - // cppcheck-suppress invalidPointerCast - auto p_class = reinterpret_cast(&output[stride + class_offset]); - for (const auto & cls : isClassTable_) { - // add up the class values if the point belongs to multiple classes - *p_class = cls.second(label2d) ? (class_index_[cls.first] + *p_class) : *p_class; + // project + Eigen::Vector2d projected_point; + if (camera_projectors_[image_id].calcImageProjectedPoint( + cv::Point3d(p_x, p_y, p_z), projected_point)) { + // iterate 2d bbox + for (const auto & feature_object : objects) { + sensor_msgs::msg::RegionOfInterest roi = feature_object.feature.roi; + // paint current point if it is inside bbox + int label2d = feature_object.object.classification.front().label; + if ( + !isUnknown(label2d) && + isInsideBbox(projected_point.x(), projected_point.y(), roi, 1.0)) { + // cppcheck-suppress invalidPointerCast + auto p_class = reinterpret_cast(&output[stride + class_offset]); + for (const auto & cls : isClassTable_) { + // add up the class values if the point belongs to multiple classes + *p_class = cls.second(label2d) ? (class_index_[cls.first] + *p_class) : *p_class; + } } } + if (debugger_) { + int thread_id = omp_get_thread_num(); + local_vectors[thread_id].push_back(projected_point); + } } -#if 0 - // Parallelizing loop don't support push_back - if (debugger_) { - debug_image_points.push_back(projected_point); - } -#endif } } - if (debugger_) { std::unique_ptr inner_st_ptr; if (time_keeper_) @@ -373,6 +375,10 @@ dc | dc dc dc dc ||zc| debug_image_rois.push_back(feature_object.feature.roi); } + for (const auto & local_vec : local_vectors) { + debug_image_points.insert(debug_image_points.end(), local_vec.begin(), local_vec.end()); + } + debugger_->image_rois_ = debug_image_rois; debugger_->obstacle_points_ = debug_image_points; debugger_->publishImage(image_id, input_roi_msg.header.stamp); From 58df2a112243562a49cf807fa8f64b7957a9ba44 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Tue, 31 Dec 2024 20:26:35 +0900 Subject: [PATCH 131/334] fix(goal_planner): fix usage of last_previous_module_output (#9811) --- .../examples/plot_map_case1.cpp | 10 ++-- .../examples/plot_map_case2.cpp | 10 ++-- .../fixed_goal_planner_base.hpp | 8 +-- .../goal_planner_module.hpp | 13 ++-- .../pull_over_planner/bezier_pull_over.hpp | 6 +- .../pull_over_planner/freespace_pull_over.hpp | 2 +- .../pull_over_planner/geometric_pull_over.hpp | 2 +- .../pull_over_planner_base.hpp | 2 +- .../pull_over_planner/shift_pull_over.hpp | 4 +- .../thread_data.hpp | 23 +++---- .../src/goal_planner_module.cpp | 60 ++++++++++--------- .../pull_over_planner/bezier_pull_over.cpp | 18 +++--- .../pull_over_planner/freespace_pull_over.cpp | 2 +- .../pull_over_planner/geometric_pull_over.cpp | 2 +- .../src/pull_over_planner/shift_pull_over.cpp | 10 ++-- .../src/thread_data.cpp | 5 +- 16 files changed, 87 insertions(+), 90 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case1.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case1.cpp index 56e207c160873..46d3b97b71e58 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case1.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case1.cpp @@ -288,7 +288,7 @@ bool hasEnoughDistance( std::vector selectPullOverPaths( const std::vector & pull_over_path_candidates, const GoalCandidates & goal_candidates, const std::shared_ptr planner_data, - const GoalPlannerParameters & parameters, const BehaviorModuleOutput & previous_module_output) + const GoalPlannerParameters & parameters, const BehaviorModuleOutput & upstream_module_output) { using autoware::behavior_path_planner::utils::getExtendedCurrentLanesFromPath; using autoware::motion_utils::calcSignedArcLength; @@ -313,15 +313,15 @@ std::vector selectPullOverPaths( } const double prev_path_front_to_goal_dist = calcSignedArcLength( - previous_module_output.path.points, - previous_module_output.path.points.front().point.pose.position, goal_pose.position); + upstream_module_output.path.points, + upstream_module_output.path.points.front().point.pose.position, goal_pose.position); const auto & long_tail_reference_path = [&]() { if (prev_path_front_to_goal_dist > backward_length) { - return previous_module_output.path; + return upstream_module_output.path; } // get road lanes which is at least backward_length[m] behind the goal const auto road_lanes = getExtendedCurrentLanesFromPath( - previous_module_output.path, planner_data, backward_length, 0.0, false); + upstream_module_output.path, planner_data, backward_length, 0.0, false); const auto goal_pose_length = lanelet::utils::getArcCoordinates(road_lanes, goal_pose).length; return planner_data->route_handler->getCenterLinePath( road_lanes, std::max(0.0, goal_pose_length - backward_length), diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case2.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case2.cpp index 102e5ef53b164..3518b5041be53 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case2.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case2.cpp @@ -287,7 +287,7 @@ bool hasEnoughDistance( std::vector selectPullOverPaths( const std::vector & pull_over_path_candidates, const GoalCandidates & goal_candidates, const std::shared_ptr planner_data, - const GoalPlannerParameters & parameters, const BehaviorModuleOutput & previous_module_output) + const GoalPlannerParameters & parameters, const BehaviorModuleOutput & upstream_module_output) { using autoware::behavior_path_planner::utils::getExtendedCurrentLanesFromPath; using autoware::motion_utils::calcSignedArcLength; @@ -312,15 +312,15 @@ std::vector selectPullOverPaths( } const double prev_path_front_to_goal_dist = calcSignedArcLength( - previous_module_output.path.points, - previous_module_output.path.points.front().point.pose.position, goal_pose.position); + upstream_module_output.path.points, + upstream_module_output.path.points.front().point.pose.position, goal_pose.position); const auto & long_tail_reference_path = [&]() { if (prev_path_front_to_goal_dist > backward_length) { - return previous_module_output.path; + return upstream_module_output.path; } // get road lanes which is at least backward_length[m] behind the goal const auto road_lanes = getExtendedCurrentLanesFromPath( - previous_module_output.path, planner_data, backward_length, 0.0, false); + upstream_module_output.path, planner_data, backward_length, 0.0, false); const auto goal_pose_length = lanelet::utils::getArcCoordinates(road_lanes, goal_pose).length; return planner_data->route_handler->getCenterLinePath( road_lanes, std::max(0.0, goal_pose_length - backward_length), diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/fixed_goal_planner_base.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/fixed_goal_planner_base.hpp index f670e3b05fa77..201b7c2d33bf6 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/fixed_goal_planner_base.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/fixed_goal_planner_base.hpp @@ -38,15 +38,15 @@ class FixedGoalPlannerBase virtual BehaviorModuleOutput plan( const std::shared_ptr & planner_data) const = 0; - void setPreviousModuleOutput(const BehaviorModuleOutput & previous_module_output) + void setPreviousModuleOutput(const BehaviorModuleOutput & upstream_module_output) { - previous_module_output_ = previous_module_output; + upstream_module_output_ = upstream_module_output; } - BehaviorModuleOutput getPreviousModuleOutput() const { return previous_module_output_; } + BehaviorModuleOutput getPreviousModuleOutput() const { return upstream_module_output_; } protected: - BehaviorModuleOutput previous_module_output_; + BehaviorModuleOutput upstream_module_output_; }; } // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp index 3a1773324fe24..0765147cbeb80 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -133,12 +133,12 @@ bool isOnModifiedGoal( const GoalPlannerParameters & parameters); bool hasPreviousModulePathShapeChanged( - const BehaviorModuleOutput & previous_module_output, - const BehaviorModuleOutput & last_previous_module_output); + const BehaviorModuleOutput & upstream_module_output, + const BehaviorModuleOutput & last_upstream_module_output); bool hasDeviatedFromLastPreviousModulePath( - const PlannerData & planner_data, const BehaviorModuleOutput & last_previous_module_output); + const PlannerData & planner_data, const BehaviorModuleOutput & last_upstream_module_output); bool hasDeviatedFromCurrentPreviousModulePath( - const PlannerData & planner_data, const BehaviorModuleOutput & previous_module_output); + const PlannerData & planner_data, const BehaviorModuleOutput & upstream_module_output); bool needPathUpdate( const Pose & current_pose, const double path_update_duration, const rclcpp::Time & now, @@ -189,6 +189,7 @@ class LaneParkingPlanner void onTimer(); private: + const GoalPlannerParameters parameters_; std::mutex & mutex_; const std::optional & request_; LaneParkingResponse & response_; @@ -196,6 +197,10 @@ class LaneParkingPlanner rclcpp::Logger logger_; std::vector> pull_over_planners_; + BehaviorModuleOutput + original_upstream_module_output_; // plan( const GoalCandidate & modified_goal_pose, const size_t id, const std::shared_ptr planner_data, - const BehaviorModuleOutput & previous_module_output) override; + const BehaviorModuleOutput & upstream_module_output) override; std::vector plans( const GoalCandidate & modified_goal_pose, const size_t id, const std::shared_ptr planner_data, - const BehaviorModuleOutput & previous_module_output); + const BehaviorModuleOutput & upstream_module_output); private: const LaneDepartureChecker lane_departure_checker_; @@ -50,7 +50,7 @@ class BezierPullOver : public PullOverPlannerBase std::vector generateBezierPath( const GoalCandidate & goal_candidate, const size_t id, const std::shared_ptr planner_data, - const BehaviorModuleOutput & previous_module_output, const lanelet::ConstLanelets & road_lanes, + const BehaviorModuleOutput & upstream_module_output, const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes, const double lateral_jerk) const; PathWithLaneId generateReferencePath( diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/freespace_pull_over.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/freespace_pull_over.hpp index e32488965f69a..37c82ea904a55 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/freespace_pull_over.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/freespace_pull_over.hpp @@ -41,7 +41,7 @@ class FreespacePullOver : public PullOverPlannerBase std::optional plan( const GoalCandidate & modified_goal_pose, const size_t id, const std::shared_ptr planner_data, - const BehaviorModuleOutput & previous_module_output) override; + const BehaviorModuleOutput & upstream_module_output) override; protected: const double velocity_; diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/geometric_pull_over.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/geometric_pull_over.hpp index 89181b258fbea..d15c1e796bbe7 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/geometric_pull_over.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/geometric_pull_over.hpp @@ -45,7 +45,7 @@ class GeometricPullOver : public PullOverPlannerBase std::optional plan( const GoalCandidate & modified_goal_pose, const size_t id, const std::shared_ptr planner_data, - const BehaviorModuleOutput & previous_module_output) override; + const BehaviorModuleOutput & upstream_module_output) override; std::vector generatePullOverPaths( const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes, diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/pull_over_planner_base.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/pull_over_planner_base.hpp index 5b336a7de6acc..5af69894c0a2e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/pull_over_planner_base.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/pull_over_planner_base.hpp @@ -130,7 +130,7 @@ class PullOverPlannerBase virtual std::optional plan( const GoalCandidate & modified_goal_pose, const size_t id, const std::shared_ptr planner_data, - const BehaviorModuleOutput & previous_module_output) = 0; + const BehaviorModuleOutput & upstream_module_output) = 0; protected: const autoware::vehicle_info_utils::VehicleInfo vehicle_info_; diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/shift_pull_over.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/shift_pull_over.hpp index 08e0b8508c991..2c6aec919bfbb 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/shift_pull_over.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/shift_pull_over.hpp @@ -38,7 +38,7 @@ class ShiftPullOver : public PullOverPlannerBase std::optional plan( const GoalCandidate & modified_goal_pose, const size_t id, const std::shared_ptr planner_data, - const BehaviorModuleOutput & previous_module_output) override; + const BehaviorModuleOutput & upstream_module_output) override; protected: PathWithLaneId generateReferencePath( @@ -49,7 +49,7 @@ class ShiftPullOver : public PullOverPlannerBase std::optional generatePullOverPath( const GoalCandidate & goal_candidate, const size_t id, const std::shared_ptr planner_data, - const BehaviorModuleOutput & previous_module_output, const lanelet::ConstLanelets & road_lanes, + const BehaviorModuleOutput & upstream_module_output, const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & pull_over_lanes, const double lateral_jerk) const; static double calcBeforeShiftedArcLength( const PathWithLaneId & path, const double after_shifted_arc_length, const double dr); diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/thread_data.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/thread_data.hpp index bfef4226b2661..7173b275e26fb 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/thread_data.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/thread_data.hpp @@ -32,35 +32,27 @@ class LaneParkingRequest { public: LaneParkingRequest( - const GoalPlannerParameters & parameters, const autoware::universe_utils::LinearRing2d & vehicle_footprint, - const GoalCandidates & goal_candidates, const BehaviorModuleOutput & previous_module_output) - : parameters_(parameters), - vehicle_footprint_(vehicle_footprint), + const GoalCandidates & goal_candidates, const BehaviorModuleOutput & upstream_module_output) + : vehicle_footprint_(vehicle_footprint), goal_candidates_(goal_candidates), - previous_module_output_(previous_module_output), - last_previous_module_output_(previous_module_output) + upstream_module_output_(upstream_module_output) { } void update( const PlannerData & planner_data, const ModuleStatus & current_status, - const BehaviorModuleOutput & previous_module_output, + const BehaviorModuleOutput & upstream_module_output, const std::optional & pull_over_path, const PathDecisionState & prev_data); - const GoalPlannerParameters parameters_; const autoware::universe_utils::LinearRing2d vehicle_footprint_; const GoalCandidates goal_candidates_; const std::shared_ptr & get_planner_data() const { return planner_data_; } const ModuleStatus & get_current_status() const { return current_status_; } - const BehaviorModuleOutput & get_previous_module_output() const - { - return previous_module_output_; - } - const BehaviorModuleOutput & get_last_previous_module_output() const + const BehaviorModuleOutput & get_upstream_module_output() const { - return last_previous_module_output_; + return upstream_module_output_; } const std::optional & get_pull_over_path() const { return pull_over_path_; } const PathDecisionState & get_prev_data() const { return prev_data_; } @@ -68,8 +60,7 @@ class LaneParkingRequest private: std::shared_ptr planner_data_; ModuleStatus current_status_; - BehaviorModuleOutput previous_module_output_; - BehaviorModuleOutput last_previous_module_output_; + BehaviorModuleOutput upstream_module_output_; std::optional pull_over_path_; // LATERAL_DEVIATION_THRESH) { return true; } @@ -185,19 +185,19 @@ bool hasPreviousModulePathShapeChanged( } bool hasDeviatedFromLastPreviousModulePath( - const PlannerData & planner_data, const BehaviorModuleOutput & last_previous_module_output) + const PlannerData & planner_data, const BehaviorModuleOutput & last_upstream_module_output) { return std::abs(autoware::motion_utils::calcLateralOffset( - last_previous_module_output.path.points, + last_upstream_module_output.path.points, planner_data.self_odometry->pose.pose.position)) > 0.3; } bool hasDeviatedFromCurrentPreviousModulePath( - const PlannerData & planner_data, const BehaviorModuleOutput & previous_module_output) + const PlannerData & planner_data, const BehaviorModuleOutput & upstream_module_output) { constexpr double LATERAL_DEVIATION_THRESH = 0.3; return std::abs(autoware::motion_utils::calcLateralOffset( - previous_module_output.path.points, planner_data.self_odometry->pose.pose.position)) > + upstream_module_output.path.points, planner_data.self_odometry->pose.pose.position)) > LATERAL_DEVIATION_THRESH; } @@ -282,7 +282,8 @@ LaneParkingPlanner::LaneParkingPlanner( const std::optional & request, LaneParkingResponse & response, std::atomic & is_lane_parking_cb_running, const rclcpp::Logger & logger, const GoalPlannerParameters & parameters) -: mutex_(lane_parking_mutex), +: parameters_(parameters), + mutex_(lane_parking_mutex), request_(request), response_(response), is_lane_parking_cb_running_(is_lane_parking_cb_running), @@ -335,12 +336,10 @@ void LaneParkingPlanner::onTimer() return; } const auto & local_request = local_request_opt.value(); - const auto & parameters = local_request.parameters_; const auto & goal_candidates = local_request.goal_candidates_; const auto & local_planner_data = local_request.get_planner_data(); const auto & current_status = local_request.get_current_status(); - const auto & previous_module_output = local_request.get_previous_module_output(); - const auto & last_previous_module_output = local_request.get_last_previous_module_output(); + const auto & upstream_module_output = local_request.get_upstream_module_output(); const auto & pull_over_path_opt = local_request.get_pull_over_path(); const auto & prev_data = local_request.get_prev_data(); @@ -371,19 +370,21 @@ void LaneParkingPlanner::onTimer() ? std::make_optional(pull_over_path_opt.value().modified_goal()) : std::nullopt; if (isOnModifiedGoal( - local_planner_data->self_odometry->pose.pose, modified_goal_opt, parameters)) { + local_planner_data->self_odometry->pose.pose, modified_goal_opt, parameters_)) { return false; } - if (hasDeviatedFromCurrentPreviousModulePath(*local_planner_data, previous_module_output)) { + if (hasDeviatedFromCurrentPreviousModulePath(*local_planner_data, upstream_module_output)) { RCLCPP_DEBUG(getLogger(), "has deviated from current previous module path"); return false; } - if (hasPreviousModulePathShapeChanged(previous_module_output, last_previous_module_output)) { + if (hasPreviousModulePathShapeChanged( + upstream_module_output, original_upstream_module_output_)) { RCLCPP_DEBUG(getLogger(), "has previous module path shape changed"); return true; } if ( - hasDeviatedFromLastPreviousModulePath(*local_planner_data, last_previous_module_output) && + hasDeviatedFromLastPreviousModulePath( + *local_planner_data, original_upstream_module_output_) && current_state != PathDecisionState::DecisionKind::DECIDED) { RCLCPP_DEBUG(getLogger(), "has deviated from last previous module path"); return true; @@ -400,8 +401,8 @@ void LaneParkingPlanner::onTimer() // generate valid pull over path candidates and calculate closest start pose const auto current_lanes = utils::getExtendedCurrentLanes( - local_planner_data, parameters.backward_goal_search_length, - parameters.forward_goal_search_length, + local_planner_data, parameters_.backward_goal_search_length, + parameters_.forward_goal_search_length, /*forward_only_in_route*/ false); std::vector path_candidates{}; std::optional closest_start_pose{}; @@ -410,7 +411,7 @@ void LaneParkingPlanner::onTimer() const std::shared_ptr & planner, const GoalCandidate & goal_candidate) { const auto pull_over_path = planner->plan( - goal_candidate, path_candidates.size(), local_planner_data, previous_module_output); + goal_candidate, path_candidates.size(), local_planner_data, upstream_module_output); if (pull_over_path) { // calculate absolute maximum curvature of parking path(start pose to end pose) for path // priority @@ -428,13 +429,13 @@ void LaneParkingPlanner::onTimer() // todo: currently non centerline input path is supported only by shift pull over const bool is_center_line_input_path = goal_planner_utils::isReferencePath( - previous_module_output.reference_path, previous_module_output.path, 0.1); + upstream_module_output.reference_path, upstream_module_output.path, 0.1); RCLCPP_DEBUG( getLogger(), "the input path of pull over planner is center line: %d", is_center_line_input_path); // plan candidate paths and set them to the member variable - if (parameters.path_priority == "efficient_path") { + if (parameters_.path_priority == "efficient_path") { for (const auto & planner : pull_over_planners_) { // todo: temporary skip NON SHIFT planner when input path is not center line if (!is_center_line_input_path && planner->getPlannerType() != PullOverPlannerType::SHIFT) { @@ -444,7 +445,7 @@ void LaneParkingPlanner::onTimer() planCandidatePaths(planner, goal_candidate); } } - } else if (parameters.path_priority == "close_goal") { + } else if (parameters_.path_priority == "close_goal") { for (const auto & goal_candidate : goal_candidates) { for (const auto & planner : pull_over_planners_) { // todo: temporary skip NON SHIFT planner when input path is not center line @@ -457,14 +458,15 @@ void LaneParkingPlanner::onTimer() } else { RCLCPP_ERROR( getLogger(), "path_priority should be efficient_path or close_goal, but %s is given.", - parameters.path_priority.c_str()); + parameters_.path_priority.c_str()); throw std::domain_error("[pull_over] invalid path_priority"); } // set response { + original_upstream_module_output_ = upstream_module_output; std::lock_guard guard(mutex_); - response_.pull_over_path_candidates = path_candidates; + response_.pull_over_path_candidates = std::move(path_candidates); response_.closest_start_pose = closest_start_pose; RCLCPP_INFO( getLogger(), "generated %lu pull over path candidates", @@ -562,7 +564,7 @@ std::pair GoalPlannerModule::sync // In PlannerManager::run(), it calls SceneModuleInterface::setData and // SceneModuleInterface::setPreviousModuleOutput before module_ptr->run(). // Then module_ptr->run() invokes GoalPlannerModule::updateData and then - // planWaitingApproval()/plan(), so we can copy latest current_status/previous_module_output to + // planWaitingApproval()/plan(), so we can copy latest current_status/upstream_module_output to // lane_parking_request/freespace_parking_request std::optional pull_over_path = @@ -578,7 +580,7 @@ std::pair GoalPlannerModule::sync std::lock_guard guard(lane_parking_mutex_); if (!lane_parking_request_) { lane_parking_request_.emplace( - *parameters_, vehicle_footprint_, goal_candidates_, getPreviousModuleOutput()); + vehicle_footprint_, goal_candidates_, getPreviousModuleOutput()); } // NOTE: for the above reasons, PlannerManager/behavior_path_planner_node ensure that // planner_data_ is not nullptr, so it is OK to copy as value diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/bezier_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/bezier_pull_over.cpp index 0da5ab5dae38b..ad42ccf1582ab 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/bezier_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/bezier_pull_over.cpp @@ -43,7 +43,7 @@ BezierPullOver::BezierPullOver( std::optional BezierPullOver::plan( [[maybe_unused]] const GoalCandidate & modified_goal_pose, [[maybe_unused]] const size_t id, [[maybe_unused]] const std::shared_ptr planner_data, - [[maybe_unused]] const BehaviorModuleOutput & previous_module_output) + [[maybe_unused]] const BehaviorModuleOutput & upstream_module_output) { const auto & route_handler = planner_data->route_handler; const double min_jerk = parameters_.minimum_lateral_jerk; @@ -55,7 +55,7 @@ std::optional BezierPullOver::plan( std::abs(max_jerk - min_jerk) / shift_sampling_num; const auto road_lanes = utils::getExtendedCurrentLanesFromPath( - previous_module_output.path, planner_data, backward_search_length, forward_search_length, + upstream_module_output.path, planner_data, backward_search_length, forward_search_length, /*forward_only_in_route*/ false); const auto pull_over_lanes = goal_planner_utils::getPullOverLanes( @@ -67,7 +67,7 @@ std::optional BezierPullOver::plan( // find safe one from paths with different jerk for (double lateral_jerk = min_jerk; lateral_jerk <= max_jerk; lateral_jerk += jerk_resolution) { const auto pull_over_path = generateBezierPath( - modified_goal_pose, id, planner_data, previous_module_output, road_lanes, pull_over_lanes, + modified_goal_pose, id, planner_data, upstream_module_output, road_lanes, pull_over_lanes, lateral_jerk); if (!pull_over_path.empty()) { return pull_over_path.at(0); @@ -80,7 +80,7 @@ std::optional BezierPullOver::plan( std::vector BezierPullOver::plans( [[maybe_unused]] const GoalCandidate & modified_goal_pose, [[maybe_unused]] const size_t id, [[maybe_unused]] const std::shared_ptr planner_data, - [[maybe_unused]] const BehaviorModuleOutput & previous_module_output) + [[maybe_unused]] const BehaviorModuleOutput & upstream_module_output) { const auto & route_handler = planner_data->route_handler; const double min_jerk = parameters_.minimum_lateral_jerk; @@ -92,7 +92,7 @@ std::vector BezierPullOver::plans( std::abs(max_jerk - min_jerk) / shift_sampling_num; const auto road_lanes = utils::getExtendedCurrentLanesFromPath( - previous_module_output.path, planner_data, backward_search_length, forward_search_length, + upstream_module_output.path, planner_data, backward_search_length, forward_search_length, /*forward_only_in_route*/ false); const auto pull_over_lanes = goal_planner_utils::getPullOverLanes( @@ -105,7 +105,7 @@ std::vector BezierPullOver::plans( std::vector paths; for (double lateral_jerk = min_jerk; lateral_jerk <= max_jerk; lateral_jerk += jerk_resolution) { auto pull_over_paths = generateBezierPath( - modified_goal_pose, id, planner_data, previous_module_output, road_lanes, pull_over_lanes, + modified_goal_pose, id, planner_data, upstream_module_output, road_lanes, pull_over_lanes, lateral_jerk); std::copy( std::make_move_iterator(pull_over_paths.begin()), @@ -118,7 +118,7 @@ std::vector BezierPullOver::plans( std::vector BezierPullOver::generateBezierPath( const GoalCandidate & goal_candidate, const size_t id, const std::shared_ptr planner_data, - const BehaviorModuleOutput & previous_module_output, const lanelet::ConstLanelets & road_lanes, + const BehaviorModuleOutput & upstream_module_output, const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & pull_over_lanes, const double lateral_jerk) const { const double pull_over_velocity = parameters_.pull_over_velocity; @@ -133,7 +133,7 @@ std::vector BezierPullOver::generateBezierPath( generateReferencePath(planner_data, road_lanes, shift_end_pose), parameters_.center_line_path_interval); const auto prev_module_path = utils::resamplePathWithSpline( - previous_module_output.path, parameters_.center_line_path_interval); + upstream_module_output.path, parameters_.center_line_path_interval); const auto prev_module_path_terminal_pose = prev_module_path.points.back().point.pose; // process previous module path for path shifter input path @@ -318,7 +318,7 @@ std::vector BezierPullOver::generateBezierPath( drivable_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset, dp.drivable_area_types_to_skip); const auto combined_drivable = utils::combineDrivableLanes( - expanded_lanes, previous_module_output.drivable_area_info.drivable_lanes); + expanded_lanes, upstream_module_output.drivable_area_info.drivable_lanes); return !lane_departure_checker_.checkPathWillLeaveLane( utils::transformToLanelets(combined_drivable), pull_over_path.parking_path()); }); diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/freespace_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/freespace_pull_over.cpp index 5b11d1b170ce1..473f76b5904d6 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/freespace_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/freespace_pull_over.cpp @@ -60,7 +60,7 @@ FreespacePullOver::FreespacePullOver( std::optional FreespacePullOver::plan( const GoalCandidate & modified_goal_pose, const size_t id, const std::shared_ptr planner_data, - [[maybe_unused]] const BehaviorModuleOutput & previous_module_output) + [[maybe_unused]] const BehaviorModuleOutput & upstream_module_output) { const Pose & current_pose = planner_data->self_odometry->pose.pose; diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp index c0bac5c5ce2a8..74b3fe149fd1d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp @@ -40,7 +40,7 @@ GeometricPullOver::GeometricPullOver( std::optional GeometricPullOver::plan( const GoalCandidate & modified_goal_pose, const size_t id, const std::shared_ptr planner_data, - [[maybe_unused]] const BehaviorModuleOutput & previous_module_output) + [[maybe_unused]] const BehaviorModuleOutput & upstream_module_output) { const auto & route_handler = planner_data->route_handler; diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp index edecfd733d3be..9a3e2d6b13db9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp @@ -41,7 +41,7 @@ ShiftPullOver::ShiftPullOver( std::optional ShiftPullOver::plan( const GoalCandidate & modified_goal_pose, const size_t id, const std::shared_ptr planner_data, - const BehaviorModuleOutput & previous_module_output) + const BehaviorModuleOutput & upstream_module_output) { const auto & route_handler = planner_data->route_handler; const double min_jerk = parameters_.minimum_lateral_jerk; @@ -52,7 +52,7 @@ std::optional ShiftPullOver::plan( const double jerk_resolution = std::abs(max_jerk - min_jerk) / shift_sampling_num; const auto road_lanes = utils::getExtendedCurrentLanesFromPath( - previous_module_output.path, planner_data, backward_search_length, forward_search_length, + upstream_module_output.path, planner_data, backward_search_length, forward_search_length, /*forward_only_in_route*/ false); const auto pull_over_lanes = goal_planner_utils::getPullOverLanes( @@ -64,7 +64,7 @@ std::optional ShiftPullOver::plan( // find safe one from paths with different jerk for (double lateral_jerk = min_jerk; lateral_jerk <= max_jerk; lateral_jerk += jerk_resolution) { const auto pull_over_path = generatePullOverPath( - modified_goal_pose, id, planner_data, previous_module_output, road_lanes, pull_over_lanes, + modified_goal_pose, id, planner_data, upstream_module_output, road_lanes, pull_over_lanes, lateral_jerk); if (!pull_over_path) continue; return pull_over_path; @@ -134,7 +134,7 @@ std::optional ShiftPullOver::cropPrevModulePath( std::optional ShiftPullOver::generatePullOverPath( const GoalCandidate & goal_candidate, const size_t id, const std::shared_ptr planner_data, - const BehaviorModuleOutput & previous_module_output, const lanelet::ConstLanelets & road_lanes, + const BehaviorModuleOutput & upstream_module_output, const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & pull_over_lanes, const double lateral_jerk) const { const double pull_over_velocity = parameters_.pull_over_velocity; @@ -151,7 +151,7 @@ std::optional ShiftPullOver::generatePullOverPath( generateReferencePath(planner_data, road_lanes, shift_end_pose), parameters_.center_line_path_interval); const auto prev_module_path = utils::resamplePathWithSpline( - previous_module_output.path, parameters_.center_line_path_interval); + upstream_module_output.path, parameters_.center_line_path_interval); const auto prev_module_path_terminal_pose = prev_module_path.points.back().point.pose; // process previous module path for path shifter input path diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/thread_data.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/thread_data.cpp index f12d510e23030..89458c199c130 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/thread_data.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/thread_data.cpp @@ -21,14 +21,13 @@ namespace autoware::behavior_path_planner void LaneParkingRequest::update( const PlannerData & planner_data, const ModuleStatus & current_status, - const BehaviorModuleOutput & previous_module_output, + const BehaviorModuleOutput & upstream_module_output, const std::optional & pull_over_path, const PathDecisionState & prev_data) { planner_data_ = std::make_shared(planner_data); planner_data_->route_handler = std::make_shared(*(planner_data.route_handler)); current_status_ = current_status; - last_previous_module_output_ = previous_module_output_; - previous_module_output_ = previous_module_output; + upstream_module_output_ = upstream_module_output; pull_over_path_ = pull_over_path; prev_data_ = prev_data; } From 33b9913a65cc8cfdb99a3e0d776421f430f66318 Mon Sep 17 00:00:00 2001 From: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Date: Tue, 31 Dec 2024 23:09:05 +0900 Subject: [PATCH 132/334] ci: pass run condition to reusable workflow (#9771) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Ryohsuke Mitsudome Co-authored-by: M. Fatih Cırıt --- .../actions/evaluate-job-result/action.yaml | 45 ------------ .../build-and-test-differential.yaml | 5 ++ .github/workflows/build-test-tidy-pr.yaml | 72 +++---------------- .../workflows/clang-tidy-differential.yaml | 5 ++ 4 files changed, 19 insertions(+), 108 deletions(-) delete mode 100644 .github/actions/evaluate-job-result/action.yaml diff --git a/.github/actions/evaluate-job-result/action.yaml b/.github/actions/evaluate-job-result/action.yaml deleted file mode 100644 index c5c013080fd27..0000000000000 --- a/.github/actions/evaluate-job-result/action.yaml +++ /dev/null @@ -1,45 +0,0 @@ -name: Evaluate Job Result -description: Evaluates the result of a job and updates the summary. -inputs: - job_result: - description: Result of the job to evaluate (e.g., success, failure, skipped) - required: true - type: string - job_name: - description: Name of the job to evaluate - required: true - type: string - expected_results: - description: Comma-separated list of acceptable results (e.g., success,skipped) - required: true - type: string -outputs: - failed: - description: Indicates if the job failed - value: ${{ steps.evaluate.outputs.failed }} - -runs: - using: composite - steps: - - name: Evaluate Job Result - id: evaluate - run: | - JOB_RESULT="${{ inputs.job_result }}" - IFS=',' read -ra EXPECTED <<< "${{ inputs.expected_results }}" - FAILED=false - - for RESULT in "${EXPECTED[@]}"; do - if [[ "$JOB_RESULT" == "$RESULT" ]]; then - echo "- **${{ inputs.job_name }}:** "$JOB_RESULT" ✅" >> "$GITHUB_STEP_SUMMARY" - echo "failed=false" >> "$GITHUB_OUTPUT" - exit 0 - fi - done - - # If no expected result matched - echo "::error::${{ inputs.job_name }} failed. ❌" - echo "- **${{ inputs.job_name }}:** failed ❌" >> "$GITHUB_STEP_SUMMARY" - echo "failed=true" >> "$GITHUB_OUTPUT" - - exit 1 - shell: bash diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index 0925cb0f53930..c25f6b24c5e47 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -14,6 +14,10 @@ on: default: humble required: false type: string + run-condition: + default: true + required: false + type: boolean container-suffix: required: false default: "" @@ -28,6 +32,7 @@ env: jobs: build-and-test-differential: + if: ${{ inputs.run-condition }} runs-on: ${{ inputs.runner }} container: ${{ inputs.container }}${{ inputs.container-suffix }} steps: diff --git a/.github/workflows/build-test-tidy-pr.yaml b/.github/workflows/build-test-tidy-pr.yaml index d1ea9b2d0f79d..c0442694b5c77 100644 --- a/.github/workflows/build-test-tidy-pr.yaml +++ b/.github/workflows/build-test-tidy-pr.yaml @@ -40,98 +40,44 @@ jobs: shell: bash build-and-test-differential: + if: ${{ always() }} needs: - require-label uses: ./.github/workflows/build-and-test-differential.yaml with: container: ghcr.io/autowarefoundation/autoware:universe-devel + run-condition: ${{ needs.require-label.outputs.result == 'true' }} secrets: codecov-token: ${{ secrets.CODECOV_TOKEN }} build-and-test-differential-cuda: + if: ${{ always() }} needs: check-if-cuda-job-is-needed - if: ${{ needs.check-if-cuda-job-is-needed.outputs.cuda_job_is_needed == 'true' }} uses: ./.github/workflows/build-and-test-differential.yaml with: container: ghcr.io/autowarefoundation/autoware:universe-devel container-suffix: -cuda + run-condition: ${{ needs.check-if-cuda-job-is-needed.outputs.cuda_job_is_needed == 'true' }} secrets: codecov-token: ${{ secrets.CODECOV_TOKEN }} - build-test-pr: - needs: - - build-and-test-differential - - build-and-test-differential-cuda - if: ${{ always() }} - runs-on: ubuntu-latest - steps: - - uses: actions/checkout@v4 - - - name: Initialize Summary - run: echo "### Build Test PR Results" > $GITHUB_STEP_SUMMARY - shell: bash - - - name: Evaluate build-and-test-differential - uses: ./.github/actions/evaluate-job-result - with: - job_result: ${{ needs.build-and-test-differential.result }} - job_name: build-and-test-differential - expected_results: success - - - name: Evaluate build-and-test-differential-cuda - if: ${{ always() }} - uses: ./.github/actions/evaluate-job-result - with: - job_result: ${{ needs.build-and-test-differential-cuda.result }} - job_name: build-and-test-differential-cuda - expected_results: success,skipped - clang-tidy-differential: + if: ${{ always() }} # always run to provide report for status check needs: - check-if-cuda-job-is-needed - build-and-test-differential - if: ${{ needs.check-if-cuda-job-is-needed.outputs.cuda_job_is_needed == 'false' }} uses: ./.github/workflows/clang-tidy-differential.yaml with: container: ghcr.io/autowarefoundation/autoware:universe-devel + run-condition: ${{ needs.check-if-cuda-job-is-needed.outputs.cuda_job_is_needed == 'false' && needs.build-and-test-differential.result == 'success' }} clang-tidy-differential-cuda: + if: ${{ always() }} # always run to provide report for status check needs: + - check-if-cuda-job-is-needed - build-and-test-differential-cuda uses: ./.github/workflows/clang-tidy-differential.yaml with: container: ghcr.io/autowarefoundation/autoware:universe-devel container-suffix: -cuda - - clang-tidy-pr: - needs: - - clang-tidy-differential - - clang-tidy-differential-cuda - if: ${{ always() }} - runs-on: ubuntu-latest - steps: - - name: Initialize Summary - run: echo "### Clang Tidy PR Results" > $GITHUB_STEP_SUMMARY - shell: bash - - - name: Check clang-tidy success - if: ${{ needs.clang-tidy-differential.result == 'success' || needs.clang-tidy-differential-cuda.result == 'success' }} - run: | - echo "✅ Either one of the following has succeeded:" >> $GITHUB_STEP_SUMMARY - - - name: Fail if conditions not met - if: ${{ !(needs.clang-tidy-differential.result == 'success' || needs.clang-tidy-differential-cuda.result == 'success') }} - run: | - echo "::error::❌ Either one of the following should have succeeded:" - echo "::error::clang-tidy-differential: ${{ needs.clang-tidy-differential.result }}" - echo "::error::clang-tidy-differential-cuda: ${{ needs.clang-tidy-differential-cuda.result }}" - - echo "❌ Either one of the following should have succeeded:" >> $GITHUB_STEP_SUMMARY - - exit 1 - - - name: Print the results - if: ${{ always() }} - run: | - echo "- **clang-tidy-differential:** ${{ needs.clang-tidy-differential.result }}" >> $GITHUB_STEP_SUMMARY - echo "- **clang-tidy-differential-cuda:** ${{ needs.clang-tidy-differential-cuda.result }}" >> $GITHUB_STEP_SUMMARY + run-condition: ${{ needs.check-if-cuda-job-is-needed.outputs.cuda_job_is_needed == 'true' && needs.build-and-test-differential-cuda.result == 'success' }} diff --git a/.github/workflows/clang-tidy-differential.yaml b/.github/workflows/clang-tidy-differential.yaml index 51e0a8408468c..41d722c8e07b0 100644 --- a/.github/workflows/clang-tidy-differential.yaml +++ b/.github/workflows/clang-tidy-differential.yaml @@ -14,9 +14,14 @@ on: default: ubuntu-24.04 required: false type: string + run-condition: + default: true + required: false + type: boolean jobs: clang-tidy-differential: + if: ${{ inputs.run-condition }} runs-on: ${{ inputs.runner }} container: ${{ inputs.container }}${{ inputs.container-suffix }} steps: From 77c1a3f02a4cc5afece9ac701193f24de7af3755 Mon Sep 17 00:00:00 2001 From: Atto Armoo <168620037+AA-T4@users.noreply.github.com> Date: Tue, 31 Dec 2024 23:26:19 +0900 Subject: [PATCH 133/334] fix(planning): corrects minor typos (#9809) Signed-off-by: Atto Armoo <168620037+AA-T4@users.noreply.github.com> --- planning/README.md | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/planning/README.md b/planning/README.md index ccf8288df3911..3fadafe54ed4c 100644 --- a/planning/README.md +++ b/planning/README.md @@ -18,7 +18,7 @@ Enabling and disabling modules involves managing settings in key configuration a ### Key Files for Configuration -The `default_preset.yaml` file acts as the primary configuration file, where planning modules can be disable or enabled. Furthermore, users can also set the type of motion planner across various motion planners. For example: +The `default_preset.yaml` file acts as the primary configuration file, where planning modules can be disabled or enabled. Furthermore, users can also set the type of motion planner across various motion planners. For example: - `launch_avoidance_module`: Set to `true` to enable the avoidance module, or `false` to disable it. - `motion_stop_planner_type`: Set `default` to either `obstacle_stop_planner` or `obstacle_cruise_planner`. @@ -35,7 +35,7 @@ The [launch files](https://github.com/autowarefoundation/autoware.universe/tree/ corresponds to launch_avoidance_module from `default_preset.yaml`. -### Parameters configuration +### Parameter Configuration There are multiple parameters available for configuration, and users have the option to modify them in [here](https://github.com/autowarefoundation/autoware_launch/tree/main/autoware_launch/config/planning). It's important to note that not all parameters are adjustable via `rqt_reconfigure`. To ensure the changes are effective, modify the parameters and then restart Autoware. Additionally, detailed information about each parameter is available in the corresponding documents under the planning tab. @@ -43,7 +43,7 @@ There are multiple parameters available for configuration, and users have the op This guide outlines the steps for integrating your custom module into Autoware: -- Add your modules to the `default_preset.yaml` file. For example +- Add your modules to the `default_preset.yaml` file. For example: ```yaml - arg: @@ -51,7 +51,7 @@ This guide outlines the steps for integrating your custom module into Autoware: default: "true" ``` -- Incorporate your modules into the [launcher](https://github.com/autowarefoundation/autoware.universe/tree/main/launch/tier4_planning_launch/launch/scenario_planning). For example in [behavior_planning.launch.xml](https://github.com/autowarefoundation/autoware.universe/blob/main/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml): +- Incorporate your modules into the [launcher](https://github.com/autowarefoundation/autoware.universe/tree/main/launch/tier4_planning_launch/launch/scenario_planning). For example, in [behavior_planning.launch.xml](https://github.com/autowarefoundation/autoware.universe/blob/main/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml): ```xml @@ -63,14 +63,14 @@ This guide outlines the steps for integrating your custom module into Autoware: /> ``` -- If applicable, place your parameter folder within the appropriate existing parameter folder. For example [intersection_module's parameters](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml) is in [behavior_velocity_planner](https://github.com/autowarefoundation/autoware_launch/tree/main/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner). -- Insert the path of your parameters in the [tier4_planning_component.launch.xml](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/launch/components/tier4_planning_component.launch.xml). For example `behavior_velocity_planner_intersection_module_param_path` is used. +- If applicable, place your parameter folder within the appropriate existing parameter folder. For example, [intersection_module's parameters](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml) are in [behavior_velocity_planner](https://github.com/autowarefoundation/autoware_launch/tree/main/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner). +- Insert the path of your parameters in the [tier4_planning_component.launch.xml](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/launch/components/tier4_planning_component.launch.xml). For example, `behavior_velocity_planner_intersection_module_param_path` is used. ```xml ``` -- Define your parameter path variable within the corresponding launcher. For example in [behavior_planning.launch.xml](https://github.com/autowarefoundation/autoware.universe/blob/04aa54bf5fb0c88e70198ca74b9ac343cc3457bf/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml#L191) +- Define your parameter path variable within the corresponding launcher. For example, in [behavior_planning.launch.xml](https://github.com/autowarefoundation/autoware.universe/blob/04aa54bf5fb0c88e70198ca74b9ac343cc3457bf/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml#L191) ```xml @@ -82,7 +82,7 @@ This guide outlines the steps for integrating your custom module into Autoware: ## Join Our Community-Driven Effort -Autoware thrives on community collaboration. Every contribution, big or small, is invaluable to us. Whether it's reporting bugs, suggesting improvements, offering new ideas, or anything else you can think of – we welcome it all with open arms. +Autoware thrives on community collaboration. Every contribution, big or small, is invaluable to us. Whether it's reporting bugs, suggesting improvements, offering new ideas, or anything else you can think of – we welcome all contributions with open arms. ### How to Contribute? @@ -105,7 +105,7 @@ Interested in joining our meetings? We’d love to have you! For more informatio Occasionally, we publish papers specific to the Planning Component in Autoware. We encourage you to explore these publications and find valuable insights for your work. If you find them useful and incorporate any of our methodologies or algorithms in your projects, citing our papers would be immensely helpful. This support allows us to reach a broader audience and continue contributing to the field. -If you use the Jerk Constrained Velocity Planning algorithm in [Motion Velocity Smoother](./autoware_velocity_smoother/README.md) module in the Planning Component, we kindly request you to cite the relevant paper. +If you use the Jerk Constrained Velocity Planning algorithm in the [Motion Velocity Smoother](./autoware_velocity_smoother/README.md) module in the Planning Component, we kindly request you cite the relevant paper. From a32cae1d4547290d9e4c3bb9b86480bfc373459d Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Thu, 2 Jan 2025 11:12:43 +0000 Subject: [PATCH 134/334] chore: sync files (#9825) Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> Co-authored-by: github-actions --- .pre-commit-config-optional.yaml | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/.pre-commit-config-optional.yaml b/.pre-commit-config-optional.yaml index ff325af5e8774..f0b5bdba2d24d 100644 --- a/.pre-commit-config-optional.yaml +++ b/.pre-commit-config-optional.yaml @@ -2,6 +2,13 @@ # https://github.com/autowarefoundation/sync-file-templates # To make changes, update the source repository and follow the guidelines in its README. +# https://pre-commit.ci/#configuration +ci: + autofix_commit_msg: "style(pre-commit-optional): autofix" + # we already have our own daily update mechanism, we set this to quarterly + autoupdate_schedule: quarterly + autoupdate_commit_msg: "ci(pre-commit-optional): quarterly autoupdate" + repos: - repo: https://github.com/tcort/markdown-link-check rev: v3.12.2 From 176e2e31a4f1b89a6ad4b6e4af5a04c3cc4ba4c3 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 6 Jan 2025 11:25:20 +0900 Subject: [PATCH 135/334] feat(behavior_velocity_modules): add node test (#9790) * feat(behavior_velocity_crosswalk): add node test Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * feat(behavior_velocity_xxx_module): add node test Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * change directory tests -> test Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../CMakeLists.txt | 10 +++ .../package.xml | 2 + .../test/test_node_interface.cpp | 64 ++++++++++++++++++ .../CMakeLists.txt | 1 + .../package.xml | 1 + .../test/test_node_interface.cpp | 64 ++++++++++++++++++ .../CMakeLists.txt | 1 + .../package.xml | 1 + .../test/test_node_interface.cpp | 64 ++++++++++++++++++ .../package.xml | 1 + .../test/test_node_interface.cpp | 64 ++++++++++++++++++ .../CMakeLists.txt | 1 + .../package.xml | 1 + .../test/test_node_interface.cpp | 64 ++++++++++++++++++ .../CMakeLists.txt | 17 ----- .../behavior_velocity_planner/node.hpp | 16 ++--- .../package.xml | 7 +- .../src/node.cpp | 16 ++--- .../srv/LoadPlugin.srv | 3 - .../srv/UnloadPlugin.srv | 3 - .../CMakeLists.txt | 9 +-- .../package.xml | 1 + .../{tests => test}/test_dynamic_obstacle.cpp | 0 .../test/test_node_interface.cpp | 64 ++++++++++++++++++ .../{tests => test}/test_path_utils.cpp | 0 .../{tests => test}/test_state_machine.cpp | 0 .../{tests => test}/test_utils.cpp | 0 .../CMakeLists.txt | 1 + .../package.xml | 1 + .../test/test_node_interface.cpp | 64 ++++++++++++++++++ .../CMakeLists.txt | 1 + .../package.xml | 1 + .../test/test_node_interface.cpp | 64 ++++++++++++++++++ .../package.xml | 1 + .../test/test_node_interface.cpp | 65 +++++++++++++++++++ .../CMakeLists.txt | 10 +++ .../package.xml | 2 + .../test/test_node_interface.cpp | 64 ++++++++++++++++++ 38 files changed, 699 insertions(+), 50 deletions(-) create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/test/test_node_interface.cpp create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/test/test_node_interface.cpp create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/test/test_node_interface.cpp create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/test/test_node_interface.cpp create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/test/test_node_interface.cpp delete mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_planner/srv/LoadPlugin.srv delete mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_planner/srv/UnloadPlugin.srv rename planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/{tests => test}/test_dynamic_obstacle.cpp (100%) create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/test/test_node_interface.cpp rename planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/{tests => test}/test_path_utils.cpp (100%) rename planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/{tests => test}/test_state_machine.cpp (100%) rename planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/{tests => test}/test_utils.cpp (100%) create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/test/test_node_interface.cpp create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/test/test_node_interface.cpp create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/test/test_node_interface.cpp create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/test/test_node_interface.cpp diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/CMakeLists.txt b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/CMakeLists.txt index b4a688d711221..b28e486c9be05 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/CMakeLists.txt +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/CMakeLists.txt @@ -13,4 +13,14 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/util.cpp ) +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() + file(GLOB_RECURSE TEST_SOURCES test/*.cpp) + ament_add_ros_isolated_gtest(test_${PROJECT_NAME} + ${TEST_SOURCES} + ) + target_link_libraries(test_${PROJECT_NAME} ${PROJECT_NAME}) +endif() + ament_auto_package(INSTALL_TO_SHARE config) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml index 9739370387df7..8c34678f439ed 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml @@ -17,6 +17,7 @@ ament_cmake_auto autoware_cmake + autoware_behavior_velocity_planner autoware_behavior_velocity_planner_common autoware_behavior_velocity_rtc_interface autoware_lanelet2_extension @@ -32,6 +33,7 @@ tier4_planning_msgs visualization_msgs + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/test/test_node_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/test/test_node_interface.cpp new file mode 100644 index 0000000000000..e0ceca4e12951 --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/test/test_node_interface.cpp @@ -0,0 +1,64 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include + +#include +#include +#include +#include + +namespace autoware::behavior_velocity_planner +{ +TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID) +{ + rclcpp::init(0, nullptr); + auto test_manager = autoware::behavior_velocity_planner::generateTestManager(); + auto test_target_node = autoware::behavior_velocity_planner::generateNode({}); + + autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + + // test with nominal path_with_lane_id + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + // test with empty path_with_lane_id + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalPathWithLaneId(test_target_node)); + rclcpp::shutdown(); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) +{ + rclcpp::init(0, nullptr); + + const auto plugin_info_vec = {autoware::behavior_velocity_planner::PluginInfo{ + "blind_spot", "autoware::behavior_velocity_planner::BlindSpotModulePlugin"}}; + + auto test_manager = autoware::behavior_velocity_planner::generateTestManager(); + auto test_target_node = autoware::behavior_velocity_planner::generateNode(plugin_info_vec); + autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + + // make sure behavior_path_planner is running + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testOffTrackFromPathWithLaneId(test_target_node)); + + rclcpp::shutdown(); +} +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/CMakeLists.txt b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/CMakeLists.txt index 10b694ce22cbd..3a429008c1b8e 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/CMakeLists.txt +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/CMakeLists.txt @@ -15,6 +15,7 @@ if(BUILD_TESTING) ament_lint_auto_find_test_dependencies() ament_add_ros_isolated_gtest(test_${PROJECT_NAME} test/test_crosswalk.cpp + test/test_node_interface.cpp ) target_link_libraries(test_${PROJECT_NAME} ${PROJECT_NAME}) endif() diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml index ff01e85aa5456..1f0e9e68a65c6 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml @@ -21,6 +21,7 @@ autoware_cmake eigen3_cmake_module + autoware_behavior_velocity_planner autoware_behavior_velocity_planner_common autoware_behavior_velocity_rtc_interface autoware_grid_map_utils diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/test/test_node_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/test/test_node_interface.cpp new file mode 100644 index 0000000000000..7a875327d4dde --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/test/test_node_interface.cpp @@ -0,0 +1,64 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include + +#include +#include +#include +#include + +namespace autoware::behavior_velocity_planner +{ +TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID) +{ + rclcpp::init(0, nullptr); + auto test_manager = autoware::behavior_velocity_planner::generateTestManager(); + auto test_target_node = autoware::behavior_velocity_planner::generateNode({}); + + autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + + // test with nominal path_with_lane_id + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + // test with empty path_with_lane_id + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalPathWithLaneId(test_target_node)); + rclcpp::shutdown(); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) +{ + rclcpp::init(0, nullptr); + + const auto plugin_info_vec = {autoware::behavior_velocity_planner::PluginInfo{ + "crosswalk", "autoware::behavior_velocity_planner::CrosswalkModulePlugin"}}; + + auto test_manager = autoware::behavior_velocity_planner::generateTestManager(); + auto test_target_node = autoware::behavior_velocity_planner::generateNode(plugin_info_vec); + autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + + // make sure behavior_path_planner is running + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testOffTrackFromPathWithLaneId(test_target_node)); + + rclcpp::shutdown(); +} +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/CMakeLists.txt b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/CMakeLists.txt index 3aff4a524ffdd..53eafaffbba6c 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/CMakeLists.txt +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/CMakeLists.txt @@ -14,6 +14,7 @@ if(BUILD_TESTING) ament_lint_auto_find_test_dependencies() ament_add_ros_isolated_gtest(test_${PROJECT_NAME} test/test_utils.cpp + test/test_node_interface.cpp ) target_link_libraries(test_${PROJECT_NAME} ${PROJECT_NAME}) endif() diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/package.xml index ff91cf40a32a6..4ae1d20991078 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/package.xml @@ -17,6 +17,7 @@ autoware_cmake eigen3_cmake_module + autoware_behavior_velocity_planner autoware_behavior_velocity_planner_common autoware_lanelet2_extension autoware_motion_utils diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/test/test_node_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/test/test_node_interface.cpp new file mode 100644 index 0000000000000..f84d22debea8e --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/test/test_node_interface.cpp @@ -0,0 +1,64 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include + +#include +#include +#include +#include + +namespace autoware::behavior_velocity_planner +{ +TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID) +{ + rclcpp::init(0, nullptr); + auto test_manager = autoware::behavior_velocity_planner::generateTestManager(); + auto test_target_node = autoware::behavior_velocity_planner::generateNode({}); + + autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + + // test with nominal path_with_lane_id + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + // test with empty path_with_lane_id + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalPathWithLaneId(test_target_node)); + rclcpp::shutdown(); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) +{ + rclcpp::init(0, nullptr); + + const auto plugin_info_vec = {autoware::behavior_velocity_planner::PluginInfo{ + "detection_area", "autoware::behavior_velocity_planner::DetectionAreaModulePlugin"}}; + + auto test_manager = autoware::behavior_velocity_planner::generateTestManager(); + auto test_target_node = autoware::behavior_velocity_planner::generateNode(plugin_info_vec); + autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + + // make sure behavior_path_planner is running + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testOffTrackFromPathWithLaneId(test_target_node)); + + rclcpp::shutdown(); +} +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml index 208e7ed49de71..4f7c3aeea7618 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml @@ -19,6 +19,7 @@ ament_cmake_auto autoware_cmake + autoware_behavior_velocity_planner autoware_behavior_velocity_planner_common autoware_behavior_velocity_rtc_interface autoware_internal_debug_msgs diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/test/test_node_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/test/test_node_interface.cpp new file mode 100644 index 0000000000000..b515107e0ae8e --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/test/test_node_interface.cpp @@ -0,0 +1,64 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include + +#include +#include +#include +#include + +namespace autoware::behavior_velocity_planner +{ +TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID) +{ + rclcpp::init(0, nullptr); + auto test_manager = autoware::behavior_velocity_planner::generateTestManager(); + auto test_target_node = autoware::behavior_velocity_planner::generateNode({}); + + autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + + // test with nominal path_with_lane_id + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + // test with empty path_with_lane_id + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalPathWithLaneId(test_target_node)); + rclcpp::shutdown(); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) +{ + rclcpp::init(0, nullptr); + + const auto plugin_info_vec = {autoware::behavior_velocity_planner::PluginInfo{ + "intersection", "autoware::behavior_velocity_planner::IntersectionModulePlugin"}}; + + auto test_manager = autoware::behavior_velocity_planner::generateTestManager(); + auto test_target_node = autoware::behavior_velocity_planner::generateNode(plugin_info_vec); + autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + + // make sure behavior_path_planner is running + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testOffTrackFromPathWithLaneId(test_target_node)); + + rclcpp::shutdown(); +} +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/CMakeLists.txt b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/CMakeLists.txt index b710924410549..e6b362271afb3 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/CMakeLists.txt +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/CMakeLists.txt @@ -14,6 +14,7 @@ if(BUILD_TESTING) ament_lint_auto_find_test_dependencies() ament_add_ros_isolated_gtest(test_${PROJECT_NAME} test/test_utils.cpp + test/test_node_interface.cpp ) target_link_libraries(test_${PROJECT_NAME} ${PROJECT_NAME}) endif() diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/package.xml index 4415eadef62c7..28677bfb80b15 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/package.xml @@ -17,6 +17,7 @@ ament_cmake_auto autoware_cmake + autoware_behavior_velocity_planner autoware_behavior_velocity_planner_common autoware_behavior_velocity_rtc_interface autoware_interpolation diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/test/test_node_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/test/test_node_interface.cpp new file mode 100644 index 0000000000000..875e757cbfcec --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/test/test_node_interface.cpp @@ -0,0 +1,64 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include + +#include +#include +#include +#include + +namespace autoware::behavior_velocity_planner +{ +TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID) +{ + rclcpp::init(0, nullptr); + auto test_manager = autoware::behavior_velocity_planner::generateTestManager(); + auto test_target_node = autoware::behavior_velocity_planner::generateNode({}); + + autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + + // test with nominal path_with_lane_id + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + // test with empty path_with_lane_id + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalPathWithLaneId(test_target_node)); + rclcpp::shutdown(); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) +{ + rclcpp::init(0, nullptr); + + const auto plugin_info_vec = {autoware::behavior_velocity_planner::PluginInfo{ + "no_stopping_area", "autoware::behavior_velocity_planner::NoStoppingAreaModulePlugin"}}; + + auto test_manager = autoware::behavior_velocity_planner::generateTestManager(); + auto test_target_node = autoware::behavior_velocity_planner::generateNode(plugin_info_vec); + autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + + // make sure behavior_path_planner is running + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testOffTrackFromPathWithLaneId(test_target_node)); + + rclcpp::shutdown(); +} +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/CMakeLists.txt b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/CMakeLists.txt index 31900a23d00e5..a520b02a43c05 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/CMakeLists.txt +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/CMakeLists.txt @@ -2,14 +2,6 @@ cmake_minimum_required(VERSION 3.14) project(autoware_behavior_velocity_planner) find_package(autoware_cmake REQUIRED) -find_package(rosidl_default_generators REQUIRED) - -rosidl_generate_interfaces( - ${PROJECT_NAME} - "srv/LoadPlugin.srv" - "srv/UnloadPlugin.srv" - DEPENDENCIES -) autoware_package() @@ -24,15 +16,6 @@ rclcpp_components_register_node(${PROJECT_NAME}_lib EXECUTABLE ${PROJECT_NAME}_node ) -if(${rosidl_cmake_VERSION} VERSION_LESS 2.5.0) - rosidl_target_interfaces(${PROJECT_NAME}_lib - ${PROJECT_NAME} "rosidl_typesupport_cpp") -else() - rosidl_get_typesupport_target( - cpp_typesupport_target ${PROJECT_NAME} "rosidl_typesupport_cpp") - target_link_libraries(${PROJECT_NAME}_lib "${cpp_typesupport_target}") -endif() - if(BUILD_TESTING) ament_add_ros_isolated_gtest(test_${PROJECT_NAME} test/test_node_interface.cpp diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/include/autoware/behavior_velocity_planner/node.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/include/autoware/behavior_velocity_planner/node.hpp index 4c1f10c355226..8a52ae70231d0 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/include/autoware/behavior_velocity_planner/node.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/include/autoware/behavior_velocity_planner/node.hpp @@ -21,10 +21,9 @@ #include #include -#include -#include #include +#include #include #include #include @@ -45,8 +44,6 @@ namespace autoware::behavior_velocity_planner { -using autoware_behavior_velocity_planner::srv::LoadPlugin; -using autoware_behavior_velocity_planner::srv::UnloadPlugin; using autoware_map_msgs::msg::LaneletMapBin; using tier4_planning_msgs::msg::VelocityLimit; @@ -125,13 +122,14 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node BehaviorVelocityPlannerManager planner_manager_; bool is_driving_forward_{true}; - rclcpp::Service::SharedPtr srv_load_plugin_; - rclcpp::Service::SharedPtr srv_unload_plugin_; + rclcpp::Service::SharedPtr srv_load_plugin_; + rclcpp::Service::SharedPtr srv_unload_plugin_; void onUnloadPlugin( - const UnloadPlugin::Request::SharedPtr request, - const UnloadPlugin::Response::SharedPtr response); + const autoware_internal_debug_msgs::srv::String::Request::SharedPtr request, + const autoware_internal_debug_msgs::srv::String::Response::SharedPtr response); void onLoadPlugin( - const LoadPlugin::Request::SharedPtr request, const LoadPlugin::Response::SharedPtr response); + const autoware_internal_debug_msgs::srv::String::Request::SharedPtr request, + const autoware_internal_debug_msgs::srv::String::Response::SharedPtr response); // mutex for planner_data_ std::mutex mutex_; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml index 04b4cf0328fd1..eca49a09c8a56 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml @@ -32,9 +32,8 @@ autoware_cmake eigen3_cmake_module - rosidl_default_generators - autoware_behavior_velocity_planner_common + autoware_internal_debug_msgs autoware_lanelet2_extension autoware_map_msgs autoware_motion_utils @@ -60,15 +59,11 @@ tier4_v2x_msgs visualization_msgs - rosidl_default_runtime - ament_cmake_ros ament_lint_auto autoware_lint_common - rosidl_interface_packages - ament_cmake diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp index 5f78e4c670b49..1e3e691076b8a 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp @@ -70,9 +70,9 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio this->create_subscription( "~/input/path_with_lane_id", 1, std::bind(&BehaviorVelocityPlannerNode::onTrigger, this, _1)); - srv_load_plugin_ = create_service( + srv_load_plugin_ = create_service( "~/service/load_plugin", std::bind(&BehaviorVelocityPlannerNode::onLoadPlugin, this, _1, _2)); - srv_unload_plugin_ = create_service( + srv_unload_plugin_ = create_service( "~/service/unload_plugin", std::bind(&BehaviorVelocityPlannerNode::onUnloadPlugin, this, _1, _2)); @@ -112,19 +112,19 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio } void BehaviorVelocityPlannerNode::onLoadPlugin( - const LoadPlugin::Request::SharedPtr request, - [[maybe_unused]] const LoadPlugin::Response::SharedPtr response) + const autoware_internal_debug_msgs::srv::String::Request::SharedPtr request, + [[maybe_unused]] const autoware_internal_debug_msgs::srv::String::Response::SharedPtr response) { std::unique_lock lk(mutex_); - planner_manager_.launchScenePlugin(*this, request->plugin_name); + planner_manager_.launchScenePlugin(*this, request->data); } void BehaviorVelocityPlannerNode::onUnloadPlugin( - const UnloadPlugin::Request::SharedPtr request, - [[maybe_unused]] const UnloadPlugin::Response::SharedPtr response) + const autoware_internal_debug_msgs::srv::String::Request::SharedPtr request, + [[maybe_unused]] const autoware_internal_debug_msgs::srv::String::Response::SharedPtr response) { std::unique_lock lk(mutex_); - planner_manager_.removeScenePlugin(*this, request->plugin_name); + planner_manager_.removeScenePlugin(*this, request->data); } void BehaviorVelocityPlannerNode::onParam() diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/srv/LoadPlugin.srv b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/srv/LoadPlugin.srv deleted file mode 100644 index 7b9f08ab0ded8..0000000000000 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/srv/LoadPlugin.srv +++ /dev/null @@ -1,3 +0,0 @@ -string plugin_name ---- -bool success diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/srv/UnloadPlugin.srv b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/srv/UnloadPlugin.srv deleted file mode 100644 index 7b9f08ab0ded8..0000000000000 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/srv/UnloadPlugin.srv +++ /dev/null @@ -1,3 +0,0 @@ -string plugin_name ---- -bool success diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/CMakeLists.txt b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/CMakeLists.txt index da2f4ce33ff60..a2f35ada11b5e 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/CMakeLists.txt +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/CMakeLists.txt @@ -17,10 +17,11 @@ ament_auto_add_library(${PROJECT_NAME} SHARED if(BUILD_TESTING) ament_add_ros_isolated_gtest(test_${PROJECT_NAME} - tests/test_dynamic_obstacle.cpp - tests/test_path_utils.cpp - tests/test_utils.cpp - tests/test_state_machine.cpp + test/test_dynamic_obstacle.cpp + test/test_path_utils.cpp + test/test_utils.cpp + test/test_state_machine.cpp + test/test_node_interface.cpp ) target_link_libraries(test_${PROJECT_NAME} autoware_behavior_velocity_run_out_module diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/package.xml index b3ced8b2e9b9f..18db8281356f8 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/package.xml @@ -20,6 +20,7 @@ eigen3_cmake_module autoware_behavior_velocity_crosswalk_module + autoware_behavior_velocity_planner autoware_behavior_velocity_planner_common autoware_internal_debug_msgs autoware_motion_utils diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/tests/test_dynamic_obstacle.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/test/test_dynamic_obstacle.cpp similarity index 100% rename from planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/tests/test_dynamic_obstacle.cpp rename to planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/test/test_dynamic_obstacle.cpp diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/test/test_node_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/test/test_node_interface.cpp new file mode 100644 index 0000000000000..75bf59751ed44 --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/test/test_node_interface.cpp @@ -0,0 +1,64 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include + +#include +#include +#include +#include + +namespace autoware::behavior_velocity_planner +{ +TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID) +{ + rclcpp::init(0, nullptr); + auto test_manager = autoware::behavior_velocity_planner::generateTestManager(); + auto test_target_node = autoware::behavior_velocity_planner::generateNode({}); + + autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + + // test with nominal path_with_lane_id + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + // test with empty path_with_lane_id + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalPathWithLaneId(test_target_node)); + rclcpp::shutdown(); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) +{ + rclcpp::init(0, nullptr); + + const auto plugin_info_vec = {autoware::behavior_velocity_planner::PluginInfo{ + "run_out", "autoware::behavior_velocity_planner::RunOutModulePlugin"}}; + + auto test_manager = autoware::behavior_velocity_planner::generateTestManager(); + auto test_target_node = autoware::behavior_velocity_planner::generateNode(plugin_info_vec); + autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + + // make sure behavior_path_planner is running + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testOffTrackFromPathWithLaneId(test_target_node)); + + rclcpp::shutdown(); +} +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/tests/test_path_utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/test/test_path_utils.cpp similarity index 100% rename from planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/tests/test_path_utils.cpp rename to planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/test/test_path_utils.cpp diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/tests/test_state_machine.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/test/test_state_machine.cpp similarity index 100% rename from planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/tests/test_state_machine.cpp rename to planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/test/test_state_machine.cpp diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/tests/test_utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/test/test_utils.cpp similarity index 100% rename from planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/tests/test_utils.cpp rename to planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/test/test_utils.cpp diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/CMakeLists.txt b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/CMakeLists.txt index f4528f0d13cf4..a187b4cda9459 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/CMakeLists.txt +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/CMakeLists.txt @@ -14,6 +14,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED if(BUILD_TESTING) ament_add_ros_isolated_gtest(test_${PROJECT_NAME} test/test_scene.cpp + test/test_node_interface.cpp ) target_link_libraries(test_${PROJECT_NAME} gtest_main diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/package.xml index fd4b9f83ae998..849ab3915c649 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/package.xml @@ -20,6 +20,7 @@ autoware_cmake eigen3_cmake_module + autoware_behavior_velocity_planner autoware_behavior_velocity_planner_common autoware_lanelet2_extension autoware_motion_utils diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/test/test_node_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/test/test_node_interface.cpp new file mode 100644 index 0000000000000..c6d6ff638cfbb --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/test/test_node_interface.cpp @@ -0,0 +1,64 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include + +#include +#include +#include +#include + +namespace autoware::behavior_velocity_planner +{ +TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID) +{ + rclcpp::init(0, nullptr); + auto test_manager = autoware::behavior_velocity_planner::generateTestManager(); + auto test_target_node = autoware::behavior_velocity_planner::generateNode({}); + + autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + + // test with nominal path_with_lane_id + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + // test with empty path_with_lane_id + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalPathWithLaneId(test_target_node)); + rclcpp::shutdown(); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) +{ + rclcpp::init(0, nullptr); + + const auto plugin_info_vec = {autoware::behavior_velocity_planner::PluginInfo{ + "stop_line", "autoware::behavior_velocity_planner::StopLineModulePlugin"}}; + + auto test_manager = autoware::behavior_velocity_planner::generateTestManager(); + auto test_target_node = autoware::behavior_velocity_planner::generateNode(plugin_info_vec); + autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + + // make sure behavior_path_planner is running + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testOffTrackFromPathWithLaneId(test_target_node)); + + rclcpp::shutdown(); +} +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/CMakeLists.txt b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/CMakeLists.txt index 6370dd5e6c21d..02ed192459970 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/CMakeLists.txt +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/CMakeLists.txt @@ -15,6 +15,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED if(BUILD_TESTING) ament_add_ros_isolated_gtest(test_${PROJECT_NAME} test/test_utils.cpp + test/test_node_interface.cpp ) target_link_libraries(test_${PROJECT_NAME} ${PROJECT_NAME} diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/package.xml index ebc45d372f92d..4bc7a15cddc48 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/package.xml @@ -19,6 +19,7 @@ eigen3_cmake_module autoware_adapi_v1_msgs + autoware_behavior_velocity_planner autoware_behavior_velocity_planner_common autoware_behavior_velocity_rtc_interface autoware_lanelet2_extension diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/test/test_node_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/test/test_node_interface.cpp new file mode 100644 index 0000000000000..e24c2dab5dab9 --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/test/test_node_interface.cpp @@ -0,0 +1,64 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include + +#include +#include +#include +#include + +namespace autoware::behavior_velocity_planner +{ +TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID) +{ + rclcpp::init(0, nullptr); + auto test_manager = autoware::behavior_velocity_planner::generateTestManager(); + auto test_target_node = autoware::behavior_velocity_planner::generateNode({}); + + autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + + // test with nominal path_with_lane_id + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + // test with empty path_with_lane_id + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalPathWithLaneId(test_target_node)); + rclcpp::shutdown(); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) +{ + rclcpp::init(0, nullptr); + + const auto plugin_info_vec = {autoware::behavior_velocity_planner::PluginInfo{ + "traffic_light", "autoware::behavior_velocity_planner::TrafficLightModulePlugin"}}; + + auto test_manager = autoware::behavior_velocity_planner::generateTestManager(); + auto test_target_node = autoware::behavior_velocity_planner::generateNode(plugin_info_vec); + autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + + // make sure behavior_path_planner is running + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testOffTrackFromPathWithLaneId(test_target_node)); + + rclcpp::shutdown(); +} +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/package.xml index 6d3bc68242d7c..056f84a970c58 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/package.xml @@ -18,6 +18,7 @@ autoware_cmake autoware_adapi_v1_msgs + autoware_behavior_velocity_planner autoware_behavior_velocity_planner_common autoware_lanelet2_extension autoware_motion_utils diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/test/test_node_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/test/test_node_interface.cpp new file mode 100644 index 0000000000000..9cb6bbfd40639 --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/test/test_node_interface.cpp @@ -0,0 +1,65 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include + +#include +#include +#include +#include + +namespace autoware::behavior_velocity_planner +{ +TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID) +{ + rclcpp::init(0, nullptr); + auto test_manager = autoware::behavior_velocity_planner::generateTestManager(); + auto test_target_node = autoware::behavior_velocity_planner::generateNode({}); + + autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + + // test with nominal path_with_lane_id + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + // test with empty path_with_lane_id + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalPathWithLaneId(test_target_node)); + rclcpp::shutdown(); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) +{ + rclcpp::init(0, nullptr); + + const auto plugin_info_vec = {autoware::behavior_velocity_planner::PluginInfo{ + "virtual_traffic_light", + "autoware::behavior_velocity_planner::VirtualTrafficLightModulePlugin"}}; + + auto test_manager = autoware::behavior_velocity_planner::generateTestManager(); + auto test_target_node = autoware::behavior_velocity_planner::generateNode(plugin_info_vec); + autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + + // make sure behavior_path_planner is running + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testOffTrackFromPathWithLaneId(test_target_node)); + + rclcpp::shutdown(); +} +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/CMakeLists.txt b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/CMakeLists.txt index 11504d9c8999c..8b11fdce7283e 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/CMakeLists.txt +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/CMakeLists.txt @@ -11,4 +11,14 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/scene_walkway.cpp ) +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() + file(GLOB_RECURSE TEST_SOURCES test/*.cpp) + ament_add_ros_isolated_gtest(test_${PROJECT_NAME} + ${TEST_SOURCES} + ) + target_link_libraries(test_${PROJECT_NAME} ${PROJECT_NAME}) +endif() + ament_auto_package(INSTALL_TO_SHARE config) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/package.xml index 5f1aea22855a4..857d9b524beb0 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/package.xml @@ -18,6 +18,7 @@ autoware_cmake autoware_behavior_velocity_crosswalk_module + autoware_behavior_velocity_planner autoware_behavior_velocity_planner_common autoware_lanelet2_extension autoware_motion_utils @@ -31,6 +32,7 @@ rclcpp visualization_msgs + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/test/test_node_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/test/test_node_interface.cpp new file mode 100644 index 0000000000000..e0b7fa5c31965 --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/test/test_node_interface.cpp @@ -0,0 +1,64 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include + +#include +#include +#include +#include + +namespace autoware::behavior_velocity_planner +{ +TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID) +{ + rclcpp::init(0, nullptr); + auto test_manager = autoware::behavior_velocity_planner::generateTestManager(); + auto test_target_node = autoware::behavior_velocity_planner::generateNode({}); + + autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + + // test with nominal path_with_lane_id + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + // test with empty path_with_lane_id + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalPathWithLaneId(test_target_node)); + rclcpp::shutdown(); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) +{ + rclcpp::init(0, nullptr); + + const auto plugin_info_vec = {autoware::behavior_velocity_planner::PluginInfo{ + "walkway", "autoware::behavior_velocity_planner::WalkwayModulePlugin"}}; + + auto test_manager = autoware::behavior_velocity_planner::generateTestManager(); + auto test_target_node = autoware::behavior_velocity_planner::generateNode(plugin_info_vec); + autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + + // make sure behavior_path_planner is running + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testOffTrackFromPathWithLaneId(test_target_node)); + + rclcpp::shutdown(); +} +} // namespace autoware::behavior_velocity_planner From a8a843a6cf7645a125658bdeb8785bd9d5fa71ac Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Mon, 6 Jan 2025 11:59:04 +0900 Subject: [PATCH 136/334] fix(simple_planning_simulator): fix bugprone-branch-clone (#9725) * fix: bugprone-error Signed-off-by: kobayu858 * fix: build error Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../simple_planning_simulator_core.cpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp index d61654c32af02..8c95e144b3f8d 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp @@ -585,9 +585,7 @@ void SimplePlanningSimulator::set_input(const InputCommand & cmd, const double a std::visit( [this, acc_by_slope](auto && arg) { using T = std::decay_t; - if constexpr (std::is_same_v) { - set_input(arg, acc_by_slope); - } else if constexpr (std::is_same_v) { + if constexpr (std::is_same_v || std::is_same_v) { set_input(arg, acc_by_slope); } else { throw std::invalid_argument("Invalid input command type"); @@ -640,7 +638,7 @@ void SimplePlanningSimulator::set_input(const Control & cmd, const double acc_by input << vel, steer; } else if ( // NOLINT vehicle_model_type_ == VehicleModelType::IDEAL_STEER_ACC || - vehicle_model_type_ == VehicleModelType::DELAY_STEER_ACC) { + vehicle_model_type_ == VehicleModelType::DELAY_STEER_ACC) { // NOLINT input << combined_acc, steer; } else if ( // NOLINT vehicle_model_type_ == VehicleModelType::IDEAL_STEER_ACC_GEARED || From 4a181d6a6d09071a22a99ce71a4ad2c3d18c827e Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Mon, 6 Jan 2025 12:23:41 +0900 Subject: [PATCH 137/334] fix(autoware_behavior_velocity_occlusion_spot_module): fix bugprone-macro-parentheses (#9712) * fix: bugprone-error Signed-off-by: kobayu858 * fix: fmt Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../src/scene_occlusion_spot.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp index 522e83390b0f1..c5d1cf61614b2 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp @@ -36,7 +36,7 @@ // turn on only when debugging. #define DEBUG_PRINT(enable, n, x) \ if (enable) { \ - const std::string time_msg = n + std::to_string(x); \ + const std::string time_msg = (n) + std::to_string(x); \ RCLCPP_INFO_STREAM_THROTTLE(logger_, *clock_, 3000, time_msg); \ } From ca2d4e7774abe3a8929fecbcfd17c2f1bb7da55f Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Mon, 6 Jan 2025 16:40:09 +0900 Subject: [PATCH 138/334] fix(autoware_carla_interface): fix lidar topic name (#9645) Signed-off-by: Maxime CLEMENT --- .../src/autoware_carla_interface/carla_ros.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/simulator/autoware_carla_interface/src/autoware_carla_interface/carla_ros.py b/simulator/autoware_carla_interface/src/autoware_carla_interface/carla_ros.py index a4f8dee7af1a0..9b978b66feefb 100644 --- a/simulator/autoware_carla_interface/src/autoware_carla_interface/carla_ros.py +++ b/simulator/autoware_carla_interface/src/autoware_carla_interface/carla_ros.py @@ -147,7 +147,7 @@ def __init__(self): elif sensor["type"] == "sensor.lidar.ray_cast": if sensor["id"] in self.sensor_frequencies: self.pub_lidar[sensor["id"]] = self.ros2_node.create_publisher( - PointCloud2, f'/sensing/lidar/{sensor["id"]}/pointcloud', 10 + PointCloud2, f'/sensing/lidar/{sensor["id"]}/pointcloud_before_sync', 10 ) else: self.ros2_node.get_logger().info( From d86c46a35882e75051a0abcba55853da78c1d21f Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 6 Jan 2025 17:42:32 +0900 Subject: [PATCH 139/334] feat(motion_velocity_planner): introduce Object/Pointcloud structure in PlannerData (#9812) * feat: new object/pointcloud struct in motion velocity planner Signed-off-by: Takayuki Murooka * update planner_data Signed-off-by: Takayuki Murooka * modify modules Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../src/dynamic_obstacle_stop_module.cpp | 2 +- .../src/object_filtering.cpp | 20 +++--- .../src/object_filtering.hpp | 4 +- .../test/test_object_filtering.cpp | 6 +- .../src/obstacle_velocity_limiter.cpp | 2 +- .../src/obstacle_velocity_limiter.hpp | 2 +- .../src/obstacle_velocity_limiter_module.cpp | 6 +- .../src/obstacles.cpp | 14 ++-- .../src/obstacles.hpp | 4 +- .../test/test_collision_distance.cpp | 9 ++- .../src/filter_predicted_objects.cpp | 25 +++---- .../planner_data.hpp | 66 ++++++++++++++++++- .../src/node.cpp | 5 +- 13 files changed, 121 insertions(+), 44 deletions(-) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp index 40aa985ee42e2..7fd5834ba2cfa 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp @@ -131,7 +131,7 @@ VelocityPlanningResult DynamicObstacleStopModule::plan( ? 0.0 : params_.hysteresis; const auto dynamic_obstacles = dynamic_obstacle_stop::filter_predicted_objects( - planner_data->predicted_objects, ego_data, params_, hysteresis); + planner_data->objects, ego_data, params_, hysteresis); const auto preprocessing_duration_us = stopwatch.toc("preprocessing"); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/object_filtering.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/object_filtering.cpp index 2ab3c09e64edd..0726fdba02de0 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/object_filtering.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/object_filtering.cpp @@ -96,20 +96,22 @@ bool is_unavoidable( }; std::vector filter_predicted_objects( - const autoware_perception_msgs::msg::PredictedObjects & objects, const EgoData & ego_data, + const std::vector & objects, const EgoData & ego_data, const PlannerParam & params, const double hysteresis) { std::vector filtered_objects; - for (const auto & object : objects.objects) { - const auto is_not_too_slow = object.kinematics.initial_twist_with_covariance.twist.linear.x >= - params.minimum_object_velocity; + for (const auto & object : objects) { + const auto & predicted_object = object.predicted_object; + const auto is_not_too_slow = + predicted_object.kinematics.initial_twist_with_covariance.twist.linear.x >= + params.minimum_object_velocity; if ( - is_vehicle(object) && is_not_too_slow && - is_in_range(object, ego_data.trajectory, params, hysteresis) && - is_not_too_close(object, ego_data, params.ego_longitudinal_offset) && + is_vehicle(predicted_object) && is_not_too_slow && + is_in_range(predicted_object, ego_data.trajectory, params, hysteresis) && + is_not_too_close(predicted_object, ego_data, params.ego_longitudinal_offset) && (!params.ignore_unavoidable_collisions || - !is_unavoidable(object, ego_data.pose, ego_data.earliest_stop_pose, params))) - filtered_objects.push_back(object); + !is_unavoidable(predicted_object, ego_data.pose, ego_data.earliest_stop_pose, params))) + filtered_objects.push_back(predicted_object); } return filtered_objects; } diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/object_filtering.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/object_filtering.hpp index d20d6354066c6..6024cde019489 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/object_filtering.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/object_filtering.hpp @@ -17,6 +17,8 @@ #include "types.hpp" +#include + #include #include @@ -74,7 +76,7 @@ bool is_unavoidable( /// @param hysteresis [m] extra distance threshold used for filtering /// @return filtered predicted objects std::vector filter_predicted_objects( - const autoware_perception_msgs::msg::PredictedObjects & objects, const EgoData & ego_data, + const std::vector & objects, const EgoData & ego_data, const PlannerParam & params, const double hysteresis); } // namespace autoware::motion_velocity_planner::dynamic_obstacle_stop diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/test/test_object_filtering.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/test/test_object_filtering.cpp index 3fa179903c23f..5993f81c7a8f1 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/test/test_object_filtering.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/test/test_object_filtering.cpp @@ -14,6 +14,7 @@ #include "../src/object_filtering.hpp" +#include #include #include @@ -26,6 +27,8 @@ #include #include +#include + TEST(TestObjectFiltering, isVehicle) { using autoware::motion_velocity_planner::dynamic_obstacle_stop::is_vehicle; @@ -202,8 +205,7 @@ TEST(TestObjectFiltering, isUnavoidable) TEST(TestObjectFiltering, filterPredictedObjects) { using autoware::motion_velocity_planner::dynamic_obstacle_stop::filter_predicted_objects; - autoware_perception_msgs::msg::PredictedObjects objects; - autoware_perception_msgs::msg::PredictedObject object; + std::vector objects; autoware::motion_velocity_planner::dynamic_obstacle_stop::EgoData ego_data; autoware::motion_velocity_planner::dynamic_obstacle_stop::PlannerParam params; double hysteresis{}; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter.cpp index e501b756af6a1..9be7f52bca99a 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter.cpp @@ -29,7 +29,7 @@ namespace autoware::motion_velocity_planner::obstacle_velocity_limiter { multi_polygon_t createPolygonMasks( - const autoware_perception_msgs::msg::PredictedObjects & dynamic_obstacles, const double buffer, + const std::vector & dynamic_obstacles, const double buffer, const double min_vel) { return createObjectPolygons(dynamic_obstacles, buffer, min_vel); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter.hpp index d7d2de63b33f8..b0cdb1f802e0f 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter.hpp @@ -56,7 +56,7 @@ void calculateSteeringAngles(TrajectoryPoints & trajectory, const double wheel_b /// @param[in] min_vel minimum velocity for an object to be masked /// @return polygon masks around dynamic objects multi_polygon_t createPolygonMasks( - const autoware_perception_msgs::msg::PredictedObjects & dynamic_obstacles, const double buffer, + const std::vector & dynamic_obstacles, const double buffer, const double min_vel); /// @brief create footprint polygons from projection lines diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp index 532cc834c19ac..1923f023552e3 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp @@ -170,7 +170,7 @@ VelocityPlanningResult ObstacleVelocityLimiterModule::plan( const auto preprocessing_us = stopwatch.toc("preprocessing"); stopwatch.tic("obstacles"); obstacle_masks.negative_masks = obstacle_velocity_limiter::createPolygonMasks( - planner_data->predicted_objects, obstacle_params_.dynamic_obstacles_buffer, + planner_data->objects, obstacle_params_.dynamic_obstacles_buffer, obstacle_params_.dynamic_obstacles_min_vel); if (obstacle_params_.ignore_on_path) obstacle_masks.negative_masks.push_back(obstacle_velocity_limiter::createTrajectoryFootprint( @@ -189,8 +189,8 @@ VelocityPlanningResult ObstacleVelocityLimiterModule::plan( obstacle_masks.positive_mask = obstacle_velocity_limiter::createEnvelopePolygon(footprint_polygons); obstacle_velocity_limiter::addSensorObstacles( - obstacles, planner_data->occupancy_grid, planner_data->no_ground_pointcloud, obstacle_masks, - obstacle_params_); + obstacles, planner_data->occupancy_grid, planner_data->no_ground_pointcloud.pointcloud, + obstacle_masks, obstacle_params_); } const auto obstacles_us = stopwatch.toc("obstacles"); autoware::motion_utils::VirtualWalls virtual_walls; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacles.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacles.cpp index 47215ee5cb0c4..187f028dc5969 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacles.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacles.cpp @@ -25,6 +25,7 @@ #include #include +#include namespace autoware::motion_velocity_planner::obstacle_velocity_limiter { @@ -58,17 +59,18 @@ polygon_t createObjectPolygon( } multi_polygon_t createObjectPolygons( - const autoware_perception_msgs::msg::PredictedObjects & objects, const double buffer, - const double min_velocity) + const std::vector & objects, const double buffer, const double min_velocity) { multi_polygon_t polygons; - for (const auto & object : objects.objects) { + for (const auto & object : objects) { + const auto & predicted_object = object.predicted_object; const double obj_vel_norm = std::hypot( - object.kinematics.initial_twist_with_covariance.twist.linear.x, - object.kinematics.initial_twist_with_covariance.twist.linear.y); + predicted_object.kinematics.initial_twist_with_covariance.twist.linear.x, + predicted_object.kinematics.initial_twist_with_covariance.twist.linear.y); if (min_velocity <= obj_vel_norm) { polygons.push_back(createObjectPolygon( - object.kinematics.initial_pose_with_covariance.pose, object.shape.dimensions, buffer)); + predicted_object.kinematics.initial_pose_with_covariance.pose, + predicted_object.shape.dimensions, buffer)); } } return polygons; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacles.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacles.hpp index 7e4704ba6818c..a98d92994f497 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacles.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacles.hpp @@ -18,6 +18,7 @@ #include "parameters.hpp" #include "types.hpp" +#include #include #include @@ -163,8 +164,7 @@ polygon_t createObjectPolygon( /// @param [in] min_velocity objects with velocity lower will be ignored /// @return polygons of the objects multi_polygon_t createObjectPolygons( - const autoware_perception_msgs::msg::PredictedObjects & objects, const double buffer, - const double min_velocity); + const std::vector & objects, const double buffer, const double min_velocity); /// @brief add obstacles obtained from sensors to the given Obstacles object /// @param[out] obstacles Obstacles object in which to add the sensor obstacles diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/test/test_collision_distance.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/test/test_collision_distance.cpp index ac07c62f62cf7..023ae83774917 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/test/test_collision_distance.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/test/test_collision_distance.cpp @@ -15,6 +15,7 @@ #include "../src/distance.hpp" #include "../src/obstacles.hpp" #include "../src/types.hpp" +#include "autoware/motion_velocity_planner_common/planner_data.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" #include @@ -27,6 +28,7 @@ #include #include +#include const auto point_in_polygon = [](const auto x, const auto y, const auto & polygon) { return std::find_if(polygon.outer().begin(), polygon.outer().end(), [=](const auto & pt) { @@ -387,11 +389,12 @@ TEST(TestCollisionDistance, arcDistance) TEST(TestCollisionDistance, createObjPolygons) { + using autoware::motion_velocity_planner::PlannerData; using autoware::motion_velocity_planner::obstacle_velocity_limiter::createObjectPolygons; using autoware_perception_msgs::msg::PredictedObject; using autoware_perception_msgs::msg::PredictedObjects; - PredictedObjects objects; + std::vector objects; auto polygons = createObjectPolygons(objects, 0.0, 0.0); EXPECT_TRUE(polygons.empty()); @@ -404,7 +407,7 @@ TEST(TestCollisionDistance, createObjPolygons) object1.kinematics.initial_twist_with_covariance.twist.linear.x = 0.0; object1.shape.dimensions.x = 1.0; object1.shape.dimensions.y = 1.0; - objects.objects.push_back(object1); + objects.push_back(PlannerData::Object(object1)); polygons = createObjectPolygons(objects, 0.0, 1.0); EXPECT_TRUE(polygons.empty()); @@ -431,7 +434,7 @@ TEST(TestCollisionDistance, createObjPolygons) object2.kinematics.initial_twist_with_covariance.twist.linear.x = 2.0; object2.shape.dimensions.x = 2.0; object2.shape.dimensions.y = 1.0; - objects.objects.push_back(object2); + objects.push_back(PlannerData::Object(object2)); polygons = createObjectPolygons(objects, 0.0, 2.0); ASSERT_EQ(polygons.size(), 1ul); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp index f9ba7f4af9877..a6c8368c20571 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp @@ -106,23 +106,26 @@ autoware_perception_msgs::msg::PredictedObjects filter_predicted_objects( const PlannerData & planner_data, const EgoData & ego_data, const PlannerParam & params) { autoware_perception_msgs::msg::PredictedObjects filtered_objects; - filtered_objects.header = planner_data.predicted_objects.header; - for (const auto & object : planner_data.predicted_objects.objects) { + filtered_objects.header = planner_data.predicted_objects_header; + for (const auto & object : planner_data.objects) { + const auto & predicted_object = object.predicted_object; const auto is_pedestrian = - std::find_if(object.classification.begin(), object.classification.end(), [](const auto & c) { - return c.label == autoware_perception_msgs::msg::ObjectClassification::PEDESTRIAN; - }) != object.classification.end(); + std::find_if( + predicted_object.classification.begin(), predicted_object.classification.end(), + [](const auto & c) { + return c.label == autoware_perception_msgs::msg::ObjectClassification::PEDESTRIAN; + }) != predicted_object.classification.end(); if (is_pedestrian) continue; const auto is_coming_from_behind = motion_utils::calcSignedArcLength( ego_data.trajectory_points, 0UL, - object.kinematics.initial_pose_with_covariance.pose.position) < 0.0; + predicted_object.kinematics.initial_pose_with_covariance.pose.position) < 0.0; if (params.objects_ignore_behind_ego && is_coming_from_behind) { continue; } - auto filtered_object = object; + auto filtered_object = predicted_object; const auto is_invalid_predicted_path = [&](const auto & predicted_path) { const auto is_low_confidence = predicted_path.confidence < params.objects_min_confidence; const auto no_overlap_path = motion_utils::removeOverlapPoints(predicted_path.path); @@ -130,10 +133,10 @@ autoware_perception_msgs::msg::PredictedObjects filter_predicted_objects( const auto lat_offset_to_current_ego = std::abs(motion_utils::calcLateralOffset(no_overlap_path, ego_data.pose.position)); const auto is_crossing_ego = - lat_offset_to_current_ego <= - object.shape.dimensions.y / 2.0 + std::max( - params.left_offset + params.extra_left_offset, - params.right_offset + params.extra_right_offset); + lat_offset_to_current_ego <= predicted_object.shape.dimensions.y / 2.0 + + std::max( + params.left_offset + params.extra_left_offset, + params.right_offset + params.extra_right_offset); return is_low_confidence || is_crossing_ego; }; auto & predicted_paths = filtered_object.kinematics.predicted_paths; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp index 9ef3bf5c7f756..07c8e1580e4f0 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp @@ -39,6 +39,7 @@ #include #include #include +#include namespace autoware::motion_velocity_planner { @@ -54,11 +55,72 @@ struct PlannerData { } + struct Object + { + public: + Object() = default; + explicit Object(const autoware_perception_msgs::msg::PredictedObject & arg_predicted_object) + : predicted_object(arg_predicted_object) + { + } + + autoware_perception_msgs::msg::PredictedObject predicted_object; + // double get_lon_vel_relative_to_traj() + // { + // if (!lon_vel_relative_to_traj) { + // lon_vel_relative_to_traj = 0.0; + // } + // return *lon_vel_relative_to_traj; + // } + // double get_lat_vel_relative_to_traj() + // { + // if (!lat_vel_relative_to_traj) { + // lat_vel_relative_to_traj = 0.0; + // } + // return *lat_vel_relative_to_traj; + // } + + private: + // TODO(murooka) implement the following variables and their functions. + // std::optional dist_to_traj_poly{std::nullopt}; + // std::optional dist_to_traj_lateral{std::nullopt}; + // std::optional dist_from_ego_longitudinal{std::nullopt}; + // std::optional lon_vel_relative_to_traj{std::nullopt}; + // std::optional lat_vel_relative_to_traj{std::nullopt}; + }; + + struct Pointcloud + { + public: + Pointcloud() = default; + explicit Pointcloud(const pcl::PointCloud & arg_pointcloud) + : pointcloud(arg_pointcloud) + { + } + + pcl::PointCloud pointcloud; + + private: + // NOTE: clustered result will be added. + }; + + void process_predicted_objects( + const autoware_perception_msgs::msg::PredictedObjects & predicted_objects) + { + predicted_objects_header = predicted_objects.header; + + objects.clear(); + for (const auto & predicted_object : predicted_objects.objects) { + objects.push_back(Object(predicted_object)); + } + } + // msgs from callbacks that are used for data-ready nav_msgs::msg::Odometry current_odometry; geometry_msgs::msg::AccelWithCovarianceStamped current_acceleration; - autoware_perception_msgs::msg::PredictedObjects predicted_objects; - pcl::PointCloud no_ground_pointcloud; + std_msgs::msg::Header predicted_objects_header; + std::vector objects; + Pointcloud no_ground_pointcloud; nav_msgs::msg::OccupancyGrid occupancy_grid; std::shared_ptr route_handler; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp index cefc84836beda..a78ab1489e080 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp @@ -161,13 +161,14 @@ bool MotionVelocityPlannerNode::update_planner_data( const auto predicted_objects_ptr = sub_predicted_objects_.takeData(); if (check_with_log(predicted_objects_ptr, "Waiting for predicted objects")) - planner_data_.predicted_objects = *predicted_objects_ptr; + planner_data_.process_predicted_objects(*predicted_objects_ptr); processing_times["update_planner_data.pred_obj"] = sw.toc(true); const auto no_ground_pointcloud_ptr = sub_no_ground_pointcloud_.takeData(); if (check_with_log(no_ground_pointcloud_ptr, "Waiting for pointcloud")) { const auto no_ground_pointcloud = process_no_ground_pointcloud(no_ground_pointcloud_ptr); - if (no_ground_pointcloud) planner_data_.no_ground_pointcloud = *no_ground_pointcloud; + if (no_ground_pointcloud) + planner_data_.no_ground_pointcloud = PlannerData::Pointcloud(*no_ground_pointcloud); } processing_times["update_planner_data.pcd"] = sw.toc(true); From 7fb4c1bd29c657847f366eb8853c016729f753a2 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 6 Jan 2025 22:01:40 +0900 Subject: [PATCH 140/334] feat(behavior_velocity_planner): remove virtual traffic light dependency from behavior_velocity_planner and behavior_velocity_planner_common (#9746) * feat: remove-virtual-traffic-light-dependency-from-plugin-manager Signed-off-by: Takayuki Murooka * build passed Signed-off-by: Takayuki Murooka * fix test Signed-off-by: Takayuki Murooka * fix test Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * fix typo Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../behavior_velocity_planner/node.hpp | 4 -- .../package.xml | 1 - .../src/node.cpp | 3 -- .../src/test_utils.cpp | 2 - .../planner_data.hpp | 2 - .../scene_module_interface.hpp | 26 ------------ .../package.xml | 1 - .../src/manager.cpp | 40 ++++++++++++++++++- .../src/manager.hpp | 18 ++++++++- .../src/scene.cpp | 25 ++++++++++-- .../src/scene.hpp | 14 +++++++ .../test/test_node_interface.cpp | 11 ++++- 12 files changed, 100 insertions(+), 47 deletions(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/include/autoware/behavior_velocity_planner/node.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/include/autoware/behavior_velocity_planner/node.hpp index 8a52ae70231d0..472538406c382 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/include/autoware/behavior_velocity_planner/node.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/include/autoware/behavior_velocity_planner/node.hpp @@ -81,10 +81,6 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node autoware_perception_msgs::msg::TrafficLightGroupArray> sub_traffic_signals_{this, "~/input/traffic_signals"}; - autoware::universe_utils::InterProcessPollingSubscriber< - tier4_v2x_msgs::msg::VirtualTrafficLightStateArray> - sub_virtual_traffic_light_states_{this, "~/input/virtual_traffic_light_states"}; - autoware::universe_utils::InterProcessPollingSubscriber sub_occupancy_grid_{this, "~/input/occupancy_grid"}; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml index eca49a09c8a56..c40d80c2bf998 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml @@ -56,7 +56,6 @@ tf2_geometry_msgs tf2_ros tier4_planning_msgs - tier4_v2x_msgs visualization_msgs ament_cmake_ros diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp index 1e3e691076b8a..443bfebe2a3eb 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp @@ -271,9 +271,6 @@ bool BehaviorVelocityPlannerNode::processData(rclcpp::Clock clock) planner_data_.route_handler_ = std::make_shared(*map_data); } - // optional data - getData(planner_data_.virtual_traffic_light_states, sub_virtual_traffic_light_states_); - // planner_data_.external_velocity_limit is std::optional type variable. const auto external_velocity_limit = sub_external_velocity_limit_.takeData(); if (external_velocity_limit) { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/test_utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/test_utils.cpp index ee1bb8f89fc46..8b9f39e97d22b 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/test_utils.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/test_utils.cpp @@ -113,8 +113,6 @@ void publishMandatoryTopics( test_target_node, "behavior_velocity_planner_node/input/traffic_signals"); test_manager->publishMaxVelocity( test_target_node, "behavior_velocity_planner_node/input/external_velocity_limit_mps"); - test_manager->publishVirtualTrafficLightState( - test_target_node, "behavior_velocity_planner_node/input/virtual_traffic_light_states"); test_manager->publishOccupancyGrid( test_target_node, "behavior_velocity_planner_node/input/occupancy_grid"); } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/planner_data.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/planner_data.hpp index 983aaec2acf4f..f8b37999cb6bf 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/planner_data.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/planner_data.hpp @@ -30,7 +30,6 @@ #include #include #include -#include #include #include @@ -64,7 +63,6 @@ struct PlannerData std::map traffic_light_id_map_raw_; std::map traffic_light_id_map_last_observed_; std::optional external_velocity_limit; - tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr virtual_traffic_light_states; bool is_simulation = false; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp index 9dbed9009a93e..d8d640a078267 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp @@ -32,7 +32,6 @@ #include #include #include -#include #include #include @@ -95,17 +94,6 @@ class SceneModuleInterface planner_data_ = planner_data; } - std::optional getInfrastructureCommand() - { - return infrastructure_command_; - } - - void setInfrastructureCommand( - const std::optional & command) - { - infrastructure_command_ = command; - } - void setTimeKeeper(const std::shared_ptr & time_keeper) { time_keeper_ = time_keeper; @@ -123,7 +111,6 @@ class SceneModuleInterface rclcpp::Logger logger_; rclcpp::Clock::SharedPtr clock_; std::shared_ptr planner_data_; - std::optional infrastructure_command_; autoware::motion_utils::VelocityFactorInterface velocity_factor_; std::vector objects_of_interest_; mutable std::shared_ptr time_keeper_; @@ -161,9 +148,6 @@ class SceneModuleManagerInterface std::string("~/virtual_wall/") + module_name, 5); pub_velocity_factor_ = node.create_publisher( std::string("/planning/velocity_factors/") + module_name, 1); - pub_infrastructure_commands_ = - node.create_publisher( - "~/output/infrastructure_commands", 1); processing_time_publisher_ = std::make_shared(&node, "~/debug"); @@ -201,9 +185,6 @@ class SceneModuleManagerInterface velocity_factor_array.header.frame_id = "map"; velocity_factor_array.header.stamp = clock_->now(); - tier4_v2x_msgs::msg::InfrastructureCommandArray infrastructure_command_array; - infrastructure_command_array.stamp = clock_->now(); - for (const auto & scene_module : scene_modules_) { scene_module->resetVelocityFactor(); scene_module->setPlannerData(planner_data_); @@ -215,10 +196,6 @@ class SceneModuleManagerInterface velocity_factor_array.factors.emplace_back(velocity_factor); } - if (const auto command = scene_module->getInfrastructureCommand()) { - infrastructure_command_array.commands.push_back(*command); - } - for (const auto & marker : scene_module->createDebugMarkerArray().markers) { debug_marker_array.markers.push_back(marker); } @@ -227,7 +204,6 @@ class SceneModuleManagerInterface } pub_velocity_factor_->publish(velocity_factor_array); - pub_infrastructure_commands_->publish(infrastructure_command_array); pub_debug_->publish(debug_marker_array); if (is_publish_debug_path_) { tier4_planning_msgs::msg::PathWithLaneId debug_path; @@ -299,8 +275,6 @@ class SceneModuleManagerInterface rclcpp::Publisher::SharedPtr pub_debug_path_; rclcpp::Publisher::SharedPtr pub_velocity_factor_; - rclcpp::Publisher::SharedPtr - pub_infrastructure_commands_; std::shared_ptr processing_time_publisher_; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml index 002c3362260cc..9f920dff8f166 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml @@ -45,7 +45,6 @@ tf2_geometry_msgs tf2_ros tier4_planning_msgs - tier4_v2x_msgs visualization_msgs ament_cmake_ros diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/manager.cpp index a51cf9211c21f..3815c83d3b6ab 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/manager.cpp @@ -21,6 +21,8 @@ #include #include +#include + #include #include @@ -53,6 +55,14 @@ VirtualTrafficLightModuleManager::VirtualTrafficLightModuleManager(rclcpp::Node p.check_timeout_after_stop_line = getOrDeclareParameter(node, ns + ".check_timeout_after_stop_line"); } + + sub_virtual_traffic_light_states_ = autoware::universe_utils::InterProcessPollingSubscriber< + tier4_v2x_msgs::msg::VirtualTrafficLightStateArray>:: + create_subscription(&node, "~/input/virtual_traffic_light_states"); + + pub_infrastructure_commands_ = + node.create_publisher( + "~/output/infrastructure_commands", 1); } void VirtualTrafficLightModuleManager::launchNewModules( @@ -89,17 +99,43 @@ void VirtualTrafficLightModuleManager::launchNewModules( } } -std::function &)> +std::function &)> VirtualTrafficLightModuleManager::getModuleExpiredFunction( const tier4_planning_msgs::msg::PathWithLaneId & path) { const auto id_set = planning_utils::getLaneletIdSetOnPath( path, planner_data_->route_handler_->getLaneletMapPtr(), planner_data_->current_odometry->pose); - return [id_set](const std::shared_ptr & scene_module) { + return [id_set](const std::shared_ptr & scene_module) { return id_set.count(scene_module->getModuleId()) == 0; }; } + +void VirtualTrafficLightModuleManager::modifyPathVelocity( + tier4_planning_msgs::msg::PathWithLaneId * path) +{ + // NOTE: virtual traffic light specific implementation + // Since the argument of modifyPathVelocity cannot be changed, the specific information + // of virtual traffic light states is set here. + const auto virtual_traffic_light_states = sub_virtual_traffic_light_states_->takeData(); + for (const auto & scene_module : scene_modules_) { + scene_module->setVirtualTrafficLightStates(virtual_traffic_light_states); + } + + SceneModuleManagerInterface::modifyPathVelocity(path); + + // NOTE: virtual traffic light specific implementation + // publish infrastructure_command_array + tier4_v2x_msgs::msg::InfrastructureCommandArray infrastructure_command_array; + infrastructure_command_array.stamp = clock_->now(); + + for (const auto & scene_module : scene_modules_) { + if (const auto command = scene_module->getInfrastructureCommand()) { + infrastructure_command_array.commands.push_back(*command); + } + } + pub_infrastructure_commands_->publish(infrastructure_command_array); +} } // namespace autoware::behavior_velocity_planner #include diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/manager.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/manager.hpp index 8e0abc98c90de..aecef0851d8ab 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/manager.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/manager.hpp @@ -20,16 +20,20 @@ #include #include #include +#include #include #include +#include +#include #include #include namespace autoware::behavior_velocity_planner { -class VirtualTrafficLightModuleManager : public SceneModuleManagerInterface<> +class VirtualTrafficLightModuleManager +: public SceneModuleManagerInterface { public: explicit VirtualTrafficLightModuleManager(rclcpp::Node & node); @@ -38,10 +42,20 @@ class VirtualTrafficLightModuleManager : public SceneModuleManagerInterface<> private: VirtualTrafficLightModule::PlannerParam planner_param_; + + void modifyPathVelocity(tier4_planning_msgs::msg::PathWithLaneId * path) override; + void launchNewModules(const tier4_planning_msgs::msg::PathWithLaneId & path) override; - std::function &)> getModuleExpiredFunction( + std::function &)> getModuleExpiredFunction( const tier4_planning_msgs::msg::PathWithLaneId & path) override; + + autoware::universe_utils::InterProcessPollingSubscriber< + tier4_v2x_msgs::msg::VirtualTrafficLightStateArray>::SharedPtr + sub_virtual_traffic_light_states_; + + rclcpp::Publisher::SharedPtr + pub_infrastructure_commands_; }; class VirtualTrafficLightModulePlugin : public PluginWrapper diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp index 206fb14b6d41c..86239816ed6f2 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp @@ -333,12 +333,12 @@ bool VirtualTrafficLightModule::isNearAnyEndLine(const size_t end_line_idx) std::optional VirtualTrafficLightModule::findCorrespondingState() { - // No message - if (!planner_data_->virtual_traffic_light_states) { + // Note: This variable is set by virtual traffic light's manager. + if (!virtual_traffic_light_states_) { return {}; } - for (const auto & state : planner_data_->virtual_traffic_light_states->states) { + for (const auto & state : virtual_traffic_light_states_->states) { if (state.id == map_data_.instrument_id) { return state; } @@ -457,4 +457,23 @@ void VirtualTrafficLightModule::insertStopVelocityAtEndLine( module_data_.stop_head_pose_at_end_line = calcHeadPose(stop_pose, planner_data_->vehicle_info_.max_longitudinal_offset_m); } + +std::optional +VirtualTrafficLightModule::getInfrastructureCommand() const +{ + return infrastructure_command_; +} + +void VirtualTrafficLightModule::setInfrastructureCommand( + const std::optional & command) +{ + infrastructure_command_ = command; +} + +void VirtualTrafficLightModule::setVirtualTrafficLightStates( + const tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr + virtual_traffic_light_states) +{ + virtual_traffic_light_states_ = virtual_traffic_light_states; +} } // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp index b031ba5b2bb2b..7f37e7078a431 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp @@ -17,6 +17,7 @@ #include #include +#include #include #include #include @@ -24,6 +25,9 @@ #include #include +#include +#include + #include #include @@ -84,13 +88,23 @@ class VirtualTrafficLightModule : public SceneModuleInterface visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; autoware::motion_utils::VirtualWalls createVirtualWalls() override; + std::optional getInfrastructureCommand() const; + void setInfrastructureCommand( + const std::optional & command); + + void setVirtualTrafficLightStates( + const tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr + virtual_traffic_light_states); + private: const int64_t lane_id_; const lanelet::autoware::VirtualTrafficLight & reg_elem_; const lanelet::ConstLanelet lane_; const PlannerParam planner_param_; + tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr virtual_traffic_light_states_; State state_{State::NONE}; tier4_v2x_msgs::msg::InfrastructureCommand command_; + std::optional infrastructure_command_; MapData map_data_; ModuleData module_data_; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/test/test_node_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/test/test_node_interface.cpp index 9cb6bbfd40639..ab2fd5847c5be 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/test/test_node_interface.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/test/test_node_interface.cpp @@ -26,10 +26,17 @@ namespace autoware::behavior_velocity_planner TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID) { rclcpp::init(0, nullptr); + + const auto plugin_info_vec = {autoware::behavior_velocity_planner::PluginInfo{ + "virtual_traffic_light", + "autoware::behavior_velocity_planner::VirtualTrafficLightModulePlugin"}}; + auto test_manager = autoware::behavior_velocity_planner::generateTestManager(); - auto test_target_node = autoware::behavior_velocity_planner::generateNode({}); + auto test_target_node = autoware::behavior_velocity_planner::generateNode(plugin_info_vec); autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + test_manager->publishVirtualTrafficLightState( + test_target_node, "behavior_velocity_planner_node/input/virtual_traffic_light_states"); // test with nominal path_with_lane_id ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); @@ -51,6 +58,8 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) auto test_manager = autoware::behavior_velocity_planner::generateTestManager(); auto test_target_node = autoware::behavior_velocity_planner::generateNode(plugin_info_vec); autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + test_manager->publishVirtualTrafficLightState( + test_target_node, "behavior_velocity_planner_node/input/virtual_traffic_light_states"); // test for normal trajectory ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); From ab845fb7371ca60ef35889c390236abfc3fb4763 Mon Sep 17 00:00:00 2001 From: Kenzo Lobos Tsunekawa Date: Tue, 7 Jan 2025 13:35:44 +0900 Subject: [PATCH 141/334] fix(autoware_lidar_centerpoint): fixed rounding errors that caused illegal memory access (#9795) fix: fixed rounding errors that caused illegal memory address Signed-off-by: Kenzo Lobos-Tsunekawa --- .../lib/preprocess/preprocess_kernel.cu | 2 ++ 1 file changed, 2 insertions(+) diff --git a/perception/autoware_lidar_centerpoint/lib/preprocess/preprocess_kernel.cu b/perception/autoware_lidar_centerpoint/lib/preprocess/preprocess_kernel.cu index f300411a44aad..95ac7b4353e90 100644 --- a/perception/autoware_lidar_centerpoint/lib/preprocess/preprocess_kernel.cu +++ b/perception/autoware_lidar_centerpoint/lib/preprocess/preprocess_kernel.cu @@ -148,6 +148,8 @@ __global__ void generateVoxels_random_kernel( int voxel_idx = floorf((point.x - min_x_range) / pillar_x_size); int voxel_idy = floorf((point.y - min_y_range) / pillar_y_size); + voxel_idx = voxel_idx < 0 ? 0 : voxel_idx >= grid_x_size ? grid_x_size - 1 : voxel_idx; + voxel_idy = voxel_idy < 0 ? 0 : voxel_idy >= grid_y_size ? grid_y_size - 1 : voxel_idy; unsigned int voxel_index = (grid_x_size - 1 - voxel_idx) * grid_y_size + voxel_idy; unsigned int point_id = atomicAdd(&(mask[voxel_index]), 1); From f242fbf91e5d5e55da8e04dc3f8fdecbbf20a6e6 Mon Sep 17 00:00:00 2001 From: Kenzo Lobos Tsunekawa Date: Tue, 7 Jan 2025 13:55:52 +0900 Subject: [PATCH 142/334] fix(autoware_lidar_transfusion): fixed rounding errors that caused illegal memory access (#9796) fix: fixed rounding errors that caused illegal memory address Signed-off-by: Kenzo Lobos-Tsunekawa Co-authored-by: Amadeusz Szymko --- .../lib/preprocess/preprocess_kernel.cu | 2 ++ 1 file changed, 2 insertions(+) diff --git a/perception/autoware_lidar_transfusion/lib/preprocess/preprocess_kernel.cu b/perception/autoware_lidar_transfusion/lib/preprocess/preprocess_kernel.cu index 49131218ff698..a89268e646cfc 100644 --- a/perception/autoware_lidar_transfusion/lib/preprocess/preprocess_kernel.cu +++ b/perception/autoware_lidar_transfusion/lib/preprocess/preprocess_kernel.cu @@ -176,6 +176,8 @@ __global__ void generateVoxels_random_kernel( int voxel_idx = floorf((x - min_x_range) / pillar_x_size); int voxel_idy = floorf((y - min_y_range) / pillar_y_size); + voxel_idx = voxel_idx < 0 ? 0 : voxel_idx >= grid_x_size ? grid_x_size - 1 : voxel_idx; + voxel_idy = voxel_idy < 0 ? 0 : voxel_idy >= grid_y_size ? grid_y_size - 1 : voxel_idy; unsigned int voxel_index = voxel_idy * grid_x_size + voxel_idx; unsigned int point_id = atomicAdd(&(mask[voxel_index]), 1); From 515a21f86808bb15e5fb0601576a966f2abe9614 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> Date: Tue, 7 Jan 2025 14:27:14 +0900 Subject: [PATCH 143/334] refactor(autoware_behavior_path_start_planner_module): remove unnecessary time_keeper parameter from pull-out planners (#9827) * refactor(autoware_behavior_path_start_planner_module): remove unnecessary time_keeper parameter from pull-out planners Signed-off-by: Kyoichi Sugahara --------- Signed-off-by: Kyoichi Sugahara --- .../freespace_pull_out.hpp | 5 +---- .../geometric_pull_out.hpp | 3 ++- .../pull_out_planner_base.hpp | 13 +++++++------ .../shift_pull_out.hpp | 3 ++- .../src/freespace_pull_out.cpp | 10 +++------- .../src/start_planner_module.cpp | 3 +-- .../test/test_geometric_pull_out.cpp | 3 +-- .../test/test_shift_pull_out.cpp | 4 +--- 8 files changed, 18 insertions(+), 26 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/freespace_pull_out.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/freespace_pull_out.hpp index e358e35ed7794..364d2d31a2577 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/freespace_pull_out.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/freespace_pull_out.hpp @@ -35,10 +35,7 @@ using autoware::freespace_planning_algorithms::RRTStar; class FreespacePullOut : public PullOutPlannerBase { public: - FreespacePullOut( - rclcpp::Node & node, const StartPlannerParameters & parameters, - const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, - std::shared_ptr time_keeper); + FreespacePullOut(rclcpp::Node & node, const StartPlannerParameters & parameters); PlannerType getPlannerType() const override { return PlannerType::FREESPACE; } diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/geometric_pull_out.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/geometric_pull_out.hpp index 18d1f3c3b9b81..78eb72183cdf5 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/geometric_pull_out.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/geometric_pull_out.hpp @@ -35,7 +35,8 @@ class GeometricPullOut : public PullOutPlannerBase rclcpp::Node & node, const StartPlannerParameters & parameters, const std::shared_ptr lane_departure_checker, - std::shared_ptr time_keeper); + std::shared_ptr time_keeper = + std::make_shared()); PlannerType getPlannerType() const override { return PlannerType::GEOMETRIC; }; std::optional plan( diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/pull_out_planner_base.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/pull_out_planner_base.hpp index f606679e7f2da..dfd972aff9be0 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/pull_out_planner_base.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/pull_out_planner_base.hpp @@ -40,12 +40,13 @@ class PullOutPlannerBase public: explicit PullOutPlannerBase( rclcpp::Node & node, const StartPlannerParameters & parameters, - std::shared_ptr time_keeper) - : time_keeper_(time_keeper) + std::shared_ptr time_keeper = + std::make_shared()) + : parameters_(parameters), + vehicle_info_(autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()), + vehicle_footprint_(vehicle_info_.createFootprint()), + time_keeper_(time_keeper) { - vehicle_info_ = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo(); - vehicle_footprint_ = vehicle_info_.createFootprint(); - parameters_ = parameters; } virtual ~PullOutPlannerBase() = default; @@ -68,9 +69,9 @@ class PullOutPlannerBase double collision_check_distance_from_end) const; std::shared_ptr planner_data_; + StartPlannerParameters parameters_; autoware::vehicle_info_utils::VehicleInfo vehicle_info_; LinearRing2d vehicle_footprint_; - StartPlannerParameters parameters_; double collision_check_margin_; mutable std::shared_ptr time_keeper_; diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/shift_pull_out.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/shift_pull_out.hpp index 5b4f78b252d22..8da104940d327 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/shift_pull_out.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/shift_pull_out.hpp @@ -36,7 +36,8 @@ class ShiftPullOut : public PullOutPlannerBase explicit ShiftPullOut( rclcpp::Node & node, const StartPlannerParameters & parameters, std::shared_ptr & lane_departure_checker, - std::shared_ptr time_keeper); + std::shared_ptr time_keeper = + std::make_shared()); PlannerType getPlannerType() const override { return PlannerType::SHIFT; }; std::optional plan( diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp index 42698f799c6b3..a089f6a8a83fc 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp @@ -28,15 +28,11 @@ namespace autoware::behavior_path_planner { -FreespacePullOut::FreespacePullOut( - rclcpp::Node & node, const StartPlannerParameters & parameters, - const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, - std::shared_ptr time_keeper) -: PullOutPlannerBase{node, parameters, time_keeper}, - velocity_{parameters.freespace_planner_velocity} +FreespacePullOut::FreespacePullOut(rclcpp::Node & node, const StartPlannerParameters & parameters) +: PullOutPlannerBase{node, parameters}, velocity_{parameters.freespace_planner_velocity} { autoware::freespace_planning_algorithms::VehicleShape vehicle_shape( - vehicle_info, parameters.vehicle_shape_margin); + vehicle_info_, parameters.vehicle_shape_margin); if (parameters.freespace_planner_algorithm == "astar") { use_back_ = parameters.astar_parameters.use_back; planner_ = std::make_unique( diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp index c223390e454d1..f45924b9542dc 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp @@ -90,8 +90,7 @@ StartPlannerModule::StartPlannerModule( } if (parameters_->enable_freespace_planner) { - freespace_planner_ = - std::make_unique(node, *parameters, vehicle_info_, time_keeper_); + freespace_planner_ = std::make_unique(node, *parameters); const auto freespace_planner_period_ns = rclcpp::Rate(1.0).period(); freespace_planner_timer_cb_group_ = node.create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_geometric_pull_out.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_geometric_pull_out.cpp index fb39e186afd4e..dd8bb02c97dea 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_geometric_pull_out.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_geometric_pull_out.cpp @@ -156,9 +156,8 @@ class TestGeometricPullOut : public ::testing::Test parameters->th_moving_object_velocity = th_moving_object_velocity_; parameters->divide_pull_out_path = divide_pull_out_path_; - auto time_keeper = std::make_shared(); geometric_pull_out_ = - std::make_shared(*node_, *parameters, lane_departure_checker_, time_keeper); + std::make_shared(*node_, *parameters, lane_departure_checker_); } void initialize_planner_data() diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_shift_pull_out.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_shift_pull_out.cpp index 156cf62f9ac4a..474da055b4de7 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_shift_pull_out.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_shift_pull_out.cpp @@ -139,9 +139,7 @@ class TestShiftPullOut : public ::testing::Test { auto parameters = StartPlannerParameters::init(*node_); - auto time_keeper = std::make_shared(); - shift_pull_out_ = - std::make_shared(*node_, parameters, lane_departure_checker_, time_keeper); + shift_pull_out_ = std::make_shared(*node_, parameters, lane_departure_checker_); } }; From db78285c34a6bdf6b1db0d3666180f680ead15fe Mon Sep 17 00:00:00 2001 From: Atto Armoo <168620037+AA-T4@users.noreply.github.com> Date: Tue, 7 Jan 2025 15:19:04 +0900 Subject: [PATCH 144/334] fix(planning): corrects typos (#9840) * fix(planning): corrects typos Signed-off-by: Atto Armoo <168620037+AA-T4@users.noreply.github.com> * style(pre-commit): autofix --------- Signed-off-by: Atto Armoo <168620037+AA-T4@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../README.md | 36 +++++++++---------- 1 file changed, 18 insertions(+), 18 deletions(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/README.md b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/README.md index f373afc2351bf..efe4a9a353ecc 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/README.md +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/README.md @@ -1,33 +1,33 @@ -## Stop Line +# Stop Line -### Role +## Role -This module plans velocity so that the vehicle can stop right before stop lines and restart driving after stopped. +This module plans the vehicle's velocity to ensure it stops just before stop lines and can resume movement after stopping. ![stop line](docs/stop_line.svg) -### Activation Timing +## Activation Timing This module is activated when there is a stop line in a target lane. -### Module Parameters +## Module Parameters | Parameter | Type | Description | | -------------------------------- | ------ | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| `stop_margin` | double | a margin that the vehicle tries to stop before stop_line | -| `stop_duration_sec` | double | [s] time parameter for the ego vehicle to stop in front of a stop line | -| `hold_stop_margin_distance` | double | [m] parameter for restart prevention (See Algorithm section). Also, when the ego vehicle is within this distance from a stop line, the ego state becomes STOPPED from APPROACHING | -| `use_initialization_stop_state` | bool | A flag to determine whether to return to the approaching state when the vehicle moves away from a stop line. | -| `show_stop_line_collision_check` | bool | A flag to determine whether to show the debug information of collision check with a stop line | +| `stop_margin` | double | Margin that the vehicle tries to stop in before stop_line | +| `stop_duration_sec` | double | [s] Time parameter for the ego vehicle to stop before stop line | +| `hold_stop_margin_distance` | double | [m] Parameter for restart prevention (See Algorithm section). Also, when the ego vehicle is within this distance from a stop line, the ego state becomes STOPPED from APPROACHING | +| `use_initialization_stop_state` | bool | Flag to determine whether to return to the approaching state when the vehicle moves away from a stop line. | +| `show_stop_line_collision_check` | bool | Flag to determine whether to show the debug information of collision check with a stop line | -### Inner-workings / Algorithms +## Inner-workings / Algorithms - Gets a stop line from map information. -- insert a stop point on the path from the stop line defined in the map and the ego vehicle length. +- Inserts a stop point on the path from the stop line defined in the map and the ego vehicle length. - Sets velocities of the path after the stop point to 0[m/s]. -- Release the inserted stop velocity when the vehicle stops at the stop point for `stop_duration_sec` seconds. +- Releases the inserted stop velocity when the vehicle halts at the stop point for `stop_duration_sec` seconds. -#### Flowchart +### Flowchart ```plantuml @startuml @@ -85,15 +85,15 @@ Then, we can get `offset segment` and `offset from segment start`. ![find_offset_segment](docs/./find_offset_segment.drawio.svg) -After that, we can calculate a offset point from `offset segment` and `offset`. This will be `stop_pose`. +After that, we can calculate an offset point from `offset segment` and `offset`. This will be `stop_pose`. ![calculate_stop_pose](docs/./calculate_stop_pose.drawio.svg) -#### Restart prevention +### Restart Prevention -If it needs X meters (e.g. 0.5 meters) to stop once the vehicle starts moving due to the poor vehicle control performance, the vehicle goes over the stopping position that should be strictly observed when the vehicle starts to moving in order to approach the near stop point (e.g. 0.3 meters away). +If the vehicle requires X meters (e.g. 0.5 meters) to stop once it starts moving due to poor vehicle control performance, it may overshoot the stopping position, which must be strictly observed. This happens when the vehicle begins to move in order to approach a nearby stop point (e.g. 0.3 meters away). -This module has parameter `hold_stop_margin_distance` in order to prevent from these redundant restart. If the vehicle is stopped within `hold_stop_margin_distance` meters from stop point of the module (\_front_to_stop_line < hold_stop_margin_distance), the module judges that the vehicle has already stopped for the module's stop point and plans to keep stopping current position even if the vehicle is stopped due to other factors. +This module includes the parameter `hold_stop_margin_distance` to prevent redundant restarts in such a situation. If the vehicle is stopped within `hold_stop_margin_distance` meters of the stop point (\_front_to_stop_line < hold_stop_margin_distance), the module determines that the vehicle has already stopped at the stop point and will maintain the current stopping position, even if the vehicle has come to a stop due to other factors.
![example](docs/restart_prevention.svg){width=1000} From 95e6b19b69dc59244d4e70361e0f95ea9628b937 Mon Sep 17 00:00:00 2001 From: Atto Armoo <168620037+AA-T4@users.noreply.github.com> Date: Tue, 7 Jan 2025 15:19:17 +0900 Subject: [PATCH 145/334] fix(planning): corrects typo in svg (#9814) Signed-off-by: Atto Armoo <168620037+AA-T4@users.noreply.github.com> --- .../docs/node_and_segment.drawio.svg | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/docs/node_and_segment.drawio.svg b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/docs/node_and_segment.drawio.svg index 182c941907f57..6cd47ffc14a56 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/docs/node_and_segment.drawio.svg +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/docs/node_and_segment.drawio.svg @@ -233,7 +233,7 @@
= node(i) + node(i+1)
- = all segment has two points + = all segments have two points From e5070d18e4c37c02bd60a4228c2faf430d602698 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Tue, 7 Jan 2025 15:20:44 +0900 Subject: [PATCH 146/334] fix(autoware_motion_velocity_obstacle_velocity_limiter_module): remove cppcheck suppressions (#9843) Signed-off-by: veqcc --- .../benchmarks/collision_checker_benchmark.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/benchmarks/collision_checker_benchmark.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/benchmarks/collision_checker_benchmark.cpp index 1d980e220ccef..c8aa9895a0451 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/benchmarks/collision_checker_benchmark.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/benchmarks/collision_checker_benchmark.cpp @@ -76,12 +76,10 @@ int main() const auto naive_constr_end = std::chrono::system_clock::now(); const auto rtt_check_start = std::chrono::system_clock::now(); for (const auto & polygon : polygons) - // cppcheck-suppress unreadVariable const auto rtree_result = rtree_collision_checker.intersections(polygon); const auto rtt_check_end = std::chrono::system_clock::now(); const auto naive_check_start = std::chrono::system_clock::now(); for (const auto & polygon : polygons) - // cppcheck-suppress unreadVariable const auto naive_result = naive_collision_checker.intersections(polygon); const auto naive_check_end = std::chrono::system_clock::now(); const auto rtt_constr_time = From 9d5c246baf29ceed9c8e1ad264d559415591631b Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Tue, 7 Jan 2025 15:42:29 +0900 Subject: [PATCH 147/334] feat(autoware_test_utils): add visualization and yaml dumper for PathWithLaneId (#9841) Signed-off-by: Mamoru Sobue --- .../config/sample_topic_snapshot.yaml | 9 +- .../autoware_test_utils/mock_data_parser.hpp | 13 + .../autoware_test_utils/visualization.hpp | 117 ++- common/autoware_test_utils/package.xml | 1 + .../src/mock_data_parser.cpp | 50 ++ .../src/topic_snapshot_saver.cpp | 11 +- .../test_map/intersection/lanelet2_map.osm | 839 ++++++------------ 7 files changed, 479 insertions(+), 561 deletions(-) diff --git a/common/autoware_test_utils/config/sample_topic_snapshot.yaml b/common/autoware_test_utils/config/sample_topic_snapshot.yaml index d9eff5d579540..2ff746b84c3ac 100644 --- a/common/autoware_test_utils/config/sample_topic_snapshot.yaml +++ b/common/autoware_test_utils/config/sample_topic_snapshot.yaml @@ -24,6 +24,9 @@ fields: - name: dynamic_object type: PredictedObjects # autoware_perception_msgs::msg::PredictedObjects topic: /perception/object_recognition/objects -# - name: tracked_object -# type: TrackedObjects # autoware_perception_msgs::msg::TrackedObjects -# topic: /perception/object_recognition/tracking/objects + # - name: tracked_object + # type: TrackedObjects # autoware_perception_msgs::msg::TrackedObjects + # topic: /perception/object_recognition/tracking/objects + # - name: path_with_lane_id + # type: PathWithLaneId # tier4_planning_msgs::msg::PathWithLaneId + # topic: /planning/scenario_planning/lane_driving/behavior_planning/path_with_lane_id diff --git a/common/autoware_test_utils/include/autoware_test_utils/mock_data_parser.hpp b/common/autoware_test_utils/include/autoware_test_utils/mock_data_parser.hpp index 5e07237e2c495..8375d3e731683 100644 --- a/common/autoware_test_utils/include/autoware_test_utils/mock_data_parser.hpp +++ b/common/autoware_test_utils/include/autoware_test_utils/mock_data_parser.hpp @@ -59,6 +59,7 @@ using autoware_perception_msgs::msg::TrafficLightGroupArray; using autoware_planning_msgs::msg::LaneletPrimitive; using autoware_planning_msgs::msg::LaneletRoute; using autoware_planning_msgs::msg::LaneletSegment; +using autoware_planning_msgs::msg::PathPoint; using builtin_interfaces::msg::Duration; using builtin_interfaces::msg::Time; using geometry_msgs::msg::Accel; @@ -97,6 +98,9 @@ Duration parse(const YAML::Node & node); template <> Time parse(const YAML::Node & node); +template <> +Point parse(const YAML::Node & node); + template <> std::vector parse(const YAML::Node & node); @@ -145,6 +149,15 @@ std::vector parse(const YAML::Node & node); template <> UUID parse(const YAML::Node & node); +template <> +PathPoint parse(const YAML::Node & node); + +template <> +PathPointWithLaneId parse(const YAML::Node & node); + +template <> +PathWithLaneId parse(const YAML::Node & node); + template <> PredictedPath parse(const YAML::Node & node); diff --git a/common/autoware_test_utils/include/autoware_test_utils/visualization.hpp b/common/autoware_test_utils/include/autoware_test_utils/visualization.hpp index c2185e65422e8..dbd3dd6638c95 100644 --- a/common/autoware_test_utils/include/autoware_test_utils/visualization.hpp +++ b/common/autoware_test_utils/include/autoware_test_utils/visualization.hpp @@ -19,6 +19,9 @@ #include #include +#include + +#include #include #include @@ -150,7 +153,8 @@ inline void plot_lanelet2_object( const auto center = (left.front().basicPoint2d() + left.back().basicPoint2d() + right.front().basicPoint2d() + right.back().basicPoint2d()) / 4.0; - axes.text(Args(center.x(), center.y(), std::to_string(lanelet.id()))); + axes.text( + Args(center.x(), center.y(), std::to_string(lanelet.id())), Kwargs("clip_on"_a = true)); } if (config_opt && config_opt.value().label) { @@ -214,16 +218,111 @@ inline void plot_lanelet2_object( axes.add_patch(Args(poly.unwrap())); } +struct DrivableAreaConfig +{ + static DrivableAreaConfig defaults() { return {"turquoise", 2.0}; } + std::optional color{}; + std::optional linewidth{}; +}; + +struct PathWithLaneIdConfig +{ + static PathWithLaneIdConfig defaults() + { + return {std::nullopt, "k", 1.0, std::nullopt, false, 1.0}; + } + std::optional label{}; + std::optional color{}; + std::optional linewidth{}; + std::optional da{}; + bool lane_id{}; // & config_opt = std::nullopt); -*/ +inline void plot_autoware_object( + const tier4_planning_msgs::msg::PathWithLaneId & path, autoware::pyplot::Axes & axes, + const std::optional & config_opt = std::nullopt) +{ + py::dict kwargs{}; + if (config_opt) { + const auto & config = config_opt.value(); + if (config.label) { + kwargs["label"] = config.label.value(); + } + if (config.color) { + kwargs["color"] = config.color.value(); + } + if (config.linewidth) { + kwargs["linewidth"] = config.linewidth.value(); + } + } + std::vector xs; + std::vector ys; + std::vector yaw_cos; + std::vector yaw_sin; + std::vector> ids; + const bool plot_lane_id = config_opt ? config_opt.value().lane_id : false; + for (const auto & point : path.points) { + xs.push_back(point.point.pose.position.x); + ys.push_back(point.point.pose.position.y); + const auto th = autoware::universe_utils::getRPY(point.point.pose.orientation).z; + yaw_cos.push_back(std::cos(th)); + yaw_sin.push_back(std::sin(th)); + if (plot_lane_id) { + ids.emplace_back(); + for (const auto & id : point.lane_ids) { + ids.back().push_back(id); + } + } + } + // plot centerline + axes.plot(Args(xs, ys), kwargs); + const auto quiver_scale = + config_opt ? config_opt.value().quiver_size : PathWithLaneIdConfig::defaults().quiver_size; + const auto quiver_color = + config_opt ? (config_opt.value().color ? config_opt.value().color.value() : "k") : "k"; + axes.quiver( + Args(xs, ys, yaw_cos, yaw_sin), Kwargs( + "angles"_a = "xy", "scale_units"_a = "xy", + "scale"_a = quiver_scale, "color"_a = quiver_color)); + if (plot_lane_id) { + for (size_t i = 0; i < xs.size(); ++i) { + std::stringstream ss; + const char * delimiter = ""; + for (const auto id : ids[i]) { + ss << std::exchange(delimiter, ",") << id; + } + axes.text(Args(xs[i], ys[i], ss.str()), Kwargs("clip_on"_a = true)); + } + } + // plot drivable area + if (config_opt && config_opt.value().da) { + auto plot_boundary = [&](const decltype(path.left_bound) & points) { + std::vector xs; + std::vector ys; + for (const auto & point : points) { + xs.push_back(point.x); + ys.push_back(point.y); + } + const auto & cfg = config_opt.value().da.value(); + py::dict kwargs{}; + if (cfg.color) { + kwargs["color"] = cfg.color.value(); + } + if (cfg.linewidth) { + kwargs["linewidth"] = cfg.linewidth.value(); + } + axes.plot(Args(xs, ys), kwargs); + }; + plot_boundary(path.left_bound); + plot_boundary(path.right_bound); + } +} + } // namespace autoware::test_utils #endif // AUTOWARE_TEST_UTILS__VISUALIZATION_HPP_ diff --git a/common/autoware_test_utils/package.xml b/common/autoware_test_utils/package.xml index c328f37ba357d..740e7f840141d 100644 --- a/common/autoware_test_utils/package.xml +++ b/common/autoware_test_utils/package.xml @@ -8,6 +8,7 @@ Takamasa Horibe Zulfaqar Azmi Mamoru Sobue + Yukinari Hisaki Apache License 2.0 Kyoichi Sugahara diff --git a/common/autoware_test_utils/src/mock_data_parser.cpp b/common/autoware_test_utils/src/mock_data_parser.cpp index 6e7002501bf30..29aed75357441 100644 --- a/common/autoware_test_utils/src/mock_data_parser.cpp +++ b/common/autoware_test_utils/src/mock_data_parser.cpp @@ -65,6 +65,16 @@ std::array parse(const YAML::Node & node) return msg; } +template <> +Point parse(const YAML::Node & node) +{ + Point geom_point; + geom_point.x = node["x"].as(); + geom_point.y = node["y"].as(); + geom_point.z = node["z"].as(); + return geom_point; +} + template <> std::vector parse(const YAML::Node & node) { @@ -285,6 +295,46 @@ Shape parse(const YAML::Node & node) return msg; } +template <> +PathPoint parse(const YAML::Node & node) +{ + PathPoint point; + point.pose = parse(node["pose"]); + point.longitudinal_velocity_mps = node["longitudinal_velocity_mps"].as(); + point.lateral_velocity_mps = node["lateral_velocity_mps"].as(); + point.heading_rate_rps = node["heading_rate_rps"].as(); + point.is_final = node["is_final"].as(); + return point; +} + +template <> +PathPointWithLaneId parse(const YAML::Node & node) +{ + PathPointWithLaneId point; + point.point = parse(node["point"]); + for (const auto & lane_id_node : node["lane_ids"]) { + point.lane_ids.push_back(lane_id_node.as()); + } + return point; +} + +template <> +PathWithLaneId parse(const YAML::Node & node) +{ + PathWithLaneId path; + path.header = parse
(node["header"]); + for (const auto & point_node : node["points"]) { + path.points.push_back(parse(point_node)); + } + for (const auto & left_bound_node : node["left_bound"]) { + path.left_bound.push_back(parse(left_bound_node)); + } + for (const auto & right_bound_node : node["right_bound"]) { + path.right_bound.push_back(parse(right_bound_node)); + } + return path; +} + template <> PredictedPath parse(const YAML::Node & node) { diff --git a/common/autoware_test_utils/src/topic_snapshot_saver.cpp b/common/autoware_test_utils/src/topic_snapshot_saver.cpp index b2cb2a17c9621..bd9af2d5672b8 100644 --- a/common/autoware_test_utils/src/topic_snapshot_saver.cpp +++ b/common/autoware_test_utils/src/topic_snapshot_saver.cpp @@ -25,6 +25,7 @@ #include #include #include +#include #include @@ -46,7 +47,8 @@ using MessageType = std::variant< autoware_adapi_v1_msgs::msg::OperationModeState, // 3 autoware_planning_msgs::msg::LaneletRoute, // 4 autoware_perception_msgs::msg::TrafficLightGroupArray, // 5 - autoware_perception_msgs::msg::TrackedObjects // 6 + autoware_perception_msgs::msg::TrackedObjects, // 6 + tier4_planning_msgs::msg::PathWithLaneId // 7 >; std::optional get_topic_index(const std::string & name) @@ -72,6 +74,9 @@ std::optional get_topic_index(const std::string & name) if (name == "TrackedObjects") { return 6; } + if (name == "PathWithLaneId") { + return 7; + } return std::nullopt; } @@ -196,6 +201,7 @@ class TopicSnapShotSaver REGISTER_CALLBACK(4); REGISTER_CALLBACK(5); REGISTER_CALLBACK(6); + REGISTER_CALLBACK(7); } } @@ -243,6 +249,7 @@ class TopicSnapShotSaver REGISTER_WRITE_TYPE(4); REGISTER_WRITE_TYPE(5); REGISTER_WRITE_TYPE(6); + REGISTER_WRITE_TYPE(7); } const std::string desc = std::string(R"(# @@ -253,7 +260,7 @@ class TopicSnapShotSaver # map_path_uri: package:/// # fields(this is array) # - name: -# type: either {Odometry | AccelWithCovarianceStamped | PredictedObjects | OperationModeState | LaneletRoute | TrafficLightGroupArray | TrackedObjects | TBD} +# type: either {Odometry | AccelWithCovarianceStamped | PredictedObjects | OperationModeState | LaneletRoute | TrafficLightGroupArray | TrackedObjects | PathWithLaneId | TBD} # topic: # )"); diff --git a/common/autoware_test_utils/test_map/intersection/lanelet2_map.osm b/common/autoware_test_utils/test_map/intersection/lanelet2_map.osm index c5c5b7b1fc657..9f28ed79a91ae 100644 --- a/common/autoware_test_utils/test_map/intersection/lanelet2_map.osm +++ b/common/autoware_test_utils/test_map/intersection/lanelet2_map.osm @@ -1,6 +1,6 @@ - + @@ -8002,391 +8002,6 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - @@ -10004,16 +9619,6 @@ - - - - - - - - - - @@ -15586,6 +15191,181 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -18669,142 +18449,6 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - @@ -19364,12 +19008,6 @@ - - - - - - @@ -21131,6 +20769,68 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -22269,15 +21969,6 @@ - - - - - - - - - @@ -22853,6 +22544,60 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + From e2accc57e9d0b1328641bd88a48e446c74879af3 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 7 Jan 2025 16:21:57 +0900 Subject: [PATCH 148/334] fix(tier4_camera_view_rviz_plugin): fix bugprone-parent-virtual-call (#9815) * fix:bugprone-error Signed-off-by: kobayu858 * fix:fmt Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../src/third_person_view_controller.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/visualization/tier4_camera_view_rviz_plugin/src/third_person_view_controller.cpp b/visualization/tier4_camera_view_rviz_plugin/src/third_person_view_controller.cpp index b7d754b02d4bd..386c8cdfb0b13 100644 --- a/visualization/tier4_camera_view_rviz_plugin/src/third_person_view_controller.cpp +++ b/visualization/tier4_camera_view_rviz_plugin/src/third_person_view_controller.cpp @@ -184,7 +184,7 @@ void ThirdPersonViewController::handleMouseEvent(rviz_common::ViewportMouseEvent void ThirdPersonViewController::mimic(rviz_common::ViewController * source_view) { - FramePositionTrackingViewController::mimic(source_view); + FramePositionTrackingViewController::mimic(source_view); // NOLINT target_frame_property_->setValue(TARGET_FRAME_START); getNewTransform(); From 3aa84a0fb2a9796a8e54f99e44e89ae3a125131e Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 7 Jan 2025 16:23:13 +0900 Subject: [PATCH 149/334] fix(system_monitor): fix bugprone-exception-escape (#9781) * fix: bugprone-error Signed-off-by: kobayu858 * fix: clippy Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../reader/hdd_reader/hdd_reader.cpp | 83 +++++----- .../reader/msr_reader/msr_reader.cpp | 146 +++++++++--------- 2 files changed, 123 insertions(+), 106 deletions(-) diff --git a/system/system_monitor/reader/hdd_reader/hdd_reader.cpp b/system/system_monitor/reader/hdd_reader/hdd_reader.cpp index 740f841382f47..098f4240782ae 100644 --- a/system/system_monitor/reader/hdd_reader/hdd_reader.cpp +++ b/system/system_monitor/reader/hdd_reader/hdd_reader.cpp @@ -43,6 +43,7 @@ #include #include #include +#include #include #include #include @@ -655,48 +656,56 @@ void run(int port) int main(int argc, char ** argv) { - static struct option long_options[] = { - {"help", no_argument, nullptr, 'h'}, - {"port", required_argument, nullptr, 'p'}, - {nullptr, 0, nullptr, 0}}; - - // Parse command-line options - int c = 0; - int option_index = 0; - int port = PORT; - while ((c = getopt_long(argc, argv, "hp:", long_options, &option_index)) != -1) { - switch (c) { - case 'h': - usage(); - return EXIT_SUCCESS; - - case 'p': - try { - port = boost::lexical_cast(optarg); - } catch (const boost::bad_lexical_cast & e) { - printf("Error: %s\n", e.what()); - return EXIT_FAILURE; - } - break; - - default: - break; + try { + static struct option long_options[] = { + {"help", no_argument, nullptr, 'h'}, + {"port", required_argument, nullptr, 'p'}, + {nullptr, 0, nullptr, 0}}; + + // Parse command-line options + int c = 0; + int option_index = 0; + int port = PORT; + while ((c = getopt_long(argc, argv, "hp:", long_options, &option_index)) != -1) { + switch (c) { + case 'h': + usage(); + return EXIT_SUCCESS; + + case 'p': + try { + port = boost::lexical_cast(optarg); + } catch (const boost::bad_lexical_cast & e) { + printf("Error: %s\n", e.what()); + return EXIT_FAILURE; + } + break; + + default: + break; + } } - } - // Put the program in the background - if (daemon(0, 0) < 0) { - printf("Failed to put the program in the background. %s\n", strerror(errno)); - return errno; - } + // Put the program in the background + if (daemon(0, 0) < 0) { + printf("Failed to put the program in the background. %s\n", strerror(errno)); + return errno; + } - // Open connection to system logger - openlog(nullptr, LOG_PID, LOG_DAEMON); + // Open connection to system logger + openlog(nullptr, LOG_PID, LOG_DAEMON); - run(port); + run(port); - // Close descriptor used to write to system logger - closelog(); + // Close descriptor used to write to system logger + closelog(); + } catch (const std::exception & e) { + std::cerr << "Exception in main(): " << e.what() << std::endl; + return EXIT_FAILURE; + } catch (...) { + std::cerr << "Unknown exception in main()" << std::endl; + return EXIT_FAILURE; + } return EXIT_SUCCESS; } diff --git a/system/system_monitor/reader/msr_reader/msr_reader.cpp b/system/system_monitor/reader/msr_reader/msr_reader.cpp index fc7bcab795be0..89f95d05c282e 100644 --- a/system/system_monitor/reader/msr_reader/msr_reader.cpp +++ b/system/system_monitor/reader/msr_reader/msr_reader.cpp @@ -212,90 +212,98 @@ void run(int port, const std::vector & list) int main(int argc, char ** argv) { - static struct option long_options[] = { - {"help", no_argument, 0, 'h'}, {"port", required_argument, 0, 'p'}, {0, 0, 0, 0}}; - - // Parse command-line options - int c = 0; - int option_index = 0; - int port = PORT; - while ((c = getopt_long(argc, argv, "hp:", long_options, &option_index)) != -1) { - switch (c) { - case 'h': - usage(); - return EXIT_SUCCESS; - - case 'p': - try { - port = boost::lexical_cast(optarg); - } catch (const boost::bad_lexical_cast & e) { - printf("Error: %s\n", e.what()); - return EXIT_FAILURE; - } - break; + try { + static struct option long_options[] = { + {"help", no_argument, 0, 'h'}, {"port", required_argument, 0, 'p'}, {0, 0, 0, 0}}; + + // Parse command-line options + int c = 0; + int option_index = 0; + int port = PORT; + while ((c = getopt_long(argc, argv, "hp:", long_options, &option_index)) != -1) { + switch (c) { + case 'h': + usage(); + return EXIT_SUCCESS; + + case 'p': + try { + port = boost::lexical_cast(optarg); + } catch (const boost::bad_lexical_cast & e) { + printf("Error: %s\n", e.what()); + return EXIT_FAILURE; + } + break; + + default: + break; + } + } - default: - break; + if (!fs::exists("/dev/cpu")) { + printf("Failed to access /dev/cpu.\n"); + return EXIT_FAILURE; } - } - if (!fs::exists("/dev/cpu")) { - printf("Failed to access /dev/cpu.\n"); - return EXIT_FAILURE; - } + std::vector list; + const fs::path root("/dev/cpu"); - std::vector list; - const fs::path root("/dev/cpu"); + for (const fs::path & path : boost::make_iterator_range( + fs::recursive_directory_iterator(root), fs::recursive_directory_iterator())) { + if (fs::is_directory(path)) { + continue; + } - for (const fs::path & path : boost::make_iterator_range( - fs::recursive_directory_iterator(root), fs::recursive_directory_iterator())) { - if (fs::is_directory(path)) { - continue; - } + std::cmatch match; + const char * msr = path.generic_string().c_str(); - std::cmatch match; - const char * msr = path.generic_string().c_str(); + // /dev/cpu/[0-9]/msr ? + if (!std::regex_match(msr, match, std::regex(".*msr"))) { + continue; + } - // /dev/cpu/[0-9]/msr ? - if (!std::regex_match(msr, match, std::regex(".*msr"))) { - continue; + list.push_back(path.generic_string()); } - list.push_back(path.generic_string()); - } + std::sort(list.begin(), list.end(), [](const std::string & c1, const std::string & c2) { + std::cmatch match; + const std::regex filter(".*/(\\d+)/msr"); + int n1 = 0; + int n2 = 0; + if (std::regex_match(c1.c_str(), match, filter)) { + n1 = std::stoi(match[1].str()); + } + if (std::regex_match(c2.c_str(), match, filter)) { + n2 = std::stoi(match[1].str()); + } + return n1 < n2; + }); // NOLINT - std::sort(list.begin(), list.end(), [](const std::string & c1, const std::string & c2) { - std::cmatch match; - const std::regex filter(".*/(\\d+)/msr"); - int n1 = 0; - int n2 = 0; - if (std::regex_match(c1.c_str(), match, filter)) { - n1 = std::stoi(match[1].str()); - } - if (std::regex_match(c2.c_str(), match, filter)) { - n2 = std::stoi(match[1].str()); + if (list.empty()) { + printf("No msr found in /dev/cpu.\n"); + return EXIT_FAILURE; } - return n1 < n2; - }); // NOLINT - - if (list.empty()) { - printf("No msr found in /dev/cpu.\n"); - return EXIT_FAILURE; - } - // Put the program in the background - if (daemon(0, 0) < 0) { - printf("Failed to put the program in the background. %s\n", strerror(errno)); - return errno; - } + // Put the program in the background + if (daemon(0, 0) < 0) { + printf("Failed to put the program in the background. %s\n", strerror(errno)); + return errno; + } - // Open connection to system logger - openlog(nullptr, LOG_PID, LOG_DAEMON); + // Open connection to system logger + openlog(nullptr, LOG_PID, LOG_DAEMON); - run(port, list); + run(port, list); - // Close descriptor used to write to system logger - closelog(); + // Close descriptor used to write to system logger + closelog(); + } catch (const std::exception & e) { + std::cerr << "Exception in main(): " << e.what() << std::endl; + return EXIT_FAILURE; + } catch (...) { + std::cerr << "Unknown exception in main()" << std::endl; + return EXIT_FAILURE; + } return EXIT_SUCCESS; } From 19f7f95b8a25fc7deb748db8671a33d0d835bed7 Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Tue, 7 Jan 2025 18:42:38 +0900 Subject: [PATCH 150/334] feat(ekf_localizer): check whether the initialpose has been set (#9787) * check set intialpose Signed-off-by: Yamato Ando * update png Signed-off-by: Yamato Ando * style(pre-commit): autofix --------- Signed-off-by: Yamato Ando Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- localization/autoware_ekf_localizer/README.md | 1 + .../autoware/ekf_localizer/diagnostics.hpp | 1 + .../autoware/ekf_localizer/ekf_localizer.hpp | 1 + .../media/ekf_diagnostics.png | Bin 142232 -> 145097 bytes .../src/diagnostics.cpp | 19 ++++++++++++++++++ .../src/ekf_localizer.cpp | 16 +++++++++++++-- .../test/test_diagnostics.cpp | 13 ++++++++++++ 7 files changed, 49 insertions(+), 2 deletions(-) diff --git a/localization/autoware_ekf_localizer/README.md b/localization/autoware_ekf_localizer/README.md index aad65da2516d1..802bf7dbb16c3 100644 --- a/localization/autoware_ekf_localizer/README.md +++ b/localization/autoware_ekf_localizer/README.md @@ -191,6 +191,7 @@ Note that, although the dimension gets larger since the analytical expansion can ### The conditions that result in a WARN state - The node is not in the activate state. +- The initial pose is not set. - The number of consecutive no measurement update via the Pose/Twist topic exceeds the `pose_no_update_count_threshold_warn`/`twist_no_update_count_threshold_warn`. - The timestamp of the Pose/Twist topic is beyond the delay compensation range. - The Pose/Twist topic is beyond the range of Mahalanobis distance for covariance estimation. diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/diagnostics.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/diagnostics.hpp index 20a77354c0996..b194c3e956341 100644 --- a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/diagnostics.hpp +++ b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/diagnostics.hpp @@ -24,6 +24,7 @@ namespace autoware::ekf_localizer { diagnostic_msgs::msg::DiagnosticStatus check_process_activated(const bool is_activated); +diagnostic_msgs::msg::DiagnosticStatus check_set_initialpose(const bool is_set_initialpose); diagnostic_msgs::msg::DiagnosticStatus check_measurement_updated( const std::string & measurement_type, const size_t no_update_count, diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_localizer.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_localizer.hpp index 1b437f26e9c7d..0561e250298ac 100644 --- a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_localizer.hpp +++ b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_localizer.hpp @@ -119,6 +119,7 @@ class EKFLocalizer : public rclcpp::Node double ekf_dt_; bool is_activated_; + bool is_set_initialpose_; EKFDiagnosticInfo pose_diag_info_; EKFDiagnosticInfo twist_diag_info_; diff --git a/localization/autoware_ekf_localizer/media/ekf_diagnostics.png b/localization/autoware_ekf_localizer/media/ekf_diagnostics.png index 234b2f1e19b6dd701dd1253b853580ab759f725d..a1561c3f5270709791a19557b874dfae1d6f56ba 100644 GIT binary patch literal 145097 zcmdqIV|Qi2yD!?^LC3aj+qTuQosMnWwv&!Jwv&!+yW^}lE9N@sv+o}FzwbEb3*35B z6IC@ao>}$7Gb5E0B;jFjV7`3$0xvBkrt;;>*Rn5Pz8ynBejcGWh_L#sz@0^;)u29$ z50q)d=RUTJxTcG$y}66Kk(1dM3p;yTGkRweCo?lUXG?pRE3jUH&ql0PYML&hPG&|f zR`zy8YF4&pp9jBuVPRrnJ8W-aW;x1FCk*)Jjx7WV>^rpW9B$6OEPgcpZfBJ z=!>+Nu$o8C`Icvn{5|N;%}V?0`RmUxBe>xD+A)PRI#I16C9(U|h?JrtvUeFNX_*F! z21aTV1Kd}J*H!GWzN*LV+mCl<6GFHO3g5i=5nsO3Y5wC|?ql6!U%~vDS091(BJpT& zab+~|F;TfM@HlKwWoLy{QAJcMSRVkGe;eb~Y7Q!B;>tig^qkKsg-;TK^0PhpjB=m! zzi!TI4lk5?S`*jDI;FlstIfi-_<+? z1KXjSx(82A|Jz3iU_ zB;1$X^SfgzB&Ag1jgNEsA5sE!QJ%674u_?Ws+#kxIK3#onwcMz(H@!yEZ!P#;~fL( z?F*?+WRttq!^|NbnoONfs+U`??ue#dDA~tyly+A`yqC8|9rxb*d|X))eT8hVmr(vQ zoYKl4UhaqrR^d;snw(ib7~~4V(HobdeTFI*8je@0_#X*B?tLp$0DSvbihV5f&p%go zfE&++buZ#dY#mUA1nc>msuY!iKNTtwF_K*tw&p_IJ&=o{Lw3#HlEvTj?o47X)&u8` zPp@xc4y*K8aua7#N4Q)8irch;*xihGRP*Vc5& z$=>R$w`xd=y{{}kKxs4|xLl4rAlp9efy!wjzsg&UG@}xqtM)3uyGGhgg4tlBjV;BJ zBtn6S?~eb_)Hc$55Ti!ZQ(0vp72=O+dP?b|mDapt&>kbna(~lXFSiYsL)LBN$ZGeg zg+#1Zbg7>f$Yud?diR|pmHK2qXo)`q+O1_Xt(Z-yW!7sF8 z4L};!vye58yuDgQ5HiRoosa!}tgB_}bx?pnRIGrKqY*-*H%QH9E0|}R&#D> zJVO}??KW_PAyrS=akE8#e>ko{@n|OkP(rj}&<{bgpVsKiA;Q#}Z6tws->S>7eZug` zi8B~>zCmzgbyl|cX0wFtr}>?GAOn(vO}-OgMza{r?)IlA4e_TKa>`Z^0^?3pd|FO> z1unI-86pf;V@o6dGym~mUs!8#J-UB*tOjn1Q{KISYl$1Ozpm|NNSfVnw%`T%{W`Ri zsqjvi8eJA5At$VP<#%H8?Ca$!(X|~!N^glp($QWRLfh%~R2oc9mZMb2lBlt85Xw%ZfBPokMSU)T_czNf-=Yxs%Hm6qgJ%SNvBI&n} zd)h@>jEL+h^!)1vmn)YfARE%UWdWVUwWRC1-Q1JGJX|aITTds&+NsZ z&MxWN!aY_ufG(t+?4 z6!;;QYEXjpUw85fDHj;qHIq&S_@5uPraIbKK^eJ&SbHj4cMn?C~QR zw2^ibU}mrr&s^0=C)MKzS1l4-WF_Hx| zHa?F$dfzV*VB((^n=U4X=i~rT%WO1lt}?)-MD^A{HE{lQr=9FNJ#W#BifFC({1U=I zLW14vg5qz@j_o!|O@biJ(;(}1zDmsNcAoGQnM*dlM}huQn<`5}GL70`K1}y)yTqf_ zYLn$NOO>Ay#50;>ik#?@3F@lVr0JsXwVhe_TSOYZ3#*zcZ}L62Xuw0Wg-cbAjSNwf?D0{F61GNJ)q2%lpr z<=!_c0$P4@sAFQ!Ss`&zkEJTF6>E0ztYXYbp_hPYGF3295U(RAb6({QF2cN;aVKY9 zT#!{O?|~I6>jzG(Jer=}mc*c^UFIEwEjoPg6F;wN5@ESb;-s%=NryZtobdeN3LNrS zimPwYV1%$wwhtw=8*)8iV(n>rbg9;_m+OJOE{vQQm8aO|Bx(h2_MY}9ETpOCcDW9! zmEdG%6|d^{h3Af~YR=5b=I)X@ZneC8Z{@p6!VWx2P&AWlPdcV-R)lHI8L9G-lBdx& ze13a!%n(o|;>T|UejmeJI>jTaP!SL7KhzMV2|Hyib)KiA29%ThSQJjf#J*yRWhlyAL4Lf*+cJ67~ z+kxl9SLQvK=}H06cnTCX zSfcxyfcMgsrRmE%y1DqB&rkdr_F%KR%u37mV$C)O4?y|+{z%Hjq;dc_t~j*#l5Xtc zQ-fn3LW{dxf7_yu2@jI_L1p}HE?K&#s`&XwkxUA**m3_eEVnr>_S?_vQ`l6d;^Z#s zJV6%1Up7pVYK6w-U++w(bL7F^(Qx-r9g33KK;keN>}<~9TYEJ`dt|$YA_#hpkl$!D zh{vJ!qz)#Z!&3=MoV^w(;&5nHYD-t{>k%G*FM3ag4o+oDIh^Kfw*`Wmh@UQBclh#& zDVpA2V|o_J5sUbA-!R^NV@-0IUtn>{7pJhucwdK&QLvrj+;J~-cqsoxW^aCO9b18w ziYRDr0OTYbFtXsW0<;raJL9eXIWi^uy+j{>ahjb)*nFBgROe5sb2$qt_mo6N2S1+9 z>6GNin$E1&;m&N2?n~XOU$a@Y;n=M79VW~y<8nMbT|!H;=#r`2wXk}=Ak$~C>pauH z(y)tLs29wW$Mp5+vg5X6+?t*#QTs*QubPqOU}yWtMMh1iFl@nt&A z>NPWNS8xk;e5SvTnvxyM(A`Ez(*YW(Z`=suRv5HeKirDWzO64Y6*`ZIj>dW~5hCe* zZ#om#2f>z6x)!eKbe3~^aIv0>?_Wq*6D^YpW2oyH@XqRQICN%K ze)jSmm7;byF3h`qJca3f?5cwwwew5n_e^$gR5v!==v1VRagKvxxlF^D%J{^b za@B@?UOv>rC<#alM9MuBvmI%BG$=n*$qgujiLJsXt zA>3v4E=%Njw&$7mBPsWEdih}n-3@3=I7}%t;&sj#vg#BIH8-*D2H#&fY{|(R@a-Qg zB_L1@d*!}zUU)govk6IJ5|;%OL8*WN0eWodpX zqld8{s9kAsb#xU@VsvU9>5>bbP#wPgW}RkBTr7N8MM#}AI9`%HN7|{f{yK9sj19%` zBg)Vhhc^ylwza_kp?c!H1MTNj26gqdUlDn(b_i0J3)50JL6?vGL`U4W3}?q23Rx?e z4n4#BdHP=~wLYq6WA)ak8+c~Vb^aPS5?BFnD8S4)g>5G)_ZRYm&6$H<*`nu4>ug(oY9j78$7%4y1t)JH*!h;`}G3?QI{CJ zw(I3o8$M2I$77jRLYVJN`Xb`vh+sKe_g)fmx{8Z;CB%n6P~T(+D1aW^4+Tp-R@tj3 zCI?})Q%&8I^-P>+F_%Mx%1oNo`q%-NXe0+$pjkngGoXhLp;QYv(1iza?btyj2Nc!w@ zM8jdbHNJcSt=rQA%Q`fk+TUP}2iBW0(NJ=m$z_IaVb|^M#kLo#f5`nI?!E30WR+E? zGxph8?&4UGO73A)<g3rS(xbivxkN3&dfG|xQ^)c`sPDb zGaKHx!ivZvms^;OM!Ec6ePMN4?aX)9&PKe>9*@j!t7qpbtbD%PaKs`-+0Gt)$!2Idk~CV~uW zs0gndBe+ma#o(g@v}oYhXyb5On4iRC)WJ+Tzmn~``g)&@mH-j_4Wy^(V5^? z^9SL-tf3(^+!T}DwSOdveAF1TWDPAbij1>)X!yy_i`&UYAUP7?P%P0w9nk;*ALsK5 z9~59ZDTzvmjaXBcD7p>BaxxCv>^h2M;vDfdO8UUZ4pC5 zibX$N6P0@@w^H5;3|6Uj+$tH#gSLi@8zL10qvpNm$P*_ASUT-dsnPcs%!8Hb?0QhN z+qztG9LQ)B|MVD8xYbZScU6v#c;j(WikZIA=mo)PNMhIa+9;02Yl!8PrH@Kh(@Oa< zMq|aAJKiIt1(g_^4L+O?1~+X1MUO|wddtM+I0PeqgDPyAcCxA|Nv0bcey-lCR43G~ z(%GS?brs&_G^y6;^0(okkdQg&-bFUZM1Eus`qkQWpWm{U>VQQ;-y=nj(On9QmmKLt zlS$85fjV-YpS8v;5E3m)b1~inQNFoIYu^;I(dARuJd;U4X=@PwbewPzS036=eaABnMj^@x5&M>R&wAD_n_qN+jm=qkI|}qTSyoO3 z!tkuqQB($Ew7aC}g(o{4q%aq(K}AJT4Bp$cX)xLrV$D}etMCRP6<B{cMy~h7WWP~zDG7zY--S@Scve9X z>oa6bF+7E&7fRPspSRcF@A3`&PGnRTq(D=w#E#BpG@47bT=k_1Z>%IrZ(;tpA5MXD z9Qk=m;s0EA!g>1zuy)^hCgL{z?z7d5*}KYfy>QigW0rsH*`Y-@)5Vt{U73ChFe!U_ zDB;Y^cJcOb!pk0-P;4?$KN0fF+zJO?ws(nq#s)~7ThSnef_1|yB23svRCG{$VUX9Y z>yz2!d=Ha$#gvaBHbOBLW70@c{BVefU^w>o6fdI7DrlE7+_fCLGDCrv=d*@S??yo8 zcWmH0EQZdK_92;&J_OF8?CBUtnOvMScyOrzI!oMmdyC8s8JS-z?U9C<1AZ<>A4Rz(DJA+E4J?BBcYM_Z8uF_h zw(^K1oTV{voN+ERcu-uFO;y;_YEFFaikUsm_v}?=+%$FFfMCi|uka3?|5w47d{$hq zksgf>EOxJLlnd1!O`&33LbZm|s?w*p*)BcZCoM=`oL>i%QL@LIKXLmESEMyQ7S78s z@p}a}TG=@fM^qraB`?d6j;veVB8uxH0aR&>EbpB7ThvXaBjUuuKgl8pE~uidt8tDY z4xdm;%XzuW3#_%oJoT{7Vv0MxUANYk+tBTue`F z-t;U0Xe@#Hh>_fQq~9662&f)fQq$blbPtDsV3bcg;z&mGrPV*z_~ea3B0-aTDnSJY1+;DSrpCmLklVYb+n&;mS1w=Igtk%=L_yX&_4* z*lbY(GtvCcFyzG!IqtH%au3eehE(0-%B+`^`1rt}8L`Gpu4>3dg=%yu#Q)S=ljbE15gfMNgZ$)4zw4h7HYKZC<5U7$ zXZs!my3e0sX3q@x6tVda-;iqj5`UTEv$5(6_@!9g(KLs5PudImk2uPqc^31^zuDN_ zFAB}Kc`$>yP%3<7(~xQPjHO8AoLv5`MTKn(ZVj=m(~wneln*?7Y<%{;WYX8-%Kaf| zXKFk_l!sNHb!Zj_Tq}pBTV;yv!#`p&*%#q}gSVKJ-NM4Or!*LFKiTOaTYf_B0uFiQ zNU4A8Zx)Ag){bC|UdTlEjWN3Ss1P;tv3ts4{)O}PQL2hlQXF+mm%~;dSfBj7I6Ew&3RN~ahZx|Kqz;Z794KqXR#sFoJEMICJM)UY_ zQ;M;|kaKdv^W(!oz+x3>S}MUl+dLNJ!N;pJPcA>5$Cch4BOG;3pdw#|V@$WIs;;L+ z#~6wQJ|(+8J&F@7lfR_E$2O>IUSQ)M!4>aA%x~ZRYUjyUKbQK@Umk#Y6o3UXyu7Y;e9FLs2}@~V z_@}A~j7u6h`9^&{rn{B0`IUmq>t!w7zOoEjDUaO}Ewek-eB7(c(Vah6LZ>tn$+Ta(M^UOmjeEuur>`tSU6W6ty-cqI zkXlYPWAS>9w9+K##Wd>Y|~(V(cXW8H_LKUV9blau13=wEO5S8K#F`aO&$)waDm_@0|g z1{w7xfxZB6i5~@S)hKKCH)Uhx=yY#gyw#^Gza+Mf_%wQn#JS@!tKkrrr6o zRX8?L+g;*Jx1u8&m_x8?OZ^REt+*R8K!lB)bVtdQpK*4BGczb4KGI5AS1Uw0T%$F@ zSx@Yq={6uFwU8+HT0rLy=NZT8C#_N$PZL#i@E18NRkzLMjS27(3f1&=x^ePMI}>Av z($JPAE~FhFbk}h6&)3@7pUX_uWnd}Oq0R#>$tl$#meQ7SC#Hm94OlHSQ~S{{QAZWM zS@ZFre#)L{*W)R0%}HKITo&_N)SB(&_Mj(R1CIOd-aGqGtaC_sf6|l#hurk+1a12P z@cL(*`L7o*IQ?_Z2(UeAxujWMHKt5}oW+_Be+Ai=p5K$iFdm}G-LAFI5pDA=H1CYO zd3-;0G&7WFT5IeNA8W{3A4|yss&P^>dkD%`909wzoa2v20oET59jxt>+vvRwm)D29 zrA53bN7w56SR#CM8G3KjkCz>t-&y!0r<_YsTOap!lC~KtI<68V-?-MEJ$*^uwwQ3?u;9#f`M@Hmek7~&OI}X|_Bxsgzhjwnx*6WJ^Z4+Ya95_w zSsXZ%1Mj{RAK{3Z&K04-IQzRA-F;6xM$IPRrZyUeA>5T zHgQBG`|af|py$WY={-DMBh7E6*U5(baj7}Q(RG`8)C`d>#DFAtD*hAWVPI%a#vyb2 z&F%STS&~9OCVM?Lo1FNzX*d3CJnQc`_~2#?()iPW+@)H~{$JP*womkB7rfX@zxfh{ z^E9V0bl+iA+7G=a6-Vt}0g@TFcHXDy@noX|VQZ(-4mS^SJbBHvos20N-lZ(>TJ9W? zvefBZEtlRMpQc61md{QzZ?d9UbHimvIdMXV1&uvhr4X?or|vtfYUNq0O}k4tLhGcj z&k7w{Jd1rDn=}z?ESn?`tp4>tft6(z>=dOz&(*%rbmK>5%_75IeC1T`?EI9+ZCUr` zB4k%X@>qAa63-%7b~GmOQ1+KhUl$Gu94z3D+?Gj-|?qDC}? z2FUnMH^&V$QcE>1ctqTk6O&P!Lq^Z(Zz=g?gC)0)f58$rp|1sdhsoEI zCu_%%!O|G7%O7)VVYQ zH&xqNk*lo@6at}_Mv;T|T!E^rsy#;h-(p2xGJ|#5UQv;$a}=eB{Dz70xC#F}kZ(~R ztd0cPm(@MR7`ogHuPg`yJz0A`aHONXlqlWUUN1Plk;3jKdIX@Gc+Z{`DER0iMhQqc zkNlPCp!DFzD3PlReI(Z$kxLJEx=+g7UR}? z3Ap(@lIe5$XLxRz0NRT&b{Ggn@D1RTzE&+_Hv}QaZhZmE+qHYtdX{tZ!I2GqR8(yR zNtyq+`McV$2w3Sskj%l&SZ5%FH&|ITSX84jVKj! zVozy%oTe=4K>d8+LftoAefF4@*VY2rzi#GkP(umz>1~vlK>nIl}PMEMSo{q|4|Bt;U zLH#zYJ%)zNPbxpp+A``*F8_@p((4&h+9hiAFmrxd5*6-a9*_=){3_vD)+RmMb(o2r zPVQ^P3C&4jnDVxjE;~F_0c;AV$e5Ur>};gjci5 z8C}wD(%5ejk>}kKmvw4J9O36UYWh{r28nGc)|g@lzWVZ2J@}?}r%PuhsR0Vfrn|U@ zgRH;mW7b^@=!%NzNr3T9OtRQ zu_4Z~a-T@$T;9cWRkUf6E0OpgCJXZ1j1TQ6m7RY%zUy4p>a7#gr!`LwpzKY2cSD|2 z9Ob;<8f;xsdhe2paYap+FgdLH2>ATUWb&Ni(~`r?nGD+;XGL6G-op&uUaa;6 zd=l*jFdY9T-FoQ=$?gJEb95lHhQjWF3@sP#LBuIu)u(^$ztE{yablR$h%ZpW0>>^z z-+H`IH#RjKWV&wddj>1mE7$H{p_j{`N;4?f;#f#9S8j)7^`0%46{a`rsWv=9Cn~-% zw5|-9Huj}f!jhYt)2FOH4v&9UQqO`5ql;tuGB6hk(eir9({c2jV|+ci!#z7Yb+F$v zA!#WYpuoYP##r@Benj!wnltVm?zIRi_ik__*cduDATFJz9k1uH3;tZ9jW)WJXwh}q z>vaT!9**iV7&v=yq~}juGU%H6LzvcZYl-5ff!IWr`(}j=bzp}lH_i0gjER-Io>lSb zg498eZcZKHTj|Q33zf@`oDFfa6dpJ#oFQE!#Th84_%HKcwn4&lwdD8?{5FDYXt*C& z@|>-)&X>|!j7K13_#306l?ST&ejluO>)h)%$wkvHC*6{q=~m+n za-Q9k@Un3wKR&`UeiFO$n5_&%o$zooUQ*@cEry!gUleWs-JLAQjFdd3fowh>3)IyR zIzCXWowLn?)jN(acy8Xu5Q_S!gc@GKrPxdt8!3lyrT8Z@ur6#1u+R>9)JPq3m5QHpIb4l)SR_BW zmesem$fSMm89J{IS!eL~nmS?>WLPH6GTmsg_Sp4$dVKB_Kzu;0Z-e0wuO1A`Y!=nO zSB>{TB@%p%ry%1-JE>OAZc^IR{~DR*@)KF)dcIHX(d&AXPacflTinQb7npL>^(V_r zXVg*&n>K)~-U(oSH(HbOz=5Ls8?A3zi%u(3u5*|(E`)ov)ryun@xr4~l9eXo%c~ho zn^h|WrQQtpu9)CGD!)N~wBqBCkM7Lt3pXozu}w^*qt2tSDQ?jeqEFi=bTRU0(U}o4 zTyqM+?&~pQx}R7n`bcJEvGZpj2w=fD9`c((vO}4k^o>Lj?mJ+7!V{#}0(x($M5@!n z7|-H!jY<|%9A4L~8%sI++b;xuCq4{yo|8PW-- zyK5uc&2zK2@|uD9Lcu%?Y)!@Q)lMG0`3j_-uCfFG^=mZsz^LX<GvGaZv@z z+Vh9E8t-FLPVOM5Hq+-hTUhhu^#+0HvKgF?;QK3j9o6h6P(MeH8+!_-#|oRSn8R5S zU%;#TzWWQt4*n2i^*;8@A&B)T*6@t;pUZp5f16A~kH*?*Wv`uLoBwq+k-{EWvR-*t zlh+@DY2xX7N4KX=XEAq2sM$nFB8xHLb!`zAr~PMrN@uOZjFWPqMnmC0T?9vGy@PMP zcmB~@(=T0{{n@1dbpB%nw@U$uhO~H&Zr%j{Vi9K^$Q8e|OepETLLMDYnQg7y#g?Yb;VoLUFlzAH51)Z3>D1w?u{~I?IB4V*v(ep9Lg`l=akAMh z5{YE_t^paTi_3+>a#cHLZ;=pDH+Xxp&^NuIU&L8`WDI%2C|V!To)1%V4R0s0huo%* z*E}dE8h|+3OZ~O?;=4$C%H3@a=1jezUL|x-tJAqElkO~}o4ulQvkO=5+uO#Z89b61 zIbQk~Fmmvdq^3PlE44wzp!JzFHDu&tEiLwQ&kFTX4I2zjXqs&$FNJk#4ZF?Leu?K6 z9banXa|VoLc^??HlP6xs0yj2qe#SL4$n%FxJBz}iPBdXDl>%ELzkT;BBh zq&`tWFbW`Kx8?iDewT?DSPcUSkOJN0TiMxXE2rEnoh!jUIl#(s17Ix%Z()EvnJ`ps zIr~$Jj`-KDrf`S~|3z^{^GC`p?P#&d~fH37p3@CJN)CX-R*sXqW5X12SnC`Q@e01oenN z$LOMVr!Q;r5U9yTtWCi2spB|gteNkI${ZV6>$W01J{W#pCE0d)!54$>b&Idr&8cW;c5i%zK>jeByX9lz)x zEF6d;a_l>aa=mvh;VBy>B2 zsrnX#aDw+*kDE(zwBODBUSS8xM*A$24FYH%S+$=nH;%BDUKxfVUJhtjHx~IG^=aMN zs)sQ#;;L&9iWJezc><9yx3bgv*5glAdHM<6qp_pCiIkT%ZUMkXPMgZ)wg*}L8bZ;C zaP;VC!o(#nR>2#uf`o%ew#HAY_Vuxabxi1ZFee@$=t6ac@X1+pw#!nqL|N0#|8Phy zOHAYYC@lw>*8!hqgSk*jXAkR1LOj|HIXeHM>W5Kum)23xM~7c;?k7HV zXgVU&$XsAbHau*?TM)ToCVR0JcqHIrVERXOU!zij#>~q;*LhUf!V+txN_G05OTVQ{ zMDnm=0tXk%Q}6YsMj{$)jsL$)ZanlxzP_DrYSEgMO5x+_7fXu|$OO2m6ifzA;G5RO-DEduLvoWo9L0>yKoc=;(w7*!_XDg;G zOeAiz#$hNVuxw3J>7te|f^0OIA@I}j33-&k3=84%+qn3m3X#PT_vfHJZLmAivS(Ke zQg?54_ks@V;~VtloXvB=rrtP862^Uj!nx(chAp@RMnCDz7uw;6f;r*br#1pKb~2W; z!!SNU02hyX7Z`lbntuxIZ{kua7@=YPJ@cBrMS!<;87iLV>YoTCC z4(9G9B|i-PFYvcf*LE+2-nUlPM$r?}#ISe6k-vPyfuz_GM>11^y$uhKQ|G+CG0;<6 z&h_Qs9R=ch>6i#?3{q_D(bQ&_C%QjMxJ~f#P zx09i`RS`4T(aS;#gr&+o(CdsbzcZL|KeD?0)kIjeReSdUlYG3|9sL+!r*B-UaiYR4h;|`JJ+JZak|`ys%sn#;eK>x8gXNGj zaR}$0Ty0B$A2|E#m@co1abG+T4$HN#o^~vFCj9<);cc^)kTnkGTLJGJgwTNHsq?n_#nK1xMyicUEbCAs4Il%SF%PKB;7^ef(-JENlI?u; z%3}xV{{{XXk=89=U<63ISrJ#+GZprdIh>K<^GPKk zl$MvBY&DY3@GZnReQ>G`RHK;{%NOLE^kq=vNlkcdI8tY#eGN`W)Q3!H>bBX*|B*3p zIoi%;!ggU$6-iq`hyTVrG5@F1$YT9~Gk`VlJ)9MJD)&@x`>4ciX0}D0*zTOW%S6kr zgbLI4+t^>5pIFr|K7R^?gR$=X?0MV)3TJy1a?I#dwhIY&hdz(@<_v-)^0uEVpEg6F zum|^Jqc;fOuC&xRC6?LI=}aIZhJxqirP4BF=Ry<@q=JZ%!=gT4>jUN2mzYAOnp&Da zoJ@_g93jJujna_)SaV+bQ zz?j#k$nug9S0SeNGaRR{C-ZCStuhf`KmcShSC$FuxR7RcdgT3zgQ@9XrjWU#!y|CZ z0O~AY$=2)v$^vhC@z3rsHtf0-T-5tZ%{28OhN~u$&0o$x?cB#9Uy#tw!#lGHhYT{O zJim%s>TCmWVpC?x>kvP4a6dyI4 zwS2-6H}X9K?RcUO9<+%hbT=r?iaAanHY=1s;^Cz>R1K? z=+l(EH}rTR>_5J*boksYDCJe+#f9H~qfBNC+Jx8b5S*3WmfgP0ss#d;*fh?m?s`fP_cdlt~bm4Ep|+AfD38D85wU6wlpA(`XbA7JX2`a7clj~?5adz_O*LnwBFs8mig=doUtB1R3zyD!aZGxAo z1MK7Yx~q7>QAes7^`MD(h4k`ImxXeZz(Fim!dBeYTAt>MPa4@R)$4VB?wCYZ|Kqt0rW;`=buc~!&vOVjr;jTGOdwiqw z&pOg_0^>=cHwQm~+juQwx-T@LZ$MO4cce2G(7^|~xF;Lne;~Lt&#U*h@WbDPV@NmO z270B9fq_u#Zq!cs6D5K+3OUo?+itVR7jCn6N6&9lE;f0r<;%XWQY--eP;;k%h+Z|& z4(Cjv3Z9Rnsr`h%yTrY(#wwuR-fZW5sBwa2rTUaiJ+4pqYhQNUpWnm)cr$i`U$2+e zt1R<99WZ>eQ;8=h!j_i86Ut>=@_Y{RWXpn+RUHZEN}a%a7%+6Zf~Yi)sCzaYo6${= zpZ19P9zDo<7}Pg|qf}mp607*#C-QQ?KfgJ`W|bPzT;tGQuEnQ~CmGpakJTZbfCdoG zp`;xNuhn8%#6ltVE`IjyVMw`brDHczb6aOVY_zm1BvH;!mKIt;Zf;DIk%rHlLaUwt zHIYTSbeXdCuAv!4ll4_sle0`9zRt#f$jwNkQe#}kcP_;Y(Fc_Oyuf1e7PR6_^Y{Fo zyd6lNYVp&eTKAkzSVRWeYwuMwqWQoOb0;*S)+telQyJwW&rsM93Y}hvfJ5 zxkaUvPYA`bUmdc?J5n(({|KmBZU99oL}jjqjF4L*YYLP%r!f6KSXsSeb|g+J5Gtd* z&YM~suFCX^`<2*A8S!*5&b)U^!qAkM4+XK#*ai^?e=#!tOn9!6cb@Jk43q2+1l(t) zFSotbk? z5+<$(mIhCGeFLwr%>4o?jjr5-Qy)LvOM|-VSYtDF-H$+`(*g<%d+%D1s z6L1ORS710w{K59s4IOd#K}QLialND}6V{3&|nD#1nHGkbrf3?!n!I zVuksFLtf6z`TgSwqFemo*@gF7r#qrfm_Q(T+06e1eAauv_t*3FVS2|qpPmc*`Sl=4 zyu-l?;!S7CNj=|#u)5y9?P-TTuH^2$J*!p$G`?n&)w^6PrIkXDg(EsDd^a(b9Huvr ze2Xj2(b`DIA|1`Ng2U+vMKf{qqUWA02P12b@1$@~WHj{f$&ZI~2ekGhk1H zWUo~1bVQ|rJlsp8D|-Tfh8=6hj^*C#@SAA`6&klquvVFJcS;%d-bh)t-~Z2uH79yG zn)x^Kl(FvIIWCq`{g)CG@0+QP!K%wYO;c4n=8|Nw&AujeRybjQIOOLc8xIQqs@L3Go($Ti!%!yz%PdNCo|eKG=(|A=Kf!WTP0F;N+mLv#y+y)e%%{C9 zG30B$ZVwk{YZ)YeSEpuw=2>QiX>2ia{{?^VH$pJ*5bN2B0#Y?xncv2-F-)Hdl}E#8 zPlZj9rzqU2I_B_910;W0U-hlyW>G4}XifoHM4xRI!7*$yhW{csXVg0q>NZ}A?nS#pPlqPlZ30u zLkE+DAJ36cu?hjrpTQbTF>)=WMrC&b>e8LIlllN_x%lX{p zA^HExb$`)vyWk5(h#1JbZMgRTPl)VVhv1D+!i&1<&xJa-S+RX+tN-&6&ej@z@8}JW zl!8=7s`R?A9nH8nXF+4a{{Yu1=b#ii6TZHV#jmZ24%dhD$ zt|{FMBz}UBR4J1Ck>!V@SZb+BN&?*}x#(ttE7Sev2aZ7}0T{mr5V|Alu_7aDeJQR7 z*W0!dZ<9V=+`LSIzayqvMReyBjOu0Ktz=x%4fJaEVUmJz+=@=F6~g-Hv(5Aa1jZfo zWXdd-xRoQHXJadI6GHTZL0K|I6}NH}%gv=QUW8GkXKc6Q{WxR)H5O2^nNn^MMMAM2 zMS)#)@*~cChe8)o3ER5-T1)h7upQq@zd97PpQ4M0Dp=-?HKi`$-e(VXqx;>2C=|xacycAJwG(ZK22<-s-xc@_ zj&yz%S*eJ;9>e=IBQR1*1#(QInX*E039#>YG`-8=N~4c98LIhp_6R8|uzq(b^pPuS zx%L1?L8mz!Wd@tc^ApaIk}y$#pMZ%=8U{Qi=EMJCnztkBr}f`n*4DDe>=1BKXlQm} zp(qISuU{dQk#Qr6H0uhw9<`K&p?Z!*ePL)g=%|9AsGy?QguU!Zppl^2W07P;#;0=M z-yMU&;SMNBE~f0OtA=pQr`H-E+b!}Nj%|Wu9uiwTVP8uys_py}BljVZG{htAG?4DI zx#k+(ug{L)Wcrg%I8Ib4J`7mQ*^0b;#~E2wPMqcWc9)HTz&ImEjv`xr|0r-JqfKTn z5>amo)I%x?&ReEsOTjzQ<54OBe5~ht+|3Oh41aflS45f|KO9K~y|M-4Hqd}{myZtY z&kFu3ZKm|lji|^7`!UxQ4hqe$+O`B9k0u0H2|^k2$fq$}Mo6k$u4g<{qk>`VERj0; zIpcTfI>umiY{s*95I#>H7C52QFfeGyu{^g=;jkG3<;WNzCOysVe9M!4xjL&&?@%A` zyw}&fs@R_0_-aV_+i#iN_V5KJ$y9hXq6g?yBKtatNI%;sz=CgOgfR8`dTN3R0Mnfkfyg=gJ-uQxvPjD@wJrSrAM66fP- zN3G?z#XRHSDu|h>4U6ezD$9|lJNGbIV(VA0|9AfFb(Lp= zglbazDlAdXk+o{{0-LEymmYh*R~p+P=vqYro1$l&zZD-7@HEOqTxwEkg&y!M!chQ z?RP9bH){RkS7$;}PG8b&cf!h-?P!$3yK8+voz7UWVPZl^NDwR5G{9J5XP^^b)N$E< zC>ZroH>rX_29r-=Yj&LtkkAjDzom~26lPBZqx0P-s42$}7~l*F-dKUFGU|^&-Ouj?9(4B4J?W*{?D9 zbU7&aa^eYxs2w!5B?;-jwgGcLJCQaRrRvEqCnEZXZ1}Wm_Fk zTDj52b@TfsbORKIH&zT)VXU)3byM&!m(*~l^I2i_Mo(*Wn!W>(z5k23cMg&)TDN_x zy36dcyKLL+vTfV8ZFJdImu=g&ZDiTF)%)Ci&U>qIk4$NRZRYApdiCO(Gh4w$Qg@_7M#7{zd-B%RQ5_| zt~Z%odsyjCgHR_=c6LzkcAEMN#VUI+qN$<4IR~fBhe@iHYs3UA#uYFg-bjBjpj}^y ziATFbT;pxDcwpbyg>WdRGk$qgWfzCyKPs9y8yhD3ztwL6~ z=xPCa-LSb`ap*Yqocq=O{_Mc?`cC-qsAji1J$1{RFiOrZ8@pdK1QGA4Zq(bK$HDvK` zm0l9^V;@9^ZIB(s@_Ntr24L zBlb@Or<{yne?yq$EHe@Ns#baan%y8Epi#TmG=PMOh;@g>6t#3?S3kbEQHrM7-6Xcr zF+h>sg{UHggoKQnZZ2+bs*qgwAQ7!HjVCig>^cUU#aoq;gqq1{8VU5eEZwTJ4Dp<& z7O1!PcnM-B?jMrj@cK>Oiq=?Jnf2D2Ps~uQiJKIBa~_T;GndZDN5CwY`mI1Y07Ohw zG-2Q5P*iNe=Bvk$W^dSX{QM}=G`f$?(!t@ei?>MRN;ZxCBXWpo)ttfmoNiy*QjR7F zpk-W6&g`oKxD1tO8hWy4#5A_Xo{to?H)IK*^hO!5#5>@{Y}EZM@*A1xB=2*x`Gw)G z%)to_GCqO9WCcmNXldj#N%b>QetUDWS!J-M&!~8#OS#VDRhgktCZ|ck&Tu3oa%=lw z9E`3BeYBSQb!3$(yzCt6@gvod%OFAwwX{p-*JsiIC5&c z-1x5A+0gM+o55i=b+(FzggYHqxP4$&o{h-@Cc7X}fDe3gJw?iS5qJ^Sre_4Bc)VV6 zMbvxIS(!Ftj8=j-U#1+A+Xn%9u|>MI>SP;tB`!_;v}(?kN!w)MSWj||7R2S%m%43M zbnTuppYsWyee3pvwXMu^%HUSp;5ddov;k7)tvMo~MQtBv)KGj&^s0ApVPP(1zQfR% z=5VFRxW6G2U}DMRhI+CTP?Ih%Cbcp8!pfmvp$!WLc7*NXOtOL~nK0+Qn}^D;7)Zd& zxR&y+!VmkHan96igSXMgTwn=ZwurL5TA#5HXs0ge+pQMn4}qmLQ3H38YQl6rm$Ep(4NotxF~C&&jyz z?&>s!`uBIb6?P%n`lJIa2?Xj4ns;|Z17L}ZwUae+2q|&ZF3*jvIbAAxN1r!o#PRLT zreJ0diIo~V=%8;&sN5|bemK+BE7Tdt+?6KuHiGbo0&fseosk?-0OPlxtfKfL(390< zIVQF43pDG;*cs1w$!f@>h(q0OprOqxiJfKP+hGi|NmPU);1XrvuB`?MLuTr4S513~ z6&Ce|JED17wX{%~8RhGBoU(rhwLgEJU8K`c(v|#tD?M8CMtR2A&1lyaYvV&^ex>r|(3p3yhhr(rRXDrW_5&rE|JB4*viV+A$qxbg295~*e{LH|>u%=teHHxrRT;Z=3M{4nSQla|f zPK39C6HdG^7<8c|ySExV2s8eTXdgW=eU{xPCMJe&bgcWrdk5me!~wkp&8a?3GU7iA zf3;__Rl5XQxuNjnY0cAG8#m9 zj+*kCIu3HWyTOrm`BS;aFpamzj|AD;*=n;_ z57-fnrbNizo`@u{uZ2Sj;NgcrPF_&Z-XH%CekIz(k+HInUb5AW@d2f2(YgO#=$4h5 zgzWHS8|KnjnUp0RgNiPh116s^T6B?BIL@HLoD2&KGx=RzQe##7Q2(HP0Gqn&@WTrj z+L@zyw{%}2=?eBku;Cj4U&4S6fdS#b);S~*M6-3hCFPfk^taL1Dlz%JBrU%bzNHC1 zVAHm3WWinqD~ALQ5R2FCgV=E-?;)gL6grfj?xp6Mx@d{-f|5 z5gUgP!P{6a(dsV0{~U{kUXEX131XCHgtj6{A0c+viJ>;Cixh~@LDaMY=>Qu(luY}r zex4bhEJTpBAvrp8RqP!|N*1ogK)fcjnb_;D;lK}488W<*T8_WrV27PpzVU+l1Xwua0UqzM{-CtvEt7 zY}}hplPMwaF8yRiVMo)gzEO-X>=22j!JwDuxV6bB8I2z2tG|llwK-27iFUF1ji5qEmgs~kmV`lp|5W}WA6NP$Gav0(pim8 z>65YH;d_1YOTZ!TMa-0pF(JLaP4)_1=)Qo;^F|_de}MDe$lw=KMce@M8twm-7>pEF ztde;)5{B}s3?p4vm(<>*rz(=}%`8;Zh7`=Kb8Uu1i_=p_5w2gbq>v8kOc z@r1VNZhX>m!tEmj)bmPEB~3_!e0XyI2Y)|{`B>BvD+!<9#i*Vqn&vZR9f+rC4_ z6Y5&Q8(2mh>hz8e-v)U$6ARRNns08|j3e-QREzma8=V^N97#Mm=x)wfo12`dJ}x~U za246!nWE9{n!(VxNKUzLQ079K^p7;Wj@`$2Q!ln+uD3qZAH0t=8liESJsvDi)?04H z&^{BA3moCTo4f4fXYjpD4)5QlM=s1V$~8Jeh*@bLuqvqVZ1Bc=;}7Dyfq^A+2=f&G z)i+vP;9W_Rd$?BFy2g4&zl<5LW26t;iZPXHlI2mXXSccne%e^&&T7GGh-|9T2U|yX zDULjg+@!p1JGHmh-^jv9l;OYKx#8wT-TwM3W{}Wg9OClNw~~a_3-RZT$HBv=M$wjt z-7qXAB>I$AeEuq-I0y{Nz3EM>fLhDwi35mCz)@COfGGDbKk5?amg}I7ZF= zepx<;&U-~-iYe1yMf9OgeuzrAvWw~FEcn7HD-HIhIPQB(9r9O?n9-qH|5Z~kG;EV> z4(j!$Gc9p_fAvgU_c7}foQb0}G#U+;i2gss4kr5h;mS_r!o>)>* z3PUh71d*w8paGLvRX_I*wc+Vp&*g7AxG#IXBG>PtEH}N*Z4xiv@DqM+j@ei=+2yE< z_-0(PXTIz3_DppA+&*zZjdzijd1KRXIy3yF^B2kTPF*6k*}gIxC11Pw>E*FL;A=8e zSJPbNgn^!c3v=X1pAXpCh|Xm@YufDz^C%s*_OO$0-L^XoUMvy|K~Bo1q1;pRob28% zw?DVAb}`K=NFDmbZlW)_dV)1N&*V|RzWjR1LO(YW+&`C zBKB(qYnWdJGkbltKt&)DW2;#9>$8gF*0t}(priqBcN9K`X5-4ny5k)--1-v@Nq8WR zUJrtH-I?>jD8jYz@D(gB{M8NBV~Zf9x9!oMQ3ohlo7cUhF{O zxMI8>#^mX|f(1S=UqM>%y?W=TbWM%rOGA^|rT@wuzsG1F2R$}y_kv|9tZsaUUt7-s zWcB9IRG6V-1!qtAFR*4jm0cPyyR4Cy$|{~rp1`yar>cLjSn@la(6ihpd{>cBWvN9H zv(tN0qgH(<2<>Wx&qqDXh+|(GC_O@?rwppqmL9FjvQwFPFl%?!kT3^dt$7uhD;SIS zY`hMAoGdrRn$tcPI^)29QmuFrVa-3{Oy^=yHnOO?V@m8{ZOS*>P!9xMu33HyvtEtr ziI3_RB>=^})3b6gCA84U(30bS z4*AS>%2DC-C{r~8>C`TXEWU0)tk)Y$2foA_6Gi9~JAYQ0`9f=q4+zCx35L!IY%lu5SK5-gBaZg+HZQ&yI7R%|N*F^W@nk&g4SM&NewU&ky5 zF-qEYPnI}C4MRkk72DjZiU_6oTF#8(TABE3gr1j4SoJfOBZF*ypcbPpqsZP3lWZP6 zC(Mh&M?}5;wwd z{T#k3rP{^)Ngd0tEF-KoLC)$^tFTT$Ac8hB7nXIFRo>;NKbIhjk5m~dq0GIc`mImD zKsx{oQA0Z#)xFI#F+ZZ&Wn^th6*PgZ_e@kkz@Lcek{n<~iS(ESIZL@pB%az&+v>*@ z`hXNKz;tBApqGtiW;o_NEV4l$NZC}ZlcFHt`BpFoo|@;OcXoO@Ld&I2@O|uF&x~xU zlI)tPgZ(>^{I3LZK67T#-+_UGV&2Bl35xh1C)u3%;GS0Gyf!xL zXT)oH&e$0$WFk|L^Ae=|Gk11vuIow9Hx43xDPg>YO15zdGBJg@yH+Agq`qdCENn zjD+>I2g^{ z-=_3HEHN&Fcfg|<_BeHLt>u(=ElbocMO$x&56M;q+5J5IIg)dNdH*JN?A>>8w(582 z%g{x#4VGwxJw~>&*S*E)Na+m;V`&bBmxX}>liR+~CRKH)5aXzw_31!4xw?w4#hkq|8r0}!R;L$Ibw0x84v+ghJ--?U zrOH9xfJ?3i5^jP8bDz4FuzZZkldfCk(U5X|GzykhD00nt3(0b#K*aGxfhEp*+mn~d zeG>$=os}s{g`aoIc?JQQ`q)iWVJNC}vNv~Fjc?(@#oYyRAPI4~PUqy=LEb4O;;+Xc z08tOjrI&?jT~h)MR+B85uGvid8rCu}Z2Cs87($Ob>aFk{9)5q!^zqoAxhLyEfL#Ex zef?~^@=*4e;eDxA^9(!NEk8{iSpspi-!0S+yE;lQ6%?#WqXKF*;b^!dW%w({A+ngc z`llV6Axe!U)25+V!8Su3WDa(<7892oTQKSR`277t<<9DYa%W4|Tonfg>rQew=%8_o z6j9ByO_R;pE4O4($bdC^pDTmxXc0K`?>bRJ1Qd@@UhV2*B)fEzB%8_S3+bD}*g#3xE% zgnvQ_WUW+jnbr8lhW&$QiO^2~+2->;r}E?zZOq3NYy@fLPK31e`ZqG%ICtI=se1~T z=Y+(fFy>*qvhrn1s2_Ln-@qxLh!x977nqm|`NGL*u0QyV>I{^CI9h!X%TXhm$Ohp@h@#axaOq;307$rD`g&0G$Lt$^z!0jg{cf>!a-Z2F=g0qbSA{S?LWI~ zdx1DUJ?PkJ;S6TxS=nnFk>A?v$6)h=L z4Id@oCX&@FE_WMT=2DhUyCl^#C8yE}LhXBHQddw`|D

YbpvNBYf`F%rAI);i#Bl z;O*09jjl_wrtF!{PQy#ovD9D5iCz;7#>nKOXRbeIGZOZ}9&*%MB1BVgiYl8CxWIpg zA9NMp>`e6hsr4FvvIZ^eoM`5nfsq%OtU-5wcVHv`LJ=@HlAj@2+tI=%_|?-h{w!js z3EsZAyst?eG`1I6y+;nWGl_`>izAB9nR)DS#}KeY$qN#5r731DWYnN!hI{j=1xbFW z>!E`U<^4^fBz)hO(yrSdCA5ig{!I4VIl`UlMt3Fl1YGV-a<)0Rse;CveSmX~5r1XVIwAcMri|+N^y5E?8=P9ySJ>In%RhFW8o4>55Lf;El4eTGPnm$jH6;*7F z1p8{aHD$$;oPo*Ba2Zo{b}F`$9}N*UL`W6=LvJ1T80xWp=iq zso7G5OPkS^k9T<*wSylvJVp<45XZ|ASOF-PUYt+wDZYj5UfQl19)R|EEUZ@y1Me!b zrMMOZl}1PsK=N}r@5gs?wV^lS=fFm5k={>tDyRP!m02l({r{25h_i%gl^r|>8w01W z->vY^2qk}K#Eol3RrfE81r<@m& z99{E;fd5+i;N)mEeoNbm9Q8;2j}z|aoMQrlkj_L8LMDE*T^BXVmQDo` zGo>{esQ7-KkGcfq2M?+t$~K+Aw~{SKK+?%420p;&HlIqhna|k!x^#Vxif_E;aV)ak zp0mjx%WAHtxR<`E(~^bf z=RM!96i{b94t+@Wrl;@2{daOs`9NZh)Spw*yGOLIKg#^pPz2ver0>pg-dfoM;;M;S zVP6u$K9eIcqW*kEqsJnVUo??qnj2Eu+YMARqD(cWvh(T~mQ?<8jI>ZzXZW8|q=b;r zBm<~oYb|il=b>t061%Yoh13swiK+AP#f&2#)oySZ$3nIGME`S1I0Qk<{Kj=xFN1H$ z%az!JtOmG;Fa1E#Z;dH#w@bf`q6$Y6S!X$vzcZcka7AASaL&=KOX@kZ480N9Hbc$q z;u@{)inULd!8!>rLBY9NE|xDCEqBNj<)i#Eq18R#(-JE^2%zMRF=#~J4RC@gFxOC# zkTK~k{!ZBC9pIrcvBBQ z;1}(mS_K*0Cri{IQY)q#`IK^LVPM?uv*X{?_bcwsFwZd_!JUsL$Uk#s+BlZ&m+EXU zr!0Ap`7-y*PNvt*JU8I+MA)mHfB{?!=~y<$<2W)tlI{VdDNFz@YdG?zy#rc0s~ZK) zMssu*$CHVxhI@1_BZ?_vH=G-Xkv!w6Eb6Z%1bI$&vv1-OCiVC(Xgm{;M7J>H8EYa^(DnVmuv=yThHcA!KH=ZL4vYcfSHbVA zPR7L3e!c zyhmq!bocEsNR9(s*r8n->=)S>-d-B`lsO*3|GTANf#ci0tZ{48jU0&6{s6h}ezo1+@W)UE>eH_j%Y<_z`LrXqgN@Pih@9{QmOrE8WX{GGbUBp_$yloC@ z85A)%InqjQaSJpJ700`TvDyGK;$K+@H+;TRW6l%wFNF^r$|&Z;-QhCFaHE6(yZ@vd zU0Ezby zcFR`|B(@s?2CB~8>G$wE+wD8+?otfb^avo&sx>ddzn6Cqcr-nl1;DijJD>B9mpXy< zcvw7pF{eAX$PNLwH_KzaV(W*pWDZ_nv<|==7&bZqQsm`UAAKyW$8E)QeU8g6Nk2;4FdjCX!zqxJS{*okS&J1Vb-`-LYPm;BaUWbwASOkf3(9Mvdn-dLcR}n{ zUH1J6VlOtFbgDUR5gZrKEl-ZWDKlADs`tXA-CT@Y^>aS|m|;4(AGDrtopHWb5YbR^@yKM#ft@zqIBKTHP(9c6ydFMrCxW;^;B8e_A}K zIB-ylu-rV)ZJ1&ngiQPtyg+SYFkFS>GDe9m#~w4_t}3#Vq~lSB=D|;%v0i2nuRXfW z{$QOU!B4{rK`GN=yJn3tjz}+E3(xAgOMaOy5#rAHaQ*^n1X%YwV;yL(HQNaA2C-G^WDd8tReU?iIBV-@w!!O+-W_DzKMzv)RaC2S~;1$dk%T5PQqR z5)Clrr6(73*d#%EP)Zb5799QGV`^81->6gng-JunO+e;z9g4M;YUburm5WH z$epLwevD*uRwFXvPlC<|kmoLx%F_E&>Ex!WYlI*~4OjpA_PmyU5y4R{h3Kq;fVrg$ zDXa>jvGOd!xtIP>F?{hAqGb%44^$bC8xEw(Ggi0P7u^|IeYkS!u=~ti*-(b1*boz3 z#ExAXNwt1jDouYc>{;h|XY%L1q_pL4y+l;gG~TQ}G;XbERtGVXYvPj8x{&a#9r(~yw+-Zry zGU++lLTHBv!3j8=t?nz@Izok9s}(lkpoy*W5W)XGU#re|Bl*9=ce3l0HOg?H6e^2?7o@J~0*K7{IaykriEAn0Lw?Ryn2y4jk zuQRg8XRH%qZ`}XPJl`Di?#W}4#`=9SNx}%8A%}pHR4pke7);2XYItT1XK1WoY>$Xz zw+ly25C<_KiK>#RYZ={=dPBBe*Ip6|@;%=Diw2>e<##H~Y9k(*!t_~R*)D5a;v2G-&ssn%c* z6$+G!+TGscJ7I_^o_3ML;J7XDF{aP4X zZnS3xcd`XMXK3^?C)oeyvZSU7jEme_QAy=bfb}RO1VwUgD;%^Mux$F2@jTjHLFHZ$ zJsto2)Ia^X~r8CHt?w|=-pyN~S3 zxhjfpG)+!4Wm$dT9B4es^ucSRE1y|y;JL*=E0cc{4*2}I96*` zUt!a=S9Du1#~`^-VcqmqrD*XFG8wbPO^w0|ivrT11!E!n<5n!-1o^C1!K$pf(n$xD zwXjOU;)&w(AZ;ZeoGtC%-hEcr_m1mvb?#J^S80>eG+fp9#RlzpuMEsaIr74SS;Y9@Bd z7mWgtCt|b68~1D7&D2pCsnH4xfr2bEIO69Srv0&Inv)WrP)9&ax78W59=%H}-7Ek5 z79pjAI#z`)H^w)V=0(quSBYCLMr!iIs~tpur4}`J=1*$66h7DjvP7vh?hfnJvQwkJ zG#-~jfsPpq`WALnbsna0von|49UT?D{6HMWPLq6A>Ao=*a~2P(KPH!kD)cGo^+Y3; zzjuQ?xtwuC$~Kxiq0i3MM$jI`rK@MmHjG7MezhZsm0H=cw^To3{WV(w#cbSI>Jf=wX~lz z0T)8kf*b!b!l^5|*$#zG7)xw~7%l?Sek0gVq4KQFN(DKhWAnKi>Dy@z3PDt_U zBPO8`Er;S?A$~4gkf$P$Z(mZAUBi^j?uvn(0{Vusfq+ZkEJS(_penIMOQ znN<>C;xw7&`Dn=aoU_d&Eu{g+j0bj`)sbsoh`AB0WdfzMh9^=tvRMM}$<|pia4kK=@gUMu4Ih6Jkvkt8n zt?(!ok7nIi5b9om43$OAJ6#awOpqy&fvLE3j{PHrSTyqZggpYHU=GZG1} z79^e9TM>JEGs4wpwr%tOv(+D#)e)e>Y9fo6B-q5C&2ar0N1uLKkIJ9W>P!8&ZF9UorNRKe5b+)x z`p!8sZB|6b8PP|PvMRM|XAnXHqBQ@9JfqbK2YDa24>Pr&npWEAWsI7;j#0xQ>r)RH zmun``ct#njmXTfXM@`hK{oZ{Pq^xe6J^EIpSIQaEcea}~{lf{JUrEeKBr2PtXR5H% ze_pTH2H`Iy`)nD5R#vcYBf57e1S5PB%pypy1*%x)A!o?gwrkYtl#}%yg;S%IVKO^> zYhql8OOoI#-?*Yz^h4nn$$ytx{p|)Iv*9A&USKb+a3Z=mv){o{q-%8u~Nve@W#&F3v#&@$Mq1MRlEn*dh-Tzt_+`Wra)L9iTw-cSZ`+lw>k zr;~{fM^p4@jtntnztrhwW6g~V%u^2s$JlrK;J4=AG2k1Lx645L!@zK7e*Mfg0tqEW z;kQK^^2Q39RQCtTFOW=$cbA`TBxSe6?KcC}v z)4%ev9^8;!{lyvP59cehEe=QVG#})&Vkg*O^OwCM?0$Edu_H&U7$J_CVYLmvM9pt0 zx>8%eHe^V>gKp{9i2Z^!u~Q|%8PYarGJKLJTpu$JkjALWm}|e@^5dT`ON5oq3l)RX z?;Zg;LmC=?99?=BV_B6WbJO=|mFz!axkz|jacF5PxRCp1%^`TbHbah~ofJL(iKJrf zuGvW0M?b903Y0JftOh-Ep31TJ6ylP58ta)THrg6l508nj_4qMD9;^weD{kmO%NV=t zk34&9|JlO-0=52c1X(aghW|#&^uCA?VrIt{7vJ7*UBp+JUs;{@3;w0m39wWVKG$XP#H})i*9)IM5Uit01*_q*Q)1(st1#G_oTe)W z_2qG8!*iYW6HJp;hj^UevLiG8m(HUjTQx7%{IxaNQSq~-S=&9a_?hKA*#~P+=jt~I z^>?7LO$@$}eh5!Xp1?(mp^d6Zy{cqV%cLToF^7%#Fvxm?TSyX$52zQJVLlO)tvjFV zT`Zd``B7wsb)#}`9)t+_tolQgkMm4kB8`t$sxMr*AY}4c;B&RVG;sH%`%Q-V&4L~2 zW9iEJaDQ`b6xYXCD_R%Y7I8;K)cW)rkDD_+uT5rexZOsW?2syZITC9@dHxUR5ByGK zfcC^bLQ{?78i=ygvDAD|mD^i%a*Fe?pzVe+5h#wqwU9tj^C+bek`;F@Pm%bDPG zVSv{KJYtYrDA_Sn={AcX7i#U)qbtwmwNrBC2+RU+5<&+G{+!TB3AL66yhDY$N?T>? z73EQDEtx!Z8%rr>Y+2@1#^AWin|IMEzJ+r(T|TE~|1jEz z?WR1Ta&$Y;2S%uCP5`eh?dNkLgoW$(G~yRqHUoH}hiY*V|f+AlxjJWy0hi1F1c(AV_RFF7RB#*K!iwB-o-|4@=ccHzg?K-*EoD@_Ru@BS0B+nZH^8S3%jVF|=eTb^ z)Z`Gb|5(v=`wIWPqza|(c`xR<@Mav8)b?N5JtB07S<}s4#^Ei+q==oyEVWI|M9_i& z2cL$!SX$SgW&gMsFok*rm=zfReZxg@9j*FMcodCbxaxx@(z$r9(4Db-BiyCdTj!XU zaqQiDxq1sUtMTchcZP;OHM0jZcl<(`^N#S*_BeRUc%Ez$8`vZzU;jkqot7d#Bv7Rk zrK$p%>;smKCW^0ocsCrNx)0XU*t0GJE_2KVATwHiCci4vXUPLQdU`-Y z$8T-lKMpcl+#70NaAuZRcy z?Pj65++JUdaJ{|r7<)GP&u0Ct@{ixa{!f8}OH3~NU4@5}5x>$ICC_|@hy)~;dV<($ zk%{GlF$|UGE9OAi3WqdlN=gD+NiCrk`$^XHoUJZR9T!hXPrcH&qnTOs*wLMN%|j+W zypkG0NCOtnA?#T2eE?xLnbxGM4P&O5qVf8GsgC?GdEcHb2U>>Phj_=>7I#EfMvTg? zc=44qd}N|#`X*OS(&HGVv2!u?aEey%ON*_rovQ0gw`kmW?`OXcRX5DXP=0dz#V&!p z)2lw6{k@IRGYtM#x{7OUcLXq4ESJNeiFrqUNlX2Qh(MG@wB0aWQ6?df#~aI%K@1U) zMZJcHMGPqdVG28E*LH3b(zMY2{a?l$%F2NecVPY*bWr(>Px0AZt~DvFS-5Q{rW4mE z@Ej=rK_}7cP}WaOa2Z)MOW*AfvqCGNpBFIj1$aRvwg3@Af(4dq9<${2Z(hu8Anb%h z!+NOH1y$o@hzK(W-3e{|CHQ1gp1u12m}(>Y|62m#_?ZDPB3MJtb@LPy#yGE2o+ec3 zN-Z^7>Ylory`L)@@x*>6o?k#zf@b~|+sQr~9F}g!Q?#sLz3u&Gm6q2y~qfYK_J;e%i0@_&fihbsn16ja|0w3xlSo2>=$8cK|%1#@3M0!>;O@K1dhl9+%7myrcC4 z@n2pjtkXbKWbCVUo4=D_T0}ks_cKn<$HniO3cMh27o=^|0;-url`SRQ*Uq36p>Q@I z;~7n0(=}qqa7*|%P{_I06`~Lo?n~lO`0Zu{{KTJAn{FX0a-KGC8*4W107%H+0;Xbk zOeeYG0HJW?6FdS6DMdm4=h?&}e@8*S(gaz7s#$&k2{L@5uLt+zWoH+!wLh=`;t#W~ zcdn^}nTaIEx;h8v!;DN;u-GG-ZMY4DRc~zNk6HLlne_%q%`VLEgutR^p&giE!=iHl zdq)EMD}ZI}*WtDTvDRp1us0ZmyYduBBQ^Z8#4A~_hBRC(Mo z0`VyqV(Tsc=WU@TGIHFAx$!5DjVczC#dr=5K=tfbk29WmAnl#_I!qul>%3mt_N zgb<6^STed_+Ohs^pd5M_7#OLaxX4rNW|(?CS_se|1_n?G*_%gtzJhRpK;XPY7>U<&KBV0Gl1OV{m`lYWmi)j9Y}9XBhrHv^fori2kkF z>qE~#N(Cm#p2Y93w&%Ol%YpYIb+c2Q+QQQ3W`fvUL1Qa^u2mLF%c#Gk2yeyNl&#qP zDdm+spX3PH#-OmjKIb#8$#kD+=K;_mw>XIkyrHr!Y`1T|#R3CPUm|7Uh;;|LsO6Of zszto6P7guNaW^>R0H5cI8Hl+1@rL=G2Q%igf+s40wRAH|G@>Ii9?d|{b)o3%(sK1` z>}N!>b$Kz;5EJj+99ppvKC&G!A7Qua)4;4%wa3x&65|UmMc%Li)CBCienN<3zTR<*#)7_=kA~oH_ z$QB4jkb0R6o*vEC^^39f3Gy+=0ebS@eYty>d-4*; zWk*^A68tl@p`lHD=Fd2>LM~BEDn$jxgT>HUohW#+o55xXfHsF>S32a@mVk{haj0-Q zWGj1?*iw}CNANZ@19qg!@*<1BQ`MWBj^pfT)KPY7`hcdoabipvNQa1%9aw@^sDEel zz*V&3{h4mFuOz;6Fwyb=F5Cd)AJPD)&ZyD+qRgLtFf&XkMOmouPcMMgVWJcIQYAxs zxzn^-Yp&*;-qZbffDdZ35n}YjNd!mXMeb5c5Am_Vxu{p;CJU+g_rXRu|F%L@_4GJX z=10WHn2SDelj^5@V={m_aK$8;cH*l3d21P2Ic6aiYqSg$;uO!*iRICJa1R|NCpc$1cN3mf?ha?FC(0^*x-ObGgSuYUf_g_akIK9r zJ)!~ZNbCO|f_$>g; z8pR^tdZYD^MiX3VLcPDhNuYhhSz6;l37pP`PRhGBx8hZ8NUHF6#t;VdpILqd1JpTl zO?{I<4C6h|+_a_a0c8Fp{x5G#HOjE^y7V;@dvmLh-gP{cp)frY+paQZpjfxOu%1}9F zT7;8rgs}-J%}#h;%-`^jPZT+PwHGO%ewZq`fYG9mFTFH#P^ETu;BKJgCWVUqUX-ZUN4!sq-b_seG<-E9Lhfq)!O^cp)N-r2xao3 znM;@{(S=`O^`PW>wQYJ+GSMRcyNAsLP3!Lxk7qgG5>1i=JqvS`Z@{v*lZx6%Vwg1c z#$Fl}c(O(p1HQA9^UygtH+r8|BMDG{T;lfMi7kx`eyP~#yd>Kfr3&DIz>ax+puq+c zzV)k!L11<=USJBv4UTQqm0}_@F|*y5ss?`H*vhjWM2b0foHvR(aW@x*H3gNu1WFRZ z+Qx_6^ajQb@z=SfiP-|=^1EH%E2cQG59UfLB_I^kN~#NhjL+xIc>{%?e5_GYtXo_$ z`K3O`GuMX9IgfYoliB!|}Cxlizxx zR2*Ww3tVpYW)$oY&Cw+xc(a~3XVUy?-NG(9>iu22_1Bn@HN$=&mTJOa?=8VW$;Yo1 zhD3`_zM<8BnDi~T+8`d6hCZHPuL&+E8!C|Ex4|dFw5#>EfCaqy+_zK7;FERX05Otv z^btUr85xB8Vv1*$8d2fX*7AxP|DSK{hk?1F1U#E!;_Zx8zzsl3oxhqX)kZrs<&NmD zr`ZoiDv#E8S05$hA!Sc)@gEN!-i7l;zfwLfHp168i#t?h-$1=6X(Wul{{Layvb4nb zDRna$rtyw-hB-ZVB0oR+lf}tQm)=Y^>3%Z_-VTAGB7?wMOoZl{vJG4xD1j*6;Z!F= z5{%3{otsl4udx$Xn9EoIBbWEGy#plUz_e3TQ%^l7$*tyI9p!z+r?ND&@nXmKPiQIS zVEs_7l5RWikdFijqlClQORn2doT5UyD)}pb%*~~boaocRc_@U4K~8%QuNuj&C*OqU zA-^#zk)XX3=yOd~{hCM4F$~kjLZ^-0y+0{0ahqqCW11zyNb#l(o>`K)4l!<2dPDljNBg1@m!2zQp2hdE+pDAo#5k{q{)kS9oP zWGL=Dp^fzETRn=1HS-CD^X3N6FUvoB)cC{6EWR0 zgs~H>e|#aVX1nM1k|P)mIm8a9}A8|+( z{m2JjzvDP|wKK@Dw4KA-Wzb4gB9m#~sn&vD(00E0JaG!$SBgBAYG$hh{F9APE zXZz!#Ru0WX&Cy>?ZPoZ3KvG!|2@nDGz@Tu#{<@Wab|>QxxB;H}n24TrpnpO|n%34q9Sbvj627F@>Auob&o z)6kHcGhaW!_V>AT6m^E%^w?Ki)i-~WrKz{h<^#Vxy56;s7FtNLQC!KuT<-9z&^3MP zQgImjdc@PCFLiL$4;kxkmlOWr|KZyzui{9~ilURX62m;E((P`8nNt!CXC;AFVJt~d zH2^7dJrJoAw$ovvZu^vEtf?%SQ@pnvQg^(pf`JwB( zQ-U!BQW9tqL%jSZHXy=b$A1Ko%_;=f4v}?DAFn%1{|zthp-RZL9O6&ATxBHaJW6S9 zTq=<9#XuZ!?67}epjJc;y*h{@&mYYZ1pjNE%R`Wyvp^I!&v!)B`syIv$ezJ_k>3W| z!1%xvzAK?qS9~EdB)Yr(VJS}oL&vv0vW_sG&b*@uZLZrhi1|J%0hCLN|AV)846?21 z(zQ#wY}>YN+qTVJwr$(CZSSgGwr$(^>Uq0Q#~X3FBff}p;^eQzoNLXTGcw1O_dP~I zX)2jz{4Il>xKwJ!y72AFSg8T|-K~*P$f|@OV5KxUw$X+6^&P=;EjN5@7 zdT=tDhIp7-;T@P#-IX%3tXu^IO@o8;K4})hCIa#S5J^}P2*jahO#dXF4J>WyBE`#)@|h7&5< z)A)I?qR$LMGu4h}%oJAf*S{nIt+cGj0nlr628X2q;0@@>BUDU(q6x_EM5d}?sy4Sn ziY*Bh(EdZ^Hpe$cc}f64!0(Tb?#q1l_MTB^Pja!>IU zR?Ly5e}^j?FCr3o+Ncp8VPVN~fvA;~T<;w;<+&_WFh4mDhrO9;{Cysrkt}=}qia!U zB@7D?xWH)MbSzV(XwG*FV>1xBIW~rRBLUVjOi?#b5Nnj9QPIHP%;s#owla%d?F4@m zs)nTQ5Fn6@#mq_acxK(4LD8pn=bD+>k=1Zk4-^y^o;HR=Vv>=XOWE3uH$^Ru`T5Bd z&ioe!GSln>wnb_g2n0x;%T1mWV*|+ww>0?pSG3+5O9RO!_$1~=$CAS2ABQA`j~Dr< zQ^scCX*u&^a{Be?MxuKpRED~uAAfQ*U1cbXXRQ&t+^MO+oGI2S_A5Hf2!)^V8+B)3AWNXoS{W4*S+59WclBm>z1|vm-IP+wrX$$< zTKb|cW+?RStZj3EFq93ztSRow6PFc?Ne2_`^a_>fg$b!e z1ej3xJjYq#t!6t*Y6-a&AYHH(Fn?U7ywF&}$${i&UdeOfFcWuBbNJF`Zor`|SiKQZ zf3<*DmhWpGB)nK>N7%G_A5cgP9vXr!%LZ2HP9kBt z6!OJaHO%(tJj@q8hd?5A7N3#?7%e5zgxiXWHKG=RDw*_Yj)59$9L+U8+SHUK9Y zXlo*0-OojCqw40KeClWP3b0~4ihsB9Ya^daa6NW#T<@)43y|C!%y9Ed1${mr)9V6R zywj}W9x|UK?=LX`AgztB;Lsby$(yXjO4zdl884LPu_AcQI`krUgo9OcKlC=pEvra0BbDa9yIG9_t#YdI_;rGT|$ZWexqi2Q5EWLHo%pRfpnt2)TQDn10-GH z%=Shb`6~^|75J%5qpb8^VLe#Q12kK)33kdl@05e!o9E4f`#DQVYu)p7EZ_LE?jjQo zJnv{Xpm+sX5>T&TKmt_kOxGC-@GVf-fN_V32*%J1+2F>`c2bxEF6WtQsd#t-# zbIBThcqzUpW;AhQ?Qb6@Pf8G&z+TSDy+ehJIK)DC76v=y#KDu`>XSSGl$dKr#}Qxs zhA3$SZtnwPC3LyURyMQXu&iu!4R3PRQnUxtynySz#h+}n`m_B`0Q!Wg&()!~U{JEa z@}V)qDF)voE6aX{Ne=IOSN5L2`n_+juN4}PpoQ-N_YxcP$!F1!LRH<+S6Fghe(KKB z3P=k;WI%#By}6@#;GRbG$;tK44P&T^k7RR={Rsi}zkU|+{`^ZF{STe#&)m;Si{MHn zLP%Gwb5z{?>k&c>MwDQuCu(f$;_ti2PR3I&IgmMet|cmT;cZ+t=fEfNt951y{d*p| zE0c~S2E(BZ6(by|7gxS$$F?I38VXMtrY%~E&B%dE3z(~S&3wg(xd-DF)_9wk=>ABF z`?$y==$ESq^-F9t1+ooRm3VU9o=BFIy=d>H#);aHEgJN8S6F2?W`xFwnt#m~a#nce z-9m4r)wFPvgDHZUMu>N<(e6Kl1^f;T>mLfkSc?-Jll649`QC65_YbL}ihG|#6Uv{W zASB!)N&gq+alwDiqze(uo=4O3y8X|O75*g6rTc+92R`>0W0gNHM zGA{c+vCe4bPYwx3g1xQb?iF7`#AhC@0yUmzLpLLY)~DLOkk8b(i*2mJ^<>Je3Z#E^ zLKoHQb&wRnC&nVQo-;^qGMWuUOaMuU^j`WnI8(oEa2x+(h-*83r_FhQdWzZORVPE0o*|a)yGgt)R8X`+;lA2oMTT9r?p6RAujnbT1v+jI7?D6dkP~ zS+U=6%@cU*Ix_=twE14S6zJIckyVwM3?>uiP16+qe^hV`=m5kc`^r#x>W6CZdcLbM zs-~v;%?dRON*DE3R!TvTV=n2BW9zZy;u0!^2Z=N<`*G~(kJ%Orv5Zsek4`AhzkA*|C8MP$fINka%& zP$g$y4vhdbz9qrNIX2>mqC13)3aX$v3FK z6XU$R+4(O?R)HbHe5rbECw^ zqT^{}D0xM?zn!QdVl~YA_Xuv_lDrK4KJ_n1bPI`KW0|b^kfOJtABBCw zAqis;=@<9kxzFm4KCS7yLRhBH_+I0?iD%~%Rd;4r8|-n!j*P6Ivz*IvH}}Bl1o@ie zdCfOGo&}7pF!!TxCPUGPC~(U#9$`A;fLPG%oS7U;IMW{1%KZs^$>NPUW4&+%@4Y13 zID`4YB|BVohtcDc5K|hftNFnx*HR!279|0lnyrT1U5OJAky>GkYDMuuc(NtIX8vl5 z00LE?P3@5EBbo9FOr_gtEN&E8S2WlcMOMd10>-kF-7fuhu~$-rPinHiFU-ySl?+s7 zZ##O(KnUd`YrM3?>(uB{qGsXy)}f(D;wSIn!0(0`tyWT(ff+>UR~UmKE*Yh_5@iZh zcK1!)YJeh`2vC+%k7s_pOUcgx1LDpXKxk~TelObR7rldN zrH_kUN9Q${%K5=vHvd2`b%zZF)M_YdA|fT^*yqf>M~kX*2BSR!CFbS%X>KgSgJJ8lLP$K^d}#6^#Y4L^jr&>MgVIw4C=lc%d21 zIoBFmjgKFZUCC)`MKSZtpmp$7RENpZo0E_U(CQeKv=!c_Sl0SMq73A`FPt3V5tf++u z>eS~4(-V&gq_(K&(JR8fA%d7z8|SgomMVMyq6EL9HFnO^%Axfolvy+fcLgke+cNtH z;}cFAFu=USvn?cu85{fYdHZCRj{Y$FM!09w^IkXK&E|$x8M7g_=E`AatJG%XEwEa_ zLF@hO^z)bn`+hOc3YJx{-^eF}`>Tua$14#hgw<^ADSp+o%($T@>p~4H`m^># z?#c^@m~>;eg-ehEgm0d|2pN0f_^|>L7H9A4sFx%U1;4O`-o*q{6o$2Io3~Sm4*xhR z9^|eyI5&&4MH0whEQLr6Z&7ZMH;0GA87fGGZf~$psx8YER_&?CZz9oTtA_DyQ6#R0 zx+qwc=NEKv00!U$UWEz$6Qo{|5lR3-o5k)3a{}&*NLO3@5`fpoc>=D9@Jm7tE+giE zk{3O47SMUO62{()f67~2V#?GtN)GLB7SXn^8RWh!@6)Mz z?_`74<4FeU*vUG0@`>@?1N7VdD+oLoR5Ka?K8{%FSd~B9|Mi{6#w2Rn8K7srbSE_U z+`(zz3HsyS^+L}bND3<)9)h1o7Y zU5)C^q~V7o^feEX=lq3&;~(RPT7y8TpUoXbx4A(hDVLLwjD0wx=XB>6n^T&Lu+%)t zO;j98v_TdKcNQ`MkC+YTXjLQ1Y;#Wa8S^{@0P%#eTd9Jv(+aQI-)>?_(|l>l$%0|- z0@=V;9wQ2M2M4tep&Bb`ssujO0**B`1`v=ILiIELp?hyGHSd zFXY2XJ|>$&1P;)>c}5rZ4rAPNI;{h&S>___PEVh*kHGiInQE3j<($ zvV*6WGIh3>dM`Dq)o6EuUr|#M0R*Gq{DDQERtUIMK$Ln(R7QZ!YAni(?+{vyPljU& z;!PMAkqiHToV6yoL&+HUsAq&sB)=LY)tzn!wp+({{D*Di!07W>{8E`;K_F#yyH2co zOx!cOiT-8g)d0{EVG+N&x+CaSc0=Oy*~p*8_Rr2ZR+xB0V@YNk0@)*;N`&z-_ruGP$BUdaM7kl1u9Mf`_28zJQ$2< zRaW7ZXCPOSv;B~N;wSqDE_-Fby+HGg@u#5HL#XzD7OcF;xQhziL4Z^)S7Mf_rgb3r zy4%s43LeTBSjt_n+WCF}z|f!o@a79d_`eKkhTjPwj)p4O)x;!W(6MexW~(UM(PWf36|je z5d9eLxCuq5f|8sl-8!NHkbl9+=VY2mh5?Y5(VXs`3Q8qY-1b#$QR}iM7-Pak*NA)f z1c7%8;^*Z_Ws-DJWCXmMFne&ifz=7d@nt^(5tM28d{AJL-%Xv>JWTM^=G7M@HsVY! z0y$sP8Vk;r(=h91PnW>9yI9(sob3u)Mc;@E2HoCavo=g`isctZHzL_QP*Pra*c*{b zV7k3ULbgNTX?8qmj~*QGtxQS?fJ15~ft!4a!eE>g7Xpy*gkHF(F~=h?M3E$y9DoR@ zCC=BNGD(w@*qeBIQUX9yN_Duk&rkK>s1+fnz#II<&1?`iW%BZ)LV-75v;l4uH@!X) zL;I=a=6XCrouG*53JaB|3IOPD2?fTvuBBKg-#G3XPc2##{xe7j+!!ltcW1FM=7luF zPfA}qH8xNjRT(tRUxOI&l8RlECOACiNG}Mk#R(G}{lWX+qr+G(^oG~8wz_XLohglZ zYo&axB*!j(a4x^aEnqG!y@vE!FZVjG*BgqKVq}i=e2FOtoNdrFtt@YRhfe}?#KYqD z+Dj_2RGyk&SI>mFonKsiRR6|wH00jOhm>ohsY&k~1pC^*=YU^r+(7Z!sbqNA;PY|B z-2$CW4mA#Efv{*xxeLT+1z|J61-ZP!X8K@3>yZGY6}~NV)p={${e<{1`+?GBn*lRt zjVddRRb1RCe&%%or@yD-_GGmY;$PNuk2S zG32?x3Op#Jj8TcG3#b?2dare2rq@CWg4|gV4Ur7$>_dIcftg_$+`Wpg`K#7@A&oed z17ov+ES{xJ%HcJEI;4T*^9RC$(;j_flA09yH?|;5muMJlCZA7q2f@~Yl)}Kb10Bay zZy+jy>-3L9?GWEGgc!;yP=P>Jm~s4UNg_461AsZFG{foEK>Ag3gM(I(%{Qp=NqX}h zDL}A-WYz<5nBMXYIMhyH#>AzO^sliXecuTU-G8FZ>2Sni(5k)=i2SgOS)A*ZFOYTW z?a>68M1|3TCNPV)P=K^200y&VeZy^5bMz%-9Z}km%ZOY^$>&cBfVLj zUJN45-bma=+k!JTthxu_TrVO_1U5Py(UK{!;>}#5YJPj+b$2cL+Cao}(BOQ_Pk|NV zS3p(U48JoEfIt0#oyYa3onPkbWq@0kte};N75n!v>o=2JZ@wC4uM;aRHdt6}wjX~+ z$ebj8yX57nDSaT@MdM-_)wjLQn@WA>5=Ou$OYU58K2)qBNEvm}6Mt}_CD0U}=w?1?NQ?sjOS0obbVPFs6ziFFaxrA46%!qhpV{qb5ck%o{QEC`3c-J` zIZ0+k4ud2pd?GYmnEx927)knHT7Vkiot54=rYDoNe*_};rbPcQ1Ss#?VQsDsbWgcq zL*COVCo0q3=v(ST)t^*#2Hzya@6RJAF2%b26-ajQUVfEe&wDGuSanrw@H8K~hBn=K zR!pzltlvF2zB(*Ig}1;8gI#&uIi)l|hfhxHhtIg{Zv8%f2#NdR;^boQBP-+a z>AEo|%XBfM8YonFgU z4Pz?*)vb*1Oe9(u(F`ezXFbYiHrD_6SU6kIMMeFS7UHHd67C3Fs6Sxkl%1m)Fe}NU zNjK-s-fATIF>U4%C#iugaA^afc>6Sj!c*_!Z`VbZE|hSXVZYr4s}0%iaxL#b>AcU# zpNjAD9Zv%I0`l&HW+)TmEoEY1nv)Pzqu4&989MdvbvAIRw_lrDF~eUE0WQ7%!J8So ziGd{ahL3>Qua1xdh(`rR_x0>)Tm}TXpMcq#UcrtiyrUgLqxDukXynT<{P(dfd;LbG zQhW>$)m(IgI-iAzei-kgc^b#LadXzBF4(J)#ev!NW<#AP^(RM0QzT&VP@IK}4}awk zpOK}9S|D=uRYYl`vU)+!QDa0Wo1)P-eaL-$;~Tk#5wVzccc!mH8HSdlTTFjY1gaB- zQf_xI-0@_V7g)r9M@vk3xe=~|O->V4Zo+4UZr1v~oB0&TU5>qN7L%H+?p&S$tWpW@WLvGuB{$>^N`*sp=tr*iX`gJ2Yn`}k#N$Af? zMwXLn4l0^kxS+V73$dEt({9vyg-KVo`gVGBEjmtNe9Q~8_1CN!xZ%>aKHL5o5qftM zgP)0QC5=2R`H3&jLWc_BWAD5sbz0uCJS|z-G)~sd7Xm#ECQQD|x$V_-*($o&nDM^n zj!Rm!(bY^Xy ztS|IQ(;wdHXFH3WDU$vg@0eKr`b5ar*Y_>eW{@NGo`Vcr+1%#jqt50;!};zPW_m4j zK!7F{7^nKV`K%!WQgOkh%G%SrT3}!f%He}(=~6NMBE-Vo&5k; z9SxTi+AXx}-#&#OQ>TEbtxHNuuB>*vUdL$eCX&vU)SQkswr2R7I-^%xTNiJh(8E>E z7k6!r9w6Zky)Ajg8ah)Elvn(Fr;jP4OtR;zdGihCLqo&+A6+T-sL)}$tblx9 z({5{MkoRydHb2=;=AmhRYFwk&8mzZS!Nr#RL|9z_Z#(}H3D)BI$9+A+Q6d5^R#F% zl6E!-@$ks*?WpXb8WIaOQk}sPP*#^6NRjlAUW6cF*u{l4ykE^$s``Tkg!MIQlqC*W zq1`;aG^1Bg^1Rl7C;$M00w3JSaciehf9s@J?)|sj_IO6z3G1Q(=vc) zH2VueK$^mle0WAINy^zKO=RyraJ|o5i52NYCy>C5_63y=zv}J9%vf>h-y*& zuU(Ktp+DT=L}t+VOb+JC948=vkfpNfC}ewD9CYfSsws?u>LB6 z1{45upTfive!CY4S>j~+U18-c)%f5*Rf9f#DhP221@J2N#1F6VRq&eK)XD%wo(^ql zd97-KrAlanw0-41R0~ZCeQt+h%ulp|qQIp_%a^5HW!w%nM1*j7A_X92RIUQG@KWFb zD3s3^LHH>6B-n$qR=+lG_x_n%(4s|*q&2@#D0R@I<;8FoFrnO*-+?+4LD)Ok(>c$x zgoQ;$1obX?oNCX3it_}|(wo(>abbu6Mr!-ZYH14}lj`MOi3K6H1$uW%uPCd`&w-_y zF*!%|owS?~60)JP7WmI{AYQD^P^4cu#tb8#J0aD~B(0Lb_Cc*s3e=6+Z61D;#z{_?OIsU5o6Vyb7G#AOMU7X8L# zZELazAq^(u;chVwwJqcLqIb#F2;ENE8i;X&sF<^v&Hv4yofxO)h*)$i?mBDEQZg4_ z68I|`6cf;oI32r}I3ufO9E~Q_RrvJ-7(j(0C=G4#6cSD*DS}zvPqoq?z%L=F^uYZf zr^>uDi8iqQs}9UmEED> zHyjPW;v3Hefbq`Mkf1b7rEH%}CUiUAmcep~sg*pbCW$2yBYKur$5 zUU;q`zuNiTcTg1(iIc85K(oCk@$s>46(D9jJ^90-%anmY#Kof`Mu1gAo&Q~AG&vjw zEH-L%Cv*%#&drstcRyWk_9!8Zg%j?i5DlrbEmXV*ovFN3*DMbZe%ofx3#%vt2QCUM zycmh$SUw(-7ogf#a{*GM&N3WYxb0sE36Cedui8S^MH9*HKY-Y>Bnkd!B-#-zZh*0_ z5D>KDd$FvJ-G$+h7T2w5=tNI*e_rBzmaU1$ryIln5h46!yYLTHU#}+l1u|Nky&;JY z&nnbD6#^M*?T7_Yo_$T!jH2XD!}vpfvm4g39Xdd#;Xk)Bp}d>2*dron)k-^FxlTqu zqMw^Ln~T_~f{FFad@havlolMG`Zm<4m|l&L%Ou4KP8CpG^q=|T`2AU+9`{1Ren7i? z)jBlhGNw~<+8D%d_w>K3;qi-Ngy)r?Y0KTv%m8U!NJQ%~L&G6b2)B6bqyWPcOP=U% zpud_)bhvfQ%Nc(~R-aAonGi{o+|HatEF4RP%}{{=L3T803}hBi+-QpymIk^4P=UP8 zYtX?5WE_s>7WflhS6xX?Z`?y-QgL#u&uY`iKVJ!wa_6im0*qANuPzWQ%T~ka@MxP? zBj7?9V$n?-5WR1BBXh2?bIpp@77WyYv6&_m`Iq*V#bK#0&ov)&l9GM*+sZ-;%Fh%C zlb^F${*kA{`9*%pVLUxp6do03KwZvELI(b`mFd!))-OQePqn^&40`#4D-UJ4-d(ig z71afUXgsaQ3DYNU0Be-_^Hf@4CJ58J3-NT2^Yk~fu^PoCB{n#y{WJkVKq_dkPps`E zq6H@@w?!IGw2|VMO&2F+TxMrRCL?QDbuW5}IsrWYfc@1}0Fys`hk!#%a(JoR5LqQ* zwDh2{Y-)LUpqkEWxN4FI51LB^b~QykUz=#}vv97$BNbj*O+O|TR&ShYf|?+p*!+&h zv5~oywa|%9l*NizOffdTyEoR~{!_`vnit)Iye{_|*x5pJP-oe)@CIilOet~8n(F+J zC$l5Akt~^jh_}K0w-6z-{ovidN>5O((eL?HYhiFfWrWsB3alAy`_qF4E{9_jY5lm~ zE{>%6aP(GKApG~-J_G`B%W`*}^Kz ze$!{E+nMs#HS_fLPmvhZy~gFtaI;7b2+OvVy8uEC2o6(R@XI?K)=yUSlD0OE3g2$v z_0mVt?71a+-akQWG~m^|TERSjI|h{i!$7f;Xpf;Ot|+H+BSl+;M3}L9z^V9P0w5vV zT-1ZSvB(NMZS>eJ8{*Q^0Gl20D^eSTO&LrLlZxMVpS%CwYOKpA(NBvCS`$K}Ufsai z_>B;haA^JC;fPB9|Gzn++}i)h5%;_lEBVL1diBRfqZLLJf*;!0jn&x&?8Luaw|P-4 z(BciQg5l**uEccuR;l3hHAta9ebpoF&dwvac>wrv!gjG-jQZn7z@6aZQb_wK>KH<( zSE6ACf%8G}S6YUXND61Wx}Y8kaI!X%hApKS8G{Rj%K?ATlOTD4sncj@HD5pL-{*Sc zdEkh+sZ0e;#V1J@Ji1JQn<-s~zV?waWdaaoJm)

al zc{iPD7#_IEDsurMEI9#Ya_GJHLdgml#J*e(k(KF z3!>HcI=aE71^lE3h)wsl0;(2dP(a#p9`mQFmA|uEWMkgBufZUK*LDxf78X0M6)jq^ z?gw&IX}$i5zSq+v_eIBR!{2!SOQXzund$r&+x5$UVKR5T-Q1vou@S6EU-s_-)Q%5V z^mtTH3^KZr9@3{je?GXj2#<}2UN18pC@3&e+3W@}ULlfSYvF4Ro{#3m#oNPmd~t>D zsPs0+!kF|_1F}2$ETc9elGJQtp^MNbAm#<(g93ad;h?vOpfpfNw3w?)1y0)01$6za-eso zb{KtxIFuEG;+ya4D(FhL(?_uVMx@(I)rFBCo5pcD!Ype}v4?>c%BA3Pp!xOS5pQb9xYL2i4ox zSB)nNbaI3VVXKZ{%z>?&smNz=4YHf8dHMZ`VtjOI%pJ>tLz$n{h|**UGjZW9-~8!j z-4m}y5uD0)yoQIq$Ow+R#A!Zhy?dth%R5DkPq}`gs{wX@O(i6?8J1IuEy;=#x;Mu? zPR^DaV)W=iBzx{@#%f{*@qxjm2(>pf!M0{N?1)9aMpzdkTfSr#-iz&!s0sYZFIg4L zYFg5q%>eA`VA2jnc|e~^E^ojD)J;*a<$GH3$5(4o5j!I)$2u}Uv!>n z7R>aHmtp(f4rnF1eTfRN4^|6N&&$}Po$7we!CnDC!62J!}TxF{va!3RXN6bq_1D+1_TVmfT$gcl7BRRf<^B7h6XmCgY^G^i^0@mF>*xs{8ztHvuZ zStpXIaVvaprexB3-{0b)N4ya&k$|AcI>OE>NDAxN{utQmBa&jt+j1B?fC(l|n zG(Z+fK(2MLq_J9Sf1jD&&V1rb%&2hR)aX)Gb|1FN(pZlI0D$t3grd*^ zG;#V}+?_t)#LX{YBO>O>L84c(=qk@9fO#Y(l#h0*2qNH-Sb%I1 z5kMG02u`^}76EA}P={X@MlPx1aV_F;%@fTph=16<`TiLX04NA)xV_E60rqscmEP`Y zc6Bwe*`9D~We4#D9ygnqiAevOQ9rj~-U`z8X0cgau=VCcs5aN_EV*U)5DBO|nNZ zR&*rQymKCF92CZ1m%T8q^I8bm^N;<6Ibtc0`V@b`b1EeC+5xy`p6))8f%u_FVdLOmrAnUB!HnK`@cw41s zCRCO#TZ z^e)uP82?R z@6oebC#hDeGfb(GjyS)}eeT=vN-pCGYlVDsA4BsM1AdgZ{Ii|Ia8lHmXqK*S>~Nts};fVH4&|Iyq9=aZCMW zRfzW1&`=G^t?NB8J#*IFBx&6=U_r6NVTS%hZFh;}Pq~$l^h#=X(u_JVPKJ;5%_4F? z7yoK4+5Cd|t~@xB3CIYJD6^Def`Z>?D-;V4-WQw&0R(=boUB930P0ohFwZ>zhLpP5 zmcvo_r$r^k1SN*bm6!p5yKBRd+9;6L_t~xe*_JGS4S|}9+!C5R;{fx9>#d!v3c7S| zA!r5MR%@jB3IntcC384>pkH|81I3BLh~i%&F^lZX_G_qzcElQUY$!}Y9nHZy*lvgL z(=S$Du+rNf4H^wWq=z-<^JADI*xB2T^>HPLd_$`(j#umVxhX{@TTi8(Tf1Z%9QTgV zERc`(#rPUKVcyaK0IK*b1#*+Ki^U=R_U4Q8akD&D1lMa@ho+Bh&erAXW{yi)5tviDL z3hl^B&+eT3zqA0T`-2X6H>*`F)bCF8e|^;_Ml(_G7I?gXi_~q@kpW<2u&r^{6H`rb zM$|iajC3u<#wLopUN@AV1fCAmeJ(HI`S;MQmr>CEIvne#1G`_ElVV%1IMA-N zXk`^sY8>2^iEqMuAV2&K2ANJ+c5%lRb~G~<9MEsh-yic?BUKj=7QeSy+NductOe>Y zd?fawcjLZ~CxEb>#eAXhqjYU@VU?mQ(}yHt9YJw?#Z-1sjf+~8&h-g{W=2evGuo0s zk=|9V-V5CmC#9vzs3|n9yL}NTX?hTJ$THf>k}+;iD*fFAL7W(5HGINujBGR#WiVky zH`95|k4vNE#79ZtP=snVOr=+K@TY$D0i2~kM|(I+1uZg;Wm#4gwNJ%mQnyb4483by zo^_}{oTyZu0e-;=U&zBX-!W7Z`L7N7YjY|zBGQENC09)D&!)?Yf}l22Hz0b*URq~{xI+O^XG;ppI?{q|3ApGtwtRxUA18j>mORQRQchr2PR zyLm$xj7Dxoq`Xh=rCloyUrS2v)%FhX{6al~KEu4w?Q7qeyD2l}fpAS;`tH~z7$ZSb2Dg_(5huwU zR}Ap$4(W4h3fBw?=LR>6YZ8EyQjD@%cK<&$c*!2L&igsB*a99KIk z!_Jxj80+wzM+7)Cd8MLW9XVMk*CkJJla%?KImf2`f@1s0w8p?K8Q%+th+L~4m1fk2 zKnl6a00Egvv+Vss9`lu)Jw|rF-W;zB82IM53rX3Ty{ZY&2;&3BR{9<(fzMWA5)3#o z^M^x^)E7~y1*Gl0cf3IaG3#0cVR{v=cDibAc7Lm)Nd!iJ&%Q5nxneG9?1RBsJfZ9( zCei7qCEUOyrdiLqAO)YE7g6W^pnE^|R<^;W)X^C{CK<1VgqwpeP-V|R1#(^T>2%!` zfxA=2&s3?3i%p-lcBQ}lj1Y_L+D}r1qvYuAWlgD(9QX*an?LH&@iQf!H2=x;2)o@-XOuUC;iK^T4LtGT&LQ^x9}m_eRc;!@*F?yr_4b;VG5@GDnLs*@NZ%WK6q%84Ag zasDj$0g{iIN`)(Ux8BbEHa&EV(D@H(znaRL3k(9!QQ`eS#k?lU}e?Y+}W6DD9xzLU#QC$kBl&gb)0N?f=%EPe(0Eolne znzvuE*E7|s>`Oy9Rhk_MJgJ)ywd$#&$w2e~C6aVZMv{EE)Q2$TXyOxh1Djbf6>f7U zpUKqeGqEG}0_>}FjtnyWWDS@Kyd73=T68@g{t|(#4MR=o_~NxE==%x?f%#qhD`y1J`)ZsMXKc$1&zSIN5v=Rc;(Uj3PB+ z*?Q~mF$<0gAVx*dt7(s^sxqZF8$6nFWPDd8t-e#R2pWIg>W}zQwI|QV`h<? zAJ?Y%Nx26>eb2wpHQnOz6I`(V-IZ}l2A_+`I^56zlLf42w%rPiFU-xq;42M1JK0c! zG!##Z`8L;B|vsq=@PTbsRx`p6t0M#cWQvM z`fK#Jhsdtmejr%0uQ4p9HMU#XP*(0GUt&Jop1(Qpr&?~60^qm;kLb<2XL$0Vk6nu` zFtL1}n0z=Y0tp(NMVMbX22C&KbieE@X^o4sOunB6i9aKsnipng+qpU%=L90PrUzh- zC8F1d2Aa*jUzj1!7*wfOBn-zbQob9416UQOG#UI7c=Lx?F$YJwS|Jx^Up)yWs(h~* zDndK<5BB7w=h0qo&9}572+&p^P8*vl5JOTEQOvd#7fxAYR3KVQ`v0(h@C0TG?;r04 zd7c0}VfF4VB?&IW-hD<+QlK3~EFMXiH;Z9(ziec$C!1s&ZJN=|HygMMdUuz7J_#uE z*Iewbr*bJaCecl)l66Tc7k-AlW_8>mmpj*ety=k7|0t#isL{lUwBvefRwB$=9CxlHJN)Y&37;y z-*3Y933{vb?LS%hJAwC!xTz`7x8z#x`To#jIP9ZRsD16gjdUq8GW#nE>j@I4LDJs* zsPKiHe~mJv<)Yu|+NbN@+i}Cyci^v(*6g4+*S$w-Umr?J&rH-6)cD=o!67r9OY$Th zoT2=?n8Q|22wFjdXDe~FzVQ0!%iLC4k6cvI@rk`4k)-jncV%3PMu2Q#>3vDBy~|=K zG}d~suD_?on>0EoGBw7j`Z@Qgn2_XNLPu(PVJK5wVE7yuZ^1ZB3<&qx5EeTk4mk;(5 zmWyRJ?+~x9NmUaithW#pufrMcuBdQ|Js|!+-tICuj^;rVyd{glVzQW-nVFdxEoQKo znVHosW@ctt%*@QpvRGQZb2A$gF*|Yp-HY4&R@E8VU6GZY-M@G$6QNd1hqT6;+5KiH zKf%3ol)O8ckCljYdV`ECQI;oCHSTcAm-@BZ^wWpfIiy$B>wTl&(jnfDN!ED#o;N{F z1*>(=ZuxO|2$xD)(wDt9ZG3khmuz7zHtw0c-uC!yY*V(tLk1f9-UTgkgbHtw-50~xMsjFBhvm2GPYQS(#-=KO|hg&`s$ZWc3+Omlz2R-1ACPt4*<&=w#v)NHGpw7SBhs`oQD{*ejb0~Q5?5_yk=0tYp0#{AIR7j^+6TDwBClA*0A1JhO!1ao zN39NMch_E*u=frx3MNh|=u%d1KWg(HBijqdDUA5YMJw?9kirJqooNcB*V zTB!hHD(I=eJzKskBW8*KqolY=<^v#A9;pxYMF*-NW4OAAiF=Mz1DHE|y!@2a7cC9w zze*Q~BB7Gs(4*1j;*lvT^ml%Macblst8y~tR%r;JCe}ZJJ%^V|wlbz+>3R<=Es(&3 z?dphc@&kz(+}j%d-Y4bMNQ6f~A({meQJ{z8*6N-ojMY*^Xso}J_RM9_{!!7=)5un2 z!D`J+^pM#sKO@{E+)?79lJT;Z`kSNen}?%px6nGkOOQI5S-98^>E!r{T5*T%San7^ zP2TQ9vHN!$jB`JZ2biea1W!+G3a$tYByI9=ro_LbF3i#;1vkS`I_OU_-L(-=fZIJs zq2QZb@#t=M8tv{lo0Md1la@H42#<(Ji3m)UC<-%vTh$KW1tn=vNfLo*50?~V2pLtD zp1Z9HC%9?C5&>aEKcj_J77<}-?YIRGcOG2~?>!_1@wwbZ{Qy>symYda-s$iDbx`L0 z=$fzPkY2;0WS6hAi_e`gh4!#K(S`ItLYk=>X`N6mkPZSQ;kVHp334c-KiptArSH^j z_}tA)>o+5lOM5?GH&EqeCB^>aij6ulj;VMl;R=pMSy+lc0136V)8itp|sgqaG#!<7AovKoSaB~kSQL}Uw+wMH{>$} z4epo?{PIBR|6>od0PuR|IO8O^T55R zZ8-O*Nqod0Zx{(88pCC}a>CI+D;pjep(0c>yd89BemHQjjI<>Xn91QJM(10Fs|wOM z4~{uJs14nkB#=4U)ORTT!+XcM+KyRrF!aQ(yF#JDXspDdyK>oaf4YAp)RBpNarc(a zr0~%yspc}bN)$m#8_IqVRq*VyEGORVNhmc@p49AavD0LDO0M>~`{ve4rjAH20f?@t zWI#rxetRdPyy#zCCMI$Ic=>m#@Uk$SXUR5?gU7=pUw3w3qBwiHt7nz;e*<){xNL+8 z&QH9hR?1+)e)qaS$~?Tp8)ut51H{im{Lw7xjIa_%R#sV@?lm&!59xJ2TT>exqWD8Z zcMo?u_JXV=gj3D_#TRVJ&Pd?6zDH!YBocVw6PufMlitX)pma*Lmd3#B_AgFAIkoB6 zw;0GFrn`w%6K~Pgrx2GoSEP37;H}7Kj8ZSXQkxuq(jJ^D=bfT=Eth(VPvX(o>IJvS zS@mAwuOQWq47n5(_Wf0pxoOPWpQwTkiB!TVTZ~qDr1GhYRbq;$qA~+(qh^qov`7~l zz&TzBk^hfIX#VZLBSLvJ=XAZ^W)FBNfItJPQk6Lc-$E&p1=vi>?;GTw_BK~6FAFe( z6C2sPJ4o|5wf-_7lI?vL&pW8#_GJPS5p)#hB%~y0nuE^!w`624m0{fga{t_&BwIFr z?;nV?(bP+~EfP059+h=z-)ISAM52XG-ik=Rs{ybWw&!w)WdowNIYu_WTe#0pN=>j$ zK(oNyFmo$2<>B#e0sq9`2cU=g{Z~wU*7dADSmC_6i)4Yh>zSYrs!2%3thq-1DYTm0 zz=L5nVaQs7ZvBlm_$lajOH**;8WU0=JuT!t>7ptK97lVrLB|zaX}&VUp+~-EqdRT4 z*E`n(eN>*qT=R-MZ-|f|PuswRu+VDjA7BT%*d6&Q@)-=oWR2r$thF?fz+T@92TLLpJss}@5*gs)G z4d9ahl`l^_82y=Kms;^_wfroN*A=yVsZ+{C8srwFCNWucnIPnCEK)V;+$BQnvV~Og zDMql9&%ikY!5JdzU_>hm=gpD9jh}hE3Pp*Y9iYHe-MQ z+o{&s74m|Jo3m&T*+mAcPV)oSp2(r55*SfIA}P1B!4oTmd)tF1F7iz657L2wwGjg* zQK|(cCd)-Vym%-h_ys{ATH1mP%S0J|(DL#Fc8rzEfGehU2ov2Uqh+V8j9=e)2#?S4x>% ztDY_(Yzv8a4$5zc#?B;PNf+q;Utz^NNHFxWVh%?lSVf)EwMVq9^VM{^2Wh2({^j6! zLnagP-V!rTpV1%24!gsYDsW(|xWjRqy2tCe=mQZPi)d0ut~$xRGj?Q*{EEVi$+=pj zOFSg77B?eqY;G~JJ}Xlrs`Q9f$g?h!CO5U9Sy4c0rN$^|QE8*zf)kt(3K{8J`l;=m z;7|~fcY^j<z(uM~so7%JR zzSa=42A5Cz`hRt<6$5IyrQS8Z7%HCLG0b?Hb6qN|iG1 z+054q4xRW#buQ27^9hY5SjGap-2mS3$)pG>7vj@Jl?pP}Kf%gF@_RiZZmmo$#vg-& zTUFgL7X4TJJ)%ySg%L-rP?QuAAS&E04|E8?hyX#Pb4_sHMh%UK#deb5^vpmFtmD1~ z*c%-OiWYXa483Goia~KKzU%L5Q5yq!{s-5-6W~LIsI#o!{cS>Texsqp;9lJ*RNjz4 zq!KJEhw=Z$l4V3fR|L(krST4R-oLBbaxmQ#pn695Gd0$~urFN_-Mu{?Kz>a-TcVt{ zD6U)>06QA2;&ZHwApUVRxsh4HZ8l4~}er zFAd+5eaa;q<~W;Haw)PDp(!+u*!gW+#w#vKH7#U`>G;sN$)tYc3T`opUB1Dv1-r|O z-t@z`3JJeEv^fTRr^4*$qr_71GmSDiX6|6lc76$&yUQxD?tuc;t(TBV>CnG}QOqh8 zA^r&#ySII^<@WB6$oGh@L@Zuo2P9(x-=WzR@iC2bgaiv z#!l_7$99J4abW7ROLQXtIp!_@^a9L3KN?gGDhJ~2-}O$-P!Gy|I;N(*zG%3FJQz7( z>!V)aY`K*7`gP)_cRqXn)M{pS9;b>@9aZj|lUO~O78XbVK38<_Lqqzt0~}9_aX3^mya`6tU6=f0%xZdgqKzlR|pZVs5FqGu!mFqRxu- z68$9)E@AR8bX7an{?jCIW9L>;&G(s%S;@$))_dUf(OYQ-lxQ3oM^`Oiqr%9Uo^GM7 zgSZ^Uv2vVq*JR>J@7AE8nj^h(SFa+W!N)xXXBfJ4a``Eyp#q0&Q;v)gvvOCnBag-R z1A7JFl25>SGX|Kg)U&v8Z48?+Mwv1)DeUdR-~a7zb>m9sQ(nxU^pbM^EvoqkhseD0 ztsrltpJrL?M2uT~wjM=wV>K0NhqaLkoRQ;gQqHVu;YbetflO8}TzXweY&NDsfBO;W z2t^PaQadn%Uq&kl7Fm5sd_NLQmgGHW+$*;=3Bds)QV=O{MYAJvKqC5(*yMzicIx_a z-cBnLz8{lQgiQ|tKrL{zyG)(^U`~-N1s-0UC>dpnaYL=E-q!hC4(#ZX^Yqj_rA+@? ziW(VZpA0=vaGcIZsm+$%-E#n(QYXhe1V^7it8Fm`l^>%XQ&w&lNkfW?^_)=oYq^ma zzcA3TITH6hF!wiqg`1j;{{3@uMOywO-XE&SiyhP(mf~Tt^^$NAlGc|WN_9rwC(i>u z4*P~EMq5ZpmdZeg%Cib6zQTEkY1k(&J|N*|Xg z(mn6AagdNC`8kBMtWYU8*~(kc%c*oXb*aN!1JIaarjpgyRO5H?)ELus`{~QN?w{Qf z_ag=p?*G*94~UOS`9+FaZx$Bx&dnLiPjUcjZSsCsVH5k?9-iM2?Sfc5-Zs~fKX??} zU_Cz%h!;q;#B!v|7(GCxEQh`fds0u1bOu3f&=Lq~Hkilryj}lk=BVJlO)#d-)i-D6 zlfKS*?SPfBa%f&r!u?0Q$UOLpzw+rGuSYT&X0&?)8Q(SI%$@+@!yol&cRK0(KCXeE z95FVZdpme@oT*E*iM^?E+12~eTB2Hwb2DFj73dq|lt2yS_X-oXaOWmhRvPr)Sdt{S z+t=b5`hiO{MPVrn3FX@;{0!P z=(7KM*x>PS%3qH6Z)^zj?`){mXt|KB0{_o7_(Hz4xcd$-ah?#y|5GPe7=g5#z3S}3 z<(`%Ns{(FjH}03QeZBw8^I9(Vf1LURe(gq1Rh4Oab{c)oWtpRu9iw7T)dtntkqXXF zWBRISmJxL>Pn-IxKhchnH9GT9zEXFEY774|S9h;p6B<%rZ@lrd>6|~%ET7y$PikxE zI}6>V{=lkDs056KV71u5XFvJCt7_9|dLwgM`(J|8e2*Kc*RT#(^Hz_DiE{S3*OK&~ z@=e9SuGe%q!s#s_Opk*B6R);&(N$daa=edSJATPf*RSI_`rAQBSPtMb`Bjd=RzElH z>b1sa{F~cy{3GYT3XfNrfV?gLxMata_cesX``9(VKEc)CKW|N+eKr>zgS$Hu7Hhu< z?C811vH?xkKFOJrtBxK7;&~cn2fExg}*dCvNqd>|4KuCN>&(Jr8s9W?9X8W!XpZ9d{ zWc&dGHOy!MpmM-5w%t+a`^oPYsihvc5LklC}$LPsv@rC`eh>$ie#7CICHIyHb>h-#|1_+&ibL;}ar=LFNe z!2|lHE`8welHL%l>SzK9X(WMJdNX0jG8vT~Agc2wE&aZUV&ZLNh=J>PWDNJ5c#>3>Fxl=0AtSxwJ+}y(P@Y_op(knr zJN^`Sydp7u8ZW|U`mVHxtHe?g`fpYlF=`IvyP;X|JNg4@A|{=Vb|b=*5nTbxJVJ#Y zsm&&;9Ug0(>`vm6t9a>bIkid9_DJ;unjOM<1%J1}6OyRO$2aUm>#RRon&%_0(E%%x zphkJ5{drIj`X>)oMeARC?fKm@rQRnBd0Za}7hHRAh3u`8MLifVqrQ^k56&M^$){?r7O%1i z=6RBD>a_g}TEd&0zu)!rQ(8B^4m>ILQ)t+U%CMD$Ef6aNe35nq0fi~FuTfRM z)z=l8%!Q5aCOEB63@KYfh$=)O&$<@@l|>u+?Futfi73c!B1&iwRKimTuE=gr+-1LD z@X5+Iyn!NMm*k@`k97VI2~0%GQZ@l3uB*x&n=M(2vdrWz%077&*}F)A)j8#WJ|a>oA^{+LM2-fDOTSC4G~G}hg^|N!>Nk0-COBmacSCQn z8RLByxl=~>>Z(w;&>-oP5{8>v%9TLd_i#sVd`|q^1%Rm3uywrV;6H6zs zK;_F@MUxZBP00=&<-&}9BVP&VJ209q_0~UQtVmMXt#gY;$?5GLosqG9k{cU(^gfJs zSEJ>f_bsdGO-f3~Ww)WBrG9C45-;z1@c$=0PCu>{K4CX8{K z(4};N{DaWM>Iq%O&t<`?7188l!5w&DjbP8`hUAnpo+&tdu9{4C+~WUM${qD7OXN*YN`NYQ>H6>F4kMGK%{glqEKt%=(UD0x2n6*PCVVa;W!*EF*E?79dOKc z-Zob5I)anqv4thGw9{pFYcne}+Y+Mr`NcI8?QQNH+4Ndfk21S?2U=U^#!t{96su}& zE{P`1QKgR96?nduy?0BXBe8#3`bc7fR$ufTo!`2hEe}){m)}MF{!vL@W3*@Lf*X6( z~+yVgL86B{byutA5V%Y+S?hP-b&1W7krm|a_TvQ932^t$$K%)2>-Kg( zi@1>Lk)QA?q{X<7g$?f6|4wWDOR3Ra6|}TrQ!CmBB{F38<@23~15X zl^u))@r@!qckndgWAan&>5g1VZZN_y=mS8l*{d0!Q1+|sPlR~V9g|yHP?P)&Kpmq$ zCPDmLq71xNk7%@=9-XB>emcK6M0P#ooTZ#|6RmTUmbH zn7N&vaA7ryZ9~irx6A}F-qz2w@UNHA)}2%oO^_#>yfD}hZ$BS$oLi7^hL$@>k%Wzz zwFbEImz!@r8j)4ZdDBL)QR=BPKCl5UD@c-Nf2K98BffGRD9n4T3i1v-Q(!{Rx!c;E z5QVY?S}>IAEU4M1^ID9;f0h|)^q3hzu>>_ z7^vUA`z%-?T7Wr_B*Xz-A6Zwd(_j?ofBipm>O_<6E=Nt|yJmnURz-%MWA7ez@wp39*J;T5X_sZIVvSGlTB3^6gm{{+G#x?^1? zjLTZd@ncI!oIW`C-khNmcY|}EsrVYN8*E*+d3i879Ll+K^$lUe4<&^f6d2wJv3ls# zE7>aMC6-M%k)j}AvU38weFfy%hNtMo-$Ho^i8sgEoZvzv96&j$8>dZUDN5ExW{s1Y+em7@3e#jS6Exu}i-Efu!MSvcCSA z{gFhv`pToRHoM$7QT?_Z*v9}=s?T$VyF;;p_VbBN5vAbyOJ()F8t zlW{K3G>mxVfzo%4;^NALr4!Htf@T!H8{=p53B z8N{CtGwK5jyk{5oru8LXN=Sz&!WZ!a;@3ZextFMm(_*nVDBbS#^NM+mt&}d6EN&Z zDSu#&B0&bd6fxs4O!1Wi{gbw&m*cwS&!csS07auB@31d|p4Xz(d_~Q(^0jWvX)2A| zX;}%AOwl6>}Zi;+|!iuVl zRi^4VAzT-So*iWtc=U9f`VQ220Iek>v^mm2$EV)5>1`!a9ZOSaAVHVOn2Z~~tmEjfyDe9Q1_McxR3-@cj5w9r~?G)FN1Us`eZ5*fUko4dg` z9P!5*eq4b8Tl(<=u@7gu8olR-Mj=#1jx{C&CQ1r(9Ug}S6%b`>RjOrFl3!@q@-NZU zpDPlg;IU2FbylBxE?4U#lbPHrt-m;lEj6w!U!eg$UKz*OhrfD8*psdixg+&)$E23j zc;;9;paSbbjrn`9A{Givp}7I6l?N}UejZ-n)N&k(opPe%X{9>FT#NbC8V4cm(A{TEH7efD&pr*793i~V`KI0?7%+FfR(ia4-KZgR?!5_*=3g#SID zFNS)JBE?wwb!pLpV zyCN?X`5a*uh_J76J9XRAE%=or(8|kTv7Xf^3tkoJr5J#$NUGqm7CP5HNXAU`Q`PcH zrpYLAylj_4PC!94_CN!E}U)}7Ek+=(zrL?nfVKhaY zCcw+5cdCIn&T71lB)+Mb#Mz{$(0O}h6-?32&_wF8@~riY<5?%A5SzVUmqJ7hIS{5Q zs1UWgt1ctt1sr(7k6CQ@chMFI3M&~IG8q~~yS+QgFEES#R_mq`kAXh46-F|#&LKqQ z4mnDk7!xKe!qn_VN4yE3yGyA`P?a_vE5P_E8MdNo*;!9dE-^|d&hI0^Q;9TdxIR_q zHIsU44NqSy2A`m+?if@=mk3fwv#Wdd6%w6sd_Ku^QJOual_kf=U@gwta{Ynqbp7Xc zb-b|dz8&dSAxBdPFPj#c6K!nyBSgi)CHc0KFCKjCXl#i0*T6twThvOrdwwPO2!({5 zsHcNZ^6K1{kB+dmF5q0#k4hK|V{6mFzcoqm0ThgswtL@Z;klrIbuu*QN0c9-m8 zX{Or#I;{7Q!Unyy%uk8nEPz3xQ|IXPWrs|p5t%<3)aI8f$afW#QiQU8#410G%Covq zaw{7F$`AMaL=-H1nJ87HK}e)7;W-lPcz*Zf`4DhepO*&8t3lbb#+`0PJoCjKXE{@xSo94H;hPO)zFbuqe06{Y>RxDqqkjtv3ZLOY z=~@R~;eBPKEur@f;whW;RL{*=i`Jbg`lZ%TyX>1?)h7X`mB@LJOE%@k; zk+vw*%Qu+&@cgmZ%n}w)@hx$(|m+8NN9I6Logpc7$=H#yklaNKH^N;S29x20&6s(Ec@3HVQi-ybf=lak_J z<;X7d@;^?!eLc_qE}xsw;LB>&j7!w&MxAAjn8z>r)xujb#eG__35k>Am0V2mTbA7> z>*U9DWZkBoh%2DCRLJ;83;)5#TuUFlFkr4~s6I;Du}eXdSa4X1bL`_HRPv>{OsZ3C z_bUy?>3vaM75)|2#h2Lu&Mn{{pPxy)4gB!xsJ<>Oz3T7X9DwC;J7EgNpfOSx92vgU zZvFJBQ-jMXkf*4P9;~TlfcE^bFgJT@sYL)OESouMXYO`VxBCiSLrWUHd&VmA&f}6} z_!?z&4abTz!*v4bifAIRE^`o0`Ain^6RAYwOcJ`i_vpr2v~*be|oT zQwDC9xG?kln)BaBO|^%Co}a1_O-Z?Ud+)30sG_|pyP9hHnxlz?VyJHTkQewTS!z{!QA2lg-OGx&QJMKzyPic5PcCgj&JC?vBC?m6 z!+s4ewZKc38W50&X@7BxvNC1vGD(L!w%15}?NYb<6Hzpf55JDE^cqX^!YqZMX(&+S zx!s_)WgCAZY{sg7ZqO75FlLpBN3cEy{S^c@0q{%|$YMAZ5yO@io8+6TR};k#yxsh6 zGH|#dZ<|q;S;=w)2-nq{n6r?H3f8Kaj_bYSN*&oncvEM0b%SazAv{@{i{shOq#_i- z7rxz0Ve%j4edMTq`%*pgUT&6%k`f9jaj@-kmB6A0UPcLsHTFva*kodCwuBrD5}VB) zLo_B=Ya{U#gKOWgB2`+~u#TpCG%mP|(Y8I!r{qcr8G`;oDz~&d%H|$pRhO8`^r6wM z7<)Rj^>-e|BA~$^cKW%dsU_gjx2oFb2Qr@fagr1~iNS44;=Ow{(`ehNKzXlhr^zc( ziH+_AQS84CF9{Ll-Sl!xa`oPm?e|_aoL85VS-$mGKA~)tA&gFASXCLk_U$f7zrve; zv_ZHg_XmbkYz~A|>?xG;9P_SCG_rb;I-lQ)}k>O zFsQ@j4;|EeZ*V5Ke1>y{qArjhnZ3^%4VLd&aazG_Hzy0S<$8~Q3377>+CHo@dn~HS znXTG0lQ9Yqa>3#AHl|H(p)DYL`P_ar!C~VIg!#c55Kf^Zeu*HryNSRAw})r+bFHqoz#z~;JKq+&KDD_4!EDGDHDbVXmL-PQRy{- zt(RSF*o&TMN;g(uikzMe8(GcYFjovSsQ=~4pJ=mC4n|Tkb zv(FXoyOOd|TEEZ9R^~gNKq8{a1k)nUNFh0nwStu7B2%^wh_Ng+H8pwcd9M@`tqhBo zig_R!B=87Y6qOtT2^AIWlK05dHzzp69!a_OPCK$u<8jmJ@5kSjqqVJ?sTH6MkBH+g z&C83_zV%Z?x=GXA;AD7yTC%lh)eA>`jB!GGN^fwzm0M}bXcPUWpIDfLx>ZZK8ZHj^tdab?FjVufAgWhxIcW7vmbN!w; z`%0~Z!Hw{QEU7m8p{-_(A@bMlD`E#eR$QB-(%)2RximYQU9hw`B-Wv9$iCLN{>HYVpC3qR@i(^Ye#;8D%L&VMtb2CpE@N4=?jNO)3^@s%zo`=5Rt(n4-|ukvQR5 z0p*bX#C~d&LSmfVH7=e=IxOYP&)L~TNQaDO7woo;*3aV*l9#W3kxZcdq~M^XcqMivk>v&wv)4(67!=9L3F zaYTbeyR)v>S2R8#0J~s?GF%3WC+bAI5^S(zq{Qce!R8%EsBbMMsKXhm^80759>AlD ziUKqa$9(z`oGTO!U?CxPxl>xnbzj(P6vAxHOh* z5JIl`@kSaQKsbf0EjZ)6Z=BcthbB`Kfa__Z1+^mjt`MgJ3o3Z zXlqEex@Rw}&Z+&(vj8jl2J(T=tU&t z8r)n+0`WbA#I@D)pPGQ@r!nPlyN;lqD3Ozf^{YL#eDGGMf~fXv^kJLTU1Q6&zp%Jp z(6W47IJ_-W8TsPBhgolj{s<<%E2`TcPyVKrChH>j4S`1i92X`Wwu_ifId}|u9M}j# zjT{3HP!QLb<%aELHzJB5hLGWh|6vow`D_Sg$XFM( zkMU1vuAih{?xGq`+3@ppPWsWrK2*kzYv zyiR2M^=~#P=pbVY03E5Jj9^9GYD@?f7Bjv%joxD*^-WH%3ty#=vT%tIR}uO!sOf z)T^mn0)}_jQ~b;Z@lEr7Vtht4V-NI$(9CVb{#qtEw>yC}Sw_E0zy6{kaTE6gJi+V3 z_DIYnds;BmEsn4`W(E1#6Ubk(!)={%+(7b)qxYsmrUNxN@rlZaIQz7Rs!V*K&mWxn_)31!GEJF1kSpfZs zoh@E$B#KO--Pin(AfL5;f?$14my_RYu8<<23A$D-{6_`!;4ayv)1o_-vYgAG@KffbfVi) zaSf*?4pUvRo!;twexLuPlFrOFKD662Klokj-2NJ$LZ?fWm!Dt#tWYlPSgs)X(ZPyD zUnS1+9QKZ_pC6KAi-`EKf1RPYY564^Dkcr8~CQ+149 zwXZK5T3^zy!oj;Ed{}2MVngL!@m$=XEG(R_q(~WO- z(CT)#qG08)pp5_L_-}4u!WNGDg$wU$R^nGneEi}sL0{U z5cBXA1wva-E?xz*%n$4S9{*=1+QFLF9`uM!_}Gzqi`Kc^xZG@o&ljZpF{{7&vHiYU z|CUxatqstK?dnjF!xqcG7=(=qJw4rGRntDDd{-~A*$w!$g66L8H+tg!y>xF!Zo;RY z({Sij+b(*2bWk*zhPI&LUyC1?9DS{x3o250SdyO0u1wWH$kmo4 zkDyFQ8>owc1pL|hETc7mha+@VSVWXuh!Y8wy z1l2Mt!xL(>Gt(`Z%NRh%qnof)jNJInG_M>Y_S)$8G4y!*4^VM*S`&Hb!pIN2)ft8lxAL7uxk%5(ZX<6l#0Vs2n!)93o#cdDzV>f9*I86nNYZvt$F^X% zgxFhG%WcAwl1VQluuER|{T2aV$YbI~jSDKOXm`r%8d`7}jFUSPnf^S{MSa?+ptyqlj+r9)0w5jBsv%u_zz9F;ApwNtfjSZ`^*T zU1C$>WdxW37JIf90(uR4c{vg$>8B2-ovC$*UOn3~NJ%6IPiDYTzZo3dM>z1@C}85D zqsVn3HMpA+-5i})N1E_90v*06&oym7da@M%>kKk7y2x&smr6qNOL*|I**8k_ z`gP823^~EL=zYGy=xD-lN4b|HeY^!?L%f+C!}0v|Tv_%owfS`>R}r&o(iDyi{o7Je8 zWLZ;C>!2T_l3@(_HLAdEmRC)ku!HHZIqO_mVnr=mEu~A*Il0KY{V}Ii!oazmH!q+Q)W!_561KqDR zk%7z$ku@C1r7@Hj1|?k=SW00vrV{PgupJVFC{b=2%<8V~h-UK^Lo zy_wl5(i?BQGH$eWjQ}f)hgn;8fv!mfQC8f#E24zNgx^Pq(`u-yP>aq@Zp`Fo%+@EZ zxNs$pgbbpIw1XizhzW`u4y>L*4c^OS{_Aytj#n>HhkV#k4<)P zI^l*N^{)K!A0w}yasR0(KUJhZmes-TicJnX&M~Hmqs16(sL0sS{uR=4;i^d(ID3ps z%8J~afHh-HBrY#zYFMLw%Tj)8Mn=C<_}ULRtV9uQipgwi!1{P!{viyCh{zK0T+Mn$ zphTz5d|+f^_#kQHjp>pR@AckbW;WsiDzZCkA|i8WLHmf(!;*0owv%!(c#I!XZEFM zZyk(nG%qsWM~k8OG6hG?mAke2L&xJziR06gg@P{1rjIx2FtB<=MpK>?n36FUzB_kT zz5W{KPaO#N#@1|Q%2K^z84w{9U#!?uxzQVo z!zM?DN5tuX?(I$L$mTUL&a`In>!@FGT&jsk-5aPW&NL!3w%xbF+MyzCvW9V0!yqcE zf99T&Il8a&VoN5{N_cR&UGMNoTo3%C@0~x>pDjgbb4AX=E=@rhsnOETGuwNvsJ5y{Zi`Oz@5IY-@Bqs5 zUwguqhF^VIzh~zrYwtG1mfIx?%8_J$x8PNHhHYhu_x@e59!4UdtF_qpdhFAd*ryup z{=tod3k-|*F?Qq6bAw1zrEc$6Y?b# zC$>xCYB~=oWO4*6Qo?X7#n}3|Wads%%X8GAbij{17m%(4AAbt(U&U zgC#fTd@dQ|(ksAKmgLLDRyYqg3fStX)rh}B)!j^5S^UcYL_%HGln9Rvcg3`H3vP+!DsCLiLk~ zI=+~&ICQ2yWf!hd_Br5YhTnFn57gH7(lEzxNiN9i1*>>z+@S0PN~tr|{p{n){UOvu z=7TZux2k;fq;5%m=sKz0%xC970r%!m;wP3MWH*bC&l&AuHtGTX_WMEG7O`&QxrD)< z__O(~p&HvqQufl(TxUJPM^_CEYv(d=xjh^0_mLs|Y~QCp(SKR>|EC1eGZoZmM*ig@ z;pcj^_78@od9ek-IyC+5)xn-gWTJE^Yjz@PZ?OeP!{&J)|38Hw2j$~y_-j#e|BD_m zw$z8~u>Us(s^d-iuME^~nl9$zJfsTY!0F!^E_zg>X|t`79m4uR0K);m5V=y{GC5za zjlzA0k>}?I@->cOW)Fjiuw4s>_Qks^YdRiExvKx~F;ET#sZOI2t<#ju;KBwPRt@gP zQ193`7&WT_G42;G_)@zBfeC`O14FSWtbYW`{ixB*%~ZqpCwJ=3n#*v_l(_S;^EY=O zPgYDs*0orC%do))Un2dI$!hD;Z`wgJ-tfx2KTVIGrnc&(vt88R+eLRQHu|IRe;Ce* zPv@(Dzb`Q+C5bI@cQB$!!75KnvG2eqExzBKQ z62cN0k$abBRquZ9ygEZB0J)eMWq~Y_Y+%=s-@RX;5^DB8sC&z>xS}mvG=u;_g1fuB zyF+kycXxLJ!JWcAxI=J<;1ure?(X_3r{B3>_w7FYzJB-pdF$t{U90x4wPnsR#~fqh zRQ9(X+1cLJ-bqSiRgcUbpc?(GHFOGg9EleA^f@BpcS%t2__GT|TQt|8U* z)^>y_)2(z!kkDk7#7y1YL64qOk85ja*tk@urH1!wy11clSpD@h&SAtaDb#sVWsUI8sVdPzJ@vZ|kn zU-05Qcc|YOOk;|Xa^l%|k=0iU6SH-Wuh`Uv=zmXNrX0zQ~`@^WUAlT@^N9bpVPIDLsT z4@@>5+PLTS@9vl{feE`}IShU#E)No~bWbJ)X2x(1!W{~%4%RB>U4B*yxVQ6)roDD!Zh2}gu@ z@8)pd*Xoc0rl}gM^tzWxo*siXW?_IM?aaE?HgWJ%FZyF)2|?r+_Ht#5}teOolK=t(^GS$VZ{4dZ&!{8!5mE> zSRY(^*^q*T@X}M;1vOz01(}X`R+k#LoT)@Kl(IkKm~|q{(%JL193Aa)JsH&OCv(A0 zZ9H(-bzzH^ALGX*NQvk2(1(nmc~2@j<*x;?(SFzeb$wfmk)1QAxoQmBE3~V7Osda_(#XlcuM2vzd6c-tRy zBxzF}R+U}3M+n1bOkg4V=4;CEET`SeGe-UB;<_dEKIg(2DJ2s;gTik@5Bq(#XnHVx zczt}h>H}}Haa8~t8?8VIk|I7uZhEUXF%^Q&JVDLMuAxJi9^kag7%D9jJeMz!;xEtJ zt#`DdxpdbBzMA~FnLM2h3hM6q|J|W&YlIt85at zGugZ!FH*W5l34ETOz;G$nqk}MNb&WI|14eT zOj~J9i}iNhxgz@5KUmR4c~Jv4p6!=!^?JO$ebgTBM(dfDJ6YW;wBF(m(I~S!)u~Fe zvf5GHLlm!i@^0^mS(q@86O;_e+8BS-ijih^{fQToUQ(Xtd9_bl_0H*;n@}EO32HqX zs4cx#Z+fRWrXp{8=xg#a&VIU5;aaD(`%lmv8!GNcn)wMQ%KLHAiB!rWXNL>x+VRVd ziDOTf5W>1;WjO7_DSFG4H;f;NB*0x!)UuL zXBV$`3?8c*RlDJ)q+C*_Eg}*CX>RrPXGaWmMoxuLQl4p3aYfgO|1*%U&PwZl2=cuj zi;x)@AFQ}CNg(gXY@pK>qS2ej<-kkc8~n-pEEv~d#9D(eS6CJcYxWZfYC-|q-9PE# zVHfqp0&Q9?c4vxQ)qy3$0miEPMZ3zjz{`kzg1s`Js~qBIcc8ZeX_kKWSni2hv*`VU z3!AhAAZjKbmXcc2;{O!n)35wvRh*^PDIJ>}9|ZNZxo^;ScqlUFHgPo>tnQ?I{j)WKMJZ)*5SPPrti3w^W=y%3%MH zFOtvblQo7ZL;pB;K8R4PsxW~hV2OBU^}K1|^oOMaE7tdS=8QVU)BPg|ec3AVt-pL^ zXrH442%4jiH(B+`Nm80S_A~qJhqx&YEinh@u4yY!41tUX!JuNPS#eNelWKh+W^Yw} zUR})bqrUzbGwM6smGwAa;8dWp#waToeZpXPO_V>K)r=}}ed{!$r|C@XJO7pI!{^Fb zGqr|!HMalh#-mfd6V3JP+~{xp zq{{qkxxr{OmC4`F;pqERZ{M6zwZiHR4kb`F)pr z4&x6-(N2>4<)G%*mzkdL;zREf5rrvej<0p-Jzsk!cS#%<$wkj=g@_fzC2H%whT9Nh zFMLDKj^03du_*+;MGh}GDvlnTp%X$cosz$PZV$?r0~H}-t2V+}A`pdlBgX7GP-Bok z0|_(v)`B#XzX0UE@G~C_+e`IQyG50e+!D$l_>(ZJ5Q%m(UsY7o#;uBdY+MH;`Zuai z^L(B7RajP+5K@Kh>yZ=>uTMu%LSeke#}8S`VzY2P zFmBL}OWWkUS=F!OSAI-h*6U+Szz=zzqrhzR$hu&}VdyJQ>HJTU8to!tqM{%Y@QkjH zXF&zzE0w<6HO3qXv8bph-_>j;T&~_6xa1Hy$JWUXEga~7B2JIuA+*U$t&$Kncf?rN z8}B*2N!0LplK+U8$tJEhE4gHq{0yYUj#?(Bk7V{)!C$(6Jk+HEWawkjEJUgFj3 zpuRc^c0RsY+8b89G%lK=ZNDPa^mH!@`y{^}h$#ce!$PBC@(waHyV@k1f|1Y2gD63q z1o(X*!9#pp+@J0_`zehJ(eju|2Y|{rsAi;SjeRnY+XuObJdfhv7#H+NXHv?1Zp$-$ z$^an)Dp}ymt6030Bh? zN%UD~z^^e<2lz8J{Dsq-J|Q6zN?D}XVgJDW$?2hTZD*PTTlN)*$}CsCy$4Ay>c&gp z+n$OGqrqXyyyDb7dq~G#RFIIKHkx?9Q0dt!F!1WEnYq{$pG32xc_*hVgX&~5#w~|N zAjs9vY-;}*8ai~5t&>ljEZ%^ST`f8uQk|-4#$$V$$r+&u zRNF0!WjT=`PqW0*;cN>@u`0EB*~UXJDmk>~o2XSz%aq<23!>yGSjF>UKlk6$^P2p7 ztfi>a_kP08bwPmIu;7eHd9vGC?>%>TQqs8J{$L_KXA@2=^_U|?BG9Cyr+X`%dj4wW z$*UgQ2dvZ6a#tfWM2CH*Zf}iI3H@i(Emx1LD&uCm4p)6C^%I@j0YGi&xUQ#8e01B4$Hz)p-7Fl z&c`1Ow}LFPlW9-2E`?ycy(=_hxDP(Rj{3NzE1%SN*1g^rgBp+<&JAZ%j zZKoxbSwCrHf4cVWA3H>2{zsDi9X=Ro(ndGue6-E)wo(^9OEl!C=cw5r< zMQ%0QrtRJHkWL4vlkM0VM-k$PUE!6gN=N!FkDSIDR`-M&GCA^AD>`ntr$p6ad)Moq zQSJ#)&-P2;jljn>-2ZCgGAS0movNEk_W*6cpj-`Grd{Qo01)BW{W zRzbT2J*%A-6yL9G=>zfdY_B@38h4fzXNX03=FS#a0O=MM*nH z9|{U{#C%e%1OF|GCzPHA7)tE!P3@eMG8oN>I#x%RnV-PA?l(j2OLCSFD@HnQ$fx@M z3dN($m->G~@u(f^dia&O3!jDsV6y%bO_nuVN3BBD`Y~H)X;K2|^TvB| zbU<)sow1JQPJuNGYKPS~kua=7xBV^U=W@RE85Tq1cI`9s=-A<-hdsC0aKUKC_;lpv zbSDQBhsUwJNpU>NY*PG21rd`aKe(_LHE~%&=E{i!nIYCmC zD$66ACYUef1IIPJ@sGS-jz1V#UmC%2mUQNON#=zsK2yqU`@^~$i1p}{;~R#2!d}Pt z0gvxKjZi>A$ho_F!xA*0q96hVotRcYI z7khs8C*`J%9%6^SZ%U2vAhX*o4e#5j!}Bb?u@5m6;?f@kJecqMvZlZ^nl)WR_9X}~ z-b+C=7fMq4$CzdrGKW;7rPz>Od8kJ}`XNM=O1)Y+g*?!ujgkmw7(HalN>}4%vZ>1T&S)S^I*sl=v z@)OMEE`aSiUVCs;d-dRmZ4>`=eUa(ZaYvCBK)Xu=#GPFwUFS3^q` z`WbgS-orqu;NfwPT31)?ll2^Zc&JjJYagCYEJwrcc=_`s80<@J=pheBxrMTVP7dN< z?pGtCctYFPDn)tGd1zF*TGB~~NFo}B6sm^-9oewSw;Hfg+!qyA4q`@LN`A?DXd?RX z$M|nSg^Ol&V)Rn!mnZznnY7L`8ehpgBP=eQ*y6jte}QP$U;6!iA}#=+rNs{*p6sP1 zg(f;G4<{O7_^SHVkcV59_mm7)Py!Tb5bRRuL{H~HBMnnssYcbs#RaX?>9E>j(B)x2 zLTBBYZ-)=*5`_dEMzAm9wTnr_r8rpMv~cE95}TeI6Km)fm`_2rggUTF^sHX34Ai&W=_pNW}QF^a&W=<6Azo2rd z1Hhwt=m zWx$95p`k!zx@-&@{Sqn}c|bx!6Hs)-oyvv%?lreFNdZ*t&Doz`CJ7)D%i#6j4#z<# zM&a0=!V*czg@NMP3y<%tP7cU-P<~YCmCv#=ezjE&EOozt9XLP%scw8v|q!7WwS(6q-* z;lSeiI{8D{1a3(d;YWs4v-jGbjE`0dV8*4;OR*p{UVAKO8(GGLt8|~^)`X#*M<`AJ zLF%GV;yztL&}X{wpL7=q_xs1T@9?8bw>1RCt;p4i1&Oi0BdtwBX~J)pR_|Y4WJiBZ zl&f*QgPF$%4pO}OE!S5m-%?|Ty0w4Icw}23N7XrHC(=UeQ>5V%?QD2+pZMWPcO`Fm z;M@R5M|(H5Gl~qybsCMoR#!76LO5>RXvGewI4S~x?O~_dDE7MWN)rBl8a$y3#w5^; zyN-&EASpOOa$4lV$ZH`b& z_2EaR3Ny@_Ba;sO;Lmn4!j>t!9_(a)_ON@`w;BzGI8VtQmUbqjY#7t$M%~4&e5bGA z6!JSyZb%+!q`bbqak39gPC%<7_zQ`*Pb4YR$}K-|x*IZ(XBy$@P0uw|R?Ve&%kes| z<$Gr@Wzk3Rgpw+a4{sdw*Vm8+Xapt>q9F(J2qZdhvs=T$5%i4)HpgB3&Y`Z`WXz^g z)~-4SAF}_)P@3L<1*N5KDK`WB+3?2mkd?P?gAme2dXO4QZ)=Kbo9b#${GpoZ9%4hp zAxaawC3g!GTpk(8%<6}i3X;;bZL8xV3vjtcx1`D3y`G(){H4pDY>WTX*MO7P&H&q- zj}Bp(wKQKvQ@3C_Vr5X77DjxPIO`qWPLk(>FiH1==Z|fRKZr3m)R9SE{TEA9l%#Uq zN5#N!Z@ZlYjb@6;=P_-O(r!yog4!hc4K$*?!7De~*%Glc>k}pZZg`ng0@}xvyS3rl zPDqM?#!i(8tlVFQ9JV{2mc#Tv<~f-R{3l0lty^+zg4pxJF2+=S_sB76<_1z}us19H z&CIzc=AmgFyXAqAI1;UzePFPXI*a10I4BV3?_^2vFM-PEy!cnw#H_U#2?#0$>45)0 zGt=ZdqD$~b$S1AwnzCcAm9Mn|s?l38>3|L>fAevIS9>t+Qk}yRT!N?O=1vSos?=2I ztY4x{kp=Uh5vJiz!AQpR?OhGn5jw@O-CvqRgl^`vG2?swv~Xx`p+XKqmeA#&eoW+WOUOPP!IRe(`_-Z#1qu2cu~XDh1%lw zjnAf_BJB^0qU)tQyCEa@Ccef`aYcEivmf7P6MUwIgGjL~ucr)A|1|E<9b=M`I#YCx zv?8OfLuzLa#d> zRhhSua3h)^c0cLk(jp+wEJs_`G5j{3p@)I0-?I1zjmakbAPiaTv1;s;8g-~sv2WEr z2yY>q*}h-GtAjHOH50muAiSC`*cilPf_%)!UcGY~$;A6wo7^dwvH0OsfCx9f{^*77 zKz~QcGc#UylsL@NaBAs*uRS0-V|Xfe9hI$8x&M9qYV4JhI{9bH&f@Dj_`R6>3K6-R zeXn#m17RDaGGFr#l(zT5P+#|i77GmJJY8uzXom5(z8l|lvu+5y^SR@hKXkDPgU(DI zNxP?zyuwz9j#ZSj=w?}jTqFcUJSeEUAu2+;AQI@Q82RCnJ{P-$cuqW@^F*o)BMb#_CLWy!}k6j=V z2FF9aVt zRy(-OVs7ut6PkY~;&d<2PNYdxxR?F!lc&NwN=o5R;-f`4{rXs0@PZ0)`U*}$+^SSs znzNxZcm4dcG}(W05%P2Mzi{g+CaGHULvTzgDn@ipLWnUn`=hKzek*i&AG@Nr4l`)Y z@vmMMd@RmkJX#61dAd^$p-mfnCTP0xWf(+;A2NR!eDm-Gf|TRmWir?Tz4o;WBL8xf zZU1y`7P$AXNrsGqGMSv1W!|qqGqEY0N$GziGb7h~e~ASVE#PgHt2MU7tL zyIKY%uT3y&S^w?`{+CD1xFI6T8FHn>=Px=Nr~jzRYpBKvHIDQ~VLlwD69@6T=U30wh|9mH6#D_DNI&1pS)XYbcHtFjl@yWSZrp};w(C~M%U9Wvd!T>hd4-7|8bxWD&F;?ea;#QOX1CDc*bw#n`$Ze1gsUrkHD zCC~eAqg%{^-YKXliXO;jMw>SJ^lDA1II(Ha_J=shv^`EMId=+zI+D`#4{L| zY!gIv=@Xdg*TI?Rnoh(#4h2e&ger|Nq?S$PI5uk>S#ez|iu2}OVv>FZZ2KjMZf-ao%uX^O7Wzy<@I81ofXEZ&x;6$tC<^YU|UPV z<36>oX99A%wiQZ8f{1V7hq?v0mYbbeGpGwK+6`s?_iLR{ef3FfzgNJhG;;P|!XcaE`{ODcPq z>(^Jm?@Tgs&G*vPpS{gL-AIuMPzUD*y;lhIBVSM8l(>YpuY|u4(wjTHUK+ydKS^_Y zV=4aQNzQ5qH9cJ@E#~5K%SN!C;3^4|!pQgwc4oqx(cucKGn{GNGWsv;pXeOucf;;L z(w20=RowRFpMjqgwEnQ(ZB}E5dped~n;u7~@U;I6;>!}4)TknBgZb-zxJxTAO5|^B zH7rpGCr8YXRnQyCrD)_ZOitJ2L?@4CLhihKxdqs0F|FzqqwCNHJ)Q`}L3@TI=Ooy? zwEI9|@m!yA1>1k%CsF^1S++m>by>+%8T$8rU;BBl^7qCEbtil;WhriMZeA(;#|L}? z^Y-i5Qs3mP7pgjBt^RR8;D9Q?mASK<1%;x2H!OxGOZhqLG_2fNc>n8w?t7unxMVN9 zll*ToI~4C&Y!3&A3F{Hx#o(TnpN-JOtq2o-+Oe>r=~Hc-s@=?~rzf0?G7R8Jk-3 zRFO5fN=E5vLV9Mn0c_`~3=au`yodY`l~0KzEu5DWI^wNYh!|R};q2PHfw5s#fJTP} z2i6jWW`jw&nwL(#%YSHDkn*BQ4iRrrn7B0MK>?5^y%xh7EvEPIRPO0UXN`ElL^#oS zd61lmj~QgHP|wbbgi|?}9+B@I<6LdeP9Vavv|JqVdssu z1uyAVFcKy6MdAM_>NKsI+57h)p4f<2%S#$pJGkp>CSyA86X32yj|o}#F7SoOf0t}dzaio71xM#op={NavcqpVW1{H?IAG$+ruriU-frGSv5(qTt>t;zL?|2`}Ls@8=`1dUc z>UOnb*x2HqvFi(5Pv-0G)*_(FS_n^kN>*xJr_3wUk?q#I`vzAO1o}{*@{ypbwc4AB zV{cem4H|DvLMffG=`o~shxX@N%n}LR1CUU9<34%IK>eg zeG^}FJfpf%iz--%oRREK+kB3HTvp;tCfTz3Auz9Am7;x~78i|2z~94?fM8JfMS+6( zE7uO@5j%y>FmFmy!Cj-!$#e3iV}(m<@m7VQ>c)`3L?+QA<^*#K>>9US^YBKLS#Nfw zRUUO90ua4Ie}INd9K2Fe9^o(I2x9a<>cJ)LYJxQ##DRpL1A~b%|4e#c1fg4D6A=;F zx*z!XlUn>pgfQ;5_nWBWMaW3=9`Eoz$kZNR6>;m4RFZucRY9d6?62{4M15m``t3hv zL5(^&M@AUvpwEIya#_czY|gi-dH@gP8a^h=V1$1IT)ZUrX2yqja&GdTBrYHkoiMeJWzE>wA8Nofk`7kX061AgjBO)LpDSg?vl39OKlJ*HDRBu0|fNHt%?dI{Q`p} zn<66KM$8y4BYr7}2fa6rUasmb#>IjYVG|H7KD`Ks7pY?TOgTyihTa1j|;bh08{vXtxx}9;H z8DWd#Ls5cS&F%OIaHQvBWkx zKho;mRlm&1w~j@jWQ6Htt>{(|h79kRNc(}gwTa*^St9%2*W-S8M$NJkM@YM;Wl$5x zaHh@o&>8^5m182_nx?Z#>tf{an-<45eveF1MfaWZ3nrUjJaXSzADJ~sJ+!F9`jkoz ztLyd|osr$J*tKsUUk6nHk&w;;edgC?eO`QMQW{R0bd#&w+QLV`S;!O<+9L9n&k(pZ zAadMvEzipg1Zu;_is$RhiodxN*hjUrX>>iIX0Q)zEAU#bRg&QcuM#Y_@{F~sp4PA& zA}VIxgLnq%H~yrDd5pBIM^kAAKjSWK{i#)Kx=HL`1#RZDY{aQNX8i&2mAVR~k-97Q z#)AV#7dgeUK^XX8rr{+DvBk;yLLx&F6M_**`ocISXJ#k-IK-MZex>MYVnW|e2b-X= zIk!1M&jmjdf>39O{^h83z8=QU;^h$eb#pWHj++L^*pOvzN3y;M5U8-|kxspAJdJ}} zf+VI(#)&Lclto{~E5`- zNGpbJ1VhAkFWo`S8Z}y#8oI)mt+XgFg*Sa4(#iLk+Vjd)I8@)xiXv#h@Q&6;gVDNd zjQiWNZ94ZQL#d1l@iNO?jS_?Kj#&(3GdiDs)Y0>OAF(EUcI zVS{+GiL)86-C85dS-gXL4G;cmlGQVyKP4fEzj5S(LCI)NG;^lYOrfQ}e0mWTNCEb-N+#LpKRdrsW!@KDsI z+%aaWzrk)V))FTJ5q=*B#HN5jKsiFe$CLjs>m?tb)%;%U;s_1bGlDd-wMg8aP{Vy^ zh1Jshz^PIp-eA?`Unc(OxMFL{uvrxq4*7nznrx^EV*_$KE)tdiz-X-ZLTx4w z4R?*kkw82zr!NH{C)P@TgBBXa|<7G(VvV7g6UeM|_Wx0|bA!(&M9BS0ZQC zXdjgd;G;l#xr#09(0^wuQ*HnGxqqdfvh2d(iAq|ukK9|ol7t*Ws74}#N!zs=&$QTG;C z8X(IkkhV+}S)Ee4$>@J?_$L=&pjb*l9{=bxvP`47$(v%h1hUNKLJ|+9q`SkTAOS&a zG-JpGw%9KC@hj zEsm|O!(oA`GDL%}*C&#_DH4v{@~Jfm1XCuI5P@$3{mWzedaa?t%OBIW4C+^b zE-`;^n7$}py1Sha8AS{|vkGo^p6iWAjk?Hi%U+zz5i|Qkt%~hpGW;F5BACb?g+}d` z_P~RsjHiB5)Gp0#Ylu>@AyGihF`xn z-~Q~tRc!7Crftio#4glqzfIj*`U}u4-x?UaP-BAi+jLi8mOP#6m125L=iuZT1W8Ks-XJ78g#u-7qSEFwfAF>qioNUg|{<26& z7TkqD*XZ4lYV@^efA)L}%x&jwxL>wK{Uy2Fk^pe zPM+;&DXO%sB|&v9yLU>45;-?3EV{)X%XcyO?cEiPclhc$X-bzqht|JA#kHj$WJH-Q zHS~z9ic<^J#1UkdUU8h}e1)!SRovNIqfC=5Fo6l+(>v&Y(Y^UN-`p+sJ>tJp*m{Xd z26bkeB2(obUk*{D2zB#gvTV1+0fI4m4mt8@{GN{pxw+lR+zXunqhI9kdBk;c;mM*O zg`+RCQd}2!C?pTIuZ(eNZYy<226j)oj_SdoFaRvS_jQP%{jDDSvgP>+BrF2ZIxmD=AyfwdineFDhMhUGc?-%PLt{+9{%&Od#z1!CH+`HFdjr^D8ov(G{& zw${u@vuL;+@dJ~G#`~o;+CFHzeaV@c$3JrR|2pA3@i=Uh7Us%T( zu%%@63Cg}bhj3Di+tcB-{IEr_zdP;zL!oa9gr=A=S$w#DI#g_b94M~fdQmS-LUEcI zclKCt1i-3kDuv-M#0g$}ZS`^aeTjnd5A{JZ&V$S#I@s&b;(t-K9~+u*cRX3tmEd{hQ^voL z+MzbRg!T%`amu6-nMPo|=;voG-Hk2phsbgI=6RV^*oS6RjR$N?eOS(SX)pd9z(42d zr+oA+BTJ{)Y11JwgpGB^Y}=;Dqgu%Ni4;#-W=}!O>4F&74OdAbEBb+Pzpiu$A*Ga~ zf&uI~*Ae7fXl+SgQ$Ak zNNJMoeiUR}MM2P~arBi%t8F(Wp?69%cJeKFO~uQCGk={xI%)E2S^Bj}qDqJn60_6r zl>IgC`d8HPL7$;VDsW6}pSVLsq$d_^BHux%+mknadRDI>!-)w4;X=k?b%y>*gkmK# zlhG8t`3&Ti;MnBU@~)vUL{$Zy!Vz^~Ubw_~Iz?ecnN(W*6o8Ic>-D4Hrz#TMp6O^v zMF!woM3|dqql~{wy81N=MuOPtTW^6`hGZ>MIcCfFZsnws$x4*rbY5PyhAcg@N=JGk z8%^LbgNXk)u!~ZC{OvlKceOt7QDbZyT|-O@K7&33aE;=&R{_`(D*N>~v{|@N2Wo*S zDsfXP&dg~}i!yS8jguOK9A4=n4-=7&f9mKE6+)`+ge7C3$Rh_jw}xi~VhZQP&5@Co zj69hJeJO`HsR+~l=m+RZ9K(NKb-%VbAXj2pm0ukdXKI0zXmHCn8D23ikT%i0V$|+q zsqeh?@=enD{XtK1^JtVdd4dmpQy%l5FI&qQB-7~t}{`y4@97>W#%epN{Uykkx(s$Z7b`bEYkEs zwUINrAiDOv4Ux3U>xz3}_#Ci^-9xESN-v8h)C1M4wK2IqL$$oo;c!(|<>C`>%V^CZ zR{L#_N-}}e;ISd$PLEx3`+83CJ_X?qw|AV7`qPn&jf=eqZ?0j_B4-znqxuPB;uD5F zOL%@vj9k3M0Y}|aRQSM|)@IsAR<4q@R?39Y$pBx|DGrZohf$A;fm0sYV8Wq8zEL5w zCkwWu>C#J%Lto-B0(kk(#o2d{j`Q~V-7j5q@X0FTV5A&r;E@75FD$vYhwDFh>na@m z-rGhyO!imJv#2f(L>+zwN|7L2-KBQid+b{mPxndf{1%ZOe;q z_obn*xvKcMV|4rD=K`LA;>^|Ri9?khA%7yr+R@JlYgsHGUlEYIjcC?yWB3wKM{462 zt`)MqoBXTTSD=nRid>9E$#d6f8<`Npf2C#BR`-)J&6`1N;3~bEAVP z28pfXfr+%brV=&wX+kRk^=;!NB$TmdS$!tT(I0N6c-HPKSN0oOW>qj+N~|MId&1{( zc?*TVO8s08r*IdDr8*!U&V6b>D8I+z8%}tiHP2OI{8^1T`c9AN??6qbi>A-4H>x1R}0hJ2;@m>kYI|2n3#dyU@> z6}xRzf3C-LtF|;ROpCy8SNC+!@;g&n2`e&n@6}#W^KbKOs7g za|u?(XA@C&uVGCNfcHBFpb4B2-u$7?o8VD+V-5_L}F&p-%sB`{ufvS=X+VIC`gu==lit#l~8p|dp2_rL}YgU{N0rGJsEugrD#2l z@CJKy3C>a!n7!|xuxs;2w{>!-EGqC%B(6Dc@s$~VhTS|J@gJ`FbFe4P)IXB@`lVYi ztzC>Ys$VP>n)oXTG6uBYco!eWi0@MX?oM_OQZ06~Z1ou-^HPG}TREH!`x#a=uBs?9 zsy(L-hc%EXItN<&FPvS~={;QXzH2j3k``v=UQ_xlA`gdN$n5yTF4R5G9B9;8ps_U4 zA6&)d?Qw@judWh*re=kL2SZgqzV}Y2M}w7_LuF|wM|;PgZAe1FQcAyM>7EiP^>X3svnYJb?siVvhdZE)(J`W~vfxfDrNb(_V$-%UYOHN#NqO zG<{=~PenjdI9!E{$&T9W47{@Sv`eyldkz@B*{Ip%bX8nYKpTt!IV&%w8mUuDVzPc_ zotQX-&#LMqGM5V@*f+#BI{W9MFEe}H`^|B~wbjXSCbm+=p)ZqMN_*RRniVoo6K=kT zhsuxQ@&6iiKo7Mh{bq%!SZ|W-%N)9RDqQ7QF7jq29*2v}B67rHhpY$!06Msn4ST=O zG=(5B8nAvcak_W;jEzl2ArHt4sBvN#h`|#6cwZ~I(Ep8v=F=MW%Rd!tFs<6-srPLW zZtE6*HbOhl8Aj;tx?36o$UXeN*sf~XR+$(={NEuB{vu^=pjeE;$^s=lv98AU4s!aY z%Q;hPWO;_3)e1fQNUmyu9;B3J|DN&wH8KTlTZMM6R2M?dZbfeT&e3yR5kBk3Z>hZ- z9X(0Y)xf~KlFi?S&R;9MEh$Isd{Oa!h|;BUt!WK^1JQ5^r0Izgye`S`bSNSWCG0nj>`4fB69wd zI-}?W(B(?n#Ma4Z?x4`d@Vf7~0(lQTnmh#^0pMVqEk`~<2n~CMRIbFRH9>@d!B1-V zv_Sd4;{YIVb!z!9Y<)W5$-T9)MiM>9j)uLZ4W$34Ml&u05ntB zkXGkQ_5pT6{(N+Xm`t$=AY9 z#7NywI7^M-69V+@68OCDU+XLeUxsh9uMC^Xwt?X=b}Jz)Oi)tyTGC%!Y5}+T_tP2M@+*>sSZgdhJASoFViU8 z3w7K^M0&~P*u_W53*jXf_&}fXsB^9z$( zCM%DSkBB^|CV%2cz>K2bM$?fzZontbA!x?`o<>rv-cIyWOC?^=y$&-|#IzcxlHgSILXWv>ugb`z8n?G0STt#tv)0sO$LBBuQ zT05$cWBfirW^*)wOhO`^vgu~W*0w2A#1xxgncJHJ{G#+AS9q8St{&yi3u`jWdzBGu zYTq1#FfmU%aaX}%_bw=XmC6;LkEc9&U(r9OI-y4|&rz{_sG#M{76^0AOsReeig3SU zs^tbPQa_P-@dksLolgfOqVZjd>7Z-fz69Xg1pw^wzw9-NW5Bkeso841O4Nlj3} z#^rEwD`Y7#J7ss=krNjaj=J<@V7g*WCFb#VXGLUVa!}vjTJ8J61}OKuhyp?XRlLC2 z&Kp^7xU}Bj9^nxc|7YJTnre;?PqBw;!i2(DH6xAstkqo;W?Xz$|0{vp_Vd(TW>^C2 zet-5obg!n;tuJb0_@ZI>Nxwkp@JD9bG?%2=XNp+7{7DOYwrG&M-c0;=EndkZ^!izo zQ$1DB%`1dQBbmF;(KZx!uZ}TzG_N*v&XY+>-roiP%GulPSGmX)q0ev{=iIxOJJMJ| zg!ucXZ;8F>LL2p!*@(X;aUX%Q>eb*wSc$)uu-qS<5m{W7+D+%x(;|N-&=0WVkPbD< zQkIb!)h`H%0V&mYfv?#m!}oJj@R2Hkb{XWlRk-Ha@oHO(>O3g;w=`Y^RykR%^A+;^xq!4ojwD>w%|~&|dC=;kZ=cPo ztc@Gnv%qQ)G6K&#)bMyj^#018cKF=+UYhv|ii!r8`*aE@eYS%wHkZ?KgE5Cc-&0v8 z;PMsPdCkk6y}ip_{$(HLOnmYEXb8e4!=v0B0h0fTT3U`XO=+StW#W76c0UKd>DW>i z^|ze347cpwwwMGT5w$1Oyg@e7NuEG@0=#yz{u}-8NT8h6vD>2c9&5Ocz?QNhlYU%L ztCkH}O=kbf{G+!G_5q-#^1qJeAakZc?DpZI*vG`)4ELD?>U5E-*$V4>b%B%5lGJ^Y ziJ`RY`I^Z2a&gHfhFm4Pq79YDmz*6^>y$Gxsxw+^HPA}hbLW;yy!|~nF~HL8dM_)? zLtj5#+%aCxK^saifj%UmdgIkp{)1xoAVj%2<(-$@Zt)BR0c&*M-38NbC(L8Bh68Mc z_==)_Ekg(6Pr`z}b{P@|l7L=yw4uO^kx~M^BI`5eW^LW8>S@3hf&GD0F8dyK+lICD zukK*{8xYNfo#h^ioX>>-?M_6HRDf+b+9h}U@>yg8FPSanr8~9oR4T% zRkic4aT?mC_MdDy-~RmGb!_E*VNtiIK3^VhI-K&SzoO^BjvW2AbF}*5U*MWOz@WWw zbyq^@=UavH(>$vK*s|+%dh_n`vB^0Qm@Q0S=QPdPIc76{ljA!GV9+np9FT8c^=6F( zNKdhICQVQociz^nr@r(e@@pAYy%UoNs|YzJ(d&~%k`r@TXD8N{QJad3OE-pDTzw?K ztBEltrZC~u+6^C&5-*!BF~2EV>H+0-WY8TS5E9aD$$J#oyDti7Dbz@7Wy?^fNz|(DpL=A+*=q4RG_EZ{}Zg0`2h6<9sm(_mDh7eV8eC$rzF{(~` zS=w04_W8uREDWZ0S1H@VAZEvNGdoT)O~?%3K((7rNJ9w&f--M;P)@=ST2Gog@R9oC zVDawQ#&GoFbAZvF+ODiqq94Z`O`mx3D1RnaBu)}ue3OyxIdZ)p;w6@r(pd=hr|I@G z;b)XMPJK0;jK(I;ljwct3IW~rvARs(b{F0~?a=nlwn33A7jM~BMo-Pe%X$gF@lp2KI*9;qt@J?MfFs{8+qW{Q7Qc8eusfykq z4IHAgo6oV^4-a0np!&VcF3vDxJ8XS{Jxa>r2~Iu_TyO z^3V*HL@ke(vAQU*OzhxNMZCR6S1@$Tr}B1D*;0qNu|&nOl1h~B>S4Za0)i|ublAJVYFou{bhsMk?9Gxs zkz%@9^(E_Z1Dm?B$mx-`$$Hgcq^s7MEs<60;@08yj9V!2Y1T>ZVDgQH^Vdbiuh^d} z&PlJHurR)72%0Whz0LBd)Vk3lb{X5@xzY7!e(Ih~EuV^TBZ4CvW-T^%f+uW{q9~le zrJuy^>^OC)Bp&>x0x%W4mKP#QckIhwnNr~kQZcIrC}Pa2e(u>9V&Xae|0$%TEh3MM zE|}Q&8W$dEa&zK({9&oRKEy1rb=o-?UDBK-NREY;e{Mk`9EnOXows=k6VQWhpgB=% zUy1U0K4*1Mo{Y;=@1n!BcR}f-{~~jnFBHAsf+2rQ*Wz*z|0)J>zxnF1ZZTMC-T7hP zSsDU}eh5%BJ1XY9WPA9vx?2CbX$>!$e=vjKoCAU%vJ|6b(S43XZKc*j8aptwX9m^k&Tt5m-9Jc^ zPXH8M*D{Z!xVQp0#ao2^AAXUS_--jeQK6RD?kRlY0P|p%v*w%qMB$fx&sd{!o~#q+ zaZelh3IG7U{?!jpJ9Cz;%MWXmwb6H(ht0idBVaV=7+|a#2ww~e%QtI7r@le@bZ)1Xd-N!^Y zIk8Jq;iJyX8yG2t3$um9{VKRSlJrGSb6yMQW!wA9ft2>}+jO~FGXq*gVEp`=# zt6ydN%%~=ifI9#YdCu&;AEpBE4iiB5|JHH*bg3;kH1C(bgY>VZ8f&QG%zyKD$xQx5 z9xN4%7x}2cQ%>PhTvpBP{bP?(_xi_vhJ&vb39ryE|8|y~NSLslPc+`k0{ec-!r3l4 zPcB7rH21wDv}6%_k)~MYA3)pY8ua=Ig?a&XC0|pM863v!Lh)C2Y;$7kPML;N(a;n> z=c||yZ4;dv;uT_h7>Aik_kBliaEyzqgX6XVBa6 zT7bRIMWYyu& z2nSk?DRnK>^p@J9n)35!n0@S%)sYN7XV~NcB$g5*Mrfe;Qx|YFiZ1{^rXTEjbh~ro zYVt{D4GvX5=PI7%af66t9&H#p)0E|D*rkP5JG15(diBr18#4S%LB`LCKYq3L7XGnp>1xU$L(ZmrP(s?C zcV+zY{ybRE>P)LjuSF_zJ76@TI7?6yOnwiYpJ%rnkId8FNCuDCDMlf;8ES&{((Bbg zz?LP8-<^9KR{coDhbY$kvul_^x&A=En5L_pqRwo^r^KSPw=dhO_}wEkLvFZdjw5hl zg>}1IPbQRguf}_vBSUihx7r{0zAMSUSr)-!0hHZNfI&XXK&~XuD_-9y7l|{ z=LvLs3$GdJ0PM~SJ5>Rx-N~NMtUphiIw~q98MO&4qu@(vpUq(<=8GKNTaYqIl=yXmH zvWS%N5`{y^82v6zGuLdj@n_HvCYA)g9dcxJbdlL|18jCrRxb;zk5HmeKgmtxC~|UR z?XO6waIk3Z^-oiN+<-SCpWeQt%l8zIe0>VWw#|49OXgpV9{Vl}7O13jByvD4OGeV6 z7N3{D8{DT0T(T-e6Rl1nV`j#J64ZzjJ^Qhfiia+uG)u$7Yxz0agZ%Fk?@c?i8uMAsx$^bm(jsdmY8S9{axHEY zHeF4BGK}Sz8?umV>@2|o_Cniyu;SB4W+1MF`129wgh;{Z>o`~fyF zg`|3x8BVQW2QxG;RK{7Rf=cxJKhvTFYAxZr+VXShr;t1iAUEZ&4(*7%C&Z*|$q-Un zoo+$mHB0W@y<@j0$46?B20>!PYQ;RArE){p8i~~aYVpW6r^38!bu=_PtJ~ZRXUQgV z&`6Nf7YH~tOs(UkeTyO1%d#u-qfLc?rhA`r26B9d3+JjI3B|So zt|-X6cVBl_s6Q6+tSySsDi4ZFw}o(ykF0j(ZfozTtH;w5=Yi(xpN%v}nNzRtAZ3vm z;Vmj2!WbD{1S-X#!q(3I4K(UZa)u3B)Tv6|a6b=ndsRYf4-p}_>giQR> z+quuwTW8{1`ugliIbpLFOQ{37)Hw=86SVX1XuuqdL|8@>hevzzq8uF7(nEoy59XXg zCZ0WtR%P2Z@)z)M{d-*tYBwNp4b|)2=&Vu>RU%m<#+fze%3?%;FQ%<%`cnx z-ih3@uSK>%=RW{Nez{Z4a+u(=9$UCq?)fUJi}S}V@8L;tU{hLmdWs4G3Z3vhh>(J9 z_hweW@t7$pkszAU+lH+w7X?UqbGOz24d<+~2-)Y%Cai3F zTSBrqr;yy>zHAsO+UGB(K^dm0A$KXHh8kkmF|kMus7k;)y)3?xTabgOckl2JD-d&I z$^iCrL$_w6raTQJq;w2{;TSCWokYcmWxIOz$oZl8r1+oM2<_!33eoe#4hY3+S&AWP ziC1O!|5$El{@ZdB78?2(K0Eo(72}e#GB%y7cJSXsP0nBfNpBM^o96VX`~Svg+Wk+W zCgJ}@)U;cLu}+bo|8iQ-cxS z#ACSJTaDG;**dT5L+Ja(+9mP$z|iuzX65jL1&>h=U#+=(Zgpk*Tu2}$meH1rh- zNCf=oMZ)wlU9IbpSaqkl&a>}PVT{z%1TND+l$+n5nr*lC@!-wd>#aLadvk{!g50Ef zG5BgUTOF9KR~jE2KjMyv7d2gTVZ1DzF@^?aGo{NeFbI{BaiLuJk02NJVw>vT_k@x| z__gYqB3G1Wcy>Y|#f8}aV_$hfO2y@bm@Oyk0qV=~3!voVjVpf|jweFho?AueOwQ)XzKSP20%dWhiqxd_mbH`WTc~E?&*q zLctgcm3UapZpl^tn{Vs58_6Cd9km)fl#1o3I~dud3rk$@MQ`o{%J;qIb`&kfFj;R; zL<^XI8(M6z)(hZ_ILPK-#%0t|D3aVHnllH9nxTT{~LGWYNebcOK*+tpKxG*X;rj5>Y zsg8_Jb6qYUE~_Nyr+K4k>iycQOo`th@j00^^$-SgBpALtG5gRzZqn$C0fyK##_weGf~aMBm~eFzL(CG#LiNI84|Oi zV&hO}br__O=Z;B?1Ydw-G1<4xckp$5`~btdi9XVP8u4Bl<;3A11o}$f5w@;e9fQPS zufnaMrgpC;NmEo_JJj?T~MjEJeF=E4NF%c%YJlQgPNQPR=k&Qyi_?G)B6&dIurMx+wU zkhe|7o_SX_WRv3&kwO0i=ULBI0Th(O9}r8nU1AZK0KGjVr;3_bO$b2$@ z8SI~L`05x|SQ1f1>xS5B{A zdl&bJ&9QC+>n1qA8xmp~*Y-qJx{X47Mm`$fsL3%L4d$Ulr}dupy8F_);thg~{O&U1 zbMttbOLG7V|IZMYQ`g73rbIc0{h=&X^H5~v7lJpPs`a=c?fCHQCUp3a+AGC6a<++w zMXM&1-K74paVjZ{dk54n%Kp%_3BtjUX|pA}iT6PI$n@@U6-QxUF)^j}^w#yu_-0MG zc0H(Z7v6q}@M(m*U!~#&W%;kS^t!brhKOBkks_ibWIPcHU*Ho%jb$

??p*h8I}VrmECFrBqvrs$pT4H_@s{?J%QscWNa=Kk%7}XeC-9HNsMv?H;P|? z#7Lvk!%{#k%S;_#8fli9i$5#i z@`55_lvBTqT*i5aPmA>b0F`GYP>X&xU~@BTKT}a}Wn$)9C4wx;+YXCc0O1%py9bDO z%- znidBR5fLU;ZHg$Tg;u&ey9(@I67F{vHEwXi6k(FOE-eOg<=@HejAtnJ+#C=SYkS!`O0?iPlI2>a@jCV0BDP~liR?24-|w-<>2VyxT#4xM z&$xg7*gPxd>cbPb?ZD{QpBu7B_T<0CM_8Wu6RV#tHxY8P%lf?YSP^$ze5I5U4s_>f ze1XFe6m^GI__rO1{&&hBC(IqmGiL@3<-GCDIWoi_qd|uScCD7_>6SMr!xCtK)L62i zb&IlAS$>#mv44cq2zBZz75-vdDitrzfyNq#8b9Sb8c>ft#rhd(;%D!$Y5|BQ9fTYc z;TR@4LRPAo`u2;|k6`_CaB}f5lp??oW(vZ$rQIb5hKtHr=znhLca3A^9&EDQse>+p zhH`D_f(hG}2>9_D!s?&YkZDB$Uj^|yRFFe-DP_XtWG3HN1ej>URq7G7=qhbuM!QH| zQDu_tb#LjE=4@69Z}{ij%+oOpGz<8rdsqffA+>Om+ud`eTc<&W0=zv7zWxjc#2AYL z6SR8HVr~7wJ5D^)0$Ps=4cnZtP+hxmCJF#QNu-7^NFX~IdkAK zO7Emm>LNoX#hY$j!-3Y%KlZPn=}GId7L>`@^D!;8%Mo^!juX(nMV4a!}LSe(ReJ{0E?dqk?6eo@|n@Om+mcB3ASWZUIP|+sJ z`w`DZMAuH%+s^9y;ol#=+mdVEax;bcesnJXltO6E@@&YY{N1j%AL(5Fh7?Hxb`kzBZ4!~HW~*X*j#JBrnR=6N}sU>+7>iewUBmpxW)`bnLz zD73*(ajEGNUPGSv{JfAb_rT)d$jwVgLh@s55Z4EKKLJ;OJ^)WsIG9PLSci@T^PV6$ z?0s`>B4NZAiUMc?pFdOi zfB(vMvmXE591a%N@3X==@AWJ46AoUx#^CV`-gXv`yU}x{0)5~H-w%Ov zo*S)ajMu6Y2hQp^?OrL%Bx1JVtMS6ljs8Aax9DL z(eKG?nJ!Yrg}alXJ~+4~UhE6_8)H6eeMc;mu}PO6&MM z)7FDK%=g(lMS@;1A8QbCbt`A0Qh|z-2U_bm(!^YWKsb8?VRPtFrp$8<P%#6^t8LDk}_3;;*wqxilR&j z7{)mI>EtJOwLBw$wMWg5gw!`TA6S;(bh%=Ug|EYAt{{oj3PUkfrlP3Ph(FYE_`6P3&^u#+q{wW{5Na?K{E>Nq$yh^xvC<7pB7gZX)DS#D>d zPpO*atkWRndfL{wdUa@j40p+%XM#zfl4z=IDc zjR5E*8wSH`LaT3?%;;%VFD@%SxO?F1PFMW{4NQMya}XrUq}Z&e>FMN7?RYH6Msn!c zHr-u$0%bhgEA#x*92!eJl6yS%@Pt#vd^|=j`4TdECf>uqz2y>p*GOpW?g>N{<4n}g zv&`r7tZ{_qT@B-2P_2Qd3{NJDbes!hj{dfN-Kaagq6#yPpW1dK^u+pgAj30e=vz9# zeJpgdW`MPNE3)d>BicIj;l&wKbS1w`!GyuyC99F$?XgV6dSa>We5~dtN?F!dQ`D1U zKCx@bEXpHTQe!Mzq%zSR=V~VAXLC_nBwZ^&%>^;iup6PJs{QDq6!FMHBtX zmZ>Y);7@H)hW;jVVJ(Kb`!`cN{o(vhZQWye3^1rlO8Jxo4cU!>jf%Q?V&&vK^BpV` z4Q0L`e@Pol!=>OxK}PPulNFG*4>?N%gMK~~nU6|li$QH4xqgbJ{?M)4oSRp=VvR{n z=$C@)D%zn}|4{ z3rezTV=*qLyG@(>D~6P_xoixL>*E=ZliY1=7(L%$`ix-XjVu63&-MH1i=4a`w{mF6 z3GGY>CfM*_#WRu3rhg#PPyc1D zHpBE~wyne+J~enfcf=9g>cGw6*DME|o&X zpVJv#w%T#2H(uA=Uy7#`-A29b2hikCXTG|>l0BK4@+_Nb;zHV%SXl`Ga9;Mybw(q) z|J7*J{b|fP2_cZHcxY&-`#;r`kv=eKYqZ#KPO^}u;n(v2R9ZfW)fdCB@<0z!jBSG|1?E5dHP+up#-wLUcN zP~i)w#2S?&G$b16u6!%m17q-~Ybd}iEPN;EyPP(wDSj$5dlW?E)*T{~I-2VnMJGaA zq8dmKlTW5TKcG~-G=tkYr2fcfm-b_#6h8vd>{w!$SJ#dw6C?_V-Ad*s`Et)Nl{@%B z)Uz$Jy!+%rH?g1*6^m9!-wBi8C3^pb#Ig@3FW0fs=t`C|Y`#|-!u3B`fFG8jl z%M&kW*XZ9O^J37PJzrS2{A3rGJ>*NrENCOCNckn0hD|abvtlc$x6N$A6@P0#dDg|3 zE7Um+MGC#xTo@!c)%T58;>iSg17q7!_%&M^tZ6gLA&A=(Uz^*ihc)h=tGBSLAQXpHDTg4yKX9R@UBsMYIPf4_^!JmhP$(@))6_kQ+^DW+R4r4V@fS>7Rf*ksK@5}QGc z2|Ggn1cP*IZ9P`mg?`jttINGA@sBDs9iKI#K645Xkdx%-;c{EOkmUkj4eEI$DG*Yl zvV#QdPw|KvpL|G6Dv9-FlJHqzB0hP^?&ywtIkT7~cgXip zc1={p-K^-U%gQF%*2gDaY+MW5PJ_K3+s!##q$VRflF7?fp+LKy(Uq zWRh1anPM=Rd)O=ox5Tp>Z1-~G1H*DyzKp@+ZiTWiv*B(1x;}!Nc3z#es+~n}hei*j zcfh>FKA~0f3XfJpmVPfCmY0z zL&8;H51zomoIiUbSdPfkp-g;Sj$1s&4XMf@%hapji4OV9=<;EWb z7v=z=B_6XdJ-YhhI+J_4spm%8W4)MA^Tn7@EDbG8e2>D zbM>PH7YKw^T!LYM5Od`KyAJPIO?Cp8N`VtRPby3lL2>afpR^Ei>Pcv*k}O1#{D+?m zT&{UMl4J^8-j_0zKc0}~sn{4!l)@KioL<_p*j-P1C&?Uw6j@|9bfSi~C*K?MLG{@+ z#}`I*maDcZ3Y^&%(Z%QF?SqX)b0hBt*8ucvWmD>nBEdk+&g<`d&xZ%fq?!^{6 z3gn#=1M*;&^k#deZZeKW!~IezQc}yEu`*~$E_7eAjmbh+ ze7~-G-_MP_zSFA8RFG=1!{1VXA`(SxLQ1dSy}A6MQ1>k{(?K0FFp7LRR5+6dSgI)YP?ii6R)tV)DN6>p`>x4hNq#)2`jzb~hl|*ECz5vt?ZeIs zo@7*p8vUO{?yaD%#FLg1{{q^bP7rr%6v?;2b0R*r(1HfmZR6%XJ~LRc zOP$Yn7&l6X^Vvn`Ts4)#-6lAC!b6L=z}oh-**}r$AMr}2I(gB*+feG_E*aGWR{ zr#!^l0tvkO>(4~w_MPk$K{4)Z{wBU3qQ5hOQ1ll|?pG6#2`8bK@jx!R z#EfbF=|G6oNRl7Ib+vv({pG#3hM6qGuEKR(qLoBRq;rs(D$D9{b_k=+rT#7--Ezb+ z@Ago&)TU!R$w*PXnI8s^u-F0q;8Xd0GT}g2iIFtUp>H(oRz{^zYTR z(UoNfh?v_Sh{-l&bY%_!s;3IuP^mnU8B1-TaH3ZGzx`}gEG^rQx6uRdzID{@Vqy2J zr91##Jnxt4|E#<9(*KhGQor=)Q;0c`+Sh!{0rI@^+PNb=cEW)*JagH|6oDNNW;v!Z zU$($)Vm%iHpM@vKi3%!ok-@U1_S5*6M|0c{1fZ+y)DEr;!b*g7pB(L~D4-mLVRo&z zp_KH66jx)q|GT8TX<|71Shml0qGZ8=)f`$9;=>#gjrL?r*uW9YY80;JT-Q0Q3_GVu zKli|$!7DTrDeHCS#BHHx>&V(Yobm$(ilw5DR@vtQ?Tq-B{G$eI-)zm70@#rjt*DMd zwHW4No4Zz}9Z#8`z8uR}i`EfeQ7fdZqKJ^Ou_q~^BkZ+b9bb6goUg^E5g;uL&yO%= zbW;7U5XhclxRM61H^4fzSn%mF?pCUn!P;d^e5yDIjT#X^gTX;^5C0)|yALWdg42C! z!^|Yy+A5qfAaj58Y|>KRny12`U6rMWyJI_fGcLI{2sIh200XQ(cIwiZKVsT;CMlsf zP+!e@Y#=+`p*e83s1xtfFSyI0qUFaL z%tgY{BTrAsRkbv6!p<;L67#Y)xfQHL+rKA63f>#23{*CfB#_ix+ zE?cR&N=$`#SB6K(Nt~+Bek1O8jd*k8FSCZznOU2OcBrYGcEmdySVMpHyhwE`% z@U%;xW*IU^&LdY^>gz0d+e2mSn*MOWwcA8sYOjlriEgDBu-8(Z%TC@oHHn<|XcT?C z^>QLp2sUsfDYFZSj0H6xIQ1qDeT|~jV?}6&5i-J=ci20g|BAS-o<7R=v;U5D^@N?M zpdiYbQl%j)jW)ckJseS(i8D+tr@N)qB_3=Y98dzQE2#-1@)LOlBYT9bTtrs7j862s zqxG}}DATmbBY&;}O-v(eTrtQXcvC^=n8SvSuIxEPM<7CPXD_5MC#1!ab1B-x)aL41PR0evvr6=&$oEjHeP zi9qe(-`4cmx+)@d3nN4}nK>Icx5*8?iyXoZt5a!`9LmzdBgupLHedjwA z8yAmSST`Z(g96Y%G7W@D*X|+;gLLWaf)+ncx%KX%K^xfoXTZnzIe(lMvpfp$;HGZ=eEbV_?|HpT|HgvO0MjPsTljh`2A}Aqk8!G2E53e8qff_dokNT{ zlriWyMEOenom$_9kRBDuDEVjmp8Tj0FOvJXTK^)w-ovtSY(`8JXyW6o#yVu+buRes zY<-Bv;>6tuR4pzRET>@gFayd0lDa`^~1%Vn!%F_5rHYZV-Utg+C}chJAI!yl!Kx zSg;z`ziNxe@5%Sa7(KJaTOSvf@T*81a8R;BwU z#3WRH7A@a@wene|1#T<-ZImE)RjCY-x-*g`%?gyvAyvgQgPpKt8}Rb zx0rdEt~@%;1MWi&Zg}Y|Mz@|%i&e&k2TeDbc7AQ(>fLmKp628p z$s9yrI)Q@<%XKJ17r}JaolrMfd7nu|*4&qg6@ziB3~4#6Ydox?|AhV>QQB-Lbk z1Et$%k~$xTVMuS+zm8=WuhKm-2u@yBo7{%)^Xn z30lTCjeNse+p}qGh*s$u5Dnr!ll!U#`LKuTi)csLfx#k&apqUB%1(FW_SojFI>KA~ zE##X#sOHiA2OI#=3elc+8;nMhx+RhR^|t$b`EQ*uHa6BL_8+YV=N*x?U7Z>2IHMuv zpB5Rpof{bU&UfCh(rF6L_;3A^^`PJ%bmwv?7eE1d&9_LgD4$)v;_mQ_{yt%A{-2I2 zBJTX!g!db^wYNJCZ0-ocVt56?A;cr_${mVq}O(Q{lb#f@w&jxeq zMnJj?M6D%qP~Kmq91od%k+ZFLj=@|WDr9D7pM#=YlcSUHh&y*Ds_D@FSFN(re`Utr z95HjGWmDaOlfO8@F}+;t<@^iR4c6cCY%r0GcQg+?HmnJ!E%8q0cod^+hM!Tw=j zx{FVCdpJ_N%l^^9hLM@XUJE@v8R-g6dx$(k$H2o;IUxQu=h-!&F@JfgabraKk*q6) zN{RKY9Bl$%^!C#R3CX{&?Rx2wpV^fbPqRBs(QJXU-W@+UypEoXTs6PN@bo$L+rhL1 zpe`)Z$1m5D(+vYLx;!x5=j%6}=hSYmt}Dh8%*TpC?)AN6M%yWo28Ypii?5}zHpu6e ze=R1Tp6zqh74Pb8SL+)}m7y6HBs-e&zwS_)oxXLexUMuBcpvjZ2`DUHUe5f1;nK4J zixjd~*Rt-P8w}Kqdrl0gpkFpL1F350z4(?ub1$KiHh9}U0fhM#>G;mpd#21cG*O1T z)jhq1P6kI>W0)|SFrMWuMlTGPF1IInCzKib^e5`I8dAL|DW-3C3)0S^KdqiVS)I## zc`OFaQPR_E^Z)kN!oCBz{B~XAf4^7_PJ}3>RHFVHV&8krmBU8~DlWmK4jV9z=dX03 zP4`s>@Ej0qY4!R0;NHa>&;7DV1Qq5_+d`PseLNIr?~%bB3Pz6^GV5c_wQHBemez?$ zJ!w{%K`+oB>IF5nt#40`pTV7kQ;P&cA%;r9-n6#3qrn@^eMdvI>v(gq-m=e+N3GL` zyKp1HO$Lia!yQZx*x!t36m@VV+i6`8$4>sVe*y%P&on*{t{%UAgfISVYrTaf>T(h_ zHcr=}KKB(^k}n>XXn7&4&*%Mo2&Ef0bkaTan?EyWQR4ZLDlbgjxgUPJdL|Sc^DT~y z*nIoFpfQs8Fu>@cN%NlKRIyreHo~OP4&YMDmImx0`6-y*O|fEwPRvnUa-*zXXJL-y z)?w^+>C}Xt-$Og@w>5o|8ExdbF`zI$CMxYrpzwB?do{Neq3cs`pf6RbvaEd?3C*{gqgsxA_^4`wD>*_PFX6v zyiy(SrA+F8seD&!oY%-(#?tivQ&2@qHUA|nTsKh_GnH8uo((b1ju(yt{=n~*46R=x zGCufFI`@tXus}z)s5?yoh^Ga*hE;-8R)=SkDK>N&FvDli=C7GwnP#-TunoSY+Rnx? zAm{01@bCcF4KXO*8INw}qftD#UDDa?@?SQ5ofVq>t2tM&fTrLdd&@G(21)vd%8OVu zL6*qKw@=8A`*Tq!`(R4r`uK-nrv%k*0P(^c%q=c5ayY55CsAh~6mZEB#p9h?0TNgK z9TOw(5hknhh_oXhaXs6g$eiPuK`4~cTn{R7aym0%lDV}%+@Azv9Htkza?NLc``F^4?D(%cqA|uQ7bvk z^HWIawCPeZjeckr@$H!Gw6{)gwKLsYc+ya+}q%u1j zl>tBR8lUvUdd((-WdRAp2S4u+kBqURYPJ-G=-i2XNM1_MKD;f!g?WoQuig$FQu)wv zTC{7#+30kQW}>LWt}L|IY-ke&DIqw;MyDPpC@ioHghScXNBJUru&&+Jo+s%&=&%3X z1BuYCer_-E@{EG!x+B`~^(Es0;34(9^*f{~juQHd03oFihv85_MtlK%j4VCrLLj2mZZg>6W`j zqth%N%sUHS%DiSfbQ`%~o>#PbCER+kx?OLQd~$|_s;aOYto}wznNrR2yoa{NxTVW7 zG*BcRbKbUd4hXA$K3`efJE#jwGdk-Z?p;VKvNuugwUV;9&eEZTEpkzbYtPb=+v zD)LsB z+MKn*s&tFXHN%CnYtNhcj|~`q2CsMa_pK#g#=jvS3AS zm-w<{TdVmbX!d&*%7Vd6GLbJ{OWvd55&9ET@T6yWBIsU_yXDZ5yj>ud;31wr$(CjjnIseNNxTz7e-0dj8ILMrKAvzB8XO<`@FeX-z@W;8!}| ztij#Weghy#@UpqFk^X57N!iYaiHyx@{Xq><85@m%Vb`0PDl4hEEO|89GCl2}Apa9y z{?;^9lrqU`6A|iT+p4e-aL8AGoR_CLsB;-|RT(J9pz0iX3s;qp;2Ky!qoYWDPi1=@ zZeNOLWIvv-rzFvlAUMn9T8Wvgr9Z0SJojE)7*N||0)b)0=*#ctM*`Z$^bw72wqC^z$z!Gfw-?v*-A=tjjO+=B+k#8wekak_Q61lis~w50vJ3{l&VO`^2=^7w!Gk= ze>_j;vWhOaD=K;0%#jR4Mi-HLE85Z)eM1!ha0@3}Sz%yu^D=fHcc0o~x?hl7Dz(C+ zo8v89g{52OB#wD;;j^tY12}v#MZUEv=xwSsfKDma5h!O%Fsvstd=SK`A50ZQKdG3E zCcB7p;Wt4J*67SxQ2pbxpxHfoR6LB4`)CNP0od%&W+H>BH({)iUt)qMT3aRD*m?dC_kb?ccrEz z5+x{G6CO6UA>+f|?$C-?9c@O`+N3gSL}T{BYFZRU7;@wLBhdta#T}mWFdD*EE}7kf z8WWYf(3(qeQ9e)@X8mh-y^BBZ%35qjho$(alMpo_b(M!~V?@G4SR)22gU47akhKGq|SF8P!h zuT!V)nVt0y1^)wx&pDYvWl?5aKH3buO!zi}%Jy#b-{kk|ySMbwThH_IoZoDp`FgT! z9v$tX=Q{1>cgQ<@xD*NYnh>u?t1-DoB74*xt@E;6<-TN0;7%-i4S=S($lS3NSCJYEm5feDp}$wEF$-wit6`JVEqR6 z&81Mqq$GM%bUm&|1p9GsE5Rvf{ArqO8P>z;jm^aGdtZeMZv)(wnl zdcyXWT;zt zCm}HgELs z@^ueVw>r&{&+L)`*)i^x6cz$Grc42s?nQWK7_fxpO@-$MdmaOYB)@5!K7V#lH7^?0Dv z$I*Dx&;hEBqn`nchrvJJASW2q8bE}PXFEkdvP5`_&kh*T^6K*=5}dlgu}(Ud@uMC? z4tR~u-o>ld%&UBTFups@08Q#(+4y&hwz&@i=rLVAr{^AqI2`WYOs+5v7e+7l=9W@RfkZ-@s?@XLc~QBCK$=j7+c2-w0JAVs;{s`T8xq z7*z8$S=6e{Vs z7A7mrc*v8jKo-iilKzFO#$u%`4A}^XH&ZUBtXzXL(s}4t|H+0*3v4|lAoo{2Uo3Px zcaG4?N|~lOzp40X9>%LcKbmPBvJ@#pEmhvc6Ro=McVso6$%DNdw%#)#bhsM+^&(|E zKdVXjd{Eo~b<@+|&PB{#MBKE9@nnL|bJy%MB^De4ws)-_Os6|&u;?~tGC|G4vZ-5t zcr)Ap;WSL$g0y(vw09Y~EQbm#Xe_0;uwrlV%vBxCE%c;c#0K9}u4IlCv99@Yw0cn) zQF<8OE~_rok2Rw|hUXyCi=&jJ;EwAjosMXrR5LVHAT0pk$A`Dzc8!u~q1s!Z#>wB# z&5G5$_g5#o=9=&_cdDD+7LFoXVlLD*AMIy5*o!O2zPv3_NJsWTr66I-A(rNrbwqbL zIUkt6ng{DKEV0haKCDmwnc9B)-+)HcnexbC_MXAuSZi0?z#Lp)}jqN8_ zJ{EWW#>U{wTbHZr%dFiTUmc1mRyU*nQBw{)OkrF;P*VPH_YTN-_;a(DJI#i>8GT;v zY#Zaw8|adO@$>Lchb#Q(tyUCNDwTr0>TCzsb?Osspb~@&KTKp;a5yrWd+;p`uJA~3 zI0VLX(5PC_N~IAcKS<`VH8{2j9NJ15cb`pK2?mHStz#3?BNmbcuo`+ zU&KsaIk}rNHvccc_t%{7bI(q1WPTa9Bvmxyd8+{e3oHTME_&kjwR#&T{vn_4*vRnV zInxJvjwg&!=3cIztR#Ba{I#IzpG27Biq(cRbz$)P*Fr29k5WwMpY>%Pr4Hp_Ko&C^ zW0Mp{SCcvkd4b`bqd;epsWa;T(!34kXE)CmlLiQ;upi|}^2QaFn8tiCZ``pxQS|HQ zd2QY0@P6@xn55#e{~Tar6T2XuMG;60wl2Yzn;@q+j{2?rM(BkFVkpD+>mYa%r}Id} zPR%fF`9=&pB|Yje{nb%7F`eM`n(L6>05m;I+mAJy_~%8UOpHLIW}R;wK)-J;U|3SmwD|{ozp0-$}3JmTY?x_jkO5jUBJw z0gh@$#A;x~OH#FXQ+}B#8zVP+o>AKsC~%21`MP_U#(NU}Dld+x>mQv6;#!^n9g~ zLOm|U<*`83nb3V{`m6Dpo`%ZpAloyRDl^K)_%h)@Cx?mf|Ep8`du5BfkfJjT!*H-y zEp?Zgo$+~aN$E*$WJK|Z`s7Df;f&x` zUssH6WCz7V0`40w^>(@NMgw2NRWd1Z# zzE#mTc98rdJ-~;Uu>0V{TQvI|^j0T%#hY!~0wzPJ)tvF1JPw)+vA^8QvcJd@tEw~I z*l%sh-_#}4PGKzhY=U=xk36WI$75lUj`PoPj!u#o$YvjT`UMkY4gl>}vr3{tFVki2 zKAie*6Q*>`e+Bj=ilbM`T9_r!eE&K&^0eYQrkVe?Vf|XC*n-i?9^C2Hj1~v^_W`k@ z=>L*9e2{|pIIUOf4u6ti|LNJ*^)q3Y3Kq&#G%`B)NrwHWskR&Ve;B#RX-O1*4#{^l z%RT6h=Du{MU*rC_P69Xi|1fRufNSki(4m5}xof z$FS|LPGAG{N zj1^51*B2F?O~x|=sp&ya)#w&k$S7J2I~t`qmLn%V){XbLgTl-?J8`aqmEX!ZzXz4} z3i&^Y5cky*Snc1{s9VmLDcSDNfpn((_b;cYD2L6_t)nn>8;FL|1O^K97T_HEhUb!Y zoyDmgl)0|vykVpHtxJ#OyK|4gN5hHw*^c1B%ZqTkANP#2AD7js7f60<51?x);a`K- zqW_#F9+kagc5Z))Sz6S49HeqptwkU9!zsj;2Y;SDpw!FRqhiIYCz4??&Cv-fVaa7c zS=U6JptYN2bJ!%Xf}GLSyYEzIH|gxt77!=N#Ya-~u&mxwk<`XQbK7-uoPFl+<*JFd zSKPC0JQ=PKg_kn`8l23z#HsjtHDnfY)W?H2{Vu%OsIo4&6l*Prip506al;Y!(D25Lk0kqRuf7ml z&w)25z`9l5MsDf8vAunRkWsU6DFF=Y5HA^}J6q=1j1_#$MaBq)DYleLty^0BDM#q( z&oq%6l?R8dE0uHsQ*0}o&yu@=@dXvSFe0B8q2hF zUIA@=J{YfmYmISI6O>-0arzFAdFYwe_0BTKP|=drWO}!(p;Vw{oV!13 z8u*f3b341M8ZNF|fUG9jG7;^exjZfo(@1bwQhRNwt#5e+mkNp@ux}py>0JF6^(Jba zWhzfhKbeu*si!8Tb0|<^qs+TMrP|i2*(yBFe2;7Ou6a2}5Iv^w)BjT_lL%m6%`6zD z5oSfX%1)*f0hPD%Dv@|&SBiE)c&HPVkO8#DXnKxOs!A#H5B@Ij@8;O-svd%}{iPH| zrRw9YGnS4bSc_WifJ!>EN&pqc!J0`{9QIRfzwdq3nEqc>+B5k}Gk1fRsVq<4GsGt5 z!kL$b1LOOiffZD99{Kyu^IR{^F#$^+>wrGyy zoN;mm`mO2jpVD}P?hbJY#vSZ# zl&Y;YCJ?9(Ds=Q-(dr=;EsbYFir}D+XJAVr#)3~aOIE+c7F%b_#`if;2>Bg1LptzN zgOO&E3mK0&FukHmY8x5UrfTh`u&O?HpSQWjI$DD7ldEHDj=k_4{WXXA_CE)2OP0b1 zGRDPFxYHtZr>8c-IpSSoK{IiEwVoz0hVNW^8#i&HviT=Z?}t-nHvn7f!dCgUc6N_< zTQ4#hvruoTf+gwezV?(A;@}t?gPuOkup@^f3*ND9T|< z<9)9wj%p$ys>SA3VQZ7S^%5B$EsUVFdzjd=BxeJZKLWzU93kpVc#fmxSOMvNNpbkm z_^mEdyrpme{F4LW8_97V`rNqY?%Pu<4M#y|{oKpGT0GJ(BvsGOdt;m>x83u?n4}mH zKie#nP2jrV?V};IEiZ3GW3owoyH|hruEZAl;M=J}zKP6*3%}F`RBe5Qz~75_-R1YE z3bXL&#|jJQ?3pFp!NY2qLys36on}~4GTOsbXiRkCj)dAV7c>r%6nLd-Ql_^A&6GXlgIE;$gBb-RcsV!&v?P zlt0DQnu1!=Y0kPi@02FVi2iD}GkMlgP_EJWNSn&yLK#e|v40;G9pQ6H8YgW+%HL7D z2MuPa7md}t*!BVm&jrI>1J@^s*9}%CDY2m+qTvy011f>M*mT6BrYbE5S6C~_!3e-; zVgyE{J~o`@|9}=^&Dw0A))$lwviUSWs{&q^eDEkj6bp>#l*gg&amETblOL7^x8Rac zweiE6?hUwAn^nwpwC%&i?_xdppRLQ^(?8p{#g#p6KRR7B**dR^kbm}XBWX~8i69jG zq9>A!1@I4L0R;sN%JDAz3qi#n8x{IMgewHAOe8Al8<>PAB=l>&^ZE0$77&QWNFHV2 z-7V`y&*6DuqLtb4YJ-!T-e1!*NYTXC0nX+~!##(p1idSB11sydxI-DtH@m5UyZCho z3OacLxj^IK{CIam~(ek|CP*AezLOAJ6 zIN>nFjIACyi=*kK>9m}iw0Uc%_z)J?0abnNPax&SO(A< zCr)VB3Q2&yn9{}9qE0I)zq1+vu;J+YO?j8}24i*YT`kOiApwNmlq@5EV!flCGZ1N= zXSBOrA_} z(*u4>_E@-+@RePD4ZSUimYDDA-=pLj2J9d}Fa{a0sQLRQZBYE(IDClEd`YLtsQiNs8~gbSK3LJ6am3 zNt&P7nT5pg8B7`;P0XwhQpOe0@DXK#k`{`XxM6Q6Ph@gLGq83b6|;uHP<>)p*NR}$ z5d3b7Z@ArC3*i;v3EDg5Yhlel1izdoZ?fWGC37C&Ee1&Sz4YQ>O6{5EjXK)gV0Vn= zRLXI0@#ZudGG+mFmbi}afiyYljUqX^e96f zeVNK_AOxhT>St)Bs$*=r`ynHWIy54_3nY@r3k!ZAJdv*WvdrVIk8D6_!(%_f>!f+g zXL`P4AT?B!tY~$tX3T4hK}uqT)i>LV*_6zHwwhm-AJquvtQxMhb->G3or6ME|6^hA z%h57_3<58X@`8xW1(sEpo^c_uZf_powcf39-~FPw+Kb@IX4jD%EGtzRAQ}PdGJYmM zM)Xgmv`8d&)JRvr4Cw)X;y~FAJK@{1aHj$p&PEeBd$>2b_J$wst$Uz&pt=|C=P#Dr z7rlFl46a*l14BbZZ0vAi$F^Q^P26i+4&Tx0lij&5?vJlw2^{)2kBiz%3`JGw<{vAW z-Ya*>3wb-+HP6Y`ywC|Ru>9I|;3U3}UuKjwLyhJs`ST}9Iug;r`34h1iUwdHfx@vt z&TPM*Gpg844rRzYKU86tnoyt)3Pk9GO}B6I^~HRutAP+~I4neiEyreEsSUK7IA?AY zF{m$sQiBWo+_<`UVi`@yb@Rp2;WfqxfO72RU4JX{HIgaYk|q-50-hBsw;w3HbSMC* zpt!28kNc`7610dRIh{np$j9Wxd1Y>XEsU^`u=Y_H=|?_(Sn`M>E=4 z-=hAHlDM}lqmaJ%_|+bD0-Ey-1O6rwkrcPPdW{9hoSa94Um}WKa}|h|O#%jj=Twy@DP&>ZX zq@2|8;p?0V=NID+%6)2$3E`x-1D(vtCL_gAH!*UWUbJVp=JlM41H^K)$MI92Qn1^gpneQzUd+?eo~c!Bbr&q=sLi%-vDb@# z@~ip~#I{K&wGZ>?zMNn&$1a~ugLqj8_jD@AL{P+=vJmXCEg=ydj^Mm`oxyz8YBFcJ z*>8`{ZR@Lw!|*DPw^FAI&(YmzOu$t?8L~RhuuA`wj_#%_O3KvL_3286`tAf5>0S;D zNyM6IjRIJ2{n4Vg6QR@K!brGqHb0p+8T`nAl86%vHpo}=Q+ z4B{gDVg@wpaRl$$ECK3z2I7hV8y$KAbOAipr#B^%bP>h``@XlXdz@1q4Y38(QKk}T z*~^;2YY+AJLHJSzf4`XX6M+P%><+lbVOk;LObfkmQ}m#~G;d}Lf6*e@Ut4Fi9HqAs zn2h!XqFUuKSjQoxR~3}81{_V4esH8o|7P)EujnA`j{a$AVN#PJH|vrwBtfC_ijcsg}(x|%pG;-y@qVfF=!gg{vk1Zx)g?%_4K`3vY`I*kZ&EepF1Eey zv#6v?z8OoMfc^0lGWix)i^JM%{=Y+#6iCe`cx*kxjT*#LQh4`~o(M@r1#dg^Q| zdAE@;xSw3&F*xJ2wk0Y`7S(sA+x_SrLpSed^7%wh9Ur~^MHe{SG5~;?MfA|o>*nse zEsxnLW%DEsH!AI!Y_BpqJ_gRjNJ~Bx1^`i*y|pqlL;+24_O zz)AX#J27$3Hz+75S`Rarl`W@$Qo4vYEr`g3V?-a38sA}Wk^oQV92s!E$x z*tWvIsPawkBG9j-LT0$jbo9F8?|`GJJ=?ImokH<3zhX7t&vaipKhq&aoHTRde`ZPU zMx8WK!Eb)i-ODyw`*v+XRPZtE5&C$w{qX?M_MmB{G#s6;3i0>vWA5#~HBR;a8GVjZ z#Hupw&X;e+XSq2!IX7B46X~+S;$X!;X|_HkSWrJ>8hotd)yUPz4vXDpgI^gQ6cjYb zhxO+-LQYN%OtySv&7aQvV_EV4nvXdIDdXqFey)@=VW;3{#+;jp+lTJshrp5W^{_&0 zI0BiffL`JB-Vr4n^`DfEDBWO}<6E_bQZ0;R;vl@yI>XFWf z{&s_#cQ?ewcPBBk(cwFOM`M15r3#B9BSM>N8=SX&D6RC4NR{XWVR<>%m}8?u65_*U z$P<1i8Z!ED(Il82obc5EFoT1E>zdCxQH5U5Baa5^eW+?I;Tp!zRSsK$wi{$V&tor7 zE-&6GR37Xux+ZvN6d=r4d+qkS(|6OOg5_iuIL=v;ggM;)Uy>kTbR@6S}F!Q(te-9TRY z$~Kemb=^G^zsQ1;FT-UUZWRkN8l1tqc25~fc~SDPX|TMy@^xYG;bhZ)fK1|RzTIz! zfk?P-sq{kmfN{RVEPYmkpDkVmyP4kOd)Z$B{>FZzrBl6(K9y3{za3zkxqO4s-hRV_ zY*sDdoPDYJBRkQ)3X}cafyMvuJhTPBo^u?X90sCnJTUEzTq%z4`_1iG^F}AFK=EH* zfaAYrah%|r>k&g)nrv%&R4PxlL4M~>u3ke>6)$bfO6BkQi|v+IAT@m}^fS5hC|V_q zP~ocdeIdD~x5mRVDV}?fe12;*sf61*wQj=nPfwJ@F(sc9BpB`7_t6WQ7J2b9($n)6h#(LO*io2AI0+{0diQ=o+ z@I*KsGFc_*c+|_JImpzVtkv$rJg^Y242UI^2DelB?Jl3n#N6aP_5>@WJ~bUq=MKyI zq*F2TV(sm7FvNSf#q|j-?o!o1ca`+SiS4h(ng{&dybM;HE@Nj>j74K;m#0#hyTu#2 zi#u$mEkrmfl=XE++7_Bal|!ytJW5iJ$=g80>i=sxsot&E>ac4BGvf7)mW|?Au=6Jp zdm2E+hAGQKY6go17uWhWzKD)|FjXQAgS!fA(Vv+6!{}7GS*25u9S~)6d#5b@bpw4d zVNud;Mlio(v| zQVO0NcTq$9P04&zpZ}-881^}VlfO1#vlA$~tVb|{j>frLRNNgaqhy|I24gNF04+mL zX0~&Ziy<6%O_X6^I?+8c&AnM*3A;Huh{hZzW`eW#^_tB%bk+~6l6Uiy>Ly74Je6); zp(#lGnV0%Gf#mRTX!W&28aS{Ywt~yBy~J8b_<1YuKwL(iyr6|popKNvld$v zLa803&VZBn5s0Eh>i$xiz2XPl4(&K;PD|vN9gE@X%5s&^oRz$l5w~!s7dZLNW3MUt z3S_E+Er<9TP;z>JHL0o27tLKl3p-_(<9K1Aiz4w>Qfs6Ddg}|V%AGf*y zGQ5|Xp9O@IMRO=--QN(tir?t6K1r}}CcfoMd3G1Gf298Ii;%?eYV`9uaWg<@H-TxPIudol_6QYg-)SKhxUkKf7Ew!C!5v?^ zK0K}~b8_>G(Kjz1E7&Qc6#nk_3=rp2D-!$qchZ*!hSY1A%O-iyrv)_>UJRdmxCF!x zysXlm&}k&pUGjFE>Q^^WsD2j*AWNv%MKEJ0T3?fN8xyx%B!$hOjTSEItKqjA3Gkk@Ajszp?U^K)3 zT~>^VOa1$Dt6eku3bQn^x z3LOQ9f-~q}Vj0QfPHXgmj3Q0&v7Ap%!N`Op%mGizmhCxh0U3xWhiv2o4Da6d#rAoH z4GU$uw&^LfEd9mBf(V=G*AdUmXm3trbP6>^j^gXjtMlQ+{Dl7jdmLA-C&(=hK!)@7 zhFtNRWJAL%S}}QQ@1ijNrR^_qN*mnvrvqkmHn3jbZZ-elnF!{Y~+wo>i+Y!e_cU#?XqF@L$P*%Bxu^*th}0h<_$U?vjhhMz zIghZB6r1drsL%{8(f|7z_HW>0$f|8*;;)XSJ@V9F}L0U{)0-(C2paPZN17#Imm4EL#^lxdQF=R>4 zI!cbzs7t{KX`vd+h%e!@UTqKnTpZj+2Hfc0UCltfXCn895&-Vd8;dz)YpHU8dr%yn z1Tfdmu;uhtfta`&^G*E&9F0iWWs*>x%Gt_NN65l-`>P#&tz^K{G0%p3Bti)HKraUr zG6YaaboyNB>8g;Np0wLpkLp9G2=qs~VF>2Q;jfnB{B!eHpRVzv9=KKZ>E4jf6h(IEVu>8&k z)AqR}U=QAiDjUM}uRxYGY%M6QlPEKaF(yLBtkav0NQiXrfjV@}?hTXYk|C@L&MRt2 zaZ)e|pf5zUJMV0Dt!=FteP5x?j_w!-<&|(<;9+h~kPJBhfsq85;D{(b;+Ik}c?X{Qf`YT`KCKEh0fS*z? zbP>Y+Y-VRo08%nGgA>_Rgv$3oe6J&@y523o-7>cWu{Z+nLYfT^$o7`=W)CSffRu2H zvp4jGz1jM?@4P`2Z>pf&PuDiJeH-W_rel z0TL7Z3zRS^j9Ud{q{Y%I{ASmI^Tq)1iEB713s?FR0v8TgAi(f3vgFb-rA-$8H!*Wk z$@N?Zd>dF9!QganF+Z7rf~rXLNHE2#hp$CKwLGj05P_+Y0QM}tVO|~rDl1_A)?bnD z5itfRUk&Tjm4gCTtub%_RGRLw!NZpXq-^KOAhHpFf`UJ4we0XH3ngleL<=M08f9RO zZ!&#jhPR=gJV0D1J0EL*UbOFo)l%4%2Um`*ec-5ZOloH-ZP}Cu^mAAJ^sxu}$6>MBSXQ^*)YHQFfxex1~Rs zme5T23NZC?v6tIm_>-%DTcD|DnB_n@iLuJ_nI*FxGShPm9bF(mJs525aRO(KP997w zMNaB(&o^{qL}<^PEW#D?BF@q2cG_S{#$9@D2zh54EwLAFK0@LY7wPOAQ2;qni)A$4 z@Ft78OK7adISBp}y6(r?8tQuPQLBd+u0&u3;lw@f*7j{dikm~hli7-;a0=T9i}^8M zA>&JE(OAXbaJ zieRv?t=K_D3$P9tXgX=krjRJ)H}AI~1f%!i0{nr{DLD_0*j%^2a1M6wwO#3AN5=be zmfsi8b=^}G2=U6*3|&M{Nf2Z6_OX!k9iyMQhgIui~A7`t_eesh<} z%Ze=fyF|Yh(C-PhSd(qhn(&%}e8IlKss@T`tsVRHup(blIjR3yvkCp)1;)s?Y{dC> zcO%v1FEjReIGZQ$iiI-}G+r74Ae4VpRoB-;T{8(<=#Y$797XJF`s%W#u(%;+aA0s< zMMx45$XYi`z%7zFAA9&Dk4QM|Y*dvPu=b-x*cER}Qy>gWxTTK?I=fV!-&i3Xe>AIn z8%y?OWReJ&{I#=-q6Yq0^waUoSy96&1AkdT7x`-L&4Ce{9op3>R{h6H9D@GQ=(L4A zxv&3HI3c3+t7JZcdnkdE^vfk{s>7Q`7itNS65vHES7gw!>76mUpMM$4yLE>Rsl2Gc zM+4Zx*#-uJR-%65=LrQ=AeAq0)9MaQ+^VI=41vFI@ZxZGj=Idjcc+2wPg{0|`oiwr zGmJ4NDukfy_6+)JgSuCeBO0XOG~M`p_@>7qaQXr~St*L0B0hZ>!pW8;?|r56MOJ#+ zP&SvF90)~8<_YeJxJz`DR-AG8Wr$IKEL%jtZ#tXfUzPRrA36c z_xqb+>tVAYkMqUT^mW8EO&U#o^X;aCM%yy}m|J?2<6$zcn%MEw(Y7wlSP{$p$3*gJ z8TGhKyo&vM5&o-=Hv1VBjQ+#rM17pq$mmCFIXr7uwcW;C<;L4QM%P7U?shtLiUy1M z0sdzK>m{ywv&-XI!Lk$7zAG;=Y+tQ1XzY zEuVxVl#A^7B>K3ALiOzIYB$$HiDwpOCKV%cNnv<`nCr?5u7 zdk*%a1!`jySW@L;Qan5wr?8Ci1G=^vbx#o7AHHKu=2RDVMsU_r0eW!RC$;$Z5i8!1 z9t1FKoRUUI)74#e{H{v>;)<2IUo zbJ<2oVUK8n;7+Ds&8qc;-&0cOVz-NBd`?bQqnx5H-%F>)IIB%upP7Fa);t(r2DdVr zxPy{f$C`FT#ySw&Lk-=Vj-+6*Y6mTG)rJ*GK)9Q96%3+CQeA?jLYfU&`AscE{qlyg zuD%l0nith6R+R4or%&*@z*_RaK zvJioyqQ&Kvs+AP+kl|Dt>1O4KO+aeCnSauM_%kP0XkXy6n5E?;@n+fkmox(S6e$_j zGd9sPqXbpd0;dCGBZvFDnfULVVZ-^XSG3A7R_b*4IeE=G^x^4YPOfBSakvYoitR>x zy)2K(+fsJ|KXL||^HZ^9A>oE|yiu=8*CnxrTS|lBy6CFQ@54;>zFz6E`Ar#d@ox=J zuRFXVRD6B~Dwoe{YRflH1=Hi+og(4a`&JJRYYDc4iu@0{J5aFJlM+YD$mQz+6!Lm`njJg_LvwzQG;~GX@MbD~IlIEs&F%ReX{ye1*pzBm zoG1E8*>ZLS91wtsxf~a34TN+4EIOUGs)qIo^V(^Ly;aQ)ab9`#w^ZJ{hp7S&N8t`{ zYdb0sdi#&ydbN!Dw(uP5U;;4n%vm_Fx45w0V;**2Sa0?T+(He+gc4d?PiRDltEVSTf*?RY_Cx4@xV+yFS;xe~%*e~n|IW3b_!&I-6!%B*yRp6I8!h(VO1%G2_OHc@wMOWl zmbo89pR)0^{z>5>^FQXpk+f5g`x&lBa{m8D^TYGsS@Xz5^fuHj*M$E+pq&f-do>g~S-cLlTJ z6XPQibjfqRXKGVAXwcM|032yd;ITquk-Ph!#*^}QCr!J=+nK6v${0bg=d&a4!3v=H zcl%wohKuKy_qBTK<%`KfBFeiT#Ef0ol`gtKlD{0u$q|CoRd0u99b1~)4-M{5RLr&= z5x$yF&-S4ezDTo_R^3*Z8}Y#+zwnRne|eRVM7}Q2Jea+6y+vyIZlhAd1`Y3ULdrD7 zIvNo-kr@$wzHnJ_KVS2roNfnTlCxJ2r%qsVGhQ+k8{eL%xCNBC$_6XM zdC_yH#3fMH4BWGg^!6{G8E^V^+ZUM@w`Y{wt+CxeA#3o$EYIcH2l!0h=T*L)rTdiH*~J65sdeLlGGX&Hg0Qh>jA@mp#%GO2k%U z*9U2928;+H&-V*}WlIT5{M6Lni9(1-sRg39V<+p}#;?5NMc{6xL7B-| z4_0Fy8Vkq8-3As^KfbcalP#_=buc$og+ee>ct71CZ$x*VT;+r+FuRhDeKqe@7o34Q z?k22J7uF2i$b}BJU^XpJy=N9%QlICiSd;1%NkrIEJIocHG#cQ}_R7OhNQ@nvlshXb z8@U!m_myjPJ4JIP+gTo{X6H>R-UL^eT_2^ZVXmTxj+uS2sPWju${Xc6JA^SOKYiN? z>%xjhtt`(XbAreD13k`WE1Xoj=Gw6pgu!Ac+{d;Kc7_dCZ)&DRO+@csjmBX2 zXM$iCoc=$MK_t*_Z{^7+ME+&ISz4K7@e?KwGhqu5M7)|)N1*kI??k2yN9WBeIT_%O zSh%>nz-q0du2+rHmNg){=ywNwy%!rLSW<2ra^*|2gUwjrmEFA+!1WwC+91LoTBXY+ zr7qA$o%Zi)zZ9nUrh@v{878Lxa%D1q_O02y^zC=h>JpRM?ti;C8)WL?x2>3$*xwkn zs?599f!wC~(|(@NqAedHp3M9Ky$?SPJ=N+wsal?!q7B{E=HG8BSQo=zN}`Di>Zm(( z?2_+>*}Q0QVgRX^KUm&Kc5W9>OKo8d)9#a+os<#gHU$n4T6Y|>M>bbnB{APywAQUN z?Z11Nu`GS2m=5OcK4>a$ZcN1^Vs|_zLGN0QNQ8M>SaGY-`bEhFMR2iZw+qX+%)?UGZ4W@iOA)7?MfAjvBQK83o&uO{7ykEd!DOtg!c+@E=uC49uCVp}bw)}8Y)HFwd z#~4e)(}Va!*E<@c)SIodzWjH&Oq+BQWLCkjk6I)uiXD&29pkS~`bfWK;$)m*IWF@= znEo5iZzTO4`~L;bCsBBqz6H!zAcq)IzZpbZAPojTCS9Z{p6}ev{EWuTa z z1t%9g{N23+RUwy4)E{iEFL>)-_Tco~wSKLoIk}7aH`+{!keLlm&#h7b!X0Z&*(fJG z4G4sb{VmLNq9CIw1$P5PNN&E;3U;YfJ(llk@uegHR?}ptD36Ii?)*aVc>TMI zq2`y!yrf;6V(b6G+&c!@8nkJ;W!vU1+ctOEwr%aQ?b>DAwr$(CZB2b&cSp~e?&&i# zXMUWYD`Q1Q=2|P>m2uryK2KdcpR&J*`r71)2$^&o(!CGk&zX>9oV}iu)hwuwM@UWM zo2Z*TzGorh9b5#E?U6wanK4Z);*`yV)=H?e3DHz5iCjBl45E@}oo=+v!|xPppCUWu_{-wm>Vk9Fe#rASQ;{jNgAQAi>@D>rN*X~}<$L>8Bx?m2|D zB~~NZUAwzYL8a>LRQF(ZKp`--8VpYH%-JDewUQ2?Zp&AHPu@`zd~Ig+3JaS}MF4Ww zdwm7Th?eA^Xi1YxN3MB!hi$n{{waJyet!j~)s_@qAcQ)4Vj@FEWa-8r*<$d z0~=t;c<%Od!pvMmOC15yW7|ZJ`6#@$>BImw;8Gh}9I6lEDPs=hI+Jc zp2v;og94O{>~%C7qPRv!n!Nf5pO>zth0x&)+2fs#QMgAwzQ}R=;y8q6jA~3!qwCBl z&{~s`QFMfCA%1OKA(g8^KjPxJlr}&w&%pN!-U2HMI7i-B#A9d?5T|!Y^tt&syk-P# zPZ5-?^Z-a`q>3lY*RkoBw`9v$5L+h=jF5!`r2-od_?Y>_EG`hlCKqG?y)FpT>-(2F z0d)-R4Y{L2SNi7{=?E^E2o7Hes8hZ7XhMrn@XJcW6@w#0#ju|RGEddg$?{A~@YE!O%MD}Mn7@q?|FT0E z!XHmR8z%@-SfEct%fmoj4=BT;BcK`koRA(~3?45;T^qMj7uFxFxyD#e1Z43KY(6@^ zSP}rgOy90hGJ(L*VGQ#NrOIq>q2XAom4zJ2!L}{VwxJl5eb1YH|h*)vSbiIOqDF&vjmm` za$F+7>C~7ggZ{MHdC<`Y06^5)b(YrwoyiDZIA7vw$Y~6y+F`?a*#u#Pf9I|IgQUSu63ub$`fCobkPsL?Re&9m~B3#F8ww&jK z#h0`O*`3)jXaoo+;uUsDsb`|tXBa;yP!HWt<`O6eET?H+;FG=n-UsJ$ToJ+JmXgt- z&W_|q@L{77>PEZPd%Pr509pcDHf(JH!A`PP=zYV-cb?o|%oDbf42>m`97Yo^v2vQ= zdGGP((&(Cn$|^_OziTT@k#9jvCPDq+?C={Rp-Bf2k2h8;{m>m+=Q-=CRP*~6+`lEn z`~G50>Jg}cgp|1El%9@!1nr9WqalJ@|%PKLL{qLYY$3e<}3#_yebi2zKdFb2%r}) zx4JV#bsX(JHAiGIoRVJ^+OYXr-4y~}6) z3=J)Bhc7AhbpR1}NA=zL!}dtss+sOgs*-I}a{9Io_YT7XUvW zB5@TQj1c)Z#cR(cOIt?pfl^;(JR)cAFKjHgSB#u^h1kE8z=hQ4Bc-F_2|r?{2fq^L zjv)vuSs}{#GSW{nM1bL`=O)Op!mlK$Wpx13zQ!D6@^F}`^z*1{PVBvs5H@zXuTiJb4f`#^-qZ~rEhP<2DxXc(DnjgHEuY!%(E#0 z^UsKmx>wmPgQVBiiGI~&B81imT!IXMBU-Qk1Tr!jAR|ckZIhr0TvI;^!|(cpWlIzu zBpbK{Cx^8V4is|r26q|Q)|oXmoPH9D9a|9N!AH#V;aQ+E?(4Pou&Y0TI^Bc22wf)T zCW67jwqg$w%fT|JrQxhJlR_$;UANbQ=!f2g^W_AgTW}T{y1Ha{@qpC6!EU;q3>3?J zE4e9f=&_avjjeVZ@6ode%9GYd2advnYbdAp2bbp9_?9Ps97G~|$m8cPaD4~u@HCa3 z96(04P_yFC@#;TKl6KY{;TnT<#-RZCF>gBC<8-Dt%an{cJiCoO7<`8L!AiodlJTc9 z|0J{5*KWm&=RE0^uR>D0nF$6O11~QwXX`vA4FJuqgh?WiF#0gPyIY=^QTNBr$R$0_ z{77l<$tLtVM3cuRwW%RywS;T4i)K0HI?}V9;LB^Vex$nJsoERV>64VnZ6DlA!l!ed zO>7!Sn8Kawn}HBsZizB1g$F)(Z(ijI1-W8%ie+_^+7)qrR2eq3LJ!z z`c-}>I`AjY>D!!>PCQ;kv6DR(aRULfGY7@g$4JvJ+VdfR#=>a`4O6VhE2kNV2Fq9C zc_T?LD)Yw&n6eQIeN?jr=)fHP#oA%BI)mrlI^&}1>v2Y`TynrO8^ORLDP0@!L&O%W!RAXD!z^p0nHeTcW>NwHdZ%ZpuEv_D%PdC9MuLTgyF??U-1jufzjvcOepG_3a8nLs`-mKn9jrU zU*mDv! z`=T#ysRVBaRzDv{(oRs~j`~tUU8}uphJz+^;jaNWg|NZ1n-3{`oyxbfNs78tioB!G z%x#cL-ou+i4Ra)AG+ISIUqjdR=?vHQ7P>>zQ*I&Bf~M8Kid-Bk&bM&&z~G%W4=+HJ zL&*m~^-MijGUY74rY$VvP6~DTDPQSAv2vLBaYEkW+*1IGzq?qrH6wXN|58Q(_SBPi zQi!q23e%OQweeR={%de6rR@(i=|cUdC$aRQzFM;f;n0IsR5BK`V8k+KPINH@1Q4@^ zG$h@-QVF*c;t{-M(2w8G-tB|kbR`MkMU{IsPM4G6Mf)TSJKRUbsFfZy7`T)*^Y=1f zw7*P2+`LPHI z-XyyuU8L*nO)K7*WCF1NP8IK-_UlA9{1jjo!X2n(NVjcQbcHOiYZ9We9PW z=q!i_IC>E7pd1;iIJJKe27=-ioVOU;`eH7e5_NqG>ei4JmT5VZZ<$H3f^L*QLkQul ziyyB?-(eFL5+({%iqznrV4}1Y?%AD2#oL(%N_nU+cLjAY+lzcyN2^Lm^ zMX1Af<8|vQfca|-$?h)coa}WETY#?6eX_1VaxUMF;0*!wCM$BKt?4#9OK-vB{fu@u zUjJI7a7;B_{?q`A+Dfz2>_?H{>X&4ViKq2|&mu0(x|grCOlOVWCc4}06Pmhx$eK?w_mXpBs_c|JxygK9%h279~0NH8~ybKSF>X z*B-CcVXe_}`Csk)V<6)#PeyJ=c9EahM`-b%F#xaJ(Ii+E5sR^yHc|Yu|7+>H4pVG;J%4otu*CL#_Rlvv{L70hxjhQ$Ad&kvLk1N@ zFZSkDBA@)v!dfOB>m1_a?#@9T@Hx>Ek_U+-!StdBF9d)Y9QIsSyjLBVJ6R<$! zJuhc#;O9R#eng}O2gwSgzO1^=-_q?aZ#a$ylY0@9moOBLAxEwFP=ATf-7{!@COiwr z|2ijXK1;*6`&8XIgHejPa1cY=DZQg!`n}5#hsgIX-GGN1BAPwX8%W7kW77xWWDAS| zFDn`VuCtr$)QQEyrxp{y1AU#vWX>7!eZC1!6`+wbg{yoEl##j)Z7uc@?6CP}u(PlW z@dPgj8dVrM&KJ|SQdxDvVM9BFZM(a&ahq}@BUUn=IW#eZ_Nsbhw4bC2KC#9Q_81;q zcya=dj|ec9d%cIzFwx1Ca!}r_Cl_N&*kq>UG>P0}G79qw7Bh)Gwxs{%G+X*(+UZT| zK>v{^q9|lCSpr~%WtbB%6`&0s4aDR<+ND|giAk9xvsB#K507P_{sU38LXHCK=DH2dds zEg1RMM{|ndtJv^{IvUnXAl&Z@oe9r5`7?1X>R|>TH(J0xUJ1Zlvj?9eg&Wa2cpHGX zdw_x{`vqWVi~r|*Tt!KfBCDLwJ3-p=Z*H%=SmRRIkc6$nE-F*?_Zu&^%3X1~j?mBG zR$^Msc5_H71>e9htDK!Zi&!IUVRe3zMzTVM)>0G^|0T4dn?T*tmtd9_`%g;^WkU*h zaEnFGwilKCoJVz%pP~@Ld@Q#o!-=I`vQD>$*YV_h!ki@69~RMq<${G%8vSpZ-Nv~7>Q=E?<>ljCCHwLXi)fb1g z6v`>WB#A`~<--O)ksbujPNXK3-Mqw5exiCbuS>6WJnycGwe{Iszhs)Te|XXN^7Lq8N5iAK^?ywm&#fUdKn;g<2%|G=J9iY z)As<*#Fjexu6Nzql~>lp_IXat%KFWiAP5AgKu$>LB+QQ>Tt+~Uhhn}5iYhPPD}z$4 zg?Jc#h>Q~Za|M43a!xQoJPu79NKl+O5JbUb>Q6TxsUJYXgm3NEE6?=H&cOt&Wp(E= zheu`oGM#H&SaIE7Oc|_VBD@R-_)d^9M#D6-JBFF>+Cu6bWztSG*=ML!yT^Efz;Hrf zwA+pfdebeT2b3HmcmMLL_yd+ITs(0|q)%`f(_U+u7SM6JkCFg75{R zR;hoe*kn-akjppCVCd(x@dqJ)7e>FU6lQJF%fyQzoQsMuP*MiVQjaxRW*j))ud=EA zbT%5@aU{mB^-%1peO{Y1Bx8PnfH28%Ro7*Cd{KzskIa#H@_f2Q4V0U2mf_Z94l{|Z zW#Vg>lZQJTI;HM*Zy?Oiv)aeS%V{9cN`kAovyho{W`(iG}~7D?Eis{ zuKsj)Xa*Y~YI{(Lx-Q(%h7kvDm=RH8iP?}f%%Y3{Y+s&A8;rS>}BE^Qv_6^AWrdJ_&D;Aq@$wlpW|@ZoZ7Gir0lhDk>9 zj{Wq67I<^OV|!&#B^5tNO-`Qca7*R#j1p*Ml>CinifC+7i90FI0^#f>!>N}W&k@4I z4Vqh~FFCB;k!aYj6nHT0CwXsM{;dL~3Rn0WNI6%igCFJKR_k$(ExHfmz65I$tJ@f4;3UPMq#~|06Zo zo6jT-D1E*2=jfW0g7`-o@Dvh3?QG;{&5QBEl98f~xN9z)irR4->|6ci$Ch{X5;W&2%g1l5K76ss8_KznFqydvXuEODx_*LvM zDqs<8nbu5ZDDQ8e<8X4+6mH=4PhP(SZG4g(SEQ7XU6M01pX> z8zIzA*v^28poKn*OJNu75jv<}8=W{vSVy zhiExkz3D7wwOql2excbdSs<84`h#268DH{^W^A#GK^qK%S0ld#Brmsmb?Jd8te9z6u9wV5=B}Tsf)ku1{m)&`H3!{1h~!@*9D93o0`f$>*%JsSnt-cT< zP0|>I0>;IFPisyI`|238kF_>8x~%x7sg@EA-_`~!_t75Ae;~MS@Q1Yp|x66Dt z))*jmXW0Tm)ES}*;fuVt-FQViP)MWpx-&PW=H-`C96YhUApQdFYN%`0CzKdqda=M? zXnsEhd36*_MnDL*0p2^9w&l`THWf2OWbHqA>LxS;E&BNSnz{IEkzVk!O;5eItNRSb zhFiGLJMM{xlhibRpPsd@zD!WRC%mw9*hMiB+_8up> z5N>ysK3tz1F4S)cvo!8;o9H%T{&-z>-l#+#JcH|hq~VC~2HYNgm?Gvke-5Vpd{HqX z#&G_>4+x3tG5A-TQ{Osi`yBj2?DxGdXle{Fe{ZAm$ z)dcH!oW+05fJnZ=4Nf&@#EqE7yzY^_=GH&Uqp9XJjP)k;^pe|15M9HP7q z&9W2}3V_3qBAf8iT%oP6)|A(M zgpTd4%Q5{A1&{{E1pQhFGaFc>zy7lwf22#irFu&X zbq&`Y?N3fzfE^tepq#-v9DGsVs4a`dr5cFd~0K@z`kMAy=iz9+U$cER)d~-C{W2~mUOvyQWMrpXM z;Pi6y(q|_C=x~+GI6b|St=YQV#xa7+#>S%EvNR*+UVnoJObS#!88*|+sVOAhYoDAT zYXt!Qbb90;-AIO}9WlCfkA_*8>DNksG&EEnmX!n)Xnr@LS0=3_Gp(!7Hlh-mn;*8y zixH3>Wly2XfJjiF^&0=`YVrk7bd{9(O?wpQnyx^`p9`z^$(s4X|Ni!nz<N}06}0dLp6R!r}PrBXLD&+1uP&89du-9c-eIH z^;Pj;*w6Fl`OsxMERiC6Ll$2f_bIb2GJSdSh>6ClGy-dQ04V;h`lHAP_HDr@IvqNr z<;%TRjJ>rs2~f782|0}7e!?{Kv>Z;qnS!eIdBjMA$^M+v`+YaT>a;pfH>R4h;<&(Jm&s+Wy>>Wb zV;jZpKHXCWq3eX%i)u**HyZ9yY6eZauMi1-0p`h9#6_%p6uZWIjlQA$9QHhs$jpC# z=Dbj3$RneKm8lAIC8Llwr5x^ZvIX+@(ojZ*@^+O9dspd0t@_W_)i^Q z+%VbYi9TNf$POrw0pb4Q18x}{-f(Cbf%>j$gWU@G5)#0&(Bc}WcOt2aWu#qE$RG~V zzfUdy<^ud7cP{r6owN|tJ#f1he|hR%XsyoikRpJoLoCvx!Qy^~J&L>zPVq%5xL6B} z;+pT-aX0((%~Ns?#{ZK4Jq&#-dd&`k86KAz2X9>i{&$>TuDkkXKO6+c0^1M3n!&-b zTEMU>M#Y(1-q^9j!(i?C+EDJ??xYT$$bMf1r|Tl` z<*2ip#oaqD5$Bhe9fee0N6?|u? zbCwW;>!F94>d_Q|^>=Q15#6`zT|A0`z%>AO(}sT=oz*a% zqUI{56*{d}i`~TcRGWII5@|EvcOb-(!ENaK&6~{o6oPd9Z#6zs1pn`7IBnJKuPm=} zG^32K3O;vfKB)E(##7GSfC9{uqm|RMzQONbK3(?ysL4J&VaQ|`*=&U@$E(>JKG0fT z@47|5*kH+IGirRy%DVuew01XXwUoxPZ8HKf^Ow*K7qS&v!NF*$`g*p@U-%kryP3WZ zx|E?Q7qXoI3KPCATw3gIpAURo<_CkIf0p~vKg-PuyfS8) zu&^*6Ii`P(W&hh)Rjl|ww+N?7{<c!^bP95CEGjf_WjK1!=W`a`Y&@I zzT9s+mXU_bSP$ea{$?+1=&7G}4o+2H={BNh!r_eQ@wPRz%kMT({qqW;;?;}?uCOul z`dB>E<{oYRuH7O%i8vo{IwKG|YtM!2^ANwvz)O5|~ml1n~vBdBI z-?3j=)P{Pz1eJXC)ytk-^jRI9kZKp>HKen<^U%3W9y+r z)K1Cx^!25rxS5!_;Dg+JepUJLxir}g)_tjT=K~S+zHDHq!Rr85IZ%|~v)}Jrwk?QS z=P1uI(K`i?Cv;Cwhp{1DvU~{YnQibrLYISb%YO3-F-APsc%rCZ)we)t58 z%}~1mn+H1tiYiHOu=;$fM<~jFNB@Rj&I-Syako#~_^T?i`$%W`I#4#7;)S!3^~vM8 zrv=UD_Cf>gSJZv}nx|0Iov)@rnxgrO}_K9=3+R^YkzG%U?^@nz& z4CN$&0P=Pu0GXdVBdq7~0%^W0dqGlA^DI88puf`yxqNLih~Mpz~)dSKvo=AN{idBoelTvb*qeO0H2Rva!M& zUK8kVce`e;*MgG`%FOY&IxCB{j(V%J4P#oc9+pZ=@8OISa_`+lNhyx)o+pY|O1o08 zIC;D*SWLf{lbH%b3*v`GK0V0^PByPKb!e$*zuN&H5Oa+1h89(E`Q9jAM?c)PR9Ru1 zidBv$XI{24S`L)d>uAWDA8pnJsZ8d;;p?rftkXJS7fK!uk82lMAR1 zC3y@m_X_iucKUnTCfP62m6CMrFAtDp&gKJibvVzs{a13v=RYVpwo5^@T$&%LLtcMx zyDhQ)Q7B)U(W@9dg6|$mG&jaZ4}xA5vz5G5{E`pinH*4vr#@_jReVu9Uwc@zJhcfo zdf&x&G<8w8JXE6fd9-&4ua-^-`9Y#&laF}E9gZqG8uvi!OXUK(0l`0mz~{~fC9=;9 zvZca9GI9L0AiKAeWe~h;3FP6IyE#F!de{5~87Q}3w#OoGY zBUE>bT|ZT9xu|f5`P;8)#uBAE9;Lr^8P(6WQyRSP7Mqh5+ou#$8<~z?8;1|q99R%wU!g;buR?bB9C_l>0fIj}G&H4=2_6s-`|@ zaBor>^({*JBTxpzs14lL^=15lpH=jYKZUGnlZan#ad9Ic5r4pM$N+6_+(D!6zR8E{ z`b$vq1ZU`^%>)aCa%RWddc~O7&ML$9S99*2k$fflic+&kNoWG(%PpwDGY!AdIo~&j zmLOa@oy{bWA~wd`*0RylhW8z`oIEfbuQx6d<|#+QH~v+BitpNOZ=FTv&fMFsnk|ZO zH!`wJgs-zw`s$LeNjltN|5pQZ@G4{8QahcW2Mv_tGVdTnB|)HHQQIucy^13LO!=o1 zUNt#7L>WvM%*}Jb)&qztdfcF82-C{?L`|D~B*as}Pr=$C`-dUHtwejum7(Lj#-@u( z4Z5_6t%cwIc9h7p;U>K)WF?)dp3jaI+*;3d1msA(I>VHCY^O<|0=sagr!2rv! z*CORln@rUdL7}w8raqL5;<=J}HbHZ%hQr=z4hmZ@4)^3^ zD0=)l>-admt}GUd;h0dSJZpsqu0C%SHk__LRg=z)!zEV&!veOQAk4O@cay1-IL0|I zkLStu@&qMZc&J34Mw8CNG`g6WrrpS+N?g3O^UCwuKM1_q8ml}n@-)F(H``qC5crCU zp!RrmXb2X_XIo>VWwQ?|&w|Kn+O=#-M~zpid+~wCP;-1S$l~@%C23Y;A9hZ%+k`-7 zc_h2_JscwWbMHQvV?B*&YJB81A7QiR!NGGWN_IFu?-sL^2~XE1sPS~0Xa+l(&#H7H z#IOtppYt;_w_2{2>5DWk*%5W``t@ZWs@q-`o6BBbp_I|lA>m`ajoq|XWZ)^dy)wqE z@sPgJ;lbX;85v?}y#3dEGXs-)aIK?l!!v@M1DnC)l|haXyo&8aFcIc#>$BI5o!s}L z^Ywn_0C(t2?+Y&p?66Fs{xi08PE(Qo*Kv7yuNXn@)5@YaUv^Mr=XFjcx}4Jia!36M z5Xvi#!kh&EZm^4OuHk<+7dTy@?cu-$o=7%{bZVi8L5oE zie?kS!91~Zig&xG1%`smv>34oAXOJnzt&OIr>Y=$Jk1QhiVG@o@$9fEcmCy9$BfB$ z)ZzFhz5Qr>hR$-jU#~z-)*LRXr*yQ{S$?Zz5`fjwDNl~1jC4mk#m(vLsWb9HocpZ1 z1}d~rcL}#Ho@M=A%7w+K&QgxHKrZ-P(fh;j`cK4PE_H4iHP`#iH6Q*!&YiVtKD6i@ zsiP?_-S7j8z$sr_b?HyXxtD>M!#*OSLoOXC`Cv4~H4cON;Ec%h+usCf79aRr806;IuS?uz&CkRGpX?2);r%yn2Tl{4Ki z(V7?$9#ieyp+bDsR3*5T7^L0KbHo~cE7RhRS`Y*}8^UOI0*`;f?+>b2#6VQCU!bf` zhg&9l&wp5VS`N-g^^c|MtgaB%NM7bUm3_v|&th#im-VbU^3Rtgg_eFSv!{DhxjYI-C z+1bqvI-Ie&XqSNS;)21$0p#4C_*yq}lHJfTo;p)#?YA~6ATBfW_tp*ZGg z@%;6ez{vRT7dJf|sVrUy7-+GBfO+fFghW9Ut@1u3^v}S8Y#M@yn)Acp8EC-K2M9D{ zO5coVrqd_Q{H62UV9?TW9sXgBts58!fy%Wg1{Y^M6oeqqpccn>TamG8G5bW{qTjX; zQ47GaIrElR?1lCJ%UrzDJXozE+A+k}zanB4&Q_|Rrs`x%4OYXuFS-E5YTX?sJO+_B z51_s2axnL@J+`m};X@Cec^+svdZM>vsrTlAk&w9qPNTC4ngm2m&9~eITpYA>Ys-O> zFh@jExCB6>J}y;L8d>~r;^v3ws(SK8a^=sCTm*HM5#jSph1ej*c{^4sNDVxqhL77X zN1Ec>GS#zf(6t{=uQv4utN9{Div7wFd8|oHoZwsJtIOcBG+cmA(eLF`ykMwwqlNFd zI%nU##Mp#T3G}Lo4|P{PBl^DZ%iD_53iq}61BurE3W&=o&z6R79B`wGI(b!Ke#&=R46%jZp?Z{DHy6;b8^*q3D!l78@~S;M*VGev~D!K)-TEN~75WeoA{!nkdQx z>;}o;U-BDlfWJ&nw5oO5GHl^~04H7O26)Z)5sm{8^j0q-M4lmN^{z?Y*kHP#Uu&!V z&nUVd;~*uvFHqqgwX)F&2*C!z`v}vCj+pbltzbmT3Dma_^n^yJeLrtslOSIM<~v@N z)n&kb{jlNKPzTpl?<3`Sy1E9?`>Vq>fa#mdlwVd7o49-iYZK~Y3LG&INCPJg2!u!+ z?s9Hf03Hwa?jq0VN|zIs1KbG2A1frV3r|RVn=dfkmn>iE)LXr3m6_4vo8AP&n?)UH z!8WOZ@&JRJ^>@UqH+D!yw_!GT!SVnVfE*YR`;T+3xXq}##IkW06Deou+qWa!&=)(( zFD?&`r-~N@*~(YAb@Z#@j;`iz6tilZkn@C2UZsGmvIznDFm59wG+^>}0fjnyhKQR= z)8MJA>I!jPZlFxjkI)y)bb3>9Ba&r6EJGAdo@XC7Q&$Wy8g0J>xye)h^z=B1(0TpJcI2{93b}gem~~;v>ffZZ5uT7oNWVN z%vgH<6~=c(1qOor>bT_&j`76$JXiImBg&TTO|=AJj$$y|Q{(2<188HuX)!n0rroFH z3JxW;zljGJ{|AXTyxO$3PudsWE}K)N`t{S$R|rT?nj=y-+{&k3?V>>fO7#ASCD%Vv zQL=leNeh&mGrINOwFe0B`322Pj>f)`XJOLPdXZES_+ARI_sug&36LRXL{1J&ZNz`y>9lGXy z!rpVXAHB~Vk1C0b!twFvsy|KXAs2;ejn}=-NTX)HaxBR7k@XD3=*nNU zFQwl`BsN2Yh#?+n?Z9VmEyaa&4n7-^0f!z5Bz*e!(cCYMW>F<);ef7`1cI#tu!cmX zsK!$&w#bv-R|{g&J9v_WuANAdLZBh}0(Bgkz#h|wtLMBd(D1U+&51u?y$OHSnR2c0 z1c0phCI;31*m>m0&}x_ovwgbhyf!gxOe)VKf@E|}K8W+dzScXkhD zjpe1eF4b6;fqjT^7pY2)*g@=6WR5H0wXpaIl~lov(Q%?$Vs3eJWWM zJ-kroLv(Hq`%sNKDQYjzj15A_9Qo%n$I*E{?D2P(S7mJG%%*1RX05I97}@i@m}-bu zG41}5bN#E7r0!YX5JRnR!3S0Mscr!8WA^?LP`m_K_t}+5^HQ~AzbyEl8@<R@=2Xe;>;5%P z;&xB(A+)eEt%GJ@{}M=VUt8+6ktk^0{ZBuvVD7F!bz=)<&m9_8`+L27eWq56dkJsG z2ExtFbSA=8`;-vF)>XTo!o4qf^ADA3T+ZyA3rqr&5plkw|^n0r3aaO>k1F57tKuqDIv=0o4bsl zuho?d#3n&GI>=q91jAw}hxCd=UMK1DqIbTcI>AGR2(SvIP>TSY_6p$GZzm+p0ikGT z)!(0DrfQInP(dl~r2Bxz0*?`h3S&;KXUW2oT?BK@FkvAmqN%ak8=sHj*8R#)Ec_x*bcS zdHFc4GDE2l(Ki93?FY|&)XbF(0lR6-r?D8d-!5BFM(Hac23XXUgtiSdKo3c@cHJzd$vNKEg+(!V?!TBHvF3Z2( z0q-7M3gG+;4|@*G9U#_XCyWkl_c0`$Kscj+iv~N+tq!9ow5X-pD`5MRJd-Of^PU|~ zadj`C4R%tFQPJ+e4ol+0aMpT5RgIl+>UVY^@_B-hX=Mr8rgHAo3Fyo2rHObZFN8L} zJK{Nah{4s^^Gwx5roh^l5I_x%z?`3;*7_qW=P;Y-{?K7I8b|Q25y{%D;brg!p z!@DP{3Ab7(hpda(^Xzs`%P^T5Oa1esD}eJYa;?*CeM#%H^n=e0Vux1_T-LWYq)v3F z(6YktkGP}H)E_;Pzl6BvzM82Mj+$9U-N z)DgkHbOygmz1}ll$(}1UQWfMA>|xp7qb;usU^;z6=;^%&iqM zrZ~JFmqpc;!@R>YS-|vnKhE|{7;sE^!dcmRYpa?s3!SS_HsQ41Suk`r4QyltHyZZ*U7VvC32WvDHhz`kBi9db6LZtj^>lc!-GKjyGc*{Swq^BW_ytv|s}_-N z)#iz%sX{``^-axMy&5s@6ZM|djW@>OIX4P_)HX?Pu-m%rM)dj(@gGwVh2Q=zM?|Of zrZe@wX9y09=7P`ZV-rLfT_Bqk8**YQ<6Ug-BWP3WU`C6Wrtc7v|4$J&gb`=>&*U$$k%ITf=s7^FB zkjc;I->E zC)E5sUWkjj=&?4#KVv_X>0Tgnm|uAwPTv8;-(-3}N^`~2`5=+;ub@AxtlcPz(vE5s zN5Ot8v`z%*@(ttJvz$~aDjwsGkqRB(MoKA6?OvtI)+%~2Z92QZEm%x_RnwVDApRza ziFkXJRgK`L1@vyq%QW_S++r z4-0+3)vP&KsE0-SpV`K8rN4Uh<;NVlwz@eiUr$Oujsyb%08r(A3kxVYv((gcHoF=p;J~5q{+d=Pb652X0 z(jAAYR2WijWXZ&DT-+*fonbyY=wHI#C;v0EeegSTDf8$p^Yvk)zoF1XDJ7dZL6&DB z_)*ByY^KEg2G+2g&86;d^by-=Uw;Nu6Y_cbX6bC(EC$k`$56FFv>@3Ttzr~a2>bPG zRwVRofz0t>Y)h7>_ZFcJMYfAe0*gj!?H?#`X88PO8Oi6^;7I0Dh!V`lI~@(mzdrwc zOmZ0Ci02VA>8x|{DIJY`E(FQOhbn0OFuq|~JNn;6B0K*ciR?*bMvvEIrH!d@(z$$7 z=2t}hK=;+etT&I>-T&6xSp~(xZCMz1CrIPaSaA2o-2w>&Y23Zhpur(n(4dVIG!PO9 z-jD=ug8sM%NN8L;SR=z%8pRPp8he*4lu42UZi1Z58L9+L6En zquH0N2@N+|IbX&i({V_7lS9mZ%HHu^G$5~Tcj&y!nCHJnhJQG&t#j`D~^%CoY%|0PRx+xS5@s40e^TY^Z-hyf+LEmT9 z98Q-uh%O{V>%E=;qd~RQEJn5r-JjC~9SaFsPdi+|IVRwo7mz)6C8=zDnkR0ObeJjr z^BO+N&uh1OjBBeUQ?h=M_jei^rX(e8P$oAW(sBJQ+9!T#sAwQ^wK5#LzxEDt(EaLs z0iPIz5e?X}oHNk_^}PF~t3FBZr?GQO%fzU!P{a~j{JHVSc1kZmb0+wDdL8^Mjma+$ zY_TZCGiqtV$%W_EeY<0Pe_SKH;$6!F0M~gP1#Gdq;Ndwxs{AYHklUkKk6JvknUH*! zi>YkKoVUNuWs@O)F|&#xPe@A}p-~N0#pMUy;o$a&=a_C-+$+(GpMw1)2rivhohi&h zvQl_HK;Qp1HDfF_=$f9Nf6IfeEOK`LP+VG>*2VaaPMs5SL8`y3WgQVOUO&fXZrFmW3m$WeHgQ-;_NwaLX~`LsZNh>< zu9K~Zl;$SN02u+`G1SU`dhN%qtK^*EHBxM?A^_2s{4qV}br^@a%6Sbj)s4YuOCM&9 z=M^2Pj6ntXS})%_zZnbiwT;l^XJY8uLLyg4c3I<>0gTOty8)n0*{*FsV9I`HC% zq3XG(T-P6pre|DRLvO*KLl>J}N;y9sE~czvQ#BF}Ovb(OxxMnaZE~b2NPLm^XO8c^ zDbfYx$o#k%Gycnq^V0;gpChS)LXsWP&or)nejWe}kMu-GBlCCaas7)Fh8AJgK76i( z5=U3$(_J^pnSwUUIrf3s_nT*XfV|h`Pfqp{Tos(z&h1FTL%I^P@EMJ3M7<~loPL+H zC;%Ws)iMWQ;}CPhA+bwNo6FBzQsK8`P70f8%YmnS3zw&0({QDz&Nb6|h1}%AQ3u_w zb==K8blnKZ;#lbIl761gt%-w!$B>S&+oUf6uL;8|Zqb|xM&s8h>xD_8L*qY33xsQU zskTmXtv82~yf8dz!g31Y4t~T9TitS}{C?XLz#v{Nv_H0}`81nM#+y|i@rwm9BZnl- zF$nRc=A6*`P@2^?+@9aub?eqI_mx^Bjd|!4sB>zh8mIeg3HNj{Ke;_WAJAd&OV_~xeY-Si zallvz8z<5XFkD~7OztI;8qGlD69gjTz}^1E4a?09E4GSy(1Qo-De%t!#!?zDSQ?+1G$jT;jT>dV zkr3uBlWLC66UW{DGLA#w24717tVnG;|AV-U1|xHqoNvSkO`6g9ufsO=hItiY!sof& zk*O`P4FFlRc?-S$!JZs93jra)aqoo9e?=+>v@vz$<{*ELM^{pI@f!IE_Q7Hn4zE!{ zSP=ITN-MIADPC?3hmI@`^=c~t^us-WieC3!0v(HPO)lW+I1FJBq6- zx%?67e5g9%W<`56GSul(OPfhwII{Xrx)@Jyp@kCbbRs^xFQ7Q+O?WSvxRpY!n=w9$!8ecIG@xIcOcv3?)+by^W!e;TG z+zq#`eqVLyz<#utDt^AEib`pls{Qdb!$RH#>p-tm)-5AO#3S6y_94yK(r-w#%dN1> z__+hr7ayO83)}C%@hW&D7qAp_JnI_jd=!cq!p^&d>q;f?($TskJ<$>q`}(Iu&nhcfo(N(P z>z1*YZ`~1noE0Rw?-X|0oS7**Z<8&J$C>daWz-JMQBqS|Lcoc<=g(-(!L?31ZkbgW z+1|i<3`xMpQroWGE94O3B$z8O53~E*d%|I($n>UxN^Vig>)u$FW~}U4rJ`O#038-q zercv?Mn)x?xF-#_8BIomiwy}f=Di5(Fj4))aJ~05D{$XVBK9d>m0Ks=r;autCa8Z0 z%d{}T%$j|R!1HZKNC#T^-%bWfn^TF=qEL(hgY@oTl9%t{kunT=P%K5XlOquf%wD7P z7tR|Ei>~RjQ?zn0eul4t)#|EYz#sxe_*h))m6`_@ErOa`FPTPqsi3Nrv3UenWI*3bIebbK@!rJ7@ig z!olb*CxNKocSMi#>ALt=7XH&$mkQBg~w9r*=o@BD7A-{cxfPM=@mwU`5_Sh>kQPE69ZpFIqx+-H1OB=Mm2X;V-uqG7wF_89A31PS`FNO zqaje23%_c4H;hYDf{y)cQ#u|jRa$l>MLV104!O|PYNw42_-U&M%g)>d5bC!MNFwp} zB_t(?B;)A>j1isuWms9)hX`D>`;gR@Vp~&Je~^IaXyGm@@fUh0t$w#~m@JlK^gE13 z<_2rtCK9TOZXj~`JDO0$3|0)p6h{ipJKZgq&Yey_SDZZT0qACH?ZfjA4!9Oa(ve7E z=#IU?3lWm-r1H8hN6N#tgJXBU_Bt5YSKC)O4YvGF2A#kYZNF`|A9rcKx&%vkKBJ`A zM3Vzbh`Py^4g>*csg*0%`z+E0&wDqch>Vvr702< z{xcNF(o6Qke;M~ONegL!sc_&}rAlmc;;XG2V$vCsC3m8!gmt{#P_=$TpSpIgU{X~3? zxyE*QODE5GE@cxF@;MQTOHT}i8$(UbvdV~ekJbwD;p12stD_Ktgvb-M>Rs^XS9{+6 zHO|qkI}`%hL8VTgaQT{K&GptI|4hf1Sz1C&8=ojqGQ6=8;IJY?h~30!rAaJb zvnz^}P58x-A02F!$TMZlac=(b0ZmHH5W+HJ!UpJD=pARBH{LID_VaOzVqf1gwR73${(N0SJ#U; zHF@K7%~I*K8Z7&!H)Xe#0U`x4E{FplyA7PyaAr{R2G1PqNTM~F5gRf46gspDC-gst~*;L=U+!2UzIs53{tX0 zXj$>&8Kyl|qlgP2(Vqi9?c~KAi^Xj-QPNJ$`2AE;=25c$d?}&Nst@R%``N`K{j}Y& ze)(n0>eORE=GY34kuT!orRyTZNo@%u9)$uVKGP5t4)Y5nj(PpHk)+%_MDnJcRiF^m z2Z^YiT6fi0Hbo&JzJA8oK;!%T7B59Fb%b(_HuPfG+;oHu;nn8s*jcfg4-Gv+Hcc@Lw zur(!tqR&1q&eCde10J%IqXV-Ow)=HMuppU53% zXSaL%7VE@{k8$`LqR_Ef?gPl5LuwJFgHmJal7;HN?Qm#JiGhQ60ttX1l?ij7<0Bi zvKsHOxTl8;j5>0UbjIJP-$)<(ZUhcRory${=xni(%V!Ac6Y$TC8`hIc2g@xheC@pe z2V5m=ze*nay`s#9qw>df@B@%>XtY*>p(^mq`+Xl7MxL`JJdR9xlmy*b9|QtzB&p!B zZesx?Re&}=zA{C&1b^2!k98l!MiPUF6CcXxMpcc&Y7T{txE?$WrsySuyFq2GJ=J!g!w_b<5l zvQinTC&{WLH8ba|FnL)qcvx&$5D*Y}32|XX5D?G_5D>7jZ%|()HUo;}Uq28|f)dK# zzLNJhm1`96og9U&PnYbN#e2V*nfTHY$a1=&G{sH*$l_v{<^K%3LDni>=$OS9Pr3}yA3xv%G|H{OF|7rj8D;CydkHk-1Lw{$Iqv<)$6>1-zEA z%!x#1TXZ{CO4;Hf$T}YX+RMr|uh@CiWu{X#^vgE)K_-HHEk5>2p}b-O6w%$wm>YXu ziSXPt4*NpfgQh?0=GrAl0$HkKs&+SMKJf=Uod)MEpY~Pzs>7W#oP_>h1?ji<7a=o; z?u6wZ$ijnY6L5b-aX$@l>qb`17BV1%_T6CUUZG*R7;R6 zq&2&b*TcH@W|a1GYr7D1`cBTonHJb>`!>&9LMb_6>?ITXee_tZiYnW-Ib~nVnzQJk z()8t6Kg;8h4ByXO=B>zS+mXjokCdg|3SsXt?Q@i~Jn@t#owef==)$dUfur8YmPsK7 zm*a!iDMpNhC76CQA71F^#*DVlxBq}&M0&ldh4<76kAZAOl=itv!-mh@`}}+NOoKHk zj$|`8&ToK>?0$-7!%ig(?5}G%J`q~kE$n7FUpAI?P@f3FRJ|n?ER>f4b9&7yMy}?d z0Gvk=SrV~#wFVCi?FWlbAs+Gj3)>~?tFQxcV0(2cZSylmj^HeB&mht0mpZKh1}2WHcQ;Sl)9bJd^%OsQGCITxuz}V zH;}J8wv0xPF?(T+*>yJyM5>EKf8Bcm3oTM^9`%F3XBIofG(P3ABRNBUB-qQ`kciRD~&U$s_7lXRrd)?*b7vX;&^exuv;EVk(oVx%tCfkA?;)uh-w{csO_ z(6iav!87!H>5+w4$ueF-#v{#|cCj%}bDfPT(WhSkfDCH#mSc<99}Ee(x1hsmqWH~D z>A#FD4%v+@O+4HoW}s5wY({sh-r=$7oQ95iEcmS_VF!WR*LfhRmNMFX)W(!8BJzXX zzAWSkI^%n<)238p{Z2L?(qcw1^X1h(!_!UQ@*ja)iTAnGrL#4>8+D;dnuKP5)DK@c z?WgzKFenH3@NKdq^w!P%Mtabjwab84N!ZOJ%}3Er#iZf*5W5Bb$gGl05b8BmZW1|Yr{((+zyT#cGKp3zbR|`CmV;p20zVTBD}LsLD9}fhS!IY+iF{#!XMB1LnTno|bZ`3qFz1)4pM8R8T#yb+gQ0?R}8EddKOlw{g6m-H1 zQJF46-zdNM1UlrFn>v;{B6IZXQ4HGY>1oCM0siGJBnh2Gy^*Kjq1ily@Y{u5+|SIp zhLwW-xiOM6PGTc$sBn%ms^iyPZjE;R_Vz`>PIYgqkt?6*u}9n_0&K`Ij{MekUdvz_ z&31lYJZ2R(9Ta4Tkv|0qCJXWNwZ7+uSetF(PpKpYi)oQY$((sn?wVG^>=Z7@$P!vp z3Si|b#zzLgPypHWk?nGeQ_eVCKX>ss~i7je(XDRwd(Wzvh zW#fY)4u{-2N+n}Clr^QfiRh4#7m2WLeyg-w{-t2{)%z)RAQvAX0~^|Z?(poLtt6aL zYo;y(b5lhL&dz1~DbM*hy4djES7!{3#b_2)uE(V6$$LP(kn3aOa}sp}&PAWdvPhM> z&MLY_l9ePO#yr{z(8XRYS9H3188fQU+M#Q`xWcfnnBZY5&QR&m(;+{O?|n~nUViqI z3k6pAvz&eAjcK&2AIRX7I6W9A+PgdoKAUVXX|(w^jD0pnB)T?9^vgYjGPg~R_g~K} znIXS}Q`V$}bO62Q) zyQNWJQ~^zrnW`dzL8EFTGc8WWy{TSjow;w&>*xSHzjmr1nQsH_Gd3D8cx+O@dmq>c z7@0AV*3n!iy12476LT8^#+)#>x-duCPUQBnB;F*x%+@|ROS%sz;kt!5JGs-`LAgY; zH~2u)q!%L;VW3vi*VEG??~u|E=_UM_lmX_ymTHmud?I7K zMa%4U>v{!7*Ih$LK`e(f=h$D$mj-qnU79N46tYRF2vQN@nZ^4!N~e@|28vOy3sRf7 zc1+8p!4O=){B&bRek$?h)^Y@tkwKBikp%` z6U4-5U4c)IhT%(jQsQY6+0Y(3s3F})rM1J*c)k)kS%Uo?GrANzBZ_I$#0XR^-5TJ(XNOz6bs(;qdR-2cJaM> z%E)DUT&X_yypMVcAHQq~O6Th%y}k;1t&fYIc4P7YjEYaG2+EJ_{vF@Wv#SEJwnqkB z&RT6qWk_-iO<>dc??~h6PR&1ll;D~`Ot;v72sUa2Kz)|BzX*zq9g*5>bY&kuDzT@K z{8S$%8y_DRF2KA<|R!VObt!82SeSGJ&hi>evJC5<#c_5fh`%7vz-?Y=QzCNx|1 zb1uEy+|SYT1};FOKH;Pat*me?J+DCjaR&{&gcK3&V94t5He;rTNih5RppVF`Jb3KL zM1_|)-!%{Xn|12oU=*=k1qshHDFr>Z<>T>>{Yxh;$5=)^BG?qx4{46xQj<3EDg~%f z9oV7P#_%<(KR+UVP=j#NVdQ93tF!P=-E--nvzDt$iRMh*rw8&^o-EL)SERbMI76t3 z;xKG|s(ZCAz>PZgF8aIedoLH_TA@>8$+-SG1zTxADs&pu84AOtQ6y8BAwaNxD<9@9q39m7H^`|8qJ)BY`uX?=(cqiGoypH~BCOO{C@5Dp(P^dbU}q z*Uf66)Y)4*JlEkFWi(5RBBy%8QLa3EOrN0 z1QzZQ)!dY0`VTzL8HaDNzM)vm?7RHE72+_&;|52Fxwb<1l0by+<`;kj3@6!2r_d=S zJIf5fixkvLST~Ym89aggFFq8&FL}LfXS!@p#EH{Bb&SI^l4$q)uYlNEli|~}o*5OO zdu4#y0DZz@owE<@N5g3Brg@iqEh$kY7L7)#a5|I*$*+X>^rkr63YAT2CGuiau( zL)&s(e#F{2qpH#$$Ha%$t~3)Zi83v!-S3H{wT{Q=cSDtlH_v4p$)v*BJrlbD zcNKftGF9Alw2)d%o{HbSvn*u?3;+D4c~7C}xa{yz0deA)W{O$mTJi=AZ2zE}kketq~Ap^Y=uk6o?dUyfrK3 z89sinAS~FQy@zvdgF-+6a~F3=`*h=N?O4gS=yjp-v^I+b?R9U0legwK>4^)$>dzOx z@r}RvpEO<>$NZhUS+vK;9d%;-cnX5pJv|UGfA*!38#NFb-!IWw$M{8B*X*Tmvo|Tl zKUDYTd3>SKkR}EK>I$817HQUd%rX|!A-TC?A?;rB<5EVuZ=}DIp<0IGuatKrFOQWz zIE{*K!DGU3y~v^as+3986`r!MPtymog#2gB%BXC7utXf$eKYkah3 zj9TM@ee`mrqw$m5y;Lg-B-uSxBz6~VWsa`rS$y?s0!5g8w<7c!H`&4hh??>B#-8HS zih`#e8Z`PgFU1SGfgpZSzg3h{TTZzvGtP?Cz;*o^01myHv+bWTV;Zf21-BH;7SAwn z(`2F3jZC&zF>fD(s*N_QJs)-K5BCd`oSE=`8T=!zNUCaojwhJhHuwFRdGQaP^KEE^+Dsuc3=dK`U)Zihb ztj(D7GVmW;%8qM|Yj+E8|Dh#%$oUb_w}u``XqiYit)QTqV??a$<(9g| z#rctLB!0`+TO!?bDI@6@^p<`-6an`-U2mZm~YTv=CZX%1bYI3;I|?gm4r zDd#D>M5b1GuFW+i$Gc}s5e8zeO2N0cGxW2K zZZyjE$SPOU{M#aeG=a^5g5gt}-jf3#NJWMft?Gnjg;`YQ{GgPRGC<*RjgM}aLM1E`VG&qRocuiGJN8e zrmq*R;Sel2r|Y`u99M>xvLP6zh)47_6S=Xl)tN|tm-noY#c=qb`czvcPBR4#LSM!!BTr9$5Lf(y4=gEeuNx+s$Rv=&avI=nAh7OC zQvlA!F@{*ZI38zBQkq{Vn(a+TLI${m04n9KPSA>!fOn&2`%iH~wHJAV{iQ_7KZW+I zrTScUv`TghVW9jhxXER4i5)Ej%a>{)Ca9e_#bZGkgPVYKOXUhw@=r2b1X42_Z zzQQ-)HVjKj=lQ@+;4!+Nfur&E9J-3xea(P02Zo0;abR;b_Ie|NGvC_a-4&Xcs{C9F zH@(o{n`Qr=JD#=!ZnTp@WU1Wlj;(og6kKs^wqi}kldF#4fTUa@6N@EgK&r9tCAyGs zf$Cj)^RN6d71_!QY^lY;-m5!U;&y)0n2xq&7SI;QRAbP?3mI#vA1qobnoUE%aYtR* zhtHZgVLa`@!5Pvi|H5S|9(`tn-}QMR9I1H?EDafzys6ztvPqs~H8!vDYA=)f&1uG> z{}!>ESL8H(d`kW=(}C5+?3sJLf`KXElh4UxMwjq5d+Y4f<^UT#JZVq_#w@?vHVVH} zo^lyJOXL_6bDQZO;Yj52eGj`~%iLh!0X4p{y_jVo508(k@)r-(-E`>NxvO~^dY<2t zV$nt$161B?w&=5L<7T_D_M)9jQ3ULOA*D;amnPZ(mtK3_4@Vw4QWC7g7qG=;+MA5- z{gKeff%XQE8XYq4y7oy-&7dwX?i8cwaH9BS>kX6`U5-l|_K?{|JL8a9$!TK9=D&{v z-_m?o<6=(#3hqvfmpB}Fp?^Ga2VFEWHUH-Ux@r-y*aSGkGJJ#b^Dxj&3nd+1!|3S) z$z3iRsTQI`KIFyHo~F@{J0Xb<8*LHdrL;k3kTl<|GG6T;Yx6%2a|F;iY0wOMaCjV8 z4s_1$?6rwvJ>u|Wr&E>06Pw9pjcT7zX*|GH605>9q90L}Rno*`2*C#)&`!#ZHXo+` zDI-ejh`h`2(^eD_ z76$GmgzPJiR6rBqOz@cuq1qbK&8Zw@c9>|hyTo`uCuXMzW+zx2I=B2S*Ep!v{^AMS ziklMetHlEvmG+*_ts<$u+V>P!p7HXYYeGi?Dl?EB! z8ni}uJvCk0bABst(!KoQ| zo|cnZ(C4MqANP{(48s^9W-macS(+&Pq9rVZ+JsHA7rNUVS$Rl>otEOAyH}&>Qs7#G z#AphWkxMa@Aq&}8?y#!)dokgcBHO4~61On80CRY{UNyuQQZtWC+_0Jz>7()ro{uN| zlyuWRWpsI5ym2npIDi0C z7Lmh9>cmjl^$Bk+PV7abh(FRE4-Xl2!Wj1VgQgQaE>j)%rlac&j){{m<;W;Yxmimw zMy=&Q;KeHSKQPuU6pFA_tXQ|7IfEEM)B3|jz^zS=oAfz0AFYK`?dkVsIO3h{h)2*U z=G@Pb|%`kKB6Nv>Z0w8gf5wWBm_)}lBC=i zV13}eaof>|w@b-oa< ze|i>~R}%#^Pxu~jU29T)ubpY2kT;_aNAGYSS|6rtS!L9fn!rB{D9Fr*0vG8N0-gIvccd;I3xc)p%0S;`Hr^3SnxQPHKQVor;f9koH!;SpE6fN(;L5&QDI`=XG2SFa%lylHTAGh`OU*%at z$r_!t?wkD~H=&XLrJuzzrYD?EQJ#eSo_>0boVWiP{>N}_YS{yWo^nmD1vzZ{U(Qj; z#o=VP2%`lS8WUdQLq9-c0sWb9j)G9#{O)TVSo6}o2p%!m8Y2!ICY7T;qP-z8Q1K8tz%vR6;VVBr@_=z`S)Yg&dXVSQ~_606Yno zQbjDEYXlBaf!FQpz7=>7r-Pnqujv%S58s4)1b)8mp)@wQg_B4?Avl6+r!G>0X;;OD zTZY4#p>c$x@R!WRs%3vm&tGtG$;eJuH(5?#ve0HzqC^+3FNb4VhCw8<%Cs#ks^O;h zo9j@z;I;0;niv>Q@8G?T=uCSKGwk*B$I6X7YvL$#!=>AL>ttiNeY%+&@_pUmJEib_ zDRL$Y{=R&W8?*x;Z`Y40f zZl49%&p;TSr=BOei!L_&u~?DeD-7&V-vtprJZcB6_ikqpz<2c~`FXo`SSH@=TB^v- zxYL52ICdD5-XEyNkL*b&IsE=X{iTq0>zz4ZGwN}OXxC=Of_>y?^NjqNM?G5QPHOim zy0X^CUM=z&tr}IDmbQI*X-!B@3FheGx09Lz-y*l_3KhleZ5jm|vYi9%Ngv7BBSLfMB!c4wGV5s?@a!j1;tdBce+K4-G||80@bx zSmD>qMl>Fbzd&=oFxzlTP)DQ3Jm-D#;E>?78=&VWaoDz+i^S^(4T;Jb3UnvOHSSMY zEcO#O>)lxl{hMu@+a1N7q^G|(d2LO7kAOq>Ht?In%zTwKv`yx`C_78AsED(+X2#2# zw+;%_?11^I!M5+jW9j*Q)_wEM^uRf$;Bex^yUCk@^_@i=tolpefDLB1hlXV+} zHk6YtFOZjqn({L=q_oE}>*%w?o2SgaSZUd#Wx+R|pM}maE8Tal2ADGsHSRCi(s+LQ zqN8u>m89DWGijsmYXA1JRnsaLym%rxb=!0rp3}+u;dv2ZH%<|^Lh+pv07tD?eEoNJ z*kJzSb_N+?y3syzHqbmYPos+bh|sKL;t~t3{SFjz&;;R*dVUmbVn>hG`s;ZJA%AD> zSn{1E(n~Z}n6#MsELROhplgCX37F{cqEAb{P6o}SyJcWY2HZ-*G-lB(S>+rlhtpZ; znckFAcq-C3J~b*`xcG|Q4A~N)`QI5^*?|?x=tMM!J$>X0tpeI3N>C^WE1hRLT@2(9 z>mwXmawMk~fm({w6N+Q2e7AgsF3Px$#UZ@p?uos`b@0(J*3Hpc!1D`C-2YY!R-S7l z^#@^?KBH=Peys3|UQE=skN%gg)RH2)(IN(wR44gVHp;Z(=FwP>$RZ`3-Qd_^%p*YF z^bN`B+RY?Fh}1`iAdD$w_`4I`2+slthJ+R=eX!>KH4$__8L{V^o8qD+Fj-0Ia>ew$ z2jy6yk32xmj~W`6I5#`d?zA~VFJjp7L$lz;1B>94?%~B~uiQ8Lwd$YM!tL0>(i{pr zxSV}hSZuNGF7b|;=A)Q-J(zB9i)=B9H!*o^pL+SRm?Z-KbbsBNZwpKavq5W)vtZZ6tkGEKudB z1eQN5b+}@|)v?#y=SKL;;Dj-&ZoQXoG;NB_qpH8}uX972c21bXbXRLdL`0dxMXuBlTYlNnDkV=EFN08#(*%ffPTK!@DT|A9Zc z%vTRhyOV@NlH; zLLFti6hN;RE**2a0c0vKn+Od_+t&dH4^%F*HFMShXiwQ@x?c$St-vdTGb{uluJ{*K zDOQJ9V-cno2lt&$Azs^Hp=|+`-dx`q?P1F6H~>NUQc#)ALNZx$5-HseqSr0bECUL; zioMXNVHWPgf!K(m**-0Nrrd){I^SuJAD0epuVOKiH?!1`H+^hLH#Okac1=o=ZJ@8* z#v-F54T$ceTbS4cii-ho#3sI3-z18!zdh4=0KfeE0@;?S|IJ49a3J9E$Yz;JmlGS^ zW;fK#;3U}0NuJ58sxXiii>CyVSB|yFXjWb@*>@~q<1t&P%p&KM6D;L>QeOQcHou=IKTuF(J$ zIFd+Kg^a7kS18+ZGUw6C%!fbJ4W2cS>wK}8W}kq>_bL(&84_F7b^Dg#F2y&f7>6$N zU4JSQFf8;QY;s+)@VnKQQ?^L|=RzPlnT&tZ&VGc^w02*VrEDt2seI?WJlnppA+`}? zYx``VeZs`?@;Vjjo|JtkAO6J$nvVzhp%Vv*ztbtmh)0`&%lCZsclK0YO8D_2V!O!K zK=Kc4x5-jg#qwPomIrmo%_UiHUJs&CH5!A7r|n1`x8p|Lod1j3K7)kP1AAjdQI#<{ zsJw0FKD`yKa?E(DrM2P99Etz&9c#6TjHeLCV(F1=B&ADnU&WIzb*y=!=F8v!6`@9B zwq35A^*<5(5~D(8 z8|On!Rt)3W@39WI$u)+{-sCa3<2y>0ClFs`O#JGFr>-0VlceyZiblK!Zf%QSO(aB$ z)v$nPyfyxN?i>vY4Zi6wbI}NQh&|wrO4>*)-wavXUJj1p{?%Gc{y3@v%8@O4-Z0$; zQBc10_yd#YVbpKj!v|2sk>8lNe`z9=goWdcJ#qXP%~d^!nU{ryg%ux$_cq}3jq&Mg zFj*K=*8Aw~kW1FKcr=^^CfPWSf>}72{9@}XG}QySX$)DG`zY)fOQzq|I1b`h*RpWG z-ZQ-?Qr#fzj25A$3}Nfk>cpcwWRo2nlF0<4n%PPZaAi~iA3sdC4pvcPgoP{5o;6G>oFVS3}XxC@mWmHR58n2)9kUv*y;ZdRQ5TPf?c;BkUZhWT? z%O{9S^}&%GmPcg7i8OS0OsE#z&wp>uOFg94XpA%`A`A51JHFhtv%PJ&b+%GWt4MwG zCcD)hf92Oyqoe$AtxK`~8($?Yh1I~tOd>@FO%;B_SEwrXkMvE{emWdeDf{OLi~;!p z_`Jt0KSd2XPEK{Ne8&XmWa4|jw9WfkPUKJPkl_v)NjoK4Io(rD}CRR!mQR z!d6V@=~|7%IaP~Q5-(EV?g`5$}z|APwM&Zpn0Rm-2aR=&f9ImyH??&gFfI{m+WoNL$kMK}IrgV%%ME@uGq!kdUm`JNXycJY7bTY|?6heGSE1ZV~OHJO~`-cYt3%2yEWKnDAy5B2>*=3Xse82A^? zfx|(xwRqG5Dg!B@ygiCd(pdS#r&77;J=~mM>@pBXVtli5ekUGuBuaN z+#!(fjkS2SeAz}DIbp0icM3TBVeabgA1{)++8^>jxsXt zVctXFw$}rcIO^|xB-2<~oT#9z-At|bR)#}NXw0Fg<={AeGuxu*;8RN%H{sPSN87nu zU_YewZIrP$Jw3F7;AW_^q#S04_D$OMlK|4NGsUVOw3A8fUD#1|%cQ3D-Dn;_!rQOD z7kx}zwB}MGh6PnCs+8zpq*4mi%Ik8fvP7<(3KsNak z-)TE1eK*1}sN?J1J9X>VetWhcv-Z$6IKG#)Q#ZgE-ZJ{2cT;7#}zgpIiM~Im1;y)?8?5Y6XU4&1oKHR zig&w2%Yy%%zi+2_drZHS1O}Ck7?33^o9(!Lo~J`E!t9BRjujqKXn=St+}4ns8)c4p z&&c(7vHvI{=24|g6sk3L>6M}XQ!Wn*Ii-CezM39%oIYcyOA42-_LoPmF5v`8a0Nkf zhm?-sPS0X77FRep0**i&i&pf8-i2SI}omq05I@l zK0pNxlF)`AqNu8S?i$*(ek^8R5(S^E!u~`T2UbGLQ>m%n`R4H@QZM-6@TT-n`$i{~ zPM|A8hfa#8@($6^JEJS!;np;Zuv6X&bZ5;&4DA`8Q-*^Kw_|lp*bR7-)AkrB8=YR? z2rJ(-+ghlv0i;wDfS<1?=F(^U0xc>BO0Sk@o7-$ccWdoIfIG{@xR)f^&h^Y_^KXYW z-VIvvYAKaS!a!V#eXYrdUB;Y?>^ob`I6}8JQ}Td<=#@=xy;Im1xzfASZ>4e5ZKN(? z_F0>RyLhPxJOwf0#q1Rbi5lcv9;yNN;_%cbt_WnMtH2*`wvoNt?Y!ErqHwSvVj=MJ zuQQu)bag<4{ixVo`zH=z4nMlnxRmioL_xuqAZ7d-t;sk5e!j*z!FTH4h}je?9K&Eg z;*Ue$D?a<&2u_sIA0moefESg(MPZBTlc#RB^&=^i{CFq7AUs~M)pPxKnxRZK=RCLq{sjU%N&6W}VlYN=vJ@#k z&;m11laWIgS`9a3R~ztXYbMv4vs^mWE&(9#GOjZm8D>=c+VxNe@f**iw|634e=plC zS+iL`FmO(Egx}u5OcZaggb+UpHKbw4!Rw9R%m_Vs?*R^MGI|EjO&M)wz1a}T!VY!V zWOSEeTnWZWHag(&c>SU{iOf<~st9JIVZd_QrXcxy&Bw?`%ryt9%a0!0vn_uvr zTWPehV3x|Kf0|>quar?H(x^7~nG5ZBdK%?Q^~s`s)g7+wG9qR635AHyb)(HkZt$$m zwz?RNKp9&EdP$7*rSS6&wofMjQsS>`ZxvC7!JzE)+TjVQUY8sQ^O%ZyQ+-?pFjrhF zgK^X}Ual!y*T)A4OTPlIUGelM1Gu!M zWke{I*7{0pUWu53Q&MpFrjb9IHX9W`C>#j@v#K*y+LRweacI=__KmurF$Wg?<34umY zcOxCFJ@>^PT0J2%1ZT;xumHe&Sllb3g0Xg?3AHF*m^+5)aV70vuiTph^rNn!rbpaLX=g% z2xd2flC|H#-O$gCUUH)2nq##l5gIjI*8{~sBE$;MCX&s{ZWg}>p@DI&fpC-CRBlI> z2)Po6l@PMU0Ht`MYGF8D3yNo_Lt9x1{GTkBlaofRC=M|*<#KRai*~yCrjZ!HhjPQ~ zc$tiv-%4*`p31Q7AW%J;F(&(wp!Fq+-}rieOi;93QKLoPmm=6UVBU=)WmTa?7oCC? zp|A$>z-hM%#mL^;2v1Hhrm(((##VVvow8t!F zl_^&-l*0+|rHbM*O+}QFuI(qc&-H)$($KGD%RISNsyNYTXC4 z5;-`Mb!kr&UylzxPG8AzTZ@Am@zG`W4vOC9TOGf!MN3{~`s1Mjk1e8oyc*rg7wVl;!xPu0K_ZJgN8Pg1n35Y^F zZ%V!MMXVJ5he)4`6zZ7&p&m)PwVJ^e!~XD)WrQyPB9_%^`@z1(Xium2_l=0{%Y(5$ zT~wL=3GW7%5u@o@{e_M<_Z57~cP?Gen|Unfc>V``>z;#3Ncl+re#e$vwLJ1spUb^i zs5s!=^3~!9U-XH?2gwm`_8n}LrgQ!yyH#`SY)hJsngpOeGjp(VF&w+1Wgr_r~7Ykpb8Rl4k z^N0?AZm({GR>*KxaBGtE08!rZHin@CPIR`C960X8``zRJ{M6(W6Xlc3^F1AY z9l(o^b^Y#osSlfIJD|o@RZ+0B)tB4N z{V7c9>q`CQ$C*3g4s1AdWMXcQZT{~+Gckdola-}=jzpM;Mcp#(r_EuQ=ky+kPgt%z zbZpxj<~CZKk`6lRSO7ixj~AuTpybW(%q_sz`X|q+TCTV|2)-&a`XhgCX}v+$7G!#(3eU_uKhc$cZiRgD?`G-}X}%34c~Os?iyWM?vq$Sk4w7hN zLjFMby7`1^6!;?^k4>3D82ytkS3^W3_8*|}=4SOl0QvlbHe^QDC4QYgp0Sp}HG?2I)^l<7nT-%o~$mA(vL zj=tTaC??Yo<8%T+hNRg|5-cp&rM%J)9CkMQ721x*O9_UcUmC#<0rpQ{wqNFi1MQi{ zy79(yH4JqKEH&=W5sM9eVr~hWsP|qf#E$!B7N$ZBqLNjt$L#Y~m3Jj?$7l}Lo?_u? zOff?GDZii8g~7X#Xrg=p#B|7Uqttu%DUpk;5kLq?uZZ~^7{X+V;2|PlXs8g|9WD6= zs0UfCy#dT5&EVFiHhJc}h_(Y$d#MONs+T@!Safvqk)e#qo^Mfev|J*(f#@_#p8M|~ z$vp=6hI2?lSIkV;`KKGN$J~^gtlvL8WdHveiMZl=Q*SnqWikjt&yq|2@o(i!^`o!x?y>Uba> z7bo8?QbSNrGoQCN)i#1XCR7`4{$aZ^#Z|Dd?l}Ju4vnKKlUb@b-Xo3!8y1>6gu(S4t;fX-l#6=0TJrq zvpxd2VK8O@ziSqy)gXR^2^ZU#+0cJo^88_!#6T1cK9<^Xd$7?YMzeXgH2BxYYngM8 zil(JZKmngq?agARA2_AI8ifHb@EgiP8-Q0ODueIv=nyk2y8W?jXW_gZl~kQO*wo{M3D6(X4u#cj;n{ z>GWDg`D1+3qHuQX|0DpKn4ibL{C9P8m?&RU@FlTC*Hd$1ZAm({DKc zXWPtavpq~si$bXiBDN^DopsSaz}nt$aFD{Jre7ntQ&l#m&H z4o;g776G4{hOD=Orsj#_B8woWKND+QA3BIAd51ccGMmR8Z5O3RVM31BAE-`-%J1wGR>fGTiD zgqs0aF3rIXFQL=j?BEw4F544dGsb%YrUW_y{4VT7?nurP%tjzYFR_e?DvoVdbx#eIFxmb*=CduSUEF@*;pMJ$jC z(H9n%oT8fkz~jaKg5Thq1!6^&?Q=OGZlBnOx$>#;?v`I+0~D+#%LySP(H#VnPm7u?Y{ znIwu$RIu}0rr<*4rt*-Hatm|IU`ep*vi?ncmqm`Fu6;OHG@OiQFl09egMzW(l#Om- ziWdl1KSM!6CLxm&ld9H1WvNSaw<`nmkrfrz$6bv%GNYKj^{tnOogWjBZfALLHBn@T z8s)X?^pWZ(1@n=G)3s)#uZqB?HH--t;S38L1nL-XwBV9L536WwkSI!H=UT8`!;ex6 z;FC|+N_h&PCV1uS!QUfC1m`U0-?ib8sR)z0M8K7vrN+S-RY&+`;p}TmAxP@nx1zoI zJxp+Mm+n|~U9O!U`y|BvmKPM1L1OTSL=&J2EDrtg9hTVD&ljCWyoLx}z8V8f1Og2r z?x%Q_qA&~+3~LmUq~OTK#_fAtjsV!QFk0@TPnHk<(poBq)4^E=7qgkE^tTbB>0!Kl zC*Z>j13zk_P-VIz4Kcn1!E6n;_~1{0X$O=aXcXXw$)R4WfMXQR4bwE8zzk%RJ%$MM z897rl52f+>8*8i0+8lBd{N9R!-e}+@U*hX3 zR0Qp{fQIv3d6>t<^(7*LB6==%-ygh@qB)9SHum+Y>xzbIj0J zapdG9G*2G3FaqATAa!`|NVasLT~oWxU+uq3sd$VyBL&$jO+zFjtImIO8m8CphD)WRBtE z`S6?n%L@Q?$W4yD_RcXI(qM3S+B9`uD)zkb$wuz|N{sh5(P$0j_k+xF2jMp1B8fV4 z)W5m19f&I4iIwU-)0>jXhj-y3ByRi4-I>yQJ^hiohHi+H5f6S6%xjIQ6$c!t+4@xk~xEN>IpMQ&ryLsaCP`kMV`nY3jk5^=lw3$E!Gg z!e#q!vt$+gWMd2F-yGR%g7prCi2(rt0tIsjgH&S6owQN)l1&CFj0BXtBoq#bdnVPi zwD4*se)a78N1ep=v*Uj{R>h^txQz!-#;V@>ySu&;$kl*@X4{o*a){d}sDW%)1$#EZ z{PUX~ZJ%%g(J3X~&7vb?6ZSCr;t(^*%w~WilfEn?_(UTv)K_XiGZLKm7o;l(JHxTB z#r=B6PZ0qe9Q>DN%(UGHJD^}!yWV`7k23gQFV6>$*gtVHW*in8uk`;_suQtUS9NIQ zsBBsZt{Je<|Ci+9;RgTjoaG?sw@*+>X7+0HWjSkViyj&FLKN$axyL5?w1zklsl~bu zK-j6BWr&&>TDFl1hE4Whz6SMjWzkKSkdD1-vfMVEDy?pJAs+e)LVNJRfJ7=3lo^~+ zpNDKt-QlfQbL}J^Hc_`>am$wB0tBYYrI)IzQ&wUCLP-G6Y32z%~m>iv3Xb*1^`#}As2hpTWx3AXmZ zxrM00gJra2cFM$vP(in=RLdGV-BH7_$g;`_<5FCE51%dn6}mj-JkEdzjhe-mP>bo% zx4gZ&B9Qrk2QJmXhG0@*?86ey*9FOf^ST-Fckk3e!M&H*8|g^0Uj06VgM6Lgx%QUF zhgcBp-MD9L8lBnCke;9{rdY`{?2#+5^-*(3h<&*2qi{vBkWl==fv`C?zkC_j>$BD# zl=Sd4ZzvIa&0vv$$HfasOQGNuks7_Mq=8g484zZ$Knm8?paWWV{AGXNBA|Qu&bZP2 z=LSz8L|frBJ1aC_8hDv4J0#lr;G}J%q7p&bbjA#ZgYpmO7wbj8qZ!MWc|M#^fr}cA%V-<^b2hewAvI-9&w`>7ZUna^q3oOB+nf zlhcS-rhF2?q%|MgyPCx>Ar=l8U>iCk1fSuf$}uN+I_PrErRaH8pm+(K&H0=-NaoD$ zm!o{hqrK9J8_dNeBqWxKguNcU>jOuzu1T>B&bB&S&+-;_RWJXvoimVo&=~g9?rgL^ zTvcsNuxVyF5xEXww~UlPN`%tTE94Tr^yR_>gpbyEwQHRbVg=M6Z`?teZymm7F^eoD zRK?TBBEpxO9PH<@m!VL^<;Ehz1KnzmpA~M#_5>RQm6Cjk9|(;VC~4yl1eh z?cvUrb>6jYLbWVM=~>{z(NXc_Xh|MP#_gfnS9mL=CXd|0oZJe%M*ptOo&2tsPIlq33IpY zM21&rjDts@V3XqT@Pn1nZe(NisHGL2h&6BO4G|}hSR!7;pnXeZ z^z2?&v8d8x%?Bx>u`tzK>k*rDYF`s;~K(oP#i399TjpzJN%oOgEG{y*ftknbc!xL(F z`lg*Ob4m40s#VW*!-IDoxH>Qj2dqTu1(&4cZw)zt-604imE_1U`V#?{1dD;~i{A|x1bg+XVrBR|`P$v*9x@|45kukf z42(Kwx)hE>sg?>}Ql7N)AmDhd0z0!MHC|zYz)v!rwPb0R`OoukmVKe|OePx9i()?W zF7wo>1JNVAdx>gD9&ZMym97~VTGyf`b;idkjc?qM{E(bw1JK6HJ_OCrTvkg7BFmLo z7&Aj~Lyw6~z-4V?p6D^(P*c-={CSgAHcvDN$GSl-z!1PEc2ihWRaMro>5PQQ5i**E zji~a}i_7pjG|v{O6R}aBP@(C&TQrqXsiHz-v^|V&U#CGItIO(x^5w}n{ZP{CX{*3OKwYW3`S$P?Hn*GK zYeXSieib^~+zrRvgoZABBe}nrD$FykgUYmGbo_&XBCo$ZAtYqP9v3fu2L%1-@ug$= z4qH2OFyD0py#RlYs!~Pwr@_|l1>`yT$V|= z_zcCb!pCYgHON!lhaQ@?2Gn|?ZHYeGev|nDSt{lC9zUu*{CX#^*N?@S{Y^JC=Fe!1 z2l{D{f2e8P?k$VB{OmDlvg@w=!V~`3;~9$%5;b$uK4R&Jh4kdc55%sx(V5;pWK^&7 zK*M!{9dD0sMGdU&WpeZROo;1Ja9&FI@JD)idUxkQ&)g9L&N+(G@c@3DVL$IKO5{^N?Vx8QvewO?F%!>r=k$e?MYxro(SF2Y61>D3R zEjWI#f3&66Y{iNGu{oWIb2-pAUiB_o^zieg=NMiWNOC_uEGkOQt|90COoeqfyzVxx z(Dsg`Mu#;Pv~d@wYM0DIwVu;t$q3fE-oxf@j7g~(^zKN6@jPh(#sUR9UA|cU=R$m&PPfsaE6~jSWmD*LG2Jb1Ti|E%CLCg8;jhWn*vbwr? z=FV-|HRPccEBN;(NPcFNK*Z9y5lhTe1^hnbB)2TNr4u!jUs1H#QB-C10gB+>s6KoF zK0T(frz>$QI_|${W7VZF7z0Y$0=F^wGNUV1Pi(l|xIba$oZ1-wDVRc8k7E9^(y#p3 zc;o3KQFgOLxzZ})p`d21g6vo62~Qp_@D;wp1INO7TDcxcTa-Pa!aYY7<>x+IVlBBb zb5%szpK_LX_s$Kc!pheumMYhq+>`CuNs$6ToP@1@6())gcn7W1#oDT}*S*B25h$?c zmp;)!cMJ0HqR!!1=Yq|R$TC_eAqU>wF0OSwdwz1X^=Cq`6^NSKp5PCQlaI6nZ^_!b zvsve?xg!`|M?(J#YZZgBI75f05d3ZcN6He4)vTb53N0mJ*mpx<4~H~Ms_207(YJsX z62+9H!_SV~W0=qS=2M9(ygw*(Mgt(tk@Mo)Hjzw>-2P}q&sTKIpZOalklJroPpDt6 zsH}G|qVKK`MA)h*9Ig0W$Bp8X>|lrIOyu>TGZ=g&%JdF+b6p#7mLC6kQI&^c9Zy64 z`l*iZEwzKz?liNT?D}ddAz^10xpbAtCW@F-0Bp#3thSy~q?lGh^7D@+c4tz}wQO*< z9CI8h$O?t;lYbgqzHIx9mgPGxa3p7r^W%&{s$LKJH#xlC@^H|V3pkp;eT7Jsb6ae1 zhYALt)Nam)rJ#sShKJohVg}xd2SuZIg&@c}`o4c&UF%q<&=zzjF<-0&fBT_j$+vxK z>~2h?M6q|Vg?PT)s^P)OqM=9s8&hmbh1Htw`n!$lT)aDrwCj^p$CM>Q3kRyk21}SZ z->Fd#6q-R^01i{9aUL7&m?RcU+K7hS#OhF`0X>_gbgec)U$~p^i$~Oa?{l%3hn6D( zEG)zIw)xKT%FJmYuaoT5;`^MamoM@c&ikz}y+G3qSRXD@J@X+N+4YgJ1>Ff0>DP#w zI8}h<&}snG^0)Z=?Jqu@Z(tPa6MhAc0fmiZQ;X+zHrM;Y6N=v;ev^j-h5ALpfGyN| z1e07ux#?n$#v#aBOz z_`c9l-=4>*L$rT~jWeu0c>89c5~AP&`N8tP^VJm(`{~FT+`%Lz7vtAZel<=46fKC= zgos^wU@Xl8smTQ##mqAJt~hY9mD+a*N^Aw>U_)ij@H5)#lY%~{W@9_70Spi>#h#L* zcKJC~Aj6{Ki?i7=*qek_SNg@1Ca+j$P7rq@V(^32>tlQv^9Iu_DicjLpA*4ZD8e6t zxkyGgNVl4N$@)G5u!b9>V^X}`LqY|@jSUQ1ObG#-H1)!wZg)oVapG*DYsjSLWO~Tf z9hfEM4-+=UjJqM(fWN=g^o8$8LA^ku@==3Z)GCTO0-ve3d0aX*j6g-M9LRAX zX?@A;vbzh>lCq8=D?oH77}Rss;~&{q2oDhV>M_ihDUMDCGotZu#+N_ zI&hm_uDmR3eq{%WZ45yOqakqIG^}FhKuRD1TdjAdX)_9>)3uRFLp$yvC@N0w)uL2S zb)Yy(Hf~N559#2Nnt-V^P-rxOlq_C4wuTSc{mCgKQB^z60uNb**GqmM&bHB>pY3kN zN@{4;`6Hu&;3-U8Dee2)CcZI2DL?jdj+cbDfth2Eq}TJV9-`Ez&U!4~B#x?e{@|eB z&C$sEp)xrOhVc(ub($e_f3|<*>NAmf+`;;+r}K-eF|OgggwVawfiq#sd-H+@Fo>FW zL0`Ko`gV44dO%hJZQtIIGh!dHgw5`o9`v8+D`g`GigvyibY9kX=%dg0x`o^5Wcco7 z_Y79K``V#la*ZLInA)p>BQ2Eks5)7w;F{<}{r`?bDJci07M6WcMDa)v_->miBsau6 z&1$O;oXr_)kiG1K01LS<9baE6uGp^g;=JP282FYg&>g}EF?pE~IO^WOmw_3a2WuLq ztVhb+36ACrOb*h)Z7NFdXsPi0o?08bT!tl|8YVBRgD+L4yCoO^LwC%pJQU|#~k z?y1{)yj0rDCudc--PTHPjK<2((NZbH+e13RK#X(}z+fm>pKPmYr4ua}sP#%m2LIK> z=t>-JdvauEONT9Br*YysyaWsHG;7G3p#N*)?=B$DHt%?4t!sYF0f}TyWi7M`cQFAH2QRf9^ zr&n1p&>0x$>Efj>>GQPhX}eo%zCV){4UWh5MV)!yHK7=$j0QO+f?pc6Mk_>W`&h0< zLvCEN)1i|UM}O7Ph)S3I+Ys^*Ll__Y>w^nf*bO7>gZjeX#W|oqngx#t@Nr`k5al?P zEBu~~{tsir%iDOdwUZc7U+MOT`RFu`+Tg6&x3t&1Zh_U0S@c2HKG+%yJ@&u9D#n4p ze}Nz$Tm6%3%vV#956QNcEKzN*u(2UvJ}-hwqdjp4BCZ6M;OOAUdqpK^*L&l}n^YLJ zWe$VEId`e6^9Hu5HMoJNxu}_OU0|kSkr`v6r!zz#>~s7c&zv~l8s>Gq7<@3^@$`g_ z+edFX#9C^9UfiHuTM{JaX;0Ffx8DBQ5EaC!%$f13yFQTMeYTmymK1Xzo%z+daCm;` z&4%5T?*_U`YW>fa;?DLuW0X&ajou$aq(wEYnc9y}O4(zV-hko_XX^~xw^R+|>Qhs6 zGCt~yQ2=#b;A4h8#u=&CS7P(R>wgFh{RS)HBC}Ol_(sg#3X&agZ(VwRt<#z#{J|HD zCqJZmy}J5J_L8`J@NFH-jsZr%>jKhT>_Z)7q}atr1?(C^kE)v|bmM-);K;jA@7wMt zVky>_p80s({5M3Jk9P$=^_GrActsi9CvwzcyNnN0n4(}Yr-qJ1>p=2u1ymQulxDwGdER7{$2 zz-PhhN!iJJ=w6QP3#Xkb0y1@l*P=`4oRA@Vb@jZA;qWE)R@{cPSF``hS(4d3CGw?(L`tfdO|VnYo0ENMUDrs^t;9mp zrWGgU9feEllab3XI?HnIrRqp5^c~ygQ4E2sH@t=+(A5@a9!_E6(PSG#cBMuJIUo z6N`wmMTZ)gO|5W#cNkX@9)dhPTr`2SadrMG=-*pO!Jm>pej9I;B`P$LL9Plx#h*gb z+~pp(Oevl#&^oyC?2Ir)Vta=#UQNl*L7b}}*9)F1oI{+weOx>DYD)1wipMriRTmu~ zA}k)FjRbBGc1TwTE2)mLk(Bfs(eh{USL}CJkY0+XT-DR^xgXt*1(#pRZ|?T;n*fLC z4X5{KnEPSEx2-8e3?me9zdZmI-zo(zLTq06Zccvfc>>E%!t~z;Gk{M99eVZooD|b1Z=sxC)J*b<30n$Cgjk0jKpxq_=B%-& zVIJAB!VPwci)2JHaxOsHFJlX2OHoI5!m~RgsLa;V>=VmI3xf(nviFBw+~NQ^SOCzH z3H|aGbAaM&I85lHzlC_R9pjSMC^>X)T@p%zFV+3!6y&-~7FXn{Pc`t221v&4Ld4yp zy9-${R*6Mp%o0qWwG9h7z@7T=z3>gqj9L8?u--gu{KwRd@Gt?WO5xr~WArz}*xZymxuAYe*1X!RFDTb~rh0ZXu{Q;LnQ-BCI|FlR zKB@QBhiPkim*~F>y>X_DqV`UL#A*lL46YujC!R0K&KJsSnW?(nP3)v46c`&rzsBGc zVAint@IUMaDM z*6T&$rXT+b$90TD%W5Vc@wDrxn!0=yDJD02R(U#i6z=+;YF32?9UjlcSb0BkJWg)5 z;N7zMIvPtjq{=HU{&K}cZ9%NLd#|D7s=F=uSgq$n7l&Gh!4zM<+cJB8>#ch_CI@+5 z%0@gz7o&^gJ7^W|l^=Cn{-NiiAi2PjAJ>mWYDoz_U4CAu>l+u*=2XWh?HwOQ0tCT# zWIBIurduqA{QwmXrR?nBZXHzGJJop7J#&Olvm0;LlckMf+ldG(CEqb2AYer87{yh1 zvd5%EuIvzVf}+XlL&OM~(Uwx&O&fuX#i%T5+x7qNaGd2!?rr(%fk1x9ZZum@C9;N) zE~)YH=2D++TPfa?L8z@{nip5oC(BSvFK+HR8^?AJ0!8py+l6Pu6VA#RHaon>J^3E9jglj8II z3&wD`XE{nob2MKrnzofS7t9{}Vx^vub&)wa)LY)wiY|gPuu0hNC*pgJ$;)uCbPncL zQYolJ?9 zO9ebT52|>3n385oi9aiF11@LdLfz=Oai>ugH(SyORWS%!|Hx*mxj%Y8?-<3C1r8VP zmxx)LCWf84Q(zNO|@-oauNv%Bp$ce=KnXq z+7Z7#&%bH`{v*g1T_mMgm^^~Mc;4&XTUZPQxxj9Ix`b6)pYTpu_&qnBo{Xu@FVbUh zXjoWS2q7osdvw^Jogq>t(co6&`NDmp*fLE!ks!?24AWSP1D*dJ`0USf(SL`}sMANoJq!t#Whr@GG4cjYh+ujbyizXBSWNK|yG>~9M73DPSg+Ga0;!wl^A5Hc^4|u8{`IvRq3S-GPhb`X2;w=^#?@dRk;`uNHNd$+fl&eRNDC z-bz*Ml5ialn3*@{B4vU&PG#xHLkD*p=z4td{Ok}V0G`l}YBNMnnz&<~?Wq#;l-{MXG%z%SC+4zfWTS#^3b!!p5c zP<+0yL@qmygdD2*+o&uEG5RFSE3Y?kUlWxciLeuus6Ya2gDf5;Ehc1o5?ts1yjmYb-H#npR1VmJLaR!HD07sXv}MOguvCfg&qELtq$_{+1uKOnI9o4r}^ z6~%36&KL~c%rae8;SmqlkWvl=K~OV)J*91F$B*vVly!u>3b7ue3C14cpc;^=7XY>NTCaI&e{ej z_^_v$mjyQ~jtKD7KXVtPFZI4f)9UX0mf{af1l)V=(l$F`R!q+5(?^lgs=L#gD#74K zX)ym$)fD4;b}SNZMg_i$~2sIyP99gggt{Q_`_8IdQ!skzbC~c8_b4vG#Rn(*KrX5Ny z3ADj-oH+MV5zVat^AA`+gL*itbB$-7lqgo_s}I5U`KgEl4xZMdJ9b@P41BpFzH-wC zZ*}7I;$*lQnOaT93MwP?=R6;!O`KXcA!WUkQMSomZUy;iMTLwoh+wS)|!CObL53yKSkNEv? z!npBIE!FiA$o!26Dc(bUY!7$N)#IR;)jM||2IuX(SEd%4-fBBAe_yVC?{t>D#-j?C zuT=@-`@W}Vh9>$23~t2GsiSOg%q0e=m6Y81KyRE5oehD4GX2K!2px{ZvnZg_;F9Q7 zve!NdcU}2aHL+wG!RX@-YVO3`)KBZAcPqVv(Lb9J3S8Jl*v9XT%+r)>LHhk(*$)xe zJgRX?U5)k3l#$!je+6R(+kpQo2Ge~E@8J;qw;`ky8n)|Qw$`ZO&fmbg(-AdodHG7O zA2&2YLP-VZ3k#VB?( zI-M8UVg0`%uw#a&vG;F9PU+#OG*1wH^dGJG75#P3*I$uyd>Iwj>Z6lgV{yd_Md+Wcsvc%!^1h)DY5_A!-U2(L%p%h_Ye9U1M7kWVb*zWo|J;iE_ zueUK}!_##l@AvO6^}LVh@XX>!wmXlCl5cz_dtRPvyp*N*SAvYJcXv2H)Fjt>4@$o= z%eQa)#80smqnPj96H%$Xdx8R9O?5P}T`9Ro2>(yXPshW3#9%sKTxZE;0DC$6myB7- zmQ*%2JU*S}zIAsxhih<{@AiuqA5!R{3`2FFKhG_Lpc`8ZmlR^-Mcw*}1H0Bw@_*<881GcT{|muC0ZPa_-HKa29eds*=Yu$oOoPD~hA zB^8+`{RbfBr>N=14Vs(9jaeoxLm+f?8jCEkzWk5dqUhHv*P%opZTJVdbe{TOh{y7p z^tXLfj~uGlhx`%Q2S&M?}ht;Gy0K zI+4$HdUm!Js;yRpRAf&iXS?WH?pupeTn2^gUQvl5J}T{w3sCEm{$zi61=CtSwr*@Y z5n?Wm_C13|^}YC{J>#r0;rpwX@B0I}kb~`JN{*=}u0NAF%RIaP!L$0e=UT^y z$J0#qgz$)opv(0tTw+f~BAxe80hDeOL$-KF{OGm1Z_|T2`WpcKh?Px|2?nw;09X`_YK@vw@Oj{kDHTTgguREx&wGI7|O6F;o*U@AdAF=VK_SZR^c8vG8N;pL% zT%GFp4WHM@jZQ2n!HVRubKpdD!p7MRL?+M4AUQt(4kt6M=Sul_DX}3KQuR^!syby4 z&UfJNrn+_4GtE;4)*3aDFi3-LZ)fDEE96|uv{Y}JaIB1bIePwk_FmYF=wNJw$7iyB}Ka*DE z{t*9UXRR@`Eb#fBE~1nEQvvetjCG@6h?|#;lhG>Bot&d&%}#iO*K(h~=%-ylhmGgMsqF6d^4e+clG5AHaG4I# zCUxqvkANYi#ApDrqCyGqqcq6B?VQ-4{_dR2%mBtj0OTYkpWlsV6pqzglE%cJ2BG?8z9D!I*2zKmXJdZOqG|5iGa8A2SbBd9HReZ;%*$P zB_lc2mDIwm0==_}DNT4W*MlI2gqb z1P;D9|I5Ak`PQ2&9By{P@_;@bPKOQ#5bm5TpmCSKPVCg!_o$b$x8vCW&jDWFTQZT z_9pQUd1&YbN}a$T>d@#a)T9tM#(v5DU$v&AJ_v|NIMgoEkd%LeVroLdGwbbqNi%nE zmbR}PM8t#os5JRmqvVJPQ@eivSiL0#=vqNLZ9)cX<`m_%m5AHoZkJon%bG|*o-P&Viov*M3}UR zBycR`Wo3J0@-Rpw3^gY+H>pj=!OwKV1|LBJ3E6ELiv26GEL)v;&pS=hw699JW9H1! zDR%!ei_HI?{Iq)w^u8He#Gx*?MD(6axiAEWMU|}o1yYe)L#ylMC^%J}H-Z$CTPpa%9hhqQkYHWR=?6fDyr`Ok92d?kHh57q;` zt6vVljn2e~Xev(XXo#W}-ctW%amf{uQ48gM)M=S+fetwy_T>0|lNLKf#$z!O^(-iL zfYDd6(JJoc#lZ)h>}NmyFbr(kcKxe~0ajOmGwZ#fEjlGI0fuMnUjoydMk@xFD(}n@ z+l)V*!{59#(7iX_fA23Z&@(RnbqZ|S7Pzp>a16g$o9Ck_ow1KWgi%G?@QB75F69>$ z$RE;Tozkl(bmIRL7p6lgow8SGyRnV*w7vhLFY297n}|O0(y0*Qze$r90s_VJfquIn zwn00fed9l2B7O1a{!{XQR?cs8n*gHmzHqenc!$5E&3Z)mTm!o(aP~ibZEySxf7c}o zzJJNM)-?t~V10B-r?EJ0467Tn@0eqaV3GNkG_4-{zrT{>g8fNfjL9*2SHM^Ml*IGZ z8B^>&XpT>`gxL`+Jn^-+F^+WA$&j*3XO&&$e@?BMuPT`6>0Qw6>oS67m!9Wvm|-AE z4-+Sr3bL%-$G=n>w@*G(+H~%#7oHXmZJly@@&bdYo>#kwwv)EjUgtTNHemM8f-|=g zhOpSR%5KgI@g1>_eTRCT8-*D@B4y0V%Qu3?v6sw95m_@kja4h`<**pe z(E9fcD_ATtY|M1=8}Eo?BS8w~#{uM?O+1N-M!+}U-@Zdi75`Ik+pzlu&A%>aV4EL0 z*!;pZJJ4~i?Ak1@3XIdU6MYmXYkn)`P}V*cT#ogK7%Pc=*5to*5e&*q816oJ9!xVM z^0oPIdX(IFyKo-%0ZoPey@_B+`^^>2bH8J742>DTSHEW>Wst-*%J}iK?cTf7owV=o zB9Z95Lj=Xai%$+Q35MsJpa6QWa+jB$Z8Mi8yF?V#6pW`c3hqUgg#H@+hb3w??;i2y z3y~n7x{TayxE5a%tt=I0yKj1RYL}1|qDKuA^o|Sm1?iog1&6xVZWG7`Urraj{6Zzz zv)+)H*mYL^qs-+XUhtA6Z`r__cyLe-dpWOAA$Rv`-rV)q0gUgHk7Z2!F ztjwGi;T&oT?xvD<=6g(B+1hMouB7&sv{KD>fc6IPPX*3Laj2#0#TUq`6~LV;tiDU- zCxN#U(ZfmNM0h+ZRLxKF(zJ$~E0!ELWGD%vXR^(Oa>FwFuC+0k^Gkm=;mU=`bfpHO za1Ix1!1h1RO=J?DJOM=+Z#bKY`g!9R+O`Iu+UGo|RXhZ+>~*;h48HG3oJ3hBE4gvg z!I{$)7*sjJLHXk4C&n>Yk}ova3I$~OZ$31x-V7r;Sk5Vk)9n9$r2S8vO(GtnQD8Uy zH9G}g@F=MzQCe?~N|j?BG_pr|jrcF>{$s@dRo#D?KXMTMg(P2w#~gr8m*YZ`-P^Q{ zE?!mInd#)dZGb0FUK2QAt02$O22ESZha>O;GH6sA13yhip-a<&-%#Oaa6^I zK64x2dN-8?n0=Q(%9<2|yk$rlK__(`r7dZV6Ga;l6gR$AnEw=N_bp6X@k_|9-&EY$ z$AN)#SN#QDxjDVq=w#wB86de3#)bIb8+eEvh#lb}gI$o*RODj0ASB|N--=$$B;;kx zo*o&^T2#AJU*ogO9lFX6KO748jY%YPe&m*(7#%%|ft#&H(#K@ZW5(`5EEY8TY*mUT zo{5c&7M>~aeRa>0PT7heOi~GfdSEh&ABD_WrYb%mt@^!^B7?t~kNh8y+udH zic*jLH%XvvxNyGM^!g!%42*oD3Zp@|=1qBYelQTR9=-)MR-r(QJCx$x#LP&PoHiKa zOlxn8OG-oYJ(2ZlwcpU#y-gd0ieO(fG-6$m3lLleKGY$9)YH8#&^n*}>WJj-P*E0U z@zMgeVEn$46bjRuZdXOko}YxKs?2Nra>j1`k99NODO#$dqBHrY)Gcld-pFg*$|-{E zrT)-zhhpQHk6dah!tMb{7EavELX%VMDw-)Gpvnm&iJ*XxuvJpa*cX5jO&S6zE#T2k z*QP}X8jfkAy+$f1cbGcn>f3%2&os9|rI+kpt0P$;A`~qeitHM;97y3i)PPh9`Efv8 z^{PQkNV~+C+n`3tKJI608~+`Kp>LgXW9Nuaffy^O5fMt_#X}b0|3raZ)ZBMEUvOg< zb+VK~OBK|FmL^b+)=3Ikv(fMhi5T%>~8PEat`b1(NO4L46aZ_sg#g(&6Wj~k1slb#8 z4`2x+xH3!9ve46BN7!VgQEA3Q#nuW>Veq&;R!tR%I+Y~8#Oda8sab%gnh7i1ThP%= zFV@rXN<$lME0x4wRik&FMMl`sizqnZSw%Jlo#}0<-li%FTVXUBNg?zAfq}S>lbsXpa<(l5JXRa!bp7fSvA6=1lX$IMnpw z<%>7FcV+Fj?EcmA6u? z%jWImASNyrP` zH~hG8PtZjTC{OM>IpIbf*Wrgm)zFzqqja6ZUKwoFT@67U-(}O{cPmhKskuIWpQ7M} zf4|`DU9cVMsJog%_z{JgzIQgCy6~~s<8|Fa9kZd?9~}D#ah)ulx|~Froh7?NyYA`K zLO;KV7OUIEnDm(_<7XcmugMv|EDmKjbyh7{onBG<#skfRz* zDf`dTrbo-?YS$J#+_;}2CtaEtH>VGNKuux(w%(px)O_*31C(JU6M zCKz?SQo*9TU5dN05WAK>3bsd?m|2d9gJ)c<+V*0$6Y0$2 zLp}*bT~I&J-%qAWuq*7gkPGZ90uMolN$ts_#R9oqA4u@ww2U>9Ym;^MR~XC0x9=EO zXw{rcutD^cs!siC4XkrGC_B^NOva^l5Gly zOdSajVW-5BsMZ7%C6xB^-(s{B>iiFHUff8flK%uGWfg4v+H#8O^nRvIDdNCeO_k58 z+TYv)zk!|0D$GBcgk)MFau%IFG!RHu<7mJ$y5nFrq~NmT9};>g8Xc2Ts8Dckrjthh8xlze zG~@$@F-wTuVF=BV3qyW{k?74G@85LVV1S?N0bR*ieU>~V%2$B46=R4`SV>9yqxkSJ z`3MG70Ev`Lzr`W~cQ}yk19PePM{kg>J~h3!M)KDyIz;>xd|%2Fn8>BjeWjD7TB4=b z_uB+Fub;UJ`x&c|8y5L!#D|pdb z@Q9ilY@P^Q?Y8OiILDl5E*u+Nn}bg)IXo}1V0r@GeJg5y;lcl3+4PMW4D&pF5(_VoynuPhzdDjy-Gh2O*04&1dT3I(+&2ks>CmbrA@Tw1qqCQ zHps_)j7eHGSSa?55y6GA@jP_nP6!*p@Wd6X{5TiXd)FpZS8b4vxqOe&ZU*OLX>AB>BWIShnqOK^$WDQjx29WnAM#RI)?tzED=pIgGn7WG`=GZ)s-4;5 zsk%2zgB%AZVPyH~L-K@N?UcGSnq-j2i6iN7MMFpN z1!F7+K5E-a5nlmN!mhOb+yi=`wvN7O+hD{T2)o>I%Q7{N0y>!CHhr!ve+K#>R=RQH zS2iBVso!fyGLOSP#T3DdZTsXc>vLud2HzZYLb`rM{gPpNFdzD0c<8^Q4-pR!m(X8x zOBBZg(^oPhk!v#qLZKM!Sk3X;;4%ja3=A_L^gdUy)dIM&I^c{)IAaoGBZq*P)&sP9 zm(7^TQ;LU&whu=ss7jYZyOV`1h-$IR(zw~}+Z7{a!0)`uxposg;-F0L^f-JF zSCsMiJ{aW8Z(aj>D7JB9r=sNm&!a)kc-?*F?Ge2pgr8l&*CJwSOxb&g;cXkfk&;=- zRtvD;V)T{X2Mn> zR1R;@DWzEYH3^WD`#@yJo}|a8+ws}&_QIDpq<_$*vJM?F7IHZGhanp)G^M+LOFoFq zZsr6fR7!bMW>&bB%7R1x;w@&9t-q#lXnhxP3b@N0>kq7A`ly70>s3vG)5?r51V>IP zMGC&E!DRfla#M~K#c}G2s8VG*!J*o1cr?R44~L@{;vKs*12LW5PL?i9N;3hbY6yFW z2v8T?*6nHFc-OpuwT7lbUn{_XV>=#9&cZHUBS-b+`Q;~CS5p4?CTt+<)5ny7n=_Qh z<91osfZgd+mCz3yxJ|5gt6F~NWpkUec=2ECH9?A96=bXkOgcc0@9k_=l-N5@k52Vb zf-TU+ecc_JqFWAWf}MKgrX8t$2ajc84$G;JN zn72*;ea*~lthZdtr;N#9gxw7gTc?0Jm2Xo2Y#sFjqQw{6_j(xJ;8mMooud(VR~VFWUvTo z1#Rv~_L)pDyvt1u=n3GG%}W*P=8=14jIp}`azujdsrht-fJxAeopZ>11E^l^jR$Z? ztND-6#XADM*J&-RwM7y~vhjznKh?RhN7)}mri>2IPFn3)@Q!Qn+!_>N1Xf3rwZD`s z9|`ZFA>1tZ?5Ub`Ob46Hjew5jWA}Yp%x_NLu~WC&_ZMqc!fjs8PRXuz%Ve*+0TXVO zi8X`Fm>>V4c=F<@>;5W+jquz%j;P+xoRLhtMW)9LR_$s+S0^;>*Ea*$Rg59`dp;B8 z3z~-O7vHp>rM3?eN~*Zy*u1+O$3SM>EG3v!pM!kF1Sv7ksJtz7o-_Rn@x^qu;l> z?V#K&EF|{r!*?bVnx|Mf8a(`*D%C}}sYPm zzxWA7ZQ2kUDWCs*!I9c<3%`#L(D zN_0xI@XcsG7&a-Oov=G?>27HMHC4jPD8`K)Q`pui@s~x#?&Et0fh=<*s0mX;Ew`Sde;Sl#{1-L3(qBn$E`qXWRYOk+L0#Vbit zw;6Xj!B$YXq`d6ySU8w{>fYiWSgC3JTujcu?%aX-iObYKqF6x(6XsE9zH>u`nk|5* zek9bKhM2lBzMauGlUs91ODsAxq&V*CkjTL01mCf)lGpSY3Z)nOG1satZ1K%a&>|Vk z_#$p5!pb@%L%pVb2smm$_Dh$>IH83CtB}urvzTeF;ex8#QJI`#FvmAT^p2ZQI)V_)en|4s7AQhXS zO-)OMMMfruqsYhFEs`Qy=DHgLZqWTvBB*74^{9`7&QD0biK9--PXELN2v_-Xg|Eo= z=JyVaRltUemql&R@(hF)gU3()r4#v=I2x6yUFtInO9Oec4N9{7NHpdju5gHxp4y94 z-{q1F{y{y7(wKQR6xSuQx>* z(Waf_%t}bDpPOe_=E!FhD--I=LZzBcJ!mxO_p+0tct}azc;1ywom}YYIIP8Ga*EqM zLYCsI&^1O3-7iTDbdV10H;a?<7(RFzk%75Hx!{MqkTk}CTw+Z$W0B_6Y< zZvq8b(g%;%R3$mh&VY9h!Bs0!0pHXDdI(W^vTyI>$proYT34PoD2y7S-5X7zgV+U; zjj%Nyze~kvLZCR7P|%H#qUHW1Xz>B?bhLxA;)goEFmyRqiV;5-bA8pfFJe_;oAC^f zpa@6EP*i)NMH)7A&)Qha7T=br*v03kYDw%oXN5oY7$MYLVR|srvg&CfY< zS2Y7$cLDYg&L4nTtg29JWvd>!%+qPl(O#+N%k}&tOFN@KPAJB4HzYT4N#A73GW%+7 zB3TdoL_5d!mSLp<3IELAI~LDmg6M+B8KGHkTPrPiy@Z^aa4uNt-(EWWDqg()+VuK) zoi=DMS2OiW1V`gOw9xG!_ts%EHEgjs?MA_79aD*ajqPa8FSW~7x)H{kwL#NV#}DU^ z?#-a;6r^LE{7F+hmP!I4lbq>QTcZzO8@#`qt!#U<`v;5&YjPwX*aTO~eNfVQIsCdN z*z}eh)2ie!%yuP?8w(nP&7vM4 zpMJI$Z7jKWTKAsFLQ6f!99%Ub(mz?-H$?qRqY>ZbA3bPn-}3kwRf99xc#KU6wT{t@ zHEO6pYo*zY2Byx>c;H!1%rLo$!1}VfN=}Cs><(cP&>l=?!qAH?g%5~B+}ZNt z&}z9m7!Qd|a#v)s=dPh(dZuF}?*yvjw)&3<%hVR$ zozYHnzPp^w7I2Hs##o1L!JaZTOwp%%mojC@`cl0r9?U!B`|i~7qSx7#8wU+JN;!D& zK@w4v348?p`6_&Znpvvi@ztJM5;!Nc$^d>F`_yUpsY~X|2u;e*SHbY~!6UVv{5+z4 z(u+DLTLXW>^AB{Vi|Xz2O-%dva|LCd+pF(co3pVF5AyrUnnstZw_e*2xJU#O`4juo z`_mcxg6HHLXny8C3mrx|8N-Ce>e=bPR4O`b{)Sr6q_aGto@JASc`rG@%c|y)@l#JwV4z= zOyTD{mN(1GJ3fmn!BojvW+QnFyN%^CdWpXV_?)FDkc;MS0!#OcplrTKk9_^66Peof z9b^JEq%7Wvh1=7t)ER9nu_gzE0j&lCSNFXG2;^DC`OVpU%-yv8!(d))svHx z6QAXhc%uT-oDjkt&tMc;cyMTZd)a(-v*^^}Ip7$;SbzYf+tvT<+0A0EMv8SNQRe0! zc}#(0kGp>9xG3yJ`*L5D18#g&t6huto>p6ytAejS0dM0xH|%0JshUstXXw-YjU-PT zo=EDL&^0y^Qk2MHz==|EWYUTaCm>fBLGRN`oNI+FAZI@{mDDm1;3k)2+PxswU7wZK zNvFrz{6VaN=6+7W)Pjks0G)!N2|8Bqb2>JTpS9InZjb0gQ&8(SPpJH>{{oTc;>-=W zC7qp4kx6=0>fRW?uORu{3JLfn^gs|;GX&eNs1Ql>q*iIh+HCU)BKKFK=dLK49emYY z$TZjFPtZ~tOJ6yN*z(EA1JkFolX}hs7si(NRX55)$`z_fKfwy^ILN_6yllaGbeZEo z2@}eAZ!~8~)8x;g!f$M~_!LB{#U&^qeozzMR1S{8AxhIe=3?JxaC}H zi_en9JFGia-)J-Q82638{_?i*BsZL@GMHZ?)nHF#AG%*9!XQSScBNEw5SQKR@RtH( zorMRxuzA4M{l%dBf$Xb=eHdd2Uj7#`lVoRGY|U(96r$HoeW%-!?L7)&-saroz6CT;Y21XW1&oAa~ifx}K5!)y}4- zk5^u6ovHZT&&>`dH}C}>6p?o1)chYw^!zhNL&FeO8oZghtI`J(s_99n>foY!5nBYN zf9ni3%Hcl~3fZppWmS%OSU#@VGA|Zc32?l*5~z07TZ7$HXHPDD6s zf55kdB^iB9O`9vdj z{XzC=vD5a6BjQwk#|jrq*7kJIkU@f;$$IA?Gw1Kt8(VVc8W8C4Wv)Sj9>v8oaH}tS zcTJp0c?0%2bbDO?75-{ytJt#dSk3>?Nsu3PYAoV_xxuGPom~TOln^_7KTb`zD(xSXi!dMT#kUU)|I^zo-6AiRd-)3A~6uPzLX-+ZUs@z=?jbNm zA552h!`~V%-pCU)GV{z}Zg*>(M!yHgct%t=6(nC~b;o!e(Mvv@?@H}A9uTeEE9Tp2 zyZeA7YCz)xh}?EllxLTW_xMv?_ie5S4(_&Nrh!8&AAj_tjb2a$*8Dt>$wK&t$}bpp zzMoGVKPs%ogD(XCq>q|ydJ4VQ=&H@l-$O3DeZEV$KPw36w0zkU*xFO-_U-YC#!9Fj zFO8XAM~CM8C*c?n(}E?W9Act` zk$B>dZ1+fc6THry!5p4$|HTKUg8X9C6_0O7y~jhIP=dDmcFpy`%F@|vK`rZ8Df^IE zkzdzWI9+dIr<%yH$Zp{ikN^l*vY4f*nb}tD(&z6{*3@7$WY6SPu(Rn$YDk%69->Pp zG5>4{skFvqf_AJxAkx2*rslmbjTQEm)@=fE4 z{yIxslYaMhLm*%y@HfH%labFM5~rM%f*&_LG|UIQX4J2@&s!)C6FEfdR(v%m4v3Xf zY16Rl2z8@tPn2hT3Y5h=Vixl7+lLh_k>}H>V?{_ET6+dZrR|Y=k|H7j9oM6DnoP_0 zBbG5-$t|JZuN>LKdv@vHG4Z6gnl;C+Iz+fur-t`qzKr$F_<_utLcO)*kNEB5@JCzY z!n{lLWQ5=Hwe)-`Ds=cf{hJ&AUU&jb7Q{R&?6t3IQu{}m1K3Zw)cvIE4Vggl zHPY9sVY7`EB`s<4APhBa+Q(yPL^K{ihMu3y{V!(FOaYsdHQ&IKnji1@`8 z^=V7O`w|MP;ChtA2hSS5k=T&b?MrzhKx+CwPjAP^QkiV9=;R^6?n|0Ww9%TZQDr~a z&|bv}gSLNQbk1l)mNh0Hd^`m6&yef*5XhTc!6xtuY{khRS?9VZP~xE_P=29ybzw_xHgVVTDo5r189zZ5&~x(1{T&NfpQj3Na1mu`CTb} ztih$^sL)#vsNXKQy$P@^0k4Tq6I2DSJ%$b ziH9qsq{mMi*LU@m6qLi_;})85;Z_V&ex16LSZY&9u0D8n(xN-8T!#}K4A&yi`JZpK zY15!nZ2h}vI3}uQ&okKa4BWfl{*srP0#YWoEc99}*4PY8oitDt8%E!0P{PX{ z@ScwQ8+la(I<=l9e#^YzWb6ipFo5PhBwJT07)L-^=b*dCYmp^*(}cGR_ODwlSY~}I zCxsZOBk|_Gul?9h9kz_q?(sJf{JK5Vzo7gQBgFSTo$X7SRlq~;O?ZGx|LH!{uP#Ot zwXYcYzaO;eY05%}#aFIXfZUjR?pFY;2nAG(&d;uybW~@g)~obZ7rC(E!u+EH(v`=` zXn$AK1bGU>LurrbzR3QTM#X@+Vj!Z(wf~~5)Ze(>Ubm&;BYf@FNzw?!fDlKV6a-xu zqjvUkj86KQB)h=RN8}w2@YDpT!Mc3w3^;t{9j-`lqgizf*VCC%gxq)~Z}2G)``i{P zEIb`DnzNv7!UrzG$3sO_W(8!ZgOgfsc|qK?p(NMhD;mJ$PFrrw1dm_|88fp2HJ={= zw)Nj~=Mg#)5;C$My|u)Y;Um*bzPTHs)KZ84Gzj=o5sLsgYgZmOKqJItG_Vj?q6g=e zG)8D7I?97pQDL$j|DiL(GH1K_P(g@P;fLerAooH$ZmCMHhcJ2gB;lE`l?C074SLY} zF`cw#M9K+h^cPxzC`M+)@4@-_$59dx=12Nzt#nux!=lh$rvzahlro|MXnQ+#i_#@) zb~jM0R%Rx+o*aCQPM&dnvmQYp3{y3yz!M);E0m zT|A>BiE8(Lv$#S7qcaYJH%HlS0q|aYR0rUa;Y`l? zxe)15H0FL*lkF+nl`E=Zm6SQ5?+`D-g8p~T$l46^nJt++Fdw^zJ=!i;s@xwpE*9tX z_P$Ih*@Ew}XIMRYzKGpG84{j1Y9b*$?!%@eJ5@vDZJM6^0rq(FXP2T$7Vt(hN=DpUl}d;>2*J4IEEM|L(D zoLY$zph&~GBK|W4xXYVN`D7RrxrI;%jM$5(lvii?iT$nf4! z35(Jv>K;&$bvMA#E1mYr$Sjx&zMeG{NPCwcA#MJ1i^_Q{9acpDs7* z3*vEynH2s;drK%|LquS*Hq^9LS988OejgEFV)eb+AWmy~d#;7cuJ_J}Z+y|t>X0;j zuC0zN+?B7oKP6Wu!!osrhha-=?{zR)UqcMA%wEU(OLCYDy}&$j*04 z#bXo{{+$$MzI=_S_PYW>J5(@UL4SvZM&q7Ad-PX@p;oOR`bJmWWCxNS zd7lWh1rmDGNcrLjBL=h}TmLjG;~lr2)DXPJO7_yux?J*Ayn!3uDRc3!Nr3h%3(Acu zW}*b07^%bQIK13R20vM^ayAh%f}&Ci7_5H0&T$L%_G?$G_-;{yeCe^}Cw~jvvYxPF z_`Ld7tIzYm$-RISX>V~x`|LHDWRHC$y1afiB@C{c>0;(E4gI}9=W*jrsAv$<=Bn%_+zk082h7m}#wtyL@ENM<1tl#ODGc(k~CdOd*sbN9CWeoW-Pk6-X# z*p+ocFYk(8pp%V1B`8zc=W>9wiP1BpN62SrkcaQFt(2hsQ#jc|8^81zAV`vpvP>+= zD8}H|r`A?aE@|*f9L)5#dNCIi9`rZsNZxhpkZ(_zB&E*SGY`zp2(tfi0R%YBJe3`m zGx(L4zzweW`}!AfG|w5?JPE`f_z@?;4})$ut%GVRin^S<@W#+r6ul{jTWpK z*RqyV-P$Z^%rrmC_Wct}?q5+LML$nmDO9_kV5#-8AtSh62Ncd75Yja)Q8z#pm$}SUveliP zZsG9i{^XN{7_Z6*@#Kra5j9sDASo_n5A0UDv}aB)gvqAZ*`;B1J?FM1lt{AgRxM8c z;Ao@qezWaTEbUFuFUL^%D>8^;SigJAa$4#8RQI>cdaO@^j^7_|j7fJ$xiWT;%S+<= zaxVM&d0)wkQLpzGR=LuqSuc5-8L)kI$yL}KcJUxC-VIs(LiQ(7g`5HnyQn4AoeOTb z!>6u?5y7Z6W+3e%Kb{e(=?@8D(sYy!P@Lr{mCdRPQ&jfW*;=}M1_mml-Ox{J{S zF%3?yNCc`XmXw|?@pF_U5BmjKGIEAOd(O$+XH@i^nD+y8v!YV9BZ2fP)M)D6`1HhJ zQ7vY#Iu>jU47J&WXn?`-U$_6N_`GxaZSqEQRbwkm2e}v39)H#sDCi}ceZflQ^XiY_$QwJE=E3gFfhsKiG4gq`*`yI z5{EnDpDACa`l`)GsJJ0G>o&eUwgv8z*jBSs?s?kqYqI*w)!wb+pIHClpf{#y{Q3Y( zIB=LH!SX+IxQqvafk;V5ZhK3On_D`BkxH(xuG*kGLqgr;O4580!*of#dW&DW?TX9l zd?#hX2`*iD)2Z%If<}F7c3~~0xayyvp_#=ra`U#?n(PDuI+ZcJ{v@}gh_%x>nfuP* zba>`8!6f+Wj9s*%sE#4-z7MWuvt5>HrVPKBXAj;*WO2D7Ln=oyf`~v&jKMxba7!UY zqYxRPQpvWs>hk#TJTN?m7!a9{%^5U9XHN>)nDWRVf^QV+rlbQ?!l)SeYB&$=S_6#5 z`>rXm0X~=s<&V#v;R(v9WBG$X{kW@8c=Jxg?F1C%^(E6?*;WTLbEYNna)bAJ>39^aIwb*^;9^G$LzM z=+57Wy8Z*dsQI>~Y09VE=auR2%tmw3yr9ahSc~&De?din`-grBE7pWb%k-o>AVxWA zyp0dt9X%F?$P-0fB8=Drf2zWze&-c)I-!we3=2&svB`==s}J}|Dq-nxbpt?6n55>| zlIiF<`YUk?@UZTK9AZjnfeDuR>0QEKOWO?VDK_apCqYmA9C~2xten-OIjRrT`yb^l zGy&b~`;o*i_L{&zet}GQVBmT|Poi%;73uMcLt(w7U;AA9LUI^iC55#tE^bik%*X&` zh@dU$`95IQY4)M+eu!yzWR=h)8lMCXORWDr#b=I3Ydt?Zxe*KObMg55G~3E+QL=3j z(npPQhnmjsT-(jMR!%f&8bok}DQ52t@ZFbk@xtuczsMP+^Q$ITD8&9&N7&u5#FLGk z(LV0d|EpA7H2Qk}%jD8a$pF|a?YH%s*`c+iN}ptqD8KULsrP)RUV45=um0jkKDNl1 zghEtJub{wT-aDE1=HgJjDFZ`6q(vtIIU1D5mm-{H%6zr4X>!yoI`VPo^#53*LL09- z8bjJ`N2>Rz_2oAQ0;FXXhK}*Y%zV%Z!^RBBrX>+Awg+1y&($&<6$!L0ug6q4x)77` zArRGk_YsN&4PxrfzW_UYoLp=s5}zFA>g~Dr8@8miIV~PIkqnM3nV}a()&w2^bSiyA1Rn(p;bBDQh-1~%I zaUeCNav2^sEYW;0ntOOE41j?@t zod+H`l`f}J32Oa0iJ~8{K>5j%jvBGV;=4>H=1pg2PV*=s)LV0OqQy^&OP1r&U^zRk z+)x3E3EV*6`tBPB9$p43XH@N{ZNJ6DP#tY#@vnmW8n}1@(`2^_gnP1N<6b{@AIRu* z4IL!<7NI=eUR1@9GRGX&x^kSCT}4|u0$)9`MaDw5dLm;S-`C;Xd|zmNb-8k-%LO}{ zR3sxtgs$J}XP(%Y!coqIv?r-DZ|U)8Q+1+(Yv#>AIVVRKM~nI~?zha)10OKVn>s}f z_VuwpYlfkyW#O^kjx3(C9ZFU6a6S(kcZ83b-b>sN=& zAsnfevl(V1nlB%Bc6`L{bSBGzSs-KXz|OzYP*OC`Q3nUVrX}|n<2Q~$mai-xgb`Wc zT`(|p2sCUu=mN)FiKpz776@H-hI<2FQlg47`?6h%CfZ-9XR+pAnG>2j6cIw&sjpp^ z-8y>6IxPWpB|XKH8I0ML2McWvBUZ%!utSO*7i@*rKc!G%4jI`(5uX5YCFx`nX%8M zK=kTn`;y5&dne+u3&H$DRgt3B{uYrJjn=vWh$YT(rq~@sg{WUy|EvA zC%7T6YM=J%df-1|)H!A$xMOMOKA9Q-QNip8_PV zq$pwh-^1+ufqy!$&>N`zAEuN=CY=vckZjl75mQ3G%$4;L4CfTpnf8b*o(V?#7hm0$ zd2wZw$UGCl*{;V8r{yHy+TrKv>;sY)riOM-2qnf)?!Wnx&g&0JXk0`1y^uY9gzI-K39S0QhfaNNAFJ#^ZG9wE|vg3tVN zWFEEn$88Uyel@f-)5NP}k+nQK;R~iiTeY|y_iqcGPgqg@2%@eMa^6_li3+yelaJI7 zI>a?=XQ39%A0Ih4xo3$BVwNR8N5gnTk6v8A?tF_W>_Sx<|ExX-NtI|3PUN)u@%Khh zzQlk8R*?!_q8uK+bm~KMpJt<0(AbBehGvqiQw-e>kY|K?)Xm#?rub8ry8@}qZ#4yZ#gRC~I-C)4Wcd4udfHN433xm}x?&+F?~cg{vMzK0gITm4FIU4d9=?@qbO! zXn9-aZgoS8;VSvroR1@U0nhH?gJz>>AXHfacy5PKyK?UV9g07FfqFEPv=H8~tiR7Z z@Hol5ihKhozRw?S{jmA8@^Zk|@s(KT@9Pr3C(ATK4S%6YFq zUrauO;!FTTm?c!QmAh13Kn9XOW0a~`4ON-Kcfcr&89Zwwao1ix`TPVie0U3|kLLYa zc*KxhN`d=H1YEz?34?S)n4TVwQh-Zno^#xEst%eVk5~uDFhO8opW=TbUTE_xI1GRH z1Zv{L*MbEsX%j5eTB78UyN!M}YCT%9;II^NRHgpXZ8aV}Jv&q&J5=uqC*A+ zFY)hGS(V+132q|}rb6EuSTI;xy~0lR{3Vf-)GZMX5)7Fp1^qzA8rRu-Yrl9fwkw_4?WJ5KrUx>!W9vWWe3hGxykJC{xP zNNWathuYzFYjt7c0ClZsS27X0U%cyB@@Uf>C(nzyEQ{{y7_h?Tf(r&Yxv`a$v<#@r zCP&Ntd9=^eVx)~hXbdDxP*AZVyXxc0YRHvDYH#51(cOyF=cygHCk1L)1Qm;7n7XFb zOi>;m;mpp8qk^I5Y2aHtnVYmeixe&PSHv0Cea-Ua`^Xe6vH%uvZhQpMU*~E)G*pf|-J|1Tbny0GA&sdfdJf#`Ja^LQEP>dh!6U2A);&AnV^rC6 z5(BR#<5HU9*9yY{Lu28DVnpwWuWCjqww&$DOy;9UJJJB70oYQr?-(JR*AqPd3~Oj+ z9wi1!z=9)5NeV?VvBq$YkC?irC)k;M^r__R5ti~$t(eged7!wmoXW=rd9AL0ijz7b zoqfgDX?;QERhO8T27t z15Dy!itxKA<=^Yy6?DgvkQ9T%2*o3lvQrEvBSKx-^CB1B>`Gu4kboOT8(gM|*5R^T<=+d(y{X#mBWj;G(*7qgt>)m=bV-=+@b$-RDe5NgAG5)V_8Vv} zQ7L&);2kj!aB5r>v8R6tRwN`gGiy>jcbRqT5mzs)S``i|Crf%e(hJ7(Q%SM*jSe2E zK;{)Zy{Jdw`8dBZOzUtEscFOUWvO}wtUxG3RH6$ez|Z`qieKzN^k!%c)%LUL4@oZ$ zS4pbY*RCfn0K!tpKqMja=jL2f0ZEM7TK}ncQpos^sHUPU(8HFZv7};9lYZ%uiW(`M z^p=q14l|dYPXH_(-dN2ZP6@0wR-HXg$YPr}0v{v%^1Bg0Kodi}r}7F0zb-I6PD~}Z ziCO2k=Do+k8^HbG%LGY4uSNfj9{Ja;esUDU6O)3?T%&sspEL4o8gs@q)x8==_YG!Y zUA2=I^ODi}YIc~1B^r@WZD^(Jrtu}pR;|+{a+kgJ5aUmfR3oF}Y@J^2n}2v1t#WfW zkrEM0qIgE2r~j~=(hx8xV#uFdZLMz1u5|VizWAi zL=XISUi!l`YGvIEXu5 z4YAyM+40aQ)bhV~7ymf+Pk%BUtohrrKJQ3P>HPkJ_L9VzKIQts*z|0>ySHaUmRWUp zG0x{;(`!DHNb3Dn>KI?*);9)8+h88=o>Fn%)$#*tirL9^aG{PC`l0N&aX|U(N!Joa*UA zI3y^OlvgxT7V)}jyM_m!$xn=RHa)EOYu^u0@{XLcPIyDc;7<>o|e`Ug=oJ5J~;HApD&L~ zzrBfa@`aO17QaljJslOiXE;;$0TZ28%+x{o0!~SIn02EG^(YRX&B2gQn;?ubeg9&G z%5KU&K{JOwu{y1HexCy9!La7J+O|$r(eW9y(0)pV;zX|d2U~V(rtfg3k#2&P2aC0y zcb$KI8lp+m`;iRhPxL~WNePCedOf7|zvS^a3GSa$sA+hp_>tQg$^`gb?!@GDdDl1L z7b}Fk*$=>_MblmRQ<@2rqlclatmz+TY>;|h)$+hVu_PEjvR(!8`S%x<{Wuiq2AY;d zB9Sd_sBlBeLB#6tK;Yicw)*AWeV$x|6@Japr2|Jg$pX@{n|zUU30BuOW~oLwjp-6l zR2}hm5?!EyVHiX{AF7Fxv;iwn%Mj)DwbRkHEkoTTIW_4O<#CMAsBks9MjTUuliYM;)k1DN6U8nY$?^2 zea}RxFEcKSz}bDPi*FQM!0@=AfZW4L^VkDyIiKcct>-f((%Vl8^PYB?bj7!Y!k%2V z2hPl22B-H2S}Q(^s7QEgbT?=WS5P?izIs34Q!KUPGDwUYO(L*hPoqv-eGy_v`#uFj zcFCeoDjSPv zG}GM!a{=v-zqhy7l)MNM$!|2`pSK3$-_wcr!l+gHgOLUTsPpn*O~h-7sY9vZA!&c3 z=^V~_I~)aJNVPtkcL<>o8xg}1e_h^sxDwp5aGzXhb)E#WdJl$;&pW3=TF<@RwT}Dm z5RM;~UaiN-`FF8#yaBi|IunN*hhlTA*{zonM<+G?4d1jc%e675fODr?tr^%fqHhM( zH*?LRr6o|lhmL-_0vVd#T%^mok`^jilQs+0KPhBC1^vu2MCWjzf6LGqoQo5Y6XCS5 zfpyh!EmB_j0O>{KZ9N4KPbXPUA8cK!tugydzzb^l1Jk=km{fyjipuzoyfx}wRxChr zd$10xalw1xFIDh@nL?HWueG;!TBrv=7l1zPY{{0^e)S_zK@i@Eyg=JBeW@%oh9se7 zncd}m0X(lOt88+oqU=NOu0eJsjt&1*fVvQ~*Wb4W`_1r|=i7qZYGe%P{E<-5Op;k<(u1PQFRYO$&-0eQ+9yq^ytFgkes zdS|x`izbhb__tmRR$aY9Q@XVWw{`t-hc^25W<>B=;~h8`)GK{UQ>!i`}S zaP96_gQN0i-;zkZ6mQw`B4r;L8<)e%qK4y27a)FOdme|D!lhRYW?<|{6SGN$KH%MR@H=8i}?EURn17FhRb`v#; z-x=NF6^G*Np_V8`u{~nk+9HDo&!mnVf$_rQzur!nZs(w&f(uU3KEE#WI3Is{c{sp$ z)=c1Nj8#OI!E^89ONI~spD<5NPzm-stMU(v ztd9T8bHk`Qh?rM}w!+l2s#$EnYKJG~M%3fz^xL)DU95-B+9M74NJf36nylFA?^pUC zQL0OUQKduVX~8z;L$`NabP2LRP>MD$d^08T^-_Gwpu)ii5Z@TlDF6aBed;ii+*wU*ltc~Yc?TW(>smsjyeCn?h(%7+-&xazw61;`X z^IatrUz^B(D%|DC7E7E;6BRJ0P-{5`5#PX80mhW}Q0zmVDfxqy=E^RJM@}c&4bSub z+18^@se1^`aj9+r=Kl5tCBKnd$FlR{6+L^`qD}R;B`>UhtY=A~*-*X5eA(M@0$dgA z3}HRpDQyoKeIq|OtVS%|mN*=C4ML%(NJ6@B|8u;ac2ONGb2-YYhNdBJW;7?`!IS26 zRV~v_)oto6k%d39JTji*J=aplG-*NAK|6o&YX*VaKq=HKeo7}p8DkG5| zjA3DO?~qn-bhlb1)w6{3Em)0aQ}}5qFqd%3j{_$yMJ{uQu)n%ww*;9Fd8Q~Gw-6~Q zUzG^-zJxq`JmKKU_lk(H=@$l}-_v#^nvPXxo?mofI+N&*15Ts!O~GRF>HA4C*3JmA zUR5?f0iI|kkN6U`f_J7ZZ(BbYW}p4X9kLhtj+QSXJwZ-wyPs=bG89@eg2sXHx1Qc# zE*=qz^91)6uHLXQY9fZI==LWX$O9V?1zaT=K_~CRo=X^HT_o;`Dgk+xz-R%Vmmhq` z>NJ7P5pek{QGbr@JZ*bb6bxA5r7hkPsScIMK50gv8}uL@u~`U))HA`7x*hS|T4|v= zP@yXjY6OsZU9U{u$cAz%h({mf7Lj=Hr8zYQ&v;!Hi&0@x@s!7+J$)0s}_{%3(wLTxBndMZnC@H2PDEO9kOI8aKeNX05aodUeaO-ryN+;KCGLA z?8>pVC!iu$l78YoT#uu)bL*<$i0An-{Ko}=uDt+7Y~I1vwwZFKJKn<;8CP>@dH87^ zEcZ3^Jj~X3i9`CXGvhIMBzK1xn10jeyrz>mI2bWIl6?RRs&G_O@a(4_5OnC*ch+me z^U4>jPaAPQgqhW8_3f!wE-==gTTEEn|Ef08P8evZb^Hd!j}9_@nX9WqQJ}PhBsDOS zmgs?*sy)re^8CoJ?RbBi?3i(68BJ&)IHxvP$As4zfwumsayzF!M# zET>}=PxV?P=0{pyO`*gM6+&5)lyZ#kYIZN&s?7zMQt&zP*l##7?yywT6Omvp8*9N- z!>rsQm@(f{UTX&$lOC(R{Ybr#yxZSo6n*q~rnV+{N{`v6z=}^4p|H4*;JDjrcZM>#_e=I@RM;rSZpZ{)_*$Ktu|43bVGM}d$v*huzZG;9M4!Q}L z7fhCSQ9PRrsa6}##`{b+EgivbZqs>tDz=C`1%)~ZbqAa)8EI%}C~=+}(rDW^4*0IX z7XGQ_q#Gw%lY7`$Vt+0cT5uSG$b6B}B>i6%co#oY!ZMb3(%D{|~0;nfQRSPLDMMby@Y+7Ry4W~sK zFb27t(e0;%z6Q{Sr>?&Z99vB$7?+STRZK9ZMFzAA5QLbUIHO!KqSLGQ(uT+U0~`w% zr~u1OrIYgKi;%qT$&^IrV^bSi4Ub4kzc6A#^_Lr6&#+%f{*r2@M@8Sn%C(b?kmv&e`o$plCb|?s8sOysXe%$a}O(@ zqB-;$kc^o0i6HNAqfjo184jVG7Ilg#4j*;o{e%VXx<=+{)EEtSm+}j=u%Q8A%s72N zCFH0f=V(cp1e_1Q3IHBGk5>#6wbm|aW_$nj-sy?K(|34f1tqkw#-~Socv$ED zcOqMILWp13$cZEXWpt==gWT~CzjUXbnnK=bs(_w#t7d$UKlx~okmXduho^_sL-qae z$S%DThNQ4&PQ(5VeGg$Vm9HQF;L+n}H{TV^a+96q7}F=OYN)X6zLpVP9&l3iYA%zU zoWj{;hPmvJ0Ql}oZ)jVeKS;3uqv&TY^3;1%@Lk3OT0%`|&o6jx+$gqnpdogWWzUcI3fjB+TW^FBAJIEEsetZvM z8wnqSx3rAJ-m6R-?Kbvwa|ez=IYtu~!>v@r&gwVv-=KsB1= zNv0f+%fE_Oj@1nn++sI{2>dUq4&aJ|sl z3!~NIxPp=|B4DA{Lxf)X%K7lXwK47o%b4@oU?RcGa+Xe=TttQfv|biQ~hq> zFh_an`UpZMS#Z+WgF!qe!xW`S=o-r}i*L}9<0AW&Q_y$RbDNLA4Q=@MOd(@$6ILg< zQgS>05Xv@i?gZDJDEd(gJPqRa@;#7vrqHi<_|n=djJCPbLu%{EqQmf(d{~_1MF-Zi zLU?+=667dCpZK1K#yx>G=hs_hO@1c+AC`S|3r>LRVvTMh7UY-oD}5iP;iPf=$X{8u z9<7X+J{wn+i)ktQgtV`j=So#1+`}SCzZ7Q|6hoHX>#wrqZ21;zk1BGsbgnP^jKSL9 zk{j^`IGPh04~_~u6uHQ^X<-YuLw8uL{(fdZb+gbWruMVKU#oi~SnAtMe(yikq#uIg z(V9I@K(ZlO+`7EKYdNUuh{V>oRyefbicq*g$HHnV398D!oZE}o8l=D4pT8#}Am?5k z{s4R?XA2y2MxlfMtClf{%1B*8PC=feHR!oJ?j?9c^s76A3Suv?6tHFHwkA9;$2y65 z9Saf;q~u`!WG#XpMmsS3BreT6{*5fBuh`Xr_wzBhqE+9U4WTqMZE%ARJqHV9`B11L zg+S;tCcQ_qdEkDek-yC+o*epVDmPf;>gp0QTm zF{laY!pGa@9b32Ts?YBGNeh~5*=_YLO@E0q;p(L!Ak-)3EQ~kSDOd>hy**4kS=1hbyRU<)%!c9 z%WOZML(bn9$@w70d@p^e)P`0>@DnG%IRbCm`R=+Glj1@^yzuX512jL-iZD?<>s*M1 zVw9y8y5ha>1OJ71kwGCfx`lHW61SR|Ypi7#yw{s~o6-jq_^E3%tqXOf2{vS>zFgx) zrAz4r{8gXO8GhfL_`Wxtn9JYXg(-BAB}L_K^axAnS4v}-<&&g9;GdUbxtaOxLy7cN zH0;NGI`1)I?~q?_-jeR@RDKRW)OpVY&h-;{6T|tigLCtx-;GIy+y+FV(O{{`SR<6k z@o}rzAnzZgxJ&CQY#WZetoi`6YO}$}H?#cs7F%9_eCMAesouv=xy!1dW0f)=we?!= zW<;tN4){-dR7~OpkKQ1`|10|hN z2a@(h4UDxux^8XMOU;D5oXoHhJ>$xvRq=W3p#VHym)yuMpWS@Y<6`de9jYl48H|PW z=rcb~N^OzfxPzd>Xv1@P?@n62k!lY|D)!Xh!3w@OqYUL45U&%P*=J0F`ozcUfMhMj zZ4lz}CfkWP_^+C=D#m)9{FxzGguJm8zNg%&SUBd*D^5Vc{y1mIL0&|UI~u~{wUlTM zy$HSIw$CX#^QG3GIKsqLEuE<8F6smXqUtA`|4?$AW4oB+&9wwXA<1ew`#lUenemLp z@Xq9D_cH((Iqx0T#O+s@MW!V0XwT>EH1H0_P4VUFD|`>2ceiVdo%O8Xkft#OW4l#p z{7zEXEgq1}#D5}Kn(mC$(6u!C1qiz$Q9r|Yo*l(#3;OZ-3+bbOurMyG&JC-$e!lfc zqB_Q@ambWvrzDEQR{KS)NaFW_qc-q;AQt}cjsyGJ+M(;{1D)!_Bc1oX8gyX(*H(r$ z`hE)l*v^04JTx3oO7d#dS2CG<+N*8Df5}5*lwRYJgp)uYh|Og(479d~=TmjRwm(Vc zu8st~d-t-ub*1eX-sepUp(e5cE$WeEX45fjW_Y{*7h`W7)n*i~`J$zGaVYK%#T`m< zcemm$!JQV@P@oVTin|5Z;_mM5?hZFSGqdK*y64V4`RiK=i@g)V{`ULq-}AhUcg~@F z=vpQrdtwRI#CnR?fgMT z$HVh}{yROS-9^U43O{UFBIunHHQjEnP;i!}_^n``6<@m3P=_yK8h(-Rr=GeTV{Vq4 zYHhI_TFv~*>J}Vaz>|vDGJw3(7iXmcVa~AW4z!%3oc&9;pqpr$);5>j(FU0q0R&S& zl7M>ZbwQCp(OEl`%9NoOo_=uo78$O`y@ZMq2iS-*b7?lMiI8Tppo;ATwO_pLt{jkc zi#Xnn*JW!^`W>h@403!E)m-?vq&~B~@XoOvFrKHI@yT~|vB%*#L+0GR3p{;ad#?_K z;1l2t5~;COrCmVwdotGazbBdA67wp#7xL(}!;)qH7xESQTgrnbQGdT?=KNk5+2222 zS?C9H%(`LMmQ0Y9&LXUjH*R0{$L2P{G#nAM>~u6DZY72=J(X?rYTJD_XJ6at$3^Rx z8&$Xuu5fpmeI+7&Y}pcY{sngN3FF4KnuUOH!g)_CB@9QyB&ou&y%>Ze6-mCqzTG%+ z;(|pa35un0d|!dlR6GUNRe7jSvn3Tvh0A@Q zy*v4C6d&=+0@m|gp5j6^O3a2`B0vb$oH=a-$x?!A|mxW$2iX5q&N%hiEY_X^`w*` zOYYOF!V^zvbOTGm4kyA|VtMj7;M!hw8||CYz&1Epq+VEx7Cl?-KJMl8?jr|obfI~B z0`}l@R+^w&;OlPA?%vdWUC>UcataIpo}p8sa+ zaJ*j4eZVzI;aDjfjSO_tXu#wdfG;Fan>#I5$xd6xmb?ExDxgrgDLn{CZeC+TA*M=V@k!wH%+F!~TESZIkUoYBx`lbsNOPjw z#NUN2Q{bXV`|RvLZKpBcYEk7M(FI|;{^D4sGip_|rriE}h3?ksb#Jv3huBhGeMX@S z@=HS{52cQI&e19kc;)mwtNsmB4pECV0i}GE4O5}@{r|(Hssh9LUtIl*!)l0hp*1k43k^(x3ZoSITkQwf3Z*}nt^|S; zsbYd`HLC&RGJ?x!xi03XzO>3RYgoNUqt7x7(;=ev!>c_QCov4morAOBYd^)z`Aic}kuYBqaw~N<+-6Cv9 z5qMt5+aW{)O@p+@3v<_^m1i%G4}>q?e+?gm{<|vEd`ANK1(}@Z6x*ksh^%;qSl*15 z;|}WmB%!Ve$yS-jbc|GNw{^WzQY74)0v?Kfd zG_$piYA@a!k2%*h_y4VDJ)WZv@yu*5R?<*j#}{8O1U=v+7LOSBljlz#^Ae%STF-Jh zkXiC{NZq%KVD76=ES#RCPb8deyLcWX!222ucP7z~U)nVwOq3h-%5fnbr-nq|phTCi zoA2g54-9`T+Q3$(?x56y6vyOe0jFf;YcEL+-Q!gory%?ZoU%0Gye8yd1ieMi2<+WH zbfhmU1oy;77gt3UD6Z>Wq_G-bX%S!UJS{Wz4KqN(8FFemy}@{-g)a5z%LQ)TQa@Mh zw+|O>DRkP_O!tDFiP9cFR|-!c%iYKtR#*p{4A9*Un2SqD45m4@dtClG7z zrZOD+7rRBBtxHI7Bbt{!zdk%>b%5ac+LAf|%{CnLYZ>s2KR ze_4ayyLHBjV|)Kg$z$Q_J(H0Z)Jpqqt18pVL<3P5DauKn#ph`FSt?D)i{e{%6b{!~ zli;3PA{M`Yit-4r^>j`5eUNpuR_+uVq0vGt0%Wy59Fq_78SR>Km^R3DOZ9noU4h)28c}&ACqRW$!7$ z!p?=$KnAg&;Z}S827P#40~LApo8Nm5b|cqZSD2suK2)j$9ckjRrKb0`$R~69`TwCR z?tP?JHS6Awm5KV~SdE|2qg!6`n~gqjOzXpIA|(X@JGe#SD{G=rbkYjN(6A1>I*jYb z^!LJWx%H-a=90XZ$DG8KV6qBOz-&d9X9Hd+h?I=jh ztU`qn!NK_4tU4lhmPi*jUN?hSfoSEPj(0^S;gDX&SOr-I7DiC)c-zjI8QxvJ<~L zcFVA(BqzOFR_T`jh6ma>Y(8+(zdF+Jao~FCI%CH`o*LpiWo4uWTKZR&Esvg&5``Zl z4To+rmuE-{3VuIP?vzQ>E}e^{n=rGb6%Xb zmfyvgG{(jn)LW0#@st#c0YWsQB%1U_eDdFdR(i6@4u*%f<5EHv#Irs1TyuUL3=7jl zP5rZDfVbcgJ%*+u#2~}08R|h9OFhDGo8^tZ+ z4MvuyR!E-uo2H`S)iQmK#}%fC5l{7l2t!m&WX1gKvM$>Y3(y{Ck9QXC(f+H>Bx86^ za_{gFtwZ07yC)C7;3sF7-y$$FP?`vY$v}e-jPHbs#)P zRX^F*?3(_B(9Z*{~$U8n`+EyA$$?2PH_7GgwTPsVddEBHa$+ zVa5dX-n>VY@VUhD_m{hIyjv!kY$XNI)uhIgfy7?VNWF`i47O%7jRA`#Hvu$5HpU})byE8+zG zs=kvecvVX_JS7rwMQJ&>IOk5;J?5@@l@|1&WuWo6`nDf#ynEG#?F$x6 z3nzEzhfCGLCSpTQX%NPn$(8rnc5%0)fADw09zKvLgMFbr~2m7~ooe+VkNfk9`?d~sA{LX0>xBYF=+>&rQIo2}Q3 zu8}j-gI8918=>t;@B0HcaU2#z)kFQO>V|+}HSy;R8qoimDpv{h`%#PigBBJff5?l{ z^6s58h3|O^5S}qIjldU2Bdy5Y6vBL2dbp52M2?JrWjKa>|Kp=~M_cgpqevK~aFXXG z#e_}ML-bhI*MN|j1y5&)&MTdrL!VlD$H#v;lek6Oq}Up}({cs8sBvW${6Yrk?nC z!Btb4iP`I6^9$3#g{{CZhfeP*Qj6|Bao0chlUyqVz4Z}1$6DF$4f~Ha1}2%9;5Xw} zcR~ss@mQpO2#xsi{6)YJz8?U@PKCO%fzXIn;yAG3sgk;(kz3P0B>#ASN}SnISKnBv zI7G3>3{Gni*$ou4668-Mf*u^%xSENNgyEen00bi=F~}gwP$vOM_`sP;Pf{D_doo`i zzn84=q^!Ds;!22i2@%ZmoXD0zMfs8XNh(LS+SOkr9u3_4@!-OGH4W`2WY(thYhCWg zqnu}JDNt>nL|RxAzv*5K2wd|fYedIHl&#u{96)6xy02&@Aazi&9m=VCP^*9v!zSTL^y=Go;t76MW?7TRR9G z6oESL^0x5%*d4Gwe%Z*$j&)!2T^*;sZ90gA^dxVgn-?1CQE1F)XgNU(>3w_ljQ-+1 ziZZv>#lBONAIl;E2Bsu+J{W0wnEEHie^=Z5q`{^FKH@^rQLwlYCQt+LUhO2yBas!A zAOVBq3GS$-xtHjsFEtEFm9eh-VhP>`y@>{JFijbgM`(Wg5;!ZcpV&c?iC9PZezXt4 zM*9@gCOT7iS@v+c!-k0DedkV7hEln9lVEc-#J6GLYl1;KKytG}`sr5)9xFt|5`KzL zk(>MSddoGEA(E76YgkxO{P7WLVSw3nKp$U=l~rHmYE5lMj^AJAA;J>DZ)8ZGG*yTz z(^x@p@qYEX6)(j*F-Jam^pSf*8DsWm>iWR#)3ECw!wv-o*>-siX7&+o>DOz7w{QVqZmG!nzLCah(?S#Jd4Qqi zX(&&T!JWUb_GC&!yds9jTyVq4e&=UO-ua!(m%mwzrZ;H0uP#Q{W6f7652xs8t@;Ti zb6;N))lIg+KVL#iXfQ!!o*G~iP5r75jg-fx;aY#>+g-*YV`&vGX(w!YSSLu^C^Hw} za2R%0fAMJZn4n&W7T(iNAVryOBiBkHAOa%j-hMtD-$)EM8hf|9{oWu}w`+3$Ds3PH z8qh|-XTUTZ#W5|HoN>|ob&@!eT%Bd7jtNrOk2OX60_UP6B!caO1ZdJY6miEr2A-H6 zy&BTpO~0@?3N^9R73s}F#fx<{)!dNqB>}ek*c?WX1-W;uNy^?x;okXyE*DlTIgL}k z1B@ug>mdJf2Ann`9aVx4VupDo+t^aTr9 zTXpU*|MadvahzV|j3+mJA^#1P`^Vu=y1y-iz2f!jCaz;wv^YW%lU=~8*U-L-5}x8`TL z9P^Pn*N@bmoMJHV??jKq%*;NW{o^_rViH4=1E}Xe87G4``zI+^iF+S89>tpQoKy1x% zh?OKpRd4gOMc$phuDp*)w2jd*y_K<+A+}nXC#3p;Kpp6-51{6n7;F8`zR>(qzK-o} z-kS7XsSK+LCKyV|BW~Ltj}y*Gq(bXS(>iT-lt5VpE25(Aa#0SO>X>|$eJz~e;3D%A zWeTgMzwjut)`sns!T*Z|SQ?1h(HLIveq#is2WZ#R;ADj=eB@BBjTZPh%p+8ZPXw2P zze<&@|D%!MDiCo+FMz@ez@38mDr*m5_$0rPrv~SWIbj-_?z96xsLsI`;n-WE%19w! zrWl!xpT9?_*Gq#Ikuq&Gv^%UJf41d#i;I^_k)*gTV-h!+jt46mjk*qcb;szBP|8n4 z?9?_|Teigm5P@R#lHsDKzP|`p3n&iF039It!krxIpBvh=mS)jDwFTl+uEi7Ib;0;J z@0@q~L+r`tQn<42Y-UCDBEvz3UgwZD98~A_!$}6`Ym^r7D)RoSZ8|-!uf`;YF0P(hH;64o z=#A#I1oZ-#`qlhFVK4s-+4D%Z`3hlosvWHo*f*+Y#W?YL;R@mQ39YK5WZ#om)(gWK z(D+`}Na+(uiE<%Z+R_dXFCSMNI{IS8G>wGadvsE2U+X^ent6WuteQXxmHI!dp+xy~tgl*)Ehq?X=mR4um8) z^;VYsz69XD8W3stK;PDEkYNDwh~mm2T^`QYqZ6e*>-6rZC>d%K1(0tESgu+XZxfSc z6cAyzgzwnBNJ=WDlLv@P%FM(!vG0b|tM(l*Cgw&y{~5iUP>|E-InwI3wUzgYe0O`e)q_}oEN*h z{)_VQ7{EO<+?6deTioHDH~-wTV!mD4YP&WfzFT5Ez&tlPe0A-BDh zPHph|Q7EE2wAfb(wtD_7e6kS$=)f3UPZ(J?looM`KNacd&8|4L@_5f}ZPS+8j|jMa zMxMRy=$OO0dSKd%Egzp8gguz?qY7vd>WYTnw)XM|43;xv;rfq56^00|w_%|NI0uHF zkL-t$KZ5mpWzQ>duMYiEYCeu?XQ(b-*nJYE;=!qKak zUC13{=IW;}yPFUZ?39iIbf*8pSgC)88Jg4)TZtv;`4FpJ;4xWd^p8a((-j`G&HX#vaaB zmGznu;-LzGGbwU$xhhEc@WwY^pXqPpPz*i;w4UDf6ve?Zs4*=`ImCsePGen+o6UFqw^~kBZx0CLkVV z%Tx?~Lv37VRxbav%La$MHm2H$-QhQfCHgx%zOPdmB@F$15T?X(KfV__h6G@;BymH$%WG>0 zw!2R#Z-+Z>7I>2rjWYiQ9;rAvZoP7cZCX6{vl~EJz(%vwE}U_hIjpQFB-&4rP_|O! zd=5k8PUK8`EbGLpetM!6qZ&LkS&R;Nw?(kN-D_wi_78=3?CALcDSdCqN6&xxj(ITl zt_!;mS*WUEMdo}jxN_!D2H$ra+II_AIwUT@>1m2_3`itna z`Tal*f~hURf1tgwGk9R}_MpDW?%+3bp%&(J2;k--T4sGey2l?xU!F$hg+>4j_fJxhw80*;g#+bS<+c-a1O_z4tI69A-Zo;xlxhIdUJsAlT zxSCV97ZA?&nb%5byQH#=A!*DI=-KR%BMux}72RqV$3AxsR=*(Qu|SBT5g7{Fe*d#U zQJ>>cD4!^35b~kv4_V%eP$0K~q4{33cCvpls{d`d$^cd~Iy= z0gNx`2T)7kt9oI~Ja~f%$j58d>KtTEhJ37DCF(s=a;T+%w4BUHny2JA$y2?J%m4+W zCRF=Cuy%(9qXh7s%fUACoY!sFbEhx^BCx~?4IAaQcP1uf=x&u1QQ7N{lj{+cYMykW zE!>yW@RNi5CJCig+&t?J#j%EWVM1zirKD9wN!fo{s~j&hUc+5Z=6;+vDqq>^(9JJ= z+vz#h<~ePZg^E_-N5O=X{l1p~DL_Gt2*eD`&eSYj*|^bg^If&$ydw(wY>k1~ZH;iG$)q}5O#Qvy+7$peRw3u0CCd<`81xxtesrWEbwC+H(j(XTb+%kk` zV{SY77o{XsS7Bz)qsb5WDl*G8aj#9)Co75Jk(pI2ZAHfgKTP`U+Ff=19Ohj^xe>cY zSF@Zu$vH`g6@Wj?ESzSslXc#!{991tm~x~-OjWR5-~5t^D+9NArH~ZLbfCCG59-3I zOv!53!8d4Q$8a|l4!klbgxo~kz)S{o!EcPD#Jn1&8)BnhD9jvm`zvf;=womQRYar_ zY(8Hi_GUEwi#A>%ip=bw-xmPj+}2Rb_f}G_rt)3x$D_VH{t=k8Ty64rL8fYbqhZ`v zr0|ntX>`l+5kRNw!8sJmGFxk|@#Wt%ZO;Tp<{Jr**BIemKR!talDO_V%SD>7o2o(q zvP-;f>FjzNs4ls@{nqTHoNET@?_7{9!1R@NTp|n99Ta?gS|7vQh|GqnXjAGZB~yTv zS5H4ulX?6{E|liBzh0Tsd6|f}-CX0${uG1iOD#{l&G$-kP| zuMK}o1ERl7y~#_yLO>5ZQpWg=Y*A!b$p(3ca5w*3U$AH3ife@HEKS9+2mNtXyNRCO z_z5aSn}KsbkCcM%aTs3KQ-e9U`s$L-+ud~@Ksh-TtoVMcu>X;mtwVnM9L33TJq>6W z;wUexOLS=7ay8Vz$m{9J0y})Hl8~E>ml&;IzH;27U5as=jzi@`&0%puOPJVWKK;0z z42#maqBdTs-0zJcG)Knh4S&)yUn5-iG4}g#FU{98WB;rMctWHk8!kk)4=N3cpS(|q zQm^5W74d4WH+jc8bDP4qWUt99zmx?SJ=K+nciMmdPs|i;w*xo`Qrc^B{n+{CRKe6H z1vFo21Vj^F!^EO`r6QE#u{lh^W2gu~38A6AT;T*{j(MClS?BG-O=gS2-|+H2EZ>*O zYm(cNa#&P!h6c*5hR%HXt*oR~7Di}D;*Cv21Tj=`LaP&UGjmICb4zH|v&AqjEL6F2 z5j@TlNhN__im*^qCG@BKxn#+m2~<>6uJ+O#4O_EmhLqZT#SwDwSE#am2`=xvzFOq( zzVqGb9qyETq}!Tth)j20FduKZ566JZXt+s9peP9s=iNEj*)xG*Z_K^iyj>=WVDJZ>rn_a!mXZ%B?$_@Qa{U z)=0(l)?sM^$0$0a9DIhs3u;RU7ybOFa!1%G11cvOa!_UW!!sEhIw&}1iH^HpCS_?- z0UMjmGgNlF{$93a2|7pXlWC7$O*adLC8fEiSKAK?{{K`n6aNq4fZ*z=IC-Ua{fL=G zQi3U?Jwd$g;J)_sU4F@He|~&}LReGevZ`_5by}^*-?#au>ga07?Fy5WCzp;aQqA6r znjhTbJp@LE0Ne3eB?NFIQ@hXDD!t@kBG%L_kT4I-@$4(i10BOq=0W-=c!;qE=KYAL zmnBTtkv4Ph(;?TUhtA!-$CW%KD_fWlqY6PoS!x6E`<&ik_5nfR)^JePOHVQh1{}Y6 z0)AR3{Q%Cb{91g9$!RBLM%yI4#b@_p@oYt!mVOC7-v{O@bt6H@qi}_hPI|K6-uBHC zc`x~L+5F?*zX^h62GuW6kN<{~zL}}|pksd}W&drYIkvN#d0V^@FJ@xL&OOf_JnPus z=Jq;yICOO|v)Fq1RcMHgcCk?~z6f^lA#6?TSd;5Q6>7h}_4-9=!2V3-bM7+dxT}ZEmMN`NW9rWah)r9IGk1)5*dkA0edy+!HM>{nDGiC z+Vh3WM1d~cO+lE)hYU*vQ&o;BmtAe@*BnmV!kI1=Z@i0RHpZ`?8|b~ikz_$!g13D9 zUQij$u{(|pQpwfd1(^*T-Bvj(@F3A13iQmCD>2`87y8RT`nYpVUHG||`$aJ5eky_> zMG{6TdWI|8(zv zaTIrxZ6j^fTT}a2_v#eSj=VToxh_0LjS`S!o6Gy!Ze)w_&panFX< z!hgjTYTgW=qG?ntpT+w_2XoI#kPZO@xI!)*7)hxa$FcQc_ON3k^nd*5YDm(N%D-|; zEEi56(AVU=JCvq_{x7*o^?zC2BqbzPd;TL^|F{4DtkS@>AqckrZb=NX$Cfw^sn_0& z_EtXsGoXqZvLycts)EFF{qL*n8NYt7{cSSqaam2rH6_`m3c;o3Xzu1m*8dY)a@_L@ z=P9w{`Z?+nVEPEeg1aFZ?yf^}9BYC!57TW)gyoxkGfKf3z#-ZF1~*8KOsyTlC(;!frJ|MeuQdS{_&vo$9Qwv zir=ORyE|pHjUD%7hRHQawxcHyCmtX!hj@R{=-~KR&PkkAc->EkI6A{13a^Is76k$K zZS?M&s?rS9dA8^cf&(W6dN*C#TnKcbNBJA__L7?!BMC@MoXCr?TrgjUhBXb1(Pe0og zhRAC5St;JlaWB>lOFOG8YdWo3lft#@n+))2sM&$jjHD=X6^qgPWw z($SN9!Nam8uv^~7=9>yO3Qnf6xg=Hh(1D68%Zi8)0kktnL`J7AGrJ!Y4=eq`Yh;@tx*})(3soZnhf+1Cl3WtXC!i5Uy z(hPEL>nt)}0tRi?r&P3uUm6kcxWcn$b4p%;Xk0K(b-bH6E5C$I_gr|NhvHdH_Om88 z@p0hgAbl{Cq+CE>IKRf`Tw82(5q*`8AQEdR*i^sq=r`fqJi(HGC82yY_VI?M-5_&# z^nBtf`%%~%ZM(SF3f`OosmG3+NN+R1dGi``@^5Oe1hR~eo1B}MCdJ>u8ZaY8=5*Js zJMKVz|1WFE>(nJh7UP${Nx_dT-`SfsjOv&jE5~5So-cg+ZmgxNKv)*@P&Tfff%L}- z*P!I6;=+8>!$pd~iJCW0{b^z^KgcmqF8aR2P`1Kb0#ZwlZ zE8<{0bgI5YWX!_S_gm`3`zm!he+REB(Q>=)qSGjMs*kI1rCV%vbQ%HJlDb)8QR;He zP8}F9g&C#Tsk}=)w+wZQZB$#G&C#$mjm7ZYbkrsB3mt#DfWJce&Zk#J1RJfJ-dVGr zog*cyYiRj!*?|UV!j=HvBm}+rf}Bc5i(L3|_Bt;M66wuaWSd zE^|IIkbTU7kyZNi?VS1dgv>{Ba>Tr`5uNqeA20>-P@NlISz)AR7I(Tn8E$t==BI76 zRm>-dZ#-Ub)fqnQS5fbmo(D9-#2tZGEYb%n+Ue-&kp%1ERyn!3#TW#^rNhKMwYQRq zzTB0ovgBxJRAsxh1po^_m}g?;DmP+1WO%MBShj|gcU7~qDbV5bjk+c&168)7m<@b) zu^l|C8ol$dyj@jX?UALX1K;04y9<o?05jY+NDgA<&e*ue-&uo}U3WVKB6X#gf%k`t z+c*~Xyo$g<U=9PLJ2))ZSnkSvf>s{Fn0H+TJFa+dFr zgMyRSI{u^WH!Vmk&>9gyAWgF*&dX4GU1Lw^8M%5akcPkc!{!=DzBat?(S>`ZZFGm) zal6pte7imN4qE}Vcn`h^;LvW~{c?z=GxdQghwVei&ykKKu1p7kmI%jnE zznKpLh=s^9^4dzF1zXb<$joJ0xO8U3!aW42C~-l_pBs`;A;$%&7np9S`GaolHnW-f zJ=F=tL@x}uq#D~NHIHS22=V-B)ufKpQkT>gFN%s;GW!c%#xq}dc^|t8ed|x3yvwTx ztuTSq3GOC*Qcygs^sjIb5Un&r1oAo0R*9PBz9 znKZf2EuK6pIMcm8nzYwL%C1P`Y`^98FfU7%^7=;hO-;^pyRec&M5kN(SO%9=X*QWJB8U?~5A{l|A($9Z0d!A6O1BTV( zj^Jcl0HxZ`Zp;rOD#{c$M#% z2~CCGfaxFVVP@9I#XueCo}UFchbrklNwg6?-|0T{ON$D_E50jsny}#w&aqIn=qu-C zX9ttiZ$l-7qFNq(AWSqdG@c2%t+IOv?iVo#gKbg{RaK9+0x1nzqY=T-RdC{8V6RfJ z5}eUl9L+M>_7rS3Drc7@t@Jm~I5>x3R1PUdK7QL5ogn%gcojxyv+Md{cbqh7lHloj zF}y&<#xQk{E>)3Ba&lW<5NYIpu>gl}GcB%xfAM8ZdEmvI=-Y`m(@#n-Cq)eByI?9D zMl5mwu@&OJH*B<;il#N@BC>6kp11Xmo^Q*&^64pxB^G&-4QDfK-^OyZ2p;ynsjhxz zd+4A%#P*FOHS|kt>d$-081E3g*Q1Iqa!|MNW<6I}>8~juz3e`Jyg9;^mj1+~DATr+ z;pX(D{#o|>$DdDorvaSiA|$zZ!eaMR^VjQRs+o%7ey;QH+0 z*Vlt3WooZ6b$TUdi)@1udd-CSfX*9EzK zA%y@McA{~^VrRKRQ3`1_cn@bZ2+x80iN8jv%4@+htTvoY65;1<1Gs}|wyxv_2jwX<_F zqa~_7(Tdy7ykfG%^U?DU%w3ScVgka(UyGLd%;aiC(<43XiK&6B*0ea&K6dvLZNq>~ z3=#t2Uj-!Q5A|5=>DMZ-lCWP{`q2t=jHyaw!~`{}>{G`qOQ$mQms^Qkz`{M6+~3zP zQKxyV)z21!$b|$pEcJ$K9q&zeB&S;(VWX|gsHo%q{A4TP85b4`_c=QhH4SK+Wlce5 zj;iMNSlbkPD%rJTZoE+G#7(Lcjxqw{iXTf&zvR*{cPlhZ{wYT<*{QMlS%1 z+%tovgY!67(&MRGCe}{#C{$B+YwqX%Yt>+?9>HkxC zh(#c6<;k3>tADW{8^dKi^%qs5Cgs}6RM$29&vNoG_$=CO$wjLO+D;FDx(qY18}{SD z3qk*He!(YMk*=7}^dhm@D%t3wo&Jq2k1EfXkBViYsn&d3@Ml*VRp;-4nHs*A=x9C5 zrI_erd`i<8xd#||-AG5lmgdB9ANx~u zGhiKQWneH4eO4HW$qwx6)0<-r91XB(A*P3iZL~*Prt95o)iS(khW|~eBb+)6As5XERDHSQbg_&c zznfQZF~UtoxK;n-V^FpH+a`}@U!~b*!}%A_4XG2vvr(b)@*jl6QYeLQ)e$IuCYZ=t zOdH_-Q1(M{%FtM=u;bA=qeAr|wDd@kSCNdt14C3qz#uI%HL^>QfUbp#ktX6%??y#? zQDlfkwZTUf)S2*82|ui&&NhOT-ooI}Zv$>o*?`8l=^=jIi}tdwLTivBCw0Z8HrL zAc>waEaqTNIWm;`lMDxy=YIUMpOBduMPI}{N+~qpLg5cd!s={&aP<5G8Oz7UtT0Oq zwM6CzIU%(P*?QmTR_{V+aH=!k{sm3R=%+qr!>+W^)gk*r)iQ-TVE* zV>>JA|`VDsmg2KKTKw(V3Tm11^h z9C*sg1jPV^`TR_txX6lk1&D?y!q4Bp`@S{nL;UZNaiz8u&LJ%PCVBKHH#b*pb8>k! z0D=0$SYu-&VNoa$2vqEqa^!g@{*BMesOwz?d17odC&!_*aZ$fkPeROSduHR> zE>$2FM*xVia*q08j`hurMSf9oCAIv7wP^J9o{MpF3LY|LOF)Uj+!Y6JjV)nVO~tM{ zMhuoqsB-^&SStG1MiG`}oe^mhPK*nacQIodf>1AlTzp0=t}NXMe`n_CGoMRo>QJ1V z?v%Sb$uRSC3&?oicgVl~M5gH_^wTo`+WB(AGwHjC|3W|;s}gI_G4*nL467u{es6=Y zcUY{9c2w{KJBl$J91!sv&<#7G?5YsEaBOWOX(j5fFm+aO;b1Y z=u>gWUxzwM-t(_x|7={K3+na<746R(0@~6tusUK2EMGsZ7_1;#Po&L*sEqd3ogE0@ z371l(jkNUrN~iZA-xa`H-%;hYRysa_--)+ED$2CrwaB{l`2^g0J&JF_#3Osw@gJJv zP(4IbJS`c^_@^mO6-++%=a|!84g0`auiXf@uYuk{4KtXvEI z&wfu=>lt`mrRf%HrUnFWQ6WD45-MLb z{UaY-S z4gtsuHTZq?fxH%Y)jw<3OGy^kOuS~M;13aLTH_ji+>)YZ8zfj!1o}F0q&Zzi?TjJ3 z50})+(FoVM&M9~YD!K&%8k#rM>Ih&Z-^HhlUR&@_?7YfZXe2t9c1v>(C%dRoP`R^< z+EH|sp*|AGNn!a|8kE3!n{cH7ZcAmS4acuX?@r_be*~#9uI;W_Bwp6*I-%S4>K(II z=DE9mh~=&n4F@69Bp?fKq8{Fjpxha<+0yH*Pjr`L(=nXgkL4cl+Y!wvZ4gbrI~JbJY59QXS>X%~Fu74W`VmFr0+mgpDQi zt5ZbOS`I3CeA(yJpN+cumr-_|evYi0J-ve%mcA{Vi%zq`x}FcThNp|aWJz$D)@H*q zeru0KwG3aRV4iM~`MgqP9?VAa8w)q4Dl|T67W5{=+5O&S%+6=oe+_E^NV(Fju~>|p zL5sUR|6awpGPH}?(HXy-xqs|Yd;`YSRp|GR86Os6E#Th4y{8EVE{q8gJodhO3c6xt z0a=@i*5Wub(DyS7uLagG_Fg?)?qMCTSM`VoA$PrYK4+mb>bWMH9i*+TEwhniwt%Imu1 z_&=Cs6p@{3471@$2M4KB7b(=LWT|=YPmSU!IHG{KzeiluUBh%pk)HLh+L)*2vufgU zDYQW)$>L4Q=<8$w01s;l$J6?#?FWx3o*78vfg+Z*t$o0zk3+-Y0cw+$W#KQ8Q?rjg z+PD@G;oC*NQ%g+Q;c{R9$%aV>{B1knS96UGrNcEK%h6AYl3u+) z7@?j#GCG#2lhsudkesUoMo?5N+=EXz*9Eyw@_peu9j-{RF1X}D2V1mSHb~`|T50IQ z-qK89J2#*@KRi7O^ghFhCxih0f2e!Q;5foAJ6N_X$&v*YGcz+YGcz+wBWAM2%xJ;b zVrE8*S+ba!nWYhD{BGXOw_lRYR+368{i~~Irk?JZr|#T)?z!g_eS-Fi5Lf^7^(LE8 zMkS;3EO;{6Dor-0zy!tP9Xx92matEV_ff1QXtJZd*G? z;e5ZM<;32U7#H{Q_ySZwob@^9SQ`n~qIh1shM1}TE|o@IN{39P zsH&ylPD#Ecl{@zA=WCqw8{8XHsO$PK>&O zr{POZ-xv+w6N5Nt>DQNrY9M{Moi}-*KT(@iy#*eb&(BPxUgd$#!x0)rUVWPcvu{c6j5nFx773Oz7*w_htVL6hx6lcOU?5p%p3M z9~6a=GD#8W2567f$exvYy1bvFDHNHzoF7`cjiT_ zD}&3rJyS6=tcbH25-)SsL^gf2yUAGFH;j~K~w5+U_Es|Y#+Bq{_@;zq5 zKA5cCE*Y_7h^tCB1-)EaPqR!WaXcIN(%N8D=c?o$$Ev9)h$=~KlF#`66Z*3O>!{_M zaDGC@0UdD8{xd3^3k?=6)9M@!ZHwa^=ov4U z;p+P_2jfVUQ-3mr5oh90xX6&2x=wQsiF%}0fRRn`9==Ce=|K`NBUHy5&hl+>MoNC6 z`b=wd08hB4(RlN>ReABJdO|Tfb;!jetuEp-hn7L*JKOOjq_tSE`t&&NqGo!}gub;E zR`~gR+5iC@6$V}EsA1Ep{tVVK2^!L*P*0h}^h?7hxKFz;+%g>k%nn~p8dts!lWrBX zYN121J3`c{ush=IDb=L07zC!u_5280WJYnjn7J*}nPtIQ<#$Xlo39cK#D`>mf-kH9 z!Z9>p-3rOdeLmoVBZ>P#(vp0Yt{h2LYke^|fHy3%T zHCTxE;h8|d?kFOc%CiCZTNuX563GQbw|8@9VrG~fx6Iw_$I1P%kfP&Iw->HhtGqA~ z_mZ|n2FR>a(SKpDN~aa0c|r?aKCkm}= zi9#1s8R&FsbHv~8$cP7%CN2aJN z+|#7`y}^$j&{=G^hVWtN)UICVrqidR3*lMmBoOpJ8hRy4!H4Gl3PRge-Mqa(qr-4X zusai}9fcBygOia0v$Tw+tGDFVjPg{*XrsNW2~rV&m!P5(M~{r|7Q}w_;7eei5}2b~v$Lph|6q{mNy}C^WIIN>B6C8C?lJjsGI13TXbNp z_F{~k{YwxSV}(<&Utk@ZJ0@w0#-DSp2yO;_j!s~6S7rK?w!MNpG2Dqm_`2gpPq$f$ zQeL%WDO1E|_^4_8nT+f+Mp3@O^#l)>9}NOIQ?SsSkdPD+v?L965qq)T?VELxVnSiY zXSn;B2agT0k;aaxFN7ZG^)sjI>bLRz09qLirNE>4B6J3`+RYQMd~Mx7dvE@(_Qi>O zmNZ@2kdv{m;nc>14QAOSyyY;A0WFD;(k|F&#zL}jrv7?7DnC|j`_$eMe>Brb`SZ;b zU62yS)bGuJ9>XD{)mtj0g|P8?|DVR+C}N8Lx8iS=COj89euZ3Wmc9iq{Tf!$4J|i_ zgwvYzmbTp?UFdekkH>W&c3a_kWIlj{v|nQl-TC%upd$}}n>RUh)vIk~d`5pTVwZ?s z-s1ia6?!t-y6!dvLbW_bKq07Sh5JjXr)f zWmp)I`$d_SS=X1WU4q|Qt0=L#EYj$6+F;sV3U!ki0|gBBn^v?3-jkHh4`exyAs862 zsfz)M0f2}hjm)6ASR7WYyQ6Tlh6R;M3{R3mT5>W*8-l$vP0p^>m1`BS z7w_fc5j!z&Sz99vmA-juujN12!`BdIQ*8M`t6r`no0IL$Cf@-8HK)YxExMY>Lf&f|!x zNbmb`>R{RrXA&h9q?dlwlDxjLEAL)~dDd^Or z`6h)}>zYu4PE2};A|vli&A=@scFozvAg{Mp@D@L5)_rYgw!PW9z3<)@z2@Fs)u4L) z%1>+pcSe_INuN@{YM6xB4Hnw?t;eljGp0(?1aOYuR(w~qWNFnD716tvmL2ZFJC04& zo=sB^^k!}@V=OiKrEP~Pq6W!s;-kFr$;QzE+T)7a_?BX~Rs0Xvs?@;N+9_9jjAX?< zd?r&`)3WwxvX6c9)XO+I9RX)B$6QCX<$*Drz0_$`ofdfhE0~uVCimY#*N*7^_o8b% zGkPmG^ACjALUoROc$U%=N}ruIhcQy({Z+N^ZnOyO@WsDz18;BjO~0o!*;KEUAG( zec&)@tCHaC*yAi3%N0etyNk*4TzB0Vd#&w5hKZ~jc#GI;;dJ%1FOinC8^ga|5d6l? zB=x!vYiXbTt#=DW9`2un$@F%9BZoU51BmmJ^?!(<1C?Wbc+xqL7e{XK{U!V#Ld%+J zjs9C`*;pT~-hj)vWcAO*WOY*IxJiq*p=C7?m)6vY_S9V$>}vdjq~rlcQ4f^Duspf- zhCt+aq-GtL`tcjQWk?pO*So-dHe;tSN6zrOZe!W1BaJsdZR;E7ciii@!^72WwdUW} zHm|Ufr@)sE5xS0aCk4|1cJy2o^IaM^2?NUPH^fR=eg~5OFT!?PA;j~KWAA4lxEl6- ziJ29Zl$0#$$!p4dN0foja&mIwR6_WRr$xrC1KxP4m>o6hZ;k$5$OLooG@R;MtePT2 zI|oX@AR8EFL%jX{@114AW$E}sOS;?dD9txy(d0UrOnf~CJt^IEW8=APm*1a|K43_& zXg&F=e(WgwW8cFN*^(>=z9Gp29#!|vv5a2+H?YR_Vp>F7)gFf&ZyN?9(Ul#=Gv>>{ zeXY*p3B?1(Ktf+6)QZ$7&%m`f?$GQrCJ)a$7aZdI?>slYaBu&L^_C8C$L%407{tLl ztAz1-LiQMsjy4PJyQ?#a$~xU$Zf6HsLachWr&rp9c{? zOWoI8Of_KhV(BJ88Q>kJOz1ykYZ|Z_4jB(WA44c|LKUDluEF<_q$1`6PUxbe?eXJ6s1~zR*L}E5?!ml^=T^6`6D zY-DRGmClrW&kpI-(7cVg6!^Su&=c_ma-Qs>j;|hc8V)2sZujTBV20nzw)?SjlFc2Me`=%q>W?*hLMb;GJ5Zd~L$=VpA9Alh zA0kNjb)aUthda^JgE@fxf~@lE%RxIo+`xc@6XL&xKW=%w0pwYNyZX#KxCSW@m`b8S zj&3bM>5c1h841Jt4Z75Lu3(Mjd1sv&qrYS({P5-0*ou%qoZ0W`D`VA<*CZ}!opKvR zMTyZcTX(o9W{Uetje%*fZ_U;qnHKZdQZRccXS;H7a>?*BMI1!n3mjLHb3A>~MD2a^ z0BJ*3i6g^5NIHx3yFXrwRp`@Cdr#82X;S&UuF8FG+z-6*?>nL|+%Vs@6C#e$749xS z#sXdwJfQ7J{kkVF*54^Wu!c`G0FUPXU zC@5+z`^(taTW1PoaaYk}SaIi_{@r%oJMpdIkv|41>c!j(FmNi{@G^4-1wp$ zhU6pxDY{Ek2(~)toiNR(XcyBLwRRr;GxLvyOVAJ+QZZOhrSdiqR&*o=aNzQI7 z!5)t!%+wZ!l5CmnORo>6q&YcFKio3!6Memj&PAAEum*ra02*kGb8HVogN6VVH!2QNeCW<4$&c*+9{6V>}5!s zN_^G}dGrMRF9Oy2bo3qSr!W-LEi&{x{NS+}MLkmzrFDyW0Hc_iU@Jd!x>Z^k?Lea` zex~!MQy)-u0cB+F=A8dWuqtvk|JYXDgcvsO^MV7JDCFRk^)0-TG8!gM>{2wsugxK1 zh13LnyYSXb0ylkSJ6!CUdKLr|pz-xGo6Ktle*`rWe_t959%%KB!G-dcNUOyiBpc@Z zPcDGI>)#_Qqg0*YKI3mGrSTsurD#L`2aE{xFvzgaMgum~C5Asum>@nwJwo*xx|efD zT13St-+HzR-Z98qut-cV%6|y@0Qrp`7>MHP$`vWV6zpcS_}c=cHx0!eTu=71yfSJJ zyvH7Gas{5g!5WTRzD^QefpWQD1YA%zZry12VIJ*#-i33tU7;I}g$jK+6TRn8@}t0A zkJwn$?=y!Xacyu%U{(PwdWAVw;MxIw1M0`8Tz8(GcQE_o(6hZivVJjnqu1uOD6Pqtg*Qu2$sg^sQS|p@uoB;DxOD zQoFj@>f8rIAL5W@@@sWNksy7gAqwj=okaXQ*pAv|HyqWC-0F6s7`n+e?8ocuPgvav ze!)9XTWVJjl1k)(@Q$^PxLpohiW?jO><(%>Po7jh!*Ys)tJlm1ZM^VbL;%;wwZ3I2 zYV&%r{6VTA>@62D*sFraSgKDPW{ZrJk6v#)aLQ8x@s=`Q&Ea*wVikb#a_sCpz9}WHO{05( zF+QN}Ywg&3w6Nmd(40SQc$_j1D*nSlBPOvP_`2lb!0I1l|1Ula;*i)i!p=R zo^ok0e)PK&i?J(_He%k%|Ac<9aKr?nU<`%mHGRej!yV>o2M>4DUKP*f7^CiAYw+4; zILi(QRlJYw4{|!CXA=wiUW#C~R)L_b z0rlU@3NJ*0+2;=)msq`+8;MiOAM*>$j2=Gc?VsUCSfi+!>DihZyt2nqD|!?uH&Z71 zh0={j(Zn31m{9p-&l=wpdan`H&jy_?dj)@dhj#VzreQU-0xcvo?NGrWVv>B@EpYPO z5V+R|rMdDTwMhI+G!Q~g7}Ximy*6m+5r>C8o0zTZgxB^=WHcS))FlO{N4nvzK9j>qT!rgq?erQ2+u{{u-M&8mO`KIIVi$P=jH zl*?*6*4U4s3uT-dFKY>P@*?v-0eL+r?7VbW3~99cYQyq!<|4vO0%>bcAR&N1*x+x< zhw-}vxhNIbouI$MmFz}ebZwQD&Kk_qDKP8n2rZe-g?v!DD+3J{4FDT|pts5|s=q|= zHF4dq0hyWZ4MID)vd1M897A3i3^CgD`m2pZ2|V))Ow`eo}@R| zB8QATmUyr}`mFT7l$kb-wJhkR2HfIZ_}xP1b*^i(sb|(j9g*@VQ!e7y^&@mu|ETwM zCq6Q7Oob{ZTu9?UAcehm@3(XA=4~g|4^=d=U+y24+B&V8oGEnY>a4Vo!%!5l@i1CE z$b7>)OQqL=mgVN%$gFmkaIHdO+k%E3Uj;56*9Syvbf*T$QN zcxDhdSqL5?Qlz6`t@Ky7o_~1Pa=aaRT3WnRk&gxsLjcAW^<&G*>tbUw{yc-PY-x2ft)^~Az2#X^=G==9 z2CU^NIY#}2L9-&Uba2J-UlV@K@hAHl)jxPDs&l50Zk=SUb1WVI4oPvwhY~ z;|;ey8BfN}urp{&=@IsDVlt*LVn>*#tlpUVUR-gqs6$mOj33@I4xh=$$l`G{dJ7J3 z!=7Iax`>7E%@ECLJu^1rxa(;5Qhh#ITi)TpM5QH_uw0)8V%q<*PtX-;&%rc*DAL4Z-dtpc`Yz&Q zBCss~{aAeODdvhla|k?7#a&=eJm-X@j!?N9T_lqq?|(~$yC1uka|_{4M=0DN z>*@wuED~IW9j$&@$E9k?PpyAILoH>t)Xt6-=G!0lN^2?r4Ds>%LY8(XN^JXB=X%Z= zH!|t_`+-n>fAxa!3aH%S$>s=i108y-OAh$t3YV03vU}qut@eY*hA8M zRg-QVd?Jbh({Vbe+u#(3EYIk2zfsL2UVAxzxAUv0#8U3Rcq1g&#d8MjXqZ4Vv->FC zFR@F%wFhYlMJp?gT+7LeiJfxjVmps+XZbG7&=|!ZPm)Xh+8ti~0G5xE`O{IiS1&5o zN6eAALo+f>=5w<$y{w9i#(DJ8FHKD|!Qehl!ELE9k|3&UE}}`O%q&xp#u-_m_GrHN zyHjz!tCucvn}mLSjr@@$H~Y=t999L&)ZWWHNghvfP*%5$q_}(fV#U-1HK84ppfdi= z=!|&7ELDBbSNmRzTv@qq+AO(za$c-n^;(=V>YH+|;W7~ib#lX`WW)z`-!}P#JPza< z{DcVnRdMC9>EoT=ZBSGNgVGQCQ=i?l6}eoa#88J*w6?4yuZPF*K;cqBA8BmzO)h3_ zo)((GV@m!`J{k_N@ezkcIZ~>pI)Y7X#Mq0oykhLp;K%=bBKhtlRkbM}` znyFRZVZQ%38sGryr-nxEj!E&QOO9)2e%dK7Sm~?e{k# z$u67Co!KF*dFg8)BSH@g+2?OVvHPlGxhC2$G!O4@D*$s{X>q06op*%_Z+j3(;$>&h z1RygetEaUYv^o>hhsmz$_ZJ+0{frQ-(y6*h z`{V{VvyF}j`$zC9Gfcqdy{RYLbP^)2zU zyO3818c)YaZw9{yw`$esRA}joVAm31`i#IT9L+Rv2G)_b-fQltjAj6FTu3TilP^{9Dr-!GKRswOZ}Jf^Y*QGcGrkI3 zC-T3e!pR)f&B2Z;DDEQu5t@}VJR>SV{MJrL5A;nlrf-*iImTYs_MYc{ELbA?^H+T! z1sXCZS9h13mlU1#&IV@_6!I=h45iujupe0R1x{w<)@9QXq8P+Z*!RahO#!CFa}8Pf z^j2x9QMqLP;)BlHhK`0EaPVOR&vMur!SrtZwrxCO7xv6VCGNT?(;zfE<^pj)Wa*iC z_ON#m(_6K|h}t10YXs1|nHcb<(Ka?!SvkSOqZt=yqoiDIOnaq|AqF3elr<4}fU7tE zjdmWQ^fs`?*=Iv-6M93ppIcL?%yfS=Bm2*sDq9LXOIQ2OT=k_(|U z!!Cu_E8Lf-i*Z=M?J&Vax5(3Kg7%j^8AP&ibEV)9^!$ITKPfOQ5#lJo4tdcg!D2i` z5ZlKutDooSzoJN|;OswU#9069Lu|5PdK(Xta`bGuChFdX1>{)exs zgV}<%daW-i_L~~O0rnUosH_Quyp0Ges#Cr$@TtMD*7;rP@OUA-_YXX=L8Gi zGwSq>A4VoTYe0vs)RxR^#Xr1Udi+PgTU6z?WXs?O9?iiNm!^OWm-%Tk3qwJ$CtP0G zCrLFF!!7|9(vzM+YC{=J4{;&nG{mIc;9drw^-g&?qT)^#Bll1=`8LCrfus0d!UmMO ze#su&*`!c6nuxa2&!LW9zS;)hnrnZgp|S2-U(tivCsgLH6`{buoROI-{CGvtq9Cn- z$gze_Oqp&QABW;YWhoVrjgnzT!s*xH7iEIaYEa_n4GbnbDYffI=RP4O18>0Gm0EjO zKW4BdgSZIvc+wb)y{Z^sRaM-!mMF5JAe#4Z_xKk$b>!1)kfKO?r`6f1AFXV1K#dBd z+J`7vtIcx-=<2?xeUkOba8*G?4kPnh)>uXR)K9nm3mIh_pSU*_jY}CEXhHVKdkQO3JmaGUfcMThkdTogyi)yAYG4>dM3(yz~p{wTPW)F-FEBlFW~W zBb$!>Pb!^g-frJrDe`>S!P3RR`eeGXU*}dC;;-KSPLWI~gXNHTf+4))NQxciQMV(+ zLC~TDX+@cxE{~ z-Ci>Pq)b8ol;|U(c6r?0Ot^l~jiFwXZ%+<5l5w~2R%tM%UFL)np;s3uSb_NOH+Uc- zDed3e0{eFe3jHb|lFQK)vN^Xk3j``!8w*=e2hXrc!dNKZcnwb1l1Bhg`33o=E>&W# zGl;GLyl^+%hYXW({kPMu+OsuH;y8UhNKuBdUD~E9b@_ARw$YV~((*GAgD~tQ?}2{P4pJUomkuDo@a- z^o1`!5=*JCVP!#_)EPe;_uD$a03Ur0fc{r$p|I(Q&x(gKN;l`9wZG%JT5Rp;Q^=w1 z^gW@_7E6w;Kp+%%|DD7?S=1ZBcRa*yHb^#I?NH>LG0}R&)dwf-ivxE(2Z)IR7mBBY zZBd2`jjp@B4G!_l?E*oVnP8eix91xgCF}K9Q7*_(_d!KLb{TLX?eOzoJ4&$_xTm#T z>UQ6npK57*Hfm@T9qgbGkE2$6Hx8GdR5(+8khIKmElP79>KxWEIW> z9sAyfV`$4v2_Ez@tvO+387;DA(w*w=Kwl(qy3i(v(`24j{{^0~!S0vSn)r57o&iQA z6|4_+r~U#UuC61(5u_6!5D2#r=#Y4$t6OZ5f_MiPL z6hcBpJ-w`TKx$HydzsatZPwqn^6=~lA^q29KYPx0+G)t5Aj>psj3=GiSCH~--6$u9 zrxfa}&-pY?xg;FBII*_Z@`Wl#Hw5n&ShKE#_hV42<0t>zW0TEsZ<)nN0LY*Vc|X0 zFS&~eB;jhpkwoQ4vnA0$?`1@n=1ak_$#JU{-)kaK+>EB2sAF{|eTvEtm+4E?2b~L`F8WK)Ck>UTt zG@4RmBKBtBW2>i^aIXre*&?cJg|c@2QwbLzl?x*jT@Vh^;%GOG!0vK+7FVGZagcToZ9g#nm=h4JY#~* z+|;AV2uvn2@kKfI)PZDpH_nKdq;Oy&^6OcC|rf-g_@G#s*fon#X}zwhjt z^jQxA0?_D9a=TYpGq{||2;W&^3%Lv1yw#jB81#i4(BH28BAekS=mdR@^ z%vin0R6Vbr-A>_j$9T=-Sg%49e7&~k%e7Ug@^tUaBuq>Na+-pH&`&kyuD0H9c;Dfu zEQqPu1+xbyO&&)=e3yEY@KM{Q55ioUQ2M?kbalwxXfEtLkJxdXEsvcNciMT^vHMx- z?|(=V*w;T-NOM;Fk(S>wz3!};xViZY<;P{(Ez%#@$e{WxWZKg3{7PK9M^~OJ!fFW> zF|n8zndg8MOrZyPS|2^Eg6A}$;R6W7~R5_ZExMGmnD{g|W{d_8etiTX*Nl_$aMLvL#6)p#R-Zl*?5W(=WVm}Y$t2-u#C4VS zsjnHJVMl9i0U%fA*fxrm@^V*~4#U!0g44||3HHhxH>@*r)Y7n_3_Cu}%)?+*>UUYu zovoHZK%qUjM#b*$dZ^WH6zX%g%T;4;lWJS4dFXU#X%Y0wgJ)C~J4Sj_nD?90pxfVP zd9^7_oaPw4478xWITw)b@;h6Wvo^1hI?-Mb7fUI|rtcrtlNaE2TA|WQE8u_WQ!|M^ zRY>!Z-e9~)VUN(<5G3z)E*we(Fql+6r(|_ybFTQy2vh(tssw1s*`r7Zir20`x5SmI z%XxkZ`-*}hQq$APrByanUx~{jZ9LiNmv2nTXNNmgDsvjkq_9lvw&8wX0LudmWvei2 zEgH(SUC-^kJhJ0X3iT+tPQDBp`UIu9Z6$}VAn?!N-@742S zAVlc0M?cXIGFh&mM}H5wl;iImuKP_H6J?aYO86$_B6m{EDBp85kl8U~1$Eyk6ob~5`xdla6_o)kZw*-4~M2dxsZun_cfLTt#TZgejoVMc5_ z&)R=6G9A<ehG*hAcVNYDL}Y&qzoQnW{j$h= znX$A1VmvO{TrWm%z(cbeY(#OlKs|9U+Sxr1CALS(?3t)`ljU;n4|%FM+0N>}@H=k$ zRhWsW3sU=mMkTx>Y*>B1-39+iMxf`rBk!TF^a66X%-$3idsLTI{U=KP;I;~;=Zw- zK@>lSHlLjapNw0Re5U(uvYwAP6jxF5Fd%^fK>sxWJODxck_$6nqc!{J$3v;9a1fU_ z9M|OiPV7veP1}^ICJq*1$o1qbke8>WeP8Y#QPlt3wk47jK^o!jgNKXhr_htb<_J(& z39XD5Z#DCqBBooy7}8AY+#P(()OudCE!VC7QL>`R#6;xN(n6YDUvC!}rN-<20S#uv z%|9hIgcZRF9o0P2vSadQptR-|t1FOd5bpNL6)WbIM4QW(Hx8l!XS6x{^A{3r=3$ zt{UWlvU#y=Zj;{L!rP?MpY6tVXE?t4gQXsW?us=LhqQrIB8;l00QW(nekM9Qol&GeNR zQ7z{r^!iK}$lB6)n*&6k9#UVAQ1S=;0niS9Zt<>uO!%z}z08B5(Aj0Yl|1pgJ9zMu zT2M6wg1Hr3t-i^O7hwd%0ulvslg!aTrth$*>sxc3uh@&ZL@itxBBG+Cn1>(BRQUsV zc;^8WSM%)88F%G^wgocd*I4g+uiD04zVV{Wh-k2|FVFfMpEQcRg^9PvyzH<_wCdpY zRZp}7?(bhzK4vbQ^%)dH&%M?;!+_f-xJF8)M+vEIb^!YGUrt7ihB29 zGw_qnXmIl?n3ChnyGc@VYVp>SJzm3X?=7T2!9u|KSMVq=Alq^9rXE*Vo$3Z_*pC=j zFI7{Yvz@Ibm%kRu^xaON-CmP$<vX;d>Lg=~I}?c)4u3L* zDDZv#%m6}hVZHE}PRrd$kNt$LR{6r53@307dh*)dJ(M06mSwqT!;VyGZN?T?Spw;Z z>%4n@sDeX>ofUoRjI(;t)5qZq$T-^axI?qGhwjuvOd>-87MpzbO2~O&xU`7)r3QHn zbx7>TxKp}M8W7L9F5kKJLaOb{rhGCt#dfJyo&7_)X*F+VZtz(lG5w zJW1>2oXKCWEvy%&vG%ez!Pn(?3bZ_pu}Jqp2=Xo5a_?Y=1hdPXw?A+;)7V9|L@<{S z9l=PDISz?Z!Sw1_i6f-aWPMlI_1O~>FwQ$OB>%yb8fP9{S`XkxXVgW!hCLuZjq0}F zjf%hEvgNu0_+H*2z&}%el!EI1wL#l8NLMwy1tpI9H|(8vD7&Wb%2Zhh3{St@9LM<8 z!V&d+A-;Lc&l_9Cs{QjNKG&^6QzrBv_`YoZp6<&}S+Z3v5t;eBsfqx$j0lXD=czr_uB^wrdl^K||yC5%V6Ox}e?& z<11V)q@DB>p1~uwC=W-W{|+Mj>l4KHSBqM}Q0?ohXL|zPJ3d+hug9vb*B${u+ghwa)y~sE!mJ%zhUt0s+Q4x-Jd@o zLy5XfBuNANCcdV#fyQUjAGcX4cY3W8Q4@mpo3A*Erk$GEEgwW6-4$A zhuonXEBBivBHcl39Gs_5bAL^9ho1lQrHqB1Aa?LNIT&7Uy8Sa?*7zQKJ-fo+IvODc z=3n(Bk-qJ7{e2r78^JfernsA5@t!?Rb|wc?Uz*vmgrZ1Vh9Gk#>U^e5<_Y=Y3N)F@gZ+n*!V_@;;!)XzE(hvYFq^3c44Q{KpjQN|SvuYAbbEK_a7n_xdRp3qjM!vW{dU@@$)ch~E29ct8*O4> zYi^X=|BQz+t!i6HVg5Z~c$_!CA|OO0r#l(I^xZxquD$_i@p}E**9Wv*8_CuSkST(* zC+ba7CR&AQIgmFIj?$_0;ionDFSe! zbb?rD9ZNklV3A3_{U) zvvoA1U$*(q#!nyH%e6b|hVu!#Dv8S*S$Zt=^>pc*BBdGc#HBpLU#g>O^JhQ$ZV;h! za2vAl`DZ}S2y%kmaef9CPTwumI%t6lF>8b~jiYuX6&|=>h?$9zO*`TiL0+tQ5K7fg z=+A@Li;S1gf9B!!jwDvzIv%a0V6R~?`_D9#t)D5UJ9{n3JV5E(Nr7CPmUN~Dhu_HU zNF7qWBv713^n*h~N1B~>-df_>G?#V1f)0QJp2fiwFXXR~u7TS`^p<^*G$bV_(6R#A z3NJ9_324a5qyfnk7~+30leaRH_D*+oz>suY%mhsK|GvcA3+(g*PKhz{)O}^q(tIhz|9D9Q1yvo^k|{9Xp0rx$sL0MS zlDMAGl3M+WhUT$+27s!XvVw-$KbvLa%&D9FlSp(a*%E6X`TM7=zUJjMp_M!)`qmQ5 zoZ4iKoo&*u#c>`0a6kha*ZTi zGBSOsY>APg6B~Bl;U;}QEC5I!w+?0RCXs~vh-7^qpN&+IOdq~UpJVPyx9l1&j7fK7palA7|8 z6Klef-p~HC9A2LQNZX;JNT157o08kEEe#H7*zUV@(D@LZzQ28q6Jvm7)(#=lUSH9SCeAZkv9C*S zSC_zGl@aPvcP1TWsXNGVA0^!tDAi!zLdFx3lKR{a_q=UXAu-bmI3x?rZEfGFygT&w*ui&9WEM??ZUZWa!9f|`!$Y4@i5ID4Yj7- z+LAklUD{OTgWL}j+7ur(P48>H?>J)hq=XLkW4>r|*I3ZxZKRJyl16A{-I3`pk8VG- zU5>0$eNtk4lbLMI1|2@U>bZ<4`lpG-R=q`b%0DqZIG z8gaX8Pd?^58%;gXedZr}^z0s9L)O)!(O?YAx>K3F)CZ=4%$9^r#-XTm3yCIRF{K(k z*J|eDJM4%7cV)A-ZxpPY*(6hk(acw9nHHVWH_*M>F7$26u7IaRa1<@Z?ETDZnXi+# z+`QUa$fyE*f=XKIG~eKNg0tyy+pgK(I=Xyd_p6Cac9Gc~>UMdM3zC`rxc=tJ*)Qok z6!kr0{o^yX|1oPk{&?YyYMcnx1-2u_SMcOV(i=2#+D=OmZ4qGqWY{>qF+&r0)4xVa zSda;CKG5A4oltp(rQ6iMrCfxJ?l6g?lapsm&uP+RzqeagQ+f}vqU-H29Z?}t=5*pLOD4{2CNysmV&!T)SiH!I&kn|^6!GC{yu>MP=Ii!k4zUK5 z-&T$s(%Qg;=s^S=uDtc@>+b%~qBEkIE*;SoYE7a}>!< zyIKpp*}P z!Xd2~|J3i_MT1?7ga3=@&WoA!{~z5cADxX#e5idD;vpFhj$w!qSN`+py5B^Feu|tm z%(6uJQ=-=07gvNY>k@uQv0H_aZaC;%N5+O_ZG)?PqkO4rTGyWsW-PM5p zP-~L!w5BR`19WVkEz-q6*~P2u$L8 zMUAXuL{m`0&HBXMEugi(`ku4R4*&9fzhRENBM>272w;%C6_Mx)NNh|RP}wNVSwY`mw_TvJghX1k1A_C?QIXvmxm7T@rLl>0$ z{O>L<%N(vy=h^GinD{-3_TPQkk7WI`x*{4jItE&y$}(F0pdcY@(=vIdrAGlW@(re# zLQX&R4m7Q`xn{mu)*nHL)OUnHUB}q!-D2NhokhtsqfK>T^aq6`Ztfo zgDMzj2E&!ZZZ5>n93Bb_mQ&<)TLOO4qNHDLJKsQ53(Y7gADa%$X0b@}pdL^W(&&39F7qK2U`=N%9{H5?!?$k-c-@Ytpy!8+!ATR1Z zGwsZ)&!vXOXn3CbWmfR67wAz$Ioy8!H5E?y=%~xIhWXw-%sHymXVyb@rPua0iCa0E z1{CtcQD$CHz7qgF_Z-tIXV`tqJ{-bABMk7(Ng#D|t}N_E_n^ctp2FkKn$r3UP3iv+ zp{a2T8`=NM$P{TC((kcDy)~z~?_`7rMxFz=h4in;^f-st%AM_m-oYTO6c+wLCjXvK z6mp(nn$P!^Mp1!Ft&M}FhLyK6#1zX?1^!7|?H6>wwymPjwolvvi7$HARuw55EIHWxC%?HTUPwA7b4kYNqE)}}-r#JEeCS(<{14u#Ny z>OfEjs7RBTy9>I%Opa5mr&pzsmHL+d6K(Gp9a-1#c}E>}Y}>YNyJK{cj@7Y~jykq& z+qP}nwpDrSdfxkX6nYcnxtB6QoOjOKp3d=!^6Sj(XOi1T1)74tg^M}Xg!PfI4r|Qw8lR1)- zYS+#B%7fT!lVolUiLMUj!a=WP`_eK}1J0;N7T(mAfkP;6c-hU^*x(a^Jw-+ITzYB`TbPUHuZ>$=8y(csOvR)+&*o&#MpD> zbwru`=4*V%{VLt7v3yA&pi!y|e^uxXJF{SjQgVQTBu`?z4-=D*zA*n@r^078w-s;IwzuhN4{F4R} zJA~IWFklykE7`o~Pc`PPp|@<5!*xEB&!sP!( zu%(_WQ{GoD$MZ7JEnTI>vQJ5G)9Laq*^?dO}^XQ&2F;Esv<&BJ5w+Xokh7w@09 zK|Lw1w$#RR7gP(_yoY=FQXHptYWRe+XBv4uG^Gl)>*ZkB*3Gs52FyhTO0vn8F!F>9 zru!Pp4O^l;%*3L3MzRG9jj2yXlXGK=5XAd%pOSO-w9DCVs4&{^%^)+#3edQ^rMJ$% zsS;_Zio#~m7u6Y_LOGRcg9I-?%;9}ksyv6H+hj^SYMwe_UG|PP5V#O4B*H{PWc+w+ zJ(b15(aJ5p=`qlH6E>MrxKg-p%GW&H2-g~?P&ro;DPj>6{y5c|55p4V^dxWZ=XeD$^_7-xslAt~cGuGtu#d>v(%2%zQ@~SCjBE@7d za%z45%M4J=4cTbT*BhsOzFE0+dGNqr=8P&Z%^$^cyq>U=^eN0=u5bKZm3v!}yE++6 zTHU0Rl^)x42?(L!H?yZMM^ehf%=BIBd1ucWIz{KyT55;(US5$3k0c+xlB?w0F5I*! zrq)RPa^TB&tiz|mZPhe-SpX(pSudc%wKQ)SHzNF6{h(4Ad=YcryB|1mG!va_kWB&i1 z{i%{-ZiM_C9Vji2;Z-vg4zxl`W)6$53qrzr8)=4@u#>G)D7Q>90FUt9DA zbU&@`g;yde%MDys>`)xvK!T^Xz1Gsq%|E8&>i0Wp|1jw5qtR{ql}Z98bFDZKs`aOC zt(Li4y?#u&qYbyn(K}3#p`&!-Hp;X z`IScU-O{V1CLikqkvv~{N%BjPA23|84p5BvYvgambl}nm?g7v-6}1VV>WB`7w445w zx6ZTB7GROK|FA1M#?CiOhK!y_yqvy9J2M~zjE{2_HG^oWx^%L}g zXx9^eSN9q_>9BZz#gWlh1x@_!7(8>F?A6i!U}K35Iw;rWph$`wG?Y*B+$;Pv?*-_9 z0cJcN_$Ee%T4BW~0t-nC7AMM~W14)R{XFlrTbOumw{^rwBy&~ltZe32Vc;9mdT!$mNc@E`9l&;|h zr?NLN7k*?grQ+Yh(J4&E(zc}K2T7X@ALEy(b}{+bBBVs9Z}^YRdyO<(hqv-C)9JoD zqB+Yz?(Y8VGk59j{v`_O)%>143tXBWuRxya>axZrXE8O7S5p7|J#Jz9tdD&4bP8poAKmcND1hAh@YJHL62m>KgZH~zuJsAmNf zrn6ekTFg1<9Ct5n50s!(X-+7-BwF^BcjFyB6%^sz(teg<_HQqS&6*GLm+;XWyeAqz zr<*k3AEif4E3YhntDg-FFcU6waZ5f#Zsz&>Ni}a^E3z2(?dI8O$hu(%LpK!Rx{`=Q zbvt%Ibi$_-9vw`tMpGB2V&?C%86nASmO$*l8Yd0%iRIu~Qg#`mPv6jqj!kw~JfVc| zz(KSGGdo?r$(+L1)XCBzj8o%Jm*2zP=IC!z+>#9H6g>okN7axsElwZ|rlb^-h+yFw zxu-MRT;*T|C{KpQW9T=1qrjG!1JPOS%~UiTZ;jW}3p_o%fV`X(8kXJP5@u2e1{3Ry zY9uR*{)60q<|g$`hWsEVX9XPOfKwa!%{J#!oo0j|u&p`s?@Dbhn-NydWvUBx!PRYx z`PMa*2o$IY`s7$$M-mX46VCW1Grx;AdV+O-u z@Pj590cCn@|1jp#$H8%IGLy=2O&j7t<=~M?I^JoOzbOF=UCbUjX6{Fs)T+O}%E6+N z^f>eM^JN{{tk%Y$V2>=`BQUmciN$WDC@`X31#m$NTGfT3OC}Zu$rUavJOee}!!Aw2 zJ<@H58$zS;g-0eXAC{vzSS)1^nfY_?s-5B5ia5h&)Y-${5>oQ(wu z$!VRV6Se&#Y(n2)m~>3KG#XN-8PqGgHac*=o!lso{W;&B6BrmMB~|KjHz}RI!Z;Bd z1?r)U*2(n^E#3%J0az=TdHtQ`IF8@!lkIAp-{s!U+QG{RotfJ?agaKd!Qe|=TPH%r z@P@ID#wotSpi9n0VvWpJLY7%)ZG5AE*VhgKi|kxQTuiOC>j|CO6h216_;}>)Qs>uc z0cJtWs_NQA2bue&wCT3(myN?U*JIFOV`ZvdB#nkyGb-jcW_2va;CY5I&PO|JNm1pe!k!y0HOkY-XK~p#hRn*);unzvBEoyoi1E&$=Xe;ac!8yiNUOy4} z)*AWgb7HnA?ux<)<)U03m3k@jZB0Q)2oAqu+she*s5Evxuigc+fwW#Y$;n5-{>6P9 z1IZ|Eur%>!0PocLH2K*w!d|H;nxpY6AdJRx0nfcxm6FQTf`eXS0q@+ac>bMR9lfesop=u(udgWVwFn)xpwu!NHH{dGoOKibm=b%O~6~f}LjVcJ`MYmOe3wbS7 z2t!VHMOSJop2lehk+RqYO1no58Y>Z2*!W52>GPP(_r%;@4`KU+q3w+E7bewt^35bi z#d?DeeH>mY|0z{%#qby>Wa*Sm2|8EcU=~eL7nA7hlSvOQVhsuNtKSNNRK+eRdJPkHDWSS)(2B~HtZBS6l+cwx_I1b{XP-L9QXVCIUChZSiP$NELvF) zEp1gU2^l#B@qb+oWdA|(g=#qLaseVa4>70`k6;tP1Oge3-7i{wN#pjTRDu~i1V_;; zFKkaM$Wr`~h-SG;Uv#o|$~CbBWXVB|@jAp`#@dOF=J)-L+}kpA&+1@sj(<=oKmn^1 zEG|LH#p1^yu$-<#lYr2S^TYqUO2z80s1>0FG88-0ThhTq8g>~&kcAT|BQ;#grpq0m zJ6T5WRBskr+&))jdMbhQ4^DkNelhE`<2jQ~#2j|y2jHvX0G!caQ3*y{dJ_h-9R%TAJ`<1SS`#8 zB2Fo}w&}ofkN-q2q3L6&s$+Z-I)md{0iK9p6&Q3F-!ZH}ypy&ETnYB6Ilg-*i8}H{$ORvO3PEA^@&!E?7O3(fu zQQ-Sesu$PPQI2UGxwk#uqmRa*R69Gv**V0OmO~qwG=c^`R8z;H=f5R1DE!I0-d(?p z<0#n;Qb+#a*y4S?vJ2=t(!1VWFGC8rT!2v_B%FWH(0@0B6;zf>psou3-V899lk!&c zw39PsF=|%3c!JZShzEnVtUAj;2kOpX4qdRHes|$B1)lQGk1jjG*|{lSbJ-}DmJc4k+b zUXvH*P|(j`p<0wU^TB%CL|9BwDO!t;@W&Mbc$H=c^~(e4LKcjJj{#g&3-75=X5)jEj1=#D$m>VnBYdjFk}MzrX0%aoyLU@C%(?=;HKE-WFaqJ zEmvJLh3%@r59>mLfKRLs!k+0gD*1ZnbAr5QtTy(5*Z%@MTc%xn{mb=iKYCaI6p24O zNQFRG%UVA-PL_Nyb3%@Y1$gpvc3|Hiwf;x8FYz}%_Z|B`L!zO0dkXVY@}p~ZWnyyIa>9&^ z{-R?lr2tyGjuQW^V3BWnN>{Yc!Xd}ee#9?sNBQQdVGACol2NO|$GR~hU9F!}O{lj& zj6d$a?HUx&cI(yU-&;(^FnnV|FOzZyex;ShzZ%Qf%;)@0Q<6i`@0R^x$e}fU!yJ|aOCM72-R2Ado9sRU?Sdh|5{+`6 zk|!Q?ugV||Bdf`=6SriumKnD{AH`EDM`RF(G5cm6{8FNiPeCxF+NNS57nT`v&7+j7 zZk*-}@ZUt_nsc#c37c)yRkpP~{yYP?xqrL)kZhM$)-8P;g2vgfADeYPdZrSq>1HH< zrzci{gXn%i_>?i-wN&9`e&Y7!`-D|3^McowUz1LwO8Jg9HQRdb-+t%O42E?`}Ls|X9oL%G-CgoQey?5T$q zT^6m>keu&P?RBxF*bMXB+dU3%4?qPZ4xyyI{k$x`ePQ}xB`dqF>LuvJwN0-#{ukbA z)s1W(DuID8Q}T)EGO{kEk})gzl_iO5!90Y(vd|r8n-9Hf2*+@5>@#>YV0D! z0@I^<)!Ds2VBG6}OTs%m!eIwB?mDKrNEvy}hvFu%%KJTe<<;>U z7N6gNS3>1CG)+YGCC+UbZjj~k{(9p4$zC=1@{(8A4QksmRS35!A&?0CK56^@ZG1UT z_?v;#b0Y9s0Ko^~7uTOg!#Gvzq1mazYE*9xoan@z1!YQO2-)Xe6`yN;x*Omm+(?9W zi~NcModz>0UCiSUCm6Q(eB-q z?BtI(?Gztp@zJ~_c!5ZvVmIPoHLw!KzE)ERsx+Bga+DH+DP#A_B0*?f*w&2Om0iB? zr5sLkbX(au>bp17D21}9CL68&TOu-DKG`r0VlTQs{Anhi<#SiZ&=d5z4?FO!BVMz<3WexEe8fGY~nAO^)C<$EBDSfr6e9 z=amjyT}5Z#qhf{oQ;%{@P9W|Pr?V9~+vfdG3$e**<61~{Ht*j8DTYCE(l;WWXS<-{ zBQ|z60P6wwFg0gBm-ik7vKCLf8%h28@J)=#q5Cj(sIGv!KdP3k2Gh?F`B{Z1cd!C| z{^3zn$~py}pVZ=c`~<2>KgJ;Nb~h5k$<8;aG#kHV8sJW^s1qP!xE1E+-f9AMi1V87 zvQw*FUJfSgGDm}wB$w2Nw!_t-G~EI={8<(c33%)Lu^#|_?TP+h zT0o+8Cp?ht&ntur9JV~`}x!c-? zZF9%prlC@x8WK1T5c8;iI<|q_4|E3apZ09v3&CTKpX>$b=SUEd+DsUCsRvKzD&Isi z5908;{%)&VQ|eZZ)gVXK^IbpG+TZiFbJ*_pP~#^WTuE_TO$oX$6zHugo-BE1$k9tT zW0spbzI6X{P~UXjNUp^Mt||Pj>C_ir$DxR^!EfGFhr0^5SKTPF;q_~TksFeJV~6gd z7K^orq+MGRi@`D?IVg<|eBhEDns_n;}N`yl-#~$ z^F7*8!$)SsXg2vQMbh*#XySWQ%|19|WVISsqIQJgV5stlZZi3_ujAP@sN%o=a!wsi8NCsdWGJ${ zT)B+ylSwtdd6J`Os}!x|P5GDCkli6%=RG>rz6q&aPlvhVY=0X3KIiVjg*VR`CX&x@ zY?V+yZ*k@KSycMa%iOXS2LQgU8FE`MTV?!~_(~Dh#Hl=M;_hUc@?Lw#;RbgLZ!;~6 z!Sf~G&c`V_4=&X7wg&@F%OH-kOMBqHE>yZ2u|PbG^1ZmZSJkiK6V+mSmo<*pYa&Bh zI3t}kiJ8%<2c;>N6Xhn!DTI|1crP63G>7hUF6$$y&L{I^708k!b`xpuNJ*@q3@UI@{C(_Za@4`afu7k9s~nJ>Q4<>C@uNxpl)f>{ zEo{*ogR+{4dT|GQHO`B$)xy=vi<7$U^FB(Y+DQ4#NY*cK0ezZfwHjHFcCk02Y2{q10sZK|H*&5hgP7`*s_xI^wN;W60!3z+!oA6QFxv9=hw*J4;zyf3!QpFZk;&7dk@HfKy%#6F?w`Tu2DgtQEcl{ zO&qpGYvAC7mK+y8&aP>2YtDeo`x%ScLTKh)s+Q$-aMKc__>aS!%LNN}vdc36e<36q z5{}jmQ-7zjID-v(iQ1MIDL;qHgYtk=Zhi=4WNH3-v7rWPN>Bv~=GLQRm7q;=C?gL5 zE4R(GOqSGH>ENAdxkKFaARR?{`U`p~owsQ=dV9fmRRN6d z+MPW{d@q%HG?>a^kn6A2%dpj`k!f#S*+i7r!RdZ!Imr4JNPbGjj`ol1HZ#7y^E$gB zXp0{LO1hJf%W%GI;oSec{|HT+RmqrGJcwT(60I7aBk(bzVU}$@BJ88X^ArNS?NIGdS!kh-dNaOo~2{tFDGBPu{&BjvsyI#1DW8HRu&7kX<_Um^bO4B})*-#!# zKD!7C$2_}LvOs_LH1<{-{`JL3SCfz=?65JTu>)&dd`)uU^<%+(3qD%oAF|Tz`wLRL zn%~3R&{e{fVFCwPqkShD{zSi0ak1tB$Xj0)j4emjkO<&H-mpDUw^I& zs7&TAR48LSkDHCS+_jr33Lj%g1=TS1_0b^jnSf+|=awFBHGd#&@M2=nP^k63h46U( z@<*lF;gWs0W49J`NMmcK^%0<`%Gey-yN$kip_Kfdl;RNbY5d+N(l?85h63#KmR^jq#FZ>M!X|x%w$c1E zr;vyw+W)b4X+h1k-og`O1+ku+2R{4Aro_>Cai)}^GTl8Er!&>}XYjFs@F;vSLm=S( z+3{cm8KDwi);j=qa-DNnUK!|}PUO-d!Ck`dLs*Hn{w3=`AlYP1D!;h9S;rrlSv9TH zg68Y5hW>E)&df@acKNOt-(Ui__}EO-d=RaEwThmhz&Cl9n|lIkoawp}n=o){A_}wk z{b@ytM3D;w{E^~#vQ|3qfWlyz>I}M7UGNpqvv|vEZrCarR$*%|BEQB{ToQi>susMu=-Nlja7S6G)P468c zO`hoO2003Eb(k~yE%#*Xwy%v%C2F|F@R29a*UQfma(AprDvuR*`&9hey_hT6Ev*n- zCO?_>;=_X6Of6<%u!Gh9d$N7;s7^X}c9NKi2hXj6QxCfZF>28Tv8+L&a_nsemzO_k zH(aqlL-418_uyY0YaNS?Y_2#IDHJ=f${@7tDUlp;Vt(S&zkZgrr{v)S1F}?0L=`~| zP2ubyh|+sraUM{2HL+NHSVf(2!jDhnL0cA1D{Dr zdgf<^{RF&`!6M}|Pp8qLe4fR@bOZ}_YWSo%`fXBwsalrpq@2NXiel5M{L@C#ZuOw= z?fW@P;7rQ-r!rU(V(3`HB8*{%X8tZ9&iSPY%gAv2Bn1p7o1>qFw)-;W9$MaCggL1N zPDD(k4|Q}n{NxbDf!e(?BrdRa$LXvM(ghuz$QhZ*n`$)2y9)D{aWH}{^T@JUS1^)P zEF}1}*ewS?rg`wJqm~Gqz@NoyDUy-rN=5I9T;u0eSp@<9uOVc$*AAZ33dkLwF;F$( zcj$G)HMT_I z4^6EP7aCnO=x&TrMh6?)Ka=D*Y0>cW1qHYuvByWyimT=ANsH}UVu7%8$D*NIdvc&; z5>qMAV{_yo3-Exj+S*cBzcQfUx;SRzE@%%3A5l1_e9fSF!fs0BckH+S<@k)s#?BF zK||9%ea-jBOihv7m9#6!zpFSnwaLt6%rSe4jrd6zOGXI9?vFs~H)SJB-L% zJ>sEkifl=D?wJs^jgE z$0(Yy$iRaCEQl&eLQlx{#}&Rf`Q?lKoEnqb#Z)-y+ibh5+1bmc{`cP*;rj#VpvE?D z9Zz(MPgnBombS|g{cwLj*v;9AvsAhN03)z&-9z>y>U*nM9&Wezmhv_#lUb`JF~!8h zuphWW^jN|lG1W!{`ZCPlA;Jb69F|)U%GK-K?_Lu570B60?fgAnu#n5j^?jG_kwTD|7aH-3S(n5^r`fDWaByo*7 z!CZbP<53Cn?svh%Rb3qsYZ;W>xRNs5{Qi4%!i{ON=}nP^{=o`L8Hcgr+~Ok)Bu)5t zmgoV0w0NduP#^cA?+U~zsd(&ZRSmS8Y)Btvc|-m6MY8lLfd{X5X$d?53N{P(!s{5` zBfM6p^nfitZa)$vDhcA28o|V>iH2_M>!$S+jxDMx@D3Px&~8t=bsfY8>@Ay|>dzq1 zX1P7XtJ{^)kOo_mI@-v$9bcZk(Bj=76XJ*%>#2xNJ_`H4@G;vrG?Q$OtyBgN=zMY$ z3r*cpG&9kKnPnn5pQUQ23b@-3H~(I}I-Fz-a<(LBZouVjjFoekCBh*vg{3!Us8#-u z9ee*rFPRJ_nCKQ9V)Klv(x0-ul;I^K9kM8E+1Vxf)TN;~0h^cdQD`~Oai%T_dmFuqL(O~m5pwxQiIuTQ_PA&r38~5Te@M#wl7N{D57E^pomOWGRostdu`(&3d(CN2V11Wr z$EJksIKCDlu*~z?=2eOiMjX}ou0DSDYA1CLk`E!+su}lP*U!-iT$NsFMB zQ*9>U-&z2mU|RHjjpaPkwx*@N2ITx6QW%r~cEU(f6G3ZL&9y0WU2147y#!cT+xL!C0Te|?%# zTy=QRb*?f8HV$ljUc9L2X+3|x&PXhYU6IYAi9AwVnj@+7r52l+Q82#!5r`Z&QdkvT zICH+}J`rBMF>NTb5r<0A=@@Lj77*z~LPR4J1dA+mI~)Jjv6|1&JBHm+~93dSOy-Y_revhl>i>%eB@r22U;$AWs(-&k#H(kS5Ydqq3 zO_g;-%v1#o^OmH*l60-H;;$s~G=oHf`7tt|!${W9d8DLoydeJZUiPr1+ z5GhUL#%~;^;J|&~aDv?WK-V<-ObGrXJA_B3Cyuem%0Zt;Eet7EeJfdw;L=ttUuZB$WYc>pMQ>@XLEa|?84V= z`gwYTaFDBc%5Kb^Es!yKk&A!IWzE2ySyb!g!TIt1t)g|xicaeV%%rJ%k`z&JjJJL4 zelKq@qSSeRH1vxmY@{*WP+OP#A9L}#=zO|wlxO4CRV%v1`_!{r$u`~;I{VD>>+Olg zIo9%vz^ljLrU*mL@0oy(*4C3u1>?`!inPt(oc94`As{~l>}9cLIFN_#OGZ1CN%gyj z4v?(B<=t$d?Qk=rOM=`hr)`{Rd8dAzX3yTX_AXp}bVRZo+!z3`-;~cffLJ zJ_ItlnU?S7;THeA3f5QSK{@Yyw{>9a;&%+Kh7g|mKS(|0n%n&o_`fOA#e7M)1{LIRkJcD0*x;O68>Bw z$UZmkw}_10c3ud2AFiD@ReH_T(<<_PQiMl+_HXO7iJI_6O`A=yGBVqqIYb?9UGM`x zB?ZCh`k61@hu5Hw$r1SD0=2>!T7om{)6sRi{HZQC)lSyDQ0nx@Qg7l>^ai6_du-eI zv>N#Zzpg$K7bzKI+w8Ed0HEYPo`0zA~B`Vy}klnApd_wMo zn7UpxGhQp47vppp0h#r*+j&-#LK_*I&=rfB_T8D?MS7Uo!=3WLyDdH!o~wv#s`=xa zHHC+GUX$Bjm*rrgul2D-Dr)`BZ8LQ*ZWj+1Be8()FVWX#ovi*{p{r2}VlF(I=YkU) z-_(lC>-olKU6jn~?Q|p-7q5wY{;%QI5CEK)1&%Ropivh!VS;DAWvG)5;+m7ioav9-`D7o3Jccg{QGcL)n*`si5NO|S zjh&XNQK0k_)sT$}DGB|eMC7LS@2ZGcN%1yjGJo_J^Sw)8E8n4=lBjQa4U%e9zaA;N z&`C(w&<&ZzTjgm@=F=?BgYe)92a??BIpn(&T*A?ouE_%b==c=fkAl5`{)6<+)b8zi zcM;rDtsxEFNJ!?kH`$;f#WAS!I9RX&0P={o{S$I{aePX~XF(r0_(6T82Do#1+|#)1 zolv66-la8Kz^EQrSwkFg_H~TY;~JljuMe_)Mh0a7j(P$JA|*3c#z46m{V9_}7Ty@m z%X_IfOPMigsXm94*XE=VQ>*mP$0rs`fMKi3NooCl(pY-5m{dtJaCns}jg#{%{5*|9 z01@H*M~qUn{0KMR^g;TPBq#iKIfWy=c=h`j^D*ct83gL&X` zzZL^Ib^}%Ru#usWY-Ey*Vwy#zvZMLL7JWop%wa!igf`Psx+YjlZb~0TDYpwQ1(y+_ zcC>1_Jk+nxrjM?&TMB8h$)M=5g7lE?%7_JPaFtSx#G`|FyhkMh?3|%*4!q!z{A`1H2v!@P{a_P2pyyfFDhJ3$} z(k1=Eoe{=SgGE!M%*WFEED#AUb?DItYqeb*mQiX73Gr~x_IfumgF$q`tX~!N@8=y4 z-@b|;Kbu^O3<=RgA=yseLM|Mfw?z} zZWR}>+9v}9sE;j{{h0SnBtDdtZnoPi5F^g1Umg#^K`%IDHIO8ULD~V$(&u>Y^9fQ(9kI_xYeuE4t9kZ&Nr!b1nB#WFN zn6o$SyY{&J(6}7jEKT+D>LVset^1%Z$LiNlI>{(^ut~zC#U?kukr|DPJ5cuO{9LDQ z-Bpv@Q{|EC>+35R3qbwVepyH7z9H$P%bwuE&D7O|B^# zF3}&`Xc+==jwF7}P}q+v^?63Tr{mjk(Y#%@u}45HdgSbkq9k^FKo6>}$V~lhOlCH; zKDyg24GmNr?uS7lzB>sC$ErY4n%i4q++8A#bV%|)@=ZI%R|c)bJ_*D@qADNIz5R-D zMbs5VpRwkMxchSY4<`F$OSpTjDIGs#tPS%V#4oP5Ur}R&AaTr=Vbj(Z= zDvDCT5JRmrabW@0;H01w7~j2#YQ&F&#LCyrNqf_*2e`R#e-a)u##?93qhk9?N;{ir z&g$;t01^*MyV|$*!|~#j!lRYTI8sg;A$F52r)PDDL87h0bE$x~MDm&9N-ul;M59qn zMp9bL5z9NI@I}=L9`TmMT_?QcQp6UZe%JJisT5OLhejLhpjI54BnYl}ie8B(Fi2Wc z6W-lYIIJXU|4x}z@fL=GHnC4+aGCn+v#sexEQ+@v#!qSBz%Y?0yd4W2Vo)5%*G=rs zK)mU~y*t#63ObC$R54t$0~qBNN*+h7RreUlvsXqGwyH6v&OqB`Dz21Kuynpo*51u(My0UeE8v~G&Vq3z1rQg5jL$*5SNl6^nm+lPm&C7 zF!@t&Dl)G$bU1VxjcLJjAWq(T(>>*Wlokt3^Fw=l5Iy^Dau%2pGkDM`O-5c+_nz6d z;UK(Z|FS8}#@>9v_(9KW}hkDp} zrN#q)Ra*A4%sYr(Dg&!bBAh%EZ^iDXyNQQx(lEoj+I90%xEjMC1|{5{-AO) zLs6E5nm_Y}k!L5ZAqGbEDWdh;g%P+syD@~4UMUve< zX#qRc3&4agG}NsD{BdNx_Y2UDCGHkuR%>#}aVJ9J=I{XLqm4WIT)nt6^R9RL)Z3MQ z_FdfdzUx>@hDf>trU65xiRZf?M$khbnZy62&xtH^VsP0b+yoGK`-OA1p ze>_e}u=93+Z8(eYf6^o@+h8q8tcF~PCx+p-b6658pST>SxPKkqzWYKdZ8Zz<4dt zjgrlJ(nR>2BEr3$R^0UZuDyPzsw;n^_1^Wzai#KcDpRrIgq+>={|%P67LKwn6sZm? zMf|#5zZnbUa7(DYf3h#d;-$xIz8l@&)!gWWrqWB2K~&t$!55n(+m}I3EOA4bZNY&Q zl2;%T|F)hLDP{&8rYie4(mXI4p(i3e9cI0&@?rv|hHx*xh=3~0->iH(#PLrWfuh$N z{zj)7U&(ffP}2gLN_d4ezkeo5TKjPed8QW&{wre zpf=1yk5c_(eYUWawfmzf(m>$hr)&}wqP$n^!Sc50=iaF9RwC5Z<>}fQY8Vs#TUfsq zj$W7|rTpO+hV9Qu%>0lKL-hHks-K!OljEIwa!3BLRsDY8N^+)huzzyOVj3Ojyoala zMjJUk1-<;5Ktt(pc#{T;504P=!%Bsaq07qhD5lK@{*+csKNOzUqhhbEgp+PZ?0qht za$-*Wi`chE?zmLndSv6IG%FsSDmLxyn3~Y0Oi-Xf{BYKdFRIy(NazWdxN{gq6`IYZ zwS+dQ8cvT*FL}8o6L>eJUiSf{6#KsVMc%vK*(jdVzxQ2FQZPP4GWMl!9|)(HriZ|O zg&-DB8xH=%?Vl+zu0MkCRSASz(@M2hW{0MtLO-!PZ?N8E_*0nLcn=*k?ytVHazl%= z^9uD^bL4{L@%)C);kko?2t)XML@YXL#)U&a<=aEHM9bpB9#b7|E$sq+I3%@)7q@9My69uRQ?=5LMya|JoGzQIUeKQ2|OY zvUE>YiljSpTpu6TQlJUlfOCu3kmCxxb5w|=en7ki$dWFB7&v)+_fywQ{9ktj#ETgP zq6Jk8zgWV2ApjrGc4P=zSPFC`I7KvYmlBlsjBg(O3*e#~1nM8oBD@ z%|>r^@~RGBKLNw_bnz&wps}pxj~mV0>s;;DemJ%dwP3-$o*P?=@D)3N3{xBJ-y;o1 zng$q{oa}eHSBSUjFq-K{GlYbMu$at{Uwhp!$w@L|CY7vjW&_MH7WNXfq+C?SkmTSsIoE zj_y9SkrzC6{34?>1`8P4d#>EwK>!E&01{Q7!DRxjhvaMtl{>7k(RWJ6>pGp;_8Cs) z=JM{}8H`ZFNbxr%1`p=yb!)Sz-g%Z)jYF$MeKM>~Fb!WL+CmC47%|I#1~w27 zYNvc6!=9&%jk~^NeQ<^lv_GJ|G{lQK%Z5iPamE(egVzk)u+YHWHsO%49agSljs$aV zkz^~RV6F(2p*AP{?{_9_l@I>M&V*^s3m*U+%?>}}(R{NHH}hBRQEM4QGIfwakMYNE zY$4*DdD4d8-`Y3*RPz-Y8r5@DleMufTrPnAZUP(Ec*cQ}jI>uOlg|$-eD!z_`fQU~ zE%XPBvBXEAR+Cm&6#S$$XR1P|^{i)eo#t;g>xf3C7nc_7qOClE?fhFPr_FKqg0mYj@|Sc)GOSoW5^Z15tG+teBTCfMettPPy&rKQWC~smbqS%)M{=(} z`-q*-b!m>N=c)%Zb#xt(lo=5Qy~d<6Qy-D$Kwsgo90W-jbT3&mMahHfxi1}dDd{FKA)N2eUvvm&hK(D zhZ7vqLjmYQ?>=V3H{d>D9X`f1KgyrIK+f%kx5QMjCf_YusHMZQLo` z-QC@3+@W!IDBNLr=AGI7VrSls`L+KlG9$AxGBUHWu5+FHoY3f}=E#i42bGzC_zrbP zonHR=v;4wx`N~nL1;p~ze?@%MFYu_ZL~2?(ds%f$Yr5`TV6x2VteC0(pKTTtQv3Ho~YVEEmz;$BVpF*H0|i}DKaI)eDB>o^;Q#xQVuS5q49J%PRd@h4Gut;8oM1H zNR?R`ZJQuk{Dt??HfXCga5_m9pG(Vbvk?r(NKqm7HRo3LE6^?xYOX#4QpF9=vdu0D z)@h*FYu4(9*Dr%Lm~#=_u~~0lv^day=q30$MZD;Qn(NN`u=5E;?G4eCg2HiVGO&T+ ztS0M1H6pPhRZtx*N)7jVUc1}pfwcUE#?+ivvs`en!Jzt}1XYa%EW+KLa?&$7h6BvO z?a2^!u7F7>n0RS=FZuGGW-ndlM?a*EU0?8`{iK*H{b%?=drw5&5{{ql8!bm{x8$Ql z^vOq`bh@neRAqP3jL3(1wBpaL0`9vc;s-*ZE|r`o8sDE=_h#ztj}}w);p{!921lC_ z(&HAhBc413?ad`uR3(reGKT2c&W8 zS?6#<2$Q1u>l*(Ju%NS{f}e>|dm>dEvfv7B-?64()b)R=p~QBsxp$9U&PO|*ABoBvoTyL8vn7k;)CxkSmqe#!Lj>L^cu+$L$n=-0?s zQx>^@8QxP4^SDPZ_h+BdJpV+;UV5^3dHOr34B%p7-Xll+qk}tM6`V}I24&z)c~1&x z{$qvPIo1$Ww65t^wRj`i#{Q=&&N+kdpQ^ZRF7AKTSGKeHMzkngNrjp^#F!1Zxf zu`0+LoUhTAF8SnyYut}@ZnvIOovuN~{WXWGxv~FtKfBC2zW#G4>>p}x(B_%6(mhcY zE2CV`4n_z7)n1|jz%=4fvU?B7jmyW8?zyD-Oj9QIhpPn8`m|?HhB0RE7WZ~SCMu&n z)1>VaDeaPg*1{i0n1k4!_VGDJ#ouJ*(SNVwD`5BO>V}v(lY-3osHRfTGkn2!T+{j7 z?}cQ2qkrm`+Bi>wU%bh zHXukivlR~-2+?9P628QT5Ae>`DwAw3eZ1+Gu4I~Qv6b7Jz3F9LQ*Q(a65H>H=3N(? z4g&qfh;ln);TZ)ne+r)CKj=l{o~}&uHOWy&I1Nm%yL=718V0@T3HLw3JKPG;czjI5 zG>FN{&cc}$e%*f9iVat(@P%vq4CcQ%R1P1JEztaNa z|7ilm{QkY-)=jB~2y^(rdK*alji>&;fapfJ%E|cN1*@P>nqOuyAuK12Q73`02atu| zBCda;DibI$VeIsf5CC^?*1PV}mcIL^ZiuznTMzb{IdYXjvAoG!-h5aWt?6lmRg5HvhT;xVVP;OBBIuh z2`$(RN!S$`Mg1~5>yO?kck@W7BT@wzjIW)rdZ<#QLQTh(xK4jp1m@xl zZ7j?DlTCI^(fSC+bEHUdzgE3lO~N~_QqM0Vz8~?%%Pj12JXkZWJVq@qy7r~b&*`{O z8w2SXlIb*uv_vq(v~b&R@=N{yI+%}kR?C0ojAeFGFpnze{*z%b#UU{sI{qb!Fscwc zphAA1_%Kpt%5PR}gcvo6yeV?aOrz=wyvwKda)d7@PYzuFl5lvfk<;9(Jt%aOc3i$z z3k2Qe=l-5rmGRk#{+iTVeZOCIp-~7F7GY`qZEu+S#C;+TIt##~ri1e;dw=?rhW6L{ zxP?$nenC|mv{Hwdm~&Luz7E}R)D^Tkq!H{hD^k`hed0Y>j<$|e*l!gRx2a?8s){|H zkvS>xOL!_(QeG_lN(AWe@%~Ht9r0(qI%2#bVgB)Yk&6d-nSp?~&si+s{b4t_ZfvS< zaj=vmLMBc%_IKP@D_3Fvtx|%9xWJ(;4jp1e@E5C34OWB0iVb|Us$|#Bzg2Amp3N)I z7Q#d{Xws^t%w*gHxluoD#bS z>1z?tJ!>;-s3XSQ#vHO(mr!V$e;@R*=8i{mCw^GpyL9S$Ccp!56OQqS-EM zWP8W?kS(dAN#J4mOH?*&FcP06oZx}})AeO9|38iD@Ne$Cn1o!FomiA60``Ie zIZjuThEhY{w7YGwt+~t%s}`e=N*KSfo>F}*(`$}-l^+c7;F>2zcI+u9I#w# zh(AUUakLuyYNZ3tf~Gn;vl*>nPsY%HEtB8sHsa13=us1DPg)Fm=U!_r3GkOBvOWvn zl`=f2Cp5J)_!HrbimZV|X(n>R0L}nrha4{;G)U2h&p~D-L zu>!oLbwj<9)--MRukz{ThjPPw;HMQ*L1tc z`=ep)<|fZyyLZMJ1o>Zd6~OE*uRpypt_TWwZzOTQI3)vZC$q8#R_W8sM>x{cJ9q5- zI2O=yvnJE+820i5f*~@)4h%`M+iU?~H96Cb2xL^v6|ANC;2mWY%s?~lx0$j}$S=?J zm@z-4%ZIbjZoq8b)KQVQ8Z-9j|53Bkul`CxI^Z*oj`Z`gl)nKZ69*}*iiPqObW2+}rD zw^65y1(Ljw%0MuA9W1`Ry{Ukl3?(OBLy`ZGOM&D(!Dyf&qFtco;|o zd=rsxcFX~Maz$#X(le*|!Phfg#2#@lzc4W_2|V?Nsr*0r>UwicrY+ajQpG^^E4Z3pP@E*pOpd)0sSyVX7gOUNTFZ*pK>nuOO;AQw4sOE3P3~Mn@qg zlNz#AAQ0pZ2B55Jb>|&@jZVpI)Q`_E6PO}c$~-eQ{%wG(-h5lPy}4QRgC0JeOkp_j?fOR=0Bz zRX$H~=&2Qo1!x3Y%~?qmgtU(^(0e3>qFS;zW%KM{&g);~)!>2)u!_@0DA_j54!5vF zG@Fz@SW8J;l&b(YrWAj!(r<~TG>W<67l+xCJy>H4eVXy%Be2n++jHVMU|y9@*@IX^ zP6;V88@@XKP2E7l5e}bW%_gn>U{QNlca&#Ts|4nlJa>(N=l%7gUhW~bCNT#(qLrVS zW2>)_-1I8p8gX45RAe?XGFI(PU?P7R0Kjh9x6eANBxEFg3GAfnrar4z7;8+KdY0#a zGB^PqNRM@uIiuuLn_t7xQhYEz%X9KtD?DFzijn_&Q~G_y#qz9Td|K>?TwguXg9l&y zXkNpQ@mEP{`a>80Zq`+6{-X``)yT@fgziJW`{T^6PX{EYYKj`Wv7~QZzis*U7imMS z3H)!6e5fb+lkoXvWDW^T0pM4Q=na9?l>TLZ8>9Ib^2?u2Q6{SPZ=K6a%Y?>NitYmi z#a|fY;yYU{=l-goem77LeM?slo=^FA?z>}hGUIJ~d-xcc6s;;U0MCs7HmlahYb+4{ z)OAV(N&2-e7UKA3EmG2<$cHMgmKnB!MG;HCcKkUcR^~Tp&n9MKm}aHmu9fOw**jN) zGMf8O#OSlu*|8x;$9e5YKwIZs=3Rk!^_xVt{V~H~Eh<_v>9?2$*2j3|T{YK2as4Y& zPnDxw>$W}~DFUb6$mU&Jm=vTdro;yvw47lwv!y>$ zS~nu@G!_r>Zfx@V-WL_&H@;WGEKmaE_6(W~6-Pa!Rp3!*Z~Mm5j0;=~w+2%9RM;o% zucG1dC`p~0mxvJta;lw{Y-WT#@_16?v{CU9+>Pe>iLP=N z^<%H0;OBw07xZZyJ+MXzw`Sd$V8cJ|7ESg&yN2!aj5PRE*x=eS#YVT+x(iQvNmA0> zir15|s8p*5L4I{;`V!;nQa1gTme3kv`yAMZRw${_&g5Kx1^fYU2#nGgb?{KCdj_Gb zd5OM`{_!CvXwsxazXoKmzdIWYn$!jY3pOmbOTfSP{ba>z2&gFe`)|3W#tQe&_illL z-NgsFVfUK>O+OUknDS_8fiW(!EwkI?vs;Yn)|6uT-@h84g3cqmqP&yU5#DWBu9{tF zfBY6wWHLdhmhoIhkSG2-60eGWknynd{yk@A{OE-WbuMNkz8GwG`=-r=K){Rr)BT(t zaLxS;Bs-E64<}vk4!81Xk(v8Qye^mX3*1n zN66XE1xC$D3cc%854TS$xdh0*z#ZVUrXk^Xw@KSE2rS)#kB$vXuj(&rX;AR&2-mlBjKN;1?g^bbvAU zjWIa+x?kBiIyIp8~foD**8zBAAoCNWK-fy@eZh(TGA3QCVSpdXv9wyg^D~! zjW++g!>j}Ss+Nw9JTh!e?qiY7^-PWZoap?mf@fijYn2^=#R)#0eeIy4zHMl@0WderB8RFDcy=qPXZ?Y7~1{;9p|t{ zN4u+EXIA^}5npb}<#I#C)%|hR#*LVEnL)w)Tx%+;Y0sugJ_9Mp!}-mj99Mbu&A!}y zZ2PUQfMAmTuLGX4^X0Zv%0Jl>278xy@c7|Qu@rr`9~ao6inaj6lyKo>0Dm_j~QK;SdXW55gn6@ULDIb5C5fT*>N#;7J=O9JIX(B>2=pmF)F;Fqy@?20sMFL%-8WkzNNx{a=%!$EBORaW2 zzJAofLTIiBK*qiED|m>yJxolbr8ysN@;qh_9BnV33Eb7V`nx3pVo45Pqq#l)z}iy9 z2+!a2L@f0MjV?N`e992`@loXMICm+&ZcV(uaxMCfYd556Fhj%gwU}%XAMMP(c)C2z zCpjV!@O!*LS94<)zO%y)jK~g-jDHO}1F0P}xh#$Mu)P7Scul1XjyU-swW~h_*muop z=6L#dhDiv%GwA#8V0QA6K~Y6s#&W*ZW#6KR7_x6H*xOy2cDUI+u zgJ4ip_s*PFmp)h#*!3VpIQosVBUoZ06+|LIO-KBkG5NNX)!~SQnf-=jvKBh9yb98? zEphxfW@nnb0nLKmQGEYhwH6;?NEv^OE}9@soIwf>l}v12dk5t)|N^ts3FvA1s{SC=QIiTFV>F?8DSBfMXT$;TC05cd{xYLOrY zcigWxVJs`}^}zQImmONVNaMk?&ZBD{WMbMjl4h%F_%rm?=;$nqW&5n57E39P`%%j! zy%zcx)5O5(6=i|z1OMF_KPcbLI8D%rCPyc@MD^m%Ng7?J3bxl1Uk1+RAKrNcy~iNnjgGp*)G`Kn#(EUSjVj2P`8==XBY{q3P}dIrb){U7qj z`Z*$Yyr;TvT3s8|e&{(W)%(>g&0|0M$`&(M_##M&ysWb1qHNd#8}?XbPE}Kzp7q?U z^)uAyp5``k^M=O&MpfBIncx8XQm)UH$IO`uR60+s*CTTTqe=6P=bb4h>Ww!(i~Guv zKN1>Ni+FgQqBx6t4ApY9lv)!eIf4@Iu&R)V+ouR2`y}ipP0!m971`|3JRE(Za}!T3)=CVzEAKjIm480-m;@lH zJ?{^Y+d|ecH$t0ez2>zFiicMLY8e9Kv3~M&vqmhj^j>LQ+DpdY?JcYpdE22Ec1u$U z{#a-@*o;tCD$xXNR`ZrOG2Ye8W}EZ~3|AcBs2uu^U%ucchE)VgvNX3&c*ro`v9v3f zxE9mYGe|PLWqDGVWHeZCO1jt%kHQhL|6E}AfNB_9>(G?-J_|72ywU|4<4dGxmd*0c zR*2#diw+(hRgw}q?WIE-5O8?fcB|--?78bOOoh)gM%-`}? zF74>Z#ZYQP-^XIeDTYqL_%wf)^=x_K-9A|5Vm+(^PFmUM?^}$^EXSebGKPPe^~SmlcZi0Xw;+qcRdR1;b-0$di+QIhVm?~s9c4L?v& z*cS+cnDX56TY7}L?$98G)wWTp z>9kl<<_+qCYD_O;4ao5&zRwh*L%5uCeFC@YRoE1zIQ%~m(M?8JmFcLTU61meS#5Dw-=YUJMZiM#|7`O{uhdGQbm7bIUSaXs z()^tQh^dN~6{sdWo8b#Usv_V$vqk|P!y4b8P)9-2^|Sby|#ZGVNR|M8PLh`$j7 zgyJe&H(lTDyo&ek=03kcFlz5HwI()vW@d;h!0&SD3Qi8fU`+*yO7WCCBt^f^2mv16 zWYA=G-GY&AQ&jQHyl_m+BDo6bpj9t~E2ipevk^eHJQQbIy71~HFY|40@aY1KA~$5M zger!$+Ktg7z*uYIX2I9O`Ko;{DUJJ4+Dn=wSe(jU$cwLxCLnCxF+tVzjF*jgSLeVX zlglZDCFrfJ>Ke=OUQzY94E*A$9B5jar>&xk9N=yee8vyenfH z-QrOiwSEK4<(2Pfu}W)0yYj8Y*VvAb+}sS=m$8%@pOV-G5N>BS6U^oiiFN};JJNc{ z1lZt@mIPuIlcOT(HV4ihk*oSS5>DyMO8)5{`?&*!L68JZFZMoX+kIZ;%9PSz|N%GIYOv z5M1&T4M)A_bVV+X!7ZRN8Sg#Qn-&k5yzCL7JVRffKntxqVC7YRa=PUxNSyAJ{Vc|g zOEjtVQeX)%K2K-C#b>hgs8;nWtJ3kiQ!eYxMnb@+*(UuiDH4s zo&Bi1T<^!qZBI&9R-tI}tWI2dcF20BN9S^_>|IkcqB&7dKvEK+ zM^!N%JC)%@Y!5(aBON37E3Q4}Yi!+KtS!2tI(wtS?l@bSl-y>_vUR!0IBunm_Y>6W zY3WY_S-Fv-P8%EVGFrIvYH;|e>>q(4Xi<8CL(Q#SPZzRyF>=;^CV>xYOaENLcqs!< z=7;9G$_u3rZ@igu3L@rzo%k;->DC`e#iUyK7^tOQE&27eE`vW*B=TbLKyKsH)4`44 z0?HYNy z^;}MIzz}chEKRvZ@dQF(Wst}uK@^p1{kOD66&+{}c~lo*VB}yV?8d-p_Rdcl-2F7G z$xW^{$u)CDf5!g$dBOl13WMO$jLS}P^DwgW8*#h})-oy-6fJk3grN&WF~RXzk=3*m z0%FO@%pMuvP+JiBZrOoA zmtQ_Md~VsRAs0RAq%P4jWm&MI(nBfIdMJknU{?VVrK<0^^!!ZV6Oz@FnK=P7r+E!c zcnD3ijWKKx7=qF+FoT8d$Tr}}nY1x)K%`+l34AZBKowNW@t0huWGozR zPYyIVJ3_<^*R6wfu|B1@6cX?R*w{xaNMhIkb?B^phfMb{NbIG~-<;ExVo!HXsjIV( zFJ9jatsOVwi!Vk=Y^6F+dN{||53qJbhCaY!B5d?#L<7q+gNEyyr9JX|w~&C(MzB*= zdZB4UXO8mfd7_WqKh3V3&;#goCc|lgj{I9asDJEC)jlS-=|CYLhLX@3Tqu?jBfwy| z8q?~~>s*U>_EzER>^_}3xBL;+iJo9zOEd!M!2=+!D8ZR4)r8aZenUJC_xXQigI6L+ z^8pq`;j`pHNHDZOMW`tZP~AE57*;;}grf}n(8_0seiLmGCP#9b+>CE+QwLaU6?sBZ z`OEcUf&~OlJZ*5tFXIZfI4+c1k=5}sqOg@r^=gc_n2ZBV>h52oQ=2RZL)Sc)rrW+- zG+yieE|TOlS!%(Kul9tv>fHGitG^YRQ~bOwOqA(|jF0RK2>_tI4jQyw`=jnR< z=NTXZ6P?oVfM@f&s10b9JUpnVlIiOfcF~J^?#g|=nHilw?b-(~3iG{I0QXgK>dP2F zv)=MHlE?MGTmUMpw=MZf-CH8R)o1@wS7_I*+4YW4+@YbE+|r&uthK| zZwD(o@SaPQqJ)$}50q9Lp8BM0RFR$e*;7mzcgG%#v$!yM^>|E5VKRXEW#B0;IOFd{ zal4nm!UAk9GuG|lFaSpy_Zi?!YQ-VpO9hJc5f}omkc$Gx+RWG+E6ti)9Sn6})j{#- zHl3$X3+J@U-}&l_X6nlQf@}%;I&D~?RHe_*3MV}FC$M?dp%arZ`uJGd<2Hm8N3f7W z7EH0CN<~M6vIsq=FleYW_&ur)(1nCM>TNnal?-oG0Ni=}@ZlJIVzS4~!He2u@r+G%y`}bFlFEr?_NK2p|+;0Em=q_&8juZOcGr z(3{p^E(|BEs`|Z@gv@Bs=PjWK1ahR#VN5=ibX&IuwH$DyholT*wFLYHflKB0gqOjj zJG6LrD>cbfV?-xm+^;nnx4mVDp-*_j{&Hs%(TmS3ZaNq>6gM5)hqi*$mF}5)40J*8 zu|==9S3z`EcBH6f+f03ALzAx=3^2q@s?@BEnXJExTh}g-URj$oG3^pSz~td+Y*yHr3zOo3#j zb1atgv;Fm7EbSOq;r$}Lz^}Nrz1y4*VdZn~1x0kvYwOx;7oJPsBW9j5`CM~T<(6yDTS}Tn;yK(M;5YZHGTbq85H`wfE%Qr!{3|Mh)u+G!JW&rf;`(K%owf zAp-q%=UNZ7DpmaTa!Q{Vg3q&{Acn1CCb3jKNxP{H2g57CnHbJ$$-|Rj+eJ}*l$?BnxJj1+jh~IJhlTCP_ zGsj-M)E?%IM(~Cuqaz$YpRY>j02ZkpIQoiMik>_3!dkC|FF4DZu!#nvXYJ>xl$Y>K z1`SyOqlN-qIc0cVrscD)r&vnsxbh;y8Q5$}={J|DokbNSYF#gX59bmOkq5W?o8dqa zYm83lp+pG`6!EP4k&odAYmZldnYd6DPlahe<|WR+A6k_D-hjWc^>S;)m8X=b{k@xX za9@$;rzru^I^fL_tvfshKTz)Qa0Wzm5Ic+%*`90_?0^f8E&u*Yhs$RYfak4@&6!?Tq?Gz# zN?rC=9V^5EssOw&%V>LEYk6wT3B}CT8@od*Q1SrkEx9`xRrNLCHn=iaAXbW498pV* zY&~lVmG+4ocoPiy#OnwV^{dDGxh$4{#W1s+*FCm2#1&FRuL5mm z9)dP)Q1<1IBvd@sMX?BU`jx5%j?c~qKCG)hELE$V9mvI^rxs4TG>e85r+9w)W{Qvf z9pzeEFwG5%p_P^k(x8yI_ldNg(#;|9^rt_{=)!BLk40akMa=3H(>w}qX+2SHBa+%# zZL+U7k@IhFZ9M8sNK5m#;W0Q<2K=()waW6reK|Jt`-&4(=hGG(k*4h==t;FlJRTfL zZ`n^&aJ3*K4oC5F)3M@8Nu%eUGTY;=RfpuVq7aeZ6R+uo;k;yy&uF-P8b7vDg%^pX z>Y-gF!DRW^@LGTsaed;x9PMe#!XnCA14LK6%xRG+&9%?oqs8;)=7vhXS+k!FTY5)6$MVW2 zINeZouT>#|>vE`C>Kfqduk9-IXKEiGIBW6XPY2@L)KbTkS8`jUWND4&--!U^gQzkQdF8zbVSnr+dn&5S(T zVPHoh*Oaz5Yf@&=o6{&6g5$E%k$(7O=+r?Tof#d=t<404Te(qT;!=2Vx*oUVyXRl{ zm>!d^jS-leVX>$%sv2FQ6t~;&TZ`tZzGl!Lsed6p%a*^T&c~-#N;-V!Dh0tH$ck`_ z)*pE2FZXagQu0}N5?a)OM!KXyj@@|k_Efxgv%ivJgCEcFMnHGRTzk`;cL3vLJPr$h zzV3Y{dYnWPB2?ha3Wd-9VCL0{b7jHQmxEX|9yCPWBkh~PTA;X73^xU?SRzdqMuZ&z0+?QV5Ak7=l;D5``Av1M8Mq&;Q!4f zLdfl~{dL6N!?rct{?7*h|Av3oIRJb2YBP|bTU;~i>gqm?*}fKSZ}*KDaSBPiPCA!?hWX#{sx~ zP29Sx8uu_yjzG+YO3V~183Wdf7TZ=JvD-9eV0^}7{X#H)&2y~13f_G$Vd8uEeoch; zeAnXf9-;xfjKayJZx{M|_n5cc{}`mSF^<0Tp0ax`_9#J^&wT{;!R>*@CErr9!kq`+ zj))V2%%$6UYkK4#-cxZ2cAhGTP(bPP8`68uKBIZs$%XU9-4ky>U+4E0!O1YeTi6pa z_tZ_iyP*Il)d9&ZP}_#*dAob`s;@7Q4By0o|CLpK*rwN>b4%%QtH@(5vhlmlH^9*yU-=LoJ^sfk7o1lKN)(ViFEQBeLydWn%7+FAz44I-BAhFVgDrWX+93UdU&6* zzWJrWSbiQIqL9!ni7W#3@myZKTX)(8N(2YO%{PjIBg7QdluD$ zWa}|yH3*VnqV|LS^N^ch)G?nR8{YC_BGWXQtQ;`XGL+ksL;`tR@9_E+&v7eD8MjfZ z6S2j*hk4H?D`oN|8?IKT>p`0SU+IAH(tpyTG6Vu`zsb2Qot&Ve4Q--p+^T{~Q)G;L zc`6FebS=Ag>V9K9dKJ7w$u-5BaOFCT09%((x9A4|5%Yg z8pw|(uu6d08T+uVYCE=@l++v*nD?sve({IB4Zl?B?1V@&L!p~Fqhr3tVwI7%DWb-; zd=l>KhYFGCuHtW85H?kPQIm4GFMKP`bn6nm~r|t6{Dp?_th#-TlK1K8TX)2JSv0GCa-K~B;D@3%{P-RXVDso z%6+qooD7y=jttkMFuw6Tm)on%#Reiee7!O?>z_b4Bh}cJR?f0iQ<(c@t$J-zesd4IJSE*RSHp0L=F?Sc_bc*H2 z-3pE$@-nYilQ+B?rp7n1jmkF$9m$DUkfX|3lb`FHlT1&a2(5m!Bf}Jw;x&yTaqpR< zqx>Uevzm#AJkrx|9^=7QJ1yIbAuBr1hG(Dc@(*=ZJQk&WjQLe*#NC2*sXH5Mp&Qo} zzYXQM8kcmsr_s11!Aw407os*^XGPsmKy2%QsHNTH+CJN)Q2%$PCbQt#aJ(+A3JLYX zNRYg%iSK~toI~{vn%lQbB!sfH$g4`tDMzlOy~bY$PZ*poR{dqL_0bBL#gkW3*m@>@ zE(}U%X4NNGlD2~x{DzcTond=o9CyTxDLh52vA(_3S@<0cQ-#V%xGBM9Hu=sbBlgPG z2lsLx2Hx$b8MldStYiGc2&_uz543wf=6$fvcUu(^!9(o~dFUevy998O1{|?~Gf9%i zl)^9~Ssn2b$l$&&)y9msZAVpJE?6YNq1Bs23o?NywCcwVQP^f7X_4)7Y5@t3C?+@3 zH?+&h*98#ag750{c0bJiKS2MHE7`XbffM5GFEY&$*_C(bVb>$7EI5hFkV#EadW&ch zRN7u?ez!MIS6P+v1@UV@Fhdk)DM*s?Kp9nG6k`@^;hNY41hPueNXVH4Kb~RJ z$7AB-N}X@>Vmq=Kv#^-QW58qxOBCDcM1SH8^!IC7oKs>Y+m`$hX6iY+ohlgM&jvhG z`O=s#y`WYWV+J$NXmVusU0T7xv^TvajW84@)CF${K$0%pRVv3upN7qERWS6(s@o-b zueD>E+ftW-2WoTKwgftSg|=XpXV`7fBde3C z_g_f67nVFC!!DWapMy@hFR~q3ohde74Y{g&F=IQs;Ku-SaVc5RgG_wAJhnXfLIS}) zJ0Wgt{*qqiSW{KrM0vEh*czQ-tJkcZf8E4nut6!T*_MVd!M=Of**QaDjKSM>2tZ-; z-5=RM!6ceAkOsb(43&`+$ViE-O;nZV-?{5tQe8tybNBKVGW5N4Atiz`Dl)}2)&q?l}hU+5OG+YL*M zhA-Ma&+lz(P;%=;Y!ChqjOtW$ijtkbqmLTm(y(GrV!eg;i3dxF-y8lfpm70?fxgPna~skftYeX8owD@YrQig z*04@);aBi35vZ$PlztPsHxhxE(+e;E5tChlcSidG#Dw>ebtY{J%H2c@cUD^XMDX`x zLXy0veSTT(R8wbtx}%-}i!Fm-`nMTpC9pY_`S|VwiuJLi*J)DnB=>X>5O|8#=d6Co z$%@|n%kV$3T>0=3|IL^44V zkubHryTz#pR(-GEds~HoLf_lh6=tNg{JkWGbcTdDLn4%{a8@O?cAwb^0)ztc^)V|1 z0TN)GE%rS+U?$jbKZQSzbt+rX`zY+-2kTd+av&sa@B_~8lub0l-@O4A86x1{?EML1 zR(@O01+z;GfWRs`#ii(jP>*rDP~)R4#{hvIV#gdllUK~n8Le3JoXN6a41^{PhcM?{3;58<^E9$N|PDzTMT6RG*k zm~w;wkpf0rMOo1Xq#zU;)C=T=s3Ysm)~wuS;F^NE_2`3pk&@u%^w+aP#!c@|XyKMy zDdamNQo-E%b_?7<95V9F*~LHva$jJ}TkzUC!tjEXe$ z4yU7~%P`_MKs*#Y!zDIdEusjnc;>3O6@KI~Ix8rMcx}N*LdOJsw0D@B;mH#!@C>F7 zxJ-dv(bjb@H0EQi9J%R#2=iAzoYKDTH4);Lim!^4mr_i2p0WEKj-vl_s|DQ0PczWj z8en98?Uk9RRyxzgq`lg)4nZ=$L{S6hLooel4>8S(S^k#MrvV0Mce}wS39lDkRFn_W zk7#RtE^d=$`Q-5+TDjIkaP?>qlnm|H|8bH`G7du0*D(fyV2!D0j{U8#%MoY*r^Q$y z_7|QNRr}Zl3?y$94n~ybIij@!*0%2h8Or$WCQ&iuLHO?JvQ)PbH__k&N)l9eoOY6q z``H?-8U+NybogpGymJcJ7G0pOh9AD@_$!si6{=gin^32lAhK%9ey~#DjJfkPM=yQ! zGp@Sk>@Yp_vpRrCDc_UU?TR0!3Q1c@S^YWj1rwJQ6ozWS@07x&Qdz=6G%|gMR(Kf% zz2#E8NuhZ6wnoF`DmKS(P+`ktqy@UR^r#9MZmat;!;h&(TQe#@j6U$iUeZY-BvfH< zK#QujXopI(t^j4Dop)gW2VEX*r52@svScO8>zeVN+O$30CyTnS@YS zjGm23c^oW&i}&<`pO-KnmrxCYSp}JNr)o-#m-^O8TJ}{11jSdG`!ivUds2prBH@oi zoN&Z`?xv#GMPzjfp@|de>AWWsRT%X)-iFeISJ0gZ0`K3~A3~)F1Bt7Hy*)yXtEeFw z^wNz2vc4t|CfG+i8h#7BT$YYo+&LC1ghX&Vg<2?8uffuV%r!L=S+n8ZjEIqNxg+m< z?ngl&oyl+Zf%Cjve`ycz)@vt0aMz~TOdl1{< za#8r-5q~NqZ8+gcJi$1Uy+LFHliQGr)^tCjvgd;)zac4EZg^a@x3%d03bAa7oNPH% z53#V{QK@w}H_t4ZU~73AY{(dd*)hLrY(*bz%Z=n|t0CNm@o)Vk`cIN^P$~lxFe4Z1 zwEXP=MLi1Vc5|^tE4?{ir zL$)6i>=X}CQOCXs{quEKW1kl+;*;_Rm;3)w3GkxYhjX*pfNpbAVZR2DKyr#CMwp*( z)PuKCQ0%j<)iTTml$yKd(u5%_mztM`c-VwbQfnoOd!4HjV7UUNlGt)%2FaoY;+uTw zkdimOs9!L3+|36%lvIKR=%+2$eU3fHjjEi&zn<&LbU(nzzZ4x$J{4llZ0||W^>+zd zygv}oxa1EY|2-V7I z30l^?7W7+f$%9lW>MNr6rXekODw6x~R0|&ds}2yyk=jQ_64x!iM1nuIkSLRAR_{O- z_F{Q#Ts|@Sw@GVAM+Q`+WW=0RiIRcJqM@qAG@10|#E5lnAh&pbF-ItcOj)(HfaCru&<3x=-d{-lICG>#bE+tyQ(^ci+$R&;?949AaXkQ>O_yD%3%TVWN?vanBYrL>O(-jPVd!X^U`ds z%Ds$JS{H-oS&WxLCktFi-`<*G6*f*{=eZQj?2DPjMbsD=`-$L3 zfG?C)Q>ARSC8%~y58ddg5ft>Z79EdFe|vW`;65C$ud;>gz)9zBhRpZn!_ziuV=z_h zs@{%{qbvyGW@y&K%>-7zqO3@Ljw!RtfJWVCJ}b#Z&zj>%MykIf1YpW1hp3DGnE49Y zWc!@X!1h>3Z_R2XUBGxTqM-DmOXz0_lD)k)#_n|2WOw5r08hi)mUu!wLB;z_f5y{N zv$(wyz0#Uo53!hA?}S#cR~-iXLFd^PSL7}3g5^gM=|t^p;GF#2iztjJGWqGHc8r8bKk+ierq7qnbqR8_v;Kz8A z2|}6w#o^(wS1sW;Wx|NQ@K5g)<81JPWxx6f0!lLdd?TT-a6;`W8rPS92gAE6*Iy{d zKds_{Kp0mETbUSKJtQ+&Rn9R+R>cijpcjvmf)clD-;3TX{&(;$r@DV%%~Lz3xmL_i zaj7v0En>#1(cm&lo@iErh(W#^>jg|Nvkl%#Tw<3Y%b2@iaQ~`!XGL7dKB+#zTdI4X zBx$|2MVsvT=@nwlFIv0{V`00TPE>7C)m$dQTxsCjtTV2MEL&t0lHv&=?V`*Z2C#ES ze?n}278UDX3O=t>DY-XxjW1hZaYx zw7;`d!Q@$~!lRlPMd0F}*7E}pO92|qkD$C-p0uX&p^SM;nONiA%!shrSK+aJm<2U+ zwEg3k5L=0+$EO_;s$=@%13p)|Prv1NI)YRgZ3lj~>uE=YfeUTAm)u?NCyn*Z+IAkd ztwxtspLY`~XS}nCcyt-aNf_1<^q_C#f+*NKQ?Igl!mq)W?=ECX+$ipSso3FjHUoHh zUGJ_AgcjC1I!GsIY5gvlWY$gI?#2H5T%tY7Y1}XT>$ctHJBio5yiu$IPhrUHk3ek% zSqHBCfs1&lZE|I^HIBg$yi^_79t_*;-UAX;3h~{Z3;~rgM%2ZH!gWL5(~Le*{@Y~Z zU5i!D($u)jo%9R)KlkLjtlUGRfLqfDH+U*^#N@pb0nUB_^l!~|0*6xU)p|}nuX%gg zt+~Rs+G?bi|2pZgmGEd8GCKQ*FhuQ{CVta_Z<1gSx&9b=m!j|c!m+mV4>CaHMQD4m zx7QxR#>IVOVE^t02#G-8jrTnhb-OY4P6!s!^6#wY`mC z&-ouce3ozjE+#i%Nv>QA0xLq+BbdXWDBkNHRb6&{#(Ved2>WcfoU*;WMeg_RLWY#* z%Dd=CHrM)8pZPpn&);hsR#VGFiCfkUv#+B<@yTgn63hJO*m?ApfmJspb8|QxP5)W zp2Vm}-fCt4K`(=T-44ld?VxA1Tt6Vw!j=rjMj)R<%wM(&;^Gjg7fvEHB?z~Dx3}<6 zVST*-{O#1ic_%by4t>5N{4q96H^akRVU+?GeFtv_@-706BRyGtGUw@wn2J5NjGVa0 zGneQUoF;ENS8&2@uSo{? z(cLs{1le?(A0CKzgxv*iXyft~(V&-EjIA?4nb@MCv|k*wCtX|=b+ke3`XSnc1xMa6 zRg=OS#2wW|a;<>%I2%X%Fe=H+H(G94Nx?CqM9pv-`rptDb3i0Q@Q`{UJ34TKknR3hEY*QK~nG=CR5riC5G834EgoR>;Voe&K_0;1f- zDSntS+de`yMzGFk0ss<{XkPL<6UyLZN!Ijd2SUI?PkLLmtSL5=Pd>-Qf+MV{XSWxW z@T!ixTz<}8i`P!YYDbf~o*U1HqhMNdglm#2I)4*HWKoEDSNv>_VU|Y{&ec;y z9QZEupB0<7Xk8IgwZEy-n=DYJ{$mnA25!6AbY9iP#MMCUj%E}kRhN3iA#1QzoODvU zG`oT|nk>SbBPL432ai+MP<0<= zK4GALZr13Ci=Psd&r<$knz9OKKcjS}m#|Rot^`uzV~is|*7&MFP8y|WTAkdWF|(GY z)ew6L+`vgqG32{7ERY5;C3x>TRoVJ8{dU8kT(VAK;rt(!JygfEdAouSxmx$)B!L`X zloe>534h^Sa6PUWwQJE|Xr#7trFRri&nj2vZB7iwuWoSO)uc6%)g{Y2t&(ctN{z5p zVEX*QSk)#)__VOC%^2|Fgv@shto+)T}yr( zM*}?IIyJ=j1|hbpkVZ;NPsHoo!v)u~W7rd+9A(&6KW8@!P}P|L$(G>4g=YqgDC-ey3qp>)^Iw!iA>zA`-T*Hr?Y5r zDhetb;SNG5x@b-u4*}FQwCQs6d-Z^+Ve;~&1*t?pbxKfjjZb^XF%Q;UPqdb-x#V70 z0c>sn^^l)%@UVGJ-{9&fIp^l@_*ty7`3XASU`-99I4{P8k7!p%llI|82~Fr+Hvm9B<}|_AYzZ&yZ5L+7gflRU#uK!vM=M# z>~q|;YqObWA>(h)p3R}3eH>f6_TS%Oz2v&^^NpD!PD?UT z8xuP@MU@o#_Qh5O#ft zRXusEzi9?WluQd_Sm_aphvSF2ntD+0bVwA#UF)8T>dvz6z*2~&+;zdA7L38KImFnS z_`<|b{I^sxVf+ye#8jKJqTKFQo+P@zRHlb!dd9P9BJb@%l;kDYH-o-e9J$3hv3ISg%8@V{8rEHQe(ds^gAS+JnM2XIydx7X7*12=c`70b zs7#R=EGD<7ioUnakmOLUZu-441LAAdmj`ET3t;on-giJ3D@bEkSG83T!NtT|AC>z! z3x>r5rWsWQg+un{Z15q|b*u4gGK!=1;^%QGL0y9ruJxRks%mp8+pyYW&5~RZEL!HJ zS9PiCwy&KZw;0)(o6!&=y0NiRhMoB}&yFNZaaCe5owzB7nq5lQL%ffrhoVbmHk{_7 z42zGIgJu}nR1WjZQ+}I?+yGBJb~8FRyy&CPhnyO9bbP+G34>i(h_S}K_FfY{-4cYe zK6&*)N56L=+mBPOMMqb|zLBn#tf$BO$J}2WoWtJckh_l1d3GT?1sUDaAVBy!I)51n zWBWe6g^vlvzCI16MFQ>4fRB}=z%}HIt~%kmn@F>5&k%?Kzxq}`hS!>K&ge(uy?J)h z*lk@co3{5iKbi}HZePHUPicgpKu_D9kW7)pq|EGZsz`Wki2u75JO_Sb3gUkjVlN1A zt;VVjs{xxr%eUJl)0r_@O&ZG`?P2E-Vn! zm^?m+{Gui>EE2};71L?|;WffA(#GA?|H)|Y-u$bg>V=YJ#VM5fw3ii%uGluFF&rQp4!^pi?{YjQ0OPz0~^ z$I%XKbkb-wnzl6$!rVm*3MrCgty<)Nk!J%cAw6M{zZ3^-^__Gv}f0gNT%tD8c$sD=8?*i?lEwS?* zwv`kB$9F;7A-uwsF@@E->!_A6f-uCq<7}LD`6sY&?{xP=nK$4NT`@b-7A-(ELxA^y zn#E_A0`)vnL}6&rP6q&>l|241Jdf z{MW0`WR#-X5t1+?`RStz}_`+oAqB!1E=bkWlKwcaLF#@z^X62nCEBrem`Eg4~X^% zTg9TdghE&;PM;wEVg%1vtZ4OCH;FTx!8Hgmx3gxM9)%)XI9{>tRx|cun^9*iNR!<_ zYm=2yc#?MSb|R1(a{T@T-ZwY3@*t%MA@k{65S4g)#~B&x@jn6WMyY&muoXz#1Zzla z1ftiu7clhbY9etn0)}rVMyZ>dkbxHRt zMh80C1;!h<7daS?&*+rEM+s}TCpoy+T+S7DucT_mJnwt-8PJw7F2v`Gl#vxvL2x;( z1)7P*VWW*lv>m!!&!0*SDhN~dk4#dW2_gH$Sm$!{TFR{V4k_O%`B@1hj8uBZJhyu$ z=d*8r`S;Lq4RVI{4-^7(I0$e8aF%I`Mt|e&cB+OK4$|@BJ&jjx6wUs{L29VD7h`a4 ze#VHfpZs?$4u!C0s{b*f{{TwlviQQe6kM2|t4yDxXsbQxf2DDIN zt*{Tf-9q9+-#uEc;qf*+t#hG~*$u?U$Y%j6umj#th+Q(SoAA!YHjPHB3GVJbzPQ5ZuiBuM8iilgm0xdlNsuNF?*q z`skNfXC;ucY~+e6w&`j^w#C?p!T}z@mUb#hDrV+LI{r10 za#$PDovDM%25#Kn#rz_6x?pY5`r|G%U3=Ow-X&3Zy}@{ivmT$*bitd7A}#boAxBbm zL|K%Nwg>4s0Ehml8CHvN@7MZ^aeBQz`sD#+HkbPnmiW1)^PQf4y7!m4Bdq)zvlK#x zm7sn{_UlS&92_GEhr>ai^#*IaH83meMY|PUtDV>-&XL}Jri!CtqokB#$BE4jowuCJ zii$gf{+CHxWi=c#70)z*E)urvR#QF zafzvT?(^qO5P}Y)j0kTF_M9hV=$T%146_a8!W?fCL^C*xDQ*LP))LiuoQdd?rG&3d z&Hau8XA1Alm0A#oQ8yf**z4xD6lSR&|m28}wC&fGk6- z{k*)NM#h4boA1P8B%0m(TSIkbb7ic!4JxG%_XwpufUWlx{_r1_dxib?vR|fClqAPz z#l=)5rBAH&N-`{uX%77aHM@dClV>&@fUcF$8DhQp((kwafrWuSgixTy+^6U-i!H65z>XAz9>QE`nq%e$q*93CUBPu(yGWo>yM!XWF=_t?hj!Rv$*S zcQ>}Svd2*k)z^LXdySKBsOL$^V)L9p9rm02Mh{AD*f>wE|5anDP*hv8r?LtEN1P^a zs#lXtkxOP_(vg~XFQ#G8N#4Q?O9ir*{HBAxkoiHw9@_94rX4|!*MZ}W5v5;ydw=BU zmF-}{jf0zP4%PQ+?%mttAf!D|wTpW!fiyJ~`U2d{s15CqroWQbTB^x|B@Jyuh&A5+ zSOXR6EwyXS+bisIBXofPYE4e9F@jm;*56lGP&lUAJj&$1Wz^E%k#us0Z{i2x1`9^x3c%Rz|v z^MVr<1%<$n3GI803Pf&s^HMeJ(c10wz{O4&fFi+j2{6ITB@otXrhYVW*za2%|`TnBQ$_!0LU!J*dMRAY-RVpwxIw zIp`qRhIP^j6YfgB10T?}9nzq!sW!*(AXd})gXJ)~0NahA_xxY|c>ZcxZbjAGu*l z5+t6i%<}i0DDSbJ@7Y!ce$ab{8kwELwjn!3JiS{4m}@Co}y-pVyQ@1t=y-WP&c@ZwY)u(Xk+nxS&OP*&Qhr(DVS!mh9<&r}x@DU@SLo6}aT z+Y2&#DT>qkGYCHum`nPf3t7V0!;;ybFspIA5vDog-Kpv7wa(-A_vb(wu3xzFn=Q0X zMv$F&uWXa-gwfTTr7#;S=&9E;X2+jp;E+r00g)s?NL)*fxgM`9)|tp(ytaKNfj zcrCCVhZNf%j~z^FtVsIr^BCEX#XB8OJh@Frdhd(XAfm-aGr5iKMm}hv@|xk4&Cq*W z_`!`Yos#dHz6P!ayGO_CCLp)1(S7STd7Lb6Wa919;IB5gH+q$~=h{~RJo-ZTo!n#J zt)~tZ8snhzQsiW_)Tz!M)B5I6q)wQdm?SQk#REb8V1mHAe>k-d*UlPtW(|s)J$Oz4nbT09y_hf%t*H#!m=BicZ^{6Dk>tPKPnMG0* zI3Cs3e?EF)s~Xrb=f#u3de}a2cCI(0_}pu?W|Y@yc8#p3E2?PyNR#IG4xuxmnX#T% ztbE8VdZo#9njEC*>KZFv5IHuQR;YaVCHR1W_xxbHS`F0ERk|8DC(W5}#2OT>W!XVp zBOZ)6z|2rbzn{ltS8r9nTCsg5SE(gYoxAGoq}k}SGR%BFKiWaKnETq;M(g5zn4vOS zB=d4WPPZemfm4&;l&$3kTcFiBX|cwzRpIvI0JC$BK9;R7==dzJK+DSb*95z_*{0&A zeKFPx%#rJDE>ME6Px4Am*CT41CydI{bNpKcnT-TzV^yessLK$6!A@Gs`Bn)GDDQ(x z`S;IZgy~wIlSg66hh)m)t-jA%oxy^j=Ly?<^INUsTDALd@)SO5+s(;x862C}oNPhy zrbf3Vn?^5D3{JP%BWdna{0!sIr- zLS5D-HvZnj2HY99T`5P6lHBe3txb!3k#+IXC5#``sngAie*RvI8cS+Q>MOIvV*N#~ zYky>NR++giJd`%{v6r0-_`VG<`MwQ5x5?cai%RV~TW6w9z66015<%3rI~5B+Qh~eV z&%q>1OF80|M+8QjsCHa&No?;y{{W#9F4UhQAOH56+zk18tJB{Uf(0AYvC35&r-}Rn zxihOP+kd`v@=R*O%g?_tG7iUGQU~}8id62bJI53{N9wb=6aWQqe@QM{DTJwx1ACuf zdX*MAIjyisiU}#qV5uaj21Tnt=bC#2I5BX#{Y2oAJ3*u5JrPs3=ln<3uin(7cryKc z0pHlXhxV5>M2wl4IdLH;_K3cGd>p;HK2nVc40Ix?oM~M8``YBokge0_)vdsUQo;5< zzB&@>cu}RFBE3_;H;PXQF-RiSBp(j41P-Q-4qDv5?c|=!jKR~Al?KkueJEVn70aSR zGI7luZ~=j_mKS*S zII*x6h)Q#m`X062Ez5&xamx66a$+8RBOq{8P`SI3eSgChVk)Vf_k%ve$+p^YP{;KV z8A?btCtQQQLOUj)Snd6A7r#+SYg6t672hqBe);=cJ>e*tLtPO)8f8N%PP(b=n02Q97S8s(2Ck>bkwda4LOf2G@wfK}JDm$*9PodT&kw=1TwBzw}b z<4a@%fWohu{@IxD_%|0I(^1WE5fT5S*eCJ#?nA{L;3;{8Gwz zH*@O2$u1~O?yy1@@Z9ZC0KaaC4bRg~f00w_M?11VdK-mbpcp1}PUANZ7->_M{YQm4!_*_Z1Y{)&f!|s_n4VD6_P*I9>nQ-jul%$ z81dRGHU8`jkyzo$O3;LBCQmSs_S@+uU#z=Kb!m7ldBYPs$gE=-|AVw61$k0I z?iSEC<_gYM15$cPAlN6vyGdNC^)7g?TPW4zdiSbioa>W-kd$hogKf16-8T3${+J+y z5YAcy)X5}PRvRnt-q~4+=UVV0w&1y>fJl1l1>v{*$fcQ*lL0w1@44a-cP5yTQsMd4jjz0 zE~{XGr467+fpybrB_yXqYyK3mOoB7LkCNJz_5wyfD39@*+70H3VW@?J3rBf*8g7&BB5!AxcjhCr$*g76xC z1uUiG5-}ov>;L|;x{w!Zs=*LTwXZRjCCk@h(V1RAD$ zLw67fvUY{PSTGY6Z97Nq&6a#emj+_DyKXc2`Ix-#L5j6X_;7mJ;Mk(Ja`cxz)`lXp zgkcU@{>8SG&ZT9LM8be2&f}6%@qe;;d;0Iw)l+^Lv)1VddpTEl0rNFCtr`letl)`8 zHWxUd&5H+t>$WM>oHf=V3<&!qg*g-9ySXyExw-_r)|0_lESdGXJz8B8^rkREqs@8< zXhsvUt{U-i%VSA3xGi3KNI*=`_Kt34bmG8CucCw%Y26Iv${M@hs1^M^9BXTO=&q7OA4`M(P75{PG#0bK_F5sc8Qq z(yvw91#!~#3K4hmiyMp1i&ml`LYk>4>#NdR71`bA#-UJWRNQt@k=Cb+8fC~;7{HJT zKmSv(JAr6`aAm0ud`Lg}VO(T(QXl-NN2t!2Lq#aK3@#*PzflmRCzzd~DP(K6g|p3> zzZk8mTT?1zdy=7`rG7~kDACxCqAcF*TB~~PNxl>$qgx;BHj{FXoVNQ-m3L7qfu_{(#>qBX-SgsZE z)dgBS)feBXZ(vl#kPi2WSIzb~SbMeE)6Ay%MB6h#8x^Ig;otivR|KVQ%yZN)7X?c; zMvn;gbCoGedX&aNRyHqAJ*`TS*L}8-?LrenfM-y72WF>5R{r*R$gWV(O(6 zUZQ!A6aHTAZ#lzWE4%GCT{W;Kf&fIX#X#F7b$6dz1j%haL~F2b;T;%=e7NpTe=F+J zwumkztC7Z~tUN4k(MBkVVQ5cai>_yKtF!;C>nnQV?(vsgN*f0s&*)mIpCefxXpL?X zIg%+cY^lWyP$Yz%BLsaBD*poAG}n6){14dI0+TP<@T@wFdQWw_11>?MNYSypudv#+ zzG?y~v6D4!O8L9#u1|E$T$h_cdY1V2?4m%B{&RVh4PCSIXPMJpZwqA``0nV zBn5yA|6>iNG9Fm6RJzt)nt-ZAu~Ln#Bq8p*)6FS7R-D+|?*z^&XlE+HSv%>QFtq5@ zRG<<;W3%Cs1uw9{{vlF+U$o6r4y2&f(1QD_G7a8_59||OIe-Q*8p(?>3|Tmo^#{f0 z$`!fu)hre=3!Phe zx7SEWqc%fHyj^OITBi$Bw5d>Oz><+q9WZ=)KW9Z-JKxRmtQ~wlMOFVfGxx+AG7uD! z&Zu(GG6j6Dv{u~1$N-DNQjNz3y<`#&DZN6lL=Z(ujA(@{l`k&kEb8KpKT;4SPBZ8! z74OV2WLn0ef!~d{QxAW|S|a#XXbkd8^Z8t})68AffYu9)dY597Rvy)L_n1snHP1sr zU&~zjm<^%moPy!a2GJ@gA_(`y;Y!BYm>K~ds+Bw_$VR&FfqlRRv4?J?a zJ#U)Y>jvt|A1Ph$Y9U!m+Ho9o4EYg#)Z(~-(f)o$Th1mg&f#aRuGA zJ}ZGymGEI9VaWWxf_-Pw-W>qv!zyb8m?2s+&ghaVY#s8L4%7P7KP?P+5743nN*aZ{ zT5pz-pM{y?t`9CPnnZ4~KY#2%EN6QMUiVc|0k5K|ickoRzrf zQ=lPj^wqJ6)~gW3Q6R7`U0$%A`$zL!1#OxH=ey(q5pxcc=;HMFEp5 z7@CW$=*uq)KM2fiYsZW>8?)*>0B z!Go|bUj=v&n>hRDE~8D=zEtAUqNBYDooq~))PC7xWfyI-zkBl z>~#IR`zKCS8b{<5m^s$_sBkf6n(F7Kyynux@Tw2MVWqVwa}_|bv4P9TKjSg{+o>Z7 zF|$hpmfxJq0#q&fD(rA!V){_GCkcd<8VuVYX&srvlub?cJPJVV)#FNsn4XK}>}|)- z{yvSG$DyoVFz8QgzDEa=kDV3vDBN6LegCQvt&`yYg}uWb%C-biaawplXo4AlAQ z1JMc@x$V;3rN-utsndNE6y}i7Q?hj+GM>SNgf1qidf-C4%1ii-5rmtiL@y6$(ON@t zT|Z!^k6IYP59hG=%>4Xa8$f==%P>M(C>k9jras7N&)+f#&Nen^)IY#sso=+Cdw?Wu z073a4vwINmU!nyGitsZl)#t%83wOeRxqc92_(n-g6{~JnPe_;^!kg17hDTisrVZSj z`bTtm2V}?e<&7=J1+(GWUzbt#8fA+{abtwXI-j4rXsJUIzIPIAb*?}(1pOVBl^#%a zCuOBZsLWXMKjNc{2%j|hhFHKZSx?t{_W|x@bN>`KyNMP>lSK)^Q{*6Lr&QQw0r)BOfZm7q= zf^a?Mb4Pmxn5QHfoMF0WOGG=O{Nt*pJ13@WpZ9xPmtt;Jd+l=M}&IYn=#XTfC2WVM<=|eEPqs}k>5Zj@Qy3t4~^-EHIvj^9eUG_MT858 z5C8W^A z*)x~Wm6lm%0=LOxxcz!Ts~Tu?uro~So7Q0~YwrY--i&qZ)T_?D#<~elakOdn`~-_7 zbZak{vKncv<_q?NM_VB-dmV!f{$KLr4i-xO4=Upal+x zpKlaXM1=D2ZkFYWfBb`FsMZmSIvs4+n{Nz~MTCTe^41HUCx(KQcqW5`gTpl7{=pu% z|AsxrwB2j|ffxn(?Y8Ca^Jr(4?Rgar)c?8<=+B}5JMFk`;vD0@+Q%8!?*yeh2zB=| zr_o4_<%7jE_z0+nI_Addu>4{h*k2IQc)X)Nmvs~=kJFRbgLH>G4LYR9-x_);2`P<` zTy7<#gvq~lj0^R9#V&_IjKDRk_1bfNPawirxEZ z4%zC&1uwor9xXfg0>@Q)|_3p zM!fnwNa8`r0W(=QC#O+yNwV*3M~q)!?L2XP&7 zpq<_EtaRaCTv3|IP+eYK+B{qmd$W)d$!LxiTce}*PpWf2hJTwsj=)8idZ0@W!AVRZ z_?tX+-Rx&6_XHv=o-tcK;Kp&3y$}glU=PMU1L?xhY(Kx-ew!Ej|4YW9e(RhJF;{D@ zpxs`}57P&r?MGb?zPUmWUh~!`^W8%31W`zR=Hhls^KYl$V|4STnjFWEKxS|b@Ldyc zS1;#%TlCtVR96VAp1f7P%;EZTVI+K9q^x{|KHBPYc>PyYsdfBfPS0$N>f2rR^i;R* zwk4!9P$H1xin?p_RQ4CFt`fMhRCHVsa04^}MJ9LZ_-4r^)T44aN#ZWT*#p#$2Bw$g z@M^CMKN9uT0hU+kkt0X3&iX8wabqhhy|)r4*Z-KiX_J$DP~9iuPKKt zU*VsgN@a)|k3s=>El}B{-RIe5RbF*gNGe^eF~0|!u~1delcFVsz009do37ow-q}+{ z5{rYE2K^ehIqG{hbBpWB-r|m~?bW*h)F_ja=8C%F>+<5&wR41YZak-H*Kz_e(vNY1 zd5aB;2+IKuGs41;RlBqmp5mK_qYOss|;^O$oI`_^PKuF)VO$gI``S8oKykkmNtqoz$ zw6Q>ODO`Wu+F$*}sv5|$JZ_tyoW_G&zR%T>ch5Q7`pL&q5!*!X-456DIA=cvK%Us5 z^H>&=KJ4e{bi2q(ZwPy^LYYBf;Y(-Y2 z{9aay3l25^B2lLo#9d*Cur1xSEKQe{F;*o+4HFnSm|IqXV_f(XNNfx?)2pY4?Zz$g zu%z}UfOAKRAw959ldX=#=i!mLg(Jhd%cJvu6MyX1CVB=4CiR4U`V!1%=pWqjGW&@M zKzL|ksc|K$2J)6*2$uA6n#ER6!$BV0E8c5;02Y>mU%= zblH1sMP+4ug=Fe3msFE=>1-zS6+PwsI6f)@ z)PB&K9;T?pF|(*+oIry#WOv@ve!A`B>i87V;%kr5Urxj-=k^F>CL|<8SIk7r$^ALz z1P{=XXQA8VZlj-9<+8T=w0R_j!om4?KiM<=wf_A3PiCVX%~N!RPz(@^tx&~EF0fVD zTkWkjG;O=AMA3oltmj`UL|BgqJvEnt{Zayq=AP}_rnCV12dtiA0cSTT$i@tu+GeEiiG;bND5jZ0q0xOos3^N78?_YWftbx&8@+3FFG?* zIjiXf&07)J8&dy21o@932u}Y0mmo;>4-0L>(b_vn*^THY%Tl2;DcX;VT;;6V=8Ka2 z>&aH*Ony%sfS(^|(ttPK`;}j9>3-dxMz&5VIf=mq9b;N|=;B@BEzP*}->EkvZj#h! z$g4&Ka=M+-W0Xg^+VSDNs4R@8k7+3E9$~R(ZLO9C;*|z8_Rq^qcszfhs?~ouC<7k3 zyq#WA=ylhFpR7uS)+}iCJ-69)OK|&*u8N#>Mkab+o2W^rEZ!Q4$xq;{(F`s*q0gGG z`UwGZ_RhV(o7R-DJ@oY-!1<+zK{jx9_AW|?$7Kc<6CQGp&?~;IK^Bj=66=97ISt4CKxXk2z<2z3YCS~^=Hmp1g97;*3Wysk zMoR6;@c-JWBje}{opO}r8TMf^IbH%A!vgKAoNp$9Kr>g-p2fl700$P6Y-(h{DhZF4 z{&~})JzBs|T_=SwMYID84kRn$WiVysBVRZMvFh*+OYI&-yGWqYKl2df}8FRcn z1YqV_1`|$vR!zk7?(8!#YYE1@2ud&^fAy#@A}Nsl3S%-euGv-?&yKykFs3LpO<{@Zw_@S7^Dz4I8Q0yT+a8$E@K$z_J}F*OnEKU_Gc0o?YQs zY(!?~y_3oatD%{ZL1D~9A|b=Bx=3flK!FI{8#!%IRTkV3&^#P_Ph2^SNfhAF)S6j6a!U}}8(X)l^8gO!O zJ@J5z!P;5?SEJdIb&%$Ya{#*cA{B_STV0UZ6L`pPyIqt5Gz>m z_O%=C{?FzzsjGmCyC)XPfu7MCsgQMcZn04kPbIU3WmXU`Eo}*SVdYji*aRHb>5@ z;~G)6PY#9n3@|MzWGyTn69j()b$lf^9>&oC@g^=Chx!Xtt~B=(E}X1Tf7JgMLhuXI z3SdV?#wA8$eir(dFNmp(d_NnAfAE>Q6VbeFaH}myY8P_78KDHfv2jI4$kwE!KR4d@ zgk2G!?S)o>*053{@~LjXR#re^RjA%adhdqnJVrUr9a9Y|lJ9e<*%}sb5VG#1y zahT9YdJhSZWy40oXz7UL2qX~tIpIe4%04Tgz)w35of+td%MXn2p&sCDWea5xY_|ys zRYD!Wd$s0%%qT-_0SMrduQoqE;{%aVQGw9I&*88eJmb1kzl#ip;(E0|APg1O?Eh@4 zqDKK51xT}oPS9xlg~@Vc0>F?1D!2Lt-a3LWb#X`wjfE{4p0UIP<%V`dTvyENdk^(+ zYZvB$VB>vB!F0d4aBjYj_{$yZ72X|nBmXBMsT5|S{VN2pEdD(n6IQkJRqP^LbQAn{ zFLZ~rz`UOuSniSjE>qSrYkxfa<`xHRKbI=A7@04ieKv5Ctt=^Xi8jhJdcOTMt}4H*2m*SMUpzYZetK{X2HZ0xNJFmoVdZ zbX~{$&U=KpSa~#=LY8utco94+G7ojuPx-7xC(AVj6>Vf=xqQ?00GHysQH@nR?3j%^JU3s0yz^|+Ll*y-)v}_Z4U>aAEm4kb*QUww@9`$PD^$m6#&`liDl7kdX8MC` zNsN3!;TkA3x#jo`h{NnB_YHDn-F3m$bj zJR2x>2Z+$@il4lltn8r97?Hb~oIz0NPo10(CUpps^gp%{Y8IjAB%f$IqXOD5wrgwM zxAZOTnxuyU+k}o9+i{? zQVM+WD*)mDslZ4L9aE3n?5Ve&9~^KUs(R2iO=PKqv-*?jS$WN(h5mkRjd@HsRM*dVmlFNK0Ry<)q7Q89@^a?^>PM!d6`yJ!vaT30^jmc#QJS-2M2h zg8np@x#K=j5$$5l^l+=GJrhKv8o?vqbKgrzlR1g`53Pcld2wjepOUyyd4B^ls(p@( zZ;M)Fh;PWi=Q{qV9~3^gN&%+B*_+cLO-G?J_bj5p7)eF4)u^`Slb*Y1)1=z%^Nj4~ z-{pb4rJRjY**PGpHZy!!LVmvAkx7oj2$U5&P%9;OmokF09p+tAFK8bf4MO5u#6hTUv+X1$pKPU-Z zxFGE9gJM%VxaL%>PSR7yNmQpjpQ|u~3_xrVw@kC~r3I^NAFzlKY0!KeB;8A8b!(W- z7rrZ<3QQ=$Vau=0E18v^Q-*Sd4QmCC?RMiYvm#D`;W2Dm=69WRW@mqpWl~jjmwTwi2t6n+75a=R2Ns}vVr~cbF{R zSY9dFcDaAj+CNpH>E2js(pC&3M3QWICP(LPajRFXdE@{lGmQZIt}Q-_HjfnY^-#W_ z4;Bi3gF;-R1HKuq%ghq$8Igj-Kir#B0-cHpP3d@}sucUpbo5#;dbcLn@GEcMw69*< z@S~MbWhyjdZXe_C;nE~ktaN04{Q##wba^MA0hjd$$^5WBOPB;a2>7B+b@s^I2|Hc$ z#Q$d}*<`JHI(x0LOS{zr7C{F@^;as|#6siLj*CdCG7<9LGD0g{R&@*`D%Kls3PWP_ zU$cT7zr-KuV&zYH0bt4Z;dbMLJ?ptPWhcJc9C*B5n@JpYv15B7T)a#6?1UReuvK^t z==0`MQoeCflgm=)r>&VWURZ~&&AgB9ODBoUKr30ORNHbV7uStly=B%(W@?zh zwJCg|_5TpeiJiYA7!xG%kQPQd|CV6JYyXL0a0dTPMr_-gx(kE;;3^d@LRCPjb>y9~ z=7WfamsxqgJ|_z_GWs1+-Hxw5Ty{f<0zd;&>=9 z<$Dnya#Ot6*-c|~J#&=;x>4$)!AUtT8sgqaCcRoUU(OAUaLjJLJF{|K@8DlyI}f)Y zZ5uF8EzBfJ?g6oX3a{qY$H22T28vBm$oAEo@5NU4x40h+s4Buu5u-UWnharmG57L3? XiOI=(SH+P(0Q}{QaCfBJ2a*2+{3E69 diff --git a/localization/autoware_ekf_localizer/src/diagnostics.cpp b/localization/autoware_ekf_localizer/src/diagnostics.cpp index a1af492487fe4..45468abf72d6c 100644 --- a/localization/autoware_ekf_localizer/src/diagnostics.cpp +++ b/localization/autoware_ekf_localizer/src/diagnostics.cpp @@ -41,6 +41,25 @@ diagnostic_msgs::msg::DiagnosticStatus check_process_activated(const bool is_act return stat; } +diagnostic_msgs::msg::DiagnosticStatus check_set_initialpose(const bool is_set_initialpose) +{ + diagnostic_msgs::msg::DiagnosticStatus stat; + + diagnostic_msgs::msg::KeyValue key_value; + key_value.key = "is_set_initialpose"; + key_value.value = is_set_initialpose ? "True" : "False"; + stat.values.push_back(key_value); + + stat.level = diagnostic_msgs::msg::DiagnosticStatus::OK; + stat.message = "OK"; + if (!is_set_initialpose) { + stat.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + stat.message = "[WARN]initial pose is not set"; + } + + return stat; +} + diagnostic_msgs::msg::DiagnosticStatus check_measurement_updated( const std::string & measurement_type, const size_t no_update_count, const size_t no_update_count_threshold_warn, const size_t no_update_count_threshold_error) diff --git a/localization/autoware_ekf_localizer/src/ekf_localizer.cpp b/localization/autoware_ekf_localizer/src/ekf_localizer.cpp index d34be2a537ef1..11d7788adfade 100644 --- a/localization/autoware_ekf_localizer/src/ekf_localizer.cpp +++ b/localization/autoware_ekf_localizer/src/ekf_localizer.cpp @@ -56,6 +56,7 @@ EKFLocalizer::EKFLocalizer(const rclcpp::NodeOptions & node_options) twist_queue_(params_.twist_smoothing_steps) { is_activated_ = false; + is_set_initialpose_ = false; /* initialize ros system */ timer_control_ = rclcpp::create_timer( @@ -143,6 +144,13 @@ void EKFLocalizer::timer_callback() return; } + if (!is_set_initialpose_) { + warning_->warn_throttle( + "Initial pose is not set. Provide initial pose to pose_initializer", 2000); + publish_diagnostics(geometry_msgs::msg::PoseStamped{}, current_time); + return; + } + DEBUG_INFO(get_logger(), "========================= timer called ========================="); /* update predict frequency with measured timer rate */ @@ -264,6 +272,8 @@ void EKFLocalizer::callback_initial_pose( params_.pose_frame_id.c_str(), msg->header.frame_id.c_str()); } ekf_module_->initialize(*msg, transform); + + is_set_initialpose_ = true; } /* @@ -272,7 +282,7 @@ void EKFLocalizer::callback_initial_pose( void EKFLocalizer::callback_pose_with_covariance( geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg) { - if (!is_activated_) { + if (!is_activated_ && !is_set_initialpose_) { return; } @@ -359,8 +369,9 @@ void EKFLocalizer::publish_diagnostics( std::vector diag_status_array; diag_status_array.push_back(check_process_activated(is_activated_)); + diag_status_array.push_back(check_set_initialpose(is_set_initialpose_)); - if (is_activated_) { + if (is_activated_ && is_set_initialpose_) { diag_status_array.push_back(check_measurement_updated( "pose", pose_diag_info_.no_update_count, params_.pose_no_update_count_threshold_warn, params_.pose_no_update_count_threshold_error)); @@ -439,6 +450,7 @@ void EKFLocalizer::service_trigger_node( is_activated_ = true; } else { is_activated_ = false; + is_set_initialpose_ = false; } res->success = true; } diff --git a/localization/autoware_ekf_localizer/test/test_diagnostics.cpp b/localization/autoware_ekf_localizer/test/test_diagnostics.cpp index 165102adec1d7..5ce39df484e98 100644 --- a/localization/autoware_ekf_localizer/test/test_diagnostics.cpp +++ b/localization/autoware_ekf_localizer/test/test_diagnostics.cpp @@ -35,6 +35,19 @@ TEST(TestEkfDiagnostics, check_process_activated) EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); } +TEST(TestEkfDiagnostics, check_set_initialpose) +{ + diagnostic_msgs::msg::DiagnosticStatus stat; + + bool is_set_initialpose = true; + stat = check_set_initialpose(is_set_initialpose); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); + + is_set_initialpose = false; + stat = check_set_initialpose(is_set_initialpose); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); +} + TEST(TestEkfDiagnostics, check_measurement_updated) { diagnostic_msgs::msg::DiagnosticStatus stat; From 1e686028828e17913a1885480c8d27101585adae Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 8 Jan 2025 14:18:01 +0900 Subject: [PATCH 151/334] test(blind_spot): add unit tests for util functions (#9597) Signed-off-by: Mamoru Sobue --- .../CMakeLists.txt | 16 +- .../manager.hpp | 3 +- .../parameter.hpp | 40 + .../scene.hpp | 15 +- .../util.hpp | 32 +- .../package.xml | 1 + .../src/manager.cpp | 18 +- .../src/parameter.cpp | 45 + .../src/scene.cpp | 24 +- .../src/util.cpp | 49 +- .../test/test_util.cpp | 448 +++ .../test_data/object_on_adj_lane.yaml | 2698 +++++++++++++++++ .../test_data/object_on_shoulder.yaml | 2512 +++++++++++++++ 13 files changed, 5824 insertions(+), 77 deletions(-) create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/parameter.hpp create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/parameter.cpp create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/test/test_util.cpp create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/test_data/object_on_adj_lane.yaml create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/test_data/object_on_shoulder.yaml diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/CMakeLists.txt b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/CMakeLists.txt index b28e486c9be05..220c380eb0fd7 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/CMakeLists.txt +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/CMakeLists.txt @@ -1,6 +1,8 @@ cmake_minimum_required(VERSION 3.14) project(autoware_behavior_velocity_blind_spot_module) +option(EXPORT_TEST_PLOT_FIGURE "Export plot figures in test" OFF) + find_package(autoware_cmake REQUIRED) autoware_package() pluginlib_export_plugin_description_file(autoware_behavior_velocity_planner plugins.xml) @@ -11,16 +13,20 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/scene.cpp src/decisions.cpp src/util.cpp + src/parameter.cpp ) if(BUILD_TESTING) + if(EXPORT_TEST_PLOT_FIGURE) + add_definitions(-DEXPORT_TEST_PLOT_FIGURE "-Wno-attributes") # // cspell: ignore DEXPORT + endif() find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() - file(GLOB_RECURSE TEST_SOURCES test/*.cpp) - ament_add_ros_isolated_gtest(test_${PROJECT_NAME} - ${TEST_SOURCES} + # NOTE(soblin): pybind11::scoped_interpreter needs to be initialized globally, not in the FixtureClass instantiated for each test suite + ament_add_gtest(test_${PROJECT_NAME}_util + test/test_util.cpp ) - target_link_libraries(test_${PROJECT_NAME} ${PROJECT_NAME}) + target_link_libraries(test_${PROJECT_NAME}_util ${PROJECT_NAME}) endif() -ament_auto_package(INSTALL_TO_SHARE config) +ament_auto_package(INSTALL_TO_SHARE config test_data) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/manager.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/manager.hpp index bf01986d5c28f..41330e459a524 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/manager.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/manager.hpp @@ -15,6 +15,7 @@ #ifndef AUTOWARE__BEHAVIOR_VELOCITY_BLIND_SPOT_MODULE__MANAGER_HPP_ #define AUTOWARE__BEHAVIOR_VELOCITY_BLIND_SPOT_MODULE__MANAGER_HPP_ +#include "autoware/behavior_velocity_blind_spot_module/parameter.hpp" #include "autoware/behavior_velocity_blind_spot_module/scene.hpp" #include @@ -38,7 +39,7 @@ class BlindSpotModuleManager : public SceneModuleManagerInterfaceWithRTC const char * getModuleName() override { return "blind_spot"; } private: - BlindSpotModule::PlannerParam planner_param_; + PlannerParam planner_param_; void launchNewModules(const tier4_planning_msgs::msg::PathWithLaneId & path) override; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/parameter.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/parameter.hpp new file mode 100644 index 0000000000000..59322caecb62f --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/parameter.hpp @@ -0,0 +1,40 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__BEHAVIOR_VELOCITY_BLIND_SPOT_MODULE__PARAMETER_HPP_ +#define AUTOWARE__BEHAVIOR_VELOCITY_BLIND_SPOT_MODULE__PARAMETER_HPP_ + +#include + +#include + +namespace autoware::behavior_velocity_planner +{ +struct PlannerParam +{ + static PlannerParam init(rclcpp::Node & node, const std::string & ns); + bool use_pass_judge_line{}; + double stop_line_margin{}; + double backward_detection_length{}; + double ignore_width_from_center_line{}; + double adjacent_extend_width{}; + double opposite_adjacent_extend_width{}; + double max_future_movement_time{}; + double ttc_min{}; + double ttc_max{}; + double ttc_ego_minimal_velocity{}; +}; +} // namespace autoware::behavior_velocity_planner + +#endif // AUTOWARE__BEHAVIOR_VELOCITY_BLIND_SPOT_MODULE__PARAMETER_HPP_ diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/scene.hpp index 50ce8634ec600..5e8ef9fc8a063 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/scene.hpp @@ -15,6 +15,7 @@ #ifndef AUTOWARE__BEHAVIOR_VELOCITY_BLIND_SPOT_MODULE__SCENE_HPP_ #define AUTOWARE__BEHAVIOR_VELOCITY_BLIND_SPOT_MODULE__SCENE_HPP_ +#include #include #include #include @@ -70,20 +71,6 @@ class BlindSpotModule : public SceneModuleInterfaceWithRTC }; public: - struct PlannerParam - { - bool use_pass_judge_line; - double stop_line_margin; - double backward_detection_length; - double ignore_width_from_center_line; - double adjacent_extend_width; - double opposite_adjacent_extend_width; - double max_future_movement_time; - double ttc_min; - double ttc_max; - double ttc_ego_minimal_velocity; - }; - BlindSpotModule( const int64_t module_id, const int64_t lane_id, const TurnDirection turn_direction, const std::shared_ptr planner_data, const PlannerParam & planner_param, diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/util.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/util.hpp index 9d908414b6d95..e18d96709ef92 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/util.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/util.hpp @@ -16,6 +16,7 @@ #define AUTOWARE__BEHAVIOR_VELOCITY_BLIND_SPOT_MODULE__UTIL_HPP_ #include +#include #include @@ -25,6 +26,7 @@ #include #include #include +#include namespace autoware::behavior_velocity_planner { @@ -50,31 +52,49 @@ std::optional generateInterpolatedPathInfo( const lanelet::Id lane_id, const tier4_planning_msgs::msg::PathWithLaneId & input_path, rclcpp::Logger logger); +std::optional getFirstPointIntersectsLineByFootprint( + const lanelet::ConstLineString2d & line, const InterpolatedPathInfo & interpolated_path_info, + const autoware::universe_utils::LinearRing2d & footprint, const double vehicle_length); + std::optional getSiblingStraightLanelet( const lanelet::Lanelet assigned_lane, const lanelet::routing::RoutingGraphConstPtr routing_graph_ptr); /** - * @brief Create half lanelet - * @param lanelet input lanelet - * @return Half lanelet + * @brief generate a new lanelet object on the `turn_direction` side of `lanelet` which is offset + * from `ignore_width_from_centerline` from the centerline of `lanelet` + * @return new lanelet object */ lanelet::ConstLanelet generateHalfLanelet( const lanelet::ConstLanelet lanelet, const TurnDirection & turn_direction, const double ignore_width_from_centerline); +/** + * @brief generate a new lanelet object from the `turn_direction` side neighboring lanelet of the + * input `lanelet` by the width of `adjacent_extend_width` + * @param new lanelet object + */ lanelet::ConstLanelet generateExtendedAdjacentLanelet( const lanelet::ConstLanelet lanelet, const TurnDirection direction, const double adjacent_extend_width); + +/** + * @brief generate a new lanelet object from the `turn_direction` side neighboring opposite lanelet + * of the input `lanelet` by the width of `opposite_adjacent_extend_width` + * @param new lanelet object + */ lanelet::ConstLanelet generateExtendedOppositeAdjacentLanelet( const lanelet::ConstLanelet lanelet, const TurnDirection direction, const double opposite_adjacent_extend_width); +std::vector find_lane_ids_upto( + const tier4_planning_msgs::msg::PathWithLaneId & path, const lanelet::Id lane_id); + lanelet::ConstLanelets generateBlindSpotLanelets( const std::shared_ptr route_handler, - const TurnDirection turn_direction, const lanelet::Id lane_id, - const tier4_planning_msgs::msg::PathWithLaneId & path, const double ignore_width_from_centerline, - const double adjacent_extend_width, const double opposite_adjacent_extend_width); + const TurnDirection turn_direction, const std::vector & lane_ids_upto_intersection, + const double ignore_width_from_centerline, const double adjacent_extend_width, + const double opposite_adjacent_extend_width); /** * @brief Make blind spot areas. Narrow area is made from closest path point to stop line index. diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml index 8c34678f439ed..dabd3045b31d2 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml @@ -25,6 +25,7 @@ autoware_perception_msgs autoware_planning_msgs autoware_route_handler + autoware_test_utils autoware_universe_utils geometry_msgs pluginlib diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/manager.cpp index a1410d2fecfd5..d6cae9004600a 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/manager.cpp @@ -34,23 +34,7 @@ BlindSpotModuleManager::BlindSpotModuleManager(rclcpp::Node & node) node, getModuleName(), getEnableRTC(node, std::string(getModuleName()) + ".enable_rtc")) { const std::string ns(BlindSpotModuleManager::getModuleName()); - planner_param_.use_pass_judge_line = - getOrDeclareParameter(node, ns + ".use_pass_judge_line"); - planner_param_.stop_line_margin = getOrDeclareParameter(node, ns + ".stop_line_margin"); - planner_param_.backward_detection_length = - getOrDeclareParameter(node, ns + ".backward_detection_length"); - planner_param_.ignore_width_from_center_line = - getOrDeclareParameter(node, ns + ".ignore_width_from_center_line"); - planner_param_.adjacent_extend_width = - getOrDeclareParameter(node, ns + ".adjacent_extend_width"); - planner_param_.opposite_adjacent_extend_width = - getOrDeclareParameter(node, ns + ".opposite_adjacent_extend_width"); - planner_param_.max_future_movement_time = - getOrDeclareParameter(node, ns + ".max_future_movement_time"); - planner_param_.ttc_min = getOrDeclareParameter(node, ns + ".ttc_min"); - planner_param_.ttc_max = getOrDeclareParameter(node, ns + ".ttc_max"); - planner_param_.ttc_ego_minimal_velocity = - getOrDeclareParameter(node, ns + ".ttc_ego_minimal_velocity"); + planner_param_ = PlannerParam::init(node, ns); } void BlindSpotModuleManager::launchNewModules(const tier4_planning_msgs::msg::PathWithLaneId & path) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/parameter.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/parameter.cpp new file mode 100644 index 0000000000000..0984de6f73262 --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/parameter.cpp @@ -0,0 +1,45 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/behavior_velocity_blind_spot_module/parameter.hpp" + +#include + +#include + +namespace autoware::behavior_velocity_planner +{ + +PlannerParam PlannerParam::init(rclcpp::Node & node, const std::string & ns) +{ + using autoware::universe_utils::getOrDeclareParameter; + PlannerParam param; + param.use_pass_judge_line = getOrDeclareParameter(node, ns + ".use_pass_judge_line"); + param.stop_line_margin = getOrDeclareParameter(node, ns + ".stop_line_margin"); + param.backward_detection_length = + getOrDeclareParameter(node, ns + ".backward_detection_length"); + param.ignore_width_from_center_line = + getOrDeclareParameter(node, ns + ".ignore_width_from_center_line"); + param.adjacent_extend_width = getOrDeclareParameter(node, ns + ".adjacent_extend_width"); + param.opposite_adjacent_extend_width = + getOrDeclareParameter(node, ns + ".opposite_adjacent_extend_width"); + param.max_future_movement_time = + getOrDeclareParameter(node, ns + ".max_future_movement_time"); + param.ttc_min = getOrDeclareParameter(node, ns + ".ttc_min"); + param.ttc_max = getOrDeclareParameter(node, ns + ".ttc_max"); + param.ttc_ego_minimal_velocity = + getOrDeclareParameter(node, ns + ".ttc_ego_minimal_velocity"); + return param; +} +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp index 7d1a68c5006a0..8a9401646aaea 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp @@ -101,8 +101,9 @@ BlindSpotDecision BlindSpotModule::modifyPathVelocityDetail(PathWithLaneId * pat } if (!blind_spot_lanelets_) { + const auto lane_ids_upto_intersection = find_lane_ids_upto(input_path, lane_id_); const auto blind_spot_lanelets = generateBlindSpotLanelets( - planner_data_->route_handler_, turn_direction_, lane_id_, input_path, + planner_data_->route_handler_, turn_direction_, lane_ids_upto_intersection, planner_param_.ignore_width_from_center_line, planner_param_.adjacent_extend_width, planner_param_.opposite_adjacent_extend_width); if (!blind_spot_lanelets.empty()) { @@ -179,27 +180,6 @@ bool BlindSpotModule::modifyPathVelocity(PathWithLaneId * path) return true; } -static std::optional getFirstPointIntersectsLineByFootprint( - const lanelet::ConstLineString2d & line, const InterpolatedPathInfo & interpolated_path_info, - const autoware::universe_utils::LinearRing2d & footprint, const double vehicle_length) -{ - const auto & path_ip = interpolated_path_info.path; - const auto [lane_start, lane_end] = interpolated_path_info.lane_id_interval.value(); - const size_t vehicle_length_idx = static_cast(vehicle_length / interpolated_path_info.ds); - const size_t start = - static_cast(std::max(0, static_cast(lane_start) - vehicle_length_idx)); - const auto line2d = line.basicLineString(); - for (auto i = start; i <= lane_end; ++i) { - const auto & base_pose = path_ip.points.at(i).point.pose; - const auto path_footprint = autoware::universe_utils::transformVector( - footprint, autoware::universe_utils::pose2transform(base_pose)); - if (bg::intersects(path_footprint, line2d)) { - return std::make_optional(i); - } - } - return std::nullopt; -} - static std::optional getDuplicatedPointIdx( const tier4_planning_msgs::msg::PathWithLaneId & path, const geometry_msgs::msg::Point & point) { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/util.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/util.cpp index 5c5aa0a26b3b4..8451661b2b71f 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/util.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/util.cpp @@ -88,6 +88,27 @@ std::optional generateInterpolatedPathInfo( return interpolated_path_info; } +std::optional getFirstPointIntersectsLineByFootprint( + const lanelet::ConstLineString2d & line, const InterpolatedPathInfo & interpolated_path_info, + const autoware::universe_utils::LinearRing2d & footprint, const double vehicle_length) +{ + const auto & path_ip = interpolated_path_info.path; + const auto [lane_start, lane_end] = interpolated_path_info.lane_id_interval.value(); + const size_t vehicle_length_idx = static_cast(vehicle_length / interpolated_path_info.ds); + const size_t start = + static_cast(std::max(0, static_cast(lane_start) - vehicle_length_idx)); + const auto line2d = line.basicLineString(); + for (auto i = start; i <= lane_end; ++i) { + const auto & base_pose = path_ip.points.at(i).point.pose; + const auto path_footprint = autoware::universe_utils::transformVector( + footprint, autoware::universe_utils::pose2transform(base_pose)); + if (boost::geometry::intersects(path_footprint, line2d)) { + return std::make_optional(i); + } + } + return std::nullopt; +} + std::optional getSiblingStraightLanelet( const lanelet::Lanelet assigned_lane, const lanelet::routing::RoutingGraphConstPtr routing_graph_ptr) @@ -200,15 +221,9 @@ static lanelet::LineString3d removeConst(lanelet::ConstLineString3d line) return lanelet::LineString3d(lanelet::InvalId, pts); } -lanelet::ConstLanelets generateBlindSpotLanelets( - const std::shared_ptr route_handler, - const TurnDirection turn_direction, const lanelet::Id lane_id, - const tier4_planning_msgs::msg::PathWithLaneId & path, const double ignore_width_from_centerline, - const double adjacent_extend_width, const double opposite_adjacent_extend_width) +std::vector find_lane_ids_upto( + const tier4_planning_msgs::msg::PathWithLaneId & path, const lanelet::Id lane_id) { - const auto lanelet_map_ptr = route_handler->getLaneletMapPtr(); - const auto routing_graph_ptr = route_handler->getRoutingGraphPtr(); - std::vector lane_ids; /* get lane ids until intersection */ for (const auto & point : path.points) { @@ -216,19 +231,29 @@ lanelet::ConstLanelets generateBlindSpotLanelets( for (const auto id : point.lane_ids) { if (id == lane_id) { found_intersection_lane = true; - lane_ids.push_back(lane_id); break; } // make lane_ids unique - if (std::find(lane_ids.begin(), lane_ids.end(), lane_id) == lane_ids.end()) { - lane_ids.push_back(lane_id); + if (std::find(lane_ids.begin(), lane_ids.end(), id) == lane_ids.end()) { + lane_ids.push_back(id); } } if (found_intersection_lane) break; } + return lane_ids; +} + +lanelet::ConstLanelets generateBlindSpotLanelets( + const std::shared_ptr route_handler, + const TurnDirection turn_direction, const std::vector & lane_ids_upto_intersection, + const double ignore_width_from_centerline, const double adjacent_extend_width, + const double opposite_adjacent_extend_width) +{ + const auto lanelet_map_ptr = route_handler->getLaneletMapPtr(); + const auto routing_graph_ptr = route_handler->getRoutingGraphPtr(); lanelet::ConstLanelets blind_spot_lanelets; - for (const auto i : lane_ids) { + for (const auto i : lane_ids_upto_intersection) { const auto lane = lanelet_map_ptr->laneletLayer.get(i); const auto ego_half_lanelet = generateHalfLanelet(lane, turn_direction, ignore_width_from_centerline); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/test/test_util.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/test/test_util.cpp new file mode 100644 index 0000000000000..5c2a239e4142f --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/test/test_util.cpp @@ -0,0 +1,448 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include +#include +#include + +#include +#include + +#include +#include + +#include +#include +#include +#include + +#ifdef EXPORT_TEST_PLOT_FIGURE +#include +#include +#include +#include + +#include +#include // needed for passing std::string to Args + +#endif + +using autoware::test_utils::parse; + +class TestWithAdjLaneData : public ::testing::Test +{ +protected: + void SetUp() override + { + const auto test_data_file = + ament_index_cpp::get_package_share_directory("autoware_behavior_velocity_blind_spot_module") + + "/test_data/object_on_adj_lane.yaml"; + const auto config = YAML::LoadFile(test_data_file); + const auto route = parse(config["route"]); + const auto map_path = + autoware::test_utils::resolve_pkg_share_uri(config["map_path_uri"].as()); + if (!map_path) { + ASSERT_DEATH({ assert(false); }, "invalid map path"); + } + const auto intersection_map = autoware::test_utils::make_map_bin_msg(map_path.value()); + route_handler = std::make_shared(); + route_handler->setMap(intersection_map); + route_handler->setRoute(route); + self_odometry = autoware::test_utils::create_const_shared_ptr( + parse(config["self_odometry"])); + dynamic_object = autoware::test_utils::create_const_shared_ptr( + parse(config["dynamic_object"])); + path_with_lane_id = + parse(config["path_with_lane_id"]); + + // parameter + auto node_options = rclcpp::NodeOptions{}; + node_options.arguments(std::vector{ + "--ros-args", + "--params-file", + ament_index_cpp::get_package_share_directory("autoware_behavior_velocity_blind_spot_module") + + "/config/blind_spot.param.yaml", + }); + + auto node = rclcpp::Node::make_shared("blind_spot_test", node_options); + param = autoware::behavior_velocity_planner::PlannerParam::init(*node, "blind_spot"); + } + + std::shared_ptr route_handler{}; + std::shared_ptr self_odometry{}; + std::shared_ptr dynamic_object{}; + const lanelet::Id lane_id_{2200}; + tier4_planning_msgs::msg::PathWithLaneId path_with_lane_id; + autoware::behavior_velocity_planner::PlannerParam param; +}; + +TEST_F(TestWithAdjLaneData, getSiblingStraightLanelet) +{ + const auto sibling_straight_lanelet_opt = + autoware::behavior_velocity_planner::getSiblingStraightLanelet( + route_handler->getLaneletMapPtr()->laneletLayer.get(lane_id_), + route_handler->getRoutingGraphPtr()); + ASSERT_NO_FATAL_FAILURE({ ASSERT_TRUE(sibling_straight_lanelet_opt.has_value()); }); + EXPECT_EQ(sibling_straight_lanelet_opt.value().id(), 2100); + +#ifdef EXPORT_TEST_PLOT_FIGURE + py::gil_scoped_acquire acquire; + using autoware::test_utils::LaneConfig; + using autoware::test_utils::LineConfig; + auto plt = autoware::pyplot::import(); + auto [fig, axes] = plt.subplots(1, 1); + auto & ax = axes[0]; + autoware::test_utils::plot_lanelet2_object( + route_handler->getLaneletMapPtr()->laneletLayer.get(lane_id_), ax, + autoware::test_utils::LaneConfig{"intersection turning lanes", LineConfig{"blue"}}); + + // for illustration + autoware::test_utils::plot_lanelet2_object( + route_handler->getLaneletMapPtr()->laneletLayer.get(3010933), ax, + autoware::test_utils::LaneConfig{std::nullopt, LineConfig{"green"}}); + autoware::test_utils::plot_lanelet2_object( + route_handler->getLaneletMapPtr()->laneletLayer.get(2201), ax, + autoware::test_utils::LaneConfig{std::nullopt, LineConfig{"blue"}}); + autoware::test_utils::plot_lanelet2_object( + route_handler->getLaneletMapPtr()->laneletLayer.get(2202), ax, + autoware::test_utils::LaneConfig{std::nullopt, LineConfig{"blue"}}); + autoware::test_utils::plot_lanelet2_object( + route_handler->getLaneletMapPtr()->laneletLayer.get(2010), ax, + autoware::test_utils::LaneConfig{std::nullopt, LineConfig{"green"}}); + + const auto [x0, x1] = ax.get_xlim(); + const auto [y0, y1] = ax.get_ylim(); + const double width = x1 - x0; + const double height = y1 - y0; + ax.set_xlim(Args(x0, x0 + width * 1.3)); + ax.set_ylim(Args(y0, y0 + height * 1.3)); + autoware::test_utils::plot_lanelet2_object( + sibling_straight_lanelet_opt.value(), ax, + LaneConfig{"sibling_straight_lanelet", LineConfig{"red"}}); + ax.set_aspect(Args("equal")); + ax.grid(); + ax.legend(Args(), Kwargs{"loc"_a = "upper right"}); + fig.tight_layout(); + const std::string filename = std::string( + ament_index_cpp::get_package_share_directory("autoware_behavior_velocity_blind_spot_module") + + "/test_data/" + ::testing::UnitTest::GetInstance()->current_test_info()->name() + ".svg"); + plt.savefig(Args(filename)); +#endif +} + +TEST_F(TestWithAdjLaneData, generateHalfLanelet) +{ + const auto lanelet = route_handler->getLaneletMapPtr()->laneletLayer.get(2010); + + const auto half_lanelet = autoware::behavior_velocity_planner::generateHalfLanelet( + lanelet, autoware::behavior_velocity_planner::TurnDirection::LEFT, + param.ignore_width_from_center_line); + + /* + TODO(soblin): how to check if they overlap only on the left line string + EXPECT_EQ( + boost::geometry::within( + half_lanelet.polygon2d().basicPolygon(), lanelet.polygon2d().basicPolygon()), + true); + */ + EXPECT_EQ( + boost::geometry::area(lanelet.polygon2d().basicPolygon()) / 2.0 > + boost::geometry::area(half_lanelet.polygon2d().basicPolygon()), + true); + +#ifdef EXPORT_TEST_PLOT_FIGURE + py::gil_scoped_acquire acquire; + using autoware::test_utils::LaneConfig; + using autoware::test_utils::LineConfig; + auto plt = autoware::pyplot::import(); + auto [fig, axes] = plt.subplots(1, 1); + auto & ax = axes[0]; + autoware::test_utils::plot_lanelet2_object( + lanelet, ax, autoware::test_utils::LaneConfig{"original", LineConfig{"blue", 1.5}}); + autoware::test_utils::plot_lanelet2_object( + half_lanelet, ax, LaneConfig{"half lanelet", LineConfig{"red", 0.75}}); + + const auto [x0, x1] = ax.get_xlim(); + const auto [y0, y1] = ax.get_ylim(); + const double width = x1 - x0; + // const double height = y1 - y0; + ax.set_xlim(Args(x0, x0 + width * 1.3)); + ax.set_ylim(Args(y0, 650)); + ax.set_aspect(Args("equal")); + ax.grid(); + ax.legend(Args(), Kwargs{"loc"_a = "upper right"}); + fig.tight_layout(); + const std::string filename = std::string( + ament_index_cpp::get_package_share_directory("autoware_behavior_velocity_blind_spot_module") + + "/test_data/" + ::testing::UnitTest::GetInstance()->current_test_info()->name() + ".svg"); + plt.savefig(Args(filename)); +#endif +} + +TEST_F(TestWithAdjLaneData, generateExtendedAdjacentLanelet) +{ + const auto lanelet = route_handler->getLaneletMapPtr()->laneletLayer.get(2010); + const auto adj_lanelet = *(route_handler->getRoutingGraphPtr()->adjacentLeft(lanelet)); + + const auto extended_adj_lanelet = + autoware::behavior_velocity_planner::generateExtendedAdjacentLanelet( + adj_lanelet, autoware::behavior_velocity_planner::TurnDirection::LEFT, + param.adjacent_extend_width); + +#ifdef EXPORT_TEST_PLOT_FIGURE + py::gil_scoped_acquire acquire; + using autoware::test_utils::LaneConfig; + using autoware::test_utils::LineConfig; + auto plt = autoware::pyplot::import(); + auto [fig, axes] = plt.subplots(1, 1); + auto & ax = axes[0]; + autoware::test_utils::plot_lanelet2_object( + lanelet, ax, autoware::test_utils::LaneConfig{"given", LineConfig{"blue", 1.0}}); + autoware::test_utils::plot_lanelet2_object( + adj_lanelet, ax, autoware::test_utils::LaneConfig{"adjacent", LineConfig{"green", 1.0}}); + autoware::test_utils::plot_lanelet2_object( + extended_adj_lanelet, ax, LaneConfig{"generated", LineConfig{"red", 2.0}}); + + const auto [x0, x1] = ax.get_xlim(); + const auto [y0, y1] = ax.get_ylim(); + const double width = x1 - x0; + const double height = y1 - y0; + ax.set_xlim(Args(x0, x0 + width * 1.3)); + ax.set_ylim(Args(y0, y0 + height * 1.3)); + ax.set_aspect(Args("equal")); + ax.grid(); + ax.legend(Args(), Kwargs{"loc"_a = "upper right"}); + fig.tight_layout(); + const std::string filename = std::string( + ament_index_cpp::get_package_share_directory("autoware_behavior_velocity_blind_spot_module") + + "/test_data/" + ::testing::UnitTest::GetInstance()->current_test_info()->name() + ".svg"); + plt.savefig(Args(filename)); +#endif +} + +TEST_F(TestWithAdjLaneData, generateBlindSpotLanelets_left) +{ + const auto blind_spot_lanelets = autoware::behavior_velocity_planner::generateBlindSpotLanelets( + route_handler, autoware::behavior_velocity_planner::TurnDirection::LEFT, {2000, 2010}, + param.ignore_width_from_center_line, param.adjacent_extend_width, + param.opposite_adjacent_extend_width); + EXPECT_EQ(blind_spot_lanelets.size(), 2); + +#ifdef EXPORT_TEST_PLOT_FIGURE + py::gil_scoped_acquire acquire; + using autoware::test_utils::LaneConfig; + using autoware::test_utils::LineConfig; + auto plt = autoware::pyplot::import(); + auto [fig, axes] = plt.subplots(1, 1); + auto & ax = axes[0]; + for (const auto & id : {2010, 3010933, 2200, 3010920, 3010933, 2000}) { + const auto lanelet = route_handler->getLaneletMapPtr()->laneletLayer.get(id); + autoware::test_utils::plot_lanelet2_object( + lanelet, ax, LaneConfig{std::nullopt, LineConfig{"k", 0.75}}); + } + for (const auto & blind_spot_lanelet : blind_spot_lanelets) { + autoware::test_utils::plot_lanelet2_object( + blind_spot_lanelet, ax, LaneConfig{"blind_spot_lanelet", LineConfig{"blue", 2.0}}); + } + const auto [y0, y1] = ax.get_ylim(); + const double height = y1 - y0; + ax.set_xlim(Args(300, 365)); + ax.set_ylim(Args(y0, y0 + height * 1.3)); + ax.set_aspect(Args("equal")); + ax.grid(); + ax.legend(Args(), Kwargs{"loc"_a = "upper right"}); + fig.tight_layout(); + const std::string filename = std::string( + ament_index_cpp::get_package_share_directory("autoware_behavior_velocity_blind_spot_module") + + "/test_data/" + ::testing::UnitTest::GetInstance()->current_test_info()->name() + ".svg"); + plt.savefig(Args(filename)); +#endif +} + +TEST_F(TestWithAdjLaneData, generateBlindSpotLanelets_right) +{ + const auto blind_spot_lanelets = autoware::behavior_velocity_planner::generateBlindSpotLanelets( + route_handler, autoware::behavior_velocity_planner::TurnDirection::RIGHT, {3008067}, + param.ignore_width_from_center_line, param.adjacent_extend_width, + param.opposite_adjacent_extend_width); + EXPECT_EQ(blind_spot_lanelets.size(), 1); + +#ifdef EXPORT_TEST_PLOT_FIGURE + py::gil_scoped_acquire acquire; + using autoware::test_utils::LaneConfig; + using autoware::test_utils::LineConfig; + auto plt = autoware::pyplot::import(); + auto [fig, axes] = plt.subplots(1, 1); + auto & ax = axes[0]; + for (const auto & id : {3008057, 3008054, 3008056, 3008061, 3008062, 3008059, 3008067, 3008066}) { + const auto lanelet = route_handler->getLaneletMapPtr()->laneletLayer.get(id); + autoware::test_utils::plot_lanelet2_object( + lanelet, ax, LaneConfig{std::nullopt, LineConfig{"k", 0.75}}); + } + for (const auto & blind_spot_lanelet : blind_spot_lanelets) { + autoware::test_utils::plot_lanelet2_object( + blind_spot_lanelet, ax, LaneConfig{"blind_spot_lanelet", LineConfig{"blue", 2.0}}); + } + ax.set_xlim(Args(905, 920)); + ax.set_ylim(Args(650, 950)); + ax.set_aspect(Args("equal")); + ax.grid(); + ax.legend(Args(), Kwargs{"loc"_a = "upper right"}); + fig.tight_layout(); + const std::string filename = std::string( + ament_index_cpp::get_package_share_directory("autoware_behavior_velocity_blind_spot_module") + + "/test_data/" + ::testing::UnitTest::GetInstance()->current_test_info()->name() + ".svg"); + plt.savefig(Args(filename)); +#endif +} + +TEST_F(TestWithAdjLaneData, generateInterpolatedPathInfo) +{ + const auto interpolated_path_info_opt = + autoware::behavior_velocity_planner::generateInterpolatedPathInfo( + lane_id_, path_with_lane_id, rclcpp::get_logger("test")); + EXPECT_EQ(interpolated_path_info_opt.has_value(), true); + const auto & interpolated_path_info = interpolated_path_info_opt.value(); + EXPECT_EQ(interpolated_path_info.lane_id_interval.has_value(), true); + const auto [start, end] = interpolated_path_info.lane_id_interval.value(); + tier4_planning_msgs::msg::PathWithLaneId interpolated_path; + for (auto i = start; i <= end; ++i) { + interpolated_path.points.push_back(interpolated_path_info.path.points.at(i)); + } +#ifdef EXPORT_TEST_PLOT_FIGURE + py::gil_scoped_acquire acquire; + using autoware::test_utils::LaneConfig; + using autoware::test_utils::LineConfig; + using autoware::test_utils::PathWithLaneIdConfig; + auto plt = autoware::pyplot::import(); + auto [fig, axes] = plt.subplots(1, 1); + auto & ax = axes[0]; + for (const auto & id : {2010, 3010933, 2200, 3010920, 3010933, 2000, 3500}) { + const auto lanelet = route_handler->getLaneletMapPtr()->laneletLayer.get(id); + autoware::test_utils::plot_lanelet2_object( + lanelet, ax, LaneConfig{std::nullopt, LineConfig{"k", 0.75}}); + } + autoware::test_utils::plot_autoware_object( + path_with_lane_id, ax, PathWithLaneIdConfig{"original path", "red", 0.75}); + autoware::test_utils::plot_autoware_object( + interpolated_path, ax, PathWithLaneIdConfig{"interpolated path on lane 2010", "blue", 1.0}); + const auto [x0, x1] = ax.get_xlim(); + ax.set_xlim(Args(335, x1)); + ax.set_ylim(Args(640, 670)); + ax.set_aspect(Args("equal")); + ax.grid(); + ax.legend(Args(), Kwargs{"loc"_a = "upper right"}); + fig.tight_layout(); + const std::string filename = std::string( + ament_index_cpp::get_package_share_directory("autoware_behavior_velocity_blind_spot_module") + + "/test_data/" + ::testing::UnitTest::GetInstance()->current_test_info()->name() + ".svg"); + plt.savefig(Args(filename)); +#endif +} + +class TestWithShoulderData : public ::testing::Test +{ +protected: + void SetUp() override + { + const auto test_data_file = + ament_index_cpp::get_package_share_directory("autoware_behavior_velocity_blind_spot_module") + + "/test_data/object_on_shoulder.yaml"; + const auto config = YAML::LoadFile(test_data_file); + const auto route = parse(config["route"]); + const auto map_path = + autoware::test_utils::resolve_pkg_share_uri(config["map_path_uri"].as()); + if (!map_path) { + ASSERT_DEATH({ assert(false); }, "invalid map path"); + } + const auto intersection_map = autoware::test_utils::make_map_bin_msg(map_path.value()); + route_handler = std::make_shared(); + route_handler->setMap(intersection_map); + route_handler->setRoute(route); + self_odometry = autoware::test_utils::create_const_shared_ptr( + parse(config["self_odometry"])); + dynamic_object = autoware::test_utils::create_const_shared_ptr( + parse(config["dynamic_object"])); + path_with_lane_id = + parse(config["path_with_lane_id"]); + + // parameter + auto node_options = rclcpp::NodeOptions{}; + node_options.arguments(std::vector{ + "--ros-args", + "--params-file", + ament_index_cpp::get_package_share_directory("autoware_behavior_velocity_blind_spot_module") + + "/config/blind_spot.param.yaml", + }); + + auto node = rclcpp::Node::make_shared("blind_spot_test", node_options); + param = autoware::behavior_velocity_planner::PlannerParam::init(*node, "blind_spot"); + } + + std::shared_ptr route_handler{}; + std::shared_ptr self_odometry{}; + std::shared_ptr dynamic_object{}; + const lanelet::Id lane_id_{1010}; + tier4_planning_msgs::msg::PathWithLaneId path_with_lane_id; + autoware::behavior_velocity_planner::PlannerParam param; +}; + +TEST_F(TestWithShoulderData, generateBlindSpotLaneletsShoulder_left) +{ + const auto blind_spot_lanelets = autoware::behavior_velocity_planner::generateBlindSpotLanelets( + route_handler, autoware::behavior_velocity_planner::TurnDirection::LEFT, {1000, 1010}, + param.ignore_width_from_center_line, param.adjacent_extend_width, + param.opposite_adjacent_extend_width); + EXPECT_EQ(blind_spot_lanelets.size(), 2); + +#ifdef EXPORT_TEST_PLOT_FIGURE + py::gil_scoped_acquire acquire; + using autoware::test_utils::LaneConfig; + using autoware::test_utils::LineConfig; + auto plt = autoware::pyplot::import(); + auto [fig, axes] = plt.subplots(1, 1); + auto & ax = axes[0]; + for (const auto & id : {1000, 1010, 3010907, 3010879, 1200, 1100}) { + const auto lanelet = route_handler->getLaneletMapPtr()->laneletLayer.get(id); + autoware::test_utils::plot_lanelet2_object( + lanelet, ax, LaneConfig{std::nullopt, LineConfig{"k", 0.75}}); + } + for (const auto & blind_spot_lanelet : blind_spot_lanelets) { + autoware::test_utils::plot_lanelet2_object( + blind_spot_lanelet, ax, LaneConfig{"blind_spot_lanelet", LineConfig{"blue", 2.0}}); + } + ax.set_xlim(Args(330, 365)); + ax.set_ylim(Args(580, 625)); + ax.set_aspect(Args("equal")); + ax.grid(); + ax.legend(Args(), Kwargs{"loc"_a = "upper left"}); + fig.tight_layout(); + const std::string filename = std::string( + ament_index_cpp::get_package_share_directory("autoware_behavior_velocity_blind_spot_module") + + "/test_data/" + ::testing::UnitTest::GetInstance()->current_test_info()->name() + ".svg"); + plt.savefig(Args(filename)); +#endif +} + +int main(int argc, char ** argv) +{ +#ifdef EXPORT_TEST_PLOT_FIGURE + py::scoped_interpreter guard{}; +#endif + rclcpp::init(0, nullptr); + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/test_data/object_on_adj_lane.yaml b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/test_data/object_on_adj_lane.yaml new file mode 100644 index 0000000000000..97068d69cd296 --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/test_data/object_on_adj_lane.yaml @@ -0,0 +1,2698 @@ +# +# AUTO GENERATED by autoware_test_utils::topic_snapshot_saver +# format1: +# +# format_version: +# map_path_uri: package:/// +# fields(this is array) +# - name: +# type: either {Odometry | AccelWithCovarianceStamped | PredictedObjects | OperationModeState | LaneletRoute | TrafficLightGroupArray | TrackedObjects | PathWithLaneId | TBD} +# topic: +# +format_version: 1 +map_path_uri: package://autoware_test_utils/test_map/intersection/lanelet2_map.osm +path_with_lane_id: + header: + stamp: + sec: 563 + nanosec: 125840339 + frame_id: map + points: + - point: + pose: + position: + x: 330.010 + y: 643.206 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00655991 + w: 0.999978 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2010 + - point: + pose: + position: + x: 332.010 + y: 643.233 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00656125 + w: 0.999978 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2010 + - point: + pose: + position: + x: 334.009 + y: 643.259 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00658745 + w: 0.999978 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2010 + - point: + pose: + position: + x: 336.009 + y: 643.285 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00660718 + w: 0.999978 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2010 + - point: + pose: + position: + x: 338.009 + y: 643.312 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00658719 + w: 0.999978 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2010 + - point: + pose: + position: + x: 340.009 + y: 643.338 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00656661 + w: 0.999978 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2010 + - point: + pose: + position: + x: 342.009 + y: 643.364 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00657433 + w: 0.999978 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2010 + - point: + pose: + position: + x: 342.809 + y: 643.375 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.0162350 + w: 0.999868 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2010 + - 2200 + - point: + pose: + position: + x: 344.008 + y: 643.414 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.0355542 + w: 0.999368 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2200 + - point: + pose: + position: + x: 346.003 + y: 643.556 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.0600763 + w: 0.998194 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2200 + - point: + pose: + position: + x: 347.986 + y: 643.796 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.134724 + w: 0.990883 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2200 + - point: + pose: + position: + x: 349.912 + y: 644.329 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.199426 + w: 0.979913 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2200 + - point: + pose: + position: + x: 351.776 + y: 645.121 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.281519 + w: 0.959556 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2200 + - point: + pose: + position: + x: 353.448 + y: 646.194 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.345347 + w: 0.938475 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2200 + - point: + pose: + position: + x: 354.997 + y: 647.513 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.407454 + w: 0.913226 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2200 + - point: + pose: + position: + x: 356.322 + y: 648.989 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.480104 + w: 0.877212 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2200 + - point: + pose: + position: + x: 357.418 + y: 650.701 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.544895 + w: 0.838504 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2200 + - point: + pose: + position: + x: 358.228 + y: 652.525 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.610262 + w: 0.792199 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2200 + - point: + pose: + position: + x: 358.741 + y: 654.467 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.646506 + w: 0.762909 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2200 + - point: + pose: + position: + x: 359.070 + y: 656.445 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.697457 + w: 0.716627 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2200 + - point: + pose: + position: + x: 359.124 + y: 658.438 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.713869 + w: 0.700280 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2200 + - point: + pose: + position: + x: 359.085 + y: 660.438 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.714886 + w: 0.699241 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2200 + - point: + pose: + position: + x: 359.052 + y: 661.935 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2200 + - 3500 + - point: + pose: + position: + x: 359.040 + y: 662.438 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 3500 + - point: + pose: + position: + x: 358.993 + y: 664.437 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 3500 + - point: + pose: + position: + x: 358.945 + y: 666.436 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715334 + w: 0.698782 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 3500 + - point: + pose: + position: + x: 358.900 + y: 668.374 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.714518 + w: 0.699617 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 3500 + - point: + pose: + position: + x: 358.858 + y: 670.373 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.712894 + w: 0.701272 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 3500 + - point: + pose: + position: + x: 358.825 + y: 672.373 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.710606 + w: 0.703590 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 3500 + - point: + pose: + position: + x: 358.807 + y: 674.174 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.705159 + w: 0.709049 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 3500 + - point: + pose: + position: + x: 358.812 + y: 675.174 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.705159 + w: 0.709049 + longitudinal_velocity_mps: 0.00000 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 3500 + left_bound: + - x: 329.488 + y: 644.822 + z: 100.000 + - x: 332.672 + y: 644.864 + z: 100.000 + - x: 334.352 + y: 644.886 + z: 100.000 + - x: 336.351 + y: 644.913 + z: 100.000 + - x: 337.719 + y: 644.931 + z: 100.000 + - x: 340.352 + y: 644.965 + z: 100.000 + - x: 342.813 + y: 645.020 + z: 100.000 + - x: 344.277 + y: 645.102 + z: 100.000 + - x: 346.200 + y: 645.256 + z: 100.000 + - x: 347.374 + y: 645.428 + z: 100.000 + - x: 348.470 + y: 645.697 + z: 100.000 + - x: 349.568 + y: 646.035 + z: 100.000 + - x: 350.592 + y: 646.513 + z: 100.000 + - x: 351.572 + y: 647.043 + z: 100.000 + - x: 352.507 + y: 647.713 + z: 100.000 + - x: 353.327 + y: 648.476 + z: 100.000 + - x: 354.109 + y: 649.196 + z: 100.000 + - x: 354.661 + y: 649.830 + z: 100.000 + - x: 355.275 + y: 650.523 + z: 100.000 + - x: 356.177 + y: 652.020 + z: 100.000 + - x: 356.615 + y: 653.084 + z: 100.000 + - x: 356.929 + y: 654.139 + z: 100.000 + - x: 357.146 + y: 655.241 + z: 100.000 + - x: 357.284 + y: 656.160 + z: 100.000 + - x: 357.312 + y: 657.420 + z: 100.000 + - x: 357.425 + y: 658.703 + z: 100.000 + - x: 357.383 + y: 660.465 + z: 100.000 + - x: 357.349 + y: 661.894 + z: 100.000 + - x: 357.386 + y: 664.700 + z: 100.000 + - x: 357.338 + y: 666.699 + z: 100.000 + - x: 357.291 + y: 668.699 + z: 100.000 + - x: 357.243 + y: 670.698 + z: 100.000 + - x: 357.195 + y: 672.698 + z: 100.000 + - x: 357.148 + y: 674.697 + z: 100.000 + - x: 357.021 + y: 680.023 + z: 100.000 + right_bound: + - x: 329.531 + y: 641.578 + z: 100.000 + - x: 332.717 + y: 641.619 + z: 100.000 + - x: 334.395 + y: 641.641 + z: 100.000 + - x: 336.394 + y: 641.668 + z: 100.000 + - x: 337.761 + y: 641.686 + z: 100.000 + - x: 340.394 + y: 641.721 + z: 100.000 + - x: 342.805 + y: 641.730 + z: 100.000 + - x: 344.462 + y: 641.823 + z: 100.000 + - x: 346.283 + y: 641.878 + z: 100.000 + - x: 347.708 + y: 641.985 + z: 100.000 + - x: 349.158 + y: 642.284 + z: 100.000 + - x: 350.570 + y: 642.681 + z: 100.000 + - x: 351.954 + y: 643.219 + z: 100.000 + - x: 353.269 + y: 643.933 + z: 100.000 + - x: 354.499 + y: 644.727 + z: 100.000 + - x: 355.646 + y: 645.678 + z: 100.000 + - x: 356.516 + y: 646.483 + z: 100.000 + - x: 357.282 + y: 647.228 + z: 100.000 + - x: 357.690 + y: 647.819 + z: 100.000 + - x: 358.527 + y: 649.081 + z: 100.000 + - x: 359.237 + y: 650.418 + z: 100.000 + - x: 359.789 + y: 651.774 + z: 100.000 + - x: 360.225 + y: 653.220 + z: 100.000 + - x: 360.523 + y: 654.391 + z: 100.000 + - x: 360.701 + y: 655.780 + z: 100.000 + - x: 360.976 + y: 657.487 + z: 100.000 + - x: 360.804 + y: 658.842 + z: 100.000 + - x: 360.774 + y: 660.766 + z: 100.000 + - x: 360.755 + y: 661.975 + z: 100.000 + - x: 360.585 + y: 664.776 + z: 100.000 + - x: 360.537 + y: 666.776 + z: 100.000 + - x: 360.490 + y: 668.775 + z: 100.000 + - x: 360.442 + y: 670.774 + z: 100.000 + - x: 360.394 + y: 672.774 + z: 100.000 + - x: 360.347 + y: 674.773 + z: 100.000 + - x: 360.220 + y: 680.099 + z: 100.000 +dynamic_object: + header: + stamp: + sec: 563 + nanosec: 160706650 + frame_id: map + objects: + - object_id: + uuid: + - 6 + - 144 + - 167 + - 221 + - 26 + - 196 + - 145 + - 186 + - 207 + - 95 + - 21 + - 211 + - 96 + - 13 + - 92 + - 5 + existence_probability: 0.00000 + classification: + - label: 6 + probability: 1.00000 + kinematics: + initial_pose_with_covariance: + pose: + position: + x: 404.688 + y: 647.065 + z: 100.630 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00901435 + w: 0.999959 + covariance: + - 0.415785 + - -0.000621846 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - -0.000621846 + - 0.388031 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.0108039 + initial_twist_with_covariance: + twist: + linear: + x: 9.96635 + y: 3.24754e-05 + z: 0.00000 + angular: + x: 0.00000 + y: 0.00000 + z: 5.69744e-05 + covariance: + - 1.01780 + - -2.02150e-05 + - 0.00000 + - 0.00000 + - 0.00000 + - -3.54650e-05 + - -2.02150e-05 + - 0.00403854 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00708516 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - -3.54650e-05 + - 0.00708516 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.0124301 + initial_acceleration_with_covariance: + accel: + linear: + x: 0.00000 + y: 0.00000 + z: 0.00000 + angular: + x: 0.00000 + y: 0.00000 + z: 0.00000 + covariance: + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + predicted_paths: + - path: + - position: + x: 404.688 + y: 647.065 + z: 100.630 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00901435 + w: 0.999959 + - position: + x: 409.670 + y: 647.155 + z: 100.630 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00901435 + w: 0.999959 + - position: + x: 414.653 + y: 647.245 + z: 100.630 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00901435 + w: 0.999959 + - position: + x: 419.635 + y: 647.335 + z: 100.630 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00901435 + w: 0.999959 + - position: + x: 424.617 + y: 647.425 + z: 100.630 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00901435 + w: 0.999959 + - position: + x: 429.600 + y: 647.515 + z: 100.630 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00901435 + w: 0.999959 + - position: + x: 434.582 + y: 647.605 + z: 100.630 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00901435 + w: 0.999959 + - position: + x: 439.565 + y: 647.694 + z: 100.630 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00901435 + w: 0.999959 + - position: + x: 444.547 + y: 647.784 + z: 100.630 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00901435 + w: 0.999959 + - position: + x: 449.529 + y: 647.874 + z: 100.630 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00901435 + w: 0.999959 + - position: + x: 454.512 + y: 647.964 + z: 100.630 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00901435 + w: 0.999959 + - position: + x: 459.494 + y: 648.054 + z: 100.630 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00901435 + w: 0.999959 + - position: + x: 464.476 + y: 648.144 + z: 100.630 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00901435 + w: 0.999959 + - position: + x: 469.459 + y: 648.233 + z: 100.630 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00901435 + w: 0.999959 + - position: + x: 474.441 + y: 648.323 + z: 100.630 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00901435 + w: 0.999959 + - position: + x: 479.423 + y: 648.413 + z: 100.630 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00901435 + w: 0.999959 + - position: + x: 484.406 + y: 648.503 + z: 100.630 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00901435 + w: 0.999959 + - position: + x: 489.388 + y: 648.593 + z: 100.630 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00901435 + w: 0.999959 + - position: + x: 494.371 + y: 648.683 + z: 100.630 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00901435 + w: 0.999959 + - position: + x: 499.353 + y: 648.773 + z: 100.630 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00901435 + w: 0.999959 + - position: + x: 504.335 + y: 648.862 + z: 100.630 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00901435 + w: 0.999959 + time_step: + sec: 0 + nanosec: 500000000 + confidence: 1.00000 + shape: + type: 0 + footprint: + points: [] + dimensions: + x: 1.90000 + y: 0.501209 + z: 0.690476 + - object_id: + uuid: + - 32 + - 119 + - 141 + - 16 + - 72 + - 85 + - 32 + - 153 + - 66 + - 136 + - 88 + - 177 + - 247 + - 166 + - 151 + - 80 + existence_probability: 0.00000 + classification: + - label: 6 + probability: 1.00000 + kinematics: + initial_pose_with_covariance: + pose: + position: + x: 323.928 + y: 644.831 + z: 100.568 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.00410256 + w: 0.999992 + covariance: + - 0.0657687 + - -0.000366900 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - -0.000366900 + - 0.0451891 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00300423 + initial_twist_with_covariance: + twist: + linear: + x: 10.0048 + y: -0.00124906 + z: 0.00000 + angular: + x: 0.00000 + y: 0.00000 + z: -0.00219133 + covariance: + - 0.522271 + - -6.09993e-05 + - 0.00000 + - 0.00000 + - 0.00000 + - -0.000107016 + - -6.09993e-05 + - 0.00263830 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00462859 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - -0.000107016 + - 0.00462859 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00812034 + initial_acceleration_with_covariance: + accel: + linear: + x: 0.00000 + y: 0.00000 + z: 0.00000 + angular: + x: 0.00000 + y: 0.00000 + z: 0.00000 + covariance: + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + predicted_paths: + - path: + - position: + x: 323.928 + y: 644.831 + z: 100.568 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.00410256 + w: 0.999992 + - position: + x: 328.930 + y: 644.785 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.00453640 + w: 0.999990 + - position: + x: 333.933 + y: 644.723 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.00622365 + w: 0.999981 + - position: + x: 338.935 + y: 644.640 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.00828910 + w: 0.999966 + - position: + x: 343.877 + y: 644.600 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.00409926 + w: 0.999992 + - position: + x: 348.624 + y: 645.122 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.0547342 + w: 0.998501 + - position: + x: 352.898 + y: 646.993 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.204867 + w: 0.978790 + - position: + x: 356.221 + y: 650.176 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.372718 + w: 0.927945 + - position: + x: 358.029 + y: 654.521 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.554937 + w: 0.831892 + - position: + x: 358.484 + y: 659.393 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.673390 + w: 0.739287 + - position: + x: 358.380 + y: 664.391 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.714418 + w: 0.699720 + - position: + x: 358.261 + y: 669.391 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 358.142 + y: 674.391 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 358.023 + y: 679.392 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 357.904 + y: 684.392 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 357.784 + y: 689.392 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 357.665 + y: 694.393 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 357.546 + y: 699.393 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 357.427 + y: 704.394 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 357.308 + y: 709.394 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 357.188 + y: 714.395 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 357.069 + y: 719.395 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 356.950 + y: 724.396 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 356.831 + y: 729.397 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 356.712 + y: 734.398 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 356.593 + y: 739.399 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 356.473 + y: 744.400 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 356.354 + y: 749.400 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 356.235 + y: 754.401 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 356.116 + y: 759.402 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 355.997 + y: 764.403 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + time_step: + sec: 0 + nanosec: 500000000 + confidence: 0.250000 + - path: + - position: + x: 323.928 + y: 644.831 + z: 100.568 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.00410256 + w: 0.999992 + - position: + x: 328.930 + y: 644.786 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.00451016 + w: 0.999990 + - position: + x: 333.933 + y: 644.725 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.00607237 + w: 0.999982 + - position: + x: 338.935 + y: 644.645 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.00796688 + w: 0.999968 + - position: + x: 343.880 + y: 644.606 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.00392303 + w: 0.999992 + - position: + x: 348.786 + y: 644.906 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.0304731 + w: 0.999536 + - position: + x: 353.463 + y: 645.966 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.111241 + w: 0.993793 + - position: + x: 357.696 + y: 648.148 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.235723 + w: 0.971820 + - position: + x: 361.186 + y: 651.334 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.361617 + w: 0.932327 + - position: + x: 363.716 + y: 655.456 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.488304 + w: 0.872674 + - position: + x: 364.853 + y: 660.052 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.616332 + w: 0.787487 + - position: + x: 364.887 + y: 665.003 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.704715 + w: 0.709490 + - position: + x: 364.768 + y: 670.003 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 364.648 + y: 675.003 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 364.529 + y: 680.004 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 364.410 + y: 685.004 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 364.291 + y: 690.005 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 364.172 + y: 695.005 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 364.053 + y: 700.006 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 363.933 + y: 705.006 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 363.814 + y: 710.007 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 363.695 + y: 715.007 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 363.576 + y: 720.008 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 363.457 + y: 725.009 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 363.338 + y: 730.010 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 363.218 + y: 735.011 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 363.099 + y: 740.011 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 362.980 + y: 745.012 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 362.861 + y: 750.013 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 362.742 + y: 755.014 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 362.622 + y: 760.015 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + time_step: + sec: 0 + nanosec: 500000000 + confidence: 0.250000 + - path: + - position: + x: 323.928 + y: 644.831 + z: 100.568 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.00410256 + w: 0.999992 + - position: + x: 328.930 + y: 644.786 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.00451016 + w: 0.999990 + - position: + x: 333.933 + y: 644.725 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.00607237 + w: 0.999982 + - position: + x: 338.935 + y: 644.645 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.00796688 + w: 0.999968 + - position: + x: 343.873 + y: 644.613 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.00329511 + w: 0.999995 + - position: + x: 348.698 + y: 645.015 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.0415760 + w: 0.999135 + - position: + x: 353.223 + y: 646.395 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.147464 + w: 0.989067 + - position: + x: 357.115 + y: 649.075 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.296991 + w: 0.954880 + - position: + x: 359.997 + y: 652.871 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.444541 + w: 0.895759 + - position: + x: 361.525 + y: 657.337 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.581548 + w: 0.813512 + - position: + x: 361.651 + y: 662.207 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.697878 + w: 0.716217 + - position: + x: 361.533 + y: 667.205 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715386 + w: 0.698729 + - position: + x: 361.414 + y: 672.205 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 361.295 + y: 677.206 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 361.176 + y: 682.206 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 361.057 + y: 687.206 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 360.938 + y: 692.207 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 360.818 + y: 697.207 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 360.699 + y: 702.208 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 360.580 + y: 707.208 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 360.461 + y: 712.209 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 360.342 + y: 717.209 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 360.222 + y: 722.210 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 360.103 + y: 727.211 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 359.984 + y: 732.212 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 359.865 + y: 737.213 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 359.746 + y: 742.214 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 359.626 + y: 747.214 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 359.507 + y: 752.215 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 359.388 + y: 757.216 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 359.269 + y: 762.217 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + time_step: + sec: 0 + nanosec: 500000000 + confidence: 0.250000 + - path: + - position: + x: 323.928 + y: 644.831 + z: 100.568 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.00410256 + w: 0.999992 + - position: + x: 328.930 + y: 644.785 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.00457230 + w: 0.999990 + - position: + x: 333.933 + y: 644.721 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.00644958 + w: 0.999979 + - position: + x: 338.935 + y: 644.632 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.00883007 + w: 0.999961 + - position: + x: 343.938 + y: 644.526 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.0105871 + w: 0.999944 + - position: + x: 348.941 + y: 644.416 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.0110042 + w: 0.999939 + - position: + x: 353.943 + y: 644.319 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.00972075 + w: 0.999953 + - position: + x: 358.946 + y: 644.250 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.00691289 + w: 0.999976 + - position: + x: 363.948 + y: 644.219 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.00309863 + w: 0.999995 + - position: + x: 368.950 + y: 644.228 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.000886733 + w: 1.00000 + - position: + x: 373.952 + y: 644.264 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00363761 + w: 0.999993 + - position: + x: 378.954 + y: 644.305 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00413557 + w: 0.999991 + - position: + x: 383.955 + y: 644.347 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00420318 + w: 0.999991 + - position: + x: 388.957 + y: 644.388 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00411113 + w: 0.999992 + - position: + x: 393.958 + y: 644.432 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00439488 + w: 0.999990 + - position: + x: 398.956 + y: 644.454 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00215849 + w: 0.999998 + - position: + x: 403.941 + y: 644.630 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.0176845 + w: 0.999844 + - position: + x: 408.939 + y: 644.821 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.0190608 + w: 0.999818 + - position: + x: 413.938 + y: 645.012 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.0190608 + w: 0.999818 + - position: + x: 418.936 + y: 645.202 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.0190608 + w: 0.999818 + - position: + x: 423.935 + y: 645.393 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.0190608 + w: 0.999818 + - position: + x: 428.933 + y: 645.584 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.0190608 + w: 0.999818 + - position: + x: 433.932 + y: 645.774 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.0190608 + w: 0.999818 + - position: + x: 438.931 + y: 645.965 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.0190608 + w: 0.999818 + - position: + x: 443.929 + y: 646.156 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.0190608 + w: 0.999818 + - position: + x: 448.928 + y: 646.346 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.0190608 + w: 0.999818 + - position: + x: 453.927 + y: 646.537 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.0190608 + w: 0.999818 + - position: + x: 458.925 + y: 646.728 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.0190608 + w: 0.999818 + - position: + x: 463.924 + y: 646.918 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.0190608 + w: 0.999818 + - position: + x: 468.923 + y: 647.109 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.0190608 + w: 0.999818 + - position: + x: 473.922 + y: 647.300 + z: 100.384 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.0190608 + w: 0.999818 + time_step: + sec: 0 + nanosec: 500000000 + confidence: 0.250000 + shape: + type: 0 + footprint: + points: [] + dimensions: + x: 1.90000 + y: 0.604998 + z: 0.767451 +traffic_signal: + stamp: + sec: 0 + nanosec: 0 + traffic_light_groups: [] +route: + header: + stamp: + sec: 21 + nanosec: 17351334 + frame_id: map + start_pose: + position: + x: 301.475 + y: 642.905 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00500123 + w: 0.999987 + goal_pose: + position: + x: 358.812 + y: 675.174 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.705159 + w: 0.709049 + segments: + - preferred_primitive: + id: 2000 + primitive_type: "" + primitives: + - id: 2000 + primitive_type: lane + - id: 2001 + primitive_type: lane + - id: 2002 + primitive_type: lane + - preferred_primitive: + id: 2010 + primitive_type: "" + primitives: + - id: 2010 + primitive_type: lane + - preferred_primitive: + id: 2200 + primitive_type: "" + primitives: + - id: 2200 + primitive_type: lane + - preferred_primitive: + id: 3500 + primitive_type: "" + primitives: + - id: 3500 + primitive_type: lane + - id: 3501 + primitive_type: lane + - id: 3502 + primitive_type: lane + uuid: + uuid: + - 195 + - 84 + - 241 + - 105 + - 133 + - 218 + - 136 + - 83 + - 104 + - 191 + - 48 + - 109 + - 85 + - 60 + - 177 + - 115 + allow_modification: false +operation_mode: + stamp: + sec: 550 + nanosec: 913829317 + mode: 2 + is_autoware_control_enabled: true + is_in_transition: false + is_stop_mode_available: true + is_autonomous_mode_available: true + is_local_mode_available: true + is_remote_mode_available: true +self_acceleration: + header: + stamp: + sec: 563 + nanosec: 188542779 + frame_id: /base_link + accel: + accel: + linear: + x: -0.770147 + y: 0.0409905 + z: 0.00000 + angular: + x: 0.00000 + y: 0.00000 + z: 0.00000 + covariance: + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 +self_odometry: + header: + stamp: + sec: 563 + nanosec: 188542779 + frame_id: map + child_frame_id: base_link + pose: + pose: + position: + x: 337.371 + y: 643.219 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.00401753 + w: 0.999992 + covariance: + - 0.000100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.000100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + twist: + twist: + linear: + x: 4.13155 + y: 0.00000 + z: 0.00000 + angular: + x: 0.00000 + y: 0.00000 + z: 0.00992133 + covariance: + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/test_data/object_on_shoulder.yaml b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/test_data/object_on_shoulder.yaml new file mode 100644 index 0000000000000..9a20cbee9c1ff --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/test_data/object_on_shoulder.yaml @@ -0,0 +1,2512 @@ +# +# AUTO GENERATED by autoware_test_utils::topic_snapshot_saver +# format1: +# +# format_version: +# map_path_uri: package:/// +# fields(this is array) +# - name: +# type: either {Odometry | AccelWithCovarianceStamped | PredictedObjects | OperationModeState | LaneletRoute | TrafficLightGroupArray | TrackedObjects | PathWithLaneId | TBD} +# topic: +# +format_version: 1 +map_path_uri: package://autoware_test_utils/test_map/intersection/lanelet2_map.osm +path_with_lane_id: + header: + stamp: + sec: 74 + nanosec: 11949715 + frame_id: map + points: + - point: + pose: + position: + x: 360.306 + y: 597.246 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.710800 + w: 0.703394 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 1010 + - point: + pose: + position: + x: 360.285 + y: 599.246 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.710829 + w: 0.703365 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 1010 + - point: + pose: + position: + x: 360.264 + y: 601.246 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.710857 + w: 0.703336 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 1010 + - point: + pose: + position: + x: 360.243 + y: 603.246 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.710881 + w: 0.703312 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 1010 + - point: + pose: + position: + x: 360.222 + y: 605.246 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.710951 + w: 0.703242 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 1010 + - point: + pose: + position: + x: 360.200 + y: 607.246 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.711036 + w: 0.703156 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 1010 + - point: + pose: + position: + x: 360.177 + y: 609.246 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.711601 + w: 0.702584 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 1010 + - point: + pose: + position: + x: 360.152 + y: 611.245 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.711932 + w: 0.702248 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 1010 + - point: + pose: + position: + x: 360.133 + y: 612.628 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.716985 + w: 0.697089 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 1010 + - 1200 + - point: + pose: + position: + x: 360.116 + y: 613.245 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.732064 + w: 0.681236 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 1200 + - point: + pose: + position: + x: 359.972 + y: 615.239 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.740537 + w: 0.672016 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 1200 + - point: + pose: + position: + x: 359.778 + y: 617.231 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.759018 + w: 0.651069 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 1200 + - point: + pose: + position: + x: 359.474 + y: 619.204 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.784627 + w: 0.619968 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 1200 + - point: + pose: + position: + x: 359.010 + y: 621.159 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.835622 + w: 0.549305 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 1200 + - point: + pose: + position: + x: 358.221 + y: 622.986 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.876871 + w: 0.480726 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 1200 + - point: + pose: + position: + x: 357.127 + y: 624.700 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.906015 + w: 0.423245 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 1200 + - point: + pose: + position: + x: 355.847 + y: 626.230 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.934815 + w: 0.355135 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 1200 + - point: + pose: + position: + x: 354.341 + y: 627.567 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.956562 + w: 0.291529 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 1200 + - point: + pose: + position: + x: 352.674 + y: 628.688 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.976933 + w: 0.213544 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 1200 + - point: + pose: + position: + x: 350.854 + y: 629.523 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.989029 + w: 0.147720 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 1200 + - point: + pose: + position: + x: 348.920 + y: 630.114 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.997418 + w: 0.0718077 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 1200 + - point: + pose: + position: + x: 346.951 + y: 630.399 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.999926 + w: 0.0121684 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 1200 + - point: + pose: + position: + x: 344.951 + y: 630.448 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 1.00000 + w: 0.000253960 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 1200 + - point: + pose: + position: + x: 342.951 + y: 630.449 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999959 + w: 0.00906744 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 1200 + - point: + pose: + position: + x: 342.741 + y: 630.445 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999949 + w: 0.0100898 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 1200 + - 2500 + - point: + pose: + position: + x: 340.951 + y: 630.409 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999893 + w: 0.0146423 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2500 + - point: + pose: + position: + x: 339.014 + y: 630.352 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999803 + w: 0.0198557 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2500 + - point: + pose: + position: + x: 337.016 + y: 630.273 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999732 + w: 0.0231414 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2500 + - point: + pose: + position: + x: 335.018 + y: 630.180 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999702 + w: 0.0243973 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2500 + - point: + pose: + position: + x: 333.020 + y: 630.083 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999705 + w: 0.0242858 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2500 + - point: + pose: + position: + x: 332.731 + y: 630.068 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999615 + w: 0.0277448 + longitudinal_velocity_mps: 16.6667 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2500 + - point: + pose: + position: + x: 331.733 + y: 630.013 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999615 + w: 0.0277448 + longitudinal_velocity_mps: 0.00000 + lateral_velocity_mps: 0.00000 + heading_rate_rps: 0.00000 + is_final: false + lane_ids: + - 2500 + left_bound: + - x: 358.794 + y: 596.731 + z: 100.000 + - x: 358.788 + y: 597.342 + z: 100.000 + - x: 358.758 + y: 600.198 + z: 100.000 + - x: 358.736 + y: 602.392 + z: 100.000 + - x: 358.718 + y: 604.199 + z: 100.000 + - x: 358.698 + y: 606.199 + z: 100.000 + - x: 358.686 + y: 607.440 + z: 100.000 + - x: 358.610 + y: 610.191 + z: 100.000 + - x: 358.512 + y: 612.597 + z: 100.000 + - x: 358.405 + y: 614.096 + z: 100.000 + - x: 358.218 + y: 616.079 + z: 100.000 + - x: 358.086 + y: 617.465 + z: 100.000 + - x: 357.913 + y: 618.622 + z: 100.000 + - x: 357.666 + y: 619.746 + z: 100.000 + - x: 357.285 + y: 620.810 + z: 100.000 + - x: 356.832 + y: 621.812 + z: 100.000 + - x: 356.284 + y: 622.823 + z: 100.000 + - x: 355.663 + y: 623.752 + z: 100.000 + - x: 354.964 + y: 624.613 + z: 100.000 + - x: 354.158 + y: 625.437 + z: 100.000 + - x: 353.306 + y: 626.152 + z: 100.000 + - x: 352.395 + y: 626.788 + z: 100.000 + - x: 351.400 + y: 627.366 + z: 100.000 + - x: 350.389 + y: 627.820 + z: 100.000 + - x: 349.337 + y: 628.212 + z: 100.000 + - x: 348.219 + y: 628.479 + z: 100.000 + - x: 347.083 + y: 628.681 + z: 100.000 + - x: 346.042 + y: 628.729 + z: 100.000 + - x: 344.050 + y: 628.720 + z: 100.000 + - x: 342.764 + y: 628.777 + z: 100.000 + - x: 340.080 + y: 628.723 + z: 100.000 + - x: 338.078 + y: 628.751 + z: 100.000 + - x: 336.079 + y: 628.710 + z: 100.000 + - x: 334.080 + y: 628.670 + z: 100.000 + - x: 332.082 + y: 628.629 + z: 100.000 + - x: 326.872 + y: 628.524 + z: 100.000 + right_bound: + - x: 361.830 + y: 596.762 + z: 100.000 + - x: 361.823 + y: 597.400 + z: 100.000 + - x: 361.792 + y: 600.231 + z: 100.000 + - x: 361.767 + y: 602.446 + z: 100.000 + - x: 361.748 + y: 604.230 + z: 100.000 + - x: 361.726 + y: 606.230 + z: 100.000 + - x: 361.712 + y: 607.493 + z: 100.000 + - x: 361.718 + y: 610.230 + z: 100.000 + - x: 361.754 + y: 612.657 + z: 100.000 + - x: 361.627 + y: 614.331 + z: 100.000 + - x: 361.519 + y: 616.330 + z: 100.000 + - x: 361.452 + y: 617.634 + z: 100.000 + - x: 361.277 + y: 619.056 + z: 100.000 + - x: 360.998 + y: 620.486 + z: 100.000 + - x: 360.581 + y: 621.905 + z: 100.000 + - x: 359.991 + y: 623.293 + z: 100.000 + - x: 359.319 + y: 624.583 + z: 100.000 + - x: 358.490 + y: 625.825 + z: 100.000 + - x: 357.546 + y: 626.984 + z: 100.000 + - x: 356.525 + y: 628.025 + z: 100.000 + - x: 355.377 + y: 628.981 + z: 100.000 + - x: 354.158 + y: 629.845 + z: 100.000 + - x: 352.881 + y: 630.552 + z: 100.000 + - x: 351.515 + y: 631.167 + z: 100.000 + - x: 350.098 + y: 631.615 + z: 100.000 + - x: 348.672 + y: 631.919 + z: 100.000 + - x: 347.236 + y: 632.124 + z: 100.000 + - x: 346.083 + y: 632.098 + z: 100.000 + - x: 344.082 + y: 632.081 + z: 100.000 + - x: 342.719 + y: 632.113 + z: 100.000 + - x: 340.012 + y: 632.058 + z: 100.000 + - x: 338.014 + y: 631.950 + z: 100.000 + - x: 336.015 + y: 631.909 + z: 100.000 + - x: 334.016 + y: 631.869 + z: 100.000 + - x: 332.017 + y: 631.829 + z: 100.000 + - x: 326.807 + y: 631.724 + z: 100.000 +dynamic_object: + header: + stamp: + sec: 73 + nanosec: 980215670 + frame_id: map + objects: + - object_id: + uuid: + - 251 + - 180 + - 23 + - 85 + - 112 + - 118 + - 142 + - 88 + - 241 + - 29 + - 194 + - 27 + - 222 + - 164 + - 130 + - 251 + existence_probability: 0.00000 + classification: + - label: 6 + probability: 1.00000 + kinematics: + initial_pose_with_covariance: + pose: + position: + x: 357.408 + y: 667.312 + z: 100.774 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.712257 + w: 0.701919 + covariance: + - 0.299126 + - -8.23923e-05 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - -8.23923e-05 + - 0.349251 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00879510 + initial_twist_with_covariance: + twist: + linear: + x: 9.98083 + y: 0.00185652 + z: 0.00000 + angular: + x: 0.00000 + y: 0.00000 + z: 0.00325706 + covariance: + - 0.970951 + - 0.000139981 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.000245582 + - 0.000139981 + - 0.00384142 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00673936 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - 0.000245582 + - 0.00673936 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.0118235 + initial_acceleration_with_covariance: + accel: + linear: + x: 0.00000 + y: 0.00000 + z: 0.00000 + angular: + x: 0.00000 + y: 0.00000 + z: 0.00000 + covariance: + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + predicted_paths: + - path: + - position: + x: 357.408 + y: 667.312 + z: 100.774 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.712257 + w: 0.701919 + - position: + x: 357.373 + y: 672.303 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.709614 + w: 0.704590 + - position: + x: 357.520 + y: 677.298 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.696604 + w: 0.717456 + - position: + x: 357.917 + y: 682.299 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.678600 + w: 0.734508 + - position: + x: 358.531 + y: 687.305 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.662668 + w: 0.748913 + - position: + x: 359.266 + y: 692.315 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.653723 + w: 0.756734 + - position: + x: 359.995 + y: 697.324 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.654217 + w: 0.756307 + - position: + x: 360.590 + y: 702.329 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.664107 + w: 0.747638 + - position: + x: 360.955 + y: 707.330 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.680844 + w: 0.732428 + - position: + x: 361.063 + y: 712.324 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.699424 + w: 0.714707 + - position: + x: 360.983 + y: 717.314 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.712725 + w: 0.701443 + - position: + x: 360.864 + y: 722.303 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 360.746 + y: 727.292 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 360.627 + y: 732.280 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 360.508 + y: 737.269 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 360.389 + y: 742.258 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 360.270 + y: 747.247 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 360.151 + y: 752.236 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 360.032 + y: 757.225 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 359.913 + y: 762.214 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 359.794 + y: 767.203 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 359.675 + y: 772.192 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 359.557 + y: 777.181 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 359.438 + y: 782.170 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 359.319 + y: 787.159 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 359.200 + y: 792.148 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 359.081 + y: 797.137 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 358.962 + y: 802.126 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 358.843 + y: 807.115 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 358.724 + y: 812.104 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 358.605 + y: 817.093 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + time_step: + sec: 0 + nanosec: 500000000 + confidence: 0.230769 + - path: + - position: + x: 357.408 + y: 667.312 + z: 100.774 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.712257 + w: 0.701919 + - position: + x: 357.340 + y: 672.302 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.711946 + w: 0.702234 + - position: + x: 357.296 + y: 677.293 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.710176 + w: 0.704024 + - position: + x: 357.286 + y: 682.284 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.707820 + w: 0.706393 + - position: + x: 357.304 + y: 687.276 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.705868 + w: 0.708343 + - position: + x: 357.334 + y: 692.269 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.704976 + w: 0.709232 + - position: + x: 357.357 + y: 697.261 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.705452 + w: 0.708758 + - position: + x: 357.355 + y: 702.252 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.707256 + w: 0.706957 + - position: + x: 357.314 + y: 707.243 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.709999 + w: 0.704203 + - position: + x: 357.231 + y: 712.233 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.712949 + w: 0.701216 + - position: + x: 357.119 + y: 717.222 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715047 + w: 0.699076 + - position: + x: 357.000 + y: 722.211 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 356.881 + y: 727.199 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 356.762 + y: 732.188 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 356.643 + y: 737.177 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 356.524 + y: 742.166 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 356.405 + y: 747.155 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 356.286 + y: 752.144 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 356.167 + y: 757.133 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 356.049 + y: 762.122 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 355.930 + y: 767.111 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 355.811 + y: 772.100 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 355.692 + y: 777.089 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 355.573 + y: 782.078 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 355.454 + y: 787.067 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 355.335 + y: 792.056 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 355.216 + y: 797.045 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 355.097 + y: 802.033 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 354.978 + y: 807.022 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 354.859 + y: 812.011 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 354.741 + y: 817.000 + z: 100.306 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + time_step: + sec: 0 + nanosec: 500000000 + confidence: 0.769231 + shape: + type: 0 + footprint: + points: [] + dimensions: + x: 1.89999 + y: 0.500442 + z: 0.612431 + - object_id: + uuid: + - 218 + - 141 + - 152 + - 171 + - 185 + - 127 + - 84 + - 175 + - 69 + - 40 + - 199 + - 89 + - 96 + - 107 + - 61 + - 243 + existence_probability: 0.00000 + classification: + - label: 6 + probability: 1.00000 + kinematics: + initial_pose_with_covariance: + pose: + position: + x: 358.218 + y: 603.622 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.707443 + w: 0.706770 + covariance: + - 0.0636258 + - -0.000170219 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - -0.000170219 + - 0.0826995 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00394708 + initial_twist_with_covariance: + twist: + linear: + x: 10.0303 + y: -0.00247386 + z: 0.00000 + angular: + x: 0.00000 + y: 0.00000 + z: -0.00434011 + covariance: + - 0.579437 + - -9.81341e-05 + - 0.00000 + - 0.00000 + - 0.00000 + - -0.000172165 + - -9.81341e-05 + - 0.00311875 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00547149 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - -0.000172165 + - 0.00547149 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00959910 + initial_acceleration_with_covariance: + accel: + linear: + x: 0.00000 + y: 0.00000 + z: 0.00000 + angular: + x: 0.00000 + y: 0.00000 + z: 0.00000 + covariance: + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + predicted_paths: + - path: + - position: + x: 358.218 + y: 603.622 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.707443 + w: 0.706770 + - position: + x: 358.224 + y: 608.637 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.706633 + w: 0.707581 + - position: + x: 358.279 + y: 613.653 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.703235 + w: 0.710958 + - position: + x: 358.397 + y: 618.671 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.698737 + w: 0.715379 + - position: + x: 358.567 + y: 623.690 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.695068 + w: 0.718944 + - position: + x: 358.758 + y: 628.710 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.693532 + w: 0.720426 + - position: + x: 358.932 + y: 633.729 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.694735 + w: 0.719266 + - position: + x: 359.054 + y: 638.747 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.698453 + w: 0.715656 + - position: + x: 359.097 + y: 643.763 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.704045 + w: 0.710155 + - position: + x: 359.057 + y: 648.778 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.709938 + w: 0.704265 + - position: + x: 358.958 + y: 653.791 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.714096 + w: 0.700048 + - position: + x: 358.849 + y: 658.805 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.714730 + w: 0.699401 + - position: + x: 358.740 + y: 663.817 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.714768 + w: 0.699361 + - position: + x: 358.620 + y: 668.830 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 358.501 + y: 673.843 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 358.381 + y: 678.856 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 358.262 + y: 683.870 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 358.142 + y: 688.883 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 358.023 + y: 693.896 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 357.903 + y: 698.909 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 357.784 + y: 703.923 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 357.664 + y: 708.936 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 357.545 + y: 713.950 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 357.425 + y: 718.963 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 357.306 + y: 723.977 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 357.186 + y: 728.991 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 357.067 + y: 734.004 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 356.947 + y: 739.018 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 356.828 + y: 744.032 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 356.708 + y: 749.045 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + - position: + x: 356.589 + y: 754.059 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715481 + w: 0.698632 + time_step: + sec: 0 + nanosec: 500000000 + confidence: 0.500000 + - path: + - position: + x: 358.218 + y: 603.622 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.707443 + w: 0.706770 + - position: + x: 358.206 + y: 608.635 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.707930 + w: 0.706283 + - position: + x: 358.149 + y: 613.642 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.711130 + w: 0.703060 + - position: + x: 358.010 + y: 618.635 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.716853 + w: 0.697224 + - position: + x: 357.024 + y: 623.117 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.779378 + w: 0.626554 + - position: + x: 354.441 + y: 627.006 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.881248 + w: 0.472653 + - position: + x: 350.340 + y: 629.665 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.958935 + w: 0.283625 + - position: + x: 345.469 + y: 630.694 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.994592 + w: 0.103864 + - position: + x: 340.508 + y: 630.814 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.999926 + w: 0.0121264 + - position: + x: 335.554 + y: 630.768 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999989 + w: 0.00460609 + - position: + x: 330.597 + y: 630.677 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999957 + w: 0.00925679 + - position: + x: 325.638 + y: 630.576 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999949 + w: 0.0100898 + - position: + x: 320.674 + y: 630.476 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999949 + w: 0.0100898 + - position: + x: 315.708 + y: 630.376 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999949 + w: 0.0100898 + - position: + x: 310.737 + y: 630.276 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999949 + w: 0.0100898 + - position: + x: 305.763 + y: 630.175 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999949 + w: 0.0100898 + - position: + x: 300.785 + y: 630.075 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999949 + w: 0.0100898 + - position: + x: 295.803 + y: 629.974 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999949 + w: 0.0100898 + - position: + x: 290.817 + y: 629.874 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999949 + w: 0.0100898 + - position: + x: 285.828 + y: 629.773 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999949 + w: 0.0100898 + - position: + x: 280.835 + y: 629.672 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999949 + w: 0.0100898 + - position: + x: 275.839 + y: 629.571 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999949 + w: 0.0100898 + - position: + x: 270.840 + y: 629.470 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999949 + w: 0.0100898 + - position: + x: 265.838 + y: 629.370 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999949 + w: 0.0100898 + - position: + x: 260.833 + y: 629.268 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999949 + w: 0.0100898 + - position: + x: 255.825 + y: 629.167 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999949 + w: 0.0100898 + - position: + x: 250.816 + y: 629.066 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999949 + w: 0.0100898 + - position: + x: 245.805 + y: 628.965 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999949 + w: 0.0100898 + - position: + x: 240.792 + y: 628.864 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999949 + w: 0.0100898 + - position: + x: 235.778 + y: 628.763 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999949 + w: 0.0100898 + - position: + x: 230.764 + y: 628.662 + z: 100.496 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.999949 + w: 0.0100898 + time_step: + sec: 0 + nanosec: 500000000 + confidence: 0.500000 + shape: + type: 0 + footprint: + points: [] + dimensions: + x: 1.90000 + y: 0.644288 + z: 0.991445 +traffic_signal: + stamp: + sec: 0 + nanosec: 0 + traffic_light_groups: [] +route: + header: + stamp: + sec: 19 + nanosec: 549630704 + frame_id: map + start_pose: + position: + x: 360.481 + y: 591.844 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.721675 + w: 0.692232 + goal_pose: + position: + x: 331.733 + y: 630.013 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.999615 + w: -0.0277448 + segments: + - preferred_primitive: + id: 1010 + primitive_type: "" + primitives: + - id: 1010 + primitive_type: lane + - preferred_primitive: + id: 1200 + primitive_type: "" + primitives: + - id: 1200 + primitive_type: lane + - preferred_primitive: + id: 2500 + primitive_type: "" + primitives: + - id: 2500 + primitive_type: lane + - id: 2501 + primitive_type: lane + uuid: + uuid: + - 83 + - 230 + - 40 + - 201 + - 182 + - 232 + - 31 + - 237 + - 204 + - 91 + - 39 + - 90 + - 153 + - 179 + - 6 + - 123 + allow_modification: false +operation_mode: + stamp: + sec: 65 + nanosec: 819714871 + mode: 2 + is_autoware_control_enabled: true + is_in_transition: false + is_stop_mode_available: true + is_autonomous_mode_available: true + is_local_mode_available: true + is_remote_mode_available: true +self_acceleration: + header: + stamp: + sec: 74 + nanosec: 42641063 + frame_id: /base_link + accel: + accel: + linear: + x: -1.01094 + y: 0.00400509 + z: 0.00000 + angular: + x: 0.00000 + y: 0.00000 + z: 0.00000 + covariance: + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 +self_odometry: + header: + stamp: + sec: 74 + nanosec: 42641063 + frame_id: map + child_frame_id: base_link + pose: + pose: + position: + x: 360.302 + y: 604.493 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.707950 + w: 0.706263 + covariance: + - 0.000100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.000100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + twist: + twist: + linear: + x: 2.31221 + y: 0.00000 + z: 0.00000 + angular: + x: 0.00000 + y: 0.00000 + z: 0.00173214 + covariance: + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 From 9ce874c9131f37a57c8661a5e65affa95831b381 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Wed, 8 Jan 2025 16:02:09 +0900 Subject: [PATCH 152/334] feat(lidar_centerpoint, pointpainting): add diag publisher for max voxel size (#9720) --- .../pointpainting_fusion/node.hpp | 2 ++ .../src/pointpainting_fusion/node.cpp | 17 ++++++++++++++++- .../lidar_centerpoint/centerpoint_trt.hpp | 2 +- .../include/autoware/lidar_centerpoint/node.hpp | 2 ++ .../lib/centerpoint_trt.cpp | 6 +++++- .../autoware_lidar_centerpoint/src/node.cpp | 17 ++++++++++++++++- 6 files changed, 42 insertions(+), 4 deletions(-) diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/node.hpp index cd6cd87976522..5bc428a8e7ab8 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/node.hpp @@ -23,6 +23,7 @@ #include #include #include +#include #include #include @@ -58,6 +59,7 @@ class PointPaintingFusionNode void postprocess(sensor_msgs::msg::PointCloud2 & painted_pointcloud_msg) override; rclcpp::Publisher::SharedPtr obj_pub_ptr_; + std::unique_ptr diagnostics_interface_ptr_; int omp_num_threads_{1}; float score_threshold_{0.0}; diff --git a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp index 25d9064ddbfc7..2f6f853d4281e 100644 --- a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp @@ -186,6 +186,8 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt // create detector detector_ptr_ = std::make_unique( encoder_param, head_param, densification_param, config); + diagnostics_interface_ptr_ = + std::make_unique(this, "pointpainting_trt"); obj_pub_ptr_ = this->create_publisher("~/output/objects", rclcpp::QoS{1}); @@ -389,6 +391,7 @@ void PointPaintingFusionNode::postprocess(sensor_msgs::msg::PointCloud2 & painte { std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + diagnostics_interface_ptr_->clear(); const auto objects_sub_count = obj_pub_ptr_->get_subscription_count() + obj_pub_ptr_->get_intra_process_subscription_count(); @@ -403,10 +406,21 @@ void PointPaintingFusionNode::postprocess(sensor_msgs::msg::PointCloud2 & painte } std::vector det_boxes3d; - bool is_success = detector_ptr_->detect(painted_pointcloud_msg, tf_buffer_, det_boxes3d); + bool is_num_pillars_within_range = true; + bool is_success = detector_ptr_->detect( + painted_pointcloud_msg, tf_buffer_, det_boxes3d, is_num_pillars_within_range); if (!is_success) { return; } + diagnostics_interface_ptr_->add_key_value( + "is_num_pillars_within_range", is_num_pillars_within_range); + if (!is_num_pillars_within_range) { + std::stringstream message; + message << "PointPaintingTRT::detect: The actual number of pillars exceeds its maximum value, " + << "which may limit the detection performance."; + diagnostics_interface_ptr_->update_level_and_message( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + } std::vector raw_objects; raw_objects.reserve(det_boxes3d.size()); @@ -425,6 +439,7 @@ void PointPaintingFusionNode::postprocess(sensor_msgs::msg::PointCloud2 & painte if (objects_sub_count > 0) { obj_pub_ptr_->publish(output_msg); } + diagnostics_interface_ptr_->publish(painted_pointcloud_msg.header.stamp); } bool PointPaintingFusionNode::out_of_scope(__attribute__((unused)) const DetectedObjects & obj) diff --git a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/centerpoint_trt.hpp b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/centerpoint_trt.hpp index ce5ec3ea0abfe..671ff54f8ce0d 100644 --- a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/centerpoint_trt.hpp +++ b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/centerpoint_trt.hpp @@ -62,7 +62,7 @@ class CenterPointTRT bool detect( const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer, - std::vector & det_boxes3d); + std::vector & det_boxes3d, bool & is_num_pillars_within_range); protected: void initPtr(); diff --git a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/node.hpp b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/node.hpp index a49451fde9d0d..1748db0e48392 100644 --- a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/node.hpp +++ b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/node.hpp @@ -20,6 +20,7 @@ #include "autoware/lidar_centerpoint/postprocess/non_maximum_suppression.hpp" #include +#include #include #include #include @@ -59,6 +60,7 @@ class LidarCenterPointNode : public rclcpp::Node DetectionClassRemapper detection_class_remapper_; std::unique_ptr detector_ptr_{nullptr}; + std::unique_ptr diagnostics_interface_ptr_; // debugger std::unique_ptr> stop_watch_ptr_{ diff --git a/perception/autoware_lidar_centerpoint/lib/centerpoint_trt.cpp b/perception/autoware_lidar_centerpoint/lib/centerpoint_trt.cpp index 6ee2b3733bdb0..530f59179d25b 100644 --- a/perception/autoware_lidar_centerpoint/lib/centerpoint_trt.cpp +++ b/perception/autoware_lidar_centerpoint/lib/centerpoint_trt.cpp @@ -19,6 +19,7 @@ #include "autoware/lidar_centerpoint/preprocess/preprocess_kernel.hpp" #include +#include #include #include @@ -127,8 +128,10 @@ void CenterPointTRT::initPtr() bool CenterPointTRT::detect( const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer, - std::vector & det_boxes3d) + std::vector & det_boxes3d, bool & is_num_pillars_within_range) { + is_num_pillars_within_range = true; + CHECK_CUDA_ERROR(cudaMemsetAsync( encoder_in_features_d_.get(), 0, encoder_in_feature_size_ * sizeof(float), stream_)); CHECK_CUDA_ERROR( @@ -155,6 +158,7 @@ bool CenterPointTRT::detect( "The actual number of pillars (%u) exceeds its maximum value (%zu). " "Please considering increasing it since it may limit the detection performance.", num_pillars, config_.max_voxel_size_); + is_num_pillars_within_range = false; } return true; diff --git a/perception/autoware_lidar_centerpoint/src/node.cpp b/perception/autoware_lidar_centerpoint/src/node.cpp index 59acceeac54d6..825fc40234120 100644 --- a/perception/autoware_lidar_centerpoint/src/node.cpp +++ b/perception/autoware_lidar_centerpoint/src/node.cpp @@ -107,6 +107,8 @@ LidarCenterPointNode::LidarCenterPointNode(const rclcpp::NodeOptions & node_opti circle_nms_dist_threshold, yaw_norm_thresholds, has_variance_); detector_ptr_ = std::make_unique(encoder_param, head_param, densification_param, config); + diagnostics_interface_ptr_ = + std::make_unique(this, "centerpoint_trt"); pointcloud_sub_ = this->create_subscription( "~/input/pointcloud", rclcpp::SensorDataQoS{}.keep_last(1), @@ -144,12 +146,24 @@ void LidarCenterPointNode::pointCloudCallback( if (stop_watch_ptr_) { stop_watch_ptr_->toc("processing_time", true); } + diagnostics_interface_ptr_->clear(); std::vector det_boxes3d; - bool is_success = detector_ptr_->detect(*input_pointcloud_msg, tf_buffer_, det_boxes3d); + bool is_num_pillars_within_range = true; + bool is_success = detector_ptr_->detect( + *input_pointcloud_msg, tf_buffer_, det_boxes3d, is_num_pillars_within_range); if (!is_success) { return; } + diagnostics_interface_ptr_->add_key_value( + "is_num_pillars_within_range", is_num_pillars_within_range); + if (!is_num_pillars_within_range) { + std::stringstream message; + message << "CenterPointTRT::detect: The actual number of pillars exceeds its maximum value, " + << "which may limit the detection performance."; + diagnostics_interface_ptr_->update_level_and_message( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + } std::vector raw_objects; raw_objects.reserve(det_boxes3d.size()); @@ -169,6 +183,7 @@ void LidarCenterPointNode::pointCloudCallback( objects_pub_->publish(output_msg); published_time_publisher_->publish_if_subscribed(objects_pub_, output_msg.header.stamp); } + diagnostics_interface_ptr_->publish(input_pointcloud_msg->header.stamp); // add processing time for debug if (debug_publisher_ptr_ && stop_watch_ptr_) { From 14ee08b9d19c5f33ed37c72b9504fdcad464ef1b Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Wed, 8 Jan 2025 16:38:33 +0900 Subject: [PATCH 153/334] refactor(autoware_image_projection_based_fusion): organize 2d-detection related members (#9789) * chore: input_camera_topics_ is only for debug Signed-off-by: Taekjin LEE * feat: fuse main message with cached roi messages in fusion_node.cpp Signed-off-by: Taekjin LEE * chore: add comments on each process step, organize methods Signed-off-by: Taekjin LEE * feat: Export process method in fusion_node.cpp Export the `exportProcess()` method in `fusion_node.cpp` to handle the post-processing and publishing of the fused messages. This method cancels the timer, performs the necessary post-processing steps, publishes the output message, and resets the flags. It also adds processing time for debugging purposes. This change improves the organization and readability of the code. Signed-off-by: Taekjin LEE * feat: Refactor fusion_node.hpp and fusion_node.cpp Refactor the `fusion_node.hpp` and `fusion_node.cpp` files to improve code organization and readability. This includes exporting the `exportProcess()` method in `fusion_node.cpp` to handle post-processing and publishing of fused messages, adding comments on each process step, organizing methods, and fusing the main message with cached ROI messages. These changes enhance the overall quality of the codebase. Signed-off-by: Taekjin LEE * Refactor fusion_node.cpp and fusion_node.hpp for improved code organization and readability Signed-off-by: Taekjin LEE * Refactor fusion_node.hpp and fusion_node.cpp for improved code organization and readability Signed-off-by: Taekjin LEE * feat: Refactor fusion_node.cpp for improved code organization and readability Signed-off-by: Taekjin LEE * Refactor fusion_node.cpp for improved code organization and readability Signed-off-by: Taekjin LEE * feat: implement mutex per 2d detection process Signed-off-by: Taekjin LEE * Refactor fusion_node.hpp and fusion_node.cpp for improved code organization and readability Signed-off-by: Taekjin LEE * Refactor fusion_node.hpp and fusion_node.cpp for improved code organization and readability Signed-off-by: Taekjin LEE * revise template, inputs first and output at the last Signed-off-by: Taekjin LEE * explicit in and out types 1 Signed-off-by: Taekjin LEE * clarify pointcloud message type Signed-off-by: Taekjin LEE * Refactor fusion_node.hpp and fusion_node.cpp for improved code organization and readability Signed-off-by: Taekjin LEE * Refactor fusion_node.hpp and fusion_node.cpp for improved code organization and readability Signed-off-by: Taekjin LEE * Refactor fusion_node.hpp and fusion_node.cpp for improved code organization and readability Signed-off-by: Taekjin LEE * Refactor publisher types in fusion_node.hpp and node.hpp Signed-off-by: Taekjin LEE * fix: resolve cppcheck issue shadowVariable Signed-off-by: Taekjin LEE * Refactor fusion_node.hpp and fusion_node.cpp for improved code organization and readability Signed-off-by: Taekjin LEE * chore: rename Det2dManager to Det2dStatus Signed-off-by: Taekjin LEE * revert mutex related changes Signed-off-by: Taekjin LEE * refactor: review member and method's access Signed-off-by: Taekjin LEE * fix: resolve shadowVariable of 'det2d' Signed-off-by: Taekjin LEE * fix missing line Signed-off-by: Taekjin LEE * refactor message postprocess and publish methods Signed-off-by: Taekjin LEE * publish the main message is common Signed-off-by: Taekjin LEE * fix: replace pointcloud message type by the typename Signed-off-by: Taekjin LEE * review member access Signed-off-by: Taekjin LEE * Refactor fusion_node.hpp and fusion_node.cpp for improved code organization and readability Signed-off-by: Taekjin LEE * refactor: fix condition for publishing painted pointcloud message Signed-off-by: Taekjin LEE * fix: remove unused variable Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE --- .../fusion_node.hpp | 124 +++-- .../pointpainting_fusion/node.hpp | 20 +- .../roi_cluster_fusion/node.hpp | 21 +- .../roi_detected_object_fusion/node.hpp | 16 +- .../roi_pointcloud_fusion/node.hpp | 35 +- .../segmentation_pointcloud_fusion/node.hpp | 48 +- .../utils/utils.hpp | 12 +- .../src/fusion_node.cpp | 518 +++++++++--------- .../src/pointpainting_fusion/node.cpp | 86 ++- .../src/roi_cluster_fusion/node.cpp | 63 +-- .../src/roi_detected_object_fusion/node.cpp | 63 ++- .../src/roi_pointcloud_fusion/node.cpp | 91 ++- .../segmentation_pointcloud_fusion/node.cpp | 73 ++- .../src/utils/utils.cpp | 12 +- 14 files changed, 603 insertions(+), 579 deletions(-) diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp index 239d406650ce8..b8881bc6abff7 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp @@ -52,14 +52,33 @@ using autoware_perception_msgs::msg::DetectedObject; using autoware_perception_msgs::msg::DetectedObjects; using sensor_msgs::msg::CameraInfo; using sensor_msgs::msg::Image; -using sensor_msgs::msg::PointCloud2; -using tier4_perception_msgs::msg::DetectedObjectsWithFeature; +using PointCloudMsgType = sensor_msgs::msg::PointCloud2; +using RoiMsgType = tier4_perception_msgs::msg::DetectedObjectsWithFeature; +using ClusterMsgType = tier4_perception_msgs::msg::DetectedObjectsWithFeature; +using ClusterObjType = tier4_perception_msgs::msg::DetectedObjectWithFeature; using tier4_perception_msgs::msg::DetectedObjectWithFeature; using PointCloud = pcl::PointCloud; using autoware::image_projection_based_fusion::CameraProjection; using autoware_perception_msgs::msg::ObjectClassification; -template +template +struct Det2dStatus +{ + // camera index + std::size_t id = 0; + // camera projection + std::unique_ptr camera_projector_ptr; + bool project_to_unrectified_image = false; + bool approximate_camera_projection = false; + // process flags + bool is_fused = false; + // timing + double input_offset_ms = 0.0; + // cache + std::map cached_det2d_msgs; +}; + +template class FusionNode : public rclcpp::Node { public: @@ -71,75 +90,72 @@ class FusionNode : public rclcpp::Node explicit FusionNode( const std::string & node_name, const rclcpp::NodeOptions & options, int queue_size); -protected: +private: + // Common process methods void cameraInfoCallback( const sensor_msgs::msg::CameraInfo::ConstSharedPtr input_camera_info_msg, const std::size_t camera_id); - virtual void preprocess(TargetMsg3D & output_msg); - - // callback for Msg subscription - virtual void subCallback(const typename TargetMsg3D::ConstSharedPtr input_msg); - - // callback for roi subscription - - virtual void roiCallback( - const typename Msg2D::ConstSharedPtr input_roi_msg, const std::size_t roi_i); - - virtual void fuseOnSingleImage( - const TargetMsg3D & input_msg, const std::size_t image_id, const Msg2D & input_roi_msg, - TargetMsg3D & output_msg) = 0; - - // set args if you need - virtual void postprocess(TargetMsg3D & output_msg); - - virtual void publish(const TargetMsg3D & output_msg); - + // callback for timer void timer_callback(); void setPeriod(const int64_t new_period); + void exportProcess(); + + // 2d detection management methods + bool checkAllDet2dFused() + { + for (const auto & det2d : det2d_list_) { + if (!det2d.is_fused) { + return false; + } + } + return true; + } - std::size_t rois_number_{1}; - tf2_ros::Buffer tf_buffer_; - tf2_ros::TransformListener tf_listener_; - - std::vector point_project_to_unrectified_image_; - - // camera_info - std::map camera_info_map_; - std::vector::SharedPtr> camera_info_subs_; // camera projection - std::vector camera_projectors_; - std::vector approx_camera_projection_; float approx_grid_cell_w_size_; float approx_grid_cell_h_size_; + // timer rclcpp::TimerBase::SharedPtr timer_; double timeout_ms_{}; double match_threshold_ms_{}; - std::vector input_rois_topics_; - std::vector input_camera_info_topics_; - std::vector input_camera_topics_; - /** \brief A vector of subscriber. */ - typename rclcpp::Subscription::SharedPtr sub_; std::vector::SharedPtr> rois_subs_; - - // offsets between cameras and the lidars - std::vector input_offset_ms_; + std::vector::SharedPtr> camera_info_subs_; // cache for fusion - std::vector is_fused_; - std::pair - cached_msg_; // first element is the timestamp in nanoseconds, second element is the message - std::vector> cached_roi_msgs_; + int64_t cached_det3d_msg_timestamp_; + typename Msg3D::SharedPtr cached_det3d_msg_ptr_; std::mutex mutex_cached_msgs_; - // output publisher - typename rclcpp::Publisher::SharedPtr pub_ptr_; +protected: + void setDet2DStatus(std::size_t rois_number); - // debugger - std::shared_ptr debugger_; - virtual bool out_of_scope(const ObjType & obj) = 0; + // callback for main subscription + void subCallback(const typename Msg3D::ConstSharedPtr input_msg); + // callback for roi subscription + void roiCallback(const typename Msg2D::ConstSharedPtr input_roi_msg, const std::size_t roi_i); + + // Custom process methods + virtual void preprocess(Msg3D & output_msg); + virtual void fuseOnSingleImage( + const Msg3D & input_msg, const Det2dStatus & det2d, const Msg2D & input_roi_msg, + Msg3D & output_msg) = 0; + virtual void postprocess(const Msg3D & processing_msg, ExportObj & output_msg); + virtual void publish(const ExportObj & output_msg); + + // Members + tf2_ros::Buffer tf_buffer_; + tf2_ros::TransformListener tf_listener_; + + // 2d detection management + std::vector> det2d_list_; + + /** \brief A vector of subscriber. */ + typename rclcpp::Subscription::SharedPtr sub_; + + // parameters for out_of_scope filter float filter_scope_min_x_; float filter_scope_max_x_; float filter_scope_min_y_; @@ -147,6 +163,12 @@ class FusionNode : public rclcpp::Node float filter_scope_min_z_; float filter_scope_max_z_; + // output publisher + typename rclcpp::Publisher::SharedPtr pub_ptr_; + + // debugger + std::shared_ptr debugger_; + /** \brief processing time publisher. **/ std::unique_ptr> stop_watch_ptr_; std::unique_ptr debug_publisher_; diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/node.hpp index 5bc428a8e7ab8..9505a926df2f8 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/node.hpp @@ -42,27 +42,25 @@ inline bool isInsideBbox( proj_y >= roi.y_offset * zc && proj_y <= (roi.y_offset + roi.height) * zc; } -class PointPaintingFusionNode -: public FusionNode +class PointPaintingFusionNode : public FusionNode { public: explicit PointPaintingFusionNode(const rclcpp::NodeOptions & options); -protected: - void preprocess(sensor_msgs::msg::PointCloud2 & pointcloud_msg) override; +private: + void preprocess(PointCloudMsgType & pointcloud_msg) override; void fuseOnSingleImage( - const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const std::size_t image_id, - const DetectedObjectsWithFeature & input_roi_msg, - sensor_msgs::msg::PointCloud2 & painted_pointcloud_msg) override; + const PointCloudMsgType & input_pointcloud_msg, const Det2dStatus & det2d, + const RoiMsgType & input_roi_msg, PointCloudMsgType & painted_pointcloud_msg) override; - void postprocess(sensor_msgs::msg::PointCloud2 & painted_pointcloud_msg) override; + void postprocess( + const PointCloudMsgType & painted_pointcloud_msg, DetectedObjects & output_msg) override; - rclcpp::Publisher::SharedPtr obj_pub_ptr_; + rclcpp::Publisher::SharedPtr point_pub_ptr_; std::unique_ptr diagnostics_interface_ptr_; int omp_num_threads_{1}; - float score_threshold_{0.0}; std::vector class_names_; std::map class_index_; std::map> isClassTable_; @@ -74,8 +72,6 @@ class PointPaintingFusionNode autoware::lidar_centerpoint::DetectionClassRemapper detection_class_remapper_; std::unique_ptr detector_ptr_{nullptr}; - - bool out_of_scope(const DetectedObjects & obj) override; }; } // namespace autoware::image_projection_based_fusion #endif // AUTOWARE__IMAGE_PROJECTION_BASED_FUSION__POINTPAINTING_FUSION__NODE_HPP_ diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_cluster_fusion/node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_cluster_fusion/node.hpp index 903b153af0681..b7bf8738b68a4 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_cluster_fusion/node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_cluster_fusion/node.hpp @@ -24,21 +24,19 @@ namespace autoware::image_projection_based_fusion { const std::map IOU_MODE_MAP{{"iou", 0}, {"iou_x", 1}, {"iou_y", 2}}; -class RoiClusterFusionNode -: public FusionNode< - DetectedObjectsWithFeature, DetectedObjectWithFeature, DetectedObjectsWithFeature> +class RoiClusterFusionNode : public FusionNode { public: explicit RoiClusterFusionNode(const rclcpp::NodeOptions & options); -protected: - void preprocess(DetectedObjectsWithFeature & output_cluster_msg) override; - void postprocess(DetectedObjectsWithFeature & output_cluster_msg) override; +private: + void preprocess(ClusterMsgType & output_cluster_msg) override; void fuseOnSingleImage( - const DetectedObjectsWithFeature & input_cluster_msg, const std::size_t image_id, - const DetectedObjectsWithFeature & input_roi_msg, - DetectedObjectsWithFeature & output_cluster_msg) override; + const ClusterMsgType & input_cluster_msg, const Det2dStatus & det2d, + const RoiMsgType & input_roi_msg, ClusterMsgType & output_cluster_msg) override; + + void postprocess(const ClusterMsgType & output_cluster_msg, ClusterMsgType & output_msg) override; std::string trust_object_iou_mode_{"iou"}; bool use_cluster_semantic_type_{false}; @@ -53,12 +51,11 @@ class RoiClusterFusionNode double trust_object_distance_; std::string non_trust_object_iou_mode_{"iou_x"}; - bool is_far_enough(const DetectedObjectWithFeature & obj, const double distance_threshold); - bool out_of_scope(const DetectedObjectWithFeature & obj) override; + bool is_far_enough(const ClusterObjType & obj, const double distance_threshold); + bool out_of_scope(const ClusterObjType & obj); double cal_iou_by_mode( const sensor_msgs::msg::RegionOfInterest & roi_1, const sensor_msgs::msg::RegionOfInterest & roi_2, const std::string iou_mode); - // bool CheckUnknown(const DetectedObjectsWithFeature & obj); }; } // namespace autoware::image_projection_based_fusion diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_detected_object_fusion/node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_detected_object_fusion/node.hpp index 43ec134168ef9..ba197126277a0 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_detected_object_fusion/node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_detected_object_fusion/node.hpp @@ -31,21 +31,20 @@ namespace autoware::image_projection_based_fusion using sensor_msgs::msg::RegionOfInterest; -class RoiDetectedObjectFusionNode -: public FusionNode +class RoiDetectedObjectFusionNode : public FusionNode { public: explicit RoiDetectedObjectFusionNode(const rclcpp::NodeOptions & options); -protected: +private: void preprocess(DetectedObjects & output_msg) override; void fuseOnSingleImage( - const DetectedObjects & input_object_msg, const std::size_t image_id, - const DetectedObjectsWithFeature & input_roi_msg, DetectedObjects & output_object_msg) override; + const DetectedObjects & input_object_msg, const Det2dStatus & det2d, + const RoiMsgType & input_roi_msg, DetectedObjects & output_object_msg) override; std::map generateDetectedObjectRoIs( - const DetectedObjects & input_object_msg, const std::size_t & image_id, + const DetectedObjects & input_object_msg, const Det2dStatus & det2d, const Eigen::Affine3d & object2camera_affine); void fuseObjectsOnImage( @@ -53,11 +52,10 @@ class RoiDetectedObjectFusionNode const std::vector & image_rois, const std::map & object_roi_map); - void publish(const DetectedObjects & output_msg) override; + void postprocess(const DetectedObjects & processing_msg, DetectedObjects & output_msg) override; - bool out_of_scope(const DetectedObject & obj) override; + bool out_of_scope(const DetectedObject & obj); -private: struct { std::vector passthrough_lower_bound_probability_thresholds{}; diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp index 2f2c8222e196f..77a1745faa7e5 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp @@ -25,32 +25,29 @@ namespace autoware::image_projection_based_fusion { -class RoiPointCloudFusionNode -: public FusionNode +class RoiPointCloudFusionNode : public FusionNode { +public: + explicit RoiPointCloudFusionNode(const rclcpp::NodeOptions & options); + private: - int min_cluster_size_{1}; - int max_cluster_size_{20}; - bool fuse_unknown_only_{true}; - double cluster_2d_tolerance_; + rclcpp::Publisher::SharedPtr point_pub_ptr_; + rclcpp::Publisher::SharedPtr cluster_debug_pub_; - rclcpp::Publisher::SharedPtr pub_objects_ptr_; - std::vector output_fused_objects_; - rclcpp::Publisher::SharedPtr cluster_debug_pub_; + void fuseOnSingleImage( + const PointCloudMsgType & input_pointcloud_msg, const Det2dStatus & det2d, + const RoiMsgType & input_roi_msg, PointCloudMsgType & output_pointcloud_msg) override; - /* data */ -public: - explicit RoiPointCloudFusionNode(const rclcpp::NodeOptions & options); + void postprocess(const PointCloudMsgType & pointcloud_msg, ClusterMsgType & output_msg) override; -protected: - void preprocess(sensor_msgs::msg::PointCloud2 & pointcloud_msg) override; + void publish(const ClusterMsgType & output_msg) override; - void postprocess(sensor_msgs::msg::PointCloud2 & pointcloud_msg) override; + int min_cluster_size_{1}; + int max_cluster_size_{20}; + bool fuse_unknown_only_{true}; + double cluster_2d_tolerance_; - void fuseOnSingleImage( - const PointCloud2 & input_pointcloud_msg, const std::size_t image_id, - const DetectedObjectsWithFeature & input_roi_msg, PointCloud2 & output_pointcloud_msg) override; - bool out_of_scope(const DetectedObjectWithFeature & obj) override; + std::vector output_fused_objects_; }; } // namespace autoware::image_projection_based_fusion diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp index 7454cb7bcd173..5414f98e142cd 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp @@ -34,10 +34,32 @@ namespace autoware::image_projection_based_fusion { -class SegmentPointCloudFusionNode : public FusionNode +class SegmentPointCloudFusionNode : public FusionNode { +public: + explicit SegmentPointCloudFusionNode(const rclcpp::NodeOptions & options); + private: - rclcpp::Publisher::SharedPtr pub_pointcloud_ptr_; + void preprocess(PointCloudMsgType & pointcloud_msg) override; + + void fuseOnSingleImage( + const PointCloudMsgType & input_pointcloud_msg, const Det2dStatus & det2d, + const Image & input_mask, PointCloudMsgType & output_pointcloud_msg) override; + + inline void copyPointCloud( + const PointCloudMsgType & input, const int point_step, const size_t global_offset, + PointCloudMsgType & output, size_t & output_pointcloud_size) + { + std::memcpy(&output.data[output_pointcloud_size], &input.data[global_offset], point_step); + output_pointcloud_size += point_step; + } + + void postprocess( + const PointCloudMsgType & pointcloud_msg, PointCloudMsgType & output_msg) override; + + // debug + image_transport::Publisher pub_debug_mask_ptr_; + std::vector filter_semantic_label_target_; float filter_distance_threshold_; // declare list of semantic label target, depend on trained data of yolox segmentation model @@ -47,30 +69,8 @@ class SegmentPointCloudFusionNode : public FusionNode filter_global_offset_set_; - -public: - explicit SegmentPointCloudFusionNode(const rclcpp::NodeOptions & options); - -protected: - void preprocess(PointCloud2 & pointcloud_msg) override; - - void postprocess(PointCloud2 & pointcloud_msg) override; - - void fuseOnSingleImage( - const PointCloud2 & input_pointcloud_msg, const std::size_t image_id, const Image & input_mask, - PointCloud2 & output_pointcloud_msg) override; - - bool out_of_scope(const PointCloud2 & filtered_cloud) override; - inline void copyPointCloud( - const PointCloud2 & input, const int point_step, const size_t global_offset, - PointCloud2 & output, size_t & output_pointcloud_size) - { - std::memcpy(&output.data[output_pointcloud_size], &input.data[global_offset], point_step); - output_pointcloud_size += point_step; - } }; } // namespace autoware::image_projection_based_fusion diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/utils/utils.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/utils/utils.hpp index 12577081713be..044a71ab57533 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/utils/utils.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/utils/utils.hpp @@ -56,7 +56,7 @@ namespace autoware::image_projection_based_fusion { using PointCloud = pcl::PointCloud; -using PointCloud2 = sensor_msgs::msg::PointCloud2; + struct PointData { float distance; @@ -72,17 +72,17 @@ std::optional getTransformStamped( Eigen::Affine3d transformToEigen(const geometry_msgs::msg::Transform & t); void closest_cluster( - const PointCloud2 & cluster, const double cluster_2d_tolerance, const int min_cluster_size, - const pcl::PointXYZ & center, PointCloud2 & out_cluster); + const PointCloudMsgType & cluster, const double cluster_2d_tolerance, const int min_cluster_size, + const pcl::PointXYZ & center, PointCloudMsgType & out_cluster); void updateOutputFusedObjects( - std::vector & output_objs, std::vector & clusters, - const std::vector & clusters_data_size, const PointCloud2 & in_cloud, + std::vector & output_objs, std::vector & clusters, + const std::vector & clusters_data_size, const PointCloudMsgType & in_cloud, const std_msgs::msg::Header & in_roi_header, const tf2_ros::Buffer & tf_buffer, const int min_cluster_size, const int max_cluster_size, const float cluster_2d_tolerance, std::vector & output_fused_objects); -geometry_msgs::msg::Point getCentroid(const sensor_msgs::msg::PointCloud2 & pointcloud); +geometry_msgs::msg::Point getCentroid(const PointCloudMsgType & pointcloud); } // namespace autoware::image_projection_based_fusion diff --git a/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp b/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp index ea0904215cb86..310c68f12db88 100644 --- a/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp @@ -28,6 +28,7 @@ #include #include #include +#include #ifdef ROS_DISTRO_GALACTIC #include @@ -45,79 +46,66 @@ namespace autoware::image_projection_based_fusion { using autoware::universe_utils::ScopedTimeTrack; -template -FusionNode::FusionNode( +template +FusionNode::FusionNode( const std::string & node_name, const rclcpp::NodeOptions & options) : Node(node_name, options), tf_buffer_(this->get_clock()), tf_listener_(tf_buffer_) { // set rois_number - rois_number_ = static_cast(declare_parameter("rois_number")); - if (rois_number_ < 1) { - RCLCPP_WARN( - this->get_logger(), "minimum rois_number is 1. current rois_number is %zu", rois_number_); - rois_number_ = 1; + const std::size_t rois_number = + static_cast(declare_parameter("rois_number")); + if (rois_number < 1) { + RCLCPP_ERROR( + this->get_logger(), "minimum rois_number is 1. current rois_number is %zu", rois_number); } - if (rois_number_ > 8) { + if (rois_number > 8) { RCLCPP_WARN( this->get_logger(), - "Current rois_number is %zu. Large rois number may cause performance issue.", rois_number_); + "Current rois_number is %zu. Large rois number may cause performance issue.", rois_number); } // Set parameters match_threshold_ms_ = declare_parameter("match_threshold_ms"); timeout_ms_ = declare_parameter("timeout_ms"); - input_rois_topics_.resize(rois_number_); - input_camera_topics_.resize(rois_number_); - input_camera_info_topics_.resize(rois_number_); + std::vector input_rois_topics; + std::vector input_camera_info_topics; + + input_rois_topics.resize(rois_number); + input_camera_info_topics.resize(rois_number); - for (std::size_t roi_i = 0; roi_i < rois_number_; ++roi_i) { - input_rois_topics_.at(roi_i) = declare_parameter( + for (std::size_t roi_i = 0; roi_i < rois_number; ++roi_i) { + input_rois_topics.at(roi_i) = declare_parameter( "input/rois" + std::to_string(roi_i), "/perception/object_recognition/detection/rois" + std::to_string(roi_i)); - input_camera_info_topics_.at(roi_i) = declare_parameter( + input_camera_info_topics.at(roi_i) = declare_parameter( "input/camera_info" + std::to_string(roi_i), "/sensing/camera/camera" + std::to_string(roi_i) + "/camera_info"); - - input_camera_topics_.at(roi_i) = declare_parameter( - "input/image" + std::to_string(roi_i), - "/sensing/camera/camera" + std::to_string(roi_i) + "/image_rect_color"); } - input_offset_ms_ = declare_parameter>("input_offset_ms"); - if (!input_offset_ms_.empty() && rois_number_ > input_offset_ms_.size()) { - throw std::runtime_error("The number of offsets does not match the number of topics."); - } - - // sub camera info - camera_info_subs_.resize(rois_number_); - for (std::size_t roi_i = 0; roi_i < rois_number_; ++roi_i) { + // subscribe camera info + camera_info_subs_.resize(rois_number); + for (std::size_t roi_i = 0; roi_i < rois_number; ++roi_i) { std::function fnc = std::bind(&FusionNode::cameraInfoCallback, this, std::placeholders::_1, roi_i); camera_info_subs_.at(roi_i) = this->create_subscription( - input_camera_info_topics_.at(roi_i), rclcpp::QoS{1}.best_effort(), fnc); + input_camera_info_topics.at(roi_i), rclcpp::QoS{1}.best_effort(), fnc); } - // sub rois - rois_subs_.resize(rois_number_); - cached_roi_msgs_.resize(rois_number_); - is_fused_.resize(rois_number_, false); - for (std::size_t roi_i = 0; roi_i < rois_number_; ++roi_i) { + // subscribe rois + rois_subs_.resize(rois_number); + for (std::size_t roi_i = 0; roi_i < rois_number; ++roi_i) { std::function roi_callback = std::bind(&FusionNode::roiCallback, this, std::placeholders::_1, roi_i); rois_subs_.at(roi_i) = this->create_subscription( - input_rois_topics_.at(roi_i), rclcpp::QoS{1}.best_effort(), roi_callback); + input_rois_topics.at(roi_i), rclcpp::QoS{1}.best_effort(), roi_callback); } - // subscribers - std::function sub_callback = + // subscribe 3d detection + std::function sub_callback = std::bind(&FusionNode::subCallback, this, std::placeholders::_1); - sub_ = - this->create_subscription("input", rclcpp::QoS(1).best_effort(), sub_callback); - - // publisher - pub_ptr_ = this->create_publisher("output", rclcpp::QoS{1}); + sub_ = this->create_subscription("input", rclcpp::QoS(1).best_effort(), sub_callback); // Set timer const auto period_ns = std::chrono::duration_cast( @@ -125,40 +113,34 @@ FusionNode::FusionNode( timer_ = rclcpp::create_timer( this, get_clock(), period_ns, std::bind(&FusionNode::timer_callback, this)); - // camera projection settings - camera_projectors_.resize(rois_number_); - point_project_to_unrectified_image_ = - declare_parameter>("point_project_to_unrectified_image"); + // initialization on each 2d detections + setDet2DStatus(rois_number); - if (rois_number_ > point_project_to_unrectified_image_.size()) { - throw std::runtime_error( - "The number of point_project_to_unrectified_image does not match the number of rois topics."); - } - approx_camera_projection_ = declare_parameter>("approximate_camera_projection"); - if (rois_number_ != approx_camera_projection_.size()) { - const std::size_t current_size = approx_camera_projection_.size(); - RCLCPP_WARN( - this->get_logger(), - "The number of elements in approximate_camera_projection should be the same as in " - "rois_number. " - "It has %zu elements.", - current_size); - if (current_size < rois_number_) { - approx_camera_projection_.resize(rois_number_); - for (std::size_t i = current_size; i < rois_number_; i++) { - approx_camera_projection_.at(i) = true; - } - } - } + // parameters for approximation grid approx_grid_cell_w_size_ = declare_parameter("approximation_grid_cell_width"); approx_grid_cell_h_size_ = declare_parameter("approximation_grid_cell_height"); + // parameters for out_of_scope filter + filter_scope_min_x_ = declare_parameter("filter_scope_min_x"); + filter_scope_max_x_ = declare_parameter("filter_scope_max_x"); + filter_scope_min_y_ = declare_parameter("filter_scope_min_y"); + filter_scope_max_y_ = declare_parameter("filter_scope_max_y"); + filter_scope_min_z_ = declare_parameter("filter_scope_min_z"); + filter_scope_max_z_ = declare_parameter("filter_scope_max_z"); + // debugger if (declare_parameter("debug_mode", false)) { + std::vector input_camera_topics; + input_camera_topics.resize(rois_number); + for (std::size_t roi_i = 0; roi_i < rois_number; ++roi_i) { + input_camera_topics.at(roi_i) = declare_parameter( + "input/image" + std::to_string(roi_i), + "/sensing/camera/camera" + std::to_string(roi_i) + "/image_rect_color"); + } std::size_t image_buffer_size = static_cast(declare_parameter("image_buffer_size")); debugger_ = - std::make_shared(this, rois_number_, image_buffer_size, input_camera_topics_); + std::make_shared(this, rois_number, image_buffer_size, input_camera_topics); } // time keeper @@ -180,77 +162,127 @@ FusionNode::FusionNode( stop_watch_ptr_->tic("cyclic_time"); stop_watch_ptr_->tic("processing_time"); } +} - filter_scope_min_x_ = declare_parameter("filter_scope_min_x"); - filter_scope_max_x_ = declare_parameter("filter_scope_max_x"); - filter_scope_min_y_ = declare_parameter("filter_scope_min_y"); - filter_scope_max_y_ = declare_parameter("filter_scope_max_y"); - filter_scope_min_z_ = declare_parameter("filter_scope_min_z"); - filter_scope_max_z_ = declare_parameter("filter_scope_max_z"); +template +void FusionNode::setDet2DStatus(std::size_t rois_number) +{ + // camera offset settings + std::vector input_offset_ms = declare_parameter>("input_offset_ms"); + if (!input_offset_ms.empty() && rois_number > input_offset_ms.size()) { + throw std::runtime_error("The number of offsets does not match the number of topics."); + } + + // camera projection settings + std::vector point_project_to_unrectified_image = + declare_parameter>("point_project_to_unrectified_image"); + if (rois_number > point_project_to_unrectified_image.size()) { + throw std::runtime_error( + "The number of point_project_to_unrectified_image does not match the number of rois " + "topics."); + } + std::vector approx_camera_projection = + declare_parameter>("approximate_camera_projection"); + if (rois_number != approx_camera_projection.size()) { + const std::size_t current_size = approx_camera_projection.size(); + RCLCPP_WARN( + get_logger(), + "The number of elements in approximate_camera_projection should be the same as in " + "rois_number. " + "It has %zu elements.", + current_size); + if (current_size < rois_number) { + approx_camera_projection.resize(rois_number); + for (std::size_t i = current_size; i < rois_number; i++) { + approx_camera_projection.at(i) = true; + } + } + } + + // 2d detection status initialization + det2d_list_.resize(rois_number); + for (std::size_t roi_i = 0; roi_i < rois_number; ++roi_i) { + det2d_list_.at(roi_i).id = roi_i; + det2d_list_.at(roi_i).project_to_unrectified_image = + point_project_to_unrectified_image.at(roi_i); + det2d_list_.at(roi_i).approximate_camera_projection = approx_camera_projection.at(roi_i); + det2d_list_.at(roi_i).input_offset_ms = input_offset_ms.at(roi_i); + } } -template -void FusionNode::cameraInfoCallback( +template +void FusionNode::cameraInfoCallback( const sensor_msgs::msg::CameraInfo::ConstSharedPtr input_camera_info_msg, const std::size_t camera_id) { // create the CameraProjection when the camera info arrives for the first time // assuming the camera info does not change while the node is running - if ( - camera_info_map_.find(camera_id) == camera_info_map_.end() && - checkCameraInfo(*input_camera_info_msg)) { - camera_projectors_.at(camera_id) = CameraProjection( + auto & det2d = det2d_list_.at(camera_id); + if (!det2d.camera_projector_ptr && checkCameraInfo(*input_camera_info_msg)) { + det2d.camera_projector_ptr = std::make_unique( *input_camera_info_msg, approx_grid_cell_w_size_, approx_grid_cell_h_size_, - point_project_to_unrectified_image_.at(camera_id), approx_camera_projection_.at(camera_id)); - camera_projectors_.at(camera_id).initialize(); - - camera_info_map_[camera_id] = *input_camera_info_msg; + det2d.project_to_unrectified_image, det2d.approximate_camera_projection); + det2d.camera_projector_ptr->initialize(); } } -template -void FusionNode::preprocess(TargetMsg3D & ouput_msg - __attribute__((unused))) +template +void FusionNode::preprocess(Msg3D & ouput_msg __attribute__((unused))) { // do nothing by default } -template -void FusionNode::subCallback( - const typename TargetMsg3D::ConstSharedPtr input_msg) +template +void FusionNode::exportProcess() +{ + timer_->cancel(); + + ExportObj output_msg; + postprocess(*(cached_det3d_msg_ptr_), output_msg); + publish(output_msg); + + // add processing time for debug + if (debug_publisher_) { + const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); + const double pipeline_latency_ms = + std::chrono::duration( + std::chrono::nanoseconds( + (this->get_clock()->now() - cached_det3d_msg_ptr_->header.stamp).nanoseconds())) + .count(); + debug_publisher_->publish( + "debug/cyclic_time_ms", cyclic_time_ms); + debug_publisher_->publish( + "debug/processing_time_ms", + processing_time_ms + stop_watch_ptr_->toc("processing_time", true)); + debug_publisher_->publish( + "debug/pipeline_latency_ms", pipeline_latency_ms); + processing_time_ms = 0; + } + cached_det3d_msg_ptr_ = nullptr; +} + +template +void FusionNode::subCallback( + const typename Msg3D::ConstSharedPtr det3d_msg) { std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); - if (cached_msg_.second != nullptr) { + if (cached_det3d_msg_ptr_ != nullptr) { + // PROCESS: if the main message is remained (and roi is not collected all) publish the main + // message may processed partially with arrived 2d rois stop_watch_ptr_->toc("processing_time", true); - timer_->cancel(); - postprocess(*(cached_msg_.second)); - publish(*(cached_msg_.second)); - std::fill(is_fused_.begin(), is_fused_.end(), false); - - // add processing time for debug - if (debug_publisher_) { - const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); - const double pipeline_latency_ms = - std::chrono::duration( - std::chrono::nanoseconds( - (this->get_clock()->now() - cached_msg_.second->header.stamp).nanoseconds())) - .count(); - debug_publisher_->publish( - "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( - "debug/processing_time_ms", - processing_time_ms + stop_watch_ptr_->toc("processing_time", true)); - debug_publisher_->publish( - "debug/pipeline_latency_ms", pipeline_latency_ms); - processing_time_ms = 0; - } + exportProcess(); - cached_msg_.second = nullptr; + // reset flags + for (auto & det2d : det2d_list_) { + det2d.is_fused = false; + } } std::lock_guard lock(mutex_cached_msgs_); + + // TIMING: reset timer to the timeout time auto period = std::chrono::duration_cast( std::chrono::duration(timeout_ms_)); try { @@ -262,154 +294,141 @@ void FusionNode::subCallback( stop_watch_ptr_->toc("processing_time", true); - typename TargetMsg3D::SharedPtr output_msg = std::make_shared(*input_msg); - + // PROCESS: preprocess the main message + typename Msg3D::SharedPtr output_msg = std::make_shared(*det3d_msg); preprocess(*output_msg); + // PROCESS: fuse the main message with the cached roi messages + // (please ask maintainers before parallelize this loop because debugger is not thread safe) int64_t timestamp_nsec = (*output_msg).header.stamp.sec * static_cast(1e9) + (*output_msg).header.stamp.nanosec; + // for loop for each roi + for (auto & det2d : det2d_list_) { + const auto roi_i = det2d.id; - // if matching rois exist, fuseOnSingle - // please ask maintainers before parallelize this loop because debugger is not thread safe - for (std::size_t roi_i = 0; roi_i < rois_number_; ++roi_i) { - if (camera_info_map_.find(roi_i) == camera_info_map_.end()) { + // check camera info + if (det2d.camera_projector_ptr == nullptr) { RCLCPP_WARN_THROTTLE( this->get_logger(), *this->get_clock(), 5000, "no camera info. id is %zu", roi_i); continue; } - - if ((cached_roi_msgs_.at(roi_i)).size() > 0) { - int64_t min_interval = 1e9; - int64_t matched_stamp = -1; - std::list outdate_stamps; - - for (const auto & [k, v] : cached_roi_msgs_.at(roi_i)) { - int64_t new_stamp = timestamp_nsec + input_offset_ms_.at(roi_i) * static_cast(1e6); - int64_t interval = abs(static_cast(k) - new_stamp); - - if ( - interval <= min_interval && interval <= match_threshold_ms_ * static_cast(1e6)) { - min_interval = interval; - matched_stamp = k; - } else if ( - static_cast(k) < new_stamp && - interval > match_threshold_ms_ * static_cast(1e6)) { - outdate_stamps.push_back(static_cast(k)); - } + auto & det2d_msgs = det2d.cached_det2d_msgs; + + // check if the roi is collected + if (det2d_msgs.size() == 0) continue; + + // MATCH: get the closest roi message, and remove outdated messages + int64_t min_interval = 1e9; + int64_t matched_stamp = -1; + std::list outdate_stamps; + for (const auto & [roi_stamp, value] : det2d_msgs) { + int64_t new_stamp = timestamp_nsec + det2d.input_offset_ms * static_cast(1e6); + int64_t interval = abs(static_cast(roi_stamp) - new_stamp); + + if (interval <= min_interval && interval <= match_threshold_ms_ * static_cast(1e6)) { + min_interval = interval; + matched_stamp = roi_stamp; + } else if ( + static_cast(roi_stamp) < new_stamp && + interval > match_threshold_ms_ * static_cast(1e6)) { + outdate_stamps.push_back(static_cast(roi_stamp)); } + } + for (auto stamp : outdate_stamps) { + det2d_msgs.erase(stamp); + } - // remove outdated stamps - for (auto stamp : outdate_stamps) { - (cached_roi_msgs_.at(roi_i)).erase(stamp); + // PROCESS: if matched, fuse the main message with the roi message + if (matched_stamp != -1) { + if (debugger_) { + debugger_->clear(); } - // fuseOnSingle - if (matched_stamp != -1) { - if (debugger_) { - debugger_->clear(); - } + fuseOnSingleImage(*det3d_msg, det2d, *(det2d_msgs[matched_stamp]), *output_msg); + det2d_msgs.erase(matched_stamp); + det2d.is_fused = true; - fuseOnSingleImage( - *input_msg, roi_i, *((cached_roi_msgs_.at(roi_i))[matched_stamp]), *output_msg); - (cached_roi_msgs_.at(roi_i)).erase(matched_stamp); - is_fused_.at(roi_i) = true; - - // add timestamp interval for debug - if (debug_publisher_) { - double timestamp_interval_ms = (matched_stamp - timestamp_nsec) / 1e6; - debug_publisher_->publish( - "debug/roi" + std::to_string(roi_i) + "/timestamp_interval_ms", timestamp_interval_ms); - debug_publisher_->publish( - "debug/roi" + std::to_string(roi_i) + "/timestamp_interval_offset_ms", - timestamp_interval_ms - input_offset_ms_.at(roi_i)); - } + // add timestamp interval for debug + if (debug_publisher_) { + double timestamp_interval_ms = (matched_stamp - timestamp_nsec) / 1e6; + debug_publisher_->publish( + "debug/roi" + std::to_string(roi_i) + "/timestamp_interval_ms", timestamp_interval_ms); + debug_publisher_->publish( + "debug/roi" + std::to_string(roi_i) + "/timestamp_interval_offset_ms", + timestamp_interval_ms - det2d.input_offset_ms); } } } - // if all camera fused, postprocess; else, publish the old Msg(if exists) and cache the current - // Msg - if (std::count(is_fused_.begin(), is_fused_.end(), true) == static_cast(rois_number_)) { - timer_->cancel(); - postprocess(*output_msg); - publish(*output_msg); - std::fill(is_fused_.begin(), is_fused_.end(), false); - cached_msg_.second = nullptr; - - // add processing time for debug - if (debug_publisher_) { - const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); - processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_->publish( - "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( - "debug/processing_time_ms", processing_time_ms); - processing_time_ms = 0; + // PROCESS: check if the fused message is ready to publish + cached_det3d_msg_timestamp_ = timestamp_nsec; + cached_det3d_msg_ptr_ = output_msg; + if (checkAllDet2dFused()) { + // if all camera fused, postprocess and publish the main message + exportProcess(); + + // reset flags + for (auto & det2d : det2d_list_) { + det2d.is_fused = false; } } else { - cached_msg_.first = timestamp_nsec; - cached_msg_.second = output_msg; + // if all of rois are not collected, publish the old Msg(if exists) and cache the + // current Msg processing_time_ms = stop_watch_ptr_->toc("processing_time", true); } } -template -void FusionNode::roiCallback( - const typename Msg2D::ConstSharedPtr input_roi_msg, const std::size_t roi_i) +template +void FusionNode::roiCallback( + const typename Msg2D::ConstSharedPtr det2d_msg, const std::size_t roi_i) { std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); stop_watch_ptr_->toc("processing_time", true); - int64_t timestamp_nsec = (*input_roi_msg).header.stamp.sec * static_cast(1e9) + - (*input_roi_msg).header.stamp.nanosec; + auto & det2d = det2d_list_.at(roi_i); + int64_t timestamp_nsec = + (*det2d_msg).header.stamp.sec * static_cast(1e9) + (*det2d_msg).header.stamp.nanosec; // if cached Msg exist, try to match - if (cached_msg_.second != nullptr) { - int64_t new_stamp = cached_msg_.first + input_offset_ms_.at(roi_i) * static_cast(1e6); + if (cached_det3d_msg_ptr_ != nullptr) { + int64_t new_stamp = + cached_det3d_msg_timestamp_ + det2d.input_offset_ms * static_cast(1e6); int64_t interval = abs(timestamp_nsec - new_stamp); - if ( - interval < match_threshold_ms_ * static_cast(1e6) && is_fused_.at(roi_i) == false) { - if (camera_info_map_.find(roi_i) == camera_info_map_.end()) { + // PROCESS: if matched, fuse the main message with the roi message + if (interval < match_threshold_ms_ * static_cast(1e6) && det2d.is_fused == false) { + // check camera info + if (det2d.camera_projector_ptr == nullptr) { RCLCPP_WARN_THROTTLE( this->get_logger(), *this->get_clock(), 5000, "no camera info. id is %zu", roi_i); - (cached_roi_msgs_.at(roi_i))[timestamp_nsec] = input_roi_msg; + det2d.cached_det2d_msgs[timestamp_nsec] = det2d_msg; return; } + if (debugger_) { debugger_->clear(); } - - fuseOnSingleImage(*(cached_msg_.second), roi_i, *input_roi_msg, *(cached_msg_.second)); - is_fused_.at(roi_i) = true; + // PROCESS: fuse the main message with the roi message + fuseOnSingleImage(*(cached_det3d_msg_ptr_), det2d, *det2d_msg, *(cached_det3d_msg_ptr_)); + det2d.is_fused = true; if (debug_publisher_) { - double timestamp_interval_ms = (timestamp_nsec - cached_msg_.first) / 1e6; + double timestamp_interval_ms = (timestamp_nsec - cached_det3d_msg_timestamp_) / 1e6; debug_publisher_->publish( "debug/roi" + std::to_string(roi_i) + "/timestamp_interval_ms", timestamp_interval_ms); debug_publisher_->publish( "debug/roi" + std::to_string(roi_i) + "/timestamp_interval_offset_ms", - timestamp_interval_ms - input_offset_ms_.at(roi_i)); + timestamp_interval_ms - det2d.input_offset_ms); } - if (std::count(is_fused_.begin(), is_fused_.end(), true) == static_cast(rois_number_)) { - timer_->cancel(); - postprocess(*(cached_msg_.second)); - publish(*(cached_msg_.second)); - std::fill(is_fused_.begin(), is_fused_.end(), false); - cached_msg_.second = nullptr; - - // add processing time for debug - if (debug_publisher_) { - const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); - debug_publisher_->publish( - "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( - "debug/processing_time_ms", - processing_time_ms + stop_watch_ptr_->toc("processing_time", true)); - processing_time_ms = 0; + // PROCESS: if all camera fused, postprocess and publish the main message + if (checkAllDet2dFused()) { + exportProcess(); + // reset flags + for (auto & status : det2d_list_) { + status.is_fused = false; } } processing_time_ms = processing_time_ms + stop_watch_ptr_->toc("processing_time", true); @@ -417,18 +436,11 @@ void FusionNode::roiCallback( } } // store roi msg if not matched - (cached_roi_msgs_.at(roi_i))[timestamp_nsec] = input_roi_msg; + det2d.cached_det2d_msgs[timestamp_nsec] = det2d_msg; } -template -void FusionNode::postprocess(TargetMsg3D & output_msg - __attribute__((unused))) -{ - // do nothing by default -} - -template -void FusionNode::timer_callback() +template +void FusionNode::timer_callback() { std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); @@ -436,29 +448,20 @@ void FusionNode::timer_callback() using std::chrono_literals::operator""ms; timer_->cancel(); if (mutex_cached_msgs_.try_lock()) { - // timeout, postprocess cached msg - if (cached_msg_.second != nullptr) { + // PROCESS: if timeout, postprocess cached msg + if (cached_det3d_msg_ptr_ != nullptr) { stop_watch_ptr_->toc("processing_time", true); + exportProcess(); + } - postprocess(*(cached_msg_.second)); - publish(*(cached_msg_.second)); - - // add processing time for debug - if (debug_publisher_) { - const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); - debug_publisher_->publish( - "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( - "debug/processing_time_ms", - processing_time_ms + stop_watch_ptr_->toc("processing_time", true)); - processing_time_ms = 0; - } + // reset flags whether the message is fused or not + for (auto & det2d : det2d_list_) { + det2d.is_fused = false; } - std::fill(is_fused_.begin(), is_fused_.end(), false); - cached_msg_.second = nullptr; mutex_cached_msgs_.unlock(); } else { + // TIMING: retry the process after 10ms try { std::chrono::nanoseconds period = 10ms; setPeriod(period.count()); @@ -469,8 +472,8 @@ void FusionNode::timer_callback() } } -template -void FusionNode::setPeriod(const int64_t new_period) +template +void FusionNode::setPeriod(const int64_t new_period) { if (!timer_) { return; @@ -486,8 +489,16 @@ void FusionNode::setPeriod(const int64_t new_period) } } -template -void FusionNode::publish(const TargetMsg3D & output_msg) +template +void FusionNode::postprocess( + const Msg3D & processing_msg __attribute__((unused)), + ExportObj & output_msg __attribute__((unused))) +{ + // do nothing by default +} + +template +void FusionNode::publish(const ExportObj & output_msg) { if (pub_ptr_->get_subscription_count() < 1) { return; @@ -495,10 +506,21 @@ void FusionNode::publish(const TargetMsg3D & output_msg pub_ptr_->publish(output_msg); } -template class FusionNode; -template class FusionNode< - DetectedObjectsWithFeature, DetectedObjectWithFeature, DetectedObjectsWithFeature>; -template class FusionNode; -template class FusionNode; -template class FusionNode; +// Explicit instantiation for the supported types + +// pointpainting fusion +template class FusionNode; + +// roi cluster fusion +template class FusionNode; + +// roi detected-object fusion +template class FusionNode; + +// roi pointcloud fusion +template class FusionNode; + +// segment pointcloud fusion +template class FusionNode; + } // namespace autoware::image_projection_based_fusion diff --git a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp index 2f6f853d4281e..bcd62383319c1 100644 --- a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp @@ -91,8 +91,7 @@ inline bool isUnknown(int label2d) } PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & options) -: FusionNode( - "pointpainting_fusion", options) +: FusionNode("pointpainting_fusion", options) { omp_num_threads_ = this->declare_parameter("omp_params.num_threads"); const float score_threshold = @@ -156,11 +155,16 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt const auto min_area_matrix = this->declare_parameter>("min_area_matrix"); const auto max_area_matrix = this->declare_parameter>("max_area_matrix"); - std::function sub_callback = + // subscriber + std::function sub_callback = std::bind(&PointPaintingFusionNode::subCallback, this, std::placeholders::_1); - sub_ = this->create_subscription( + sub_ = this->create_subscription( "~/input/pointcloud", rclcpp::SensorDataQoS().keep_last(3), sub_callback); + // publisher + point_pub_ptr_ = this->create_publisher("output", rclcpp::QoS{1}); + pub_ptr_ = this->create_publisher("~/output/objects", rclcpp::QoS{1}); + detection_class_remapper_.setParameters( allow_remapping_by_area_matrix, min_area_matrix, max_area_matrix); @@ -189,15 +193,13 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt diagnostics_interface_ptr_ = std::make_unique(this, "pointpainting_trt"); - obj_pub_ptr_ = this->create_publisher("~/output/objects", rclcpp::QoS{1}); - if (this->declare_parameter("build_only", false)) { RCLCPP_INFO(this->get_logger(), "TensorRT engine is built and shutdown node."); rclcpp::shutdown(); } } -void PointPaintingFusionNode::preprocess(sensor_msgs::msg::PointCloud2 & painted_pointcloud_msg) +void PointPaintingFusionNode::preprocess(PointCloudMsgType & painted_pointcloud_msg) { std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); @@ -254,9 +256,9 @@ void PointPaintingFusionNode::preprocess(sensor_msgs::msg::PointCloud2 & painted } void PointPaintingFusionNode::fuseOnSingleImage( - __attribute__((unused)) const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, - const std::size_t image_id, const DetectedObjectsWithFeature & input_roi_msg, - sensor_msgs::msg::PointCloud2 & painted_pointcloud_msg) + __attribute__((unused)) const PointCloudMsgType & input_pointcloud_msg, + const Det2dStatus & det2d, const RoiMsgType & input_roi_msg, + PointCloudMsgType & painted_pointcloud_msg) { if (painted_pointcloud_msg.data.empty() || painted_pointcloud_msg.fields.empty()) { RCLCPP_WARN_STREAM_THROTTLE( @@ -288,10 +290,6 @@ void PointPaintingFusionNode::fuseOnSingleImage( lidar2cam_affine = _transformToEigen(transform_stamped_optional.value().transform); } - // transform - // sensor_msgs::msg::PointCloud2 transformed_pointcloud; - // tf2::doTransform(painted_pointcloud_msg, transformed_pointcloud, transform_stamped); - const auto x_offset = painted_pointcloud_msg.fields .at(static_cast(autoware::point_types::PointXYZIRCIndex::X)) .offset; @@ -337,13 +335,13 @@ dc | dc dc dc dc ||zc| p_y = point_camera.y(); p_z = point_camera.z(); - if (camera_projectors_[image_id].isOutsideHorizontalView(p_x, p_z)) { + if (det2d.camera_projector_ptr->isOutsideHorizontalView(p_x, p_z)) { continue; } // project Eigen::Vector2d projected_point; - if (camera_projectors_[image_id].calcImageProjectedPoint( + if (det2d.camera_projector_ptr->calcImageProjectedPoint( cv::Point3d(p_x, p_y, p_z), projected_point)) { // iterate 2d bbox for (const auto & feature_object : objects) { @@ -360,41 +358,45 @@ dc | dc dc dc dc ||zc| *p_class = cls.second(label2d) ? (class_index_[cls.first] + *p_class) : *p_class; } } - } - if (debugger_) { - int thread_id = omp_get_thread_num(); - local_vectors[thread_id].push_back(projected_point); + if (debugger_) { + int thread_id = omp_get_thread_num(); + local_vectors[thread_id].push_back(projected_point); + } } } } - } - if (debugger_) { - std::unique_ptr inner_st_ptr; - if (time_keeper_) - inner_st_ptr = std::make_unique("publish debug message", *time_keeper_); + if (debugger_) { + std::unique_ptr inner_st_ptr; + if (time_keeper_) + inner_st_ptr = std::make_unique("publish debug message", *time_keeper_); - for (const auto & feature_object : input_roi_msg.feature_objects) { - debug_image_rois.push_back(feature_object.feature.roi); - } + for (const auto & feature_object : input_roi_msg.feature_objects) { + debug_image_rois.push_back(feature_object.feature.roi); + } - for (const auto & local_vec : local_vectors) { - debug_image_points.insert(debug_image_points.end(), local_vec.begin(), local_vec.end()); - } + for (const auto & local_vec : local_vectors) { + debug_image_points.insert(debug_image_points.end(), local_vec.begin(), local_vec.end()); + } - debugger_->image_rois_ = debug_image_rois; - debugger_->obstacle_points_ = debug_image_points; - debugger_->publishImage(image_id, input_roi_msg.header.stamp); + debugger_->image_rois_ = debug_image_rois; + debugger_->obstacle_points_ = debug_image_points; + debugger_->publishImage(det2d.id, input_roi_msg.header.stamp); + } } } -void PointPaintingFusionNode::postprocess(sensor_msgs::msg::PointCloud2 & painted_pointcloud_msg) +void PointPaintingFusionNode::postprocess( + const PointCloudMsgType & painted_pointcloud_msg, DetectedObjects & output_msg) { std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); diagnostics_interface_ptr_->clear(); + output_msg.header = painted_pointcloud_msg.header; + output_msg.objects.clear(); + const auto objects_sub_count = - obj_pub_ptr_->get_subscription_count() + obj_pub_ptr_->get_intra_process_subscription_count(); + pub_ptr_->get_subscription_count() + pub_ptr_->get_intra_process_subscription_count(); if (objects_sub_count < 1) { return; } @@ -430,22 +432,18 @@ void PointPaintingFusionNode::postprocess(sensor_msgs::msg::PointCloud2 & painte raw_objects.emplace_back(obj); } - autoware_perception_msgs::msg::DetectedObjects output_msg; - output_msg.header = painted_pointcloud_msg.header; + // prepare output message output_msg.objects = iou_bev_nms_.apply(raw_objects); detection_class_remapper_.mapClasses(output_msg); - if (objects_sub_count > 0) { - obj_pub_ptr_->publish(output_msg); + // publish debug message: painted pointcloud + if (point_pub_ptr_->get_subscription_count() > 0) { + point_pub_ptr_->publish(painted_pointcloud_msg); } diagnostics_interface_ptr_->publish(painted_pointcloud_msg.header.stamp); } -bool PointPaintingFusionNode::out_of_scope(__attribute__((unused)) const DetectedObjects & obj) -{ - return false; -} } // namespace autoware::image_projection_based_fusion #include diff --git a/perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp index 32db5319bb487..0a9d9e3391882 100644 --- a/perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp @@ -41,8 +41,7 @@ namespace autoware::image_projection_based_fusion using autoware::universe_utils::ScopedTimeTrack; RoiClusterFusionNode::RoiClusterFusionNode(const rclcpp::NodeOptions & options) -: FusionNode( - "roi_cluster_fusion", options) +: FusionNode("roi_cluster_fusion", options) { trust_object_iou_mode_ = declare_parameter("trust_object_iou_mode"); non_trust_object_iou_mode_ = declare_parameter("non_trust_object_iou_mode"); @@ -54,9 +53,12 @@ RoiClusterFusionNode::RoiClusterFusionNode(const rclcpp::NodeOptions & options) remove_unknown_ = declare_parameter("remove_unknown"); fusion_distance_ = declare_parameter("fusion_distance"); trust_object_distance_ = declare_parameter("trust_object_distance"); + + // publisher + pub_ptr_ = this->create_publisher("output", rclcpp::QoS{1}); } -void RoiClusterFusionNode::preprocess(DetectedObjectsWithFeature & output_cluster_msg) +void RoiClusterFusionNode::preprocess(ClusterMsgType & output_cluster_msg) { std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); @@ -71,36 +73,14 @@ void RoiClusterFusionNode::preprocess(DetectedObjectsWithFeature & output_cluste } } -void RoiClusterFusionNode::postprocess(DetectedObjectsWithFeature & output_cluster_msg) -{ - std::unique_ptr st_ptr; - if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); - - if (!remove_unknown_) { - return; - } - DetectedObjectsWithFeature known_objects; - known_objects.feature_objects.reserve(output_cluster_msg.feature_objects.size()); - for (auto & feature_object : output_cluster_msg.feature_objects) { - bool is_roi_label_known = feature_object.object.classification.front().label != - autoware_perception_msgs::msg::ObjectClassification::UNKNOWN; - if ( - is_roi_label_known || - feature_object.object.existence_probability >= min_roi_existence_prob_) { - known_objects.feature_objects.push_back(feature_object); - } - } - output_cluster_msg.feature_objects = known_objects.feature_objects; -} - void RoiClusterFusionNode::fuseOnSingleImage( - const DetectedObjectsWithFeature & input_cluster_msg, const std::size_t image_id, - const DetectedObjectsWithFeature & input_roi_msg, DetectedObjectsWithFeature & output_cluster_msg) + const ClusterMsgType & input_cluster_msg, const Det2dStatus & det2d, + const RoiMsgType & input_roi_msg, ClusterMsgType & output_cluster_msg) { std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); - const sensor_msgs::msg::CameraInfo & camera_info = camera_projectors_[image_id].getCameraInfo(); + const sensor_msgs::msg::CameraInfo & camera_info = det2d.camera_projector_ptr->getCameraInfo(); // get transform from cluster frame id to camera optical frame id geometry_msgs::msg::TransformStamped transform_stamped; @@ -149,7 +129,7 @@ void RoiClusterFusionNode::fuseOnSingleImage( } Eigen::Vector2d projected_point; - if (camera_projectors_[image_id].calcImageProjectedPoint( + if (det2d.camera_projector_ptr->calcImageProjectedPoint( cv::Point3d(*iter_x, *iter_y, *iter_z), projected_point)) { const int px = static_cast(projected_point.x()); const int py = static_cast(projected_point.y()); @@ -168,7 +148,6 @@ void RoiClusterFusionNode::fuseOnSingleImage( } sensor_msgs::msg::RegionOfInterest roi; - // roi.do_rectify = m_camera_info_.at(id).do_rectify; roi.x_offset = min_x; roi.y_offset = min_y; roi.width = max_x - min_x; @@ -231,7 +210,7 @@ void RoiClusterFusionNode::fuseOnSingleImage( // note: debug objects are safely cleared in fusion_node.cpp if (debugger_) { - debugger_->publishImage(image_id, input_roi_msg.header.stamp); + debugger_->publishImage(det2d.id, input_roi_msg.header.stamp); } } @@ -291,6 +270,28 @@ double RoiClusterFusionNode::cal_iou_by_mode( } } +void RoiClusterFusionNode::postprocess( + const ClusterMsgType & processing_msg, ClusterMsgType & output_msg) +{ + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + + output_msg = processing_msg; + + if (remove_unknown_) { + // filter by object classification and existence probability + output_msg.feature_objects.clear(); + for (const auto & feature_object : processing_msg.feature_objects) { + if ( + feature_object.object.classification.front().label != + autoware_perception_msgs::msg::ObjectClassification::UNKNOWN || + feature_object.object.existence_probability >= min_roi_existence_prob_) { + output_msg.feature_objects.push_back(feature_object); + } + } + } +} + } // namespace autoware::image_projection_based_fusion #include diff --git a/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp index 7be18d59fdbf1..37769ad73e8c7 100644 --- a/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp @@ -31,8 +31,7 @@ namespace autoware::image_projection_based_fusion using autoware::universe_utils::ScopedTimeTrack; RoiDetectedObjectFusionNode::RoiDetectedObjectFusionNode(const rclcpp::NodeOptions & options) -: FusionNode( - "roi_detected_object_fusion", options) +: FusionNode("roi_detected_object_fusion", options) { fusion_params_.passthrough_lower_bound_probability_thresholds = declare_parameter>("passthrough_lower_bound_probability_thresholds"); @@ -48,6 +47,9 @@ RoiDetectedObjectFusionNode::RoiDetectedObjectFusionNode(const rclcpp::NodeOptio can_assign_vector.data(), label_num, label_num); fusion_params_.can_assign_matrix = can_assign_matrix_tmp.transpose(); } + + // publisher + pub_ptr_ = this->create_publisher("output", rclcpp::QoS{1}); } void RoiDetectedObjectFusionNode::preprocess(DetectedObjects & output_msg) @@ -82,9 +84,8 @@ void RoiDetectedObjectFusionNode::preprocess(DetectedObjects & output_msg) } void RoiDetectedObjectFusionNode::fuseOnSingleImage( - const DetectedObjects & input_object_msg, const std::size_t image_id, - const DetectedObjectsWithFeature & input_roi_msg, - DetectedObjects & output_object_msg __attribute__((unused))) + const DetectedObjects & input_object_msg, const Det2dStatus & det2d, + const RoiMsgType & input_roi_msg, DetectedObjects & output_object_msg __attribute__((unused))) { std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); @@ -101,7 +102,7 @@ void RoiDetectedObjectFusionNode::fuseOnSingleImage( } const auto object_roi_map = - generateDetectedObjectRoIs(input_object_msg, image_id, object2camera_affine); + generateDetectedObjectRoIs(input_object_msg, det2d, object2camera_affine); fuseObjectsOnImage(input_object_msg, input_roi_msg.feature_objects, object_roi_map); if (debugger_) { @@ -109,13 +110,13 @@ void RoiDetectedObjectFusionNode::fuseOnSingleImage( for (std::size_t roi_i = 0; roi_i < input_roi_msg.feature_objects.size(); ++roi_i) { debugger_->image_rois_.push_back(input_roi_msg.feature_objects.at(roi_i).feature.roi); } - debugger_->publishImage(image_id, input_roi_msg.header.stamp); + debugger_->publishImage(det2d.id, input_roi_msg.header.stamp); } } std::map RoiDetectedObjectFusionNode::generateDetectedObjectRoIs( - const DetectedObjects & input_object_msg, const std::size_t & image_id, + const DetectedObjects & input_object_msg, const Det2dStatus & det2d, const Eigen::Affine3d & object2camera_affine) { std::unique_ptr st_ptr; @@ -131,7 +132,7 @@ RoiDetectedObjectFusionNode::generateDetectedObjectRoIs( return object_roi_map; } const auto & passthrough_object_flags = passthrough_object_flags_map_.at(timestamp_nsec); - const sensor_msgs::msg::CameraInfo & camera_info = camera_projectors_[image_id].getCameraInfo(); + const sensor_msgs::msg::CameraInfo & camera_info = det2d.camera_projector_ptr->getCameraInfo(); const double image_width = static_cast(camera_info.width); const double image_height = static_cast(camera_info.height); @@ -162,7 +163,7 @@ RoiDetectedObjectFusionNode::generateDetectedObjectRoIs( } Eigen::Vector2d proj_point; - if (camera_projectors_[image_id].calcImageProjectedPoint( + if (det2d.camera_projector_ptr->calcImageProjectedPoint( cv::Point3d(point.x(), point.y(), point.z()), proj_point)) { const double px = proj_point.x(); const double py = proj_point.y(); @@ -289,14 +290,15 @@ bool RoiDetectedObjectFusionNode::out_of_scope(const DetectedObject & obj) return is_out; } -void RoiDetectedObjectFusionNode::publish(const DetectedObjects & output_msg) +void RoiDetectedObjectFusionNode::postprocess( + const DetectedObjects & processing_msg, DetectedObjects & output_msg) { - if (pub_ptr_->get_subscription_count() < 1) { - return; - } + output_msg.header = processing_msg.header; + output_msg.objects.clear(); - int64_t timestamp_nsec = - output_msg.header.stamp.sec * static_cast(1e9) + output_msg.header.stamp.nanosec; + // filter out ignored objects + int64_t timestamp_nsec = processing_msg.header.stamp.sec * static_cast(1e9) + + processing_msg.header.stamp.nanosec; if ( passthrough_object_flags_map_.size() == 0 || fused_object_flags_map_.size() == 0 || ignored_object_flags_map_.size() == 0) { @@ -308,33 +310,34 @@ void RoiDetectedObjectFusionNode::publish(const DetectedObjects & output_msg) ignored_object_flags_map_.count(timestamp_nsec) == 0) { return; } + auto & passthrough_object_flags = passthrough_object_flags_map_.at(timestamp_nsec); auto & fused_object_flags = fused_object_flags_map_.at(timestamp_nsec); - auto & ignored_object_flags = ignored_object_flags_map_.at(timestamp_nsec); - - DetectedObjects output_objects_msg, debug_fused_objects_msg, debug_ignored_objects_msg; - output_objects_msg.header = output_msg.header; - debug_fused_objects_msg.header = output_msg.header; - debug_ignored_objects_msg.header = output_msg.header; - for (std::size_t obj_i = 0; obj_i < output_msg.objects.size(); ++obj_i) { - const auto & obj = output_msg.objects.at(obj_i); - if (passthrough_object_flags.at(obj_i)) { - output_objects_msg.objects.emplace_back(obj); + for (std::size_t obj_i = 0; obj_i < processing_msg.objects.size(); ++obj_i) { + const auto & obj = processing_msg.objects.at(obj_i); + if (passthrough_object_flags.at(obj_i) || fused_object_flags.at(obj_i)) { + output_msg.objects.emplace_back(obj); } + } + + // debug messages + auto & ignored_object_flags = ignored_object_flags_map_.at(timestamp_nsec); + DetectedObjects debug_fused_objects_msg, debug_ignored_objects_msg; + debug_fused_objects_msg.header = processing_msg.header; + debug_ignored_objects_msg.header = processing_msg.header; + for (std::size_t obj_i = 0; obj_i < processing_msg.objects.size(); ++obj_i) { + const auto & obj = processing_msg.objects.at(obj_i); if (fused_object_flags.at(obj_i)) { - output_objects_msg.objects.emplace_back(obj); debug_fused_objects_msg.objects.emplace_back(obj); } if (ignored_object_flags.at(obj_i)) { debug_ignored_objects_msg.objects.emplace_back(obj); } } - - pub_ptr_->publish(output_objects_msg); - debug_publisher_->publish("debug/fused_objects", debug_fused_objects_msg); debug_publisher_->publish("debug/ignored_objects", debug_ignored_objects_msg); + // clear flags passthrough_object_flags_map_.erase(timestamp_nsec); fused_object_flags_map_.erase(timestamp_nsec); ignored_object_flags_map_.erase(timestamp_nsec); diff --git a/perception/autoware_image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp index 998072d87774e..b1eef00053946 100644 --- a/perception/autoware_image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp @@ -37,58 +37,23 @@ namespace autoware::image_projection_based_fusion using autoware::universe_utils::ScopedTimeTrack; RoiPointCloudFusionNode::RoiPointCloudFusionNode(const rclcpp::NodeOptions & options) -: FusionNode( - "roi_pointcloud_fusion", options) +: FusionNode("roi_pointcloud_fusion", options) { fuse_unknown_only_ = declare_parameter("fuse_unknown_only"); min_cluster_size_ = declare_parameter("min_cluster_size"); max_cluster_size_ = declare_parameter("max_cluster_size"); cluster_2d_tolerance_ = declare_parameter("cluster_2d_tolerance"); - pub_objects_ptr_ = - this->create_publisher("output_clusters", rclcpp::QoS{1}); - cluster_debug_pub_ = this->create_publisher("debug/clusters", 1); -} - -void RoiPointCloudFusionNode::preprocess( - __attribute__((unused)) sensor_msgs::msg::PointCloud2 & pointcloud_msg) -{ - std::unique_ptr st_ptr; - if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); - return; + // publisher + point_pub_ptr_ = this->create_publisher("output", rclcpp::QoS{1}); + pub_ptr_ = this->create_publisher("output_clusters", rclcpp::QoS{1}); + cluster_debug_pub_ = this->create_publisher("debug/clusters", 1); } -void RoiPointCloudFusionNode::postprocess( - __attribute__((unused)) sensor_msgs::msg::PointCloud2 & pointcloud_msg) -{ - std::unique_ptr st_ptr; - if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); - - const auto objects_sub_count = pub_objects_ptr_->get_subscription_count() + - pub_objects_ptr_->get_intra_process_subscription_count(); - if (objects_sub_count < 1) { - return; - } - - DetectedObjectsWithFeature output_msg; - output_msg.header = pointcloud_msg.header; - output_msg.feature_objects = output_fused_objects_; - - if (objects_sub_count > 0) { - pub_objects_ptr_->publish(output_msg); - } - output_fused_objects_.clear(); - // publish debug cluster - if (cluster_debug_pub_->get_subscription_count() > 0) { - sensor_msgs::msg::PointCloud2 debug_cluster_msg; - autoware::euclidean_cluster::convertObjectMsg2SensorMsg(output_msg, debug_cluster_msg); - cluster_debug_pub_->publish(debug_cluster_msg); - } -} void RoiPointCloudFusionNode::fuseOnSingleImage( - const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const std::size_t image_id, - const DetectedObjectsWithFeature & input_roi_msg, - __attribute__((unused)) sensor_msgs::msg::PointCloud2 & output_pointcloud_msg) + const PointCloudMsgType & input_pointcloud_msg, const Det2dStatus & det2d, + const RoiMsgType & input_roi_msg, + __attribute__((unused)) PointCloudMsgType & output_pointcloud_msg) { std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); @@ -137,10 +102,10 @@ void RoiPointCloudFusionNode::fuseOnSingleImage( const int z_offset = input_pointcloud_msg.fields[pcl::getFieldIndex(input_pointcloud_msg, "z")].offset; - sensor_msgs::msg::PointCloud2 transformed_cloud; + PointCloudMsgType transformed_cloud; tf2::doTransform(input_pointcloud_msg, transformed_cloud, transform_stamped); - std::vector clusters; + std::vector clusters; std::vector clusters_data_size; clusters.resize(output_objs.size()); for (auto & cluster : clusters) { @@ -162,7 +127,7 @@ void RoiPointCloudFusionNode::fuseOnSingleImage( } Eigen::Vector2d projected_point; - if (camera_projectors_[image_id].calcImageProjectedPoint( + if (det2d.camera_projector_ptr->calcImageProjectedPoint( cv::Point3d(transformed_x, transformed_y, transformed_z), projected_point)) { for (std::size_t i = 0; i < output_objs.size(); ++i) { auto & feature_obj = output_objs.at(i); @@ -202,14 +167,40 @@ void RoiPointCloudFusionNode::fuseOnSingleImage( if (debugger_) { debugger_->image_rois_ = debug_image_rois; debugger_->obstacle_points_ = debug_image_points; - debugger_->publishImage(image_id, input_roi_msg.header.stamp); + debugger_->publishImage(det2d.id, input_roi_msg.header.stamp); } } -bool RoiPointCloudFusionNode::out_of_scope(__attribute__((unused)) - const DetectedObjectWithFeature & obj) +void RoiPointCloudFusionNode::postprocess( + const PointCloudMsgType & pointcloud_msg, ClusterMsgType & output_msg) { - return false; + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + + output_msg.header = pointcloud_msg.header; + output_msg.feature_objects = output_fused_objects_; + + output_fused_objects_.clear(); + + // publish debug cluster + if (cluster_debug_pub_->get_subscription_count() > 0) { + PointCloudMsgType debug_cluster_msg; + autoware::euclidean_cluster::convertObjectMsg2SensorMsg(output_msg, debug_cluster_msg); + cluster_debug_pub_->publish(debug_cluster_msg); + } + if (point_pub_ptr_->get_subscription_count() > 0) { + point_pub_ptr_->publish(pointcloud_msg); + } +} + +void RoiPointCloudFusionNode::publish(const ClusterMsgType & output_msg) +{ + const auto objects_sub_count = + pub_ptr_->get_subscription_count() + pub_ptr_->get_intra_process_subscription_count(); + if (objects_sub_count < 1) { + return; + } + pub_ptr_->publish(output_msg); } } // namespace autoware::image_projection_based_fusion diff --git a/perception/autoware_image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp index 486ae291abc6a..7d63cac7273c6 100644 --- a/perception/autoware_image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp @@ -36,7 +36,7 @@ namespace autoware::image_projection_based_fusion using autoware::universe_utils::ScopedTimeTrack; SegmentPointCloudFusionNode::SegmentPointCloudFusionNode(const rclcpp::NodeOptions & options) -: FusionNode("segmentation_pointcloud_fusion", options) +: FusionNode("segmentation_pointcloud_fusion", options) { filter_distance_threshold_ = declare_parameter("filter_distance_threshold"); for (auto & item : filter_semantic_label_target_list_) { @@ -48,47 +48,24 @@ SegmentPointCloudFusionNode::SegmentPointCloudFusionNode(const rclcpp::NodeOptio } is_publish_debug_mask_ = declare_parameter("is_publish_debug_mask"); pub_debug_mask_ptr_ = image_transport::create_publisher(this, "~/debug/mask"); -} - -void SegmentPointCloudFusionNode::preprocess(__attribute__((unused)) PointCloud2 & pointcloud_msg) -{ - std::unique_ptr st_ptr; - if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); - return; + // publisher + pub_ptr_ = this->create_publisher("output", rclcpp::QoS{1}); } -void SegmentPointCloudFusionNode::postprocess(PointCloud2 & pointcloud_msg) +void SegmentPointCloudFusionNode::preprocess(__attribute__((unused)) + PointCloudMsgType & pointcloud_msg) { std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); - auto original_cloud = std::make_shared(pointcloud_msg); - - int point_step = original_cloud->point_step; - size_t output_pointcloud_size = 0; - pointcloud_msg.data.clear(); - pointcloud_msg.data.resize(original_cloud->data.size()); - - for (size_t global_offset = 0; global_offset < original_cloud->data.size(); - global_offset += point_step) { - if (filter_global_offset_set_.find(global_offset) == filter_global_offset_set_.end()) { - copyPointCloud( - *original_cloud, point_step, global_offset, pointcloud_msg, output_pointcloud_size); - } - } - - pointcloud_msg.data.resize(output_pointcloud_size); - pointcloud_msg.row_step = output_pointcloud_size / pointcloud_msg.height; - pointcloud_msg.width = output_pointcloud_size / pointcloud_msg.point_step / pointcloud_msg.height; - - filter_global_offset_set_.clear(); return; } void SegmentPointCloudFusionNode::fuseOnSingleImage( - const PointCloud2 & input_pointcloud_msg, const std::size_t image_id, - [[maybe_unused]] const Image & input_mask, __attribute__((unused)) PointCloud2 & output_cloud) + const PointCloudMsgType & input_pointcloud_msg, const Det2dStatus & det2d, + [[maybe_unused]] const Image & input_mask, + __attribute__((unused)) PointCloudMsgType & output_cloud) { std::unique_ptr st_ptr; if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); @@ -100,7 +77,7 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage( return; } - const sensor_msgs::msg::CameraInfo & camera_info = camera_projectors_[image_id].getCameraInfo(); + const sensor_msgs::msg::CameraInfo & camera_info = det2d.camera_projector_ptr->getCameraInfo(); std::vector mask_data(input_mask.data.begin(), input_mask.data.end()); cv::Mat mask = perception_utils::runLengthDecoder(mask_data, input_mask.height, input_mask.width); @@ -128,7 +105,7 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage( transform_stamped = transform_stamped_optional.value(); } - PointCloud2 transformed_cloud; + PointCloudMsgType transformed_cloud; tf2::doTransform(input_pointcloud_msg, transformed_cloud, transform_stamped); int point_step = input_pointcloud_msg.point_step; @@ -150,7 +127,7 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage( } Eigen::Vector2d projected_point; - if (!camera_projectors_[image_id].calcImageProjectedPoint( + if (!det2d.camera_projector_ptr->calcImageProjectedPoint( cv::Point3d(transformed_x, transformed_y, transformed_z), projected_point)) { continue; } @@ -168,11 +145,33 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage( } } -bool SegmentPointCloudFusionNode::out_of_scope(__attribute__((unused)) - const PointCloud2 & filtered_cloud) +void SegmentPointCloudFusionNode::postprocess( + const PointCloudMsgType & pointcloud_msg, PointCloudMsgType & output_msg) { - return false; + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + + output_msg.header = pointcloud_msg.header; + output_msg.data.clear(); + output_msg.data.resize(pointcloud_msg.data.size()); + const int point_step = pointcloud_msg.point_step; + + size_t output_pointcloud_size = 0; + for (size_t global_offset = 0; global_offset < pointcloud_msg.data.size(); + global_offset += point_step) { + if (filter_global_offset_set_.find(global_offset) == filter_global_offset_set_.end()) { + copyPointCloud(pointcloud_msg, point_step, global_offset, output_msg, output_pointcloud_size); + } + } + + output_msg.data.resize(output_pointcloud_size); + output_msg.row_step = output_pointcloud_size / output_msg.height; + output_msg.width = output_pointcloud_size / output_msg.point_step / output_msg.height; + + filter_global_offset_set_.clear(); + return; } + } // namespace autoware::image_projection_based_fusion #include diff --git a/perception/autoware_image_projection_based_fusion/src/utils/utils.cpp b/perception/autoware_image_projection_based_fusion/src/utils/utils.cpp index 4456d25b18167..81424d4c23a34 100644 --- a/perception/autoware_image_projection_based_fusion/src/utils/utils.cpp +++ b/perception/autoware_image_projection_based_fusion/src/utils/utils.cpp @@ -67,8 +67,8 @@ Eigen::Affine3d transformToEigen(const geometry_msgs::msg::Transform & t) } void closest_cluster( - const PointCloud2 & cluster, const double cluster_2d_tolerance, const int min_cluster_size, - const pcl::PointXYZ & center, PointCloud2 & out_cluster) + const PointCloudMsgType & cluster, const double cluster_2d_tolerance, const int min_cluster_size, + const pcl::PointXYZ & center, PointCloudMsgType & out_cluster) { // sort point by distance to camera origin @@ -123,8 +123,8 @@ void closest_cluster( } void updateOutputFusedObjects( - std::vector & output_objs, std::vector & clusters, - const std::vector & clusters_data_size, const PointCloud2 & in_cloud, + std::vector & output_objs, std::vector & clusters, + const std::vector & clusters_data_size, const PointCloudMsgType & in_cloud, const std_msgs::msg::Header & in_roi_header, const tf2_ros::Buffer & tf_buffer, const int min_cluster_size, const int max_cluster_size, const float cluster_2d_tolerance, std::vector & output_fused_objects) @@ -162,7 +162,7 @@ void updateOutputFusedObjects( // TODO(badai-nguyen): change to interface to select refine criteria like closest, largest // to output refine cluster and centroid - sensor_msgs::msg::PointCloud2 refine_cluster; + PointCloudMsgType refine_cluster; closest_cluster( cluster, cluster_2d_tolerance, min_cluster_size, camera_orig_point_frame, refine_cluster); if ( @@ -184,7 +184,7 @@ void updateOutputFusedObjects( } } -geometry_msgs::msg::Point getCentroid(const sensor_msgs::msg::PointCloud2 & pointcloud) +geometry_msgs::msg::Point getCentroid(const PointCloudMsgType & pointcloud) { geometry_msgs::msg::Point centroid; centroid.x = 0.0f; From 811f59d696d39c99e8731b70214f01bdcc64378e Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Wed, 8 Jan 2025 18:39:53 +0900 Subject: [PATCH 154/334] docs(bpp): revise explanation for Failure modules (#9863) Signed-off-by: Zulfaqar Azmi --- .../docs/behavior_path_planner_manager_design.md | 4 ++-- .../autoware_behavior_path_planner/package.xml | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/docs/behavior_path_planner_manager_design.md b/planning/behavior_path_planner/autoware_behavior_path_planner/docs/behavior_path_planner_manager_design.md index 1e8532eba2f3a..3b787303d8d20 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/docs/behavior_path_planner_manager_design.md +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/docs/behavior_path_planner_manager_design.md @@ -533,9 +533,9 @@ If this case happened in the slot, `is_upstream_waiting_approved` is set to true ### Failure modules -The failure modules return the status `ModuleStatus::FAILURE`. The manager removes the module from approved modules stack as well as waiting approval modules, but the failure module is not moved to candidate modules stack. +If a module returns `ModuleStatus::FAILURE`, the manager removes the failed module. Additionally, all modules after the failed module are removed, even if they did not return `ModuleStatus::FAILURE`. These modules are not added back to the candidate modules stack and will instead run again from the beginning. Once these modules are removed, the output of the module prior to the failed module will be used as the planner's output. -As a result, the module A's output is used as approved modules stack. +As shown in the example below, modules B, A, and C are running. When module A returns `ModuleStatus::FAILURE`, both module A and C are removed from the approved modules stack. Module B's output is then used as the final output of the planner. ![failure_modules](../image/manager/failure_modules.drawio.svg) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/package.xml b/planning/behavior_path_planner/autoware_behavior_path_planner/package.xml index 7b7e2438a3fd6..f9c736b9d5dde 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/package.xml @@ -21,6 +21,7 @@ Kyoichi Sugahara Takayuki Murooka Go Sakayori + Mamoru Sobue Apache License 2.0 @@ -29,7 +30,6 @@ Fumiya Watanabe Zulfaqar Azmi Kosuke Takeuchi - Yutaka Shimizu Takayuki Murooka Ryohsuke Mitsudome From b5c008a2b6726458e7b2c304fce7b3e5c159cb5f Mon Sep 17 00:00:00 2001 From: cyn-liu <104069308+cyn-liu@users.noreply.github.com> Date: Thu, 9 Jan 2025 08:01:43 +0800 Subject: [PATCH 155/334] feat(autoware_point_types): move autoware_point_types to autoware.core (#9864) Signed-off-by: liu cui --- common/autoware_point_types/CHANGELOG.rst | 150 -------------- common/autoware_point_types/CMakeLists.txt | 25 --- common/autoware_point_types/README.md | 1 - .../include/autoware/point_types/types.hpp | 188 ------------------ common/autoware_point_types/package.xml | 34 ---- .../test/test_point_types.cpp | 66 ------ 6 files changed, 464 deletions(-) delete mode 100644 common/autoware_point_types/CHANGELOG.rst delete mode 100644 common/autoware_point_types/CMakeLists.txt delete mode 100644 common/autoware_point_types/README.md delete mode 100644 common/autoware_point_types/include/autoware/point_types/types.hpp delete mode 100644 common/autoware_point_types/package.xml delete mode 100644 common/autoware_point_types/test/test_point_types.cpp diff --git a/common/autoware_point_types/CHANGELOG.rst b/common/autoware_point_types/CHANGELOG.rst deleted file mode 100644 index 5e26002677a36..0000000000000 --- a/common/autoware_point_types/CHANGELOG.rst +++ /dev/null @@ -1,150 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package autoware_point_types -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -0.40.0 (2024-12-12) -------------------- -* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" - This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. -* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) -* chore(package.xml): bump version to 0.39.0 (`#9587 `_) - * chore(package.xml): bump version to 0.39.0 - * fix: fix ticket links in CHANGELOG.rst - * fix: remove unnecessary diff - --------- - Co-authored-by: Yutaka Kondo -* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) -* 0.39.0 -* update changelog -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) - * unify package.xml version to 0.37.0 - * remove system_monitor/CHANGELOG.rst - * add changelog - * 0.38.0 - --------- -* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo - -0.39.0 (2024-11-25) -------------------- -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) - * unify package.xml version to 0.37.0 - * remove system_monitor/CHANGELOG.rst - * add changelog - * 0.38.0 - --------- -* Contributors: Esteve Fernandez, Yutaka Kondo - -0.38.0 (2024-11-08) -------------------- -* unify package.xml version to 0.37.0 -* refactor(autoware_point_types): prefix namespace with autoware::point_types (`#9169 `_) -* feat: migrating pointcloud types (`#6996 `_) - * feat: changed most of sensing to the new type - * chore: started applying changes to the perception stack - * feat: confirmed operation until centerpoint - * feat: reverted to the original implementation of pointpainting - * chore: forgot to push a header - * feat: also implemented the changes for the subsample filters that were out of scope before - * fix: some point type changes were missing from the latest merge from main - * chore: removed unused code, added comments, and brought back a removed publish - * chore: replaced pointcloud_raw for pointcloud_raw_ex to avoid extra processing time in the drivers - * feat: added memory layout checks - * chore: updated documentation regarding the point types - * chore: added hyperlinks to the point definitions. will be valid only once the PR is merged - * fix: fixed compilation due to moving the utilities files to the base library - * chore: separated the utilities functions due to a dependency issue - * chore: forgot that perception also uses the filter class - * feature: adapted the undistortion tests to the new point type - --------- - Co-authored-by: kminoda <44218668+kminoda@users.noreply.github.com> - Co-authored-by: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> -* chore: updated maintainers for the autoware_point_types package (`#7797 `_) -* docs(common): adding .pages file (`#7148 `_) - * docs(common): adding .pages file - * fix naming - * fix naming - * fix naming - * include main page plus explanation to autoware tools - * style(pre-commit): autofix - --------- - Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> -* Contributors: Esteve Fernandez, Kenzo Lobos Tsunekawa, Yutaka Kondo, Zulfaqar Azmi - -0.26.0 (2024-04-03) -------------------- -* build: mark autoware_cmake as (`#3616 `_) - * build: mark autoware_cmake as - with , autoware_cmake is automatically exported with ament_target_dependencies() (unecessary) - * style(pre-commit): autofix - * chore: fix pre-commit errors - --------- - Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> - Co-authored-by: Kenji Miyake -* feat: isolate gtests in all packages (`#693 `_) -* chore: upgrade cmake_minimum_required to 3.14 (`#856 `_) -* refactor: use autoware cmake (`#849 `_) - * remove autoware_auto_cmake - * add build_depend of autoware_cmake - * use autoware_cmake in CMakeLists.txt - * fix bugs - * fix cmake lint errors -* feat: add blockage diagnostics (`#461 `_) - * feat!: add blockage diagnostic - * fix: typo - * docs: add documentation - * ci(pre-commit): autofix - * fix: typo - * ci(pre-commit): autofix - * fix: typo - * chore: add adjustable param - * ci(pre-commit): autofix - * feat!: add blockage diagnostic - * fix: typo - * docs: add documentation - * ci(pre-commit): autofix - * fix: typo - * ci(pre-commit): autofix - * fix: typo - * chore: add adjustable param - * ci(pre-commit): autofix - * chore: rearrange header file - * chore: fix typo - * chore: rearrange header - * fix: revert accident change - * chore: fix typo - * docs: add limits - * chore: check overflow - Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> -* ci: check include guard (`#438 `_) - * ci: check include guard - * apply pre-commit - * Update .pre-commit-config.yaml - Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> - * fix: pre-commit - Co-authored-by: Kenji Miyake - Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> -* feat: add point_types for wrapper (`#784 `_) (`#215 `_) - * add point_types - * Revert "add point_types" - This reverts commit 5810000cd1cbd876bc22372e2bb74ccaca06187b. - * create autoware_point_types pkg - * add include - * add cmath - * fix author - * fix bug - * define epsilon as argument - * add test - * remove unnamed namespace - * update test - * fix test name - * use std::max - * change comparison method - * remove unnencessary line - * fix test - * fix comparison method name - Co-authored-by: Taichi Higashide -* Contributors: Daisuke Nishimatsu, Kenji Miyake, Maxime CLEMENT, Takagi, Isamu, Vincent Richard, badai nguyen diff --git a/common/autoware_point_types/CMakeLists.txt b/common/autoware_point_types/CMakeLists.txt deleted file mode 100644 index c149f79dab71f..0000000000000 --- a/common/autoware_point_types/CMakeLists.txt +++ /dev/null @@ -1,25 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(autoware_point_types) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -include_directories( - include - SYSTEM - ${PCL_INCLUDE_DIRS} -) - -if(BUILD_TESTING) - ament_add_ros_isolated_gtest(test_autoware_point_types - test/test_point_types.cpp - ) - target_include_directories(test_autoware_point_types - PRIVATE include - ) - ament_target_dependencies(test_autoware_point_types - point_cloud_msg_wrapper - ) -endif() - -ament_auto_package() diff --git a/common/autoware_point_types/README.md b/common/autoware_point_types/README.md deleted file mode 100644 index 92f19d2bc353a..0000000000000 --- a/common/autoware_point_types/README.md +++ /dev/null @@ -1 +0,0 @@ -# Autoware Point Types diff --git a/common/autoware_point_types/include/autoware/point_types/types.hpp b/common/autoware_point_types/include/autoware/point_types/types.hpp deleted file mode 100644 index 0fde62222e276..0000000000000 --- a/common/autoware_point_types/include/autoware/point_types/types.hpp +++ /dev/null @@ -1,188 +0,0 @@ -// Copyright 2021 Tier IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__POINT_TYPES__TYPES_HPP_ -#define AUTOWARE__POINT_TYPES__TYPES_HPP_ - -#include - -#include - -#include -#include - -namespace autoware::point_types -{ -template -bool float_eq(const T a, const T b, const T eps = 10e-6) -{ - return std::fabs(a - b) < eps; -} - -struct PointXYZI -{ - float x{0.0F}; - float y{0.0F}; - float z{0.0F}; - float intensity{0.0F}; - friend bool operator==(const PointXYZI & p1, const PointXYZI & p2) noexcept - { - return float_eq(p1.x, p2.x) && float_eq(p1.y, p2.y) && - float_eq(p1.z, p2.z) && float_eq(p1.intensity, p2.intensity); - } -}; - -enum ReturnType : uint8_t { - INVALID = 0, - SINGLE_STRONGEST, - SINGLE_LAST, - DUAL_STRONGEST_FIRST, - DUAL_STRONGEST_LAST, - DUAL_WEAK_FIRST, - DUAL_WEAK_LAST, - DUAL_ONLY, -}; - -struct PointXYZIRC -{ - float x{0.0F}; - float y{0.0F}; - float z{0.0F}; - std::uint8_t intensity{0U}; - std::uint8_t return_type{0U}; - std::uint16_t channel{0U}; - - friend bool operator==(const PointXYZIRC & p1, const PointXYZIRC & p2) noexcept - { - return float_eq(p1.x, p2.x) && float_eq(p1.y, p2.y) && - float_eq(p1.z, p2.z) && p1.intensity == p2.intensity && - p1.return_type == p2.return_type && p1.channel == p2.channel; - } -}; - -struct PointXYZIRADRT -{ - float x{0.0F}; - float y{0.0F}; - float z{0.0F}; - float intensity{0.0F}; - uint16_t ring{0U}; - float azimuth{0.0F}; - float distance{0.0F}; - uint8_t return_type{0U}; - double time_stamp{0.0}; - friend bool operator==(const PointXYZIRADRT & p1, const PointXYZIRADRT & p2) noexcept - { - return float_eq(p1.x, p2.x) && float_eq(p1.y, p2.y) && - float_eq(p1.z, p2.z) && float_eq(p1.intensity, p2.intensity) && - p1.ring == p2.ring && float_eq(p1.azimuth, p2.azimuth) && - float_eq(p1.distance, p2.distance) && p1.return_type == p2.return_type && - float_eq(p1.time_stamp, p2.time_stamp); - } -}; - -struct PointXYZIRCAEDT -{ - float x{0.0F}; - float y{0.0F}; - float z{0.0F}; - std::uint8_t intensity{0U}; - std::uint8_t return_type{0U}; - std::uint16_t channel{0U}; - float azimuth{0.0F}; - float elevation{0.0F}; - float distance{0.0F}; - std::uint32_t time_stamp{0U}; - - friend bool operator==(const PointXYZIRCAEDT & p1, const PointXYZIRCAEDT & p2) noexcept - { - return float_eq(p1.x, p2.x) && float_eq(p1.y, p2.y) && - float_eq(p1.z, p2.z) && p1.intensity == p2.intensity && - p1.return_type == p2.return_type && p1.channel == p2.channel && - float_eq(p1.azimuth, p2.azimuth) && float_eq(p1.distance, p2.distance) && - p1.time_stamp == p2.time_stamp; - } -}; - -enum class PointXYZIIndex { X, Y, Z, Intensity }; -enum class PointXYZIRCIndex { X, Y, Z, Intensity, ReturnType, Channel }; -enum class PointXYZIRADRTIndex { - X, - Y, - Z, - Intensity, - Ring, - Azimuth, - Distance, - ReturnType, - TimeStamp -}; -enum class PointXYZIRCAEDTIndex { - X, - Y, - Z, - Intensity, - ReturnType, - Channel, - Azimuth, - Elevation, - Distance, - TimeStamp -}; - -LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(azimuth); -LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(elevation); -LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(distance); -LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(return_type); -LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(time_stamp); - -LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(channel); - -using PointXYZIRCGenerator = std::tuple< - point_cloud_msg_wrapper::field_x_generator, point_cloud_msg_wrapper::field_y_generator, - point_cloud_msg_wrapper::field_z_generator, point_cloud_msg_wrapper::field_intensity_generator, - field_return_type_generator, field_channel_generator>; - -using PointXYZIRADRTGenerator = std::tuple< - point_cloud_msg_wrapper::field_x_generator, point_cloud_msg_wrapper::field_y_generator, - point_cloud_msg_wrapper::field_z_generator, point_cloud_msg_wrapper::field_intensity_generator, - point_cloud_msg_wrapper::field_ring_generator, field_azimuth_generator, field_distance_generator, - field_return_type_generator, field_time_stamp_generator>; - -using PointXYZIRCAEDTGenerator = std::tuple< - point_cloud_msg_wrapper::field_x_generator, point_cloud_msg_wrapper::field_y_generator, - point_cloud_msg_wrapper::field_z_generator, point_cloud_msg_wrapper::field_intensity_generator, - field_return_type_generator, field_channel_generator, field_azimuth_generator, - field_elevation_generator, field_distance_generator, field_time_stamp_generator>; - -} // namespace autoware::point_types - -POINT_CLOUD_REGISTER_POINT_STRUCT( - autoware::point_types::PointXYZIRC, - (float, x, x)(float, y, y)(float, z, z)(std::uint8_t, intensity, intensity)( - std::uint8_t, return_type, return_type)(std::uint16_t, channel, channel)) - -POINT_CLOUD_REGISTER_POINT_STRUCT( - autoware::point_types::PointXYZIRADRT, - (float, x, x)(float, y, y)(float, z, z)(float, intensity, intensity)(std::uint16_t, ring, ring)( - float, azimuth, azimuth)(float, distance, distance)(std::uint8_t, return_type, return_type)( - double, time_stamp, time_stamp)) - -POINT_CLOUD_REGISTER_POINT_STRUCT( - autoware::point_types::PointXYZIRCAEDT, - (float, x, x)(float, y, y)(float, z, z)(std::uint8_t, intensity, intensity)( - std::uint8_t, return_type, - return_type)(std::uint16_t, channel, channel)(float, azimuth, azimuth)( - float, elevation, elevation)(float, distance, distance)(std::uint32_t, time_stamp, time_stamp)) -#endif // AUTOWARE__POINT_TYPES__TYPES_HPP_ diff --git a/common/autoware_point_types/package.xml b/common/autoware_point_types/package.xml deleted file mode 100644 index e35e6a63de648..0000000000000 --- a/common/autoware_point_types/package.xml +++ /dev/null @@ -1,34 +0,0 @@ - - - - autoware_point_types - 0.40.0 - The point types definition to use point_cloud_msg_wrapper - David Wong - Max Schmeller - Apache License 2.0 - - ament_cmake_core - ament_cmake_export_dependencies - ament_cmake_test - autoware_cmake - - ament_cmake_core - ament_cmake_test - - ament_cmake_copyright - ament_cmake_cppcheck - ament_cmake_lint_cmake - ament_cmake_xmllint - pcl_ros - point_cloud_msg_wrapper - - ament_cmake_ros - ament_lint_auto - autoware_lint_common - point_cloud_msg_wrapper - - - ament_cmake - - diff --git a/common/autoware_point_types/test/test_point_types.cpp b/common/autoware_point_types/test/test_point_types.cpp deleted file mode 100644 index 08696a9948f60..0000000000000 --- a/common/autoware_point_types/test/test_point_types.cpp +++ /dev/null @@ -1,66 +0,0 @@ -// Copyright 2021 Tier IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/point_types/types.hpp" - -#include - -#include - -TEST(PointEquality, PointXYZI) -{ - using autoware::point_types::PointXYZI; - - PointXYZI pt0{0, 1, 2, 3}; - PointXYZI pt1{0, 1, 2, 3}; - EXPECT_EQ(pt0, pt1); -} - -TEST(PointEquality, PointXYZIRADRT) -{ - using autoware::point_types::PointXYZIRADRT; - - PointXYZIRADRT pt0{0, 1, 2, 3, 4, 5, 6, 7, 8}; - PointXYZIRADRT pt1{0, 1, 2, 3, 4, 5, 6, 7, 8}; - EXPECT_EQ(pt0, pt1); -} - -TEST(PointEquality, PointXYZIRCAEDT) -{ - using autoware::point_types::PointXYZIRCAEDT; - - PointXYZIRCAEDT pt0{0, 1, 2, 3, 4, 5, 6, 7, 8, 9}; - PointXYZIRCAEDT pt1{0, 1, 2, 3, 4, 5, 6, 7, 8, 9}; - EXPECT_EQ(pt0, pt1); -} - -TEST(PointEquality, FloatEq) -{ - // test template - EXPECT_TRUE(autoware::point_types::float_eq(1, 1)); - EXPECT_TRUE(autoware::point_types::float_eq(1, 1)); - - // test floating point error - EXPECT_TRUE(autoware::point_types::float_eq(1, 1 + std::numeric_limits::epsilon())); - - // test difference of sign - EXPECT_FALSE(autoware::point_types::float_eq(2, -2)); - EXPECT_FALSE(autoware::point_types::float_eq(-2, 2)); - - // small value difference - EXPECT_FALSE(autoware::point_types::float_eq(2, 2 + 10e-6)); - - // expect same value if epsilon is larger than difference - EXPECT_TRUE(autoware::point_types::float_eq(2, 2 + 10e-6, 10e-5)); -} From fd23b61e8c81ef22deacc4ef29970bf1fe460629 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Thu, 9 Jan 2025 09:10:40 +0900 Subject: [PATCH 156/334] fix(image_projection_based_fusion): remove mutex (#9862) refactor: Refactor fusion_node.hpp and fusion_node.cpp for improved code organization and readability Signed-off-by: Taekjin LEE --- .../fusion_node.hpp | 2 -- .../src/fusion_node.cpp | 30 +++++-------------- 2 files changed, 8 insertions(+), 24 deletions(-) diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp index b8881bc6abff7..e05339771f667 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp @@ -40,7 +40,6 @@ #include #include -#include #include #include #include @@ -127,7 +126,6 @@ class FusionNode : public rclcpp::Node // cache for fusion int64_t cached_det3d_msg_timestamp_; typename Msg3D::SharedPtr cached_det3d_msg_ptr_; - std::mutex mutex_cached_msgs_; protected: void setDet2DStatus(std::size_t rois_number); diff --git a/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp b/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp index 310c68f12db88..700d249831000 100644 --- a/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp @@ -280,8 +280,6 @@ void FusionNode::subCallback( } } - std::lock_guard lock(mutex_cached_msgs_); - // TIMING: reset timer to the timeout time auto period = std::chrono::duration_cast( std::chrono::duration(timeout_ms_)); @@ -447,28 +445,16 @@ void FusionNode::timer_callback() using std::chrono_literals::operator""ms; timer_->cancel(); - if (mutex_cached_msgs_.try_lock()) { - // PROCESS: if timeout, postprocess cached msg - if (cached_det3d_msg_ptr_ != nullptr) { - stop_watch_ptr_->toc("processing_time", true); - exportProcess(); - } - // reset flags whether the message is fused or not - for (auto & det2d : det2d_list_) { - det2d.is_fused = false; - } + // PROCESS: if timeout, postprocess cached msg + if (cached_det3d_msg_ptr_ != nullptr) { + stop_watch_ptr_->toc("processing_time", true); + exportProcess(); + } - mutex_cached_msgs_.unlock(); - } else { - // TIMING: retry the process after 10ms - try { - std::chrono::nanoseconds period = 10ms; - setPeriod(period.count()); - } catch (rclcpp::exceptions::RCLError & ex) { - RCLCPP_WARN_THROTTLE(get_logger(), *get_clock(), 5000, "%s", ex.what()); - } - timer_->reset(); + // reset flags whether the message is fused or not + for (auto & det2d : det2d_list_) { + det2d.is_fused = false; } } From 51818f00ec4775510386c7757065bba84474a0a1 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Thu, 9 Jan 2025 13:30:05 +0900 Subject: [PATCH 157/334] feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files localization/autoware_twist2accel (#9868) Signed-off-by: vish0012 Co-authored-by: SakodaShintaro --- localization/autoware_twist2accel/package.xml | 2 +- localization/autoware_twist2accel/src/twist2accel.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/localization/autoware_twist2accel/package.xml b/localization/autoware_twist2accel/package.xml index 75cea94546516..013ef54fe52d1 100644 --- a/localization/autoware_twist2accel/package.xml +++ b/localization/autoware_twist2accel/package.xml @@ -17,13 +17,13 @@ ament_cmake_auto autoware_cmake + autoware_internal_debug_msgs autoware_signal_processing geometry_msgs nav_msgs rclcpp rclcpp_components tf2 - tier4_debug_msgs ament_cmake_ros ament_lint_auto diff --git a/localization/autoware_twist2accel/src/twist2accel.hpp b/localization/autoware_twist2accel/src/twist2accel.hpp index d338b256fec77..d142328f9d498 100644 --- a/localization/autoware_twist2accel/src/twist2accel.hpp +++ b/localization/autoware_twist2accel/src/twist2accel.hpp @@ -19,11 +19,11 @@ #include +#include #include #include #include #include -#include #include #include From 708fa76bcad2baf1eb17817c8fb79eb87dff3a72 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Thu, 9 Jan 2025 14:42:41 +0900 Subject: [PATCH 158/334] =?UTF-8?q?feat:=20tier4=5Fdebug=5Fmsgs=20to=20aut?= =?UTF-8?q?oware=5Finternal=5Fdebug=5Fmsgs=20in=20files=20=20perc=E2=80=A6?= =?UTF-8?q?=20(#9879)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs to autoware_internal_debug_msgs in files perception/autoware_multi_object_tracker Signed-off-by: vish0012 --- .../src/debugger/debugger.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/perception/autoware_multi_object_tracker/src/debugger/debugger.cpp b/perception/autoware_multi_object_tracker/src/debugger/debugger.cpp index 3eebb3c11ee3e..3761fc1e6f43a 100644 --- a/perception/autoware_multi_object_tracker/src/debugger/debugger.cpp +++ b/perception/autoware_multi_object_tracker/src/debugger/debugger.cpp @@ -127,7 +127,7 @@ void TrackerDebugger::startMeasurementTime( stamp_process_start_ = now; if (debug_settings_.publish_processing_time) { double input_latency_ms = (now - last_input_stamp_).seconds() * 1e3; - processing_time_publisher_->publish( + processing_time_publisher_->publish( "debug/input_latency_ms", input_latency_ms); } // initialize debug time stamps @@ -169,15 +169,15 @@ void TrackerDebugger::endPublishTime(const rclcpp::Time & now, const rclcpp::Tim double measurement_to_object_ms = (object_time - last_input_stamp_).seconds() * 1e3; // starting from the measurement time - processing_time_publisher_->publish( + processing_time_publisher_->publish( "debug/pipeline_latency_ms", pipeline_latency_ms_); - processing_time_publisher_->publish( + processing_time_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - processing_time_publisher_->publish( + processing_time_publisher_->publish( "debug/processing_time_ms", processing_time_ms); - processing_time_publisher_->publish( + processing_time_publisher_->publish( "debug/processing_latency_ms", processing_latency_ms); - processing_time_publisher_->publish( + processing_time_publisher_->publish( "debug/meas_to_tracked_object_ms", measurement_to_object_ms); } stamp_publish_output_ = now; From e60c867c73bc7f89220c83a0e228cee8b9abf4de Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Thu, 9 Jan 2025 14:42:50 +0900 Subject: [PATCH 159/334] =?UTF-8?q?feat:=20tier4=5Fdebug=5Fmsgs=20changed?= =?UTF-8?q?=20to=20autoware=5Finternal=5Fdebug=5Fmsgs=20in=20fil=E2=80=A6?= =?UTF-8?q?=20(#9875)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files perception/autoware_map_based_prediction Signed-off-by: vish0012 --- .../map_based_prediction/map_based_prediction_node.hpp | 2 +- perception/autoware_map_based_prediction/package.xml | 2 +- .../src/map_based_prediction_node.cpp | 4 ++-- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp b/perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp index 1675f8b1fbfa2..b047cd28114ba 100644 --- a/perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp +++ b/perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp @@ -71,8 +71,8 @@ struct hash } // namespace std namespace autoware::map_based_prediction { +using autoware_internal_debug_msgs::msg::StringStamped; using autoware_planning_msgs::msg::TrajectoryPoint; -using tier4_debug_msgs::msg::StringStamped; using TrajectoryPoints = std::vector; class MapBasedPredictionNode : public rclcpp::Node diff --git a/perception/autoware_map_based_prediction/package.xml b/perception/autoware_map_based_prediction/package.xml index 9012590a45b14..58dfcb17c7631 100644 --- a/perception/autoware_map_based_prediction/package.xml +++ b/perception/autoware_map_based_prediction/package.xml @@ -16,6 +16,7 @@ ament_cmake autoware_cmake + autoware_internal_debug_msgs autoware_interpolation autoware_lanelet2_extension autoware_motion_utils @@ -27,7 +28,6 @@ tf2 tf2_geometry_msgs tf2_ros - tier4_debug_msgs unique_identifier_msgs visualization_msgs diff --git a/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp b/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp index 42dbf5b83fa8c..b65020d6b4708 100644 --- a/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp @@ -670,9 +670,9 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt if (stop_watch_ptr_) { const auto processing_time_ms = stop_watch_ptr_->toc("processing_time", true); const auto cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); - processing_time_publisher_->publish( + processing_time_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - processing_time_publisher_->publish( + processing_time_publisher_->publish( "debug/processing_time_ms", processing_time_ms); } } From 8d38d7fbae8e6860c54c7a435530bfda28df6672 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Thu, 9 Jan 2025 14:46:51 +0900 Subject: [PATCH 160/334] chore(autoware_string_stamped_overlay_rviz_plugin): fix version in package.xml (#9874) Signed-off-by: Fumiya Watanabe --- .../autoware_string_stamped_overlay_rviz_plugin/package.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/package.xml b/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/package.xml index c22bc75f55290..faef2f674832e 100644 --- a/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/package.xml +++ b/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/package.xml @@ -2,7 +2,7 @@ autoware_string_stamped_rviz_plugin - 0.39.0 + 0.40.0 RViz2 plugin for 2D overlays in the 3D view. Mainly a port of the JSK overlay plugin (https://github.com/jsk-ros-pkg/jsk_visualization). From 7d8b2613988bc0289bdbe824e3032ff23ed37d4b Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Thu, 9 Jan 2025 15:01:44 +0900 Subject: [PATCH 161/334] chore(autoware_twist2accel): remove an unused dependency (#9881) Removed an unused dependency Signed-off-by: Shintaro Sakoda --- localization/autoware_twist2accel/package.xml | 1 - localization/autoware_twist2accel/src/twist2accel.hpp | 1 - 2 files changed, 2 deletions(-) diff --git a/localization/autoware_twist2accel/package.xml b/localization/autoware_twist2accel/package.xml index 013ef54fe52d1..092b227c2ad40 100644 --- a/localization/autoware_twist2accel/package.xml +++ b/localization/autoware_twist2accel/package.xml @@ -17,7 +17,6 @@ ament_cmake_auto autoware_cmake - autoware_internal_debug_msgs autoware_signal_processing geometry_msgs nav_msgs diff --git a/localization/autoware_twist2accel/src/twist2accel.hpp b/localization/autoware_twist2accel/src/twist2accel.hpp index d142328f9d498..48bc03a326091 100644 --- a/localization/autoware_twist2accel/src/twist2accel.hpp +++ b/localization/autoware_twist2accel/src/twist2accel.hpp @@ -19,7 +19,6 @@ #include -#include #include #include #include From 7f4ed3dcea5f97bb0395a4b828785e0c08ef3bb0 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Thu, 9 Jan 2025 15:02:36 +0900 Subject: [PATCH 162/334] feat: tier4_debug_msgs to autoware_internal_debug_msgs in files localization/autoware_stop_filter (#9867) Signed-off-by: vish0012 Co-authored-by: SakodaShintaro --- localization/autoware_stop_filter/README.md | 8 ++++---- localization/autoware_stop_filter/package.xml | 2 +- localization/autoware_stop_filter/src/stop_filter.cpp | 5 +++-- localization/autoware_stop_filter/src/stop_filter.hpp | 4 ++-- 4 files changed, 10 insertions(+), 9 deletions(-) diff --git a/localization/autoware_stop_filter/README.md b/localization/autoware_stop_filter/README.md index 9904707a59996..9136f6b6fc8a0 100644 --- a/localization/autoware_stop_filter/README.md +++ b/localization/autoware_stop_filter/README.md @@ -18,10 +18,10 @@ This node aims to: ### Output -| Name | Type | Description | -| ----------------- | ------------------------------------ | -------------------------------------------------------- | -| `output/odom` | `nav_msgs::msg::Odometry` | odometry with suppressed longitudinal and yaw twist | -| `debug/stop_flag` | `tier4_debug_msgs::msg::BoolStamped` | flag to represent whether the vehicle is stopping or not | +| Name | Type | Description | +| ----------------- | ------------------------------------------------ | -------------------------------------------------------- | +| `output/odom` | `nav_msgs::msg::Odometry` | odometry with suppressed longitudinal and yaw twist | +| `debug/stop_flag` | `autoware_internal_debug_msgs::msg::BoolStamped` | flag to represent whether the vehicle is stopping or not | ## Parameters diff --git a/localization/autoware_stop_filter/package.xml b/localization/autoware_stop_filter/package.xml index 1ed5e2c2082be..50ba98484f59d 100644 --- a/localization/autoware_stop_filter/package.xml +++ b/localization/autoware_stop_filter/package.xml @@ -17,12 +17,12 @@ ament_cmake_auto autoware_cmake + autoware_internal_debug_msgs geometry_msgs nav_msgs rclcpp rclcpp_components tf2 - tier4_debug_msgs ament_cmake_ros ament_lint_auto diff --git a/localization/autoware_stop_filter/src/stop_filter.cpp b/localization/autoware_stop_filter/src/stop_filter.cpp index 17eaafdc3002a..b0f1bc8eba053 100644 --- a/localization/autoware_stop_filter/src/stop_filter.cpp +++ b/localization/autoware_stop_filter/src/stop_filter.cpp @@ -34,12 +34,13 @@ StopFilter::StopFilter(const rclcpp::NodeOptions & node_options) "input/odom", 1, std::bind(&StopFilter::callback_odometry, this, std::placeholders::_1)); pub_odom_ = create_publisher("output/odom", 1); - pub_stop_flag_ = create_publisher("debug/stop_flag", 1); + pub_stop_flag_ = + create_publisher("debug/stop_flag", 1); } void StopFilter::callback_odometry(const nav_msgs::msg::Odometry::SharedPtr msg) { - tier4_debug_msgs::msg::BoolStamped stop_flag_msg; + autoware_internal_debug_msgs::msg::BoolStamped stop_flag_msg; stop_flag_msg.stamp = msg->header.stamp; stop_flag_msg.data = false; diff --git a/localization/autoware_stop_filter/src/stop_filter.hpp b/localization/autoware_stop_filter/src/stop_filter.hpp index b6d56b5f77059..71864fab0a580 100644 --- a/localization/autoware_stop_filter/src/stop_filter.hpp +++ b/localization/autoware_stop_filter/src/stop_filter.hpp @@ -17,10 +17,10 @@ #include +#include #include #include #include -#include #include #include @@ -43,7 +43,7 @@ class StopFilter : public rclcpp::Node private: rclcpp::Publisher::SharedPtr pub_odom_; //!< @brief odom publisher - rclcpp::Publisher::SharedPtr + rclcpp::Publisher::SharedPtr pub_stop_flag_; //!< @brief stop flag publisher rclcpp::Subscription::SharedPtr sub_odom_; //!< @brief measurement odometry subscriber From ddb64dbe5e3809636470dad7a33d580a628a4fff Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Thu, 9 Jan 2025 15:12:19 +0900 Subject: [PATCH 163/334] feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files localization/autoware_pose2twist (#9866) Signed-off-by: vish0012 --- localization/autoware_pose2twist/README.md | 10 +++++----- localization/autoware_pose2twist/package.xml | 2 +- .../autoware_pose2twist/src/pose2twist_core.cpp | 9 +++++---- .../autoware_pose2twist/src/pose2twist_core.hpp | 6 +++--- 4 files changed, 14 insertions(+), 13 deletions(-) diff --git a/localization/autoware_pose2twist/README.md b/localization/autoware_pose2twist/README.md index 55ca4667c423d..7f81e0dece5b0 100644 --- a/localization/autoware_pose2twist/README.md +++ b/localization/autoware_pose2twist/README.md @@ -17,11 +17,11 @@ The `twist.angular` is calculated as `relative_rotation_vector / dt` for each fi ### Output -| Name | Type | Description | -| --------- | ------------------------------------- | --------------------------------------------- | -| twist | geometry_msgs::msg::TwistStamped | twist calculated from the input pose history. | -| linear_x | tier4_debug_msgs::msg::Float32Stamped | linear-x field of the output twist. | -| angular_z | tier4_debug_msgs::msg::Float32Stamped | angular-z field of the output twist. | +| Name | Type | Description | +| --------- | ------------------------------------------------- | --------------------------------------------- | +| twist | geometry_msgs::msg::TwistStamped | twist calculated from the input pose history. | +| linear_x | autoware_internal_debug_msgs::msg::Float32Stamped | linear-x field of the output twist. | +| angular_z | autoware_internal_debug_msgs::msg::Float32Stamped | angular-z field of the output twist. | ## Parameters diff --git a/localization/autoware_pose2twist/package.xml b/localization/autoware_pose2twist/package.xml index 3fd16856ef6af..cfde18d430cfd 100644 --- a/localization/autoware_pose2twist/package.xml +++ b/localization/autoware_pose2twist/package.xml @@ -17,11 +17,11 @@ ament_cmake autoware_cmake + autoware_internal_debug_msgs geometry_msgs rclcpp rclcpp_components tf2_geometry_msgs - tier4_debug_msgs ament_lint_auto autoware_lint_common diff --git a/localization/autoware_pose2twist/src/pose2twist_core.cpp b/localization/autoware_pose2twist/src/pose2twist_core.cpp index 4dc7b5fb04209..f071d7c8c66e2 100644 --- a/localization/autoware_pose2twist/src/pose2twist_core.cpp +++ b/localization/autoware_pose2twist/src/pose2twist_core.cpp @@ -29,9 +29,10 @@ Pose2Twist::Pose2Twist(const rclcpp::NodeOptions & options) : rclcpp::Node("pose durable_qos.transient_local(); twist_pub_ = create_publisher("twist", durable_qos); - linear_x_pub_ = create_publisher("linear_x", durable_qos); + linear_x_pub_ = + create_publisher("linear_x", durable_qos); angular_z_pub_ = - create_publisher("angular_z", durable_qos); + create_publisher("angular_z", durable_qos); // Note: this callback publishes topics above pose_sub_ = create_subscription( "pose", queue_size, std::bind(&Pose2Twist::callback_pose, this, _1)); @@ -105,12 +106,12 @@ void Pose2Twist::callback_pose(geometry_msgs::msg::PoseStamped::SharedPtr pose_m twist_msg.header.frame_id = "base_link"; twist_pub_->publish(twist_msg); - tier4_debug_msgs::msg::Float32Stamped linear_x_msg; + autoware_internal_debug_msgs::msg::Float32Stamped linear_x_msg; linear_x_msg.stamp = this->now(); linear_x_msg.data = static_cast(twist_msg.twist.linear.x); linear_x_pub_->publish(linear_x_msg); - tier4_debug_msgs::msg::Float32Stamped angular_z_msg; + autoware_internal_debug_msgs::msg::Float32Stamped angular_z_msg; angular_z_msg.stamp = this->now(); angular_z_msg.data = static_cast(twist_msg.twist.angular.z); angular_z_pub_->publish(angular_z_msg); diff --git a/localization/autoware_pose2twist/src/pose2twist_core.hpp b/localization/autoware_pose2twist/src/pose2twist_core.hpp index ed3e542beb857..22540c9aee473 100644 --- a/localization/autoware_pose2twist/src/pose2twist_core.hpp +++ b/localization/autoware_pose2twist/src/pose2twist_core.hpp @@ -17,9 +17,9 @@ #include +#include #include #include -#include #ifdef ROS_DISTRO_GALACTIC #include @@ -44,8 +44,8 @@ class Pose2Twist : public rclcpp::Node rclcpp::Subscription::SharedPtr pose_sub_; rclcpp::Publisher::SharedPtr twist_pub_; - rclcpp::Publisher::SharedPtr linear_x_pub_; - rclcpp::Publisher::SharedPtr angular_z_pub_; + rclcpp::Publisher::SharedPtr linear_x_pub_; + rclcpp::Publisher::SharedPtr angular_z_pub_; }; } // namespace autoware::pose2twist From 4215995c02c917edf4e5995ea6ec81df66dcc5a3 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 9 Jan 2025 15:22:06 +0900 Subject: [PATCH 164/334] feat(static_centerline_generator)!: remove the package (#9855) feat(static_centerline_generator): remove the package Signed-off-by: Takayuki Murooka --- .../CHANGELOG.rst | 287 ------- .../CMakeLists.txt | 66 -- .../README.md | 83 -- .../config/common.param.yaml | 17 - .../config/nearest_search.param.yaml | 5 - .../static_centerline_generator.param.yaml | 9 - .../config/vehicle_info.param.yaml | 12 - .../launch/run_planning_server.launch.xml | 12 - .../static_centerline_generator.launch.xml | 91 -- .../media/rviz.png | Bin 183524 -> 0 bytes .../media/unsafe_footprints.png | Bin 229195 -> 0 bytes .../msg/PointsWithLaneId.msg | 2 - .../package.xml | 57 -- .../rviz/static_centerline_generator.rviz | 459 ----------- .../scripts/app.py | 178 ---- .../scripts/centerline_updater_helper.py | 207 ----- .../scripts/show_lanelet2_map_diff.py | 139 ---- .../bag_ego_trajectory_based_centerline.sh | 5 - ...ptimization_trajectory_based_centerline.sh | 3 - .../bag_ego_trajectory_based_centerline.cpp | 86 -- .../bag_ego_trajectory_based_centerline.hpp | 27 - ...timization_trajectory_based_centerline.cpp | 187 ----- ...timization_trajectory_based_centerline.hpp | 43 - .../src/main.cpp | 59 -- .../src/static_centerline_generator_node.cpp | 774 ------------------ .../src/static_centerline_generator_node.hpp | 187 ----- .../src/type_alias.hpp | 47 -- .../src/utils.cpp | 263 ------ .../src/utils.hpp | 67 -- .../srv/LoadMap.srv | 3 - .../srv/PlanPath.srv | 6 - .../srv/PlanRoute.srv | 5 - .../bag_ego_trajectory_turn-left-right.db3 | Bin 2740224 -> 0 bytes .../data/bag_ego_trajectory_turn-right.db3 | Bin 2654208 -> 0 bytes .../test/data/lanelet2_map.osm | 146 ---- .../test_static_centerline_generator.test.py | 112 --- 36 files changed, 3644 deletions(-) delete mode 100644 planning/autoware_static_centerline_generator/CHANGELOG.rst delete mode 100644 planning/autoware_static_centerline_generator/CMakeLists.txt delete mode 100644 planning/autoware_static_centerline_generator/README.md delete mode 100644 planning/autoware_static_centerline_generator/config/common.param.yaml delete mode 100644 planning/autoware_static_centerline_generator/config/nearest_search.param.yaml delete mode 100644 planning/autoware_static_centerline_generator/config/static_centerline_generator.param.yaml delete mode 100644 planning/autoware_static_centerline_generator/config/vehicle_info.param.yaml delete mode 100644 planning/autoware_static_centerline_generator/launch/run_planning_server.launch.xml delete mode 100644 planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml delete mode 100644 planning/autoware_static_centerline_generator/media/rviz.png delete mode 100644 planning/autoware_static_centerline_generator/media/unsafe_footprints.png delete mode 100644 planning/autoware_static_centerline_generator/msg/PointsWithLaneId.msg delete mode 100644 planning/autoware_static_centerline_generator/package.xml delete mode 100644 planning/autoware_static_centerline_generator/rviz/static_centerline_generator.rviz delete mode 100755 planning/autoware_static_centerline_generator/scripts/app.py delete mode 100755 planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py delete mode 100755 planning/autoware_static_centerline_generator/scripts/show_lanelet2_map_diff.py delete mode 100755 planning/autoware_static_centerline_generator/scripts/tmp/bag_ego_trajectory_based_centerline.sh delete mode 100755 planning/autoware_static_centerline_generator/scripts/tmp/optimization_trajectory_based_centerline.sh delete mode 100644 planning/autoware_static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.cpp delete mode 100644 planning/autoware_static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.hpp delete mode 100644 planning/autoware_static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp delete mode 100644 planning/autoware_static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.hpp delete mode 100644 planning/autoware_static_centerline_generator/src/main.cpp delete mode 100644 planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp delete mode 100644 planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp delete mode 100644 planning/autoware_static_centerline_generator/src/type_alias.hpp delete mode 100644 planning/autoware_static_centerline_generator/src/utils.cpp delete mode 100644 planning/autoware_static_centerline_generator/src/utils.hpp delete mode 100644 planning/autoware_static_centerline_generator/srv/LoadMap.srv delete mode 100644 planning/autoware_static_centerline_generator/srv/PlanPath.srv delete mode 100644 planning/autoware_static_centerline_generator/srv/PlanRoute.srv delete mode 100644 planning/autoware_static_centerline_generator/test/data/bag_ego_trajectory_turn-left-right.db3 delete mode 100644 planning/autoware_static_centerline_generator/test/data/bag_ego_trajectory_turn-right.db3 delete mode 100644 planning/autoware_static_centerline_generator/test/data/lanelet2_map.osm delete mode 100644 planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py diff --git a/planning/autoware_static_centerline_generator/CHANGELOG.rst b/planning/autoware_static_centerline_generator/CHANGELOG.rst deleted file mode 100644 index 0338cdc8b66bb..0000000000000 --- a/planning/autoware_static_centerline_generator/CHANGELOG.rst +++ /dev/null @@ -1,287 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package autoware_static_centerline_generator -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -0.40.0 (2024-12-12) -------------------- -* Merge branch 'main' into release-0.40.0 -* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" - This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. -* fix(static_centerline_generator): several bug fixes (`#9426 `_) - * fix: dependent packages - * feat: use steer angle, use warn for steer angle failure, calc curvature dicontinuously - * fix cppcheck - --------- -* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) -* chore(package.xml): bump version to 0.39.0 (`#9587 `_) - * chore(package.xml): bump version to 0.39.0 - * fix: fix ticket links in CHANGELOG.rst - * fix: remove unnecessary diff - --------- - Co-authored-by: Yutaka Kondo -* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) -* fix(cpplint): include what you use - planning (`#9570 `_) -* refactor(global_parameter_loader): prefix package and namespace with autoware (`#9303 `_) -* feat!: replace tier4_map_msgs with autoware_map_msgs for MapProjectorInfo (`#9392 `_) -* refactor(map_loader)!: prefix package and namespace with autoware (`#8927 `_) - * make lanelet2_map_visualization independent - * remove unused files - * remove unused package - * fix package name - * add autoware\_ prefix - * add autoware to exec name - * add autoware prefix - * removed unnecessary dependency - --------- -* 0.39.0 -* update changelog -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* fix(static_centerline_generator): map_tf_generator package name needs update (`#9383 `_) - fix map_tf_generator name in autoware_static_centerline_generator.launch -* refactor(map_loader)!: prefix package and namespace with autoware (`#8927 `_) - * make lanelet2_map_visualization independent - * remove unused files - * remove unused package - * fix package name - * add autoware\_ prefix - * add autoware to exec name - * add autoware prefix - * removed unnecessary dependency - --------- -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) - * unify package.xml version to 0.37.0 - * remove system_monitor/CHANGELOG.rst - * add changelog - * 0.38.0 - --------- -* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Masaki Baba, Ryohsuke Mitsudome, Takayuki Murooka, Yutaka Kondo, Zhanhong Yan - -0.39.0 (2024-11-25) -------------------- -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) - * unify package.xml version to 0.37.0 - * remove system_monitor/CHANGELOG.rst - * add changelog - * 0.38.0 - --------- -* Contributors: Esteve Fernandez, Yutaka Kondo - -0.38.0 (2024-11-08) -------------------- -* unify package.xml version to 0.37.0 -* refactor(osqp_interface): added autoware prefix to osqp_interface (`#8958 `_) -* refactor(autoware_interpolation): prefix package and namespace with autoware (`#8088 `_) - Co-authored-by: kosuke55 -* fix(other_planning_packages): align the parameters with launcher (`#8793 `_) - * parameters in planning/others aligned - * update json - --------- -* refactor(map_projection_loader)!: prefix package and namespace with autoware (`#8420 `_) - * add autoware\_ prefix - * add autoware\_ prefix - --------- - Co-authored-by: SakodaShintaro -* fix(autoware_static_centerline_generator): fix unusedFunction (`#8647 `_) - * fix:unusedFunction - * fix:unusedFunction - * fix:compile error - --------- -* refactor(geography_utils): prefix package and namespace with autoware (`#7790 `_) - * refactor(geography_utils): prefix package and namespace with autoware - * move headers to include/autoware/ - --------- -* fix(autoware_static_centerline_generator): fix funcArgNamesDifferent (`#8019 `_) - fix:funcArgNamesDifferent -* fix(static_centerline_generator): save_map only once (`#7770 `_) -* refactor(static_centerline_optimizer): clean up the code (`#7756 `_) -* feat: add `autoware\_` prefix to `lanelet2_extension` (`#7640 `_) -* feat(static_centerline_generator): organize AUTO/GUI/VMB modes (`#7432 `_) -* refactor(universe_utils/motion_utils)!: add autoware namespace (`#7594 `_) -* refactor(motion_utils)!: add autoware prefix and include dir (`#7539 `_) - refactor(motion_utils): add autoware prefix and include dir -* feat(autoware_universe_utils)!: rename from tier4_autoware_utils (`#7538 `_) - Co-authored-by: kosuke55 -* refactor(route_handler)!: rename to include/autoware/{package_name} (`#7530 `_) - refactor(route_handler)!: rename to include/autoware/{package_name} -* feat(map_loader): add waypoints flag (`#7480 `_) - * feat(map_loader): handle centelrine and waypoints - * update README - * fix doc - * update schema - * fix - * fix - --------- -* feat(path_optimizer): rename to include/autoware/{package_name} (`#7529 `_) -* feat(path_smoother): rename to include/autoware/{package_name} (`#7527 `_) - * feat(path_smoother): rename to include/autoware/{package_name} - * fix - --------- -* refactor(behaivor_path_planner)!: rename to include/autoware/{package_name} (`#7522 `_) - * refactor(behavior_path_planner)!: make autoware dir in include - * refactor(start_planner): make autoware include dir - * refactor(goal_planner): make autoware include dir - * sampling planner module - * fix sampling planner build - * dynamic_avoidance - * lc - * side shift - * autoware_behavior_path_static_obstacle_avoidance_module - * autoware_behavior_path_planner_common - * make behavior_path dir - * pre-commit - * fix pre-commit - * fix build - --------- -* feat(mission_planner): rename to include/autoware/{package_name} (`#7513 `_) - * feat(mission_planner): rename to include/autoware/{package_name} - * feat(mission_planner): rename to include/autoware/{package_name} - * feat(mission_planner): rename to include/autoware/{package_name} - --------- -* fix(static_centerline_generator): fix dependency (`#7442 `_) - * fix: deps - * fix: package name - * fix: package name - --------- -* refactor(route_handler): route handler add autoware prefix (`#7341 `_) - * rename route handler package - * update packages dependencies - * update include guards - * update includes - * put in autoware namespace - * fix formats - * keep header and source file name as before - --------- -* refactor(mission_planner)!: add autoware prefix and namespace (`#7414 `_) - * refactor(mission_planner)!: add autoware prefix and namespace - * fix svg - --------- -* refactor(vehicle_info_utils)!: prefix package and namespace with autoware (`#7353 `_) - * chore(autoware_vehicle_info_utils): rename header - * chore(bpp-common): vehicle info - * chore(path_optimizer): vehicle info - * chore(velocity_smoother): vehicle info - * chore(bvp-common): vehicle info - * chore(static_centerline_generator): vehicle info - * chore(obstacle_cruise_planner): vehicle info - * chore(obstacle_velocity_limiter): vehicle info - * chore(mission_planner): vehicle info - * chore(obstacle_stop_planner): vehicle info - * chore(planning_validator): vehicle info - * chore(surround_obstacle_checker): vehicle info - * chore(goal_planner): vehicle info - * chore(start_planner): vehicle info - * chore(control_performance_analysis): vehicle info - * chore(lane_departure_checker): vehicle info - * chore(predicted_path_checker): vehicle info - * chore(vehicle_cmd_gate): vehicle info - * chore(obstacle_collision_checker): vehicle info - * chore(operation_mode_transition_manager): vehicle info - * chore(mpc): vehicle info - * chore(control): vehicle info - * chore(common): vehicle info - * chore(perception): vehicle info - * chore(evaluator): vehicle info - * chore(freespace): vehicle info - * chore(planning): vehicle info - * chore(vehicle): vehicle info - * chore(simulator): vehicle info - * chore(launch): vehicle info - * chore(system): vehicle info - * chore(sensing): vehicle info - * fix(autoware_joy_controller): remove unused deps - --------- -* refactor(path_smoother)!: prefix package and namespace with autoware (`#7381 `_) - * git mv - * fix - * fix launch - * rever a part of prefix - * fix test - * fix - * fix static_centerline_optimizer - * fix - --------- -* refactor(path_optimizer, velocity_smoother)!: prefix package and namespace with autoware (`#7354 `_) - * chore(autoware_velocity_smoother): update namespace - * chore(autoware_path_optimizer): update namespace - --------- -* chore(bpp): add prefix `autoware\_` (`#7288 `_) - * chore(common): rename package - * fix(static_obstacle_avoidance): fix header - * fix(dynamic_obstacle_avoidance): fix header - * fix(side_shift): fix header - * fix(sampling_planner): fix header - * fix(start_planner): fix header - * fix(goal_planner): fix header - * fix(lane_change): fix header - * fix(external_lane_change): fix header - * fix(AbLC): fix header - * fix(bpp-node): fix header - * fix(static_centerline_generator): fix header - * fix(.pages): update link - --------- -* feat!: replace autoware_auto_msgs with autoware_msgs for planning modules (`#7246 `_) - Co-authored-by: Cynthia Liu - Co-authored-by: NorahXiong - Co-authored-by: beginningfan -* chore(autoware_velocity_smoother, autoware_path_optimizer): rename packages (`#7202 `_) - * chore(autoware_path_optimizer): rename package and namespace - * chore(autoware_static_centerline_generator): rename package and namespace - * chore: update module name - * chore(autoware_velocity_smoother): rename package and namespace - * chore(tier4_planning_launch): update module name - * chore: update module name - * fix: test - * fix: test - * fix: test - --------- -* refactor(behavior_velocity_planner)!: prefix package and namespace with autoware\_ (`#6693 `_) -* fix(autoware_static_centerline_generator): update the centerline correctly with map projector (`#6825 `_) - * fix(static_centerline_generator): fixed the bug of offset lat/lon values - * fix typo - --------- -* fix(autoware_static_centerline_generator): remove prefix from topics and node names (`#7028 `_) -* build(static_centerline_generator): prefix package and namespace with autoware\_ (`#6817 `_) - * build(static_centerline_generator): prefix package and namespace with autoware\_ - * style(pre-commit): autofix - * build: fix CMake target - * build(autoware_static_centerline_generator): more renames - * style(pre-commit): autofix - * build(autoware_static_centerline_generator): fix namespace - * fix(autoware_static_centerline_generator): fix clang-tidy issues - * style(pre-commit): autofix - * style(pre-commit): autofix - * fix(autoware_static_centerline_generator): fix clang-tidy issues - * fix(autoware_static_centerline_generator): fix build issues - * fix(autoware_static_centerline_generator): fix build issues - * style(pre-commit): autofix - * fix(autoware_static_centerline_optimizer): fix clang-tidy issues - * style(pre-commit): autofix - * build: fix build errors - * fix: remove else statements after return - * fix(autoware_static_centerline_generator): fix clang-tidy issues - * style(pre-commit): autofix - * revert changes for static_centerline_generator - * fix(autoware_static_centerline_generator): add autoware\_ prefix - * style(pre-commit): autofix - * fix(autoware_static_centerline_generator): fix filenames - * fix(autoware_static_centerline_generator): fix namespaces - * style(pre-commit): autofix - * fix: added prefix to missing strings - * refactor(autoware_static_centerline_generator): move header files to src - * refactor(autoware_static_centerline_generator): fix include paths - * style(pre-commit): autofix - * refactor(autoware_static_centerline_generator): rename base folder - * Update planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml - Co-authored-by: M. Fatih Cırıt - * build(autoware_static_centerline_generator): fix include in CMake - * build(autoware_static_centerline_generator): fix missing includes - --------- - Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> - Co-authored-by: M. Fatih Cırıt -* Contributors: Esteve Fernandez, Kosuke Takeuchi, Masaki Baba, Ryohsuke Mitsudome, Satoshi OTA, Takayuki Murooka, Yutaka Kondo, Zhe Shen, kobayu858, mkquda - -0.26.0 (2024-04-03) -------------------- diff --git a/planning/autoware_static_centerline_generator/CMakeLists.txt b/planning/autoware_static_centerline_generator/CMakeLists.txt deleted file mode 100644 index 261e8beb0022f..0000000000000 --- a/planning/autoware_static_centerline_generator/CMakeLists.txt +++ /dev/null @@ -1,66 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(autoware_static_centerline_generator) - -find_package(autoware_cmake REQUIRED) - -find_package(builtin_interfaces REQUIRED) -find_package(geometry_msgs REQUIRED) -find_package(rosidl_default_generators REQUIRED) -find_package(std_msgs REQUIRED) - -rosidl_generate_interfaces( - autoware_static_centerline_generator - "srv/LoadMap.srv" - "srv/PlanRoute.srv" - "srv/PlanPath.srv" - "msg/PointsWithLaneId.msg" - DEPENDENCIES builtin_interfaces geometry_msgs -) - -autoware_package() - -ament_auto_add_executable(main - src/main.cpp - src/static_centerline_generator_node.cpp - src/centerline_source/optimization_trajectory_based_centerline.cpp - src/centerline_source/bag_ego_trajectory_based_centerline.cpp - src/utils.cpp -) - -if(${rosidl_cmake_VERSION} VERSION_LESS 2.5.0) - rosidl_target_interfaces(main - autoware_static_centerline_generator "rosidl_typesupport_cpp") -else() - rosidl_get_typesupport_target( - cpp_typesupport_target autoware_static_centerline_generator "rosidl_typesupport_cpp") - target_link_libraries(main "${cpp_typesupport_target}") -endif() - -ament_auto_package( - INSTALL_TO_SHARE - launch - config - rviz -) - -target_include_directories(main PRIVATE - ${CMAKE_CURRENT_SOURCE_DIR}/src -) - -if(BUILD_TESTING) - add_launch_test( - test/test_static_centerline_generator.test.py - TIMEOUT "30" - ) - install(DIRECTORY - test/data/ - DESTINATION share/${PROJECT_NAME}/test/data/ - ) -endif() - -install(PROGRAMS - scripts/app.py - scripts/centerline_updater_helper.py - scripts/show_lanelet2_map_diff.py - DESTINATION lib/${PROJECT_NAME} -) diff --git a/planning/autoware_static_centerline_generator/README.md b/planning/autoware_static_centerline_generator/README.md deleted file mode 100644 index 426d5487cf0cb..0000000000000 --- a/planning/autoware_static_centerline_generator/README.md +++ /dev/null @@ -1,83 +0,0 @@ -# Static Centerline Generator - -## Purpose - -This package statically calculates the centerline satisfying path footprints inside the drivable area. - -On narrow-road driving, the default centerline, which is the middle line between lanelets' right and left boundaries, often causes path footprints outside the drivable area. -To make path footprints inside the drivable area, we use online path shape optimization by [the autoware_path_optimizer package](https://github.com/autowarefoundation/autoware.universe/tree/main/planning/autoware_path_optimizer/). - -Instead of online path shape optimization, we introduce static centerline optimization. -With this static centerline optimization, we have following advantages. - -- We can see the optimized centerline shape in advance. - - With the default autoware, path shape is not determined until the vehicle drives there. - - This enables offline path shape evaluation. -- We do not have to calculate a heavy and sometimes unstable path optimization since the path footprints are already inside the drivable area. - -## Use cases - -There are two interfaces to communicate with the centerline optimizer. - -### Vector Map Builder Interface - -Note: This function of Vector Map Builder has not been released. Please wait for a while. -Currently there is no documentation about Vector Map Builder's operation for this function. - -The optimized centerline can be generated from Vector Map Builder's operation. - -We can run - -- path planning server -- http server to connect path planning server and Vector Map Builder - -with the following command by designating `` - -```sh -ros2 launch autoware_static_centerline_generator run_planning_server.launch.xml vehicle_model:= -``` - -FYI, port ID of the http server is 4010 by default. - -### Command Line Interface - -The optimized centerline can be generated from the command line interface by designating - -- `` -- `` (not mandatory) -- `` -- `` -- `` - -```sh -ros2 launch autoware_static_centerline_generator static_centerline_generator.launch.xml run_backgrond:=false lanelet2_input_file_path:= lanelet2_output_file_path:= start_lanelet_id:= end_lanelet_id:= vehicle_model:= -``` - -The default output map path containing the optimized centerline locates `/tmp/lanelet2_map.osm`. -If you want to change the output map path, you can remap the path by designating ``. - -## Visualization - -When launching the path planning server, rviz is launched as well as follows. -![rviz](./media/rviz.png) - -- The yellow footprints are the original ones from the osm map file. - - FYI: Footprints are generated based on the centerline and vehicle size. -- The red footprints are the optimized ones. -- The gray area is the drivable area. -- You can see that the red footprints are inside the drivable area although the yellow ones are outside. - -### Unsafe footprints - -Sometimes the optimized centerline footprints are close to the lanes' boundaries. -We can check how close they are with `unsafe footprints` marker as follows. - -Footprints' color depends on its distance to the boundaries, and text expresses its distance. - -![rviz](./media/unsafe_footprints.png) - -By default, footprints' color is - -- when the distance is less than 0.1 [m] : red -- when the distance is less than 0.2 [m] : green -- when the distance is less than 0.3 [m] : blue diff --git a/planning/autoware_static_centerline_generator/config/common.param.yaml b/planning/autoware_static_centerline_generator/config/common.param.yaml deleted file mode 100644 index 6c547c8cd83dc..0000000000000 --- a/planning/autoware_static_centerline_generator/config/common.param.yaml +++ /dev/null @@ -1,17 +0,0 @@ -/**: - ros__parameters: - # constraints param for normal driving - max_vel: 11.1 # max velocity limit [m/s] - - normal: - min_acc: -1.0 # min deceleration [m/ss] - max_acc: 1.0 # max acceleration [m/ss] - min_jerk: -1.0 # min jerk [m/sss] - max_jerk: 1.0 # max jerk [m/sss] - - # constraints to be observed - limit: - min_acc: -2.5 # min deceleration limit [m/ss] - max_acc: 1.0 # max acceleration limit [m/ss] - min_jerk: -1.5 # min jerk limit [m/sss] - max_jerk: 1.5 # max jerk limit [m/sss] diff --git a/planning/autoware_static_centerline_generator/config/nearest_search.param.yaml b/planning/autoware_static_centerline_generator/config/nearest_search.param.yaml deleted file mode 100644 index eb6709764ce3e..0000000000000 --- a/planning/autoware_static_centerline_generator/config/nearest_search.param.yaml +++ /dev/null @@ -1,5 +0,0 @@ -/**: - ros__parameters: - # ego - ego_nearest_dist_threshold: 3.0 # [m] - ego_nearest_yaw_threshold: 1.046 # [rad] = 60 [deg] diff --git a/planning/autoware_static_centerline_generator/config/static_centerline_generator.param.yaml b/planning/autoware_static_centerline_generator/config/static_centerline_generator.param.yaml deleted file mode 100644 index 060590803428a..0000000000000 --- a/planning/autoware_static_centerline_generator/config/static_centerline_generator.param.yaml +++ /dev/null @@ -1,9 +0,0 @@ -/**: - ros__parameters: - marker_color: ["FF0000", "FF5A00", "FFFF00"] - marker_color_dist_thresh : [0.1, 0.2, 0.3] - output_trajectory_interval: 1.0 - - validation: - dist_threshold_to_road_border: 0.0 - max_steer_angle_margin: 0.0 # [rad] NOTE: Positive value makes max steer angle threshold to decrease. diff --git a/planning/autoware_static_centerline_generator/config/vehicle_info.param.yaml b/planning/autoware_static_centerline_generator/config/vehicle_info.param.yaml deleted file mode 100644 index 8941b92b4e78e..0000000000000 --- a/planning/autoware_static_centerline_generator/config/vehicle_info.param.yaml +++ /dev/null @@ -1,12 +0,0 @@ -/**: - ros__parameters: - wheel_radius: 0.39 - wheel_width: 0.42 - wheel_base: 2.74 # between front wheel center and rear wheel center - wheel_tread: 1.63 # between left wheel center and right wheel center - front_overhang: 1.0 # between front wheel center and vehicle front - rear_overhang: 1.03 # between rear wheel center and vehicle rear - 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/planning/autoware_static_centerline_generator/launch/run_planning_server.launch.xml b/planning/autoware_static_centerline_generator/launch/run_planning_server.launch.xml deleted file mode 100644 index cb368ca336316..0000000000000 --- a/planning/autoware_static_centerline_generator/launch/run_planning_server.launch.xml +++ /dev/null @@ -1,12 +0,0 @@ - - - - - - - - - - - - diff --git a/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml b/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml deleted file mode 100644 index 0590009ab378c..0000000000000 --- a/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml +++ /dev/null @@ -1,91 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/planning/autoware_static_centerline_generator/media/rviz.png b/planning/autoware_static_centerline_generator/media/rviz.png deleted file mode 100644 index e76ede78294f02c154a02ccbc133491531cb886c..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 183524 zcmcG$RajhIvo6{|a0^awg1fsD2*DjfLInVT_Xhwz@FGA%TFh%TupwVC zPU6yP2nYzP+lpHN02x49LQKs)<8t5b-@ z&N&(adC*7k|NWt)Zan7<_}@?e)qYG(5GJdNJ4)H-@?8MuzlSB4Cc<6L);+H5=P-yf zRW!T)L>^3ETt7eaC^KFq#_8Zz-GuNT>v;8kI!=z}W>ls+w08rk^!=5)bK1$1}j3l1r!_Ey%(v9ooc36Qv09MGa~y)OM;)IzK&) zkq*X5D=Pu9@{)8ugRd-&V;=;mn>~%*pxR5sMHqo0V!hGp?Jky= zd#$(ow+6`%@Z8Jl*9L9YYHX_XWfkP_y!QWElpJaE@~4zA00XtU7w4oYo*V6RG;P^N zSAvTM`(8EeGgjIEbaB6`{Q={JeWM-%O5Db#qCT^v2rN$y&Wm0}O4hh*_h{h zHqg)zecj&&_En#GnDCbefW!cVPUiRa$IGi-`1fcxlZXmK5s<;_jnKUHmq)Uo z<9LU+H_UhX*1tbbXRbZ65kuZ)Cs_;$EA-z$#grm&}8W`@eKrl{+s z&)3RJ(tAGSNy=O^#4)M+)F2%LAJ?auv~JGwWFpH!=u&DpIPNY)YD|2I26hb9|1@Nd z+U`^QEl}4RhX?|g(STFP3#T5#=I1=pn)FioyEv`j7^`OGVY|#nF*0$rBSc!r3;7GK zWIS|y;c%0)o$1l(eD3goL;WPRVAmCIwJn~|>iropns*p3#ANkW`M`VO#twt+Iv7jm z_OZkfq#w=SeWyhj_yF>NhMAqjclkIfbe2N}9T>*M9m02Lf6qZNek{#{_j;m|>-Mb9 zMh`D`PLn%JUO?2xvU~*MNoFP&e3R==Z45!cHWTWH;>D*?pT;?v*}Q-l`)3B)I?*Ko z_FsY_a@Q9pXEu4j-?#T~;X+;$l6%SkxzLTsqUW}ybixzMS{YReQXP-j?Wt02CwQ2l zXdhSC=K+ez`rucl*^=d&(l?(DLVS)Jte$h?XD@Ifx+JzO>jD74cp&|gJOSWd-Heju zIc@bakScVXN?=jj!soE<_O{yfyh3wjt&g+%M(8?zJI92!DPsIJXMwhK-+12B4goj^ zWV$*11$B~r(b=R zXd<*rRmycyE-!0i{cS=cRh-P(hg&DU7B577kPhqFgS)PobY9c{_Cuy^oFU7!QMo%eqPjx6Djj3lf2n2ov@yN zuf>=TMbG$Spa1i8;L5n3r>U)`e4H}&Td0q*6ls`pS0DAcZ?9&o8hLOJeUVV>kcC}? zz~@Afa05GIJ53imO4LaR#%!V(q_RWQ_MVwvhSqy&NaU5+ z9M8K=W=#}3sk>bo1pO$PZ=ZTk6@){$iTSyC@n56SA$o_Fd8$Pg*6p-g`LLhRQ3P>| z5kZ2!j8}3eNlXl_@~Sv9O5Vaz@d7kZqHa3`fSd=N^>FL!cP(b3U(CispXJqtut{Fs z0{?NbYCITiOafk393QU0c9Kcx^_YyPTm8Fi$xogMMMR#H#wpx(t83DcJGdqXah_&TUQax5GD;bme-_!QHho`YHj@7` zoP(5ej@V3B2XgNj^%NX|h^s}C?~-UXRhy(d9CT?06;ObZnT)+TLE%f)YuG!u7{^-*To~m9=zGx=qXMQ57PIZ49JxS9-bKPC@G_yDH>{H06**{?-LK zmgO74*3m?;s6U{vEOL)$G?dJ|R1j4)IlMM~N#=BzNoVC?O=4k5H3_+OVX9sEEvnx- zjbtt1oF0@k$Qf*!XHrEk!woP>;T8IzB27Dt2tVRq-}c@RqQrOcDgM{ zIfl=+Ie;^jeT5|9CBTM8423*JPGJsO*^;g2y2b}-1mj<0bXl>7BE&j z&#X)yB%2h{L1pSj5HX@JNWZ)qXXmCen4?q3aJX4eCZ-odUk-(YjoVW9i8+r}NSIk6 z5MW^CG=@5dSVzgk)Ez)o#9P`$!nHmuslkplBQSHDQg$l+!HLkReZ(n!@HSq@KRf-B zwW6Vsrd`@e3RLg*J6Gz)Q|_aLuy=;c3T?!P1l)usVEjG9Q8Im8)v}>j_p^wlh#4qF zgIZ!B;dS)AmH2+U-AwzlY`v=LjXMA!M~wxD$ky%5oH34VRWF{Hc-{=Y@t@Ceq9LS4 z5Z>ruc6p?1ry~!FWtWi3C>+f14unboVbwr%6_L!Dx(d$!MJO`zA|qCBAePPv&~`r| z8u3v)QS`9+d`2hoW8Zo!F%x^kH|or^t91LxTu5TNRJ_66jGqnEr zkz%G5^^IfAw8!R^e8kR=pBOtnTg_Jm)BOzp%08;&;6kfShLRerNR^#A+w6wESt^y^ z64bOhWH`R}77)7=+h?U}Wc!%NkUqp+Z-SSsM$S+{UAUVY9|-;Q@PxAdl$Tj9js=<{#FTQiC+OCrc0K zjg_bHbUj(FmyJ34S=(S6DnGB z+2NhEUF~L>L`_B7NGA$YKzdnCDB{f?qhIMiyc_@c_PLZco)eSRlFhQ5+>+{EPx1%| z964t-Y-qkJzA?{VVtS=^+rQjfPY?~Y6mj33-YuTcMFvjyhlznYyWF3V5dmwL6qdO^Th7(oZ=BtE>H%YDo!%^o=pX%Fzb;*5ZLBCn*`$CslB*?fBsyOi53NKk ztgJqo0M(r7k1We8i$^~Ir0{6C0?2fziQ7d=ZD@*csZqXB;K0HFP@)$LsGwld(yUm! ze8JJxrMb%YWe$M0vK0WaKsX*o=;y1qG_u2wXkyhHpwIE$1 zScT6it0}7hrN&k!Us=rl-76^nF@&yHD^CuVc8$u4iJ}GvRd~I=%611zRh&co~nc^1Xo@xDgv|OfI_3^b$`kbEuUzsKL`T8{a?G zoC7mzxF0T9^ds=OE7^*57pVm(O6-Wo@YS~KZx*qRq>_%({!yb?MyPS~bkiGQ1p++3LvMAfCi9-*<*EDHm25@xI1MAG>f%Q1mW@Bqv9VI z(bwtMu`=lznB=Y6$%qct>^G}Qr;a8Zf$cle*81vwpC@!hxMs=SmBHsUv7&L5(on2w zYU-vh!00*VuKbVK7m_vtn|JZQEcUT;UgUDz1xWxOKYV$+Kp2kHsN<#@ijdcHkhZVS z>z1czPs64pBok2XRP*s1#F`x)jYDTU+vWPvxgc)zE+WEy6Ov=A*!2Z};6tXGQx# zSD|M!&ROVsh>bX&vGU70-rfEpLWZ?JC20KkizK&WEttjYS% z)+~Ors&icW#a)>oDn)8N5j_5Z#!9j0&9-i=1|Fl>RPe;cXkI1m3M5Vo=G@sH$E9Ogm1(e^s~|8m5f=$(}~GXBXMEmgS33Fh~oATH9Sw z-DZj~Q2EETaUU%Q5WB|qhsWCSzEC$G&i#0x^g<25bG>neMg$aUX$4arYI9nd^gYB% zyM4fH=OroMi;Gn0z>C97&;>a$Hq%%R9-9)6@@x< zl;aG)6y%#$(FtEEAgMe&?aZ?gKq=qOKQd0x)lvD>lV|ebqwdVidko1y_T24w-P`phGBfE9{QB1%KZ;OpJ&n+4x=o@!`r!B%Rr;EdGle!> z|4BR{gTDtcwcaC=-ShUDOnUnAdjSzm-1Rj%5>L8RXYu`x{HV(pZI+JtMyqkOoP|SY zn}PyH_> zbnKK)lK8r%@rbK6kUA}WrF4phw&H52N=|%36 zOQu{vAF?)@GaqYyc1ZvxlhfNpvYZSy)+5lux%za_Hyaa8~^zGCrm9ger2 z?_9zlTM$vJAYZfp%+x%6EBBz=xG{-5>&p(k1b!V^Kj+G_M-k9-fq$C z{mU$yu>PQe)O8g`8S7~_&NIP9HV7o_`xZ;%^x2eIaX&PpJ#Nh*Hn@pe{pI19c)OA3 z;_Nl_lW?~Ka7@V8K@RH6q|#FpcDSw_y4vxde%jjP>wh%LBzNansY%qt6uP(Iy@}zh z{*nKyr_~3MH!GzQ30>qJkwIiyyi7DdqD)OelXZ$^ayCk94uiSqu7`u-Wy%b8G5Z|}8lB8V#v2N5p>b5bsFi|; z!?mzQ^p`Zp8Je0NP25s`$S(EZxjy>}+JeNiI0|pqj>o*r+s5+)PIV zEP6d4|0!;)>nvJ2QktPCUV7B|RKWIk4|3Lp?4p)bUSj9AgfRQt>880i_*YHyIY%qF zwUnldyK3j4c*5t9t?Oq9oKpX!0=(p`y1L6?$j7qXGRu@_wI-mOZWX;46hO&jqDGgX0w$X`2oZ2oQjT1;wz5eyY*9t5D$fl zj2dT(WOy};eLCNB_K-@yb&@SPjmi4&*7oYI=*j)^lcO@nS>rqv533KhtR_#5cYbeR zUT&$J32vp)NfxS&Q@xHmM|aE^-EPbJB3A+rL}eDe{)qQmE|&YffiD>SIos@3Uk?g8 z>ylY~oIpC*G0^NZ4=pT91{AL`}?~)#H;=#%JaOIv&hv-ZPqagZIX1OL@VBfe?r(cE%*4-c#m)wa8<_!Vu=FQy??ue~KTd2_NGy)6zqsl&i6%6y zPcb913!r*fIOczbn4~XM!{?hOjMXKGv)rP=uzH3;UBSV)F#bx@T(xf_0hLA0!wl(a zbrdC{PUZhNw{$y*qR8ww*{n4eD~2YkV2glyhLuW7Q;sO6{}l8WB&rP;P+|RU+j`7$ zR#zLx`5T2I=q{2>$w`3zX{EuY%TMg|@y{SEB_P#7;1cfDhHjn|!i}oyz-2qIs&>BE zM^wRMd0dNzcv9&Tz@)aPLo^ zjQ&OytjIs}PTO?9^fB^;w2^CL)m@yTdxK?Tgcs}NN(ilN;}+uos0kKdJg=)dZjjg= zHX#aRE%YyZZ;okBqEu%>%(q)?Y-sc8n9o#8Y2ez?6wre(BO)VJ&QT^L#=i`Q7h8D? ze$ee?que34UQ=&=?D>Zu&g^kMog2=QOcd;VC959@9rCqcMWGOq|4FZ%9rt{7UVC?9 zH(!O(Lt3q2D!#5{9oew(p{T#MzB%C`k*|zXquea7)Ys+F-C9~@KA!d1Rd=>@bWnR; zI#^o!i*MtuBm(*EZpNrGGPBaB68+=KaSoHj>UW0@z`HsgZn{sLuV?EAXGmj_G^=1c+c~selD!pC{)3BdI|C`2SDxdvzL$KuNZ!)*R%9tQOX6578v`2Q()Q)UE6lWFfX+-Z2-exYAlKvyH|sY3ma z$&~IM&Y=$To{_beyk4(LKKPG$IPJf5f?L(p;WS>YzAQD8!~J{SG7=>CoZ*&rA^9aE zUfacPEY>^5W5_{2VK1jB+d1LTW#S8ggM<4@jeDol`7EbLh@Gk*DP@VQ7{khSwVWWD zBtjLowlvXacYQaL7K!xl{FD`@Y-ypIHVbcULFUt9Hv$ubKvCL2!|q}+6u>`cB>(db z$4o2g0O{J)<}bz(1(fzSx78p!^msd+6i|WApMU4Rf~?XUReyYhi)QK=ac=`!0N(c_ zaEr41y7E#xQwZIR&r+(!iJ0VU3Ee(*zdFFtb^gM9o@=yT$@7TRIBP@A=-PkC&V-$e z&Oq3OLHGlY+dXt%@SQ;+;fQq2G9*q3G?G}g1!&a-gBFS z6B&F>wgEo3Rft$%-;V%5s;4V3yEIwdvs%z~d#vbZ*&+x{+nYhr`#B)yxoA>w{GyTk z5Hw!zmHg|b=`AZ&lGfMKQaV+IIr~XNX`~OJ_V;-ZT_i1L<#F>!Rcax|;i1J`uDVn# zk%|95w1;kF+(OyYG9c>e!?tnAc38qilUqESqkJLUs|#cO^F3kYb1kBO(cR4#U9*hV zL@xIr4CU#iZ^GG=ID5r@o-X^<^O_N3p)S@H&;Xm}^R6D)wD0};T^(;n+Hc=faRL5m zwvo)lD<#kk4lEuk?)Opfma0U2q;Ib$>`qJJLL94>0MP^{X>>szI3eI>VSB_-R-FpR zxAmqC;?A{O1dFwbyf{dL7km|O29oW|`g}_W1wi;6F7|DFqTG7WwG413;6-@QkkPpR zP3^)1wcIq%_CNNgH-ai!-l*m2Dha<$G!+z~EQFJaC32J3^I67`gGL}-9z$5{x^;?` zF6u)*QgogpDbqEp)(3!SjkAq*%*s`_=~*KnXRmkJg~3hF7b6`wG^fe}N=!-mwjL*c zIA1>a^Vu?$@=!8J(jnn9+$wQkoj<JzeKAucRA{<=uLdM9*(F==}S9%qMY)7oC ze&Z8&cGP19SWvz9(^cathEUQ-00;@H(K|eNA5+8JZK<7L%;+o9RF=OvJ%tt%fOfXt zxa2mtfbq;?dpxY{=oxR1U|T*QpRVPrEt}(_xO<}TJ5tQb3xzrmkVA`<)8iIH@h_1p zMX5RhfKUN|cuG2e0hh&EtOuhYoXs*-Ay|B_ZmeWoW4 zq@@Qh=OfIR6(n#+3;%lwzB1};fbl6FR{ycV0~V^=`}qG|3n10@z@L7X$?g1H!{qy> z_UAH5gMg~^0t?mqYa>tP)>$9>$0vmev%RZ8LWT7Es_MzH=id znj=__Cy$gGB+SqCXQAkpRbRq_)@7gfyWM0?+P_<>9KtR`~lLhPDK_ zMLhNIPC;d`419d8MaH84ZdHTF&|z-=KN@Sl#aA5R|9fQ!^J2UZdh}m?bFF^D{LdL8 z^JuB?P|?vR$H&Kqhf5dyt#EvNd|+S#Lr@79oXP&xoBZ~MJR&kOQHxnnu%o7CYG5Gb z??bR%8nyKGXfg{wKYtVfSJ~0`e=p&XrdP$Wb!~0U^X?eq!{39Oa;_X;@UY3s(o$bv z-`xKkUisb?l#xLM7fAjQp^PhSbjq|7nBwaBP zlX*VF(*f(tJmmkzR}9)yI~Ah+vAv?ygoz>*5T`pN346 z6!|soD(5)R<#pFEbrGBKu?^}3gFHxyn3@kjOh7PV!Y)ZVw7vDurKFqtswV9F@^G~~ zm=+EFdaIBv-0848pjxaj|IhB#;Dt~WTOQdJ-q_vr1~>h%-i>#}=HXAC27B47>AqjP zz${Qepm&?RBii9Yr8W#eQrQ&Uq;k34?c!iE8%DI-_Z3pzQ^q$zK<$Tin39sx{r*M> zC{oA-R_k?=;;3crZ*LnK8`uBX?rF4Mg#Hr%i)v zs1f-Z7GN;sDGH5aXKk$wIZ}`MdVYqjE#K$58VYI4a&rDTa5r=jpAqtkD8#!nC_mdK zj$|FYgcX|@Kn@?}eA>#kxu17t*=k?-O~Uw&%jtc4L&nZ(dI*r<b3f zP>hX-TuA@HT+Z=4uqH@B-o}b{1}LGFl10b5b@*mNLHyrpQff=3=-?FZ_#H%a7NOUV zOVj0L%q=s1mRPD!?g8$1l-T{H|`=Q`A0v z#Rr)BBja~*ipE8Z1}O<5qEzHl%n~%L{ho)uM}`nUhVWAqB&R+?AuHRGxEX;Tp{XLH zam7uQ7$wY+Do33_=S_r#r8?eTxyx<4@*#-eqm4lu^sM?l437anvrbEmIAO8lC5hOh1YeaDNxlBNv0{w zgUzj`I3ZEY*Yznxnpj=E3$2Xc*h=SdGsh3~^xNmu+`eeD5O#tUPLzri|B!v(sH?76 zPE4B3M^CMeN&{u#E+*7ePt{6)_(s3#c**dtKBC#>tzBq$;4J2$D}niwpNUeh-D;j` zCrx2XKh^weRSmmU4hc@?h$M3%eXGyL3DcLaXMV*d$gt*b6px_INYP^E+t`exNCeC#g(z)+7HzxEpu$*`ASQiM_%3 zsgUz-FVe5o_cdP$>q;S{u)KMCFJdn5`?8FXotgFym=%=D>ttEsEbW=@R^q`weYN9D zLe-FR!iR0bmGnbP>ytx5ZEl-&zlDh{%5Y>Ky-ROR3SC=UVj*MMg9R8oB4kxh1X;AV z8>(~9{nqM}riaowLKOC+?2WqtU0UonNelkFOTy(1keA)&3q+5)tV)Ri{yQ-T$>?A^ z1G5}+gY!A7tr2a@#8NW$H&GE;A6r{n-KOwPDV}%vW-ROeq0TT{F&250hS#=M65byM zJwb>~MV`ApYr!m0V24FDO^5Qqqb)loZ?n|wX8%FmZr{#54fS4b50;MN}F~Ec%N8k(YqWWELm(?V*~dBDl5{{wHeJbKTcw zxZ?K|GOM~hC`1SnFFUjs-ioKE2e;XW68)9XS4e>tJUx8QeQR=N_=3kX@X3(>|y1^V12;}eivW?WpCl` zW4KWX*;1e9`_UvOEQAkVLQq=WF0#VIrGNaWxh%w>_}XAOYqrv08HvY&hJu3q7O}hN zQra^&*O8%}{^rYVV2aEI0I(nRwZV|K;C@Pl9x0=z)}}>yy=fMfx}&amvd=H3OMRiH z{QEuh0r3D+uf_n1^&0S-32U4DT72=T+I!PwF)?s_NitjCdxkq#$aUKZyU?UHR*)n{ z#rNt06BqaX@#X*u2F_-^jf;VyT(epavKw}G_B1x*f#C!ihzE#_j9fy(hDEV{S6#&8 zHiQCvv}y~%A*515O7yVRaO)PBfGVFnwXymBvhQJ0_0x>&v>5o>XzMgq%p$|AGr0i* ze}V#t6f`cNVJm5?McZlcWyt=3YQe6iEHQ}bENZmiO8CU`r4Gm}(4I>UK4@ zzstI~pDx$gR>t;s&F+lhaZ!N zO&QL;uGVK-O?RN8Z&Fu%+RUvX^Baz*IyyRn$S;#CXSVcNxlre=CCe_EMc>uQDV?jP ze|^#6Y^|b=t69Ip{VE)b1~ie$&=xns8R}qu@w)x@AG@>{QYf6M|L*0aY92_soa(Jf z?9=J5T!j(q&753d!l)CT^xd%ATX*pf>^6%&2%ATMsB%AiN$}ZQ9!70rG=7f7oqpUVl51 zU(DmsOq?_BUx6Mk)!CE0lBMg92zcj9DqwnW+;ZNr-(|$#SuNf=@!Kb4aBnzm_AQnx zuH>s7?c@$>PtH+ex2W@@p6OUIWDQ|z`kO|Y$OP!=0#TN zb^$4_MC+MW2UsjrEGN(?LV!vW1U^wnMHBHkN<3^`Zug?0scfRtqpho;1d>*-}3%JT8?oh(*^!C-UtRHGY^Ha9s1y?2mm*1KiXhAs}WUTpa~U zsFDWcdV#ii4vsmV8fVg)L%$pNh8i9=cDE}?T_aBF024&$l2CZ}0tE9!e>d z=k0KQ?C+fac&W&hc-Jj=`P@pQ_0M0b$7mKI`!A0-!RV33#wwNVQ7_}Y6C+K^>2KX0 zhaUlI3%j=Yt9;r&7{?ONmn!@^I^wbLl+)4oWleSK1>uYOInu@u2 zyQSon#Ky*U`8?aLGz>2;YV!VU>Fo50ArWe_S)PF)n7SCAzK&88XUTT<XQmdJdw0A37uo2aagBrijeoVU{kLZ09Bg%L9A#yMt9tipib>DZ zy}>YUC+Hg-@HtaN4>+E?On27>M_AOB26SUd*d{J$u_Q8|CobY(O%|v&<~-mj^5M$F zxaa;zqNSxJwj}I_4<)r>lD)v_lcS>i(l+nM>${Uh9(#j@rrP<4X<7S)XI>&vP z@F=w+z7ormBf>O3_j_&U(}xR!cjlE(1Mn+$Vq(Q3ew{x4#q~I$;~-wwlseD-2L)!_ z0iyP#T{OugN74yPHT#h}BZylyR7Ah=4ejqHqtKOd9*>f1Z#Pp?B{Zf$Zq9wq>(bzp zf0O0WW54sS{@K(No%+5%6F(*Ys?Dc`Ul(NqPx6a}&N@7p$Bd_*gNu{3bkq0PkF z#+#-*U0w33$MM?VVt z9*3)HOQi$=hLDMDR*V&)>B>d6gU4JJ<`>MGS8w%RbPdmVoz$g;pogrGBdRJa^l@5$ z=V24EBzoOk!rm#T!{}rYp}v$n*z!E?FO~Te=A)Bn&rH^LWg0_DZDL4>(4{m;FwLM+ zi8$wH7nY{h=FR^?>Zbs4Pp~Vprh04pB2Qek+}xa%n=ZQyT@S-0$H29|aq!9{Kg|ox zllO807SCpRABX`5{j3`j_KPFXQSt%S%hVad;W3Gbh|oxdU-pI*%*N9Yv#00gIC*#u ze(+jZSrMU0-Tv(A>e_pHnJYo4{P}DTyUEwu$7QrWl7QHA;}2Yvug=TQ?**f?lI7n| zzU;Q{zWiC$8@VMHJfi5EhJz7V~mh1Na z{DkRA&rFpwGcef7{SpcZ1NV-P`8{tfL`1sdziaRv@w0xr^@WWQsVdnq~Wubo*XvKBJF*WkhFYyRy4@I5)Ilh83j_{XoNQeIY5N z!{#VyGuR#2OH$$D%jz}ZC%tbz-7_V?^2-~pX#p2K*>KKxIy`nLrP=&7%-E?}a0g2L zVP8II{Ux>p%z_4%S?}g4dev{%7eXdd>oC9CX!a)CMU%frXV36BpC3)=MRJn^;sKG= z^ltObi#X1|`no&$XnENl*)CwS8?Lvx^n|YH=>jRwARu}xKgd4YN=XY3^lL?n|K%`& zN7L*mE356c?l2U#p*l%Wi^F>(y{Npp8_Db8BHk`Z4v;jv_WX&DPs@J6y;RNg)EtsW zfJ94>Fsibm0>ZPTWM`8S5oP@TT~J=0o{{l#IGvx7k&%*u55cOPUSJXtUqM>hZ=fcN z>tckGHR~Ix3fZID8?mL6c6jp!_Ja2JpM-U`(@df7LQ%3|ZFk_0gLO&b)Nq@T4#%sT zlJedjMW)s7y6z;zH`fL+znPHlC6W9`qCGO_ynE}x%H-N^SM>I3>i=Cdu-FIe{hd+O^`}GpE z_I;NUDqR%wuc*IZPXQ+}^IMLf~XCVbM*K zUkKO+QgKLNJ`39tsP+IT-M&n>KW$VVo_k}JQnYdSKBfBC!b^9*XLWQm4^B#|;$uV1 zJeM8-&U|dS0is($okH_1+1bJ-XhJymTTsChzGZ#6$tpF z==luvnoC_&Hf&zt@#r);-=0i7dGdX1(|8L|dO23GD;)ukCbu4vAc~^sQF!0%G%93ih4QEOuKjCoIkH5d z?IZumWTpK;a{XS|3k=$r=nD3dlHk z9-a_b#q(~?tE0sV@2_l8MXx?gn;TxVFAv$KtLD9l2Q19v%`M!fJ$ki-!x0wDiLldt zF{#e;-sj8a+lm3)s3nuw0-qeptNJAe4{TmKZ{CYsfC81X5N;<}u_|NjYEqh5Q||QP zppR6Dv_V49^xcY{Bm7)&128A>nO>$sl`QzQ3ruQX=!PIoV+|EbMxZ7yw9&W zr^T3*7z80^)I?4PcD-KTyU-)w+OPtKAwjqt9J#yS*)`sz!>quH17qiFC}*_CEoTBW zKzy-pX35{!H17*wbZKH*PCsT>_)oF2osJHa`t9YZ{F&GdwdW!SSEEy@Ii(;ooNCK3 zJw0PCBp9#yUTXvi+0%LK(U6eRI4x%&CcNXnE;M3($YTMA`Gn0zhsOt74ij9cfoG6(N}G+(I;IH6Y&r_63VuK z^O4cj-a_x^oVvgZ3GSm6g`4FgC#ueaF&k@R;HKLXYrDBycA|WSJjlc>?kkaT>1G_$d>*K;gV9X4y3;xc{*pjhu0Z+$dcdL(Uc%hi2)+m_GJ zj#U-&V#Hq^n;Em+epCgzKX*s+=WD__m)RR`Z%zBZNmU`D+TN`#g)Qm8 ztq%MZFRvIIKK*6G${sgCBR>jF2x6acl^aIH{+C!0SO0!^vg_D_-xg_3bFdYl=jDdws4ws zsJ~M2U_gjxnMidWv3nfp`pU_aFvZQSGCDkl;nmIZQ1{Fui$(Ee_UkM9b?E5^>-YDg zaE@S~WXAJt6U#-M z>(J?#jXKtB-J{Y_!xWa(`C!5t4JVES-TL;;`3FwUeSCZ^uSt*XI`8+jqEE>%ftf{B z1gkv@BZU{)Hv)s1g0Ek5atpOE-*lOjDS+V$A0j6iD29)iG#Pw0P`73U-?7 z%_rgfcXoCl>?if$;Q3PRZci{W=d5+oV>E~?#L&b@!o<{cR8QQs7zrR+QY$a_Yn%|B z__VUr>UinTOy2Y#G20Z<{9Uz9FE^%6k2_R!cf%Mxf@W(P;Sbd6Qb(NQOz#`Z0vXeO za+bFCXNU8hg`3)7BB?4k=S3xZ_TIsJYzvl9S<$y0aj?9ENB=ABn` z%MlX_7R;LT-YB&9yM1w3l%C?#-}!#b9408F zM~^u!zO-q(K(YiJ3g_9H zpro6wlGlWex<<@?S0ilK8Uw@fqV6VhAq0n~dXr!Nl&s#&P#gEUx5RZj?sJ0O+@iRt ztD~ieuC;hJ#81cn(!|=0KOo=MU~6H#YVwdhn--MWPN1*Xy;eMvJn}NcL6f&SrY+P^ zTG<*ESzd_?l}D3bX6pc37yy=rRSt(GjYrDELe}dCiM*$P_rBO2KCjJn5Tv-YHT4I6 z6u*{M$bP&%n$@TTUOm3l!Oxuhj$*|6U}#~%>$vw#S63Gh>mC~)|JiRdsHzL?-KTa> zYQW?x@auM^haTzy3_yu;`!tot0YmGW+~V$fy?LWBsjU3kqpI^8y8u_9`OH8=L@2^& zSdxm8(#OzVDF6M@!sIGoDu%@GR({8?LjIbE*TU)Q$7xwANVLSdS;BMJJt;wHe z0}BAetDPiMJhU-NBG$zh>T9#>LTcy#*Z%@AG09ATI5}ACaj_*6$MrS(D=I4~K7U3+ zLc+wvB;dAjKboNu5D+jdM?^wm=irEpikhFFhaj+Ta&mLi)3tSVc_Sc6;}rB|Cx60SUWQi8 z$`SZ?Km0x<0RW(l|8X~g8@z?6_zVlVPhRYP6P&I%arOYwTm_mwWf=sU`?kEDxX0y?&>{7IBDXVl_sxN?0a_p{OBn~Q5g&I?*6fW^*Tw_RUvBvyk0%%R93mJ;35 zvaDDC^k&$plL~5z=Elawj>qnwnwmEIjhn1uGQr`|ib`qQsd|g0K7YMJ?tFLGa`owv zvQP#9xD?TU*}Sf}3rsheRg2A`rBiC_EtYV*yki@+-rnziPPZUT!?!N~2zb$ywxmze zAlmkwXR1V*NtiA1#B#kD`hF=Ta3Hd(px;fGgJX+ls3OGigWF>2&*rAzVwG->h?A2O zB&W>WCaR!Hs~M$ zyPvGVnX|RO@V8kyl#q;Bwoj|*nH@rd{z(rus(4$po(vCcpRt}_Vm_J8ShSza z<)X4MqcmTF=%#1=o+H8gJJ+e@3PO<#O3KADHaf6Ip%RC6cMlkn-VtSMw0~K27dPF+ zzFT%Xr@}}o|CTu^eF5fpIt^Ar)@Ea1hmI*3pn*;jM};q z_ZRi4*lOzL

H0Rc+!DI-UJgk`9eR6;>G*mQu@+j+HgEb1bSWc=cCBUbRK0W$B(G zAMFQa2eL)(`tk;mXs9JqT%IeBc5I7DSZ=J!|1ZkkGAybuY9AgzK}iYe&_TMC?nb4% zOS*ID76m~{x)~4wY3T+frMqJ!2N+=Jj{h-!&-3B=^1kch;=1OXIWzn0v-jHfUiZD$ zfL#ios9nFuO&|RES`n^ZYjHM*HKsPkRGUNnRP8Ouo&_svU;?PWP{B`$0=HuBs9TOF&9 zu74zjdNbSz8DqTJB&$pL)_RnSvc$evHSY^}eCOd)AEPw=UfS)hH@dKSvS=K z)NhW9UE>AH5uyc-lO`J(q8L{gZCZDOuRHvEGv`0UYI7^wMBi*u$hY;in3cqnLp$H0 z8$)SR6wvFc^#TZ+0`G1?;;Iu_BECLndxMr$EiElll9GpqhXVrxdNsC*P$=@(FXz?n zD1efYD^vL9rdV21+P40dS@CxBn_K=t0}3cbPp?QIRp6OU1W;dK+-ohrUut8? zSj6wVK1wmG)V2&2^!?kut<42I1PfU(?7=?FD>3k+!EVJj%h#o)&|{#xZ1FQ4fb;FQ z_bUB3IZ5kpc13Ao`$cZCV%>=xs?@e;=UEN?WiLWP@QA9l(gt$I?h+k|n3D`QsJ4XZ zwr8qu39W=$FUwn#^c<5i(rd*X(aJe7!p6C3c-5Y*pHFRK!m|sBF|gOmCAu+`(%njX zPm8hie%4C?ajmt3p3vQVJ|dyqN38x>Li&iqcd9%uCY5jEp4b})ch*0n@9F&X<4s*g z4{_S_`U1onr_uG& z#*?CR#b1T5=d<)n$)rPr9VHso6TMO&c{BPI@9y%ww&;xQu*Gl4Oy-Lx?Mf{Az10t> ze8?ioTXwyG!g*w@SaM*5Xg76kz+`X!=v0>F^0w;Wr5lai_Mz9bVqAG(6K6@YaeY}E zBKRBgb-M*FfJ(Q?(^EE4QuGw40$r}wMqb}OqHs8A|7y=3^s^G1wjvY)$(PC-X68{l zgelR5)4tU2v#q`N4n>^Fvlj<+uL)`F8(9}cDcEy56-~XOjiTXU>RKT|E0q+Us;VUI z_jFPX3S#CG&G}i6|LWz#0E9BB0{xF%WQOfzYVp_!V_6B?H*D)hpC3Ktc$-T1G!BJg z<(cLH@AQ)cJ}k`k(SNaNNesxJ`#jc;S0JTTkF zJ78(0YVOk(boFDTflTX=glFME;GhY-S(z1egiuuCd6&{l&FK}7VO#Cfda3W;ctV-l z6&E09PY4pZV7eaG4WK@;5KQGCPoFg(=+3^ilzAY61v&9NbCfQ4))FK4i+6J>6LN=) z(gqW7ajKcNn^ivJpkn&?1@zj;=3&gWPfUpi!pNZtZF;Zy?kSzfmYIg+)A4~Z{?p~b zI$5R{u~0}cBDZa1WCULJ$QA z4@lBbs`Pnz(8L~pCj;{5$2Mv|xoa=Go1*cO)_3~FDBldwPxxA^-&{zYp|lK;W^Ydp ze-N&4y*crGXjABdH0lYXChc%syEd74>q4syeHe9p%(UG#c&8-N3zm&TebSKEWuR6l zz($%Ra>?s`Fg=#5Y^pvMZ)(&kAD1>6S+vQ^^7?{_KV@#b%(#u+&)|6Fd}tgG7Vt5` zmxkQy*dtU^grWoYMv#8TxE67H^`$yt*ksv72K2tDQLwWu;^zipq`3%al=k`nlw~NS ztAIY>K}4^mj$S&wSo86w{8$0ssLkZ_ryLTG9OkM4^oIH1LA}TB96+Ojp78RXc1KYF z(FbAw%j(WoH#|~|xH36qZPN*YqY3uN%o^BE5C0rxwRMe%~thANe zHr2e_=%Fi=IR*sB)!6Umap=2dZ3=r`RCBEO&QFXl8u|}scZr(u)g4~cw@o$h*p;;@ zUte3pE71ypUHvFYXB+0tr`y2OJ)x39L=@V&uM@fnBkdE+pB@p6zd%1^Wr%9_TDF&N zm^7Je^+}>_ON$-#5!9u=F-7$*D_Q(1v+otVTiV1vfBpFY^Wo~1x8LRawFL-l!P#ld z2^aole?7BEFI+udJ@uMh!p}$2Z9-`Dps;VJt;1Yz_NCbMW~)#v2XZN(?7-Gi;F=m! zRNw{&;7Xj(GJ}`%KRHtinz?RLu8arFVQ&ANV8L5nfOOU;=JSl z=mlMGypFmG(8?8}VxoO+u7_p^#ZESBSgWQZW6LB7Hhgs%`C}15$epv>YVLd>EiKM( zZsR=KX`<3fybmf-g}WFP8F0ib7{UPV+iENr2sqR#vCni_|25iE4uv&Sr1mqs&RXTq z@{+N9nIFdyto(>3VR^doljtL212WMKY3XKRI#G7s?ez|pyP?}%mHY^Oo}BO9i;L$w zjTQya=76iqQiUJma0Vrl=5fTvPl{^Nv$jT)A0pjAh<|l-yk{AHYR`Yo*u!O<8?zvc zk8ig_*6b3HxoXx1%Qreoif9NpTzHqv;b?#5y_Gn(tFKKwy|Yl-H+z5FBc#pG#bI@# ztB%~m$tr#LOiPkNzrTm!%rKDbVt*>WQ#htx3D(eh>i)%GD1?&ZMAvCOp(A&IfhKRw zTiAHAs^xB}h|^;_@5nYe`gVs&=-SD8?n4Y_r1aRd~AjhxP6aTi}p!H&P)Gg_T+Ms{{bAXu4|m9?ES0{qvnweLNM zuoLCsQM7;aMuL>B(-1y+L5371BBuNmEma`%b%b`%znoc5a#`!k^1^vSx>7f;0m4 zO!qltW8mo|ty)O@Htxa0FOBi5IB#!zV3)44E-}NbWYoWOr)yl!?sK%jOL5!?b=__q zI-a-ecBD0G6pvTm1#`WijFlJG$Z1J_m8*4Qxzl<{-&F`3rj4p~cPTXJtzECwc_lRN z_n|0!TWMxrKlh4DuwJ`(Z#3X~>S`8FOQ^x*43%MPt2#M?Wl$<%PR?^-VR&g*)Rs*; zIOT<_H_bnYL<=yQ;q_3(s3Wgwfr}O{n_kVXk$Y$TGA?i8cP?Jzr^&ru-}*_Vsr}$S zx#4$Bj*fOPv~1Vf3Rr>x+u}Wm3w}M^sZ$f^Rm#k>*ha>G*X%YjwQAR-Idqmd?nKo5 z;>&5*fubSB>AWSs?P@UYMuM}$t~D%;S4&gBeB(-)W(_<5C+IBLq1GC|$h37JUX<^@ z6=JpF-RMF03{G#HKnm|>=l47>fJvRkkBhMtu)JIz-7BUo5%fE1{q!=H<-=v;w7ZkQ z`o}!wMLByVjz{So_n|e1G&3*UCsXJ=j{=-594=Y)VSEr7?U=@Zaq4r{TSTC{bWxa; zn0q-=r?B!W<$0YkeJv9dN%wgKhm!vr5W8v+(QENJc`6mUcDhMI?c6=`#c#)W(N3du zF?%p9@vK;RF3?_rg-NP&EfDaXQ?*w?^ggwQzC3*#fkPKm&=&{LHj9s|sSjJ-izaQ_ zct`V+YEpWa8+)w8yk#t@P#I>jDCb7HiebT3sshj_=&f(7nvod3Lb|$|RNi{q=7q-Z zncPzSOR=`lmXjH)dJN2Mb#L3BX=4;@JF;C4J*=XrTaO9gWtDAaV82zWZ}5DV#zTJX zTp>wi6+a9+X>FtjkM+iCwz;aH&SILsW&Hg++RD2SwO;6bP$eh zLx+vR4t-gqSz$!O9#LnI;%Up5(*1eGp#oU1Rs4@H*I~lY+3vxXRb*wE-7TqgGOP#B zq~+<4-Ic&IPxm95rd^Yz!2Fz5&$4oFDu@_~YvV+q7Yp3g>v%jy&Ax0{`@{{|c4lye zeOOVWRaH2D*5t$)bM4DZTO3$4YV&D&HFcFYpt`y?7S7>&N2b2D5J{~_aqgDo(eC!M zwxudP$tp}IV%uE?1HD1Bbope_@<$L33&u=kXR!wJiPvR@D075CkCV;@g+LqRCar7` zqr5)N_Hs0RH1&ga#9E|!FGk zURBjmseWCNc6piOrw;(_&`@9hJ|tv)u_T2MGeo=00FVgxm;QK*hM}gWhK@(AAZ<5Q z0tj|(=W9!eu~PH&r1L{}_)sPg>z#+>7hFaXjPRu&+f?FY?<#pb?c*kRYEf3O7ERZl(E1 zwnTn@zPA$rA>r!A#wn1%(477la)CZ_Ec%Wf{AGAQ5ttW~UsZE|OHru=HKqZvWCDTk za3FW4U13*?!Fa{!mwx)Jcf=)WOLIjtU1oZ3|Fv*}=7N(zJo$3^pm@I`y>a^Dw$kuw zEAV!-Trc)|865<&mOlku0^(~UBO}ZZFe3EwHU`Za?CRmc`{G4!69UK_iOUj=w*(rx z3u}Xhp`xNzs}UvW>DM`y>Q-%J3VHgR?i3>QfHX7VEI0-Zc|t};v)k6#;d(y;fhZ^_ zU`gx)v;ZF46SAzt#Ux>HZ=*sDPV8LZjGuCj3Xnv>m?&34dN-_(`m1J2loDe2BbI|| zUl0`}o*H+9Wx>HwZqMhcff={n98IqN?1SnqtakIPO1CY4QBXaWX^>s}kGb4(E zPt^C+9tc5;UGKlEsX5tOY_i~-4ZOSQc@7kSqml-X0(1wnX3^Ttj^FwIvV1bT`|jMy zY?W1XbTo%?D^WxjAWxq-QGe_Ae;NYT2&_tzVNbSdLXl3`Wkey0b!xlO@<(fP1%Zs6 zu1|ZDk=wab0U0vlQ(Z3QBkoGVUCZD zU7jI1;(NoaPj_Z1c$Hvz9SyY0r&CEtS1^60U|!f0B&J_@+2F(%<>_q3nllK zfXDb%4E2o{?q;Qw2!a>R6gL|matC3MrFKT`lxcqGi z{FauM@7+T|;sxAPC=RBk1VCRqIdKpr)0VlNGhz<%uwVwHwQzrjE=c2wfvj5KuUnKc03y<8|Bag)H|Kw? z4T@Wj2l)Uhe?Y7;>MXCVJ>39-6HCZ~R4y&d&Cjo{j)coid;T{M9L*4b5t0KFz=!Ej?W!8e-wYB0^_py*rdgx*mi|H4CK;R z++Ge=od?kwxw#$pY;h&WraEs*?@TS)@F59e-`XigWKk*V)xDwfp>g`H8F;6M^6%?@ z$*(`!sAOe%^gtRM`}!F{1eyB^>!SyqrY|@M3Z1Y*jFV80!mZ#jhKKpP8OBXQn3%N| z8xh~`*vWV&+?t<(h#B7;Y3ydl1MAq=UvRT0UALYejUlBrC?k4R@LA$WWlJ+{C!MBh z{rk!Dx0`h}hQ{(M#fxHCA7+>IV`dZLK_iV?WE10klp;>^QDvu0 z(Q4uSUlm5<0o$7WVJ6s!Q>bCxS11uE0i=uKwlK9=G@%jOkm~>1c}EN*3_jRY9g!le zj!#0<<`84!D`u$uyMFZ_GiLOSW+jdg8)$f{hUXJNB5M^DG!%%5D^+X@=%?R={cNdl zO1Gp44(1)!H#X}c<@2|gacT+ho`jr~Q?aORcigaO?KJK)YO(W{Y1COcI|s4RHXXvR z+oYh)A7%TV`9rRJ*nF^ewk+s|TG2!=*Mgx_hLH+CpGftmDf&c{uGppTJN^14hSPn^ z(~|g5O1kJ(VDvex*XJqXrG~G+>B-?>0rF+u!#-WD-TjUd>d6;T+(APY_eTnWA*1|p z<~(KB*P$Da))Y)qu7ww()a0#w6oQErl9!jq>j@~1K%l%hK#~v>qikyWS%JR4;;pWw z<^Ezi;Wp2RrRK@1sR)7TopV{1KH5nd3lKpEq8}l|h)X?SDXOihVRNw{;bZNuWGzN8 zgR)7(BO_T$$_~j;*ocpG!>e?jZHRp=;8{d7)5+C`(tijP^*^3_Q`h~ua!*rOkWyuoZ3BYz+9a90-{68*r(=lyVlN`^CKLF-#mauB8= zE{dDh3M)Z)r|G4&oHaf$lNjEyi-Q!U3E;LK!SS&iX8e_Xjq&mdpJFSNTYPvjj>9r0 zJrAX&Kg-on)K5Pqm@G!x#&Oyo)OHN}`^@{#<;_gBgtOt}YkDd)`Plwwd1Yf?6&l6t zG#AJu+|l&*{TLD!!2EStU%tI1T6ql{G38RcZr}Myz0CLoHOK>asOV)p>O;o(vV*LR zwGjr*Y5Ysgc1;N^d_*n>z$tuyH~DSW5?bhrVL2$-D(jTufx;NaJ!qdB&SHq$vt-=o zJ&R9{Lc=@u`0RFJ-Q_Nt1#y7`7dSw0E_AWqE!Q`?@Hn_d+m!4^}sHW5XI$x5)-+M+EUw7nH?n*^kumF$SQ zPp0YKZ2ufC&*1i&SiyQ2Rt5Tq;g0UGHs9%|qC7Psj!#nFYK%`ZOim_;amomvfA%3& z@K5J{tQbt^Lp0tCD(`A3KuChJxqniNTdfc2-rewrv(F4r*!uNlmZlFq)8%$p&xhW; z=pO0LUHnGY5BDhEcSGJH4u@+MTLQ1hjC+@qpx&Ms!-TQh7r6z@1x`LS2VeKzAaw>M znElS4s~0x3H65;uj--=tyb|*9)$%zzCJoPvfPH6@C&4Qscefw*el`N?0^L#PGVoH2 z6^sqYhGtQh#6Gn%x8Br**={^LGVzyX?X%5C`21NXxF1tfmmvs1m?%9ia(M(VxIun- z%As6Mjg5`Ush^jV9334SM3V@-kyE9729|2aG)<{`d2nSkgnybCgkxye_la92 z*R*=~LfC6??&12x7BAGt>SVjM^)pnZV!%YlhbHHCcJQ<99b(jzP-E&sDxN?uq1_@Z?a&NGuuOU1Ba* z(D&qvXF*v)o{qI209Dpe4^7}BRbVGl?sRI;$WZdOqGErnRUrQCg=Bc_L|=ne)hO0n z-B-snhaGMx@zry;{+t@sUb(lidFnTB<1eSYwIjtdF05gPi?K}Lh$15?D_k49E`r!B zUwD9#GGF<;SC?HQtd6iX=Ee-sxb-S7p`>#}dVAA>UCpV)7&#C6U=}D^KAx*f7aI0D z@sZ0iEO4q>X}}!&%c*;lGWm{$#{TL(Pzay{HONzYft}myxy9OFq`?dj+-yX^=Hjt8cYzo*U5C-K!duA1dj!&ytF z+&7BKyr-~1bNS`vfro3o0F32QxDAZ`?y>-E8gQ_&t5ryUH|e`J^H#*8%gf6${W_&- zP4O2Yfa7cx2OOuZ?RJG(kL|?Q7Z!a9z#hhG5&G$qGaw`cpkl4{s3bVny5e=zzHB*l zkBj~FWGM@~uKPues=z=Mii)3RiO#|9eBFGl1EA*^tg8Uja&O;d zo&t7o&|8<6t{+^uWfk%CFV=#gxdQwh!`^ji1T3JQmWj2 zrG}>PpcL2C)U>s=O>K`GT<)@sOWw+JmFy5dzvzjsy>HBh52`LQ?fNLa_Ul(RFu{Kt zW-2{I{76{D*V1b@t&n(IwU~y*x!}4d5M=!Tm`2u&A3%D_%1#>tsdF45VPS<6Ha}XG zjH?UZPUGpH-l+UM`SU5jh9c_yy^7x+PY>{TPmJsTx)k7en%Z-W>N0r%P_OdmsTKBu zk3cHu>x~bd2I11t(fJGC@&EY*ahr~KUCVr4&#&cbwqw{3@eYy>YirQY*iT{C*Vk@_ z=-(N@VDQfFuDjuVqE|q=*{J)&KNotBI^#qnY98oj!M$w!(K7u zn`_`}(wb6+g-D&WCGNZx8V&E?cw?-lH>D_V8_?M)94G%;Dc_xSxehQDHJ(1Ku$mgs zhtR7Xg=lLkD?83Y1S(ag15~;eMJnJs<9JxY`=dgaGrC@b4TYm=K!(>J6MQT4AcqkE z4jRm2S!rmXzUXGu&6$}Qj?II^j(hUzvN80$S(ACvYr2MWx#3ZHg=@g!sM_H${zJsK zDfit0>`pKm*SsLxmBRd$!pZ#*qR>dIR{>Oe#=}Dc;>xg@xh~INB_eq0N3clcIk7^A z7@1@-%$k!gr;|n6HOwC*fO`JFEiVHYrf3Ngz~Ji32but+s|8z*0G*wQ8AJEkO103J zy;azi&33peIo4%M+KpLQON8T>z?~cc$6THT^Id?(R6^s`s_zdzIyjZZ=D5kt-{)R}!ik|KVm8@RLw< zM!Q4I?A4VO%mj%#Owqh7?{{I2A`#_wT{wb@xE@73>*jTzkAgX~Tu3F8-5qnAl7^ZnUheik zyI7VWCVxVS{Np5RvEa=N0X@5yWndE>Z}2d@?{m zP%+b#-^CYYXh``5oAw!aczaAXvv{qh;`+Mrr0(SUUBD^Nuv2H1uwMX1+xPhVo8)WX zHwZW5Sz~{F?3rtmB`b@@w>@E9LZ?p9X;rt)z|y9>18Es)g$8me)IeCk@lGmQgizI0 z&smy_MAjAc(9OlP$h)B4cnXR@#!x1tz(J2w6x80plQ}bNZJ3?1#dgMfR_p^V(&*-$ z)eh`kn&<86^3|5)u^-$J7Z0$uM`H@tvM|4arDe9JQm<7Wi`Co3K|F7kS-MC%ZXp_`%7qgOH}i+rF);y;>pjl;8rX5LdiT~7mmcujU2=aGS{Rq_Jx>v zA9|4(hl?5Cv)ox*91(@1OlR8lpTWi)`cVQc0yFB8(ro03zPhNxn1T;ac*9GkAX{??DJ$Ox_oD}!gb46er94I5Am6(pI0QHf3_g1AKS?Szf|dH! znno^cPZRAl2j1aKcgKdkelz|g+r8gan(e05Wx#n$*t2(5LOzWE|HV4Xbcx~o{-Ots z%wo|8gr$@0@zrX3+}lJ_FwAmtjC{hFJ8<}}_KfkBbfn8keyP6CgYY!X2mwvs%iEEO zfJ_3|ON-5UzEitx)!00rlOrMV|9XcGt;dD3rvli6U0^5N3yNdBBh+V3#HAM2iEoV_ zvK6g}nmyWd6T-UDtEI<-^-X8U1`zb{maE5xWxXm;wm0)|(>hwNZ!6{A^e-lsSjL zAelA|u^K4WtolW5&=Tukww^#?a;DJ@MF09s>_SaQ!CAvKDKS~!tscWun6P9d)e8B+ zwXVrE(==JS6QjQdICgEPw=dy@no7I>1!?5ifsvf2Z1mJ#V%(|*T~jfafDg?%A>v8vecu=S$NP`3BLCG=_Zsuwt?%6IYbAzaCDSVQc44^+TA z3Q`2OJ=8tyZxIPt6EvP|DT_T^o}?&LGGvIhL$2%fcjcC4K0V4YUa7Z7%j$~4I4;eq z^c-qFlBE&(BuATT(6(Xb+ZU^Bjx~#im6YlhvQ%e!L;;6x z$4##upDAVfv$?pJXAS!?`e@W4W>u6MWQ2#y@{5jlVV1p_Wxt!Z}qHx*CYY9A>EXOSkSEMz*I-`Exw&aLvejSF3eV2`c>C9N z@7)8`Dco{~XDeZ0oX{*WH#L~X39o&B#?}XHAqPr5eMYZUH7TdAq5J(5F$cB0Dog&E zx9oQog9CXB6*uWawN#U9Qp}1zCxHfBC-&*a*Ayb80*(4+7#$N~SWQVBS8$m@np35t zUOhAw7n_p_*sPOnD!ri|k9$|Tpjfmu{ZqAu`pGZQWJSZ(k?E&5Hm2)khTDE#X~EmD z`|fwSuihjd^!;+8;wmf66ub)?t zt@?}hgG>h|G_nG7B^NSPB%G=nq=L%ZiwkV&z~BL34t!pJEKb7huhlP?3a1k0@tmdw zA3E%8&+FtmkU`pD!x?tZ#mu`-ZP4Idmfu3vfNhmWsX-)}DQnX;={53`j2Zl*W`5*{ z``FUEOTu?a*jOn^Hak1xkel$-7M3dM&V=H<@shrwMF05#xm;IXcfIJPTDJQ5$MWWj zcQI|y$W-2fS5;r#UczRY)pniiamc{2@J+ItA!Xdu<~;w+we4WMt^_;o6P=W+mDvd1 z5Nv&-#HXB|Zgv-KyF&DCMUKa+y`c*oIASGDR2@1~2hdup>r)W`XH!}e%$^V?@YCQ0zXb51Z7U0f@S3Uq+Ie zn3~1`q)U9St6kNvx%G#RIMup|>aKCH^q=dRc574LhlZlVfP~oNl`br{sgoK&ndtyj zj#}vp<@jF73dEO7|Axz)m;T{sBKiRo92KH(qEE#ih5%vdeIAQuRv*YnAExfJ>3 zA(uD(Fz4I?ZIH+Bcf2T=1PRh{tq*im?Ro4at+QA|+Wvip9w9aL-s)<+Cxy{Z%8J@4 zB@tVt!rs!))#To2)`X_kL8kJ)D93pP$yUIoGFJ@;$-HD-DMI7!W%S6KA$-!c4 zQKp@8<2!t}^rgDm&|yVyyWOw4%BV@hwhU~Kjqe}5z$m~rvf;OZ#~6VPr~h??fT@Px z&5Vx2-l#&BY|2-VoDk3hU7wOrH(U5lZ=B}epO&EEQFg)?BV$CW zESJ*AqXPHz^*f^ffOkSoBp*(CK})^gWm)}O<3+z!TcAumv*^X`7A=WwUhm`f!KlR>wvb=NyhtvyTKMqn{9iV9pK4^U2+)8(X1rGOZ3X=q6c9fR6} z-dus%uQK?B_80Gd)Z`>rr|C!(HamR^1cEGOwyB2dVE%yQP!fjo_Yn}~c!`LV-V#Q* z-$bHRW6Beu5)pdeA9?!psWDW-sj1Tcy7qgJphF;{^~v2-p*H-&xB6y_f81@yDG)i+ z>JjiJnLIVT&_@qS@lJU`toG#lSMKLA6`t+gYRc2R0B9&;P6zb)mwQE zh7D2qki(%uu2K3-xWl=PN^M>}2vs8|0^3(Ql09%Z1$exFB0Upk zV>UZ@c1!yvafHcY9t!-MMA@t>qMrd;x9_uGe)~ll_T|LQ-3C<}2SHc>qT*YeOWrl# zC#Z4VZEaTI$Z+e%MU+?4hhgL|60fo9ySP9+`^-I-t74}JlyusvGH{<8S`2=K=MGG? zJa=>CPS5jhHT+{(iYt%cz1!BC%~>uCVo%Gn7$ncCWZ99{1N&kDdGmt1B|o99qfM<} z!uD5D`+ygx-fe1#u^eQsTI^+rysl85$m zMRTg`?k9zLWre}T7F%}q=N!tJPqH}sWbQgLBV`aaglSyUQ%?1#E~tYovwZm-XUl_H zyQ$;tB^o8=ze!XetC_%>8({maNldLlhP{Dm;q~?P0A;F>B`kon6ds29x(3XI;!m<@ z&GWeS=+DmUVo1hu###AYMcAzirX{rZEH%*#YT0d?q&exNxtjkdPcH4wSfbovdit3- zs;{MFl+S#9&~Y45A>Bz@M|su%TI>b>g-^P)7NWsz_avuEc#?U&!)+-C#FC+RcNey zxOJm&-xJSQ5Q3Co=277={n3?`LNsCp9lu^h_{=^2Q1~yF(Fd?v;P_rQ!}}mVFpGcp z<$I7`{9P}7q8#wkPZ>^J4RWpPV^i-Z-eW1Vhf-!V9Ud1ol_PnJr`$dbdy*%$9|;c= zcKE5OU1mv~CJL4K9Q1ms_w{I(^(wUJH?~EX{Qm*(5NN8TIm||N^9W8dg(SyIw8zKSes&_h$T+XUVW2u0GUUv1z~mpSyXE^nFFU_J{etEQj&LvglZ3rjICW2TosP7#_?Z+^PY;c*Yjvm;|f_1Y*mD3GlMGA7eAtwr7u58@-w;jn)yYT*<{zRgzk`Mj_ zLq?*TC3ObJt$3cYP|o_jZ`Cm_OR!?*`oKeF>R@UZq<7rx>ro@W#CKQ6!XzL%^t{uB zQu&#iN4dV}@p>IQP{CB$y@)3+MpEugY)9IGCF7Vv2 zv=|Xy$Pd|8$Gg@&B*Xk8K@WX*`<_R=Lr6g-f%MhezjqG;^$7z@w+vhP>|3k^(PADq zdzJad(?lz6Tit0)XNUeZA?;2E?6jL|zs|r+%j&~MF&{U8?cg%$MvOdoyhVs#k-wov zzp*p4SZ63SeTqkk+~dl1G9I7pASY`PA*!O*qXg z9lM=l(|vf!{hJVF@>u$$7F2*LRm}Y4D~n-(^|rsmz&BiKUeno*@${q;{!>u^YCI%v)-aCsq}XyB^m%{KzcP z0V8e$uW!r;ss%*SWb(K!yEhVT1I_GyJ_;9pHN5E=;QDioZC8pxo8&7?EY`rlxJL=5 z-YqwC;&k#{Q*BDM*-I5HDX^^&WHLqjZNyb|R<6^ksH;P=?&_@pm4Ks%N>7c8>)RaJ z`z+H#Q$Ett>y>r(>naXA-Gdco`9S6JWrl`t8Q$w@gH3`IoCXV3BcDwtO}}i74s{=aS*Vq@_i zKTgz7zdy~c>};1kSduL zlQc0h<3{Pr{`vD~`*zWO+Y}_x_qU>r($@|$@`jUI8 z&Iu|QL;v~9muG;kCnzYWeQwKY%*X)vVV#BV&cX2nI0u*h5Y*=#}6C}`Bm)R-t0o`)Dx zUt7<*_a9Ld)XnR(By8Fl=9m70d5KB47-E`YVadrX3bRZ>Bkz0gWf(vX+Da5aZZr|m z7ZdbSwZa6s$;$D=iGh+cuFx>Az9)SucLPVPvF2TQic`evKtdF>6hqYIZe|M2GtCY2 z+P&yQ;`57(sFCFE2XX(#m-$0Hyfc7mE5KLQ=B7T>WCR9nh8mVI0{FeF&PrB5*j3ug z0*i`>7#Du0#hmEcAWRnz722Q(eG0zZZ(+Xc)h= zOYizViaoUb76E6DF&w_LwGx+3@OJy^-}FsYyZoMZYpvhH8P=(heP3D ziNygolEG(S)pr8Ra0X2?!VWEr`y4{fTdEmZEy_q}0Cce>?R}VUqxZz8i=I8m#D1_$0ToT)>GGV1hbKKipb|=Bqn%p!#|2A6t(Z87!Kmvz<;WwW(gCnfpN;gHS?M&e4hR&k{!3bUe|5uq2Z&roGz4yT69+Rtk9@cg+L_6Mf9qpzedmJ>Y zvnm~j-?FJM7?n{9o9<#MRZ0ED+o1i}e>=5?_I)c5TmPLOP~KF(%2Kg)Faa2pId4c` ze&<9*p?&lmH3|P4_SKeHNZhJGRxi_A%Ri7fJ`P zV|M*9EYB?}=3k^kyzmzSQGDIL4WyO)tqTCi7(m$?y<$O0a(MuyJXDtoOl?M@&Lh^2 zuzLd6W?^fXN@Z)hygeu*($6Z9)r`j%M_6{DT7gGrBj`iaQgtGlpT4-9DNPNZ?Kb2* zkrNHPY&7Buq(K|Ad*M@gHh(c_TSv+1Yp0U{?!j&NO2KE;j~sBce)d~j7an_7j<@Cn zhJCH9F;lQF=`S?>yy680PgR=U*NXl0DdTSCpJN5(JtThmehjAric-x1Raat8wB^UB z23pGe7`wy#rzR`@!559gR7`de^~AIs1qIb-c}$#-nZcs!L+kvgmsBku_o#Z#5N zqKG88H-Yz^>t(lZ-QGe|>xeS4s^#NJ=NGjWeLNjT;uoDRDZ&3X_n5fA1R&D)mQe$# za3AWuS2;RPT^d9wH6=AsP}@M9M=Dqh9h9nk@BGQh%|Clzi_IVLpjO12s1OXPL!vj_ z-OgX4Mcscjo<3x4cHjt^s@FrPw$)J2u*_5)#EC^K+ssM8#G!En=E$=_trGPDaGl6? zUe{Wvn!%gD-W33gtVtGthRNF42&H;siwoa{k|DW2oJ2Svo-#Qub$;hDYLYig|Am3} zl8&(XD8)1}j-5`jRUED4^ss1ICDmA`?rUi!|5vrRWTGA!&+=x2Yl*S(3-@lScH-)d z9PH38isP4E%uOBXpXIzux4Y04lCtDmO(TCPM#8;4Z#vNzm=_D z@K^BEjtw3DM`~sVwRd#*`}w&Uc99(Z@%))(#UMt46hAa^27u}0QHF+xS?ETul7{wb zIHUVCc=SJ4NHa)XeaJzQl3K8<^SJujMuWMWqsG(Wg-uUnHgTx5v_iXounEo1Ba zXI!AU2fgL(9)o&30$>St?uz1Rdh_w&!A|LwS}yG<@5lA^$_Rl=-aXoB51UEToi+yS z{Cga@WcAE~QmpQ7H2YWI9n1318-X93{B6IufJH%$1y~dsYZ9bVNSostZq+5k07&h!-XD?X?vJEuA{=k!d_fho^HLW60@WKcH^qHXZ zmmGfeDeuDv*1;(i9kI25mp`wdooq?3Ed6G*;SM&LM*#%cbb$JvK`CS8ODgflzpDo* zhyW9XJE)9E545XRep}nL9(JzH@%hNnM$3q^GPfZA#?=XF5M_~4AoT8CIS;h1UH{Gw zD}II@;r<*`&=A&BP4_u z{?Mo>5B z>zuBxt{}hTxWj<#HYMeJSnSSib3|e>2=1L^;b3p?yzy=WkXY0Ay6Whp{MWZ5(&0w$ z0a3FjP@wR4r#L@(hsubH$rc2x!g6_>^z<(QEeV(PiEOJAOw^rPQCe137AQ=Gf`SrK zqt1v0v%RAo6VfpDaPq zQBgd6eAC}(flt<8PLQMPanU8K)?iM2{S2t&fciGbVwTToNm@o`eN?u4_d^t4PyUOz zfOiOVf#$ZC`yX@X9j}r3!8H|&BJJG|lX0J@xm?d^=2UWD%nHChhMZ^qd1OHZp(LEI zN=j=QUKLENX{qW(HKVv;ZE=aeh}8yB{af829Lf7H3NDrGPXYI3ig-tdGuoY z%}&QX8RniexhOra+55cDnR`C%jP}zgcP_>ZMk>N}!e?fU=BDdho8*G8?>ZmIp=L3h zlqY>$P2Ryu4!b9HW4qnR__x zD0X7$G#)6t{6Y;G_G;Y;QOS#$tfA+V*)gGF>B-5PjeoaPK|9SCn}U=n-86YqYPc22#X330_*pm zF8+uMEaz$#>#jS0uvpJ?o)i1*v-|A5-ty2&sPoUQ4rDcnPW|`KTG3y-2zqn*Zwr(A zRX?7a>el(0W|UJbYw+{I{X-}2u}WbEUbbUmVw=%M+5=H|e&6>Q1m&`@hXEPm)}ohMwu)5x`!`>4tNdxG6C$L9lz*ff=P0p9 zd;+NpIK(nwV$H_wRa)XAjE2O|aliBvsaY#zC;P$O_*Wbr=&!0}N53nq_4Zo~V}C0| z!)34-%gFXjQ2t|;U=D5pb^AK6pHHAG@$)Ce3O5~g9I`CU%am<;Efbs2sU=Lj^a(qcB(t>gqfExZb3Fs%Dy^F;lEebH z%_)su>hIPw>qYwA{<1on75DWe##6u`m!%Aq5Ym{T-wQoTq}H`N>lh11`IWb&sFe&! z8)9=F_2s^P9l$8x*22~?K)$gu?h&K@6Ntg6AALD%0H#-d;gf)wZpcqr9c3Gn1R;Xk zEw*-5ac_UjaktqrL|5J7BP{ID)L=el&y@N?a66ao5%s%@5ZRiDqr2w0*0P`czF>Xw zQ|eRw7Oi*-!!;s?$N4x$;zqx)lB9hQs*m@q z)aGYT>2cwg(VSp1xBs7nhA72atuMa_o~}S*u0`Hk#LYT7d#a|}4BciReypR%m0cl7 z=IOTJxME2BsTme4b)8&o_S@&^FE1WTN3a+gm|5NF>3ie;CC(_#H_TLg^LjP&B_D(M zKLm52PuS7*RuKKalnA=-tG(n+g>{XyrgUMDIC`FkN7oHb%&1lEcgJWllUrGa;K*ga zHZyabZN`?3F-=BCfC*?& z`TfV#0oHy*?Sfh|X3x9n5WFYf>MxN->KlmQ1a<|@VO3D%0Y$;`0HY7USp8LI%{kD$Py{Ad+6oAfXy^T zCE|W{qa2Snhnw`5huSNy;Yk&N#2nEwk=E=$`vW0OOamAE@G}eW%O=U9EGbou_(}6p zgWYf+PtS7}5}3y%+1~T_uxb6}W=5;&;F>)(s|}?pQ8Dr1!KFYM+WtoxcsMxyu&0+3 zL|abi&u*SS(JtF`Z5}7}{Z{WM^{Q&~Rq|#&gojy(dH)S{W*OOIw!iY!{RBrWV_&5w z>kpR;GN*K2{QdOe9s#H86ioq5cUKyrRS=DrE%Vf)-A8@u(?gCy7ei3I1`gpo6cIR? z=e)|t#WgfBQ7bYjMwhn1hy2r3O@(9@NT@~Jy{!=&wVPvEGS}ety!7xS^(mR)ecGt) zTK8Xxj0N2uazjDpWO($tt@*wA=dFyyw?K)T zn>QaTTqi3&Zam7rb*@!X3$D2G=cv^pw$=~hR}U>TcKaqTtS+sGT@ z?5NM))Cy2(N6R&~mm6W6tk=B4xlcWs8YP_IS3?m?9NSfNr>LZ^w7`1a>B}|TZRe25 zH77P%h0f!KvwJdC&8GGn8!zrTEiFFHjHy;X8=6@y!zaMTZ3)h1Z`^6pEO>k%yERog z{FtpMm!s%QdS?2|h-epKYO#4#CIlVZ)7gNZM6=e-xqE@P>I5I(;Nr|~y%Tkx8{WNY zuNeK*wB3M4-$j|e-Q+#!DYF!L8QwBEcdKrn4~0wEciC%l6&dA?HeT#S#g z)UH%xNcwy(HQ7H{!*zC_fNL^4-&O)+Lv3l!XIMFrj^R$fYHfl}r`f%hin1M6l})xq z?TD)a@+-Z&kAroKS+uC{;O--fSuX5_5dY8OKnCj=G|za&ut=7vVmEsage{1K!VtI$ zN`LM1bJ$VVwp%qw7q9L#$#8Jp_zbbiB6nc-I|6TYIPZA7g<_n$6oqesu1 z@|98yG9N1GW@KHv6G~O!_x29w>84*v^z-Koy~QQn{ZnbX*Tty?T^8bN3O=Y!Y96Yk zZvVO?`sssD{fDZAHoAVBE$0I9$1{eCwogX`110$36f}?j!jiN70)nKD%v(+kS%g&@3$IGsd)&bB zsIj|B8{%nD3@@NLNvz`!3CXEG7xwImZ|g9KeiZI~?FH7G0P1T71c#5s6-&!rF?oio z{Y=r#Ez`A4?vdjDmbETlW2%{+Mc>OjrZxb>QDuDpS|oz(4%R#99a<#UD#-Y9=L%JH zv^PI;_4p%xmHh@U#ajV8FK4{OU5yXFO<7;vE6{#$;}}t1s^*boI~SVo`tgM%*JHdE zx=8X@&Zs7tvoLZx{d{cjv}t3md%Cigm2q$uWcUX^KbgL~>4xZAGRp5I zSB~%<-`PC$x}M^54sYo1=_v#knK5w)ud&5P^sVmSq*76>+aJ#z^!W1spID^*lt~K$Qhd$tITlyo38)2jbfhvm1mK|a6nm}^t5%1 z;P|Ff}| zCp!_lZc>u)zwe5;AC(I4uaz%`@J&q)+MX9iBt*#)3nLm5$a`M7)it$bj zH8(fc9GKL17rQq-j}WT`nolADA;Bw@iY=p8wX)jdD$RwtQwget^+{!>)$XX7Ys!va z85|m3e}A?&5je7X_+GHga$Fl`63=qtIfv7d=){ZX>|v_~>r12Z7g({h*v&F#3;Ar6 z3e~wyInHYSuJ0&%#cJtpf^U6P;dQ<@*T51es<$VOSuEZnI_0|=JC--jI<_xlr&)q4 z98j^7Ydz7?(WiAE3zL%m{J25kzSk=u?;>P9RSU{I?bUp@Qi=%#rT-3`LX+C))1fee z7^swU@S38014$+FPw5!4fm_LrUFQ1C))27n@*a&T<2^Hn-Gk9b5)&ETBR|JfezN#g zPMhjS){B{SW+f@AkcROF7lg!vFWw1>F@$L})IWlV0$J%6)O$$uU zXO{(8seW}kuH_br^mFo$2(XG~L$<+jsFu!93MXY4rUP~|lxuuhBJ+K#kwd_k0yEY% z8~|}`cg&tssl<4>MdW4!d{9*#n<^|k+`49+EA?rm_D8|8LGJT4lbEdm=WJM!7Ti-j z=I*OEzf_cW5l%=9`BL0s6IrsBk0f+K<*%G7I6TV_+c9VZq&w)NPv)M|Ss~aL7f+8; zBHe}^IY_fyj+{AL5;a>G`_JiC;hBS0qdoiE4HX{Cr`{Z?V`J&Tb%=>#X#$T3<5tPU z1XlyNJ<>Xn;aob*q`L#zQgMA>pZq7A(PwJS!I0^*y#()14a5(63O1v&!>t)qNPRq%52L@EV#N4EX=vsn4&uk%F#NO505jb1Z`KCTj0bVA8rl7yCX)x#OZ;Uc_f3t3V@dPAk^yD;2Xp_NYyrwxcS zz^^r5hIizs6Z|4*IF_0_9u7S3FMJ4}7}!z_YT6hGT=1?XUG+)r%;89YuOA5;shwLX z_Z#2ZFp3Hb{i5{wZ$Z6xDe^osX)f>K=1}ztf6%e0Sj|$mK%e{Ee(K@*To3<8fn^5l zcUJirjGV4dm<3rT&_*sViYp0TQ^h|C-|GdF3{LThb0Epow6tnLEg0wk1}-kZ1joN1 zUyo5&oXY}%;OSmJxJ#v3Y7*Ks)7sSq%CmKKbuqKB$jiwAr`GgHk^Z_YFNlqvmDv_;=D*$xZa$SlasT-%nWiQnVOmH@J|_)$bz7pB}1yK z-#|ih#NP6cSYbLky0_s#5~h^NSVep4RZh4E#$_AZ3d)J#M{R`xl z_lAO8974x4vfPu8yn8rgrAAM6>mo(tDAiD!l9$3O;J2uhhPX-~aGz%@xKBDQb^(j# z#Sg0f-cA1X=f64}XC(oR+85sNI_$r9V35Z2v$y+(HUn+#R4;b*zkG8&oQ8;Qk_q#G>1H zjPuBsfc*OcZFe`!_J%-yxfjJ+Iy&U<^-wFIggO*K9GbyQ$Cl4APbS*sbAk`-49cqW z_wgAkmg*-YOS{VR~|nC9*00-q?2m4 zlk(i1h>}yk4D+Cw@S%^ONYA53PUrASa}->>2zZ|3F8S>d`#IIiiHxrweEaszQ&xR? zU>kA6&FM*v{k*R~W_JUlcWY;{4v)|#%jWtWSZ$T(vaD zkS6HE4NaCzjUvQ|r%dM^Z-!X@j=bBb?r|lB*r| ziRzRsz5`cbZI6>PDxC4)XC$I6h&7gEGg$v(M}d?3v5=5+-YK%{qwvNW!kyRIe({%@ z{Evt?y2L%M2vuh9&qN*fPet?sxa_uQieiOusHR4>v=ztM4s(hw&^0BDmMyMJf%*O) zJJMWq+qWa#>A`Ab-a!eo(y!7x+6E7@2DvT)U~YN;z0$+W#Z5eq2k})@BBo4X0uYXZ(r4m9QsWmT&w)M!Qf=PM5%hwW<9%d3kg^+k-K9%MJ7pk-uU4z z6WNUzEhgqr6WKTpuEp`6AG&1;VfOVWCy_09e%R`Xng{966_q_sOFlB*8`sBand&)} zPT|uzIrSy-VNJt#nMuCgFUJS>uvk5l5ZYL~<6Dw}3qPVBAL01fJ62WJuF0cx8)niK z3_q!H9W`cB)n;SoUq=vQPLmry#pzYDT?#D=awE}})lOi3LmHWAi{!-QUQFP5dit}S z;5o%^DFq*5!0kZxBfmLcZKDAnvayk<#dAiz$jZ30K*(e;=Z-&)JO13 zNj^Zd632qxM`=P74FU$9U zt}$IwG24gTv;gWp&`3w_?dJ~-?k&p4>rl05DIGQcWT2(;eo;T`4;wAruV>2l@7&ik zN|QNI_tImVPbbEO;Yr?wnGD{DX*XB>Y0@DRx^78!erj@_@p!SX=A-63GGg=myqZ|yRVa4GHO;WGk+HLa^EFM3XF}w%D{i z>zQ*GDWe?US=<*hY-dvxNLeYbAKMDY>Les9lI5kwHboqNFN5=)lrZDxV6AT^6dEF1~2j?Bj8qO_R zDKZeJ(O<1A=O=VrMRK*>LQG>mW2W}o$&X*JIT$*5(;$&yc)n8KtNtjrX4tC1MHbmE zD~lhve5~w4ytu$gUUjOj8mmb%tP)b|Aj9&-d0lA9IHC4rc(aS?bB?lVMCzF* zb0g1cBtuAI`q^QS{3e65)%2+Q-fVMVy|ipl?KQqOi;3##de6h&0&N~PrcprpQD6$S z0NM7y{pR|X7ZqG38MGYx4!>=9-OeJ{2n3UEQ@u!h_jN|ttE;0Uj^Ekp54+Iu-*D@? zeKioY0$ffD-HFquTl>Sh6)&IgJ8$3`_$o6qtQ{xQb`{Fo?etKUNRUm{Do-j-F2~34 z{Bc3liz?>w4NQH*ww6A1CeIVzu544x{FD~{i`a4~MWw2$cf2S6rY*wr!IA*%v5_bx z+;fTC;>m*q1A1pyeyyOGp|Qg|p~ND>4s%tzx+7bAv55)lUz;u#^7OT%l@)yyS|AvL z|CPlzd5(3}gwp5;JBgj09qESu=Gn6!AMk~amQq6!cHBX28E}sZ*|A`Nb$q8jF=GQNm?8Ixp(p0zgPfa3hEku z*-8Nq*+&C9bYYS1v3JQ{sTxYJ2d34s7?tU$62R{F_08MwVI^a$?v_0_sNQ~m`}gpM#`aYGz0LKxOH20CK)^U@>aQ+cN$Z{j zrDPNo6l~g?K+Y?qr!=kMgh1Ec54!w1iZ!=pzMU!THewy);|en&=UKE z>9wmokFU_*eY4rYk~Ydl)0>1fW4ZKg&oA&==iHZH-PU+}uAHh^)|zt-IV!U4p&tlt z^?kKeP1{mauNcgg9Hr|{yRX~{bEtm2GGX>kGACv%-u2MktV&O7hn;ghIA;ZUp4`#U z>g1I3qkn!vb1<5fFPD{@SHr2y(e;im{@H;BZ8$VoO+qt_M%ll<;rE2}JSdzZ@9dJZ zt58B4cC{nKgXwnkT?V2_Hp7GPb3&N=+zt$gMF2bfUcS?U(WkZA@R4+ex)TUMxxfj2 z0(7lIMh_>x_)So~T~%G1#`}ewT>X0ac%bSSbK6;h z)vel}?B9&2nv()&2AO&{V~x{;V|y4U{5$XZ?uLau(9 zBu;lSXzB{6AR(yMlC?@sGl-NarH9FoS^qxjm?|u=8`A&S#}RURw5?Bb+<5y}gXN*c z+ud-MI%AufZvhL5j_aR<@3bls1=m_{c4g)Y@N=n6m2V&E&)2eO>VA!MbJOX!#&diE zH{DGn2$IyX4j6Y>J(r6~++-YDPv7~Cd>Rs#z|;QZz{yeQ@Z_Mm=2!R4HKK9X0}-iP z1*ZDN(kvvqy&HU&fHHWu2g1OJ`iv=m9ku%*9S@G@qjbsH3|?qxj8@vt0p@+QQM0Mz zGXKS?rViX-q@fX$(oj@P&RGGq;6OTuf}EAQ!znk!BetLAOXCC?1^hc>2Mc7ktUj_D z;1}z-Z~U>2wgKKXo(3vxHIx!;Ls>9}+V)_o3qTuO)*I!^1is?)EX0 zJ@R>ayumwHJWQ@rl)5jHo7rj7K^DW&s+%${JuhzlXScPv<6}d@a9Opda_ZBETW6gZ zk2%)}qY{WVKok!+#gVqyRE@!q2YyfOfTJIk_IdYHf+u1b6rKWQP+Dhf42+F|8UiXU zMMXt{e>Q=?d~Kx2sYY9M5IEOC6)m7|fRu!Z$0=uTr(KWdK02EnM+L&&BFhpNi*C!Q zs;W+EYoW@t4h;NtuI)666>zcZ`3<}F66D7ObzVMj!+{31MGNeXB5|$V-7HK@jy$A5 zXYmMfFyKo(-p%a_ElvaJuSoZqyeH<_ zBiB05k5{&R0htj@KFZnXikH0fIik^t_NSBX%_hfbf%9q`BD5#RkMW8Q>}$ftiVWW5 zbi1W^RMx(5AbAhgLqKjpYX~~9P2^D@2d~NJ{y(g%KWZle2SGVSkN-buN05fA)!qu> z;;9eb>v?4Xr+PE%DTYZ@3vw=MDE{n(?)UILdEz&6tV{K?->c%s4=UD8KhI?vCd6;~ z$p4?zri>lR=RotKY_oH5alyKbDyde!3$Dody+OcTge!K!b5iR_HS+S!Pn+7A_*gPr zh8lK9#e_%Q4}H6oH9fC=*VL`BIi3p?klu_z#;aEd)pj!7VUHBBIZ#(>RF`z$`ah~afUlu2X7BdkGH=T5 z79bQXt}?oV$^n3w==L))jBkDK?AO&otaW_SP`-Hshic<|tTc18idvXo6>Garllf&u ze$)nOqH?TeToAMD1Ke!FY+fxSK39FYYqxB})b6mp2gffZC99e@%@YA1nW|{nDF6Rf9+B#aVc17U6yW0kh4-MoK4 zFYBvoN11I^9osCI1E7L|ChIL0|>STlYwqTQ(zoe=%>JUFzyIwzgK z%spCYO6_$13sb_t4{3@AF7=98c@m4D)Z%qc+l@(3kc#VMX>jFm1#pj01KBvO2;`Qk zMrts(huV0eo9FJ_Eh~AwSxn`f2Dp!LD4wly1xs{Uwyr=Hu zu5R4!Zylo42@}2y)fc#QXFR0P5kM%FKw((xdoeBUG_w5Fo2|;`t5XHG)l88oB{!zw z`=2G-U|9R%&d%os%5ILa!k~Yj*j;%z+)!w-JQpHdZ*2WDoxryf zWX}X}$1Y?umEmz~+{%oLFF6|;uss@C(HGt5T5*N<7wxY%ets=eVzM63Ca6*BDI~PG z7PxI)VPR#ip`IHrEK{z=1z))5i#t9qnm*eXvm(gW7E$oloP>Ys+-CZ=^6YfJ%!Z4y zBSkSue`j%Op8mR<8(zRRy#Dcg1lB9dA{KYg=@qU}lQP_U`4~tu3f@_%%FS=9NXG|zr2%lZR-C4C{X?uM1F=U!5dfzit_eo~4kippHY zlVeR$ar(X`J2G3w4;I+@PA$nf`to@SH-v45%G#*AfIH%UQ#*u&&jf(3t)X^ghd z6lws&k*R6+=F^`?Kl)3iKR|;-z+s=-Z245$MVKw1KPj zpnx$NaWv{boO%;f-tCrnyj;$>lT%LW;9i(%KgIf6qDGUSGuq8bJoK4g^EX|l2Wc)7 z2YA+#bVw`hezmfOGBs)PzFqUr2dyWz6))??hu4mN!N(3gv?^@H+kJGiVB_WWi0Qmn zE2F7r2c2`yH!)ChRP1Fz((ennr6y-LZor9EE|AVxjKVqb_s#P*ywW)9{J2e`u zhnJRns-$Xb-rpRz4I8a=Z16bUNY$;eF?dz{X%20BONlr7y#L`&t~Ql`%>dN{g3e@3 zye$dEyMXzSAK{~9eULGj+2bk(G@Z2faT_W|fr(pHtX4naL!yWPRK?xNVx3VLC>aTP~;N=+4%XY$S`j zZ*e65Q+}9Joxdz$C9R?<9s4#KAV)nxi(T+HP5suMt~zhzwl$qtM{8ygU*k#cAJ>rw6;|22OXbks=SU&p5a7@eaT;1?g(@EAOLAAi@)&9!1I;pj_)mfK~ zrV@)Vo$R3Z=k`$oUoEGTh35=7H`?;+ZZsSwW?Wa^xmDt;W#Cw#qkURHc-|mxJNpYq z{E2Rj@lQ9TT5Uzh#r{)kP)0!?2$;qE7+jOx;#Xpk#im_epD$<>c?m3X+fC{aL9e~4 z@%NZGpsUYf-Wc720;bUigaK1@c zG@GMBGPU=xOQGUm+M9Nls*)CBt&CrZdDgoLXT>Y7n-AT-JjN}Lu+4_?q&>q*=ELVS zr*3mUfQBcxj}B4Yq+9H4S4vYLi4ll&2!HlgXr#|ZhTzxpUEto!Q?{?p8LvGcYdLcZ zS~u%A#i4nW$o?WfZ}5TELUa_K&^Q>^zET#{J*vJb5kQL@9c|CtPR>+~m-o<1=vk;; zFO#y7@Ub;jGdDBKU$kcEwM1(uW@h$6)26fxL4n~7LS3Q4|Mwo7UN}5t%0z-|Ev{VB z-mP@Qx|7yuQNUI7phu)y;l*53hVi^ruHawAFKHd4i?8ldd57^>`90g%&qu6ga*{mx z6i*hc{OZ-)*r=1@lPIh1ryq0Lyjiq`48oq#FMmqy(6d%wwC}c-uQfj*BU(r}Up~Vp zS)uT3KMObbVB^Ynr`WT`ro*r+gZuEUifQHE7i>UyI+l1eO-60s96730Gu0)f z*yas0fi0nTZcKJ{TT-4twJ$Pd>0ii(gfYBx&n&m<#f8v?fDn8ZMTf;=SQ8 zGRU|aEF<*=MoXv5!6%kyPipDRP47GLrreyRt)Zq>4+?u^By_T0n?JZ8`yhxoyYI8W z5%+oQ)<;f>snKcMwEpndPwy>6cUsw6EEes{QFWRQ2g~x1-(y^kF7c(9&|01>Oi#9g zvD|RHaWBZ_XT;v>VTi}eIg^bD$)PlRwp(&k7EK>dcXFo^3(QZx)jNvD%gAtq5Qhm+ z1>qvRf2J?`)S&I#euf~;5w9X=Xrfh%!9g& z2QQ-nbvpiEl^}>7Hoy;S*f!^MJb$sIu&}WFA57q|x$UZUeutKEz> zs_YD%$(g)OEG^@CY-b&ZwTXHH&2|w)2}jxo%@Q7%JqPE^9(Kzk0iGwF+pZ^%pq~Kv z8?~>Zz|nj)Rq+-;9%bMV7udab>FR;d?YtEr4;i1^1~yiK55SZNvM7Ua@arF*DMo<2 z{$Ljc+tHzkl>XT;z{yVKe2x!~M_DOx0UX~htR7ZhiuK=d$5!`U1*VLroE>>W&J$>T zpfNUBGfQVh84R$Oo(;BQ8K(5Js>FZe*_67;gQC=IYm1id?7{?Vr zs*{tcws6Phwkx&roiY!aJ=CQbyrFcSn#kD-4Q+DE-p!!{p#bC`%>as{nPT{6DI+gI zS9jj7-&*&g2{YVt20y{YZLa>h{STUSVZ@+*Nq4aWyszkN+dRN(ys+Y@fW?^l=J|2= zW_$vbj}4pyK4G}oq0`{FZIB9WtlAlhi^V_xrq@~L;t$QwsUSyA$?KjB8*`FfH<$Y{ zvg~|{C_7)R>A#3Z;wu@|>J*RCDM`;nM&~5eX_NMub5bfONdb|k>$pt|qdTd_O#~;I z_-@g@NC0&5MpDhWeV^-fUTQjx_I^4j%)$NWg9f)?s;6VGy>wSenfpOSCdH{h)xidG zvXh-?06t%2JRKdWvOV_jaM~%g>h7V~iIWb|F;MV&cBa1_x)ubMH*eq_(zA zrOn?*oXLw6Xq1RI_(Q0WtzM93{PSpYQPHNpbZMd|FaNlGZJD#JnN*VcKz++sh?}TF zVo)XTa58g0vBAZ2S_9w8-Q`ExHL7OAxphX}I2LbcW7%1BBK-5=_g{+*?7j5OKFXeT zZu>vsXS)lDa>BY;RQ>r!8}b{`rgva>b>npGht5w9LJ}wTM+Sr#_tk2TM*Q`ogifb+ zr@Pd>d%DJu5j!!{x))KhSCzE1)|>U;_ z={GtB!|P5svdU>POH5t|Z#gqH_j6)W_Rcz4>xi z$NjrAwr+AHsjdP!th7DWXu<~Ny59TwO}^cp%Udburtxu3qE0B34*;X5QyrJ&E#ir* ztB6}V2f4W;xv2w>U>#-~?EbBtmjS86C!;*BJI~E`;p*@K+x_%5-J|Ek0&f~$?{|;m z-Fn4(8gN=9r}12{+GwBd)y#Q(EVVbAiA}j$iJN?Y(-hIPq`+!i=-B3YP5pNLjK;|j z+Odvxqo6g%{{G!_+35YS4Lb&=ocpuJ_XU%#KoC3kL~bMiKd6eTW0e++U1gx0vy>l+ zU>ZnjO=a@fORUh@?fIb0a;n&-PT=V5eWxinQ^L|%9P zTTG+4$S&5r-J^ugiF?&%L-)M<{Lxsg#BW`Xlgx9O`t2_@zes$bP5JenV}}jrsZ}Aw z8`ZC~vh|hAH0fbjZv+m5-5U1R&L`ph?u&;76!VjZLx~k`>2zIMBv49(yH%d(qj* zTSK4ocxvlBjLcirL~DWZ-)jyCbMG>{VOU~{Dym5j2Gf!R$0^ou17)<(u=EH>T<=E2d#?WBndGA~k8w(R_C?8E zO=H!~K;omm)-&GL3A*wS+&p6}zaUV0x=}wU>t>j*J`I9A5GfeB$lBGT3`7?bj#y0D%-bBGOGM)a z`g3#`ikLyhqMtih-M^Lt)E7yhyHBFSyZta92o+mFf){Js`*XyF@Yy5w(gl7A zR2#~_X*`=>JshMpD_40y6mBmIn8*qB#Y++SD`eDMezKz)U)r*Nuq=A##+bpXNcG5< z*}X(Sx2O)F*NO2mx5^O|3wC7Z@ND|>iHTpLAFo%YsgwK(_-=Yv48%1+fy)oo7P40g zs)+UVDG7g=pl(_=lVL^1=k=MLHipE;{$!B9N?UiG!-78oH{Uv|vQ5K1UUR4YLN-4tU^kU6mj(5SLP`@RH zoN;=4canM#iYWpwLfhLRUgV1L2@kIU81E6)TMpgrR6kV4ywVZIB4 z`Cxqih293QgeARqUjcT#em%mEelLRGXTJxG(BHooI$wSO96u0@Uk8^Tq#(!}vY5$# zh(d0?{yrjf(WZwEv@w29hCZ_p!CrCVr@o+%Xjb2viv~$_v7MZMoF%($Z=zcIT_%DP z#2gWKY5$w?{*Cqz`lRf(fmM51oL^>swqU7U&?^@gs$A`ONY8GV&VEOviHGwZ&BxVd z?eV8oR=yoAHl)hJR0PrN-=p;@(DM_KH#9W#Y%#fRYL8#5`0Kj~_8ErB9|Kf(q;!CO zgI`bLPrdE^qPwz2_TjvxbV(SkiOW}l<^bfDz;!@W3onIm9j4UZ3zWGI0@Kt(C_zD)YQsBQL1Tu4k`<-VZS$I?_@>>B9bJuQI|h&2qppV_?0F9 z%lWX5GzeGiyabp7d8dGK5qJfUD4_cRsDffkeki(v`Xxz#bh4GwB0K;$yf#LZ(GS6& zXW;S#>VL0<_V)Hh?Z)r6*lz?-oZ$6q%}c=Td5K3*dt8U&u02721<*`hq#uLN3IvK^ z-Ql{pcIx$30&9z4peb}1!08%3^5U+p>+Buaa}@eK`$>pC zXI=@F-q2pK01<^EG_?hSJp=0dU(6T!jjIjzn_ARiv-o9mF`|eJcHxaZjv5aKbIrnl zEABwZhF-l~?NT;~pqy#+sc*@;US-;objmQ)6EU!U6B(+&{IL}^(`%R8hQ*of-P1%9Mgh57iVE6;+1ur!PpAp2bCK4HST$Owh!IniNn#pumfV-fM^+ zD!$ko6Nz`R(a-QrAYS#CFa7X9>;l%o9WgPnA39gx`~a4ZnZ}{Z-Fxr+X&MxRde5=j z1~w9s1l)4yF81!OM;(c|o$`>OI=)?Vq0lZp!(T!X7s|j9FLX1A9w8vQTYC6tWD${9 zoD{9f%A(I%ZCM7RdlR`q(am_?k@pmVJ2E08#7){4A3jaL*lEv?hCJ~w^IJ-{h?&({ zu6g=9O@DCHaY1 z_~?WIo*HCwIK}hcy?da<9P?2+qokF!Pu4< zl7KZy6>MCk^!I4g(Ni1=L$`zI-2j)%{Td_D^z`z~UY#XEt)eOag2IP}7kw z=#P4oRSvzxRRAA{z8m>^IRj>@Kr;XuYA6W-`iX1G4UWe50JH{r))yxhFn_Z23#^GA ziM<#e(2Fq}(C_`CqDr(b zi*Oe63gpja;{6$$*YKSy=2DfpA_FK|gVlm}!RzGc85n>iXz2!nA&7y6=<-~-@ax_; z;L(<)H3sb+(4J5cZ?Hhrlqd%{7%Z6=v&x|?4|)oVi;F3Vu1*3|w8-E8X&|POma!pU zJtSOHLxbwiwP0Zh)O$tmTNgBM zZ=~E(vr^g%4#1v*MM8*fwxkGB<0vWJ*?9a1T=@1{YD~BQ1e6nna6|_e6xZe|ILO4P zSvQqmz9&PyCo5+{_u@qlT+WmaitN#+I4RSlp_yfDHRKIyq}%)#$8x}eez*7B3&%r}p-KBH z1ef$5@Af~CK1r!NyPryb6Oe}IoaLIr>N2${8( zj6YM8`p^8m!Ii0eC>7JOaHUoZK}rRp^C`Lhk#e&>#&3;e12k+}`O0IiFA5?@)=ckY zB<17O0ZYH%t$*a?S=~>i=$Hq!$BgoBY{(wZ25Ycx7^(@eg)w^eNfPJ->;(m%=wXdt zT&x4q_npQUgzNh)5P%y+-el&;}r?C)qzV$~2(Ctv?TY>rUWB(OIDjE1s0Z)ua4K zcQ)#e%4zVYzX<*N;C#INxq%+ZD}lQFMrlT?h_9H%DJphM1XusV1>Z(d5keFM?vq@w zDymHEfS)8A)X>{NkZI;RxTy58cej?j9oXlZd~cEPIhcH2Aku=}$3uM=`*h+GY#!Zo%LA`N6g6f^0MK&t|Yzz^DCOF1O_$-}k&O8Tv;>BHQvb)^&9#6oXlMt03uN za0)%DNAgSbNzQnXKAxgNt08}$)oX#*m!eyueoWRx;|+m$0H~oL1~u!;rE$nkt<6mE z>asZ~V326IPnt8^>&@_%F^K|&H*){*=6aCPZcDUAvex!af`myazBdiMG!g)0Z`B+;a^wdKsk0bZUu zx~Bhq{#Mz$4pDp)GStrfx52JIBb;h_b8fBei;VYbHWd(v2)t7c`TRDJthdLm}s zUP?-0Yx8sgcMrrtpZj8!bf1M1c~Oy3SCU9-E+`pbRR451kq|&VeQLb3P_82$ViIaJ ztp0}&Kp;gxv_wA?y#41FJ5U9`GmH?Rk86)|sqQS%`u@kL2sYpW5HSE`8r4$77&u5K zXee>f?AlBD5+}XLwP0^)P3o@zjouhNH(2$W^a13a<>YTBudp8T ze#zjB>GYK7#c+L%n!dUPC`JW-OW*42r#8PI{E1GHcxEMT+$5dFtBvOX5y{iqpMZdG)Azt4aR zc~siFm|0g1%iZSB08*#0a3VA56_k;n;U9v0I6)lbX@GcGMN3N|p?ISTWWxEL_t>Ao z>zuqf;o%+)FA$`Z0JpKO{Tt*lBjZJ!+@avN-zMK=WcQyY?ckb$pi+5wmXxVIpHJcm z@jEccf2M|{5}+R7=ID?(nDm_o?0Mlq0qCyzt)pWGA@PI5!yjwBuYd}lH=VJ2f#wOh z+U$e|D?|=!>CVq1pk+ed>9<_spbd7iHOg2I!6N0SMZ=j7M+tuk_{0p2jIQe&U6X5v zxSC=>gaB7XzkdFaf1`3vMkgx9WM$p1G29k(;GbdxE_EV&WG`gI_~Qm|1%ebu9t?bgAQ<#yiws8p{o+G{DMm{X)p{ZkoYz#tub| zdp+>hU3AlUF$?@9k%)*0?;7t`a9JAI8w4-jB*_CxXG1$8dU1L*_71#$F#z29gZrQU zuuVTbB~+3}JE6Llf+mE|p#W&8p#95fSmT=%P**G%dghGEd5)NH-6)~A)v&izSPT&a z^R-#{4@G({^K>ef*b5fR!PawENAm6vE1S^zGa;t>EO@;Qu~8M?92X<1T)+N#nlm1rk-jb9-yWr zV!Xebf3a+d@rC`pM?Wz9v$R5>q4`wU_dI4{e9L#`X=m8ixq^>aW z;?S};L_wWa%gouSuK;{q@;SW#SDXS$61~%iA`TACk!Xl}b*-$fdf>O(RC!Zzl)1l4 zmY%;3L!Ao|35#s>2+j4lnaVg%c7k`Mu|N=~i0)br`uWn6@8msxB4CY4EKaKEM~y#7 zHm)L|-GWJ|hR**(_7zo_9yalss@b=y$yjXPKQPaEELyHNpolVQKpcR+j`|!umEGN4 z58NJap0UVECri0jsrL1?S`q#gE+qcTxmu8QTSV907|o2l6r}gwa`-g0-u4DEBlOW) z-sP;=Sg1JOmeQ8+PJl_xf;*?^=R8z+EL5l0&MV4?(o#~h zi%^bb_A_BOXL1U4jg2cOyvC92$d2f5;d#+%ZX{AT>FK2ol0@`(F>g})`4iQ>C&6OQ zQWtyn?6%5=>a{DO+KQoKSw1igsiJh8s}^!uZMMjXK{&)RU$>x;2vp zyDmDBwTmN4Y$gvuVYe>{Kq&OjD|xSjy<5w9(h(Q|Fg7Duw^JU?OHl6<2Jn*)bIIZP zgz-O$eV!Q!%cLFnutFVA@u@KU_bWxzdW^Yi!Xl4`DueakGuqjJeV1EJ|6z#=8*4D{uyfTxb~Cxq0|`bbDNApLdRJ# zN_{KGLWzQ*tWqlzztk!eUFoRSg319g$QM!H>fX@dwIlFL`4jie$2eZ6#cG4Ve`8y!|s27(F1by=N>h zbU6s5T6Rqg3nl6VvevF&=<5*NB7y_2q1$5dh*09dUrdsLbk6P_oTv9C(L<6?xuB^a z1S0-U(?7(9u!G&H(S!DY+8edU;{Ws7cjS8jbU}i8h5nR}oL6zw5d`x;U%vuu#gNx3 ze>yK`@H#D<&q^hKHFDN7)%K4Etr@-vYVE04t?Mt>o+=V3P1o`M<7W*;mD8oPDg7&e zL3;JRKh(Ww;6>%sD2CPY4SN(LW)UsGr($kiD3btPEdG%9JZ~llNXR1F&7x;yBv}WN z)OYU`x)e~IB=CS0;)-=0B*G*oU01y5PKLuuGUtv3#-{yx*|1z1R}Vc%J#=3i0rD^e z9$e<^fpk3~eduid&HtN~or2AR}MG1FQ(V^GA!Da-6>HZe}qtt0(;B|~&X^LqBMOiR3ho%Bv zVs6LoH7Pu2tWmX0_Rr;_lr}3geIB!K*+yQ9=9cv>*vRjdxd0sn5{R;oT#V>Df=xs< zK=Lwo`XyNj;gI*iO8j5>=^yhCW&=n1m}3pZ3e-QfGD(iJu_Gre^`5{`E{NA_|3fow zs(it@7FhI^8M>5;DUnDb-x6oTXm96v`bkq5*wi3i|BI=&j*IdO+J{lZq9mk48l<~H zaRF(Ojs>K8v2BM;!*BrxNA>L8+VP^44}KKHcBD?|lSZ1Y2yzj4aMgSfJrA3}(dZqQ=d?P@&+G~|2iyF+9rXEi! z$j`R~Uc0s4qUqu@lIoib)B&JfN0D(yY8U) z-Nix3!O4ikf6hwMwkN{MxPoEy8*UiSj(uc5`YHOc<(1Tp;C=ovnb-9c(`)C#SU9Rt(f+7G?(MN$?ofzG(=+ z7=SIH_|z2eg6WWo6nJJ}S#id_64VP$8f$BXnV2l@-M>xcU4bzYeX7PxHqLfJ#F}2y zB6rDkbYl6P@9_vl-W;;%$PWne7GdmPzO_M@-WJ!_9$&)^jg07h|9&8%zKtkej473y z0(Othw21BhH!61Nf1G(gHlfsr4fUfKnd70<;%4n_5t*}*p5Wta8xzx>@KjWT!GVtKBqi8A%nz2mUm+;fX*0@s$b$9en*0 z|26{qTQiVG@^@=8vpT;}D`cg$`Qb-!!o}vgkK9a7>IXdo0!4hN>yg+^a%@&}hQ>Ug z^Zh$zeP%b(=O65De1%cU+DneI}4oR6d7-kA~7a6KHQH}5w2ZS>NWat&!7 z5vyyOA)UdmP?~pw2pUWttA<+Qt=Nz;n(w;?gxR~zJ$TMQOJ%V;DGYnpq&|klEp}sN zfJfe>@+Fe1XWo}8(c{{;pM5e+e}&|R^5tKxf0g9riFB)HcIqG4ajAC$hP&SSf8iJR zr6umvv~1W!kuOX(U>d=3Cafn~_lxlhDm1;EC>HLWtwN(hV|N$z=rt+aTGVZxlzQta z#IntCWWt~p8?}@c(WyhWB562ivnXqW9p5#KfB%t()0cM@xiT?&DO82?eueUHDcoo( z1k=lg@HE#koaiwX|2C)Ff-ZCAqb{Oz z0Bstjo9i98;H}f1%8zP{(2pzj{<`h~Vq}H)OQ?{8UN)D;wd9)JynS-Hsgn!rI2xkr zALOWzl|P@s0ivM^uM1(NV?eLuV5&$Xdr#kN?B1M?ChcpyL8Q3W$+xPs(AY=me*{?K z-*9K!RrgyDr^__*by7HsHEg``aIEPO7AbOmu(GPQR^>jKo}4Of4T!tXwpBj^ ztb2Jo#=m|}I^ol;dwcCAApL#e?Y!(q{O`D(?_eIzN>pdLhfikd>5H}pybnM5Qq_3G)&jF3gJSSERXR2$%7@AIG%XM}|lSs0Fb zl)4S?`5)GJD1&K;IEYMlD=((ZR9UnBa-~WL!*lQ1pXkxY0d;@MGIJ9*w{o=#9nEUc zVH;t3M7W@zbr#rhW1_I)#P*c~d-}6HZl(&~x3OOAA9u%ny}Z;Q3#?D#7dRx&ribzd z%SKD3NEB5cPtcZ~;&i%M|7>t)d%7Wx2g?7lMMx`67pwdz)XhICH3RW=F81gpu5m@|mq>IAse$;|BBK*%XF^=EHhvfAWx#mA4m7t&dwoWPm`fok0ZM<{pUkJH_ zxW)qWn>a|5h^uB1EON}WvhIKNpC!L}%{DEF8_8y6aQ0G_x0iOX$3Ek3PU-+|?7;7p zT)e|Km{EuKWHgkNlz^5J=MCNs*kfw9+qceKeqN|5@-pSI=FVx)f|i90S2ZIoFX65M zaAv~8=bcZdk$1AD&(HECt%H#r2e<>KZGQ=UFw03O@Xy6TqIkp04Pe;P_6emZdUcrG z4>=tWag4zCjC^pnYU@WY)z584ZY|{s$uLRL3jT z16P?X%~$>{4ii5tLtX=5l(^atnCfYH=)0r|_73qYM339}+N{ort@wU=!L=t@RUzQW znJP4x6IVY8*QPgviL;cC$LVW`zE^i@_`Q8ZqZIj@LTlFHg!TY8JC`Hz9?OKjR>04< zAyYM6OhuJ%0>XG~`aCskd9j=UF&RGB#@<|2$=SBe%4XBi zq_9xMhwsXcblE&jB1a1&quzQo z#gg(klUUruNK41AW~filgH61ZYbwz8y7IIBW|s4Kx1mEEo%kQh{z%7Hnmptgi}BT#WM*w6<1vi&w~QCwu0ysV;O{PRU2O@Y6VfJ zhVuVERu{#(R^>mQLPg1*F zH!Q+sdO5Pa&3%CjCV7d(BAVk72aT<*BU^Qk6(j38m7%3xZ|O%oX(EGGoQ|x?GN=6k zE^G@>X2;6UIWLe%d7f8D#$Xo5tQaFF?gatPC(TLcWWy~ZE1Uh&6)tQd@f}vH;p~F@ zA$#BOp#2Ixcb)ckxUh?IUNoBzxltM9ziU`$LyJTFu@=z3->iXzJX=m0@_n98i^Epy zz7!PJnhoW1F%cPXhc4H3mSObOvm+>&)Lq=fcJIb7l*iSg9Pm90)gLHk_98`yh~g)? z>d%YiXdeqA)$RScN$u?)QhM0!upR3Kxp7lcgN7x zwg%6?kmnZa=hN2CjjfJ$!ug$CxAXp)@$^IuH>b)sW=8ig=6YrW_70>$mEM;nTfC#K zjGWz&gIu61mssO6Y?U(lsnl@ZC6GK9Qa=kSn85M}{Y3D}ViNp&J5#JYK&!@wrjR~N z7X&hM{X^0knS1%1V0>UW6CR)`cW%}lY&B*>z79dE%(}Be$F=8ZV)@)pS``^-lEoa_ zq|2B^iR_EZWa*;2tYF)(-+i35Y3cNTTtiW7ne=^ zitxqE86=-bO=uohCy(`X94&55zd>4{;&-*W)dn@1!??+FB*&=xUs>*1wIQ?N6Lro3 zz9*IXV!4HtdCm2-<8&6PEU%>0Ew}u{*i!GQt20v&^{hDI_fQ#1n!BZWO2GaU7lWit zP0(t*EWhI$sGO#oTPr;@3W_sXI>Nu~Ks$lWV8;J<^50ejs!wA}kc}e^C*D5`PtbO$ zoigGA5RfebXC-BYfj!?qcXkjc_~l4(HulFiNLM`j*8)Ar2(I1D4!~&x>F}AACFl3a z^mduH%2si2uRXy9YA+4h%Hyd3aw0`gadFiiqq_3cnY*eLGH&EwoDbHg;`i!)tl+ud zwC`YPstV?YbkO4G7BpT{7v6gdIyi#~!b1xw>VEkp^hyWB(qYN}bm%3>yhzE^+){mo zCtOzxLDBrMA6Z%2u<+_tb&f&eCK9>D?>11`Vd%`qPu2bf{(^X_2b0>hg&zm4U$+T- z9vCa4Q#th&Z++3L;sySOXtGhva4GQCu;1DPcTe5d`+}GroqAy`bb)^4P|p5D>kH6N zCcQCk*OB8xuF+rZrd-$tP?>D%($34tNsz{g)}#_m*9o1-Xz4acje~opw?>Qzt<3y) zYtpCWv(YVMx&ejdJtOLTtNvQ*U@YcEk7_Jj1ef(p%^hsO6|6wvW)eRe9Hw509FFC~p!^SzD$ z+NQZ>pV0AU&DV65?Llj72M5Bwy>DbRqpte=R;$*{r8Go|F;e8?1gpN;+6J1G<1##4R4}<8{N`_zyjOQ(Ztw1g z7faXu0#Ep!#4Ae?o&Q;7A|V1`0%8uDhZGA5md-ADu|t6~yc7|IFKhGV#{#4L1sH^Z zfaeWz^rJ;8_QF}L4Mg^^Z+gDD0q6;a)GwVB zdAJ|va3_rpsd8;Z8nyom(Zd|153{yio_B{9*mh&y_o<8LQGfm*sg&i3r3T7ZrtSEy zTAUf~buX~(q~Yrtx4T1kwQkDzUk7pjfla^@kVf@o-O2XGDJm<{d{U;MZtqY^hy+#G zT1I;;izBLfD5Of+7MTFs z(>hdzxbAk9ANanHy25xoj45d#(N6Tho{8bP$PXgwLJSrZ;N!h7@OzMoPu6) zY50Jod)2^$jA8;0zZrs;J*%l*Gu6hd<)>qzV6|SH>a^Lwm>#t>GHED`c%k;B=)sX- zYjm~s#q#a*y_=$#7%vkbZAbMjkgKao6gb56g@~9(D{k^&FQq8GP>acM zk5L?*JxeT{`d;;5ysR)=zw^%H3D2S5V{*k#!AWFm)kRJtcKH3nn}vTuXDzraeYEXx^6k5=!xtfW$)K zU0cY~=4sx(;BQQ47(EoCI9-%q z#+Ge+b^WUFBZ5hIRfpC7$)DSh$Pi&^N)`hZ@uOFxC}sH5+8_^CVmg%=ypm zqfG-nHmE)&i_Ey}?gzMEKOI4r%W8pxKK3VFe1wA-{UdPowhFv!WGHK2T5BL2+#zl2=?;%^aUlVFjXgW^~~pgj4km* z)$9GKJMH3zGRQYkzhtVBFMf?IVVs;47^}iaUY2yI4zR#>F(9Ghyx`cv!a}jM{kR)K z5*9+;220xSV6`)h5H(%N^knn&)t)L-WbQaJ6OhY6g#ofRfYMGZoir5z^!l4Ctje&= zx>}r#4SM=2wR{o4>I8my-eNG(FX1KuyS+OF>#iWuhZH_Ln~3(s6D871lkmBP7lzLYXo1(=^Vn@YFb`hO=UJi$_zR5(nqzMsqIvji&bX*XBDJpn2?KfZD0E5HuJ z;!|JV{olV1&vGS_6NVn1x|Jy&h7Jun}>j*e~|n=*(sapgFHoi&`DYOR(Th`o>NPt06!@QDO_6#y7G zkwozRv@JHrvr$Un!YF>O5)t+t2uZS-_Rh_EWKhPq)#E+|{cg zLlW|nJ_FKy+>cAP%(?eVgp0@5_T#ZpbK?Y_5pKCd%;{^chDgt6W_b7TW(k~}U@}_B zu>ui(I&w#vrCbH@mpd?#`v6{jgYCngyy$$QUt>GUG5_C!q!t3DM1XvE5%?$j^=k<* z7c66;syCmVU)QB_!idXSp1)s!sH~`DoH`ZBEssixC|tDPl@SAhKs^AmlaTMkDWn9* zjCjvk>JG4mhUfBwxr)b~@7-e%rP}4AFn98g;s};XH*u0qz6H)vH}C&CS&(q+KW^Hu zG!9$7nkKb@!D?b2{gMiodTj}sUd4JVE5BCSY7(c))K~}eJ?n_@*y&vm>66ckgA!xi z5#e3Y4gHe_JXt-8jurjd^e+kZ|RF>(O+teAtxT-48=1 zG?SAxpSs4@>)s@rNOv)kWxW_cL?nItTx4@e(7vQ(QTjmW255ft;(9rZKK7>ccmG|- zN1QzATV~9AEjAcp(7KvkiF-!3#DJjN({i^qj-sNhR$FhbxTLwh!Pu=TQ9t<)f@!hN zRj42%qz>jQv^hir}4?HFJ1_?r0|4yHLOqg?iUIUEe_ed&9oN1r^?Er7&&7RaTwSGmTOTZ`1k0* zUoyO~Y%sNnG>09A#^eO$0_Jh^)Ixv@jN)xe&GHQD?j|?A0)!O_w!hxmj>3DRgz!JS z4|yV=#Qy-tHXV^}R>t*^sPN#W_BrnDER+g6lXU|#!93ibcGU10R`)zhkaKPo`h-)* zk>*`nl(Q%mq?a*AbV?m#;^Mp5g5||6Z!0ik=LnPp4}b#|al`G3{s^r1#F0Ua(g*nB zk@Ts#<*5u~)j(R>F|r>_UiMc_Zi^w2RgEgN^7gjHTg18!7|wnTI`-dsoENZNef#nzH@=k~@p`A}P2h*NB++vZRVV7B$yhp08hOyG0sYY}lGL7CKy$D+8)zQioZvHbD9xD^hJG2fmXFvv4$g}Y zH!c@z&%n9Iu**!R!4*$IBI}iR6Hb4mTsb}BZg03qa0qFYp0Z$am^(xC^P*8~v4tNu zIoSVrJwnsqW7#~J`muYg#vLbB=J^?)GWX;wLnrW^5uKmJzl(xZ=R8Tno4tC^5KkWQ zhei<;oc99cFRfCd%gPwXHrxE5hMjeG_Cmj$PsgjatZBB+BJ6BEL)_3%+QsC1ON;n0 zi7?eFew6dCRxz2s?b1o12tGHSY1Io{67TcjQyDDEVgU$Dx1%q3_N# zzmATU55ljlunDvTwtu0ZADWq-I&8Mp+RhFO zz--A%+!WJPrKA^U2x%pbfEf`q5}vP{o81sFKvkj^uK2aM7|=Bbq68!` zhf{TLstn_4mkzu`1)R>u-C6bWced^7Q-IjGK47NF1GJDC0j9$ zHNAVH$tc)5W{{{$mNkoYL7Hm6X5C&?JiC7QXzJv1`TM^9jQ;+N)ICD`RqoJRb(Mpk$EpteKe$PhJ@m>m7$qiS`Xf9CgFYO_OSML zoU#7nY6Gq<$JEDt?GvalgjYK0oiW`}!n+vnE|V@XU+ zr!F#DtPlLnaIqE@Nw595=684(q^)DclADN^HyD|l1fC=4CXp8@-ZpOi8eUxDWa82j zP5DwY`Vw8^nxm6k2CDIL@cpWBaT^z;e!U?0uJHh38a$e56H>ol_9bd+qa-O~vDBTr zaaqd9Fy6hT>7X#Mw%P;5XE?Vw2e8K` zbRLkTA=^P2gZ5svwZ(l~?q2IdI5=O7oO>6Wgr&^+Zv&BtVicC4L&yFfrZ~Je_sYhP z7m6YqqH%e_S6yJ27R}>cjWE%+N&TN&k~YVNIv@CxJQp=EXUzZ|eN@PXSU$F)dKhAH zbsXYdGl;)uo95PAj7zoXkCc_1v#xh`_+#+%yS^eQwoz2(-*hD5HM%c~7kKWFwDZvB z5O*tNk!a`L_oKO?{dGy?*1ELE(ie`olNC-HH5Yyv!iX;pJDj`|C(B}C`$uv; zsisdrO3L3TU#o{`lOhbKGKB!w+cZ0SDb>p-QI@6<^3LE<*=`vsdij%*yHI2Wcz9(pu!Pv zVwDHuZwF8Fj7^Z=ZV$%DZ(N_OOPbER{v{EG2p`qXWASAsJRQk2^9Dx6=(1~u+xN%MTlyT*R97&9z!oZwY$a)EH6H!qO)DgCpT=N=EKS?>$2m_MD4L&cf2 zdKMee+Z8=pD>D)A{7qydX>;xeYld7myY0b;JlrHMS8%&rq^}9R#-J{f2|H&wY86xB z(5FpDm0zU2G^-?c3S;h3_`D@&SiP5rNJxrR(LGsY+r5qFe>D`?4Ddeu(P3sDvA7ng zr`=GqdmbOIl*~y>kf@{-m9a61d$sF=W48hH-RbEVB%(zVj)x2>z+g4dH@rM2Z*fkh z^<(eNIKfNpMxV^xeNcd&DzC9^&~j+-$3->mL~yT8qyeeh)lx_J)+cLu^ZBEwuXmG6u*`!tRlD=oacEi zN3NI;Y1#SR(tbVJ=D)_A9UhL8aq1jweu(JljOz z#|q(fkHT&k<4FQvH5?-SoJjrP#@0048G{tf4X~ZO*cuc}ccOhFpFT7 zq}?oEJ3f7YG8YzZp6RdiBA}Jla5Iz3kB1jk>Z3jwU&|-aCOSqmc6oS@u@Av`z}SjL ze+HtrCjXoslDVoMJ;QT2IQJQgOH}aI@{ewrrd=YAF`T8iE&=Pcb7P|AXZtFg38$*^ zDlS)}W7L;o)4o$`8ZG`>aA|PwF=4BF(7{U{k6w6i>#D;mX)`Q}m)6yO;{|HK@Dkay z^`YWo=h+&LbI9$5g9WR&H++fHQOZtaf+`HRn&?q}m2>5)za5w36W=B$KD^Of*p?lB z_0gJlJ$g$=bSBPktxx4GZIAV%i_+3+o99d~81rHm3CS3?kTT#IW<2 zjkUEQS8`@%=Krm?t7j4)v@Z&j>yM_>%tRg1rtf%WmQ3hO*U=7ps*KeQsJ1_2KlHqO zJ>mbNnMLVaK1(tgIKP@6{9{2K#KXTR(L3?8_nY@Y@$(W%I+sQ6)n-QPM0e+x4&Mj= z2=gmGb52?-G~rc#o2#k_iixo<^G^?NStMu%Pi;>g9IW>#<5~c1BqzW$9Q^Io{F^2K zzGWcmd_NkWk)Z-Isqm?Ja2t^Gx#JZp17)@+g@U@?DhYL=;UNBO$EaoUd+pD-+DGe= zX$S;FnMuYo+dabd#;3dBD0UVb%_7|FZIQ%1af;oSt{RYqRLt`;YuMd zjM*uVT}g4rd$+DPUr59|MI_2xifmj*erI(PFGb~32eHbZ1Cx*SB_Qn?y)3T;-Srkj z-GaV-N=~_{Pmf+PsJx+9`&Z*UT5RvyXuCc2lZ&mqc_^q@Bj~1A3oG-{KNG^6n;f7s z5z|C;X&U*j9jv}#fA(X{lpk$FJr-o7#Oy|BCHknZld>5+0}9pTmgX;#zo z-}_E$5Cv^x!bM^CV_5(-*rRH0v-L zYMG*deHfi?W|fen!hiVDDB*eDNrG>Fo&(YEg9B?P9Jx5Q0G{e8vO+&Z1F1A^^nD(V5z^pUZGr zx7~N!U(@s=2(hgkcM&2UO~1G}moc^DE3CbI#;C|hBt%iuMn6mDMD$y9X@DU&A>n5a ziC1G2VjbAQP+Xud{EG%+26C&tVe{~R^hSVe&D&W?fHTrSGXa?BPH8l`>IC@N-FAKt zYrZnUFH@pJ^2veL)&`T3$Y6!ve^KB)_wtHh2*ya?pf_S3e`)FeTWqs%9c??HnE$_A0PUki z+ho9EAf=#nv6Xa#5Zp)Us>+7gwwkKU;~Uzu=AU{a*Bc$?Cd9A4TwOV(rCG~Y_8rVm zO&tcdt;%b80Ea`@$U%ut9aN$>$I1Bvc;HXLLu@hs5w&dyS`h!c;F6jN#8Qx*=$D`Z zbcE&2Qv2pg=Plc!9&cLiyPw*1`&RkYBr`dHC4rDXYB(+&=TREMgqw?*(MQVUXU?l> zwvBqvdN^O&H_HsW-PH~=8_g5$dQ0Gvp`Bs|h}T2^tJDB+<@Hf?Be#jFwZUG+s(9Ih z8X&zdd#}FT9uGt*X0T{8Kfmfa>>D4(9Wiy+Dg&Io=Ip{P08kK1jVusi0%;St8R<1y z0TqF-L8pszEnW_1@OEd0T;TC!uX3Q@pGlv|SltlE#m1v^=tdM{X&!~jm6es{Nk4gC z$->0ciS$hV_U-6=GwolD;6I?P0r-l>wKhl==P5>EgpEye?yKO;!do?}DE!t3%w|7+ zW?@;jyl@mUS{Z%#qg1JIfrr;ceUT-1%RWQ+>*hmbMEIKfnnyY}nLPKp9n+){*Q^X{ zVuE*$*&C%rAch1!pfB2A@8t)#hGsc{o(>Y$z5D;Tz@u~zf9co!|H!~LL!#;-|J@gS zB0AdITn1IlUO;a~JzGYdq4|Ll-!$yD$4k9QHcyfs-X zprg+>=!oEm{-giLCcarN+yA8#qX*7mNSFWcMOf68t61%oxSHX03;@*jHW&m5J>g^C z&U4x;1qo$B=70_)bsoAxrKp^uQ)rX^4>IM)sk)cAD%!mc+TiA~^wJqSqw&$IfBYVkTJ{}kZ zn)&#+tXa0H0w8h1ES5hk`UHKMHS1I&$=TRiT#R~pHpJwjpra{ySKoU+96ev3;w z7*$Y$QA&D`y_!gZk5);JJb(ObR_FTA3cf^|c%Eh!d`_`6b2XW{noCb%mwxw2L}5Pj zj(1N?z^ZZ>lhg43I7f1D!$?zbtHZJ!C%)Y^{;iuWtvtT->si*=+0-YWt5wwG0Wy@O5hjIRS}g)q|teH-B76#bQ~==~Tg9u7Lg6uk0LqGaEVSFBnKw zjN?i`1&Q=B0gD1|{5$5G_l7g9#GgGh?Bco()92YZ_O=c4l^UJE^^?+MoNW>|)=PPo z3#4Kut+UInn-`Mj-*4_>F^iZS!uO*D4Y0elyMLN19B1jb7IP<@12;R`gFPkO3IkV{ zc|&%6P&6@+BhnIX-oSDp)Nj)r^~?($N{fg%Nb_lksrVD=4(IqFji8{(0V(L@*7JtV z`pXBjiJZqqn3I)D9opyH4tF1@mHTg>r(A2XWo<1dg*4QB-#k!s_`*(z`r?uqA1HYn zk5CZYU~cmXAW+fd2yi}FN1c_b!kXvYY?a)+YPlN)p&R)3A1mS|d1);M3M%#&Tt?>{ zGRA-HFw_0ETARzCrQyPuTfQoh*}_A_Le4yY>oU$l$?pPbD8OijUUvcQ@mQI?60+EI zXi)655o};?DJE|E&D+F+u&L?L#ev0&_Mpd&-^c!~3MU$qCH7j@HC07fb7NLhLQYb^ zWv}R-oUn|ZEz&z1g>)QA)py1l=+|9c(92Xyj)bIgwO${V$OOTuF%y-?>6smx*cFRG zsFRtcw$s_Wd-;R{4Qzne=!}Krg6knOj7Lw(wR128QQmS*@8alx93jcey{@tGJV@;? zG808gAYzlEnzc13Lg>dAD6k|3{23|&hOxz{?EaAqHOeegf@=N zH`x8A%OwMKm}VsoWyq~~b7=G%NOvL{^PJjEa0_?^Cq&Tl`dX%@RCvVk?5uCcZ89XI z5Wd+6iz+iAqe6$)4jBvEYA&tee93l}(t+h#d)wWw0H86;0EBg8*>W#G@KXSZ+~)Xa zfM5Stb?SU6gs1V6etcG&u@>V}A9CE-;v(yDd48W!{ojBHUf>m9;|}?C`e*@hk=Jkt zLS=Y02o)+xMjbB3P_d&8BXM!q=iCUnPJ)y^S;qIHo%_fV%uUF@`8`)(Bo^nV3L z0eSu#-R5aqQ$w!|2c2in6*LjYG@ArmCleI zXBar?hVcnPF9m-t^=&1>XlcR4;Be=(+=MmL7v=VT7~NH|bk=1XXZ|mGV`=}OfO>7{ zYf5d1>rzU{S@6CUCma6Yb=~cqF4nmg)*1YAdUfBne!FanhNWPfKT%1zo>MC?XQT&+ zkswA1^K=pSib;%tTxzU<74B(ev~Gh4BF99%8wE*}kIq zlhtawztSB=Zp!D9@Cj};wArGkdzeQ#vvD7*g%534S$i!?R!k^W_N4@S9)C>Wf^McYuE3UB=1QM7KL@6vqjL`n z$SuX4ynQe`2fXvA3Sh<`o(aRLO@FTrdG(tv4u(TcuSEj?U2Sktw_k>u?rm}v>Ke&j zp$AKBHX??iSI+eo_u<&@VBea;ro_P8bPiLGlO;`>IuM4Ju6f?PM{(O8nQMeo?8=iK zrp=ozY4S5X&4X#u=T{m_)kR9w@quT{8SSkdo(qYnwu4_~kn>fR6caB5Azi@XlC0^- z*|grC?@WaNY!zE0Xe|L}99Mu=#Ac|58slzk)wP0J5a~7-NK+lsxax%pnCDMPUz&Qb zSxE$BL->WY_m6fVsd}s4O}Oi&XqbhhzYoCQ#T>6ZfF-3=xbneLw?ekF9g-otgKjgs zl=9>l$Np_m@;RH}jZeNCi=#238t$1s@Sdug<@UoYPP$TE{T&EoP$;7*t=h#`d@3ZS zc`58UWGga*u;FAnI4$~KjNt)lsbiDQc~P#&Lj zRo28Ge+xoX?Ejk9^QI?n)Xil!jwhqxs5%^NSSpq8!DHyQRtR!Lot3`DrE>i8xIVwU zf_J+~z2ec1k!3$G+*Az8tXDIaIm5C6-YVzlwmjdPjTbh^vwlh!I=m53#47`-I2}R<5uRR8 zQs5D@4V(J5S+_yA_8*8E$e{mKFNwqZ^xI9FYf{Efx|CX3H7ufUZ)!wxb|v6uc^?M9 z1R^b<>ntdA{fukDo5jM&dOf(Jq}0mO2|?ej6xF_LU;@ z?tB$E+YOP+rM}R7xVsxMc`6g^Rn(Suu&Wqy-m0;8(0)DiS-@%EBsD>Ik9p)X}@QUMdR7%hy`ZfN};=c;%G}DmHw#k_Zy1}%@@9t^4MfD=I z3FHG4M7>X4TIX~~J= zgrNThV!KIHzR_5>OPP0Hn!R%L*!dIXvxLbSw#sZpWQS(KcPiy(&etQXA2dIGaj)1lnYtx=N-e9{(p0zbOwCOjAx~qQ)8ZzG+&VbEpf0kls z+PsZR805-aY+?)jX0ZYc@SU~8R477PnG^2@_!D;TdJDo#g3s3`Vz#Hs#_LYSds^|m z#Hi0Vv$xyNz4v`guaB)7=UeZN}C~l zQYv>ZHb7Ls5_`#K33lIq+pj_`GBq!er_Dyc zcma8_cz~W>nZWX~>A=+U56RC`dyO~*( zQ&!!+UoUzExlmniTv{?lqwkbY+F)fJJR#x;gPe7n&gx>;%S^$Lej;vD0T%b=gzKQc zYZWqnNiqB|@d9vzf47wM=z-3LfiC2_`ZBxS3rUX4&fU$*$OxbJP(BkSq2tUoXF2sxR( zq=lO>Ty315w!S-?5Y#~XmVII}tmA|GEV7}lmwcSh1`qaxqbCuzQ1c&n(ip^kUY zmjGR>BkC<@ztx<$u3-$Km!7MhcytW++hE8vu~{_#`CpRL_Wa9%rEA|g0bHWNOQ(go z!#(tN^J$q0C!a#T$5S;3f9LeEFmKzxK66G!iBreAwR6tv!*^v>zvd1r9)jT-exuCe zo7p7O8bbZyuTw(yx;ay3!jqFK*kcFVPxOEmzUp>ExvXBn?b6V_!(97*+2G@U%Xamx zr_;ODcp&C;$b{@FYM*#d!X(9KDE;7vNbZlI*tHw1e(*cI%n0g)^q2^eP0GRhZt!;y z6|}5Z+aGdy;^a}&Zpe-uyzAeRNlcH~>8en=F{1Z^uYe|h&4h&dh5d#)(s$3xDE!p^ zpizifTC{%_2cbp(*fy8DUE zgdkdg@#X9UjL&&poF&b^`yb%S(RuMaXOApWq5YBwcXAvsZt-=qEBfi@(X-OMIG!0s z^zb__E^gQ*&=Tw_0jO?ylqczx)&%WO!efJuOA-xb=HDVsy!FyPushkwjb|Qor?rRJ zz~A{fZ6aDLPo^@geVwQ1-mZxaI@)S-cs%s)g?We6qzqz46Us5YFr-R~?_NMq&zu+4T9wD87jZ3B~>VlS&fagRz z$cLE()mHthdaywq5ENwaZvirY7PZCF?thu#F@PpecUr8jm-jirIV@|Xi`<Dmwr%R5GUS+kLnV$&xztkf!{+(SRAcJ?s4eTWFa zmu^ZY&T3&~VClMVzIDTvZ?R!$Xc>>OBV)*>F8>rk?FH z%lI;$>+~hr>+78bpFmQtiwFN~W`~^XtVCOF#^1lef0l#$^6p(m;wN`HKBBcr(KAEU z@5DK`W;81`Nl9@Zu)qBAnJ)jqL$3UwN|Q=lr0=~^(?byFzp@00Qyzo6 zpig%mXgm)Z6jJ-Jgd&tu6Fcn_^Cu)ioDkE z5dnJbpPyV*r;2-6BY2tS@zr{q)?B_N6=~7L%C#<(<5Q}}yI;vY-W-Yosfxy!!Kz*FrF`g+vFElKGiwrthtX1;k z#RE@;FF);d9HH6Rz_{tc4wn!z1xfS0=(AV-Db5#eyC>iI^$76ot?2i=PO_4U_oNdk z>WmnqZ9XPOADNPW3y1z0x7ma}8jc1mKie&IIeCCrb7^Zr$(Yk*{ zs1uX??vOO_Y<_HIB%-<}jfzDwv)Qz4^htmdI5Bk2kQVY7HOFh%ckNfwx=a8cGWGT! zXuaqfi=k5v?dq}HQi&`vDy<;@PAkmDX1^3UoWg75mpfeQ5WpW3`}p&dMrQ=#G;jxU zvZbQM$T3Fuyi{X}-3}fnJ9Bqj_VV|Ev_JHBFB)3YyHOtbjRJeYT^WN2IE5P(478&o zU$!~97(Wyh6}1a59iGF)UEI4x?&<=w-Gj@ZWl^Ao+w3AhLfnku|+4WZfp z|G0YVpg6wg3v>vY;0Y4k9fG^NyL%Gc-C-d>&>%sByE_CHhlBvZ-8Hzo>zjP?{k?ki zwzjtRuicrseQ%%cbGmzW-i({FehPglw?`t?U1hwa?zqMK6g6fTBIEo1W3I&t4Kgm# zKIDGjP0*(>fE2sR>yc_;3U+Nr-NwkvI{w4>TFEIE85<1HwD&tnF-;@4>~3Q@ib2Te ztFoEk`Dq}8kW7MqtJ42s0Pab9{ zi1#qWF<-bldLth!pVer>v$8?y+=h5jkhRnVeJcE&O*Jt7~S0+&--@o+KCQ z@AQmBV5oK67laCx;GcAUxjE|!?S}~%mnxwArl**>im=@Lelp_zsDCW0$wy6@ebznk zcQ!>ZM)UnaOO=lAeuw$upH_=Ks;}jB8)2~=_w(|X8s~Il;k#C)=vp18kgbZKJdU-m zwIRaD81}2boc?6_c|Hd@AyXIbZN3SGzqQS(rTZmOE?hCs!UVB(j(o#I**Ya$ivgS* z8=Xz+U+f(Hh+ZNQd=&K>fjs5hTm@&AqS#yQ6(5cAqeK2l4$lVtDhLzBk}LB)%<;8$P-}pskrwxXIE6r-H0^>h%Q|^^bf@QZ*V(*z}#iutN)neg?^N#cx<&;BPWvv>V(7i?zT9NOKF zzqJ3bONXa-zN=$CZgu%n=Q4fc_EP+4UubiD+5-;Yb2^H1_(ntGbC`oy)y&}pTj_h0 zR%E}oT+XH-ZKjNWG8?&K?;K51WMe{Fcz@v4g*zn7;kB&!b!eN4SRZ=TI6^1HZgs-m zk25uj3o&%jw=L5&q&~eYKq?I8B&|d2i)jS6mC9_g`vjc+=LCQP%br^Dw~!cLQ0s2VT2>xHDUy z#1T~yr76(}$7lj!0BX1CF6f5P$&W4)^B4$M-R(=;JWvWC0^j#p{`q$It2KS=_AFwu zu#bZ=G0-UQ;CC=j6w~o=ldS#VXsoA?Sn#u`^{QaK#=q_HEK1(a_h+YR2tw-ZdF2r! z@xur4k{w#_4_m)*hwTbnCxoC7mYSd{L&PfCzottT{Dku&5+k+EC<%jmpdqyb2IzD5 z`PAbX$Yq*B|HAG!j(mJ>wG>mu@=1N35juzD*yJ0BHe`T9(lWL5+Q}`vPnw5%&fdWw z1kIyGGF9s}Z%>59odr^@>k(6=9upCN;m8QLF5_@xqxWVQmwx=On8@z$ZNVx58%Ki_ zkn4n-4OT;B_swCS^ohdJ_oRg z^1NF%&;Mxw2!wn+?d>AW-VPYu;{bpKz$B4LB;oaI8&jn7s+J$5*g_ec z#@FTKJwif`ULnH<9E^`&va;etx?JqYiLSQa(Z8b*2Y`YeLGY&+7fe{i%uNrjq+( zz4^ArZ!9x|IFtiIsYpq_kh^MLsWoi%Mxcgzs?6aWoU9DC&zaV zdH?8e3!rmTRUKqmzt@;(ZQ8?;55Q4|U&+%aQd`c-C|iMpfA^H$qR^m(7zJV+oZ~$} zEWe-SOqITY`(b(p+D$PnRLw6s!kHn5P^;`6>*=*H(O;W|%rntN(zG{PjMv@oetXgu zuD@tvwcC`+u8dM_xxK`-ZfAYdL=ma<#PvMfixB0%oKNE~X)v8hY?h}=)P!0G@A7ob?ffhif0i=>j! z+pDR0N*zzoX;r@mbPlm7CDoT{%oP;ahtQ!~hfQF?CB~h7&9v9HUW^JVg8zh!c2vGS z1muXA>-GIXv0a^f`{NUam_OnnPWD{p^^=aTgUxku?J_On@kWV(0R@dqUx$0rGjg?R zEvIe&7yoww!+hMfRs2bh0z(V7v=N*%wT1^96He?ab3CQ(x9OJR=~^VM-);E}Zs>Bz zsRcURf1WFHKSe8(@Mk}xjbQ%g(;gGk2Li5cA2?6}F3t0hj8SrEUB`4%c8FLQxEl5A z7p^S}iVRQ~(8{GgBl(*MPOv|dRh zvdK-?#8%VzKFR?$Nmc()js;mb4)atqMxxAI+#&Xfc?q*p%9|PEEFD)C$TEu0?t98>5||5Tbg1y*aO*-U(nF+#!;G~8_TV7We$U|0DVh;7v#@@ ztQB=lqeVKRQE;9Nt}qe^Ay$;N=|l*kdcZ=;>z%Q@(-;PD0?6-L-;Ljxc{Pdf|G!&e zs~hR(W@LKou^yrZ72E#E^z*Je z*0A^A6rLV@-*lZb4onat1B8fXnw$-M{D2CI;;)b?FU!;#opf2*%6OW3t+L_mY;=up zq%b`pNfnXdFg9HQ;FRP&&-%NtNed6fjCj?+qQv%HGV#)&pd~JX;LuP+Y7Byb$CIG8 zAms+9OFTd=&ZmSHTbz~Ynle}>PME4f+w2mrWoY`x=>jeZNmg?544pW*efA6t3qS`B z22lPNSQvNbKO6}EXNzozy(w)*IaW_nwM*{|r6Sw#IB60St!iuOU0k~UZYC}zf34;m z-Rb?Z3T>{vONAe&>R6I*#7xJSy&i$pvWl3P9IBVjE)@@5)Ef z#Uh7>2%q3APF*WiahT||ySGVVG`srugq6?(MFRhw1b;tpMRkL#du*rgAMHb|k~+Sw zIRXJnH1x*w8NWgEvGUU5;%a9Kl*Ve4itpNfW2T#6_R=zzZf?ECN5DNqFeBDcjE+jb zg7274kAz%G+6(9`RMV|!2G>MZ_FZImiI#k@imGbnxBfd=>iBX03c{ZsowPJhfo!d^ z?Gf~m!O5N;X9jKei@co)hzi>ft;aZ)A{`(?UE4eJ5@rWV{ ze#=0|b`S$%$zx90=rFGT2CbwlzjGxMcX#&|9MBo)PCZU;xypnXIPjU4^x#4n2OwF{ z(%kPsL0~*|r@k+SN%&s`4StLoD_E&u0N?zC>PEP$oACj)gRAju(uQwquDPv# zZ~(aOUn!&jnTCaX!ZIc|ZbnepDga1G`$Y7c00Fs{5ruRig)lmaa%ELjwRp<9ZJ#Jo z{e)^VYweL=nJtC~?c3d=4$WwlRThSDzkMiF&&;#p12Etcos;`E&`q6a58QV{Ne)s{ z^nls+rKu+u+xok~G7jrRsn=9V9|)>am5_1*K3Ya=Tk%2g7ch7HdfbpO#foiyqFMg4 za4d~28M%NEDEL1=)jtv|kO$r-8T0AR-NrJEX zy-WkBmVbo__l}`V%*s(KIQV7{%2KM}yj#F&W`@dn1o|gZ$4`E1>+3Gg3R(X4`rnIR z0|^q*?wPh_@Rn4tdRTr#4R6FG#?S$`jPDPmf1@}wU4OtfqX3KDxte2PE#QaG|J!R=lmRW!!K+;CHuIyPef>ObqkjX)pNVOrH=0-DHcT}x;!>f zXllY_lpmis#EE1VTsm@}h~m!%FP}mCmE2R$)#1AWl#KW{gaiYk$Q4>(bANm2)JrZP z)~xB&T`Ww&v}(o9!`&IiduKE!ga7XhDSd+f|Evnw*OZ=nFRG`rN93;Vj7k!-UQaDB zGm+9Ve#S<<|G+=Ts zBxENx7G`KX3+mv3hf851yidY?ihnP?fiEYIfe?%g?$o

4 zUFORnuJJucUDM^kNOR;^?jsB-T^~Gy;Zjmdd923;SklY{6eC7|987}C@nMl>}DJizmb z>Sc4yRoMujV&F?IAP}<6iI68tCo&+B6h=G#bn@+6CM+WU(AL_|pOJJTh!Mlx-Q6J8 z0$<=4Tmk&Qhzs^!TKWHVad(k6V^8JT4fd#0;ac9SmTJ*gA5kMxcc6RnEaRGPqi4Zs0mgQR%wTq|3modx2 zVRut@lsvT(#U7T>GA;qOo_!aOoeR(n-?4Y0SOz}t?kfBqLqiG?c?_PLX|rc>i@$~oGx2~oq>@4sHEKy`a}t&FmfW-N#=GCn(cW#nU7iA8WH{QqFLqX-%oy1K(rDaZ7`dd&{HRK) zG5v5Uo5Kz4*((e&2bQSmY!#mC^-GOiR!J?jmVY_6YwIU&@yxEBz@~a$!6h&;mEh2V6W?vY3s2i5W>Bp*_kNiHcyAit?ndO2i2{=Y5#oE;Qi0kM8ZbJACo|e6{HM z%RY9&wx;NZlH_L}kMqy+|3OcTI~!GQ#aheyM=+But{R)=u(w(DI8A~WHO>NnNLxl3 z%3xfIiU7R#0=dpzx)N)pwDfNxmhZy{$58;w%Y+3Yu*QTK!|uFn7c11Hj^SZL)=nw} zLr0IL`wx-=_zTr~^?}*WEqI|ps0Su&w?KArF%mGG{!*2V+rC5a;>CE@p*sQKxny6p zfC>a-=*Gc_#8G|aXeFy|u?19UknGT1h#TyeUR4xm|HTqrZtgJie$J0&9!9*hR0bn1 zt*q33p2H8&^HS#0zVjD--3~^?ufMW6F4wLlZL;o;{(J(XRnEK>Mr)1c_~<8}Sa2cK zhimble_XEMBGvb{8$;2{%y7G#Tq8oPQQx@qO0C?+&?Nf`P*53EYsk7b|ZLeQgJ!rzEmur){-3_ALQ43utN$ z2RWb94qbnKX{m}9ig7S)^4(8uWxqN*wBbsAP}WP9U249kUOwr$>(YE5@ycYcan- z3n@^pgnxVU^9vCzElGFxrUg3yFk`(94hGM)sLl5K%F4|_fA&W_U~dmx4P8}wSqSKh zQ#zYG?A$HHk6bJ&M8ZHcG_W@)hJguzxGpC6AD0X2k6&i+)^3*7hLyxDapk{3pZK#Y z6St@(8@CG?`tqcFymT~l|Iuyi(1V6vn6Ds@p<{NR#&!1B+#4~^Az@*N5RZ2IL9|na zKj}+1tRWWEeWEwINiS766x9I{c2@>u_Gd0*MOmjr^?WbG>Llj{dE_&>=ncQ?u@>!T zi^J{nzdT?P!}BKHI?1969jAfbvbxW7Yn{d688gX)_aS?7ioTyv9PQU(=4g3DT;{tf zkxB7mJr=#^g_bOFn&s*p!-eh7;b2$D9@o3?dVfal&-Ootze=lVeQ%|-U-SD|{60AdlXAA$s03NYlq)+uMr*Rn;aVJXSG;NT*bOvR}sA^^g6(c$&D zIFe`dveb+!aI_I?wDThHn4?+?v$UL&;Y($E)?$-%LFsBLpKE)voy%QYVpo_aX=SYI z35k#9n%Ln01?mp9V=(>!ONe#rlyJd#w_LZ*e7am0h>d?E;9mYGNk2kQs6HAiJ2Fxk zJb=cSBXWN`wJMnE6;kQOg&_gCvwamta<34j97%&!a3}9ZzA))Gl-qv*2Pq#$N$gDv zdp;ub+q}$*JO9bu@@l}QGy>hh=yqBkUFp@=Gm`yo)r7kU^s<)$$D#Vah{XY&0ld`>tL4m|it48fbTk-v#Y*zBv^ZTy)53H$-?;Roy&>Gr-_($mQAhcC#0!Qh*BPJ1Y$9bCw`)gc>TO zMCAp>wcuEC-lcl-42;O*-kf>rM=|p%ccVe%3*79qnsK^_T-s*tm1G6j>SQ60S%!$* z9frFR+6MFc1&=R>cqQsK3Q3|f0#8FP!QwcXP~pZ83eVr))@gO0-W6Yzrx`7(EN)!C z;d{DzPMVo)N(Xg0#BXuryp;XiMq0UJxLSXIv^t8MiBUjCT?-PMkTQDyXkUUPq2pcu zsqkAh!E_@`=V`Yq#n7dt>T9Oay-hdN3D^?Rk zEA@n!f(vQqS#0W|mp}eT)Bj~ztt!;|?esMgLQ4|ddVQB&8;WUZnTB2hz0tcsr|DTy zAzw7ngl@%rr*MX@v6j`9H=Sz!%We#@zTmi*lBy~aKk4_Udg6^rB-Y*8m(?e010|qo zFu-OF_WsRbCQH5E3qTh^)wUQGM6Q9IbWkQ7?f0AFRDl#iLP9jX7hULAN%6-rm%N?( zZpaPvx=Apd`{xK}+_v?Jz^Ypds=14SvvV(^ZJ|>)o(&jIferSaO!9oLkHDb__6B~- ztzItIM@tKMVYBT%7P?>IY)9Y+gnU-}Vfrw)MrVn;3YXmvJGG`K1bbT?rdo`jT04rP zcNFx-wx)uuZ5NXLs=WukvcK!GRP!kl!5t2hUjD|m*CT0zyhtYNw71u0EbK8fd%M4n zgmIsPYQuHRulna>kocwZP)*eFveQ&x{We5GEtN$cYQNN6Ko!Da6;-faXe>M}g85vz zX-q3A|Gd1(fEL+FX~=G&p>l53zzS2SeYIJG5{3vpbbnDYpXs4Meq^YBbtfY5-2@t> zGLN|~&0*~I7Jl;B^W(uc{*|ZGu&C)0LCKbOPw&0o1X}4|Ve;dMZ2bF~8OyfCeg>7K z21bzxd3OKS@2IdHlT|qV^H?a{vDRcOD7ohWX|EM|LE3QX5!1Z(BZeEBk4JEucJbmg zNZWMixn`Qj`r$n%)y&bd5ow_R@pQ&Ja%}qrBeMABCH_|u@6~JT)JsYq-1ZxY1T;4_ zLxZh-HxZxj_tML<7XQEk*CWS%p0m>5W(jbrZe})w#-vOnVh-T5AZIZgIQbI;I8}A9 zR-1d8TYYaoj)UyTG!v&DiRBAw;+9C{=}(8h3ek@ zAh!fgXH&0}pT0R%d<|4UC@%XmI3`XVg>PCkE3J>aOFFppUvsI z?I*o1DF6c2OxAwR-`S}N)q76gv#uZItKwi*46O$z?}VY(i(J8K%(@bbz5 z3DlzV;}sIy`n`lCQ!|tIkDaTI6{L=doaVZPrV(To@r;(KXWn>Y$_t+BFH@1LDz^nn zC+IUsixb{Qt-jA9Ef$LqNHhEcW{D%o;YHx#!*6d3|790`p@WghV$xHUeXl!L4(FAK=wLDd;`d zVB+K7ophmx1_#p`hXe-;Je+jp)n8h$10>55>c|Gu(ye)7CZi z&3j|Q!oqy^m8xZ8nFTW+W*wj6?CjN5ZDQw5^ipnr^-dr6YVA>0*`&W)vW7?jtQ>5_rvth zU$Y=|i2*lPw#%x=3u({=#cz!Vr)?u4VbylGo)o{SRFwnwJRZG{*BOPK>uE*}%f8&_i$W<|? zgE;=R-bOhr!TcuS6jQNMdMVN2km2vI?+5LU!O>FRm2wMbtmH+RqB%WFJ3Ls%&rRyj zq*pSQRo<-4yWm3oxA&EO-9o-mxBBc{jO7)fw`UemB(Aibn~|DiM0YsNeF_W=r0_8s zv_3@*`7dG_HI`9MEbXyH0AhMgt{R?hJ67Y3{2f9J#6Wj&;mQxthL7Ok1@>(q=L<9F zuc_V8>$8x-S-t|merTPeY&l4heMVIi>owXwwr0zEK?9Xv@t2cmgHUF)=yylJWUPEJ zNR#OQCFMNUTde>dU!GThoZJJ0HrED(Q0Tyl_x#-2U+ZJ`Cm7wNw;>-i(-ry%M+V{s zZ8(5crOyqg{@7|pUy@b za^dB##ZnnSB{ zS*J11Oe)SEux}D-lf13Scxf48m_j5cZ|0?s?y%6<-3OoMI{sBrU&($c;kf8VG`>gj z{bLi;)8m4B6H);&uZ0pf=jaDr7aIMy7|I8;x>FbAYDGhB=lv|HVWI9@P)tkmJ~ojq z&7I{syR4Ye59?J~uLodov)Cnc$txyb>2j`;Y-F4nI|bO22XP-ITQ{qT+h6{sJtpKXRvD z*|^qPb8bdb5%o4?U_C0=8+u_WZRn%PAx;REMCsDrTrG4#rPbQ+Na~Dc z_tE-2Pa>&Y;^$F9JV@p}3|{bk9Q;0(!x0d%4NJD{JXe`fL=|hdG9tf98zJB75)_ZI zdl5eI9Pftq4`l3#ZAB55EXp)M+zg{ZO$6ym3XU$mIh=c7WLpN9N z{@wEO2#~)93Y%9@-TEz;TKFwf3HeOHVETIJ1A0PJ;+2KjpI;M2%E<{gPEGmFPDk3_ zjVEy8Dey=bZQatgY`NiO)VBrzbu(#ej+P<6iP7u4Ty%6(=07_5UFnhoAi4yT-BAl! zb+z>F2a1)o@O1*x>?lLyK=vA)?hD<*Fa=*?slv>(zw}lu;b#~i-r7$4(i0N2wE>5Yw^mXb2+{+f zkJhfll9R*V>n5rK6TDj@aMBq==3JleC9~8%Io@ZGFP-!Z?7PE?WQ_I`(1ADQkJoY9 zMZv-GodT=?$^O}++@_%X$#bk@-v!ohPR`N~P{9VrKR-V!3p@8JLYG{1eU`evFPoau#wwBUXh;L59UW#2)bU)` z(WgJY8?>)g-glHG&L!+0HIg?bvMyu^mTlz#L)D@^zksb=ExUUCE3Ks7Ki$p^fi{WFd(J50ya};{y~Art-XU z8+AO^wxQdGk5x?eV(>BTyQx?R9FOex&Itx>?tL>c)6o z-!#*vMf&1Ryo+B$PQCP)RQy+jwRf}ri|9aZ$7V!eRLt1$2Em6lMkf@Es!Iv01#C;m zZ^fDGKQcoz%54oZBNEDK++&Mtdsif0>xGEZ(<h zeW&Im-FYT=myxCclbU^P+d^j-KR+Ym3b|h^LKnGyjI#}QIXrIFG)*`dG*(LJE>F~W zoC>m6-u5oEBut5Ko-J-~D|Q@xP5j)BgAQs9z*R3UO9Q3QUk2cT8cog5-hQM{p*uEy?!zJS7ZS?}l zd)*M>_iQi$QQIH^_M-Fm+1VR}puf@d3TZ9)S{@+V z<9L~um%3oB{Fl?l#y2q64Twy*_9BByfj;pN)9XFX(f2Ip=^+RqGPN_?2*4OKs6~k2 zsv0}NSM+psE&3(04i2LP!!9=?zl7+Nx}5^qF~&yZq$U1#Wdj*UM;(I^%n5tFlQ9@N zf%`p7Z@EexE(%t*VYc;&(sKrJ0-C24zvR8nHjlAj2^SgDMpcurj)%>*Lx1yL7Sq9O zQaLa#W#Hu^Aw1M8Uoa)t&b%GkdE~Jn5^2i$8JTB4DQDwiK9I<|lPQUm~^f)ptD!X)s zr>c57_HxdF7@Mx^gx`J;DM4m);u-Hv`Q}vNq^bua?<$<#onqul3*9G#_i7Gz+Xl!q zxXdkFRE!)PZo|nINERvQztbu417y?q4qs!3L{TC#!q8NZf6jU zAy+>GXP|CpMQ8s@Vn0$X9CqU%1HrSl!0M$p$ewE<9x+YscQ1cgQNH(e1+}Ist_?Z{ zL!~1ioa4!MJM3`X_{I#MV)Wj7>%8joT;se44<`)=8C?ksI3|QN5SG>z^jyT zO6AS1yQ^~yP2h9B$=9;_-uk1MGfg2!s*YEHnp%Lm$CB;wN{1+b6XY-V0{QAhO66L- zHY*pO7ul)UISoeY7^~2gkA#n!OOh?k`2K8BmEjn%(~2_B^_RA${+@iwqd^OIFsZ0Z zn#7B#eDpefkWK!D7uMFS#6@j1&JbbM5ur%4boYY>xz;DRrZOVJ+pw|c*m@IYkIZ9< zT}&QkRCVI0Wq2HH^WyR1j&(*k(j?$eXt)0e1)KN7o+GLxUe9pGv|cKrwFLjoF3EI< z^ZIYBJWCIku}5m*#)qPj%1GpNu82sv=pq|9k=Z__*+F00Ze}=N!y{vn(f00%#6)6t3UX_63UCtvgUI78JZSF^Z z|5-|zxB_viK-(B^1W4nuIbykVQ2xe-=EvqSa?QNxEh+U;2BX(X!KtloOX#*cx^<>E z6gm|{l5jZ~k!*n;F(LmGj{rL-@9@yD=}_s3@SREj24x5j_d8?5F&$;Am~U$Oxg8G8}} zKz(^t#l`Forc}EX_{+c>x6S(W(%NGnXVyO1I1#fjaxk5(=jV$6@6KPcbW%ZP5BZ`9 zuL8nbY|ln54P~dd&9Ls$Js0hMQd`*78xVbP`cvE3X9T@CW_Di6a-eDn?>?a>-vQM zkpgrg#@;1`G+?hCg*gLG*9WH)oTb58Bgd@M=ak) zCziN-yYQ7x{o2kE4>fxD4SE(nG@kO*8$bK5T1q6Gp_qVDSqc zdqiYpGP5xRCJ*%DuV|T=4$E_@C2@0vX{a}o{Gan^Xow$1-pG%*imi(TG~UmZXD+45 zlU#WcOMUzg!IDj8l3CY}kE#^UFm$i5i2>QmmT&=XtgQPcAKgEPu+{vso?`oAaM#Ay z^8LcQX|yfk%svzp>SDF{CH0kRWF@kisdDTsdAGgAS!CiQBO~WX$fYwYZ~?M)`8SkH*eE;BLssHU{9kojqhsuuR$e3tBWlgxCl={dn%#EH(QqqNNmnS@KJ48gLlHlI@sMb7gBi3c-JN6s%%0 z<>UnXwIU14S{biwFzwWsi6??R=h_Fm*I`IvvA3D#G`A~$yzkQjM=%n4btakabk6_q zMYpy@BiPJOO3~JIbL?mJ*;yV(S9L1_kp0KQB_hWx)!g8PN$kTF28E|&$e(?PxxsGw zXBRFb!%-Hsa`h5apT{Do_4$AzxN8NyXP?irG&YSgw_#RqoV<^h7t_;M6B%r{9hO0b zW;sZ^sV=sdNc&msN?zuHc7FFrep+X(barnx)C6TAhTeaaLI_w}`&e*9c=Nh!1Uy0t z-Xn7C#c7zVFeHcBc0EM7!y7se{JfXy{f^?%{&q2JMkzd>x8z`HKr_SpfBL*9>&lh~ z=gpq*LU3_tQ9%Vzu?8CuMy{!z_X3FQc6<1?d~iw3l7e=@VpA9wldBF1|1udy4xEhj zWNtOziR%R=Pu)KfO0w1}V7|y@^pWVN$Dbe$T?g0cw4 z;ZC^R+{GzE<(>&m&4;ivXHgX*;Yx?rppWPq6>F3_(xi#2!Dg! z7@PV2%oPn9Wjzz93FszUx*BJK^A~Dy zB9R&2mt(cXX{~_Dk&@DVuwLPTv3FENwp?N?w>X~g5`%L3UgNLsm+>?bMP4B5U00okv zBmgn+zo`~IKGS~pM~mlm#|jYzQYk3*m@W@*&;zxi?vV@vbnU6jnl7ckcih=?^P3-P zZC{FzOXPpz>Q{o@H^E;X+o$YME~3IrSRuhWP9*Q~0)0~Vnw*?7DEFze$jTIG(kO@% z7jMh7;{b>6#3x)>6mVr^7`{XL0kGK4vY2(oz4n(4H!dm*MlRjx=`MhK`W)K(7R5Zt zOmghlsR;(~T;;?MS)as59dL?U@&7?b*uRJm6&BBvKr0ue09ndU@H^D`@dU|!b#;@- zK>pdl+{+K*nJY9;TX}pviToWtG9!pwUh|DB+E@GN;AE%Csf~ZAPz>qOK|(!YeAhr* zyU13yVF4^aA{gnKi`|^m2wfQ3aRnu{>M^T)*YtacT=PBWV6dZ+z%RT)iA29?EEVE7 zSw+t{Q)VNel-9Lhp!M7+nt&&Z5JHtJaqC--%Y$2iBRMb6Dp_8WE4D2tX@}*LkZ1+> zX<&qVb4#jR4;$)c6E=6i?>md3v3k9s3X1=~ppaERWcO`omlY%_)6me&+B=x}NYkbe zyvm#b$=WC>TpUd7tk~QcM8rNl)Qb3rjOyP_Y9HUx(_3E}Df|%u#e2DtSlJo!MQ~R4 z%l9U3dDAAh8w_2Z>uxLF{xPtxx4&vC591{g+iAG8lGWZ9NVw$q1BR0W^xN52kyw^>f+pa^zyE=~HNO}0=Yf+|2gJd8V@#ZQH)~T>( z%3@RJ{z?)yK+1$W#kao)JWoLljy@FUr{o2ukHGd_>XN;MA6U#o7_A55{k7!HkRt}w zg9ncvawr_`B7Y5RO!CzzNSI!CKoo}~efFObLu>7PEjO}ljFwC?Z$|x-{4O`wEVfb6 zN-HQ7U)0d8?|c@vHDaSFi3)UL=;AA5*w3@*c%CTCny$E8O(8(MnGuXzviL1%({Bc{ zrq6*6P>7%M%CI5J(THe6JGakx-h#>T&HKv;i`roH%9gXSp~~pvb%ufalP4!U-RFmr zR|LQQC+;D#Zc*Er(vX`@36t;Ncj*@p+}^-uvYkj51IVH77iwIQ97xU~byxf7Qy zHf#RNe1kT4iU2!s?j9s6Ie{;`=E*0+FlU=S0~`M zwo(5HG-+vRsGHwcFVrso&rYE3s?jLn;UQz=GNMk<=`ZF_<)<6 zn{z>e{#U_r7j(Z!^OmT zKfQ!iNZkIL9yXxy`7njTnwsZKLoacyoV)gV&b`2;Q_gP?Hh7>0UFZ=P;%u_PHOm+CrZUfEd>p`EaD>WKUKl66Q zi3d*3$NmyUo_+-f_!dnIu=>g9H7c3N4W?g?Z#}!=&2;Q%XmgcXv^Q+zSk1k0fE=!e z-lh9KPfaPtH!RHc);)e+$XrM}8--RWZ9GHYNdK4A0o8sSpau?*@R zH0Ya~M=`3O5yxdaH%XVEX~4sZNQJ0q6#a_vh1c>Ar}T)i5}CHh z(_71kT&rmK0B^)@IkpdYBm@1m#h2cMgxk)VUTy9GDCz3A1SRnvgU6K?Guo0d#D=N{ zg!zQ>yRBMi6-rWVVup>vyjI{J7hKTX!hGW%Rg# z#tZ;Ng09OGB!1WDNs9&OR{~G->HI>x6tJ=L#xoG8uV_+$UWND?jw zz4JSbyZd`{p|&AJV3oh#uPZaVY(=l$9sDZ+zGCOTp^408kg0aG_wqdWRdn@h>7l3e zxzgzDfN0(4Ev;H|3#rfieSKb*&exVd>;Av&pSKgzgzvMY6bGohyowqJ2c&8DomlAd zr1cjUpa+*8jwF|1+7Q8{`>l$U4@5^&|7Q%(i9^P|Ii)3^>cF~|i}Ub0*(Ic;iS#ODak8^nt*r1wEp;A!)|RQJ07m6oduWKUWp8}gb5m(H=~PlU!a zKV`M?$He5eKO;V6ns}IB4cc<`n$N{5{``tjDS|{zmK~;AqOEOvN*yBafe zWV*%PB0#*uaNH{7Dyd235g19~LSx|C_u2mSyT+Y0r(gNIBSM!~*SLlzf_L1zJ&Gxv z`Kb-ifmnV^)Td0LDag=g_K`I3kxgd80@=5@tk~EoRO;Q^#`<7W;i>pZPGn|%=y2I& zLM#9z)a{LjAP)k#lQn5cBYxLQhsqi;1fJ{3{+4McJ6p-eBq_J=rz-uQ_NpF}A8*0V zWHuB)VZ!GbtmOvF+fJzcFz=E3zIwvZ;gRO8lh?shRiAHYvAMCW)?y9Vi(}Av3scZvIKafjr(F^viwN_)V-!tyMWV(JTsN*VTcO zJ0a^)tDG|@SdyHa-EBryNq;h3-)7`oI@>O^F2^~T@I?RNv3p1<+%+hQ|HC6sih%}~ zUBN_%M7VDXNE7)_r}uP&$r(QE?NK;zu8GP~+SA3_6l_QPX-=Y;xuwqT()SXEro%q# zHv_ed1F3tEHuky0eI?MzoL?etXKHWt_pKrC`M0wsV!V-F$y3tAmV^)FNtB3Bb3OgC z2zC^3&)hJ2ISB6|q%(6q`6VI+D%7-7w@mTa|8*R?HK%W`Nb5dZd(h3zghu;PmG5F} zHcquG9P%9SqNGBRfb#mwc_iYq4%yUvtt3jjmmf?ocooj@+{{q}OZVQ@3V45$`{42@ zg*tI^&clk+CX_&gP_XZc92wK>t^NoS#}8nyv@I|q@d3ppyIH(-(E6#L=X6m1En1mb zJEvu(%}pvE*wd)UZRhl#wSd%kf5925YAD4Y=aO6Bz#ObqB(}owTda{XfvmwkGJ|*B zhtbyl^l_ryH4JHNoeD2#2m;hy=TT1mu6u_Y!4<=yGTHL~d zCf)Pv=OoUqY_c5{%V%~YhZblX5%4yef-d3@PhR&=M;bm-1V_?*_lSDn8r z(l%W25*!^w?lD~F-|n_&23;0jBR~{W)6^8zzMd@=Hb}wap_Yk^|1^2mTlFxVW$Phu z4&A0dFY#mczdlk5d!E-uppWim*I9Z?t`kn%stA7vA}v&2{4@eOu2GaJodF zNAp3=h(@5wKma6FHQ(Y_l$FXgRX+EQ-}hQfi&XO-G1m+Q_D>Y1yt${zOl&9a=uiHC z=z7bjuGTMVbkj(KfHX*VOLup7O6QO6mJ|?>?iP^lPC;5)KtMpcyZhaqbN=tWAMWLY z4#sde#@^4f)?RDQx#rqpqwzxduXoF~v(;(pFg(2q$~3;q?!K8B_LY^mNBdxy zicYpJPl@y(0qP|LG|Jm2?T(~?_0fc);u&~qqThOKyi*%w77rkV>Y5gf3l&`Ye97dz z%>H>O_X>Ewdq0SS`PvOP+wS!w0EAuz)4cdKdr$RsFO@0cCEjfeY%we~d$~%*2)+L~ z1pPW6o(r-|RxzR$`%}7#VT$kJ!`nK7?TMy4+~-GS{x5wUa))uwadIn-#kCRm z995TibPj%_;I`ErkLS9~Dkma#Cq+GJL%%_eQ7-@6o>OqQ*%}Nc4-7)>d)f=->JGcU zVx8f4!uQWv8E0k#N;#~*y(;n{ZT7u*ix+3oIhUf!N)>tSTt~qPQ^p}FKCAs=#U)KWB!FUR5nfx^Dk-$D@BSW~tI;h{ z|J}JH@a5k7`tW!_%9k3n-8WMjABvAp>U|{|!Ubt)E|-@r*)ms4p^Pt*OO|QKL~@@3 z7u0IJlbS4$kt}3XtPjpRIT$_nsUIGTGSMz;?#Y{>g8qQ#Ns?e5gN42|MV`d<2J<8>d`cs3n;H{--vK$S@j&mSr8QN?Rp;j zpBCVDQHLMXdNm=-ZN72C-OoFW{;uW*v%?o4jkaSJu;>d^e(Co;0s zWTB&@BOoXq0)gs$t^wEC4w=!(1d*B3Aps&5MW@s9iyp$Pz8>0k<&uO7bF8?d;B848 zLJO?}g1*ou6hi?T@3Iv#P%#VNwn0ktFqGoIU@0d`brKcnd=|x~i`_Us@9pfw?$eQ@ zARhC0sKD$@kl-USwcJeKQBOZ?Z(qtuMF37$eAjMPko)p3@qwzgk;R|bp6#83xk7RH z>dAYnK`=N(>1S5Juesj_GhpQAiv$(h=#{_#8O2a!{M_0pTa#xvB7M$oA}~FRjdnX@ znGyd4x<_{O-#~w#c7J+uLeJ0oA{W>7FqS-FZ1#A&!|i|6tE;{IT>fHz7+D6~FG?Hv zTE@0*R>@D4XQ+A3MjI9-N)h`aWe@}`GaLx{Idm0XIifE+^&gIQJ!cQ%I>c-6R_%|s zUzE(FzdY`scWn!Pp-5*23&kd)oMbBGbC}*Q>9upyq(+7%&`I;GI4HL zxL0rEngiLEVS&6dy>BB^vHy;GAm+QOFE`jcF~0#m+1v4}-T!u|HE^FD|B<+OS$plZ z{bS|Wf%$?8;2~P?M-_~8YH*(r_;3QHWiB)1t9QAmAqZBoiEHDeiG-}rR${GCp=BCZ8(I>N)l>pMTW8oJyyXKNq&cs-PnwoEJxJ!jQh zP2?056x4SjU24{w_DAjS?{j!Q3qYV@|EXT`&A_;6)iz!}aarhGIpg=J7@2s3N8NL{ zI#gWNZJZfdReh5i*!8mPS#o`CIgvJ%r8L;y&MP{(vnd1A*rn3p{X`BX0f^9?!9;8^ zO7ua8#IBZ=dZvTd)#G@fzOgcf5_>!^i1N~-G|~x=l2+APu&BhQICH~IN>5crHUURc zE6J^NQ5K`O4Jxtktx@0;i7a`u{jgpuJ38RdT2xpaclYR8KGz+enmSl#&x%Jm+%+P% zRy#Q7=3WE^EGs} z!JxKqW9Q;dX})xP3JFA4{;eZ+4Yc~47jIoz@eGo4(E+M>8O^}JAQSrpN;Qr4B0WunC7oP9M#rAWi!|Vi!?24Z^g;SZSWTvgD zZL;YjLz9zrQshFRfEG7C$uAU?CQ(RGHF}j~vM%iD4YCPYoGOXp4)Q;@qD~gfh`1Df zLOVci+ls=fE3knAlDJ3vpm47g9hecmtkW^xM$H((Lrkqb@XB3JsEou)EtmyW{a ztB_?O>ezFIZY4VG=}9v%v8%dsC+S5^vI>VcPRSE0w- z=>I+OBEMmoBJG-odsc;#}`2QTPAD|@SW#>AuoSxH=fU-KMg zsGgcG|8IHCzuU_rJ|~u$#tlluuY1c?(?EvJMXFbuAUqQ##Y(72DN+dVmrP6@OT=Rh zfej6({r$BCO>)Qk7*{{bVWpPzyNa7)GS}{)m;$$ z10wk~--eH$n|pq*VbMN4O6_Ic8IG+zO z(Fv|9_fH%-GPQShn)MkOvc_ZaQ(9zbsHRhrfF5eu)J@Oq)P4ERGA%?gSxRUiIXSrR z?emf2@r3ZiJ^?KT?2`zsK89QTSEIox03&+3L8%dMV~gTCWiue)EG!3Fx`4z-9px1O z6^=<4^?FMp_{Y4cNHsbuiXumLHdlz~^<7IW8U=v;W)MDAQJNfd^hZR4oeb#Cr5px} zNaxz;r<+1?2Q6eL<)J^Xc7HU58aZZOd)c|V@?dKNFd zmRY`G_Pi=JITTEzR7TW@YPRF-JopqQ25=v|X+FM`BP$RzmDXe~N-jEJra=xBk9f3H zVrO9IXx|_$?jk8SNtLAXO5K2nfjM@nRfJH(j;Cny-n>b*-A7bZi(V2Jci{Caxy;sa z*hzt0B5vjelfIfCBf_Ahec!e(hWkA5A@k2g(VzEvKE5umzl#s#HX^Kv^eoM#U`Q4& z*f;1PCj77u_-ev4K62q?z9<*ljRhM4@;keXy#V-}|3)+)l>1Dv&BjE&ij407wX8U3 z0nLhMo}$>?a2k)eJl$(oKVat*y^_s&xN(Md!pI>kO@f0=)r@svnj?QzD^|EN!s?T- zd6yJhRH$l5FN;N4N+0DRrkemO+P$Nwl&a!GSJj?*w9D$@h9?=HB%7e3p{8}@QP!g4 z!h_Wp9;x3Piz_*@CZmwfo;N0HXE|{Uc94zGy9o(`OHB~h)-*!L%~Zx$#7%xMu@w8@ zN5Y^AE9I$RQkO88MBrKA)+>5!z$J@u6!@I7wc!P-b`CTC{ zhsjmO|6SqG*ottA(&0p?o&d7M+36jRdT%Fi#{-AuZL?$Z&-t6H%Nh=dVAwq#P?6{& zK$19U24*ey`>dTJ)$HKfQgW+mI*aYsaCcKCTBF*ZrH&|LgZ7mMsf+CEM4VF)MeC`8%KXHkNI@M#|?fV2K%mtCcVX_Xn+h4 z1u59!+UG8ED`JpRbvEkQGi%!@#m;QekBzzOF>*x}aBNH%IqF+J>b^#U zeH1e0!ITUrCoHYv&;XRB#Sx!+VZomWQvrYFtF~R?LDJBCW+H7VT5cFQcQ-rvej?#I+jU^{< zBp0odZVuVDo4=QbqyDOg10mW<2T!-_!>VJ4s-iG-)=z19Lt}E826&b{{#uL@Uto|r zo#$ht>Rf^gKFLkXMxjxunSP9|g&Q61dnfv0t4=aixUKx_C9pIrOG(Ww!9+46K^+!T zrE+el#hI{gEdapdX8yToJEg}%&j6RBY&nn%^?q-<^EC}Y@7ks6^v8}EA3MOz(jXN(>3Wo?WxHO8%< z7WDtuQRmk?p5E3+n8YRt!SvkiJb?GVEb;TIT8#UMuY{;wIWG&kmk_VJZ7$>MNZ2h8 zX{bE>!LePxu%oa(K0BqN|hRuL8V|aEF1PbCtO|5MAqcJW{8}55mjC2q%6_| z4KbRkaNZa5J|JJEtbn$TY%ns-9Azd!!rcw8MES(-FWB;0q@lRDyF;ME>x>ncgx*!5 zb$h;BF4r#c@6vE@T$6bsbjs@$BP10XpW4u2ga%OhsIW{WC2;^wt}340tfM2`%$PME zxe_y8hf{gR!B#o>N-lj`j9<8jJ>MFL5tYTv%*;$o@<+GIN=t3*?FCvBL6HZa>P`TeW(mE#7+#d4Ar<3GeV8l>ELtVnwt7XM>l(A6OaGlL*R)l z6!6u5l%%7@HYt&N*QT?`X+K7}^YYS@CH+rbT}31KD~m%Eam!Hr{B^QRmg7ePfx|(j zz~|n_``W%EYN^4r^HD4Ro15HgQV%EM|H5LN5ybQ^9~z%yD2gVot^y?ACKbt9@)@>}?P1cTL*M}a@p-8K)*@fBb5=p5b__xy%)zp-XFHqG@K#UgQ{Z19x z8z=6~KVShtHt)nHSv$jv;DE7sT3R5_?Zd3md#%NwQ&|R4kkib+>Wjz0$v15Ou^1*m zGSlKLT0KvO=uyzbL(Zq zMc};+7BKCr#dOD`cd=_XDr|7J=-8#7s3v=6S{+}sE~&c9^-dcJI2)v4jA%r@e_%fAs?t+N}Q3^W$Z;V_=8nRxiT9;q%ee>VtGDbe@z))t#62nx~P`^|z7coK^*+^PZ#b zlMJ7U3;7lAjnw+}>Q(=lncPvQPmTUXL_35op>g_q_lHmJ!xw?q6BZ0B0e7_vHJ3TM zsRFfcotqqy{yoY|;o_<)CBi^zU*EN%Jy(k&CsAFN3(@_j%DWW18AabCJ=jC1j{>By zLB|eg0IcZASsIVh8q=EpgO8tcwyqXSSuRicu|Rl{j2axEse0LFp3i|nBEwk?e)fcm zx&tA6+W5-QL4%2=!iOm4<&~8w<4Pf9yAtu_vaf;9N-}UL78>k$KdrPH1N^VS0=bz# zBRRQ9@HNtrUQM1ce_kowvD7W3z3u zU1RHFVcDAR%hSmqA@}Gia~>1`E@FxvubvlwGT$qdyb$2%x~r^C{>U3A2uT^##ZYM%3Uz_c`o3IyDumhYY0~xq$2>5k`ENyoxYhI zd-ayX36q-Ix^X}Iow1mR@>Txy++LVW?>v=29GidHw<^&T&BRlB?<%D9TOyNA_c|BA zO@>q&wtIjBzBFzWe{uHyRzaxB%S!L-6y4WR#7&I8XNu7y_?e?*e~9+KV19{lfj9MSlH>r);3J$-B4 zNp5wiyA8h2byT4G{{8KNSymP3`o6qMVDe+M{_8g=QQqXnCr|!qLYFL3ZtlHx{MMkB#Pjwb>XARknIx-o!b@j#pSDLCxLbq;$`Ngzyno#EH zn|D7i+mxF5^%BodNKD|sSv(y{R40SBWz#b+1z1s?$_EOwdR?UwcNmyC6W#T$uEUlz zLnD%^3T*Zm(%?Lppy1%~RO4g5ORm2~l?CE`TIQ{60?+MeVUnXYBiB+|8GWS{g`3QX zpU&c}G8NCjGU&jyEAPRqEK)95{hM#+1LTd+-Qha2{Esu`oR)h8>0532lo?n>(qkhH zO{xml9Q~`!%OAMGp|LDKzvageiepq1+D~tee4|lBU^xs{w4 z1rIARW5@?w0041%gHjE-WQ*X9={?STIfD-Mb9@~(%dYL|E4{0F51YzBitH7)U;Lf> z^aoSTXx<4WZ99aoZ>!)^1 z^3ciDJp;77Eki=Ce!1Z0E0#_88Y4_vO2}uX z?^@3VdvtT>lC1>fx%2%+Qo}bWRbheXv2A*~g}L7qhI*OCLXvuz(x5`I7zb?jCh=XE zwVhO`%tq6$xpM*nbj?PK6$$m*zf*kaH=p7@?qIhYqtFgK39~4l@8~`)?dFz!Fs}R2 zwd0Fp7})Y$hG6Vtw^bIG+I=>-`efxv0JvEsZ(J@t-~S4J@w;4`PJI(F?Ylnq2G-bU zO(F1nUHMJG&kpCAft2eHulWZt=dZi>zLGX~K-MM#p5k6QUY-djem}+-J217ajq@%H z5}E!_P@uk9uy=1)4aekv{g8QdJuUNP*>spl1q)64>ZUn!Y%lt2H1q!6p2-BiW6uT~ zNG7Fo_&(gH^+y{rXm5K9NJUVv`Fh->u^j$aP^@;xN#9M@T(L8{U>l7fR_N97h4h8qyg(=ZUFsE0cQ z{_t4LS7kw#!rPbGa+Fh2BcR@czQ#hvwrA^;zgx9R)DZxs5{F}h1GX6}o-bj2Tl8SL zjK@(-&ppq3TT^%<$n(8vds~H!EYg$~83PA)q~1sPYb#dAZI|5n4J$)CDN43H@pQWsl}E6tXE@G3<1+t) z#wiTzAeV3;GQLg2!6YqA_&&3|T(badtlJL%-nTbGbPGOKx#Ur3J&N(nyZ_z?+A~NXSUO z4Wd*7wl(Ac8F?(gOJHDBJ$osQ5ukk)0VN{e11Fj*qXJA$nS8Msct82Zf@X#sk&*@~ zf1ZIz+QVbfoR=sv4XSNteEH`2VFxBii!Z-_Y%wK7yf{B@y+$8XuaYae-?DL$Qq~-A z{N%>QVsbE1=tLOe+dgZFi~!9zIK`=W;Kr%Ax{JbeD`Z%NpH3bNI`T+H<7TJ0 zf*cGV_Wy%I&&VC!_f;fBWLG~tKfk-Suigq=$Px4f_j4;f2@G$odKlFntR0mH{1Hk; zxSmQi?~lTnot?Ehe)RVCwmRMfzw{vB*gbmGyjt~+TAi4f7#l9++_>_rb1dEH>y}z#H)OY zqrQ7ZG5F4Lp$s}+t5ie4L8+)<%39g8*<wf#x+3%C{m%G$quo3jn$t zhHUOT@JG+Jzd$k?1Zh&sv4IAV;IS#3!a{-*%MY3d@f`h&v+gC_%*ui?B;a?UbY^`W zK!$}fQilQrj(bsy9JsB*Ojk?ZLU!N!*|^LY@?$aFM07$!oNOsm(sH;Xa>IMhyp=O0@Xzm zXc0XAKE~{_RmQp5i4-6#t)~wP4F!N2`^7bx%PTe}COLYB@SKLZhzT!oS<$TL?$On+@91N zl=v(tX4qvD3Z`VF$S3Eep@takN~^BD1&Tj>Sbw|9Z zFen=wcybh&5JYf!h*7YL@DnFLK~Z@*0xlE%;qf*A!q;HQ3>LHH{-rqLFg>?t?cn7= z28ex+Os5e6SP<$}ba(JyWv8RBu*18%HHdTT>G* zH>Ct(KF4M`rbuEe!y7-Bt>F4j6gR0|mSk6SWvY;*Uq<{fvVX;EQ&X1(k*qp#<))Y%bnU)zQ;Z0WbW zuHs^2Uq&f+1vFH1zM|a^zg}Lp%L=~3KxLTl7@3TG--T~`udR?Joyv%Gslcf>FuJwW zx4c}TwH2?6^BN~Y5dUzW{UdqN3>~$4UG;>>Oj*HheLV&6=f^gR!G zBH>80xo*KpCVt124lr4nz=LE)$-FiNXc_Up>wwPWuSALEQO#}5)%W2E9>&MNep%>t zsNiCKD^=>gAlzEx&3#%hb7Kn|=Wh&rb-eqbl$Z30lw}(CUpJ0=I=XZkT1a5H$RmSh z&F^)&uqk;myV@$&FP1A^qGX0c8D#}>H}CK;k8b_Ulv-xwkfJscbqaEQIw4-ILWdsG zx?I^d7p%u}&ckk(`daGoh~=BpViTU*T0Y+0&RG4W4fQiK8Oq9fKLEfaC!}`4S{EMB zE2-ai12Cebz(UjrI7*vA{P(WxFf^3wH=HdHc0X_KC*G|w{V$Dhf+HgbRqa(ZHLUS6 zX&xtY*LaMtBIL>AuVEfgEkTy_ZU@|Eoc$VQp90fIJT-=Lw!>z+27le>Eq}QxbkMZZ zFKSsZ+4y>-_Pu4+-?p|{151%QBXqz=60>kmS-)w7U2>{yfw3JK!NrBLIs*I$g>M(| zbdDyMT6gtX?!G)NTN3BDS-y6DdL`U+SurfXV^=R2IFq zR%PBLbwj*d2zrt;L~_YY8H>g{a5wo*@W$(YI3iMzSYJ>_au z+n(vG>W4PzI8Msyp+zzm9<#q!*^T*%lg^B$;D8S~kVTYXA_HbQc2M12)>8`GR))*BNiUG0|xgv0(1YRUp@#vMEwh7g|Qn~{SfIG}ts zDbvpLFZ)cWIFqj;f}9-}c=GM7Sn&JWg$Cx>P+HJolRA&CaLTrxEo47mndQe{3PpiO z8ru3@-4^Kb%{A3u&(}F+#CcYr|MKX4ZqI_0%_Vz+pd9!RJk?4az7e6E^DtC5{$rwc z%YT%#(=@B^dpglZwa;N^)#a2@{X?}j`aIiA&J`^H?Dw<@{}!}T!<=A)_qADW&bj|p z{dD{G>dY{V)0y@7TwBcQn)*L->SflU`{}x(f)Us~I${DVB9MBEKohdtKX}rzqhAqK zM7@L)p2oME*&s!6L^fwKI@D{b5aBQ0Z+d@a_RT3L08-f5o(Vaj>TP~pQ0 zfS#cb-@eKf@J&jGL(5U36v$M*`~*Or_wa_Urf~88X=}bJAtBM|ZVE(2 zZ~+5mZAHZ~{5Du{@}`=X20Vq9%j0Or`$VhnOx;GeC(T9=%OTpaKN>B~1h2HE{FXUx zIwpCq+q(@fx66ey`zm}~Ruox|RRJI&Gr)OvR=HXGdA0l{VC&l%f8e{DePc&nvB;=( zeZPYu^mlZO&VTTOW&4wAR|9OP>MW`Sz41F9CTBf6+47(P!M*1q#W4iVE|(?iIiZaN z+nH3C`hW9l{)?EqyE_$lr8_%2!&R((l+l3-Cq8sy@GApWa+mP|%MW#RqK0!@23DhV z*|-M>W(^ql^rsKcpT*!xtN&3Z9yB`GEQA+c1vac2~8ajEQfDdbo0GO-!vI&s( zyo4Hkn{_eV!oto>`o3Fh$QGGvYLa8>sv-hu>|qd4ma$h~{15!7L=`d@o~N5)iiZVY zz4~j&OW5bctUdhMHg-eM%J*Szds_h>3{jbcpK3d>ox;>Li}rIID&J}Yp^U2MpbYi( zqw&Fkxoq4Wi4g|J2kS;*yJOOqvt4@-UD)fzs^5G zF?yWtzQa)2rLxFrKRti!zuoMqFiakvqmCMIT@pd^{8U%G45KjBa6s~OlsF%2+TEcq z7J|PY*lNOGIgbedZ*Yzu{&c|EaTOoanwp-l+%6ZJtm;3l8>-_6?X|8H<0I!hoK^{Q z5uF>0L{8*(9Usrx;R=y<-W?F43)p0MoSYQfptF4CcJ$duh~x73(w(FDdb`&-5vlRb zX7h}-Lr+%(V<0j}Hu2a!! zhWlFUeO_HA_CDmK`^T1VSV*W5eVF{awo=eCv{rmZOB+o9^LMv?O?0yQvXm(vB66Bn zNsQ{Hc*twCuX<>azRX~PGevZ`bM1-H6NK{qn1D4$ro5-55aMR}okX_k(_)Q({zqok zEZx_m?(Js5d8FLTX>yprZE|s?{Yj3DmOiWEPF#T#)ILU-1YS z#C|NG^fJ?7{pJV^OPZ$a1YG6_v04f8vAU$$vWo{Qa4MDz8%ZW%*CjbzY>eg^44Y7x z4+A(1plAZ0MhVmn{3Y6+>lFWj5S77wruEs^m5A^3;K2nu9gB;4fHg=Nz19{*%zq)? z`3}pe$y1huTIu7xHdo^_i9E8>J)Y}5)BEd(w6Rg!W$wiCO=W2qHpX_{=*h#;!HIvJ z&q8qP<}~T}%U(%DgZmfHZYRY){}{Mtp_g%KN8wqF=Ot8a!8uBQ8}88X=_6%urNQCR ztN3F~N$j8w|DzJ9rAyu9MHwjmy!RPO!T?`Q z=kL3_FO9q|aZ-~>A1QDeZ;XYX@2m<>?iL)DU-rf9mooKL`0fH_c zq??+T5@h2G(D-jb;1d~Zc{S%(3W0oQwI|AMdOQUMi2NrrT)>K=14Jc1vi5F#P#Lr~ zQ&S@v1qguaUq|O6qK>(At8);xNSpWD#sS1Ne1M7tzInP9wv|8*4I&n zwk80q!9pT@!+?qkHxr_uIV)?tMcV-eb^iy~zxvz#@yJ)!)9x41fveABC(A~A0r$P$ z+{-QpF|O3VY=VB?ufF*4K8;bm1l-qsYo*Zidv5FpRqleahV`d)?gt%mio<{2voG8} zlnCKp_Z15-^X9;RO>cNV7}Yj!yn5>8K1K&Qk5)>bei)BC_FZ;*Drl#k1k@axNzaK| z5$a6nxrL>#Ja5nzWZ3KWZmz<@yJ zL@I&7h%*+YEWQA&e-uB4B^aEn6A%7fp|rUC*&-O}�(<&aFy2=?v>ZFd-9-jg34A ze_MfFB7Edo9K)-_j80!+|GlQEWtLU0BDZtM%b^UNVD7tca>tH=-$1Oet7Lp3JK(Q+a7*cX>*->v?vU`xOPq5vd%3ngYNkgcQXmK zvpG<5;!kz+!8ow|v?fs3{Yv<$WiQdw=y~|l@t~FAX%m>YLleML(mysMG*RRC4fkwJ##066wk*du0+Pf ztu2%4`Mjcu9+;%?h`{Lf`ebMc@dU=tniVXzw&?aj9|I85ZCYF`u zmHXPyl2-kojDxjtCfU~hI+-fD@^H^o@1SdV_ZuOw+hp@uIe5f<^IH@PbH{0T3XTnOCi-iRpsDpt@9jw=^c5GgP63OJ58_1Ra z%WzQku#S272AOP6tm^9#EZ6nx8IkDK_D(I2wJo!yGOSEa&P?}qU#gvbE(ePn@U%rI z{cEz&ztgSA z`G`JmOV_dW{+N>K4mKT2L_Y5M^_v^VC69#JiHP&2W_?BKgBH*SLas;$Or?T-lYf!K z1X|mORynz*>~wZ(JWhlom)7mE%#tHz(A#`BG>hW(WQZyp2MdvO|Dvbo&L_guTnD38 zpHmjt;dUAt%&s`X)7)Dm&Dj__7 zy6+PpS+#VM`eJz}%nk~|C$}2a?>@{jaNC-Vs*R4k6Z3E%`}*xet;6FJLzBZ&o%c+! zB3QuOA5L5l-$&js>E9fLi#H{K7IkW+EYHaFtqyy>y+iUW-^LLB>peour>(?kIZgV) zCs4u_)&_J$gJ9Grn#}7K9OkEYzykMltu_`-T~czlFz&qJtLNs>(BXn1NJoj@797U! zB!bG&6&LU=zO6DyZ@1SK)nPVgO0kyNjvg@J-=Pn|bh~^uURNC0s4Ig849PBWbk+o3Y4vKDg{BwBg=PeWO z?-j%y1kxLLvUx%H89_cFjOJ{v)qv{VJ5=$gFHk)v=-~1pTcikIrS%4B6E*^+Js_G7%8d-Z02$J@mD*6XgvN#qA= zA-8!r_@K=;>EiL{#0{(5$DQ_~*8V~l^enoq9e3DNeSv8kYO=<)YGpqKMFMVt=qL{^ zrpK*|9FuvbuY#vR0eAT=f;H#yD3*d?6t7dXnk4)U)qoiv~ zX5>t-vZ(#se|-EQ6nb^_Y%_D;2!YqG`oTf46&_BK%1|{c*uFfqzK#btWvx4XbnyJK z!NzPPpn!47*@x%K2(mSSO&)G;N5A6P30{S>;>}>kyDZ+r_}kNeA9>|7DpfqbJ7E*` zVzDWs^UA@qA?Ty=pf5qRYvsL0PkkU;aGv(X$4B{uz2{!M5c)JEC+`Sj~ z94gfAH67F4xp%PPo%KP8K}~-i@^PS@wEOG%8H{pmYWMofjk{&>`AbSiPRGT!T)(H} zuiif^d{=LmLpH8}ykI1Hz_|fkAtu~ExBD#a4aqXamtXcb-;u#x^=3ER=16^s?aj^N zYqJiIr7-^?V*nB|a*1MQanZz=RmXE5u+_1w<56!}hhhL*mbSBfGGI2#~G`87N|CyQwK;2kJjUSwrAtF6IBmYr!ZQl91n zFeuYG>!|ghVTPh&HvRxrRRNB6aRCPtLtw%;y*$j@hV#iRx+|CyJzO;f2re<#n!b0l(VZr6EV=siRvitsO=urC9=n#l=#-HBGh75|Uwz zqu;u^DzbZxDG<^CuY{Hy$W(anctj^J{MZ>7bPb5i7B17+{t93mqq|&gdR#ZHk7n!YoSdC28fT}cd-W^l zDk>_*$5&Kn-`Q#~55|{b(;-TbVVpkrFQVoczzbR`B+uHy1pPL!q7F)-WWz>cG=9#& z9k&Hnf89>z75|+$@Hn_W%7?LtZdEFovbW?>vRnHY)@SH@BUkYCNQyRc9RwISutm^y zaezNWoMOA>V>=hwRqELx#9$BdUpr=_uC1L~y8Q8Qu~D&_B}M|;=PBQCBHhuZS?AVw zroW%fT6MmANO|gtoAdI}Zu>ECKJI~0WpyS|Mujmmhn?y@*C@yu+p15H#MyuXePC!* znLpfB>NUt9b}&KKWD|cV)wa((gsK!aVTyVWFi; zkT3f1@qKdeL;_Ty_yOt=_5YZzAlD8apjUIC1w&^@4i7jf)SA`M|?raYA_69Wet3P2?D zxo-^sf$bu|>CtsE#5cEb!Ag-9d(zYz@TbLY)Kdhzof09~O1O4C(9>t-+5>P(PO*f~ z!jGMK{!Wg0BoBa)6$mYUCd-=Q-5vP*BUP~hI^b-CLjBL`DZe_;_qbJB-V7Wo-rdck ztz7J-mOVJSR(QC;0A)-uj&2zW=T(~2o~&XgDRAMsNe9&A`?S;ot_pDrjMWR7b~+jR zO(*Ck|LAmEc%%sHbjss*B!Q1qKZYr3)x@gnF(la2zf99p(QL3~G);zbkemQO&>yrm zq1kqF>}mbVS8+D)bA`N_;3`>NEvvQeD^Nv|gS+a~TCDAx?_+J*hfj)-+w^t8>1roR zdWNtc9v>wo;WaIw-hcn-4xE-7yQ7mDA%Y8ehFC)>OM&-|i|mP`pr)Lb(%Sn{mB>Pi z4;#t6Yxw|TXK&yP-W(A6&&bG7|6$(v-jfx~X)+k}Wn~Rcy!_nr?>XtC#AX_r2=h~< zl{19=Z&H|+#+@(`07ktAnevSu6i{api^jn7zYFJI^mBGr@N!aI@BZ-I>qjORoJDI{ zclS4til2{)j!Ob*hBHEzYn^$y(l@iUbZdR@pT)jCq46Aen)BX~v^;u*H)MM?~}Q zJv+n64$|^X6?R@dX!3pW8Vs%8CH`-)6NA9kX(#+Gw#(51#SlA!%IqpgfY@adMm$Mn zQqB@Qs=GhAFw7bcjlfBmk>W-bfHwyvZkz|hmpios@UGMGKCh`>8qrJB%wz8{&Z zyaaS}h0+rT63i-gwi<3&vS^nU3m;5dZP+s85;!54B*A1TeeeJ)3TO?W%J8)O+pC?8 z4n`!yWQ0RXg4U~k!IX8ECpm#Lh@E@=tj?>05qEUn8|liv>OnB}A#gk@zr%*J9J2K2 zfa1oA2OG4%k9xEEvba5_w>LXnS9zdB)-zNWdmY*rKR$l7)a(edC-`!`+`*!3c-Zk@ zQGsJA8`(Yy@^~4_f~np0{%CZLk9}jSctWJ0cuG-~vF{YsKNWN*8N7hgg3VaCoSDIOm z`@CU^4M9Q0fQH6KDy+zb zdaDf$Yw#uF4?E+2Q}x@hi{bR2=GHDFy;5M6#w`h)t***Yee=hEO*Z#_f`-45Eu(m~ z1tRqs&A8j`wA{M}v~k%-t|x@exeBAnalHsRaJkKd`}a`5v$=rcUUpMw#go`~rHx1I zz8DYHh-$953a;VA+CzdRu;3kIbvTDd3NcDk;M#V9akuZ&j?TAJ(9APlRcrL9)X~;9 zsLA8T9c3}p>vXemSB$}m-hv`aG{FwjYpHn{VesT08zv-5=b2}b%{gukKB-PiThuXB z;Tbrv=vYA@2|SOtGH!q*m_X3YmWpj?qe^Z1-Sm>T6f>bSxe*>iF*7xJ(68;+LY8P? zy^XXqaR6+pppjS5BJzRVUk^6AzThaGdkI{hZxzEwxj|OVTVTK)MtnQy_uwy70T(@5(OLHQ%Pnffv;sqioOL?)Qaj-DQpUq zSPrcH-vr|U)}-zaSwAV_M)o+P{!C(nZVp7dAUCS*FXc=m)GbUD2`hP)X5pOoibb~$ zmc|9V>OW*+84wz>{SK?TEqjyq#lfm$slK|DT4?{3Ni2rP+R>8mSs}u4R)+W5 zxTCQ@rbgqc;2^i$Oz)C#yVn`T@*{$B*X-TWD9hu?VREsj024t*=z71>6(m zPb@ZzSQrx{s=Dd5!l|eoR4hoc8O}V!ekw4s&cj7*4Xd=-1E#BZB4spdvt`o23!f)# z(wA-qfBBQA8F*Lg?z(fUH#xjTRRy1}SXV|8-~4_|MTKil?7H|rOucnfRAJXXeCUvp zkQxC6>1OB_=@wABySp0!0Ric57`nSfBu84hM7pILzT@*e?{9tnrqMao$a?c9_HnHFlj9QTkO~6grZ!eaUf~US_&IFmaY7`84qu?xVk6 zbw47p+G)FnGW)c}wwl$ouH5bKZde#Szw7mA^YO9vbUWZ_)b*^+gDdy zS3Dcpv;OFZ8VJ*^l1%~bjWsUpIHe%|i8 zlY1%pWZ}QI)5$jP&#v_SZ;pl%Hq$}(U|s@@V|ljerGS85%E$3@idR2LQ_4$>Nve6- z&>uu70mqo$NvO0cvaEJnRVmLLth6-P@N*XhG)GG7i19XyF_?FR#ockfj!~m1J)bP7vmdilZUz>k@uUf!t3l-KoE|P;lS9(rkzNyk%J;`P?H-D%c|5N&!yq;8cBZ* zynCH3^TTD7|Ap9P1l%4EDVPx$V?X7qMT(`B7h8+5(8r>LK8GC* zzF-4MK$gK}yXdi&BRtx|@79J_Vd4H8WePDG?vCKc?%SBF_*LPHu_87h-@BhH;Z@xS zquc^O;MCQ3#WUjNcE1IdtM0#hlXSZ=`};uGZ73Ww*#Bm;UG!mBUFfLZF29ta+pWC2lI7RT3-70g z({wVkp5Sbo>gb#Re?~GEL@~xb;S2S{1m&5nGw1-e|JIUr$-*L&W(*xYFs6kpy9Y@* zyO9abeK}CD-(gnTn*Z(aJ)!jg4&}~dFp98?Z)biLfpARz`#$INW@ccnfnj{&6?$;b z87Dx)IB+%gyIgr{RHVJRI##d!Ln6&qVS+P7?0VT)0v&uiCr7U6ns+4?3+T0NvY8?5 zzHA)-nYO}h6R9jzYdn_i4-A@5+0Tms=;72QZHDahG1e}uMe2cJxaDKi)O>jMVg2GL zPE>jB2AgQ|5j;GvcS(hrH=LX7rYLY_;{h=rA*f=#1g#|rqn_taOBhWf5 zL^RtAbK+)P`DuptYS!U?7bbxJjo)igcw-PB48S=tcx-(NMq6n+bB+U2Ib`*h^WW^9fzOY1Rw(g{B?10VV?$S@BDnOvRf^10U;d& zT!7`_;V=(x!BNm1n~1_T(d<`lS67YaiG6ZootCm$5o~`$&qEP8P?K5IL4P%oVLlQw z8uoIL*8T9*-4)#)>{x!Ro7HNH2&^a(msut!MM*MMT0w;aE_IiwQo0{-01}$gG+LYV z4zuTVLQ0GAh3V>P5pc74mTcv8pDdEv*~|X*uJj>w^QdCg0Z@sZwg*#R(Gyx)k+uA(r;qcW&Yp-K?A0z$(LobeeCDo zq#&oTv9&NjSgSC|g36u^I}4E6AqJ`znbN$+MZ%b$xAivI<1!wKf786;y)UjoE#%lJ zFfpC9vlq$3BbAZ?`G#qF70g)Ugl9ZCO&iunY!EXc=B27!xdiH zLn28Y$;18847=9)sP_Zbg#nPg+Z7W0zriuM291N`aWlnJ&11JhXuVj9zp zW5OO1P%;L>Eq4zl=yEDNkEiPBV3G(O{nxkV`wYb5G+K#^OJ_enTOoZ~ z+3cGH?`zcZuC77$5A=l>SM~BKA5!*4i@>KmapLaUK`r|MwL?68l;mgI$cYsluTzIf zdg9?%7>t21iEAX6CQkUWAz@wc^12N%2<+`yz9JcAr)_4Q42%6C4EQ*?3S#25w(FM= zQTT!m%9k={$o55DP~gN0t5WLMD5)rAVT}yAli*zCbegjc6o9Q$omy7G@4@h}himlj zyVn%J^&esspye2JOUekJ^-tM!Wv9>oZSJw%1>KpM2_0PiLgu)Hrl*44Ys(|-?g=%X zF4F)FQ1n4fu%5?q<7$7^!_Bt~t&b{Fs1|T2%hWsY?uVZtsA5UK?i@00C}m)hJ>~fF zNveetie)t}6BhRHCi-8G7t!PN`cE1d!})vf`(;vnt3m4>`WRBcvUBfYLU{QP3S8_a zGlW39be{3-2fdJWKK1kTaD$Eu!sa(U8vQl5z7@G;U)Qx>x(Y4&EqBJSmzHhBic8-P z7~~wUnCTJvqXU4g8t>ZM+V#8g8Q;~bJMymDTY^}J`)MzPz>F^ck!Fjr?i-(Nzr9*{ zxM*b5|FwVMCG|gd|^;L{6D@&x|D9C24O{g#dN%?EW zac|6`sD`p1A6Hz{&pjVP*YIq52EyzF8l~Ls8j5{*+6Ip$M<3WTNJvQi# zt!hwEs5JGPNHbM|HTqozpkcpTs-C>wqSwAR5KV4Ka`%O6GT=@}I9*mTdSQvVu`yHy zPg+BRNISWyi3fhV;$_hYn^zXi^4me|-FW^lBpCx1rDbQ|_J@GpNu)eqdtQ8^`CDPB0A*fV8Q#i zF@!xzncQ6TR3HKsiVLFp)?|kU?8p`?7Cqgs@K|>E=5Jf-A(&$gE^v)i@KX4>NghR> zJpeN?v-(kIT=t@k8}n4bIS;*US~oq0_7=Y*_KBBt&K7wCyiSl8JTE%2y$?ePd`paS zZz|L}uH5?WnCS;rU;VGeH)N+H{HX7>Ih@3#s@LPl_vQPWuSZzGimkggD=`BhkjsS! z1pXVNp|fb6)l)OS=qoFcia$+-5>{4IyB{(Nb~cNWKnb&1nN4{PSy$WMIG&o!`!ZFQ zfvmZ8GvH>++-d;FKuDkGz}A-P8w%q5>y1k>Np7h`rDBJPch8xUUTdZKo^ z09B|8%0%;@Aq(EjI!o(~QwKelD+_=BU82#eF23TG@{2x3cx+nL(ifa3ogHrCRpSUyGgb?fFbM+haG9mBx z%s&EMZd)zTC_0ambGTRhCuD7}%0%yXyf!zg$0%c`E&gwy-$F*%9gTXyf*1%60mI8V zL#AMMw}!?qXkz7a20~9b*_M-kQ0c-1N4@Bu3H0_dgQOtWYCd1Lb!7f0DOfia$(6%{l3Q5-h}A9 zky)gLEY6&IVN<1`bbn0qlHz<$_veJu4vE7|`Zgl{L@!9JfLS@A@FIAe9d=AI^?l>VYj?6KFuvc0*)e5c;_=S{u)ITUWF6@I3}E|cgCoJ z(({R{`LRm`d$3PIBGV=oTlc!{~Vx-7|F3?+HB={NtvXZN^5dXHN{HF#cp*ywJ zdA730sZ~nv8{#{{+#u_YlZowVhvmnBW|rHW%%=@f)i5zt<#*FXtL+bI`^OIpY{dH4 ze=R;KFJJ9(t=qSsv8{F-3}_YGE)}|TUq!HGaUEG2ko1TC=YviS?zTEV=J0--8Ed^< z3lHF_#`=ajfZzzRsOWlkk#yCa`Y>vDwR}D#I0b3dA%&k_cCLi<9`icYAiok zKi-`F1v`cJ%cNS_8X72o>J)6#IUjZcW3bkq+?K!frMDcSS+Ohv$=u5SQ6B6)A*y<+WcXY_0s3{6J-RuyU9s)atT76V@dXXLMg# z`GAcb8iQjr1p~;S6jvySNx=9xUUk*Vb^9uj>Q)%@V$=(i*$Rf3+O7G6aN}IXsRm{V z4We1J<^Ny=?ulrJZ&fKYG%Obg&_7qn-{y*WGYw~vaDQI^dN@`@#m!F@Sx5ik``T@S zGOa8=5zRX%$RIK{Fwx&1NRKLcLLKpm6{Sz2cN~)jKVp*e3m@ITxa{ahu(eHVSW#KzNkk!*eBBrt()8As)500-;JPGM1u?uRt5k0o`Fx(+(DoGxOrrq=v)*VmukFNl8cu&xNtVsf&Up=m9b!I-wG} zmqEdNQk5K^H)cZ^Mfp&{ubqL*99eQ=`>LJRa*7?ZRo8*DltGRU9~|M+^G&CAqYu$6 zc0|gkD4|%J&MmotINwG=0M!LcmNr3pPkkT=>6YD*(=PU&MPG#B!%N58RiD%1E4vuK zlK|!3J+A-PME5`_a~XrdVF?t&0V-vD)M2}$03O2&ax?z-%#4IZ<4~Z27@21FHJMp! zW3z|6*UfiR&>n<2!<;0-Y*8W)gi2gScV9?mQHjkCf$%&s0=Vs23FsDj0WUZ=-LQ%2 zL$wtIque!^+aIW$)JFct;cX3r2f!F0ldvr9dpcDamz+TKDk4XjlQ5m>dg zu~uC${7i$fKbw+ZN-5@LkTW;&Tzu#kI`1t%$&&x7-$O4V?+o~Y*ab_~ahCC-163^$ ztVqZ}0ac8cm@6DVxopfHfbRLAlR+^%USDn-CEli^ndF8mjF;ut2pvnkRkpH< zo7#n7ZQQ7C&W_(-T?Pc+nA=qdpJ#Rd;EF(K>DVTb><1r?cdn5ptRE zRII%1J+4ZXv~%9h{-TFijHGgm&l8NA+f6~AVP+)BMp{6EC!mu}7*LBvC{fg@*L0aj z(-CIqPcgCc3rC~!yu7c=f2?+oKhk4HEG!?_oul@anpcn}63~g=8j90IXw~Fe%v2y8 zq6lpic|6l@+l=KWa3?2$R_Du6g1q79y}(^F?)(3DfqT_){klaWn^0-4VxN!*}F zLM}lBYalBi##j$yu!o?*PYGxhmdfJ7!^9YAw;sq5EMs>S+MWV4Z zRFMeariMRjCal3cd7B>$6v#gH^bHF-%|*&DVHo~oHRYW!6e|>EqP|pOStuf1ph`%B z{YKx4_+vb3g`5d{>iU=1WaN5B9A(+>wuhOjea|PPMfbEoG&Gj7cSTr^ zGRDdBAOSL%3#bT;*My^a?))tdUlqa)H)--l^G~7Z*?qZS$A5W_*VuvRVFMOid%mK$JEzgk_+k%p!pssgd0sJ>Gp`AYxh zo$C4s3X9Iyh41fSib0kY($i$m%5v6Z!h(jP)f5Nj+iWt*#*-Db!;ExZ$Rf>Ik3#+Y z{OVw4S0rgG;}!#SzGiJR%2mY3Byu-9nWW69RtN6TsVjKQ$a4d zd9S)%twu((`fj~d62;uyC)K#x zt(olv3=?WP+B^--lw8=}sqVgkEp?oGG5StNrBZT}CC`8s{oUTw(}?~&VG#4%8t04S z%;gv$=0hTLf$}YojyEs6FP2w#?TH9&XSytf7cHXsm$=daLf5}Tc8qo{);T_9hfD_I zNaw!|=!g+GLqgMAFM)Gj<~>xc_~X9Rin%_=G1@}w^1c&rO`Vdka98#pR6Zh^A~(sp z5)6M(I%c;JxjY~5?ac&l^hLn%pW#f6|AV)yCHT9d#T~o_k|yEPuZw11B&ai@1mS_(77mic1qS`IM4{=#}^l)a6)_6jBuqX z-jY){FZ0|9Lv3>(C>Vto*~4Bg%%0;|Z=nfxs^T8nT;S}D4<;9d%aN{+cagYd4WzD= zXrIYQ4UbTZBSIatFeP8*k!s~3h=Gzn`brMIy6Pty(=gP zM>tC}q*Toafy|}h8zOYe(y;+$$LF~7Y9|ZwzZT%k>C?8Cq^bz`3dX#g_tj4>d}!`9 z6v=K;Wf?$1yLQ`}gM9qx`ugMtfin0>ejU_&{{egxkT?j8z_*(8p0VFh$x~$sxnB~z zt1RQqOzpN56PhauXEV&Tn%fKum20#x>7_CT58T+Pxl?XW?1m=To1FK_UZ?%O)QbSbr zt9YRsE<+_{Dx}pZg}a8W1%rtLO+=BCFT-)JNy69_zBdJ$jOfnLFhs(#a@i_}I28%o z+Ye!foauHx^satRI@RCp{w8{$AQs6|1?LVJgN+>m@J_MaY0KSV<^c0{>OvQ)?YmdH zpl;26VZ73@a_Za*jYwjm%UiM_!Cakdaa!+>CPy%wq`9;)c-DC;=RcDE=as3wLfT|- zBz9Qua}5nf#_upI&2mL=i$1>RBg*eHs@$Nn zqUp7b1%{<)o`~wrolcMTu~psVxS;%@&ZgLMbVB{`bkZGgTfF_zR?e!+@~pV~blt#j zpTGzo_%_t#^5oI&ca`99`17pMLid_dwEJ$qUILk~^&AWB;O;L%ZsP9>wcZ%r}Hn*dF$E^PmcXAx*yxDQ$BD!aIIcnbT&79z{?eO zYjvDoB`Pj_N!oT)w1JdEw&~%O8ldccxNxDWjPT#1xAg-d)CxN6oWRTkjegDj^}ORP z9x4)(IuW1^%2^HBdM(SyhRhMfe!01Zo#s+x<)H^x?VD0MIt(WfC=Gjws?H_-;juea z=w^Qz^CHwD5x!-bNToQ{l=^|+kUJ>fDr39yrQq;8)#cWN6dHXE2Hr#oyuq!lpd)*o z_*DN0ZjbAHj`&ez888hlp4&F2j{EfvAEqQJp~+X8^?HSn+!9D&l{K^Fc*b}!^ujT- zs4VlX>J-gxZCF_7P+@qpARThsBm%IrgJ)dp>r(&8)k1t+RlKiNvGWI?XJ>xcI^ZH#| zo|ib%pgSc94L5}6OUlHXYJnqXI_zD6BD-eq-@);jnXQ>A!G-xB;^JcD&H^mOQwXY% zj|R#%b6u9uS^!!iMaqlcF_P>Xw=Oarx$;rd}FE0b>DZ=|Oz)5Xuz0c{Dm`m}> z?YEcJ4gSY)58vC$oaWna2lwmItA3rgqK_9`6(Tu!conKO#eTb08FZM|+fg2V$4&AV zx0UiDAI15W<-2@WW>*aU!ljeP%6EJ&ws`}#^Vu-=b8f!##k-wqKWuu4+$Yr3Z%04f ztc+E+RC)I@@y2?%%x0d~>5O%+Z3d?>liU5cCtvOS`wTaV_x|+c4C(mkNN}}t=UI?P z_S1Xe`rj5ziw=!wC_8WO^m4k*E;`PX_*wP;-|p#WM39cU%C82Q+RwJ5V>7e7Th8>D zq|^Awfl{FOTy>VtoD-CTql)bd0EMLenR269v&4KuzuY)eOxny082c_RYR_1Y-=Npn zy~bl#66Qt%<}0MLj@R_L@CiDkP)cbq>e4mq`9HRQB$^wa0AuW;ij^Zgb zn98rdc6SEogQkgutuI2DE8MdKi>ljDT=}Zq*0Pe5u6jD)!z+up_V-;RA1!U3*)0%S z+9!kj#!^)sojXARWc7D(>wL41Kb>@WGG6l9&%X3vAEI&Mo8)?(kyJPDuBC*AXbfF2 zO^4YnGQ%@qMq0Gi5>w|Y>#jULpVS!Kk5{6REt{#CXD5}2i{R2`7|H}mcySrTaY!Q#DGJ5h_;NOZWe8A~-Cr855dQi@j%@&KnV^8tN zr~KQz>ZPvyN1f_bj)5oDv1cx(^ciQBtE1u>XWRc~psDKa_TF1vl*($aU4wZo(VM=J zX9YChei8GTO zT=9A|p$>QP&bggNYFD~jd)EDUDod!#9%N{F5(kLQ{^#BXKPK0Y; z2^9&#FnGl2ll#(PV@+o`?ak5-mQ=l)%feZd_jU2Q7Nt|Adur3SW~X-zEl~XDVw5}| z+@l6GaamR#g9NHB@5+u;3XNpriwmf~d>Jc~W6^G)OZublU5a`*-`<>G2Kv8zsL1-;7#r`*KfnDn~ZH;2Y&s z#D5>Nju##6C7FkbvH-vdF3v6s5}5+?LYXa)VDf*sVgaPzXnD5CUm9Mn>Y>KMX#AL^n3N^2b%l zEQ;6>rx|cS0f`l85^3bz+|~w^i!(2r8&8dEp98jnZvCW-Wo4hTvrE~!nVGdFeUNho zO4W4mBb0bGd$Cu=$e?eh2(^@&n^>1>^7N8pQ;Ay|8;JmLkC7xp^MXwu5-p{pqZ2Dm z#tc7;7*!%f#imTolZ||f{Zp5fK2jzXNBVVozJisNxHu%DikkG(zk2aR3*kkC0$Nu$ zVA$I#UBJz;Ae~?Hp{Vk@$li@%4D+pMH>7i?M!>~&MuOo(?he&Nz~u6kFYDY>P~L!=<7wF?@XSdr*Bx zZxJg6emLu_Dq4~C)k^8Ia9w>{OiJpbnjTk~t2L?7rUEB`e{I5#P0yv-C1w_#51}|k zT1~=)>5I!*=JTE%6|GvsrmnKaDu}3)xmL+201sYnc;R0J48+0_=iL3m{yMBc>o~DE z8iW|LIq;8Rup&;mA<800M~DIaU}vW+$byJ<#6qbPrS9_r z7u`|BY^=*J=axEc(1kg4U;+jU1Sy9qgsP8Wv)lD{+3tHvH4?xk2Yld^T|Oe`gQT91xUm;mUIWnaRzcL+tTC4(8UF+<1$% znmX(1imJ!#!Vq)gP?w>d6>NGq0KH>KA-$kr( z_(0^b$ruLdi3F%3$A4{{-G$`ukbUFNmR=mh9y#?LQJHv~_&S>VANiD@K86xuVd=Je zHsJ1JusQkB?oTzb?o*P3Z`(s&RIg^Rh!d4BcS5=iE%#XVD!p=+$MJDWzNDodkWojk{Lk&Dpk%o!>qsh zJ9H^GJ@fOkUk6t!Jq$}rjq~h7BO}3XoNqevtORAvS;f!_NzMBsA4kQ+vZTF4kao>N z_Rfet9+;E(++EgzdlQhhB^h;D!q{j#ZwNH_=(%iPl1gbN^8?q5tB>Z3rCRmAJ3BfK zoo*m`^rbj~D^x%;E_U5>3hF0+e@d3l2fa`Si;r#d^Ww3G^xrR73mqzb4*x8A+3 zwVo~m>B*Gj*xrugRjfOEa;|QTth%4SjM2M?IP95mu{jgQtr;ui{$FmX2(X{V8%U7qQIZu1MY}OC^ubIVj0>9EAgc$*;f-5>X z)h*YBnCHwcbR#0vwjB-BRz2Yf9O%JRJ)BtZyuI!Q(}&Pu!$#cl{n!*XZ=*|UkO!sY zW`(AFro}Y}CLpocb1UZp8$|FKZS2`>esx^H2*e9xeSxo;4!LSZCIwGw?Km;Ond2bAX$65n1DRu``pa z-HFjM_ymj}Kjm*>js*YBtMgC8Qd2AFH@;B_ix}`rpdGTb@M^^Yl!EB1c}3)5_ihh9Sij3Y(t&P>g{*;2Xju0w#bSPlXVQ2G1myYUeGs^`admxbb^OSvE~V| zb&-a{o^Gv6pBxC4C5p;OmBbD@fDb>~-xYj~MGz8$+UxHc0Ok8h-l*OU#)>_T>p9in zUA}U69h_(<7)4MBqXB>eiF6+R^WxjC_T#gWksySaP^8R_If(?chln0h?=*qzhx111 zin5-6j7SK;&KUD^f0?W1X*-)yK*f3BG&y3$U2c^{QjuCQoa)>9oLS6n6AgL|90OqI zpZpu29?5Fts4^fu-eB@Rcf28`2B@GS;TSB()QFq$gckg$inEJ-lLfBo3mhU$>olwQu=Pf}8Vm}0N89i0s1Cq@yDgkXHas^K zQ=ZXlCzV_bDKl>uO z*L5O?Ur?rQR^;AKY8CHF;qU3oZkZe9w_8M}QS`M2M`E&`ibPLu{pzR^DKI-b8;#O; zymJz)%3~rKXn`Pi{a=NR^Y#l0LUr0*=*FgC4odq4v=0Bc0 z2OkBpCEdlfokta>LHBtRX-K#5Ya7!@e`!n0QsO1Lg9d|v!Fj|sR> zkKOKas2`sT9%ed--mEsWV&Maiq21oQ;>XPaUi&Cl7gn~LL-nFh-=akMo3X^;SN7Kf z#{qXBmpAG8K5Vr0kqvjrUveZhU`6nEAd(m!06e02bYA1Rodx)v{aM}3vm$=nXuYe7 z#YS-~Y_>am)z2GE`B*N9g$n$Jjk1L3(C`uB(FP&`Vpx7v6c^N|pmi^fB7pE|^UI2n zEjobtZDGI=ZE}`0F3#Vu*jWZ~Fy4yt*T9V*w(u}}$ddtUOLvJ|A(l;o7#}5MxtijY zwL~Q9T45(-j;f3-oy#B}(ML)UclXHk+bJFnM#C1Lj91eYgA`sE5`e7A$&1JwL*o`+ z16h0p0luSJl<>-8bkhL1yxzifN2Hh+~s0`Pi2d80v!3mZ2< zdsE3FciR{so+_$|tKnUd@(TnU@it{eS%cnJwg4KqIETMF59w&0_zeM*TY5-mX7fFGtsJ;;&{m>Q^;!o2Mi|bdo3bnBMSr~#e`q~ zrXVlc78%>c19m3QC7z?b#1ABM+2Nr2c7kWf|Hjdr@N3j;(%EMRa z&(Lk2&ZM3=`6PH5*Z6Rh=WxV#M@gzH{FE}0d*wM%$Rje)LZuts*mfsu6DS_L*43Z; zs1^LWe1S|&jqSfmo9dlz(w9%mfyQzbmCo~f{hda_j^Cx5lv;SGbJmVKs^$yy5|suh z97|DQ%rq6L)lM$_1?3CfNU3 z*(aY*zdMY%_ZF9#>`GPnJRokYr8=v|;2%=laS;z~{~1Q;dh-z73iiZ)A})V^=;n!a z-c_;tdBe)&T-HIcUaOX~Nv@#4C*#_-jt&TbRj_XGd7gbjZL@ZZ$UQd7P9H~Xx92b>=U@d=AY1PbKU)!#udAAL)p1y z-N3<;rEl;`>J%juHpLuej7?648UI6O(lOljZ1??uVDMcHLyCO;!3M+pkw?pD?o%!; zm34Z_ZkBj}8c&LOT1X=+kC}^AHW4?=q0uC0`TMq&6}>;^<=qn_E|KFg7OJ-Q-Gam` zk`DdYM1Cq^I_0Y#+yG z+qleOvsI*z6Qe~8DRBOVo;YqRvkW|X;Rb^{Q#Dq)iJ!ojzp=xWx6!rtX)?y&SHi>( zVQny}X((rwxph?EYegnP4ITP}lW2bjs&GBN3UlW#w`;jS6NYT1{Yu>BAD1H|Yq$C1 z871enKFlP-^AJBAJz}_=+RXaz*jkPjLARVSB^d~b7+x&jePXSp<>B5$Lrskf(@LO0 zQ7nI-$g;Ufz?DXkO?k6^Qk%voYx!NVPRP0Ec|n)xmvU8vT;qgOTfc|zrp{Ji7T(~W zZPcU~Mfre$l-1aS=pzkW3A}U7ir*hrojtNeShM^RKvuv~o*pPX)@rK2lu8YtQ%=5u zwS4)JTdw2{ib$9U-D+5E#i!osQM&CQAzXmCUbFJ6DJ(AM%6`q>f7^x#GjbRH^AAm{ zF-6aIaF#c(Vjpl0s`BK)|I;zMmHMcBt}+_pZ3`j>1R@PYhb$`p>{|o0S>pxJD>nBw9 z?e0(!_7c{n(XpyMIY_xLe&0SkJkHeYn;$24BAemSo|{ZP3ntHwEsYb??+8jhEq>_h zIRHP;@lLW-W|rhn0I=j80|o6J@bsWFIGGc;&MvK^5b491oOi6mwTfAUCn1Yq~A5LJ0`k=65z5g=g<;(e;kCobu1~&CJiTZV>LmcC|q9h(`ZvphruLsVU$5LQ# z1)HMl_|zpqYV-E9I@@&f{Ca{5Ns*nI&}aW;2b0hw3{kt4t@j}On??qn9TJ7)yp`0j zA(k+dC`En#McZkLF0EITC^nW+Z&6O?yt~@Hp?Nl6HLn zEdmLq2OBzj*Xba9n$uGBQ^i*AiFc*5=UG>S7#<~Jcw_AmzS%GH4jH@equobkJB3sK1h6#A=w3uF(4#PV5!%{h5_Oe$_zdV}j?+VI-1X zt)?9X@W+&Nesy*83Mo)Z)r9T3L{3GkXNi=>#9fR0@>O39f`b-59OmYi+V)YSi0+Ec z>9rF!>4=n_F30Fx(G87B;-(rss2whx6|B-++P|PUV0!kZT!tC0Gt=c-Wtc_O>>GcP zH*v_00j$`e0)<*1el--3eRe{}%24Kzk+=F_ObV!2E@<@N7%iYtF#Ow2A={T;k_ih{EW7{OHl z3zlX44=AsE3D`+-Do9B598$#Ifz0FgPW&TvS^nTv@Ue=t*2mF!QS%Nt+!dUkt*%iO@D0Y@4 zYPE~cDxeCbtyDF4B#b3bI7ZhADaHf8^Y&mTbi~C6KRuh%q7ycV?;DGbzm^iF$T-rTqj|0X8=ESpBK>Mzm%f zRMcXT$c2I{hRz|Hz2F6E3D*zt!NGw^|L$r8W-*h0@|kz(MmTgl#Ai+j5jB(-%pyvK zS}!z0zyD*Iv0+NyV1pc<0mkGhV=4JyVqjD>fbABM2%s4vh`j@VG+z{PO7lbIk9BDx zr~soOy{`YKM?tSTUHvMD6$t$UgH*biMrb;y6-dR2IiQ!tVr1llVoSxRYBC#?iG!q) zIAhhF850-OkoaZmPelb&%o#k^TH2MLy}xqmkEfn~Ev9lxwDYk{r$PrjA3Cr2fWMyT zVN`bTCX7XP^o3v0jP0xnWbfLN;kw-k0C0_%JxlX#DUi7S#lTQN`A$*Il1%pRukMP{ zTHkGkAYlSHBmvkB83NA|^9Pxt7C5W?M)Opcoq!8!g&tGajrp7&lj-Ks4&GOaPVhjL z-rnD>K6N$C5TL81=rihi8r77`cVDfn*ezb-=$yTK?PNKP9wLq)_ckX)oC6Z0nasgH zzP~qE)ks=84Hmtn7VpSYDhnu9pOb0*ZZ!EUMGI&h4H8&^8W5>NQcp->)(UpLG^r48 zkAPH4h`y*s4`+x)1DR2Q`5+R5Ku@#))x&NBSA+*D`L3F(n%N%8pTV;CG-`+dQkwq@ zsq*v5HF9BX<;rks8B4AP;RYK|m%2eaX4 zdo9+nZBYm3pt6}C*g3shbjj1CHy9}euURq{P!V_)^U@4E$?H&dyHvfwHy`88TK-g1^nB-#wm6CExQqcFA;bfK}Y=0M(#s!aWb8U831x=oDH&1xMgH{8BHfo z^Mc1ad}Z~~-D>W`moG2s;?0KoCHv>*NK763QuU3|VQHVT#qhrq3%tVkB=!ecCJ+EU zhk`jUg!58Yn8CM!2}dURFsVYMT~G%$<{O}E)uF8+?;LU`C?ZnNb+yu}Msp}~_w&sB zt!n#O0p~L;sn-`lfw^UMMkLH|m&{!HI%)~QXA*@l7%k-c+Wp`E;{xFHQp^zPwmQE# zRXjGqCVO65e)jCG7#@u($XQ1a7b_j7krgN%r>9w9bA{i68sK>P*BoU0rM%V4>n-^I z0CQRn0ga6RlM8@c6rEs5p~Ql}=Y|Z-%1AR-fP2&DzH~WulT>9XA6(=P)ySm;icY+)PBnt|Xj?Uj%H1w($U2l}V z)H+><;4bO7{_6B=Jk}*|N0T}-aN%=9e)b5;Ae)Er-}2Ks9*W! zJw040ov?c&-j0Z9sCi{L;AZoW!bNLtu2}K|7>HEOqSJJ?SAHfhpEf|Tzf>prI2Q1y zx|5mYI8*=-7hKVwyy$uECForwPwAi)5kh#vp3rRU>XOax&L$^|JijgWaaQNjdYUK;;R`jI5OM-K1eO5vL}m&Nnx%vRc|i_GcrF&azYbAM{^ z2SHxuK}@sSiV~Zm^;bo0vTggl%;NEh@S+{o>}K2G8ZZfU<<3=D9t?v{4Z~=%+iSDa z3M;dQ?M}OO)0urD$=(|`(Pli1;@wkObKY?9SRx^gKnhe)mF8}E7{h|bTof`{)#gb* z4mH_PY}n{Gv#R$OZr$h%sKuY~&(DndrT$zca#YTt)O$aH4m38l>NJ@a`x6rqf@}m} z3f9?fr3U93E4=rwYe-~ZajVoyu(th$V7T|I6bXGCw5P$3_|&^5jQPj$lowA%OR5pA zyxhXvOkiOBwcMhi)(X38x;sOpElJoa8y^Z*?^>C{s%s9_nkRiD+8y%6+c@f)aEd+E zJSK^PE(!oAhpV{05<7_=88{amIO{U}3X;e{n`wYPC2I3V{dLc&5ay0p&-m!mpgv2) zYn&bMDXgN_ApNU@moJ1Yj*b~15M+?P=tCzY)E(~oPZ)vP7>kW1PLxhF2yZ+PCIBK?GzQk*P(^JiJQB$4nizhC?fbBI&h{W zfCfKXD`QOFE{7>N=}xYdl~o1Ik%CP)nBoi|HoP=&^9p6Exn9d^UzM2qb4EDnIM?`L_SMq$lcj^Kl%UB^wmL8zTevq-AH${NH@}rl+ulq(v5V7 zA_yp5l1q2T(jcOAcSuW@|fMYD%XmYt8I(g47VZuKi4e!!3B^P=yjM0FucW3RU~ZzyW= zqKf9b41x;figEMbT^-MiuVKX2+NBg4rd-|`c1dNW_T4@}iDE6RQpLXWI}2@kHF<2e zE}M+lrkK>bZo*93l+s}#h(JOE!uLr}qbb#84|hH-C})pSV-sbWeTjX?J6mYqGv&S( z>^A9u@`G`8F_Q-3FMKnan#=>9A|gwZrXH<0_A#rKo80C*dXv3JQRS`OA9v+Bl)J8NLGJ zSSIK7+@H=hW@OIJ8>?J@&!qL4`olLXZ>;e$wx-4x^p_$8rAzI;PI{U$$^`Lj%d@i$ z4s$U&Z1F8Gw8LqnLutIO6-dxNq8^bV7l`GjCa}E9iA@X}QNU)(xwC_K(1b81xEJ)p;Z}hsk(XUSP-wJh5J3H$2K55&la_3_EebJk2!PjL${t8S`3cV>J_`*v}Tngd@63_nq?nP*| zpdxolLqElMd%Yb)IUYMg4qlh3VnzSz3zD+9j@H=Dz^W(cALx-Yu}-6y=t5%hkN8VI zafJ~KtXJ@SO}me40i6QU#pWo>Fxxip;p(naNuk%NT&lKQf>|x36fPn6QD9&=4%H

G=L9TLqC$?G98gt?3Fh(h~uSTdSWGX&3Gyr33$2|ShOp|F~*#Inl%bh=5H z_#CX6W>VJY+kC*<4QMVfpC21zQfsaX-HE1)kU1KQ_)w0|Fy}68{Hw0LY%uMHGUk*V zs7nyyi+s7yr2Mrne`bb%)0J1M3sR2oDygb`Y2F6&b3Re*D`y2Tq!B`32x54TgB#LO z{2rgJuTkjnFcH50VT_Ru!_+k_vRm9diErLGz0*#xBvS}dj${}r<3L019{1c8RP2-I zr9&^{xI;lGbk8x48Q{0s_=*eKU5%^(csU6D8}32=Ll*qb&8I6vJNE%>7J}kln}JIX z&i>n(<{a2TjPJLiq1m5Fj&>bVp_eifGcHfoGI2n^*xu}&x~vh&Fbqs`zB!l^GQ#Rj zc=`VDqNgtp=Zsm%?4I`aqs`+*R^IVl_x#nh{A%!4#An)Pt3i|6%l_|hJMLFjy*bA? zm#-%Ap9OTzgz!qNpg$|b0V_&?74iwtKIQ=95dSlILog6I0Qv~|5-5VpMQXlZfC z!0A3Z9!~&L&5S)=|r{$6T2{rcdg@HIr z2r&!0a&NT3tC8%bxlKfEh7C=>jPfZ0oyLL9J+d*ZvUGKJ&Z*_Un4$*OURHNrGbU+D z=w)m{!#_Cmr-VCmq$L91B~~RK9XX1sMpI|_!IwX7TXRuZk#ISpglH&j3cKH4*s>Jt zY_UduD(?&$t}?L#@V@*yZa;U~$@V{vB4)o8+xbl6w~L2j3mA0xy_mGrWNWCGoJz=q zntepfnizt?o-;pyX-ths*j&nONTP@cGP+iOauupf^Oq=~P_w);Hy0eghQl%3cqL0v zF2CzDG&mSe6VxFj?dQ>4r$r!NOv5ypgb)H=qAgi=iJ&ekL*VI(L5jbt>CLX=>7S z|B=#&+vv0}5$mos*s0QDv;LV>7Z}VwW!-$6)~B)fZ}2J-`dC&JiuSW<4r~F>IW0d$ zN$oG$jMmASol;cgxng2wNjuzLXuwl{f?#~`c|xR7h!(9p#kXZ-ZU+@ zZsBhG3wJ@!?<9PEMNRSy5vteZ>?j4tmZ%i#4}({HHY?R zUB^EZUM#)}sGGZ&ygDWvh+e(5hBlwOpD7yG`stjOB6XkX&TV(7yd zq%PpbO(&$b>o7j>E8!pl(2rI*=*AWw@x|PjNIT)vqzE1hbGlcHhBVlNaE!T&$0Fv( zZ%~0xP&(f)ZjWL|ecc%j)8EM?S+(N6+r#gz3a79EzSMur{qO4`H`oIz9owDINBHl09omHeE^_$J_#pUktt?2=xn44}Nop62SQB+=TKQtY)iUFukhK zV(3CiH%PHwFrm)=;nvZTmQNn;(MDLt9hYyQnQGIwVkrVNTh5Q~7BF zWK4S(6)!4}j(%fpZT0yqO1_dVgoO3(XL0l?;@BtG&d(P%_eURV)TKN9^%5N-O5(TxAAxJN5ow*1IuBW#mDIoM;UkV4 z%4;>4BtejakONvNgHszzgvC@*Wdg(+v-{u6LsU3){k85zcqi60nJ%LxI5J?%$K&)! zuh`qLBw=zYn+qG)=!f#fJrkwEH3R)9@~d1=@Z)c9hc#l-e|?FkIU<4xVE6D~{|Qu} zt6UJkp2kkgkEh8>o9I3bkjC3!f#)xg*UeC=AlH?X70Exh-Y(y|aaIuAs z4R*+trl(70P|?+(o1WE?OB<|VIlIvAL!p-`Sql@jU7*bK(Bx$}MzpkV_t+h%0uAgn zeKkfKdGS?cyoXX|M~STB_AT_3g39H1a3I&s%@)+T2*&FnTflA?czw zm=x_Y78t8(el!iA;27djO$QAdEeK6$2os7Xq-afTYnF#FM8-SP(2_UF$!tYba>dPR^&wTzE=x2-p9X1 zcC8k*@9IMdRq)Y?s!Si8Qy$0x6>TAGMm#)-UEF;1qckfO3x+5SsjjX<{J7GZ!lHm5 zIXXJX(!k88=$yz%X4eNN{$X&+@p|)ct&a3OK0ysfdGj3!hrc8ozTEGq?A3Hl&hI3;L+!u z+2OcQba{aA_WbrT-{%l~3#Mq%;sBhrG}nFCb$^0$b>ZI;VnmL#gcB&nzNso z*>2qAEalmndJ-0+?H{)Xnc(+M4`EH}itxha(^Y0O?bsIoNW!6avr>0s&wi@X(okPZ z03qP?-}nypcdx_9^iGBq12BGU?m6qD_WE;gH=DA*^muW`={|;Gscy;Q1j4$VXkSjg z<<`XFg#LSL3{sr+J_*`&q<0^^bT}ZS_0zK zD6z51UI9SifhZVaYen{I@(lIsZ@va;e@P=pY=MaFm=uj8*c zTYNY@k6)z`#@F8qQ*o7)8Xop{IdWITJWh9U|efAW)pE_AY{!sbgs^QrRa5)hIG?pDG>NOvoq2xPx=X z+5=rby+(V-iH%x>M%&U0)!k?c9AB|dDV5L7&El!{d= zexj&35Skpfno=oPE~f3eZcJUx?lNQ zIArEqOEZu|td_!y48z}%hp#iXf6!6J>Ilu#Iy&N#B{N$vHA*#+0t*Pt>70r;S8i8B zK1IIDW|d2#OCvCiy%c_jqDu|;6mOTP9rBvH3vd|ty{Da*>AVL02Xl-$*)29*sdXtl&V+Py6<}7NLG7pa&2`=*-#^4dcnM0s zyxe~X%5C*~4$uiTOo0Lbk9E%__M>qyV7je}uy^?l)#JQ9SZi5@F zSt1#SLzol&M6ObQGkwFYIPHy{}mU=v7;E6QnOctCNvPv z=6daDd@e7`i~-hICY(4qohmDj{`;Bl`LD!;g8F1@+IZ78zpNKqJN*2YHhUdtk2R*> zL|W#b)waTE+AQP)HpWt@W&^eN%>u4##kVsJe~|}&CC|Ob+fi?{+p0rOct3WSrg-4TE2Q9qCWH>%DI8CC~IFWqMvm^O#xuBD9fwF!dwsXH3Myl~T zAy0P&i|B4Uz3D}ajT5EPBp>$28rDhV_Xr_Y_(XPiFy~zWU>Q$i@XZ$D9N^K>Wkd%w zAj-**StcJg7I?4MEDy-i#>WqAFxEt1i4aK)M?J~)Xm}HQN{yOu=*_dD2lZEwu2@XR zGlbbC*zi-o&s@X7$!67Vc$xQF@#^O5*;x{edvRWXe;YRmM3XQVX1=38Daom7Xd+dLhrKiUJI}T#E=d^R5k8>Bjg5n$p$y%c77@Qx*H4~{ zV^wqO4gSga&$U?7L*#>zpGIx-ws$@QZ`DWo84;41sFbNb%hBPXBO@xs(r_9H0FG~# zwuGL2lD%PKQk#&q^b+LD6QNQ{cnJ^9m(iA_wY2omST>=0u`qqPlHg%XG{HA?Zo8nF zH=z+jkY#4@&CCE@yBHCG$%E~|1Pa#px4=-)c1NF2D7Or%kr=l+o!U9eM_x#yUw4ok|ZXCi)D-V;NDY7$aNA3g_RPJ7q1f zl*iHYQq2a?&`STT+J-$ctAr$-3`r8milDU4%i?%Fa{tm43`wqYlneD<|1oRubpVsN zGzk){f|FcEYjC5TrwQNzKdBw3IMlVdR>#+}Xd+}43}gic8=44n12E{L{+&6^7HG^u@8RA8W__ORjIy*Q} z2vwm2UdN6oe{p&&B?uJA`X(|o8{}UvNAbUre#7&I-+3@ehhe=zr*(OxMPA-E`W+d} zF3%KuC;<|wV@1 z_^pQ<=S-LUrwpa;*G-=8cRHbyfKP{M4-Xe;rX=-v8hhu@70Pcjnh9SG4kkit-!Cga z?s|HxNH(n|y(;*Vzj`8sz4-%+JK%Q3U(wasKk_8-#6MQ*@%k}a{ux*MU)lXEZ?$jY zH#7QX%d76>nM0sS)B0!HmDT!wYqLkXAp{C5F>L=&pk>DG3ew4ECNk`^cGm$WAuy@M zzrlK;&dTL+lO7PZJKcbr1}4`zh0-}vq9gjGBoZ^#i($MaN48o*p3gau#zWrG;!N<+ zEG;;`d_KjRE~L7=g$VQ(D!YPi*?YU|7`q zHGasQ<25qBS~Jm?94BrEK&C*e0n#E+`I@oFF2`;W9CX%wOtp!^H$f*=4Ug(~0jdc# z=D+y;J%<3F$%yyJ@gt`h5f*u6KxB7o=MD*h z8?;@n1n_Y6!+Lakyo{b95%uxq;TP`C`PC_M zz}pZuUAgrSXf(SnQ(aH@Hhg3axCQRnplo<8M+1uR)?>y7*sYXAlIBapJ{q9wC%sw= zeTEq-C;?w+U<$uHDflMmvUI#PR!Y0s(7DN=aJ_H=LHLNvyf#|bbH>1 zeWxSmQPrB8vRm$ZZkVEHNzjswDo0-5^`8aIyG9UEnGSF5w zz)DWgIe{zYtH{fjv29$dbK zTiE%>>DhQtO;lvV5L2Xz5#`u^5r=m81bazpk!RK)-@zkm@^A#8hX>}kV7@dksijYc z7tyy_Vr7vZ^d~;sCVNi^+fV0kY;?%Sct<#DlLho3qQk>mT*?U7^nCx8iV*B!ci>nz zH;;97h`{yjfr-S9-WD7y0dh=9E=mwt0WP6+HiU0~p1|{;6qz7z2!1W7Rv1O+OWbl+ii%ht5ZffA2Av*})BQu>H>;|}5 zzW;OPBBwD3`6o(zP)WJCkM0(!LNWvILTM$An>!rNarLc=x%Am6W)xb|?N@RW*)lf1 zp8FNV&>KNKtA)Xr<`AvlIhv!4xnl%jb+QvQO9B|cdo5u{%TLFVIMR8Z$nOkOaMIuY zoU&_@(M*?3_>`Tpr6Icf$IH9HU_GJLDXS28Tf$}`ki1nW#?aPv^Qy5)NWhLil*00h zg$d@_j!`JTm}njcdtJp9Z>FsLqL@KiUOH%v38WB{D`+&tIQ_oZoA5mFidAWtudS@2 zfQ?XMY^S|i7hsZ7*Jai`Xi829s^O5;?0+sh`C@wdjg{3VKnH&L1$W^_arng1QG~MIpDrZdPHzfd zDY*XV_GXI$=pxOs`_Pw(?qh#rNP@#fPH&qyKcj#pP454ep_OnUgdBAb|zCe7)suKcTh?V?!?; zHH(WE-`ps8ABSuim}-kOkKA1&s@Q9kA2d}bJnHem4uPy}v6kP&U{t8DrQIVP|Cd*Y z@+JWnL$vW2erQR_E^m5nS=1|(*Nt)U61tWjVOWu(Gfg=y3)Obuf@0$fw|Rz?4T>ru zdC|%VT1Z(@Q6o-Eu7*d2m`ua`$0GV0QfS-(0YE_tGStMk8#K_Du3L zG+DBR5;1;2&<9}%-|H}<8sbSQ_C~|4>{_da>SR5Wh`*GHXImQrYcmB4nJNh590%^q z`-_D5%HXPK(cL|fw?_p=#uj>Iq#3_Yjh*Mr%pRkBIXgI``g8J+VBG*}NOUeB2I> zgltO6%U*@b+S=8>IAooG2@3EbB<|lTpw1##;pe6~gh5X~76-X~X2wFlD!{K{63Q>L z@2;wf11joP^{rjwz&^|ex973Tiw@E8eOYUa|xqKIV2GF97Bn$01 zdqod7I=HxwTaQh7S!;c|QDJIm-^i%EQ=#Ls12r!4utDrQ!nVssv!_F|A5RZkgFU;$TMrV|4+xz?es15F zDHR^Hy*mwj_SCmYW7ckk=Od$^ns*+`%7YCy$AYv7|2tTTx4=3!SmSukY#70khuEZO z!cl&JLxs6Y2RJSNySU!Y}uPM zrDn0q3;L?T%E&Zo>V7uU9rzdQ`dO%0ps_&u!I@z%xCXZ9D*~i7`=3d&K$Iz?jg2zI ztW~biFo)^{R2h{MA-bwa;4HexD!6+IQ~frsqceSTe{Lc5WQ-c}!a*xKIvtW09es;8 zc2sjTHtH4>q%7WPWUO$Bs;i3{GE*)kar)EuLr7Dr-;Z4ddNH~$yukGA?CnFC?TM0~ z!mnotA)D9I(qxy|ar6X{FZHTTqo0dNvt0yXERYHQLsa|&^4CZ|HM3anPox?3=#t~F z=h^Q1SqBNsX7Q2@uUMObypy@7`##bx_t}xxY;`cQ1LtbP`}seLl7WX8ncc{&`NzMc zexFYe@0j?z4XmW^O8y|2>$pAz@gzE%>McCn5I$}t)xPRK7N-BK@$>T4 z36}Na`=w_q0Z-wjf%nd}Vp3+l%UQLo4ky{0)FYARJYW&GebX`41md(J?_De2gI{BQ z0^Co30*UCIe(+Eumf*e%oL*hpZuckcctx}?D$^Esy72r(v^peR#QE$~_*fT}Tzv(D zvOV_**J@kGX*nL@B%i)00e^b$8$qF=ORD_^np&p}n>sxGuII0`SXTtBqHZDFF4`y{xHiU=!n`vnrGR3(r77Y5ECyc{kxq(;B+&x}q`=Svf3*Vx}ty z3ixEod3o88p{kab5|M>>*Kzc@rdSb^zUE4`UAl>UiT8q?b>WSE)9nCrp|%=^_)USZ z$1jmD@6gB7n9v>`xl(zx{5M@ETt!_L8}z`)KYN+SRV4`Dz9H56dotzLa{cO+2D^tp z11fZ2;7q@(_|TcHc~(}XlauQIHKS_weVq{gn4VhM{QBB1SwV#?aHJ)1)qGh?lfbh5 zxs_p}_863fU*RAGJY=ewNEQSJItR~ zu0LZ9hCjx98zFb^|8)ARQ<9r<9qNBzV#7q!vK8MNx&`?^RO1lk>Q3Jryr)()=A>L{ z!#LBFXSl3sDuOS3VNPFQjfII6>YhI-DgDdGVrnwN>a`0t^V4*63NkAV>%mPdB$?vr zUBIiC9M2~KjU9NGnL&TX_HaxLqhModLt)wFe38a(X|07B3%6ND#$9O|VP=gH7VIqY z1X^_kPqbaS*Yu83 zK^4qP7w%?xxjzHccQSgi6f_~EJCPk!&Yu{!D3{5RLyg(`}YpNZRKUj2lZU%mbD@@;punHkUbtMN#EGac7Ia>0iFGbb@r zCFsKcy}{sVP&BZKuaj(Bd+uvhys^hd-_N6&Vv> z#BgKKXGTvi{P!TceihZgCw`fUF>ocT+z>n~%=$3R0w#0*t%U+QwU z-5uSKemcQ%xkkYKufj@N=X7~xWo3D<`0k7cjH{eZi=2bwo{-BizQqG1*=+f8zrg|IqE4z8v)8gxJLV7TiBI>9tS&cwx>(N!-1#fI{>Gtn-H>%S z)Fe_qxn4%jgwc#9O1VxX#|Duo-U$eb`y6M=v7bF;4*kNiun9itjLj#nr+3E{*|+_? z@HuQ5cAsxV(tvF8)z z+n-5JA5SVG7Jj!{^o@X8sta@SH%wV1SfvLGSx!Z-9O3X z4eG-htK<(4LVE{duiHkwK|-I+dC-LOulWi7kJG5ZVx%u$)^J|O7cXso3T(n#X7<8V z#$SFpYR*Q{t-O7cPJkb)3}ZNPS7v)rSKRVOIav~r@j9G`y3 zvb?obYBdDo&T4Z%zJ~ES^4-G9k6p5>GXh0K-U#f!Y2x~{NJ=~a?pty{_ihi{Nj=?D zzfKWQgVJOP^H#AC0Rlqq6D)+7dv%9R6>geTvC}&S957FZiyf(_IsUPqG(Kx-y$XS= zWn(5OAb*fG=J-&DS^!&4cMGJC=q4k5&^S2;ukKgS5&k_{X)j}6WYDNq1GUUe{n$z( z1i$d3un`ghLQC!hJqW2}je z%WQ!HY;Gn(r8#8e?uGVa#sCo%VD_pjtNw44=jVr2lP5`-M!?gfQI&DS zi-(CaT3T77HpxJXXsw3-5mn@M+j@exFDC5 z(<%2Gk`=erbH!VRYL2d(k0?tcjqGF8IVz^XCeJxD&D?f|%7u1|X}3OJq{C;+2FBA> zZxa|z=&CCpsI2ep)qo9`ht-YxZ1yhen<;n_vt;v5aZ{$N-DCJp3UOkG+F?Z1<_fS% ziMG*^TXna~e?Gos(|XsA`~hPCrL(K+a`tIB-5&G%{NGvsiLC`nCBgT3=f~<$|6@&TV4N^k^vBautdw(|bu#Ur7mWW$V^{crzFB~x>lD&y!G$Vs zNoFarlJA$Db}1F_>$`UKFfauY4Ggj;gtLqm5-)nQIGts5eWxtFz5!eysVJ)K{4PU0 z+YhR4xv-}vAlx0|+4fmhHo%cR(4zzg(v~BQpHOxZ$hhS_^THQc8#161R&K(IBI;yG!$OQf%ei}Dp zd@D!Sm1O?d+uaVGGJJ3-=-k3K{Zvz5e?Fl|+p!)_sZdABxAPa&-`k<$@HCZeRStCB zo_sE~vbkiFQ%Ii4g!yn091lk~J=i6C-mZe_B$LL7K+I|2)qGhjAH`D9JF;|&rN&0D zEhq1eXM`>W#>qij{=tjl=cz^~EhS%(h0l2I>h;xwZ^K%l#%376%NoCl0W9lr0Pu5i z&mcG8Icd%>M#K0fhy?%_u_s;b$p`H=PY)T|h{)f6p!f+p+rx+9mGPkzYxBE zWDJatB>jE!_x5B(u(C^I)3VD1*Gxd_dffkHCPPuRMl!f*7WbAy%BQPa+^zj`VTl$} z&TXXeQsC**JNQ8OrkZv+2qq0s@oL`I9M&aQdz!x2G`)(HSo;p|{ovzbaJ1xI@Ox{k zrEQe}ZfiFt=9#;*%H7p^RJ8A!RC}|f@12zCvEMLk#{8+;W8;q&;JaMSee?QZ+Gw@o z?vpqo5P};Es_?Vu@@PqFb%)MQnj5*7PJW|YZzf(-A~KnGrN_&TzjeqitV z2XBC*Sgv!fuR^Vo=eKcAiFyl;@Y>#_Vno8PEJI2O?AM`dx#u+-2J+*`kJft@a%Oe4dM28`>6T3_1P>E3+7mcXj`nrjWQADP1pBkgt z?Zx>wiON{ega<&~cNDH`7M=y)2==~T zRUc~VyqKJ`TJ`lIL5jP)>51v`9;y?AjdZw-Tu!wfkt3hD%84e!{BffGk>t_K-kgX@ zci~BV#}{xSl1djtsK^(BfS2tXxJs~AM6-nGUlhT)qgKj1tQdHAPZDb_v}1s1oy~n) zfhVcKfTB{#Bcu?J)fd>>>HAL2k=>+~lc~f$v2RM`1N#CS7BvN+g8xgj%WPagNqTz3 zKzqP;+Uk0MwNDv*)v3kAX@hj}l=eRB_5LnPQ=57xn#C%FB<(LYbWSpvZoymB(sJPB z3BuXA-J2@eo6R1rAy(dP*_)@=iRzLq%*9^M<{9t!-}DRM=9h(LWr^_}^@J+0iJ2cL z{mAiGlzJu&(K>l4Yx4$%4-SAeX6HHh{h0rl5{9xIa{okzCHxUUR$?MQ<_)D`o5#f4 z^jW$}^p8MIWsp3Z*CVwHhtx`6b7+{=y0{Pu@OB=iimcXg(y==1xdPxC>GUE zT03LIP4M%^y zqSwcVK$?hHM^{5Ptw=uQ1vUfUT+_Q$>3^`Ou5!XX zfeG#ab$Zk22^#o@Rg_vjkkA4V*hoM>PN0FE$K$!#D@2$gY~*fHgbQOA~5t6io4 zh@3k>?SHY1`Tf#}7b_aj&)7m%w~%Is8A?^D7LMO@tJVwxUbpL0{^8jZy4vL(1L{pL zhq#~z$F+skeN*UT-&#l?tdCJhm)#GOC{O&?Q;SW-1N};Gs+*+ZM#To60da56uP8)z z=Iyrpxi%+tKhti>6Hsj4^xfHdA)LzCOm`a_BwEPV0D!_9B6 zA1~Kd35;w4gEhO8PWyIN;fJBIO^y_8e{$^vLSDGOdGXN1-T85_p80|>{2m8!mD2xd zh3>pJsYN?Ji&~Hfo=z{YJYy= zf##%2*2^GKDP(sCA>!qJ&pI0sF#$Sysm_nh)3oQ*=;%=lHYn1JwY1lw0lkgRyR0fn#@m^QQ&b? z5020;O8IPuscNUHj2cuOcVXdm|Jup^83?axYq6jeFAd3YPs!BeIjQoGRu+;HO-2Rk z{v19TUENI`i=I>66`jy(AE#t=ISxxaBv^duil=Y8UYSROqw*j1+x_954M=&EaSd*C zn$PEYTq!_1xj)sfx`AiuCkHZY#h%>nnJrl_*Hz?MofnY+bmG4@*^yIkX8NGLuSuzR zr3d7}sYZkcqm<2U{T)v}E-vO12?L*st))D=BKjG3#&|U=UHzXNIe~ppbSZ*a-OrOO zmT*sBl=57zjIG38Su|R3faq7oa~HCePowy=xYgd;CG0M^)SeNuY}*C2oEd=; zQJSxrACSSSF9}*Oq1fDSE$^_ov~G6OW(Or&p32(IWNI^qp$0iap_k=zri9Mzm)t^7 z?^xTvD4Q|u`{P5mc;wNu(cCNk@J6$yp@QmWzxC)R;~)h*px3nS3}?T{A@%8^VfFd) zR(+@Y*g;o^`Q%@!U&GS}W`1E^$Gvx4Qa5@pG(3kzg8dKXcEZ4J7<06JZ+nNk1K!tV z6fj6wY|R0kbs+`*a(C_?ZWLz=A7*NwVE}U%?wv-SaJTh5tHg;~{M^l_i|zAYLMxAO zhtXTl-&Z8+#vW7cUt&3FW`95P`P)$oKf$TH{>g7`;@#(d0#Orb>1xokpM(eVJbCLo z8k~jlf2mXNJlzU@I+x;n_q+A)xKSIf|0r!&&`uwdS?Av$vy<8<8K)!O``~N)Z^3k^ zdfkj5;y)`NUus%A>Q6#T^o5tHfTP6TRg|;D{sTv7?m;sKNedaO2Z3+ z(xJ1LCyM_|{muVXA|?Nt+U=ol|5Cz>_k6T+Fl+SnRY8}hS6^~;$F|%SMFW}ell;wn zMeTf4qD$cZA0z)Gi(&N@{ou*fN33n*^ZB+p%gT{-BpyX$`2O~RAN=|KXA_SnO44O$ zN4Cgg^-&xDY{YojlV&ShYy5*+_^{aRepldoPg*gIk(RCGr{#~Pf60d)yb%EB6)44p zln9!@r9NeY*=6SDH$w0a{xr2IuO@7Reupavq4jjgq(I%bO1nC*vzeVGP6wlc-Xt)k zwzFN9Xtdrr>fHO)KOP+7dfm@RNuJHTlX~My1j94GRj@RC*R|OF-=T`I;2DyjvS;$` zqJxWVQKN-5WX7TGui!|sG3a5Ohpf7ZlP{jepdit#aw6z22p>~A~(>1Helc+IB z4i6}UD91sP>glHhFax&}o)ZcTH4+WhJwtiH55-1pOdwb=vP#kfvz`+#xR#Di$t) z`guQXc5wr7k&*ize-~efJGKbc)6rv>$b9ZukN>CNj;^V4W=zPY76Qp9L|bmSY`JYtx%RrQW@V|*fdirRUis^ zRr2I1vE-U$k7MWr@yo9HkSqlR3R{V&i8$8%IH7|3DoED9c{qhZV)1HG8}oh zw0Hc?UTAh#FQuL>PN<9TF>TX#`PI_)4;>BX-oiT;3J+l_(^e1GuPWfXs!Sl{^oCtI zZ;ULJ_Z zSii0L$LqNb&wf9{7`*TEyblH_$c4aEJNN%A(R2iT2>uKEr=(FB7jV=8vvR&6rNosH z>>pFG&iGa2c57#=gm+HQTQ3(H03nA1SZGHo`YbITq=@SZ zW7m-42Fwfdc^Dd|ZQ}GzQ2pBr^8B~xe^?j&^Fz#;rg0+T`^C_4rlft(JDv_!wPHDP zXeNGp%bj-N(Ee#NpWTuOD8($2)echSj`tT|eQgvfwPYNxLNzt3MXauLsnUY=YAJE| z#{A`i5$lN>N?-w6NJWLm3Xg1SxR#=93We6)wXqYNHg)u`9(f{W+#B-5Grry&ZIqC> z*XP9z<_t$j5@eIt&8#KqDi;rG-wWRWc>Ck`LCb^R-i%LwJhIQxNc8Zl$m~CqwWNA? zg7tw#Z<2q5TEs3HiQn>srpeO5P2npduq1DJ+4$RJ(@%#{+HUJr*$*WSjoZH!x)0nk zwj^505f{!|VdIWq7-BvD&u|XU3dFQFny5U@LZvozp|NiPztMRErDCXGIRp&%6DQNK zJ5@#~^-WfhXK7GJ-+GMD4a5~qG*COMpOtX>&KgxE#rNtX$F8{Tf#$sI;>s&DbVQ>7o@(@zrm8f7%Z4>tIjF?m>U`Xyu|(l zH8+9;bI%aTD>@|(pera%F8!2K8uuw~7Vh-5Ka$1rN7QpKsGN+pJ4Len>~p2NZ#oXa z)bUqy8JHrqbc@FH%rQ<&GiGL!`)!AApsou0MM2pol;lzxsc-c1NR++un-Y416asS2 z0yxVbE&6rX6DM6C(q--nUnR(fvz4&TFSOBot2KLW;mJk!{W->uhOBytl-JuYe9$<# zae!pyy=J|V1Oj@Kkw+XcvX5nm%JUGsaO#G;j&VWNPtuI$c!xTCcL_x%-x9DOVftVB zs-7It+hR9M>IhALj6W3QlyS|NKbXKn%Pqc3iNbJzk7b%gTQgtVzx{CCHjs!f?njkB zlw<*bzYQ5>3VE*<3f`R;4IJ}1IObs2c*(R#+4*BksRGh(idza~lJE$zF&x)akr3bd zqcg@L18I2@G(FIw*N4`xUgFwKc+Am;s4Qf*@v~wILRuldSR_>_J~}S35k0Pc)s&q}&;do$Kjk z*a|?Rm?muTfVgWa%wLmxFHBu1?X`^$;~`j}F_EL=v`brMUtsWdS~o~p@MrbSSHG)I zY*~k6QT2he$y_U(JvYD*(*Vh z7nTU5uqe>YF;eZzu;rI0MDv4 z%w<*5diWbisu~uG2D7U`2WN+qXqSgf&z)-SA{+P4No4&Z?VMcJWOhE^~XL%k~+HZEiIAD(NSbC>SxE4#mZmzNHHh8aoA z$mf=zvuX69$Ww&tEF~~B*d=DJ(wg}R7la}@CBUk8dK4u@L_}`3GaHKA&-ZqWF2A9@ zP<<(YU+xJ-mY-t6%U2%G)|qpJ_UD9$>X#XMwmonCnXDHf&mSyQS{ykcw@T*^H6!gZ zAylnTK`RfIvSr9Ccj?cuVXkuBy1p6UaSb4n2&hr+d0gZvEq0dk{0P_;<(Vg8g%zkJuK0_Er=dKuY>DJ~c^ zGuvNSn6#f^61v*&c49R6LQf15)MlbH+EOhz>RcL*T zMnYm@YMjtBuuh{@twfuHN3!kr{-(LCuV1rfXB7^l!%v^Q`9)sXw?PeY0a;%Lw$f^u zHfCLJn7fKU-kd*cwGO}?aJuIW@f>RMVMy_1WdmNd{bC8>4%&PezUH?b*-__DcGm?e zkIlU)DC+$-U*EM&l{hTq;dxXw?3F3UG4VodraTB)fmd6X+r^29B{rY>3gvPNS?Zp_ z3L*7e2Vld+h4nf=_-LUHr#P%71?r6{)Hm)5G$<+XP6A~q={Z%LUN_$t=bJm~>hKTn zE|8+?=!6k(;q%p!o;|ZnzlW^~6LARV?FIxfQ&DY|JU<&NDLe zpIUxkY=x{~uc;Hg|FG~WyjL_+y}zS_U&6f|h@@s!IE*p?_w@A4d2jGgbR!UDU7X^s zV|j?Aq`=V+Dj5px4j#bOkeWO}&&5`qIU141j1DF(z|sA}cCXdJZ=KFWxd^SPF$k9x zgARqSh5qUbnBMeiERuXt47?n2qhnNW#`?A~y!kpv@R5!zD;u)$^%QLiB!Xq8s3Tnn z7gtsFxmChqDp`V97~|PGr7tV;%ZI&ue*Su(gRK+3rxx+7%+S=b`F8|;An!T)Lx-u+ zNNuv!SS=z$Y?T!+5pa?)acDy|A}Qp0b>AYvc>JvdF$feaoF;)sHhKVYjMT^64X(Cx zaqBUTI=(UDgY~EBml`EyWU$)TSN*W83VCK`RyhRzY2EU=I-Q)N5xMqOl!T;~mYSMw zs7lL}^49o3L7?7Kac4oM>^svBu8C+<4|b~Q3NoiDSO2iSZEvDXN1EwW*mYxdnyt7M z2XjHR{Ek=Znuf!QnR!n)@8sPgbHHMh(F=AoVI2&V6P5Nysog8HxalJW;++IP;(=Cl zZx^o=Zo9O^P?Rae-kVGY-H;G4skw(@kLPP#JdSb1-jg)9jrDXKU7Xx!W}OvYNs+F? zq-l2T8-Ux>hYOVuTj<*`e3%{&`dCaP$|wNUU*;(D%aQ^F0$Dc+JJ?01%s>}Ak2zF_ zw6RUOj~^G#lOOy zcmt85fa}edzTB1ne3Sn6*B3;x+Pa3!%fL0XmWXsDOt%P&=^Q>iK9gQEW}>?8ZPL72 zOgn=*-a2SA2MhX~wFn_Hb*grmuYP*}O@z0>Jhj=^>W5>IwEs>>z#qwz;bzvRLxgnD zeo*V#{Mkvjb|-d^awfQnH`&K6Dkrq0NXGMYNZ@l*)j3>)H7V8oT~&%K7~p&U?|84M zz9ZJ7pGow@+d;pRZTrxyQH2&nszD>XQU}ZCtX{9NHu~=Q_BTNwSr z3uCv_DB(&*Zrv=aeINvHMqz3p=1gSyy>Z3&@5OQ{v3oDyEB-W;CVyy8Z47@c7∈ zE}!msKte*Y(wC%NE517E?xz&aAOsyPhz{~lu70UqbvVl~Tavqcc96D_zmNH{8m!t) z=iljPYNt>A?MFnJiD->!!YEkjxt;IE7Q5vfw%gLBNLRHeUH&sEBmeTR7)xXPAFHA{ z=|>Jj)B;-&c)qnB-}!p9i;{;U^@{aSDW*cd`Ebu6`uDO@muPBC`kZ!m{RWc$;lNIm zqjoKDJ9Kq?B*iTp%T3&2&sFm?i)tq^b91KB{r8-xia)o6vc8{o4K(|{H($0j4LIM9 zvr6^cbkat&F6CNeAefubg?pvmWzT4%za#ikMZN_jj9&2x&$d{h-@}b6z{EriR;*Y`@18+wR|IQ4d14e%8W zsQ3G+ylBkE<~@|}kt$g1aTY%?IZ0!G4OQd&qaJN0Q2MJRwX$(@(Pd`(R-=Vlrtkbz z33D6kBpnrMX5=<^9+zvFZKsbkg%g>KjdPF39%|<0B9kOA?qrFaMVVj~iV#S$=5lI$ z{CK5>s#`+v=43@%fkz7-cb4IIIMo>^&1m3axjYa31}(c@m>Tp#_fn9IpI%`>s2nhn z-FV*Cxp<-rZ{~e4$;Kvax;9?YTGXg>vjmz!Nf`tD=ytd+eoY}H;5@-BK_mBA!{?0X zrGV&8cjF48t_{A~%%?2r$=rYt8#7}OM+2-rJ!kfaW^8VN$3sKxteOau*Plp4Jj%OH z;CLcgBY}D!$m2Ziit}pmJ&ZKGA2oA6uaBpns7!`xsjlZ3T4{K%ZQ@(D$4H43+hfbp zd}iBIaCAOcc}Ldh-zU~vZUUX>EHA|{qnhRdfw#B~4a9AoQ+3X_J8n4EA8m|TtgxbE zLxt*5u?LC#ut1JuD~0UAyCv8uCsu~>`V=R@P6?Ke}gKdMHip=Qdf zUvjz?DMB{979wb)pjODkHLSkwmMIAiH)~^#F!h_nBM&<3gcVFBeX$CQ0dvh}Lmg7d zHf7dxjKs%t+a)FyT!Sk$aAr-@NM+>YAqS} z@01x-R@W^$#dsT9*e;Qobz#p^;1kzeDez^83?b}1awLy5lA5C8h;jaTzAUNZ65m8cyFX_5G3v`gB9cE6AjSL1=Fz>??75U+n zFAs?o+R1P>$+DuPL*>G>n2M)Q97px<|xJySg5D9iCzDcBwGGq*fFO z^&ixw?-*Er5%z2FoBY^^8FXo~gpVZ4*z3<+HlT=6TsGq8&!71j{-?>drD6qGV%*VY zTG>|O@nmSwfL&2YIOCZ4(R?6F;@Or(nT8rUMgN%XzUCtFG`N%53w$2zUpsrSu4~R) za40X$VwLr%ZnFyWD3Zm_06#U%gYFF9C^0EtUKev7o_sGHtto{&=iV5<6^~B# zs&vC@Ft$s*mQDFm`PQek?QELmWUVXWk_`u&nKGm2sAjfAQHiguLUo<6)RQW%l-*N> z_ODNV*J($wSX0s`?R0(ZGn9T=W4qjaSjL)O^}zDf&~er)T$Peuq8M#DrGz_sk3jg@ z86C8~6>@44A=_@IINv)`Yg`a_w}X3-Cug4(n0H0I2oNar006mjMpoWq^mMU(TV4qd|4kETW*nK#=)O5KgaX)7Iwp;XRQj}U3$3L2*b+@S=Rw81+=cs z(=XVk(|$f~=os>={B>LS`m)VPo=~XD3i;X^{n{FGcUP~*E-8z_A-Hhm^Gw>e%4Jx6 zRkGcSpN2T5uhL<_fiDAK?u7NlJ+>U=;855YFX`)Hh)p<(5I0&EEm*Xym9Q61LFhx7 z_+37M zU)$z=s!2H`UH7IN@%~452A@HO%L%ZlVa{k*^$zFGNQX>Ky6e$*I_k??7HXLE`GQGE zIs1c$Y-|uIkv(`_qnqa0t@R?kB}3u}#rc;=-p?Xt~vwo?%tk={q!i{B~fT1Q}fkQ@-7RxEX;b2SW(c6 zzKx}bn?|du3wlWz9{ESYZFhMK5@o)#A@1-}_&L0pSknP_h}b88R3Ilc0T z+9~uI6zW5*Okw08`S#=H?HNbmD>LD%(K+4mFrR{({4SAFl?O4bJhN|2 zraz1&#js>p;`dASX|V2ky-_XpVmq)OW7u8uunOfng%7Sz41vo6#*rk6XSL}bE034KGV>y#112Kg&gM@WYCH6oUJ>Dj8E{}TqBa}5;Ud~8}rOvt=sJe#?M)OR&yIwJLp-vz$qY5rc(jOcyU-q7;O}z zNNLNp5y>gE`(8h`vtMgU%N#uoS5&+o$C1kRH9ft>ZmM#BfBzbtU0{Jt0k3{&s2Vd_ zej7#pR||eO-@2P3zrC=zTDmtuRam_B^?@P^CLdO6_M=%b!2pIXbq(Gpa9 z^#TDzm+vwR-Fhv^3%@#e5G^fndh=Ioql_`+t#ZC_a}R4h?qOYP*}^ct6TX-y`Le}jM079 z$p+DSFl%m8kBm&3nX(t-+DrCG_iO5Kp5S*34=r*lt|?x#`ZMd&kFDjAJlV;H=-+p0 z$w+TH_;fzrg-A=)vKL(mcUhlfc1wIdIGh)NCwo63gROjXIuydj*4T2oUo;%+gcTR= z+O?W*eyvq|^f}ipf4|N+{k+xHMqmC#>SNqyA-b#e{HJO_Q$-7EO5p4>%VT8Y@ia*~ zuM9dONZqDZLnIoRt`-16rcDct9Azaz!F1U1Qsb1gG-J2=_5Qa{aQy}^UVKSTh7cZu zi_W&Q?EhF#lkpo6m79*_YeemnC$kHs{obB$W0(3;?p!|%Gi0v97>_wn>cQ4rco++A zir>%)2$?++Rl<2HGP*qOpZyH_Sylr&{Q?ZIibF};!@?-F=7pSI>;y9^*X}?-qz_wv z)Dgv$Q5<3lzI=k26Ug5v4DzV9^Ia+3kXDtPUn)%F@qsD_UiC8d#nm@2U}OS}4|Y^F znya-^JP{jJ#O$;_t_#}=ckR%hn!(5 zj~bUy^m;|^Kb8F)>JA;6kzOQ9qPEPiVECDW#(?pYt>GAF;WVF}aDFL>o}DokM|rEc zsq`SJY(T2zG@L(AA1_^@A??u{K-O4LX0gXwdR?1%qWUcH2foR2HViL`A3gLimgX&4 z4GXfA(G~O@$jwgKkm2`oOcX8|@nNq)QDC`6{NT`|tLO#W$!NdrDXV>dyMYdT7(I4y zKYUQMet$zOK}!3J3$||{;7`e!Jh=MU9Vx-t_3XsM)Q|R8!`oLs{mJBA1}iOkpWXVV z-iLQ4Ing%~JkK6DukiY%v^sPc;*AWVwPz;=fvH^-UPGZ!IXO9aN)qPA6!#xqibD5Z zm<_DM*y;nrEGQM2 zu&iyg(_fzN_Uq63w>^xanVLS3IQ@KU*@VBYa#qJ>l7tq2mMS5#rM~*aby^^7Idxc( zk|M-@N_^^ci&-hEz74AJY;Dl|d%>Qm=bx;Yv-{}6>2S2qfe))#Su%FeE5>oZ{>kTz z!`ZJh`Hf>~6-udM0%zYO7Br;lQ*^=N8Lrd68Cyj-)3B~tJ8ML9&D((8yh>m2a*%&fV0r+O^e0Ac37juk4gCwZbbg#oh z#uogatbur}qe)kqgO8KSAqTF0V@|5dxEWnN&kd=5z{#0Ef0z;9iP``z+0?H;XxOi5xM>QYtoVrs*(z-(20nb?Sq}1PR^Yltx>p=XoF@HBW2AES0g5bC26byPzRbIWjR&^r{ zFkXyHse;(6`73&4b=69{_H3`151!tL95W9hV}>2lMBi-4$+1Q@!~q>Qy5m~^)vsk3 z;LTk%u}$}UU^ey+(}D2hu`ruB@<$7TKB`@LlsVMS{Pe2e3wEwd;KoF9f5lY*Zi1>O z8JE6Ec%%RZs&TcB399jUHY?n{T5sY=0F}xk8?~Afc$DOst7nj7=mGNR_Vzavz|8(6 z*?H1VxJXD541iIEg=aOlf5cn{X-3|#2EGIY`uXEohH>ei{r%YU^8;wJm|xA5U8B1$ z6*YBiLc%9WNiB3bDJcaFpGwi;YpTO;Pro&TmyJeBzB1vR+Hgvq_pWn)~8EJzz36yFocbk}FwJ8aeg zE~`xjvVL#{*m@77U>zEXGUGFNXyVG7o&OUTU}U7RaNj`4TW?0EbMRqj_PKv+uywMh zBx4q5mun+ZK8Vb%5y=u|b+Ws3kRtu4zP_F%O37jt7#R_-u9eV)i(MzVQFHJ9{e)Pm zxY*6Kf^t~Tt=nG}z#W5HC-ZW#sbG*b!@327z{M*t)NXDvnY+s+Jen%-6V3;~zgh`x zZHa=V%F1E%jEEzuWomJ1dnLnAcaSms8D58n3>}vs1gODFDL%`4hc-tTiGCZ?pcD8IgzJVs==~*G8C)$|=2tJf-OF zH57aE3mjz?SkD(E&d#e}iQFodOc|)G)XJ8s&QdQ}r$oDZ=ss$mGlP@wjNAZ4&|VBV zQ05eW9t{&<_lv3M36MIVS`5I$!{Q$$dw|Y8X}1jHFB=ss$;o+{#hz^!{E&FV4A5Zf zh3uj{-zpuDDvMw`N@@oB>fnN#4bYRSb#fpS9L!t!k)pDP!&cU37BP^Z?%%$Bm&Ye1 z#V!*N2qCj6`xctnAvp3%MFsM##}0sB*WZdxl$mCGOKi^8x0!|b2B>DQRehB5(|el7 zVVBuCaz?$&FFSTqoV=hMVk=oc<{z5b0Nj5;M)vO;9%`2egTZeC`Qe$!Ex{Y9fGP!? zz#Ies#Y#)Ro+wSzn)>o%WyZL^yw+}fgJ;(}jGIPPFbA<*!x*jNuW(P~BB@L}(e=?+ zBlMG#r(4R)Ww}VQsK?TPd!KHPCCH~a1Wp*HCMI$ZY5pMtMf{I)_Y;VHaN+jUuViX? zvA6&*KnZ?O^W0N&#YS>yGk{`VUcKgj^(_Cg>2>{)6>Mm_I}_kO>6g`t0uVDozX7-k zNpatfyC8}N5Nl}rw-yEu3ky=1d+mDK@11j%$D|_{cEfsR!gZy)+5B5km?L01V&T-f7k4*1S}8?)EjS+m8+^&5q+DNdn*%M{ z2Us+~oRbtMRFISNfX~swayk9^lxGkXm0h%7Z&utFsI>sxNm-c!VC?7z5COFT4N}pC zR81JhX0%F6NGO$vG}r_7(cQfp({{p*NSmq-;G0`ftix~30YwUzF@Hm}`oN}9lX5Il zp7aU8(%4ukdY9`A^sdUvnt;LvIP&z(V%~`+9HR$6eq3P5>=qyj41<4CqKKGLQ^|f=Cj4%vuMm)SC>h-qJOC_C#qV-!{ z?gZ2?kwr;bl%E_&N!-V$s3!O~@EHrSWOXnAY!NmfKq7#tFoi zWhv!Bqy)ZNGd-Oa53_q)|20C7ak=p7Of4pdE6rZm(APJsf|yz`$o1gh#2vuX4Rw0k z1MjlMNvF&>fZKcn-KajHMQ=j=pTYqNfwm9As;Z#(O|-QB?8U*@ybm566n;iwG}P=( zwS{@&+>Uf77}I3?Zd1l61L%kHzt4S;rL_#q6U*FnD*N1QU(?bkwT_F&XVB_FZ8okm z|JgKF_?=m1Z;O58Dl84#CLW9^Kr5Ux?wu;3TIgVB3(5- z1M^dEp;$3Sdnu#RoSsioXzA67OPR`Se}xzPt~UU2#i)xQ3#!U|6*ggLJ@=ZKBqMG+AE7CYdWBqCUiOwuFVxP5(TR)4 zxUvW8kt{!h#3>XR-0*ABin5ab75>Q*W)0zzq0oGUcDFJ!(;N#b;6ZMcYE8lA?W+J~ z)suBe(EZ={U(<2pl3~|A^bP|*JrmV;h*@x^){RI9PODr69P=S}d44WkJkBRyrJx9w zTjgT>QQ)1!@6Yh#h@e=IGR?_@u!))6KbQ5q&p761ShJZZ;o zVUa5|rZj^d_@V>xD@hh&v<){IhB*Kh#4pLGpkT}Yy~j5*3;wGucjchNVDK%!wZRQmcuObv>;-9*IV^3EdcX2LSjNS2u_g)E@sjyBAaFP9b<>!{tewsf6& z+3Fur5fiAMDlhl~l$Myd>RcZl3}7D`Y2vy(jB74tW?8|BB4NTIAt4U65`27RhjHtl zfT(CL4_&i^za62;oAc#@W{^Vc*|mtH+KCOyiXu8lvrGi>Dc1j>lq?CP4b~C1hj-Em zjdmIXmYo__Di-Ra{0M;ibVvd5dIL;z6KDA|Xu!7S;NU1Mw4tX*qTN?ux~Q*eME?<8 zzOaa7?fa%Gk{QdVE0d;Qgm+S3XZ{^aBZj@TfORN=jPp&k7Aq z9NUH(6pjZ6LkfSsFt>cVXuEF(pk!rS+d?MM$kIlmZfR35Ik{++h`$D-V(lu_!(!{_ zU0{{Nx|PfYVt-|1-LQM*k*=8MFR}>7>SFGS8FPj9rO?_Li4a#6bq8drvA1uNY6lTP;ZgL=SBfE6j~0@K1>5BmP(+{$Lzu~-A1pyKK&!A4~A*RQXt4D1N{#B3~I z8;%$o7Ycg*_+`{O$2+p_*MK(Ma&N2x%$kvrvE&aQE|*Q%*3JOWWLV`5<7eKblW2De z`p2){K_2Th7?lD`l%v%}vlmHG=LVtI-D}&A9^VW1&OCP5U|41?Jzsyjl3qe3zDkSQlJB5dR?`S%Fdi;L3HYH*#+TR+{p2a|;hF zEG&Rnr_jLmc5nv5;{n336{><5Q*+tkj^itd^oiW1Ync8n1(y2}-_#^I#_5ecbprrr z=v45xG0VGqG%&hpOj*J7pd|UWzC^?~sN5o;+%WJd!F+*E%aP*o#8-pqU&yWCP%e+s zf&GwYYfG zF`?*F+x*d)>N&2N$BF3ujk4N7ho~Y3!xSYG)Bd!hjXRfDlY2h)JC!s5i}>K2;^MxI z14Z41Vx5^c@)5I4{4<0JIz2VDSbae*xF(Wm?AjJwyZM{0Q$@X1HNWFG2<2^g%rsmZ zDLC`K2-?igXoTqhQAb|CQX&wx6-E<7XMPpqR;a-R-x zllr`lP7fHt#g+LE5NJk5i9hp;(_%|19n*-ou}*k*cQ=>gHQf=xNh8-mGs_K<6}X>1^3?7lqvD*QVuKri1u}0sh=c zTfLh*6cHBG@;=QSy!u~5zqz>3(%*$o_W^Bt3eyRY!l0|b5Umqc@@+z{xdsP!u(4f= zes$*#u)V^p0v6%smjOz~F@o5_{u*n^v}Lu{=;^YN5rL+;r`aAZaz88qvuAHi4_BNF z+MI@0P5Xrg*F&asSep@Kel5Ew|Cvo^I5`C%YzWRzpJpN+-sp&xm_a)MwsX#sD|oc| zygn!A9v>fH&gJQqJugX?xOLd{YZpX>aicr4Yg_0wEiElJHo)mxrp;mq^aR%0Dj>~* z2bTg7E807*&74E?m|vPe87-}a9Z#KW#!LJTvqbXR zP0^=dEp0>M%MBfD$$5s{ms0v6T|3}551MzDYz@551gq)Y_Adk~v!%hP8}M;@;})C? zr9lc>223U5#&quJX#>ESIG`D);$<9dg2vT`<~Y~LW-mje(k9Mokt~KUw)3BTUve%C z`Y8E$ft#lHy?cP(-8_h}bKlpmxAi$FcD$Qm+XnVPtU99ivdv^oEIMaTeWf#iPuZZP zqy$cEA|3Sk+E@0b?0}n&+?C_5U%v&(QTZmt5_Jl(mybL3FNH$fb&SmcqbzayWm59A z%Hh2sEzSAbm;1;@d}LGX%R%o?ysVD6tv z&FhTzC?7I%iKxf-TwdSbcU`oN`R4qbLTvXJd&Ct185z?Ok)AAFnBj{Tnd@P?FvdcD z{oeoH^ymIid}`lB4(P$YZ0lmleXFQf=BrTcV5(-#fk2 zlObP+-1;UT#1NhPcU?~BkU_88QdwCUFaR{ccBOp04<1<8{hSHZwznxi`9xf#~Fn@@XpRRGkGQw2H2vv5rmwgKHgfEhI#lSDz#Uv9V+K?D=y5VzH|^#f+1J z&J_MCoBwpR4S@Sd>?89x%43Ku?+x)%0yBY8TnxGJuEJ_=YNJ!aw>Y$S%2`yV~^C+#1*`$tf4eKkl2`*k+)|W zs;ahiX#h|n=)UYu|9OA^rmhHb5SUk+O&mpuRs(qh$U@RLZbvmB9e_#pPkm?4m+ufE z_zq|F= zE>eKQ81rs$$_MaVbM~8W2r9seJ(UV-BNY?e=wEK$HO*tbZJzIN>PFzY#N=7CF z2<6E3>95Sb^BZN6rIb>VaRHe3tgzSa3+SEqzscaciBK-$ZhaNGl#-OoO&&Jb{prP> z7v!X%dGOy3{BCmhlB-&M739C8-*111(?P&bZ)ANU8v+e(1Kt>6fKRqP%g|LUq#0#! zUQtxL+RqiDuAw0^z*iy$%KS$04~|j-wr}NDs_T_#Iti2rC*Ra1w;z=wAryK4ugDz$ zf@%x8r2*6(A6%%vz6WTgsGxBs5c#!#!o3_e3)~|!)uqxp;?!H zzxvluau}@M#or&7VCw&n&9K%XVz!Q)2MX=~7Joha((gO}0J7vdh_h83Cxjc&%eO0b z?w%$Zx&#NqLP{AFi@u9j%3po=;2(>ulc7Cnx~q1Ir{T$T%GJR-z$*2Bum3N1J7-kN zL+@FJrjjC^J@2P@zqZw--UL;PM^V2bs6bi&{WIMuwB=m9y}bcGM5L&o>#N>_7>Ij* zB@}%gS}%G^M+$oS&&f2>X_xdpemf=NAUw)XXxAwi_IU_k&hoSArd)5s+sZ`NdjD8I zWZUXgrK5h&I$fuH>%UCRD4oh;akq~jhbkTO$;^G&Y(Q#%fm+ZVh@k5%(}#U}(k>>& z-j=nhXqAcE$|S(@Zr(rCfcz4C-$A&jt4{1=hZ%qbPbQAMaS5r0Xsh1i$r%PQi2dVv z8_ay1o0MLJXebYQk0%cV@k{xlLS%jU-zyy~%T_I`r3e>(dfe3?E5k0HlrJc#m#n=8 z5m#aKc^og_Qqt$atn$hjy?6P)A0D9q8$jmo4Ty%X7R_>*LCW7($X%~UXjophE?V-kY|ce9F3Ww_+o}YUzOv%b zfRE3>-XH^<%Txyhj@;o7p!Pu&VBj7gSy3nCRf4Ds(h^YUkMs#9geO@SIiSyE6P?!n zW|CZFvg(^&WLC)%GLM}O{$~0SGQn49UtMI55M)ah{Pxmcpy&eJ2H%+Yn@M?*ne&$P zZ>GgXP4a}-7d5pN2{o@c(f`dfxX7f@2f|4KFBC)2y0UMaIR0j;U1T!RnqOp&5Jt3Y zyAu#`14x2$7nww*U4*B1d5R+!gDUIN#NX1|**1`zARr6;uVdB1JIubF(}UhU_`yL> zr~{56?d!i}DK5w|mi7}e-{rmAC$!kU zbkX7<6=86af2xzb(1Q$8!&V?r7N!1Q?=bsUJ~>M`BI(EU!oirL|OH1 z31wxoFPOH!2>nacmq65-s_xa_vaEzL!Elv#@}gbE&xCe6KiCQr9y6l}8auP%ck+JqkB@OE!jCfi0pB9XS;z0U8+>9V1a8pp+sQ%*HfGpDgL3{tbzyb1T-rn*5 zR2quh1-QlVuoOjT>z%a{L2%hSIG6~JMH4dLSznAoN^{C+g)kZg!kn+7qT+wDl<+L-GLSEuEl1$Qh(ISRVL`w8N6yezN@a%0SwuPoF55)C6L`eqC^`2ksWsLN}+zZZC#|zfEi0 z0E#jQ{p)wiJZf6nuwTFiRzbB5RBJ#^*9cRINizi8;ErafOpm$!Fg5yt&WLiMhmDO5 zDV7ST`?zY#?hN%GpnxXgc?{QW^?geBft{61V$M0G8$gWLQR7yBY&@?q#7&BmLrauh zvmg&xZvwPy#5h5mynHUN{`~pW4E`UiCYOkl;{#A4cz_dVSnU=;9MtCKTHV+T!k(ta zTDQ>?x?!CJSRDlQUz+d%9ss3t(F;tQ0y9KoX%w1g;fTMVcK5y_&@a|z7rlM|(B_9+ zC5^r4!=cXt1pbeb5C%zdNOOX()OsxTbgMs~bYn=kP=Q1rl7L%8c)t21LboO-6rQZE zA=>pDzw>?vZRA82)JBg{K_^Nr#6HTv!M?K&+yzq%JfniGu=)dy1~XlVz^xgaNC-Jf zzm`b`8@*dWi#q@FJJKn4X1C?E!lKs`ccb;kYOX>+e7jo1MsrbQc|46h_GE7b(`>iE zxq-s(md^9AN!2We5MC7Mal%xz%np5&iDhgxY8ZO5JZ2%DwwKkCDB1xcJ#nT*r@BLq+-3>P+qkJ|CETV8@=i4bpjdF@>n1Wg~y0 zOxo!!qNZCJ?H$#+orKA*3~tC9p`4Rj&FZM`?h`xTzRS*;<~nCwCM7Ag7J&Ejw<#>$ z@Gkcp8^I?_K49m0IOR9Vuivtx3jDi)<=B3%^*-~QgcRK3DT#iH2_>)Jagtco{lkq( zuA#Vb+jEPuvLp1ASNZlv7jNp9G2ZUDVVl8_D%7!8Lg@x|k>h5*SPt4!KhbI$7Lq@dqS z$_lIB+*u9fa#PE1B>s5>c6B(W)Z|aZ_ui=}K+2AlUN_LsJSqI7*Wy!aI)UBDNR{?F z46U(}K0f>@f??9%T_`T}@YT-S@XmaT9G-1GHQHHdWNpR|lZwq`H138@JnA&Xwr}j= zefnRgWVHNVSlJ_LC_NiTdJOYd$vBE(TPBuU-!58XRISv+t>)t2!H+&xpjBI5o|l9c z5~alRV*7=>e}12=9P>zfyo6$`|4u@T)GaWR$HNhy>1 zA!i=Nkb~SF`r0}m-VE0}JWx_q@y-w^%*ORLA2nM^`Qb+JB3$a=Q@qvQ3KrwP*z0qj zX(@b`M1p)?@?jhzXX8icF!PMR0dBaY%F0gtQ$&guhR!Ak#0D~{Aj*G)8v=ycb>!<;aJ$ct=`&tG>Nn{ z9M|-pgrzrfb=_rSC+=|E60zMHvCW$u#1ve&(cm@NHa^*IGyjl6%ky%?tS?tSRf1Of zcvS;icDA*Zu3)pz&9+5Tl_PD9$o2xVUV%;!&50jbs1L<3$2V=KW@OHdS}c&UWPF=bR)eMvA;<=KTF(BQBFb6ZCciQwG&q=Mnk$-!I?nybgW693=FrT{_xGk2cLtyEO&!&;Q8P>8Ln!cJtX z8~#ui)!f?y*mHM4%3wL2gleWI4H@PL_ilE@Be-wfDRJ4{Q7~nc{n`14TjR6do~`IG z>6dYj*ILbQpSR-5OLI08Y)@+%^rU2O>0Ft%J7IqieJiuAbNo89Fu#D zXuZs)HGgv4!ie!&EHbUx`qJ*%s=@kVouq%b#D1oB49E50CQPZ;VMN893iF>zd1mJk zh#=n}vWs8+YWsS!kH&M-7ZD9!=Sd0N%}^kmjj{Lf>Q&B?y4637{!D&*NWQ48ujM`` z$b3_53ZQz&Eq5QXmo@H|dBt8)*RP6C#wSi?c@V3Bl!zaAhxNbe%QrVieXycL} zMpR)xaq{K$Vs=$;ltu!X4m2CYlxh= zo5@6ALn#M~A0jIysEYwXJ5m|Qb3@%QHZ>YTrdbc*zfLN}HFQHnKi+Mb;#cWMFi5vu z=38_AU>~LK4;y*222*owp0C-w!=)52UkZ3pQZr>HC`Dd;AVt38a$!9L5==462h&8W zDm=GX1@6puBgP%MjPb~1WSU0H{)g<-88DZ7!(uf`r|iRcSD)nRXM?hqb77sgr!#Gi(^l7V| z57bf*^45QDIkuPhzU`SbSR~8Bm?JN5v+9X`jk{Q}#?MG<)qn?#5`(i!z#6mf9*JG<#W*hQ-TA<&Qfi}5biO@V5joTS@efBs&xnt=Ka3`dFjGPl|QR~ z5uC^UFcIGqCsL-y>H@|b^4MFkM24})R9Eu{5GA^j5op@HwOgn>!zT&z2-R!iFFP;a zQ}2ts?)AlMTyn4E*a?5S@|qGawUHVxk|tKrF&@R*v?jHYqcpH?KIUf3ja0{Weetm} z71PJ~^=Ai7xf&}DV#0JcAwyqWqO59 zqd*@n=~ucTnRc!`FVzD5ay^F~Yn{a57 zwB<>yCUz|Y8?`B0e^zZ^PC07Ajn?p52+SYYEZ^Gc&13eMEu@`0Sr%b&+|Sw6>=)Y( z^%+pZ&(GQ78y{M4_~Rb2&U!qZt@Pm&U7B3XGd}#TWP8J%`MXnif6FGk)3GD^h|Xof93vwHuY7z%DW-6e{1v3hRCeNK5iF;Ew-9LL12_!u#g`x8b!g!^6W2rw<90@BYti1a{NL zpHAzVuU$gMjyX??J*4wkSWzPvuzg5g44`L=b zr&$Ci$I?Lqlm_hgxOq)TExXk|5g-r5LjiWD9Pp~EfPumM zD8Lmfga$KrU|pbO)P+wEI*0kamOv>Gs6d3EB)*5E zfU}lBIv}V|(8uy;79^3KkIt2Nw)ZwBjC~PbnZ1uQE&zzEi^cu_e((_!v;Q{O!Ewsi z9VvJ-!3!Q7@APW4qF4m=uI!qM30Q5{m)Vnz?>-npDYvPM*8gofff-T>!d97C0 zkxc=i7=RRHRa0TOY12GflDbLeRC$(A>nLHXrLI?2EJtZMw?EyGrr2L;vS%zLt^KsC z1$%ZN`VWE#N9cjt$F#;n^wY=xMgw;N{4YPC4Q|5os-M2pW(gN-@y zo5LO!-~D=(iE@{Ed1F{Y-MAN&{VUs7;vU&fTQ zMY~jMK_oe~Y5xFJXmgA8Xcppbfr*u?^<63Zh2PGLaegxVReM<6BC5rI2X$}`DWaY| zU*^a+t-AC05Ehi-wcn6!CevuMe3kEn620XJzU? zADv=JYHw9?yj19dNQ~J?cHT2bNP4afrtR^`U|~l!#0oh-_mBy;X)z97oAoOhb$he^ z9ge0_*q;d^*TDB)ZqEw|l;I}b|7>=ddT-S%nn^dW%}T@r2Wj~cak?yB+u)XPEPhr>+pDWnJlT+ zrvyzg$#)@plqs9}_|L(?*2*#JGBpQhnC6`&bT(&aSn%;g)4@0&55NfLM`1KnYG{R# z>hEP52vOW;nW&Z}+zEEk-)C>UXduNBQ+FQ!US8=IAZ`aLW&6*EE~n`E!r{KyT9g-u zfC7mfUwgrd+VJcCjWc%q`--?mHm`HrrZV6m;Cpfb9Y z%#fS(i4fmENg9$zW1};lA+{|=SvC_pz|a}d0(UYds_V$-p?M=2H>{6ri7!}Py2zu?>mnD z_^ng9K*fk|ve`!0jxG9_#T&r=1=>cviH@zu4g34qsR4fV`(4NLc#+4Qjj-=4tDfz3 zudyTC!ydBDt)uH#@J5a9MM6H->Oa$;i=Bz zgTYlbZ&y;Ck4W{&A}Ftyq>!Dr+;_~k{r!czv7rRsN1tqC&?H<2M%BJF5S;j}No0mH zY&?v5b;u{vNaX>+7kTKFKUdzyvZw(B~j&)n&3eo-&ykuh#>w_4riC8Oc8SQJvaUagq@n{K0f$pSRVw_HVH zE!m`$Yj@l&`qhhKsR7@G_c1e!Gf<}zL*2da)3=Nx&MMr~PA7l9M)`_jKCNse;`%5# zWwv+i7a@DS_Xv85;UzZ>0TFyb5~d@Jm}E7KqOVfywc=|@Vx8UDQN?(<3?vV6S|a=u zZ;=ftn0+>CT`f{U6`%4RZ8?#tRk_Km|0)geZ`eLdGxclA8cQ@E5QV<%&Sx#-F{pW) zbTdP8+G419i;~4~r>)B+D#Flzr91H2fTx#vxdXdIYywJLpi1o(Iy5d0o97YGx^PyR zW70fhXj`ue9sz&&0i&-Bra{$M>FHt8>9-&wR<>Q6b39E&Ej=>=W!YQU`yR%RrKW9}`Z+SZ!8ZO8p1)1|JD z>OyBM2b&oeh0f=#mht>s-)3Fz6jPP@4cp5OjmlwlBsMlrqj2PKW!3E4l?Aeq7?quO z?^msk2~iM!LGuZGQs~739XMGdvc=bIvk%b_beGlMiXCdU-+k{cYbhUJ$4s|H;^9M# z*Hsu86zv{Qw(473pXpb(Rv#~fG3gYgydaSaayuApqj^hzKnw!;XE}L#Acltn#@e^% zYpsM7-4L+JCjI&@Ag;(hSM`L|yTvRCmHa~O13KQ!fT%0p3Yb8Qptdl*s&4ts(Jr9Q%sRycU7g z0kjQf{pFP&b7f7r5Dy8di0+nulczSqaHzV9SH)r-E*>7wqB)^*Ls*#odqmy)Uions ztvB5}l7c>aOIXZDzSwUG9h7jb?FA`$6Dg;Jg>C?G$&FmcHdIm8ec1Mip%+922zs z0gH!Me)RF(m6tTCY_ZF@#c6#}qJu2_ar8)m0}XUq?dYoTp{8%NZGh)-3j-th!9~qw zN2I~1$FE@aaI9pztOY1z;V0R1tq9L3hg|I=l!F{>s2dAcO!-3{>kP%Au*KI55&YvG z`y|*}r9q7;vM#=wOoX>Re59|rk)8eHD+$fYt8U}b#W(qIrH%$g2pJ9q2=m*}VhqpS zd~-RNv`ub!t2nd_h-1VzV0h4q`>!ViJxD_Zy^g+xggog7Ey-aSOhw~r1{*l*c|?nvSt(cuWwRU(AXay&jH)*2H9uRl3ZKeb`sgwH7qDMF`TiPB zv+L&U9Q&Rg3L^36ES7oFtW@x*(GOCT;HloB@Z#C$FJClE5kLp>r!QPvT3R-jerxR? z#W4!d?%R7eG`<&yOJfVu{EvTi(medNiS@_u^Sl4=-Aj;q3lR69>2yKJ@c*_u|1B%1 zIsWqdIGunm4IMF%Bu~13f4Fzge+o4aZpb!dc3y29)4yKLR+@A2gpK%r_Ez^gjqb2_ z#6d43=H_(JHGXFD?t-(o#?H=;?Qf6ypIb2{zExMRZG#-;^6>H|CM4wK=1xvd4z;oe zpqYGr3mskViNn8h0{R)EQy`6w^7(2qGBVebTN196GJp#>bo=y*goI>s>5qTy?>aJl zl9iM5IbM@;ad9y-GxO%(0^8WymXwzM-f#aampE_GD4)%x|9o@rQoM&1{$Jl9 zzq34=z!HsWBM3XW3;Vq<`Bw&s2nlnGi|2EsA}SZ}&M^<2#&_m9-SjO+wiZ+C-oeLqXfTU6-Nx4}Y-@ zEq4Zp)6(V~1)*cP(6YL^y0x_x9UUz~O%n5;hPyxbJaZ%?2CI*qi%9TJcD-zP@Dk#C~cPq?i4ScNSQX6B+=^LNR5 zoB;_wq5^aqs+O1XOD{p_pMy;?jdVmlb_AgO4GhwQgZt1C&{2_*nAD9`zs1SbRlnX= z)6NbS^aL+GJzcJ0eFG3P{W5MXhD(nci@$mQIXRhasma!Fo9W;3ohJXq$2+HMGg#l! zM4g+U{m9}afHrP&VmL}Ua;Zswc@a>nSZl_~M)0;UFAo3!{2Uk{R>~p^W==7-|L}pw z@ABvo776OoT&e#j*b)!W`{a z{8z|W{`y9Uph_$#9I^qXaikCg%w-8EL29Q&5kF|}pP~CbtOyPI z`m!xXYX0E^n##!o9crdsX{1?U&^%YGw}q<*0N8D)TLf2{?x{4_7%X#7Y@-PsnpGjb zhBQDiQg@s4a7j;N8HPMd*Kk_MV|xngVB-!qctCMvv_Li`L^}p zrK24Mi(HlwAH2i8vTjs0_dhn1-&Kd^z4)lqiAoU|L^qPK)1uSa3)-!v!6jp~KVDiJ@lZ=ADi8c6+7BY#KHp#mq*hy9DY6S+paum92Q$ z{VY;2zD1`m>qOUGD2Xm-v8tWB03KkqYzq4%rQWL7b^-1@(xFGTJN|Y!|0B>KVoAg6s+G`Fw28IlKo@v&t{BRg)A-L?YXOt|X`_I5W8Y1c$9E?t! zc;Gl-W3%UGckZw$Z6&0?`f)2N#Y(mY>ox}<~#VU zmCBx;Xf3~Qbrt6qi!Cgnh0X0@-LH#_Q?s?*LtenqaR6BGmO0>ZyRQs@g@r}D`1paK zpqXwGomuGRgZubH)d0%=H!QrtY`g0!zurrKV_{+7`ma||cMvOFlVWx{+KZ~w+tJ~j z+46ex(=ZWD;&QPJR-OuQqvGn*5veuwxL%r?n)>$b+mHKhvglZL0D9i?zkWm1H_Okj zIqY{Qq&W3MLZSfvd(rwwELcCL!gbhDY4t+mR9am*uiW#*Z*JiNH zXHjwA-q!XS&B_U!tw7^<(H5P=YbD3!wx@snW%9glYD&YSUlKj@EL0@!UIxiqvbvoY z*?yzFdUjvgQ0cyn>`uf7~`r+NlLM(WM#r*zkWq)5E=EDc*I6iG{Z43;I zU{hK;x*&8^!-EIt)D=5L8n;WUrmBh`1}G>fs4@2b&r)&kj^?jHpLdFis>LDwd2>W08sPOv#yV!mv`-3j|`qTDef1B%hhg@3{a|GqT!kNxxS z&-d{YZ(>y-o!nD=*?<5?rg56Ug}aRGhCgb9KiT7TT3Spjto73?bZ>1gJ!6_g z&;5eY-EWWevl{{e0=(^W0lyDn{`^x2I9~mqN$Ln_@|Xu-6^#g;T5P|f*$0CZB=A}>M~{;c+wyjAFb!!HO#;X9>vU??rntU7im1e{i* zB>p+SpZxT9*Q}8KU;7OBH<;-6mETcl9AjpFem=;VTT@e$f&y&(E3*^R@-2oR<3Mgk z?)9ix#?Ra9MoXxnfiUnYl?gH1$$KN1R~fAY7r*cr}+MsUk=ZRKX0t&`y$-;98USx)mi3=kPe?AHOtjGJmdD{ z*S%Iut#t^Oou70Iuzr-$LBog?+Aa%pc$lS*yiH$<%v0En%@xH$+Cmufu z(Jg>W&fbF|;40y+!aol%RQ)7L+IYFf$592we^ZFJ#QCS29VKpA6Fe!fZqfq1EjKbw zNvZw4ZSj(i&wi{%kZ|$3(9^kudc4HKl?q$CBs9q{kEGMllSHA)iHzQ z!c-kE$^KrdX2q<{*}_n4mbC0V=k4~n1MEXKCqbCvfo(l`(<_1cm8!X-5qq~U3^tnN zzU(p*lXHWEYGs3d&}tA3-{x+ZlqgWha|uy4N4%xx$PUyj?_HD0Au*r5%n%irI9`A7 zYNAmlc&bA1=)G3G*s15W@sUk=*E4+5_R4?=d{Xz2gBG9tg^KJJZN|F8#&uD7fC0?3 zGD%XI$xU~2yRn82Rir&++J8cb!@(<Ipx*vf(ieiK%WngJ3OqEEAV&tPvzMKwM~tuIXvz#HS1m>V$Z4t}~c~22q3`7SG7) z52J!+!$C40W59AJ3;%7g4jM*^BqPX46v@Ly7AJ4C2IDPxK@#0Nb6{%hu(NDCsM!4y z9CMg8%VgskGoxOSzb)S1Yn;ANreptrgPm)5*&I_)gZ7>Cudw!-6%CA*I-wpl#G-KY!uf3Nz65Ijfbl=u`iaifn_|-?nV( z(>;5(FywnWPAP=#vhFTL&4GjXZ!mojC$@X)c(aMCUCBOG@QWy_YUAcc_+c=&FD2{Q z!;977IS#RKZVbos>aUz91iQ7GqHUkjsM{K=Dyp0)!Gs$De9e7rQj$wiUI0WyFm;W- z*Lg=?vKXot*Rhl5;#_#!jgWh4m>C&3@*1AOtrx|!jt@>q>DhtImh9!JUXGaGw()mX zaNT}Z4giXIPpSB6Rp(v=`?hasdb>NFdfV)007H1kUzBWBiQSmh6L)M|%{Y|50|0dK z+FGN$7M;fy>N+wGLC4P{R?VVgcJ@kZkG_lhl8>^SC=|D{bJmoN#cWWv@v+;|4F;sI z0(A!n6Z@yOX}%eFj%P4F@D>aXEh={2xJqNiINZeL)nuw|Aj3H=nI1m98^z9?fPenh zpPhJc9_|lJ^abA5M1&jSIf8exrKje&j*}++vU1}WTWsFIkfK38lvPFnR+1E=^fb`X zpIt^wqR16lj@_T=K$&X)ZsCfrxS~}B@hLI@dT$rho6^~qnnTaKIH?LmPdDRrHG1FY zuLZB42-LT12EGP}WQ4n5E_5R@$q}M7EZk-B`)(58}Pw$dMPRVLH$3fH0 zfm)jvt8w08TkBvqU37f?Wd$-qM|kEyiz`gL+*B^5E3 zt>v^qx*?F?Zr=TDA%id-%`z=Q{*pniU0~Z7I;+I3l({5QZyZ80qVG=Du=DFGLv*Tg z{i!VU;p4WoX$rV-yQA<$-=V#4WV(1|t9$nN*S5Kiq~9c=`UfSiY(+X6?C(0$ z*{4#|vAWrNM`qhC!{)R@q#KL%r~7o+Ch)WQwFR+Kb zT|G>*3Z~1kdkPZ4*gEcXnGCeMr|0(N>}g(5)S4}|Nca7IxcD>WZ%8ZYn>|!CuPm^!sYdNjT zDWb=@|2!g2+HP;3c*<|TAalz_s_)w3ph0AyOicW+6P-tGmYk+pNZ*D;+=b%`mKPjN za!pHBotleWiSmpSq@^9mWxv&*a;bX#YkHiw%GsXZXR`cr8`e<%;u25K(trXR0a&AC z-gW4-jT4+#J*$m}a4NT^=c_4)fV%ow=+@#S8=`GBm)*kAsKnDsy zh2}IRV|qqoCkAfwoOo|btpdMm1A9^vW4rXKJ;hsQ?lfX?CqAy%M~MbeuiU56yn&AM zRoS{*BOiU60TVLdq|D)!FQdi4B4#4U)PC!U^bZ<7`)a=dh~UBrA+?xamhqe8Z9Gcv z=RUCS^EXcmVaO1?^$l3M-DaLLpPPHRHQNk6+1%6~&m?MOmVKaSvS9%3XvoIY}j?KYw-%d`%SAib0f_Td|Q)K={dO z&P}`0p=zZU6mmpMj$Ns2rO1)~Udr^A6^~xk(-!iiZ6Q4_&T+rUxWMj0+@@f8saS(! zMVBDb#v)7mqS9QTopxvAMPl3Lo4Hwk^Mxt*8ZLtU&@=YZ#v?udU6B8_mJiEDHW9*A{!PZ@_KG$R6$uL&uVwk64p_eD!vK> zjm;$%a%fmJ4G*(LtBt~iZj2h&=k6yGiHnX|^OK9$;kpJ~bRY>bfBrB~^no9Z3O^O+ zNd+tV5jk-$n{H@znujzhxkS$k+T<8J8evC%@< zNGaUl@bT`zdkH1_Y=i*c8DPwRZRUke+%}29`FQhrvl|WE7q<50HlB)_(;DJ%jPW#f zV>h2w)s}ea3Hu^w>!g?$_1Yf;j3-DwhX0f$X1VVB=IZ-d+wv#g^~D#CP215?AZ%~? zsF?8BBlmNuE5ywB@RO6+3k&givP;4m(i-fCj{R5X(RGuNVdQSPepLH2 z!M)ekU>Nya%j7^yp7C&Q5XX~{p~tdM43zrTz{7)222iYBfVT`3gL;0`46F9p?bk^; z+bqbQr1iB+fmU5A)Q-Ur7caoq9~d6x*)b>f6zMfSZ*ba=RWC$v+KvcwTYQhx7ergf zp{;(xjiXcL$Xmp* zgjZjzL}8^U*9Yy@E04HqAq z<1t+ryk3-jn^k=9fDHZgt)?5iwIQluxRT_A#NAKN-NZ9ZGT$rr&`b4xAf#|VpCAnM zZujSIyfzkUw68jxK4x!q>`^@Gpw8XYnEniMVWbZV4UG`?Wt%H86pq*LSMGQEy{^K= zUg~eNl=Kj`BGPLtp#!LBdvY6!>Sf??$4-`4W^-K?#r@S_kRKkUXoFQp>qgJ;8*ol~ zh!3ZxYjNkJ;bvUEBltFk`D74zysC4urkb5+b03ZC!=fE=k_6Wxpk7|yqHE63`Dg&a_kv^O_ zjv;Ssx4UGjSJjk!(M5=~W0&g;*CpnIR;j=!OMW$9@}?kpSv7tSvBP_oSSk-k8u zlSVs>l9}*v2DH!g#HvqndvpD=wk^dCL^+5G~sL=dV`@ zl_BG)3vOmR7~Co5&VF%KT;BhLmm2nB%o(6j6p4u{p0?SKR|3Q( zB=aN2D8yQT@&i}CLyMtJv|x}=YzgwyQf&@W(Pf5gz+6Dk9mj}ZosHy}X*=^G#W3e7 zzt8j2(2jbQra4JMD^bT*`vCStv*ug81Fe}4+F62u@ufRTqo@$SsH?8KAjR-6_x&b? z4iv*ei(2SBPffP<8<(p&ECB!!`;g$Meeh9{Lw6rSp*?9|D+95xC?fVMbJAA5GSk(9 zfwsR5l$W8uj?CNZ(LZgaI0-EgR{7cNAag_4CY>e@S@(^#Z+1XqqV%xwr!{cq-H%D| z@s%qlXJj%uR_SGFW1_6bhdS44xJyOco}<@G?U8-zrqAp97k$&|2b#BFv1U7s4?OzW zN+HYC4krK&@1?VdR~Q~NF);BTm!2ILyKsQXzMi7}^oVebE2QNpSDC8AX6Cwcb$(3b zMyX?e9QqaHap7N36j;lg^*r0WcE-E1*!FA&8sO|yloxVYct`TSt4S|NsD7hZD-i|^ zLAHDBpDA;5Q%{$s`z<^6oPYBgRZ2I~I@bf4hb4VHY)ly*>d?>BxtO2HTZBg)N62ZM zxarchThKr!eWvF3CrgQtS)`eB`I_>yv?Ygmh@JP7=3Qe9Bc=HGZ)|7W(|C$#Uz9-S zbep9zq=s(q$|2gV3Dg3NUXz0q*OFtE&rLXAxH#*b-Ml-^m4Pc)7>OPh!B@Rzb??M5 zqPzhb`l!uS!qyXyn?*KhN zfvK8x_3Y0rnHP9$tt0_}=>s(mYDxk(&Zx3!e;5p8e=mbjU|a%7i;sV-QLY!cSZ|UL zFCr@#EkL{FdfM!jb4_@Ai0kKbH5UkKE%atHo-#X(<^{1Z-@eTybH@Lhz!apJ+~|6r+1Xsijz!S?yt$a%>}*~92z17rzZ@@vBZRK;6(Mh zvG4^l#3d(h$Hj|njIpher93}zHCq#_GC*_$JfY^g@NVlUOv&y-;p$EGxG(M;P+PUR zodNu86g1f6Uy0C~ndh$S2pU#vWjklT9Vr|A$UF3Ilt&omX{Ab~ZCFk2c?!aoe=I_q zGn|t0K{~H+h|a8TUr`L7@73-S@Sc=;DQ5ZM-6xW;-^4<*cLK5?}dp4zOt#+G`!U}QA*Hsr9Eq3S~)o!Sh(=E^dIzlm(?@ZRk) zZ}|9a!$h0#xzDe&HvL}~1`DqAeWn1bkdur%1wdyB;L1{T#&IXU^D$2@eFL-ehQZ*i z;pvvWDC$VlFR3lfphV*hcWckZWBS*?sb4P3eXTJJAaDXKaK0%7FV{7b18CPI65z|n zFJnT(&M;8>i?K}Blk}EmujSY6A0z$E{9tJC!=&4!C~+gJJ^x2B=TG!@64D@k?scW2oe4G@c>(KLJe~9=P9ct`zaP?gj@mUU>s#hTIy~0%kEiR zsg3kIQMb*7dimC1LFUbqC|eFGQkkRh6zmqqDql+|iB%d4lG8_&%IlR^ce*D2hLJa_dv_W3_m!1o-l z);(8N!(cGC`4E1Ge6+_j`Fdj<$W_m?8UMYnOY0d0B~dK@h~f#`S*pg!qCrnQ;IoLr zWKF}&V5z9o{=&3Wb0yufZ1JZEeG5#%071v`_Z*0mFHa)X?UM;eGw9YfalUPqv@|n) zHg3D*f-9<382*)%Hd~_mEQky9og}yU739>4dennrqA~pA24#Q7Q_$Iw|NGza^I*jA ze4{k-yt8@Au==t!;ghOkCKnV1WUx!)+DEW1lh@N7LuT8Y-$Hl}WnSPoGDxhbELpiTLbaN1J-6`bzUS zdt`w`ztBamKd;}4;P5Mhe*6yRSBfm>kimWfFtCvi@QWCRxQZe(O6y=}(aPw|;I_ib zgA6EO^CVe;9Ip{`^4boN7mPrMzc51R-AK2<`hc)@TD6edPuXl%a80^82Y#s;{2t0%zMh ztQVcJI9muRRHixGHDiYus2LeW=f&Naec0I8c%C!@2gz41(*z&#S0YC`D+KwKGZkwb z#@i?z#V!XbnN_7FW?Q~tc$5@r)AlO2zOEliS+|=k21jR#)mv%F2XP6T82LXj(8C*c zrW}|~aXZoLLP;!Qw+L0nKERj6?)RURqhR=k{NsVWoJ=IfK^t;syRU3ZQu$-jBiQKR zH$2a;n9a9os8g^u9wsz)n1*!)^DH(7C}$NWVSo_VSzMHkkBC-@Gi?y^KR9 zvZ%Xg`BaZ>M^wqGC1fFp*Zjhg-$3wN$;Z&9sm5$&+GP{+KLBX>jrOUzJ;$4*|_K(kw)(3#{~<4v+f>wd;mjGsu)jN>ou- zQ7zu1HWPN;Nki+l{8g2CasKf6C*5N85wFziJWUW7h@;h2HqPt zwq!Aq@6c9;LQ`AE5>-okLVQ(+_it4SY)EH+xT5AfTU)1|lPrvLTI)(`T2;oL^F`e? zR@xt$gyflXlLn_CL?^YtFV%os)01VpeXDd-+Sp|YK9*ab_H#xY_h!%UQ&FDJi!u)LQSidWqgmN$B?5hfrCJfOu= zsDkx#a$urvPoEACl`PYQ9P)P}8EE5zA1z0!dsdhtDTV_IPT0pkQR|RO3q%(us|hZ!u|K82#g zKbX%YfDy92Ga$t=qRlF1KEmeb1Q;P;2r%Gwars@JN#Aenj*3zOWaYEREY`=bLD# zplz~ix>t{~kjvl=f_I(FInhI2>H3Uk10O$k(!U*beVj{*W3v%oVLNZ~efgjk$bzr> z$kP$UKDbUAbE-p@T>i~my%o6?f0|ZAfS(H)zxXh*gOByZn~ff{tprr^X`D0-WnyFy zI{OUY6T}Z|4%f5POj8o(bF?!W(Xg)D*xW?nEZte8TPxi8TDjY#rys~~?pZzjAM%XXWd9lnF91nzVvtBai3TqJ# z(q@)&Zb676aE6nvJN{V!Zu{8wP3A`+vAtLe640N9;GV3M@;hN zjV`vjwY1S)ca{Tdf8)`DE1P}K&ZejyJyQzW&1c^K$)^MW$kPjmMLAr>*1oEniz_oR zs6CZNd(#8l@MAlpzBhPtt7lEKHkLN%%nHHzyhL&v4EIN=n)jYr2`?{2Do097>5F>6 zXBa|y?8|sBWjP522V3unDB8cg*gIK`$m~-b#=NyJeic!wqIJ$?Y?xyqd4ZHwnu{m> z0JA}~E#Y>7QnG{8V&VTxo=3+O6{n;SY`NJ2?{`&N|fg zoT}?J+~=&w%~`U(3)oKAW{1G|15%XLDsrMN>R-jrm(&>4WG*-+Z!I)l~r(9(|b9(q(L6>zS^?C2v$au+j8$@^6yc7+W z9pAc2Em?jW@KK@vJ_kZyd+n(v@=&a>1(`6TQeP6p_XvAI17^xFtBS;sPF$vy0&@(F zdFmS7m|pemLoLcU_g|k3OdB4v)b`}|#>6@z;a^e$`l2#G0clPh!dr_pT!Z1hI^VM zpy9Cbf3^%ba?+CfL9K>qG$wpEX8h*Vv7gW>EkJm6y01}grS*!%kzMao&9}2^O_n`j z2KBpBn;1~#Q>u+-1661>w1jW6ZKlFYeB9ULA|tHX&%)haG-T!)6OcFMG)ENEC2z?g z1aS$785{Y|OdOw(aE9>&5wLc1b()!(xw(XS`3cP%&x_6>(WZZF@4|syImPa$@D*he zf6{zTXp4+FVw^#YeImG}yGdnWX%;TkicqIU8D<&fi)gV)*rV|8hX24gKEm-yNRrTS zpWYEPMysr>V>RhxKJ#|hPshIs|AR%n%er+c!-iJ+Sz7!D()1lAI{fh!Edk~iG~W2K zM*Ns-fM1W8`gU{V!?v=BO+a?%71!-Z|J{=-ZqE2`dyy+U6I$ALym!O#h}o{c??cA) zrzGxgVWCsg)9}S+_2u%9W6dCBLraT~cjMYv(8AsA?Ph%x!7cj0aJ__vqli!a;S>5^ z83=y1g@uQwtfbU8e<}L(%R6^>cX|1t6NjHPPwQ`mCG832&MtxpZt;r_pk%gx2!d9U z|Dj>}ZO8l#A7T*r`_u2g|LeFT;}BjnGUabxfdBQv|5pn9^r`blcQ+csK}bL_Sk2pO zZDUhhT8egVCVNW$r{Pz?ztPwLB5LZ<*9wU&nuD#Py-V%B$)?ZIsYw1C1%A&De8V81 zrmh~)eU=(pqE(Kj2v%Dz|IeL1IwsM)Wu&Kf>MVuYYCij)A3k#x68G<}OEyh8arj|X?R*iP)pos8 z?f@CcICyBhoXNC4Fks*B&|zX5Lo;iTe1Yckcr5q^55qysE7p8+ytd`BIzoMsKkERk zlCQ-<=OLVPwnmcV;T;8wb35M+k)t8fOlo%w{a!N(LDl#u?ZG zex0`}FPF^hLWbi|t`||PXtx-d_l1v>^}|Zru?9r==F;DEPv}_RCy@poNq#t$4Bd)} z>RFUVTvmRZ9a2XVE#YX-g<}QGpyQYC*uiH5&C&@YHgB{$tJnYg+_EBj2Y1WW5Wz2) z_ML0XY$G>*M2}@6c(^59iC#A5X(x*9)dkXn$-4>kV=i@BzY-u9_MV`j9vmNL(Js49 zI2e91f5{58V%MuZy*brLEx1KLJZEMz)yUm2d%$1FyPYa>%L0xd+;;XmEm&)idCM6! zpS$a?khSf+9d)TO#F(uPteGK~5uFe6%oJ0;hruvy`PX3Hi8w`8f-XT^|C6neZ_rAp2*VQWz3CEGK6)x+|{_7 z3Gihz?Wrd6p`DW#B0t$YsOA0Wh5azioJaP_UjH3Ev(6=FmM8L=s~|OG8MWM*7%gV0$ZO`E1l;COVA6CBHLeXz=H7 zyJ&7pg9;PT9-r}r-pPWa0=PvTN#c31y^eYzBqNoV`&FXE zOk(H9wPnNTq54?9pV-ElT2{sp^{Q@TO>;*@^xSY)xjRZ1DLEP5&UCwcCGV(4K%LQH zAeV;7$Qzrft04jc(dnmlLls$Ccn;oJK+2mqH_a!0V&t|)&)seeja*){55;-6Wn~wr z6dBs9nPh(pmls%uO3O15@t&cpOFIxBVf90dJ|s(!<~qX^6*CysQSGh=x8&gKLqBV_ z;`u8>>B^?F4jpn1koWmn_hrIQRx3C?s?G5)7mnzB~3KbkR zd+x6b65?Z>ouvs$pU6vAM<+E@bm%f97cBKvbR4m8_9KtS-i=N>D{UcoA#Cl5r(f8I z_6N5fE0>qBvq?itf1IBbIoZHQaB_vGDn8K8;O~Nkr)6 zYNoW21E=tR7F&PGiL=K0V8r6r%B}J5Uu6J2MZRUNRCNJbGQ#y^iV8#mcfL$7UcY{Q zGCRC-2LxgyRfrJ~eFlygtBO8o{2vSARh+-d3MDs4Tq0?;BiieCQ-FtjmU~Md-eg z-5DS>ozI&y+06(7om~L{aY(h@Tn&uxj%J^hqNFjc z8c}Z(s#n`JJ$N~|0&z|ab7me?+@d5u_%Wss?&I%18~(JMqwT2mbs<8z6t z(JyyeY3c!sfLPHI@5N9WRsQsNP}ns@`ZXX&GR9*;-2R-DLsW=GiX1NPI8eVOzei%g zH((A;g&51}jLdm47Z1I-TLU8u-k{!fujUpu8yoCa^g31dzlstc_HxjlQo1Qtjt!;} zCn=fsv$c<68Le%h-f8ncuBO%(4t-7=Ck;#KSs2bOZc_H54x#jqwSubh&$6Nxp*t9qey`{oq2)Q;4=$9ZZ)mJOZ$=g~0V z2;m0(lNS+m!Hg@DA)eXE%Bh~<(|HW`>sYpV(VEx}W7qqkq3_90#iUt4tyVJ&%MOIB zq;6ZO{7EB%B#fK=z4@;6C@@E1-U^Q$Jk=DfC;qbrlC6uu;11$vo!Cj0&YCb+TN+bf=&&=0WEN{_TC#Xm+Hqs}RWSsROLt(&2p?nvAI{vI^N|K7A~MHyh@ z@_0Hc>pr_;Sj12RRU7gq-<9#AJZnM14_YXH>!5Gs@9^VZ2M&7g58W+uYyJ!l}w%9ZQsr6lJ! z>#xODtKV;!f-eMBg;qV8jd3(;v;GEFt5#$fLvR|jdGtnVlAdhccVWi6P})_S9R-xp z@l`v%KKs6(!%a~8PP?9KlE9XnH;pu%1q3qr7Evsl=%C*nu1sdJ(UWM9o&lV(U+6$B z8V(6#b$h}we}b(C8J3rMYBb%kM5`sF8acReLqKVthx;6Wm8?XVUlueAA8!*R`+2BI z%3y(F(bMNR=&0}A>Dvf<*@UZ`qdE?p^x^Y!wi2Jn#k&>Pp)c=q>2mV{00W=z3+Mc` zp`lH9h1w3dBdejIivFY-UHH|ig-Ij&?LK!C=8ot9A;C)JkzK9+85Ql>p5px^+K`*n z!tenfXETSf$A~_&YSZ4dOhUxxr14*{R{3^I<7kU3ADn)BLBg92sh&y5HiG>kb!xfj zGFdoPdsfM?!{fM3H0HFRdaI+g$s+IG0ruK{0Yih;W~>No3o zs{ZSY=_;@eKO@(ScT^E)yW_da0O|uE3qkIT(?n!an>tpKp)wsU$6=3O7Q|9=>-=_c zZ8%acgetb$`Hkbdo4fLo_jZe43>oR>39=s9z@l)_FrPB(yi&Re{?d(!pRPBn?`T3a zP}zvbEoSR-?yVz;08Q%_w&a@52puLOTkAr+kMGb8eMJWN0es;`JGxytI^}2Ksw|p zGV8-LV$}PjdC{%q)Xf}rGzjTDNi4PiYA}_P6YHM4OBx^UH#LXug}(0-N4h#bT6~X<(z4BvElcSd4Gp(_x}rpQ`Y8Sbjk@zLXXOD;X}C47VPNmSypNp+# zI=x?ysoOm|u641#Vh)q@)+LCvA$8tix<835!*3nTwFCzwQ+1FckNMY(jm{EPxl4_@ z>n$_-%6%fCO#vmqy)We<#v3xBsF4FLXxDpvriNmO@74Kbo3rQPKH=noHvhDi`Yd0W zhUY}{RNL(b5mABh+NAQ1q=G=h$!z^Y(i;tM)I2P^0v#%uXUo63pFGJ#nCxb1wm({n zw;Z0t{d#=Z-yO6K7+a?JfvLpYtv%UTSA&*c+Q^i%Qw_I~^0KlrHf*_3Neg47y&$-U zE1dTg++e&iyFIo+1yZDzfdGlJ_?uc<&2$rI=;0dr3h}V$OBD6dw~c7daJY3e@5Gz? zj5cSoz20xLoTX336nt5D+a0fNWPHhaS-T(jvlL4+6*i2W6zW1<30v^r(~RPX@H~KW zHTw@5RccA%f`-Mt^z4(3pJJm$Kp>}v@=eJMdocT=&&E{oZG_(Gr~+A4o{3FRj(*J> znc#Y=JH?V z<(^kPeaY`XOkh~K!`59{cwT8s7{0mM-2Z?8X0n8X0<5cKvMd;B{8ip?m3$@faPB_B z?Y@!I9~NRYfmB!tQlf2FCHC=GbUQKiHsD>R8U*nYsygU|- zQ9tmHSvI%n=13&#HTFE!OU=?Z-m_^+(gXa;h9L0u>eWCkUIY;r_*wG%0z)gDdK}%_ zHMQj@wES+9Tmgv{t|3}mAcgJ0rnFCTisXBR4-MMDG@k7^O$fPmqxe0{`IpNXsAF$a zalfTlLP(#se{+knIJ9aF^n}i~{a0bc%1@ojK%;mi;F-Q)X?E3-g#5c0YMe>n^r+NJ z$Nh%dS2K!pd^T50!y6G;mYEv+txlgOXBBiwi$Ws-CElH^Ur8JvCi{S-!5)N-hPXph zWji{uGUS9F7bm^QEUmcJxwAS0P50)qoshz$3z{l~ZuS`Pk*GW?E2}(~=yV)uXs zrr8wS9!&KW-s%j(!xE&;IRm>2xgq@RcI#c>9qx3LMimFk9%^@TOcr9j`Cpd)`imd7 z?z^&6Eqc1dz-SpgPqZo0Nzc+Alp&j>1Tt?xSth) zV9iy1ToG$PfG9=Qpkl0IxLhGo+*@Y3x9wm6GDpE>d_<8)yli)yx_ zKlt@i{Oa)w4(Mn(xBI?-XL|?X((c(t166XcpF-7UNu-dU=pX&IMyvPG=lV-&F4T3z zLA-N`^>LcGKEKni;MdHmeOL3hq@s0{?dMZhD1;Xt(7y6Ec}e#lCHjs?gjW*6Qoras zJl9bt>S=Ru_$#aa)9dc_UMWf|LfKwQMxpN*0GMvALGeMD@-C1sc2Bl ztje~tBR7|Bv|=kywq~PwAKez*z%JbbG<}(x@fZkQm{p|gbaX@2!-d(!H}=1!-66hA z$%U;8@GXp$ZhjLUjVGZjDkOHb9G{ELEW10XKV+el5h+Iim6SXZ>7#0_GqGYj z=9-|iamlB@B}Mg^ zJ%4Pb>}=a}2`*fdNr10;?j11gzPtLpS22xQjkzhIsmCDt($Y{yV^P>1eswOK+28`H zXBN=!ng$jv*A)AcJ#~J{Mw}rD_OtA+IHD|3aa{fa3Mzj%)&`zQ^@T?$6DRu4daj09 zD|LgerVT~0cMrCrdHW3o+c&L0_;Rl2JbgxSzOnlx={a%o<9Zgq!!%;XX1MUh3fLgi zSq8e!DxAV3H#zB&c$GjSA-7EVeB!((>O=mZWFwq%H%}pN%401u%+gKm_PCCDgsOm zrNVhyO(gKyzR?!FAeo6atNdoxT~EhHWEW~uI8Q7AYl--#5%^F=&(c5Op4>D1+1vJO z5cKq_zkdJk0&#;{2<4X zr_yGxeXKIu){^dKzVw5$*IyzdGM$erZ$G*9R;s`2Vs<+}qOYX0ku#6sK(jozHtlgK zXWYr#R{<{yhCXM%@i?bpq|zEb2{?Hfdlq@Oe&ML;bM^JPojrQ1YUA&(%limhiV>bo zPR|p7`<6Hz8-gqg{tEBhy_Vpt-+Qi11wA#p5cmZ5U)jaoPLr2tm!TORYI73gR58xa z4p=5EzFpGtAh<(< zYX}5)cXtLdxDI*<4goT_CP1*@3~qPM`Mz`OR^31QUw3ua-o4hU-s^o{lNEa%bGEHF z@c6xQQ1F+`AK!<28jV>R>s%c~vBJJxm7<+&h_3jx+9Wxp1P8@dl^^N3usI!;(-Fs+ zQ4UJBU8aj6@dEF>%;heKxz1)4%N7n2N1`!+cU0hL7031p1rxPkw<43um>k>HyK8EQ zwvN%@VTHK_ch8pAPFjQRC4PFKm*k5w-yUnz-|b4s+ah8j;Ouu_5iSr?66X;JH^DbB zKZu<%c6QJ5v^%pTVf~bPy||rzn=gL;UN+tu@5S`Wt>7K5+h*@Q7xqgwiz>ydi{#J>9jE5X;N*B?Mzne%gmT!7sK-va93ivp+}ypf!yE0; z7U!-P$X7_J)3K5mSYL@gK^{|@#Q9RwrP2E%#vB*s0_mm*drmc1x}4{0?zGQrkaHGV z*ZgMMEcY#@5J|Z>UQg1Z>W>&dly160qchS?f9+yLh-Z1V)3jpm+%J|%_5R9@zx859kY0Lzc?xw zv+`U-bHVBoe?qcakudi2F$7B|-Dks-MWfcq|Bm~YGVt!q8_@7+yV=J10FAWc zTEvd5CkJKZx7;0pyapJ0hUNu!gFR(n%C^8?xaM2bH+e1@Tq?(5^!`nwC537D_-hn$ z&>t6Hy7z)AC6)s#!k7U*Z=HPbXPA0C9KcvI_uM323Ja$Q@drO1=b1W&!#KHWEQXFt zEpyRXcP~~beGqQz_g_wEF8hil1naK_5+JWNgO=xt?JkyTWk<9r)*Iw}GbkXEf#3n3 znojrosxe2i@w3oZ;@r;5u@#ynNLWHJIgV{Xv@W>N)MguG`11L)qm_ z(LMRMaN$u_0S`8(yNzlK<)XWJrs)0aHO?mrx@6b9)Ycv(jvFf4gRlRrOkzm;1Pe?` z)R!mOH|c}SEON%HD|H!*c!s#i|d*CHC~juQ=B~deX87bgJk(!ihPdv_EA}{BRqU0cRzU-Hnr-*wc|O zQkYDeH!n3?g|8glr>974YF>3U+D!c_9()p?XJ~%EdyOUwC}+LNbd4NLEoCWvtk%RR zPL@9w3Fnn68yUr5C}!%@s(Vh=V0Sfp558TZUCS#w%oWlK3IHkA!&)1oFzY+FQGw6K zifmd6-%W368mR)|MwG~49PjFsMhOU%#$l=EpGH-0^K`+|7gy`2IHxN|#=j38D zBC9HumpacAb3%jag|JP^X&1fa3Pb~HcjI50vy4b|3%?y5FA}_FmGbwALiRxVgp~U#$5(rTLmUL8ICdc|5wlf-b7TG8l=%2DA z!`ZJykR^K#y?>%W1XOX)r~+)Gx>L_7!7llcbOB91824k5mu>dig(OuYXSg0djvS*PNHgSY$e7-RvDw?k(;;^EQ1HVBzMSe^Y$# zVxaqi3cya9GQy14(=zxnJjxwsEEM>uznPKK$t6we4`NUMIF_pQts50Q=VJ|D>S2HG zBSrrkCI1%psS`>%wfseH6I!csmh+Q=un%XZfu(F3Xow+c-xh<0$ggkvYf^;@Fs$To zvCCqrJ1P;IQcE@vv4CS*J`eP=)}e-m5}X2QT#Tl16uc9^jSr~!Qh9Ig=Oh$K5~%>l zj2QdIv|Klq&~aE)DmK5QkmIzsKaNOnK}1X?ZZAw+`JD;OZpj9`&PMyOyk|< zA3vd8(hp;OKB|=E&Z7j9mVHkO?6MMeyG5kF-khQ5sejx~3pJ~_OAZ{1w1^RVZ`Jek z@&l@!vR+(Lv-o6A%Z=@D-}oTW*?L`+CM_fD)ZKS~Co4m4eRX%DVlAO>V~NkO6><&`z%s)3%CXtrjjr<8sePg=s`ogab~ zsuCTs-&1R>Gc&(ofVy-D5}}Nr3Ksvs1>SiIdEp6o;TdJ7lM2}H9}XJAU#vgzg-0L7 z^rtaoVO|+iZGZx9x76{T%KcDLBVt%UOssKoI?gOhh^|S%PWjDbJ5w4-JBYFE5}YsF zL?xpv&vOEK{0Sf3Ty{10$#c5`h+|DzC}WS%1B!*z;PDB==IEeE0NV#XS>ngUOS4Md z=2kRrUB$u{uOaGm?nLyz*^RA`b7W2O&vuVXM2lS3lI+r7J|D*JI98T)-Oj79RXlf_ zxCKSF{1ayPQDQ&OzcYgSuO%!S5xO@wWgT(7M~+*hr`wVaI9IbTLWDG)R2geI+WY#R zCib9c(~8?Buc7KFlxNm5pX$6WJ;UFsu%98=9kdw$tUVDqdZDy5^gew zXpBHFJDD!79QR$D=P$Cbz$~O4C2gjjYptRq*;!nVhr)vJP}UHQwui{Njer%T@%V1C zK)nF7%>D1d2`HM3p248|{M~whVR3LW327z-^BKPdiTinMD#;d&a)9<56ULXr<6R%u zH^Wwow%tz5#=E)P3b+lf5_>7VCx z+^e9Bbo6HnuSwXxEw~v>p61|$b(BR`M%vXx5=pReGKXJ*B%x?PS#w*Z`}O$r*uY4I zyP@xhyeeWW1Pp|a20cgrSx!6KJvMYxASN_f)14X_l-Ops4IXY!d&PpU;qkMkT2u$( zF6~hIrzevUJK?0vdvD1kJzA-L{YVT3<}a)_?lvSebn&)B-BHg88lu}Og>XD5l`c!t zo8dTL6|?pDh4n1~ZhtVP-5X*raNnyc3`VWXLu*n=AO#IJ2|Z1!RzW$cO0bCID!X`?(!D z`KQQed`)dSR`2+X)ESAIEzpjf{bneYOit@}T6gWqUMPc2!;=m$kYZ|{>8M9a>Ardo z4JXGzZR9N>Zirs?6h@@8h2*of9C6>fof8S@p+&VApzcJ%WTJo3;M!#U;k%Aw;&ss~ zUACZf&^B4~7-&vR$UkSfskGs_2w7%L7nv7K#;c<0Bwq3u9bjlp>!mK=X(+f@fVCOZ zHCOYFO$$!h5V>nCCRQi~+nY&!@A(7(cqxB-1RO5aU)(`eD7&8FxSvPw&v~GD&j!5b zRUmRs#A_`2J3jAmd(qOZO2@RqHXK1VZsGC|1(kQxDHI`fZA4XH%IIY~)uLYo@+xVm zJ*l-6uRK-(jPw|*Z-TJ=N>ZwyseED=y^T!3EZEyqkojf0%D1uLqkx#c$1XEWl3z@8w{gT`B`&!$^{^4j0yH~SfOofOJNvWSj( z&GxM|AhoR0Wz213K6@RVt$$yY-4f0GET)MPNTN|OVz=%5_8=WgpxbMyB{QEn%?=)> zmMA`aFs|YIyKwy{2R;(iBYLa`Ypgp)czJk+e3Ix|e2nOSkuNalc$_W-cV|J#qZ8jp zcpE1C;FaP|-~U1Adh@L+xaf|eWn(s0WE~A4^uJBG@~b(GUP~wK_?SQ{c7GXWFuGKS z&DfG0gmPJKkuAJ^y+C?!ddt)mf%$IFOW1tNrW1p^6YM_oi`qu2Uf;KMV#Ncc9B{Mx z>tbUg{!E;$xCW*BZjKO;?w`y1`P}xLRt@(4bI#!)>tinyML+17xa>ZJxy?Z zmN9$2qAA_2QC?FHks{uEb@{T-sw|$8WQc&ZEEme_1o?1hzn7|uMUtmur07c=n7`1@ zwu|b1s~#)A)`)E6^`r8Biri-5r6nOG@)Hw2xCyn8h+nQOK(jxB)z8d&tz8;9Mv6g; z)}P?_ST~@_v>!D}FVoWAfb)foK4S#;r7{CMxU!&Vk|a-p9B0O-!tu@c!n48x9)@QH zFj@@;k;Tw%jZ8Z(@N~D7z=EopnkiTpG~R~(HvLk-C3LR z9(b{Y^aQK6PX6^ZYPdv?lu6~5&JxLFvgBOgYjTpdWtVFe{Fv9^L9;nsfkqQ<3xzT z`skzf(>lB~l+BJ|%X}Uf=xu>?d{Yzg>F;3jAqDix2m2|g+uN!98!Tmh7gF@q<+NFr z;C_Y;FV@{D!>)>-=s0I-cKaoLzKI(Jq4zeT??lb{9g=Rr`WjZ6)6x(IRc+?2XpDe&BF9v&ZG_ z!ZguO&dV+eL({D37Z` zeP25!Fxd^>kk7a&XA@DR(P;HOM_%lbh`!Rk%vd(f1JXVkSj-}Jni6q1h9d_xm)Y$< zYTqaC=t)N`5V>7@DsFwIp8Ib4n%ET=rOl+@u&7>eGjpAhru6zZ)a-P}%&*Ou<_4%E zgfs*j2VG1g3Ph~G6}k1377D!Vkv}+5#xaL!g+~;VZ$k z;XIPMpkiN--5w|h_kGV^g-a=m{(UMp|9G&cOV*^ZF##v8 zn!Q!2;mntk`PMC2HW-buc<=CA`5?Al%X+I6cfZz{58tiOE4SJh&FjCwf-x9t=CvJ# za13u}Y%J1Zo2GvEKzX>T5_Jr=W}=-S-~AQ6wG2f3JG$*2y3*CpKHhs=eWxP0=eAn( z*2qCvT==ei%QV9)c4bfC%lyF1y4e!^L{JHzx&?{uaMg@REY?#2-Wfi1!adX{66_0@ zzk2G&+eygo7Xs3p@gYAHtf=YSNJt=6k!KR-nNpn)C_)U;+IVSbjmG8t+TGgX4;UYo zXwzVMVQYIrAOX=gRGE^g6+?X^eE6MSUvnZ%b{NzELYg>cG#PztE+cD#1#3ZzZy~qh zlw4|hWE8lcYM?H=?<^QJ8W)(Q7OQ!rv~m2b+b$*(n5tIO=UgQyjoqzV=-}amNkkC^V2>n4@cz!G@%cY>|@-`iZNbh3a|f+Hx&f zF+P7mYnQUd?y7GU`VsiA5(R%c0XW1hk6#3GbD zZ6{Ls70UlaD64XSQ=Cg`cx2o0;o!(&|m9sA&t%yhl@r`dGhoR|(h!E*r7= zpaTW5Wu6W`HYLolSaJJH`tm{YQ3@Ewnw?d}6N~dZyEoE$aT(J&gmrH1pG~j^!q?a1 zJK~bgh4)0Bv~!(`XW-Y)**z2>EkIVUrcyp(mK{b+)`otjZfM3Zh{7Wa#>MUWy`0&u zOOU(Dmy%8;GTt}iw7<`dV;IW4?UtOiaWUXT!yw-DE+$*)cnTM;UpMt|qe1kdbrbGZ zbuXz1UO80`IL*uW)%+chVUK;=wkp5-kcHE?Tn>|Vz0AGp+=Um*r*17rK=|zZCgnu{pxm~y=g{coXxeZQudlA4OvQ>vDJbN>4h6gdU`1AI_vRrvhdb*1no zaYakGWcBB~*a$V_wQz%5Ru2E&_C5ppPO|TkRk*h?`&5%pAzc4nWI#vhP5Q`|qI6pLpE9BGP} zFVcinOj_UfPEDOi3o~HfyHuzjw;X?@&B)_}+$vcQH$R7*@RS>wG!!#`s<@I%D4r{P zi<9nTs3b|+#d{K^1)nw{;5+pfyM5j9=#_Gy^xvC=kjY1ie3D5X9-g%~8+$ekDgylc zL?n~g_wW!KHk7)R!vCy#Es#N8DV_dID9<-^Mq4}0P(Q=;wMH`3f}m6Z=`i>r96LZ- zU54r3c-c*Gw?R|*_{#nISF0L5_X?)RL;NzDEu&gfc%s0q#T0zqo+I{9-sUjQIDWzA z-%;3wk7)TeG7=IJk6D5RD5l_hOrigjdjDDJeLkW!Atfh=2BeK4d#592o5ai!m6V)( zyMPt^@2mRfS`#kJT5#?EurU~qkB^VDPT|X)S5$#wA|GGh}B{8Jlx;QubM@KN*e`76-jYj-*+ R(BG{zDj-b-nB2SI{{j0*mc;-7 diff --git a/planning/autoware_static_centerline_generator/media/unsafe_footprints.png b/planning/autoware_static_centerline_generator/media/unsafe_footprints.png deleted file mode 100644 index b4404f4cfa89bc7ce9efc9adfac4fbc2f6b35d14..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 229195 zcmce7WmMc>lV;;C!GjYdXb2u0LU4C?cZU!hf(Hm5+}*8l2oT&|8fe_z8{PiDGqaO- zcF);wdk?4kaJj!rRdwl8)e%Yxk{GDOr~m)}Lt5&K3IKo<006*$LWYIzSk`LbLEqq9 zKTE42BO`-06xRU&N`UkiQMIob$E%iFxY~q(bq?u$E|JgGL6Os6zNj7Bdb*!<+%=jy z+KP5HwpCRj=pQZPGu_6}FN&8&%A~C6vZq4);He6zDZ}@CSA0LSyY7v4?2XGg(D8in zc61a$ruvTk`M+MuNb-Sj|F)$jyaC|+-+zam%q0$loBXfy|9a8}9#e$+uS>AY-h2W? z|M#WXpGzdx|KFFC|Ih#ISz1!Yo+<~x{z;QPQ9axGKQ5Ibl@$*ev#>qbuhH7+9i)*a z*xoTWw}_`HRiok}ApbX-DdL6F?FToo;i+x~qWY#y>)mf|IHsrT>g({5gZ~FR!_GgV zZ?124m_@L^zey?2%ZpD=W9*_YicV5*><`8M?2eObzB}6T$c?c14y*g&Mixln;qJileiQG_>#3SYWc zB!o%jbfBVh&w|otWK}X6e@IM>Cyq}@IHDb@EU!%UU5TvVbi?&h_}G6tRCxg1czg_z$BaG|o+w6Q|os`baJ^Ze`m>%;PFA?vV@ zcSyKdP=)vx&(yh+i52awFn9YNjdrTfL-Q3s(&$wKWty6$k~CO!6IZosCE}JOP?vQe ztx0ueWc!5b!x*(P<#27(W#1UvB|KytRD8P<&~|}#zd&HAhy>H5cija^7zwwJC1`Ae zDk-L7$W#D=DD%OM#AgOxgs{bgPzi}VjxVx3Fjn7{o(nhTJMq(Vrn6VjSV~W{hJ#VK zb$m`oyZwFmT#ioP{4$=MT{Tdg87%Y?lV{jVrHH{vJ-2U@vwE$oYt^l%8&)fsZevv` zd}1_{y*aB`0c!ZUs-#rh_$hbHsUJaUZ2gDEvX~5+k4;G$|7^VMc+f&ARM)9Iiz(sD zY)C3FLuXETE9tl*a59tULf!pcI;F1-D~r$nVtLGV0q#kW;>CM)g{qQy7A9cwq~@}x zQMU>9sh<-Y;uderv6*e#R0S4b1Bq3Bn8o^BBINA2rgvG$NN!4kmJc=1Yj| zYJH>_10Kinkk3Cy@Zzb`;dVNwpdi*S|BLT}x;9pwLOksdyVBE4^~w2RM}_71Mlfqx zW2=q7=NEO=kcB@Ab8)IDyTHqTHs;z^G=y;Ebav)mPQ%N3rFFF< zGS-4U_3jLe1aNdbQ_hzl6ZXp}8i_St=Hol4vkdD0M=1owt-Rf?XQ@h91F_!S0~mYW zx9DqTpH>#?#6P?YwFr8%O5!8OCZofpyx>YaAI^p6>)g`{48E@C1`G-i2Usu6Si0QN zaTiH^OB>y6*dO2tW^k|w1J6=rDyge1T;M3KDotd;>FPQ4kT_#~ii|>I`d?ahX zsSQsi{=o|XlutFo@$|#|bo7kQ_FT2AIBWO-)C1B*r6dsDp8o&`@@F#{Jl0h_RIKt< zwm2v+ZuH4MafQh+QRYF;Cr1Z?h1&A_jz=Vk83Npn1(h~}D|*w-~_ioUqkf{I|o83objDDl3Z z$}whL=@bT3j5{RyFBkIh8Ptb9Z^@L5Lzp}%aaK!%AJ7!4j|-^SBR}_(W?ek`XQLF_ z+T8|v!XilHGiTgsKMaXWcqX(`=|B>Yce!^x-1mUL+gGN z#j_GsHV6~}4X$|~yRiGMg#H#F=FEIwbw_5@ySZ0TaBwf^j4 z|6Ng3;to~^dc?Xn_l&25MX%3I7Q2&6t=Xj6{Y=VILpjb3EifW^hm}DSqsu41eN8RBJX0m%T#hz4(YwoJ9Tn7UP1{EZw2h*LS*14cHE)qBhT2|+& z(w%-)R@0$S;ZMnPM+yGGk&Jmai@i-ZK$mRwmZUThZ!(8UJ5c5eeR=K|SX?!G*E9U4 zif>y}M+>o5C75{ClucUE(m>ly_V;phDDDT1< z^WjkOG@9$)8pM1Um68kBL;@6X4D6xd^;7~ynB;HI{4MutamEx%!HBSLC-*d^*t9$EIh!7Jr$sIeK;SSX!wx& ztH~C8?qv1}g*goKggKS+{_B}SgO=a$febQL0s7P%%b|;X$KQ$E=~qxaMGhk3vcUt8 z3V!4K_)+OF@}F$$p%nX@0of`Sim2Xt@ZGzGud^vpQ3H?SM7J-luWp|C1eGMUSsge; z&+P3@NvN3~{?8d>cXiQ^6%V!&Q4(-SP3`wxl0E5```b(-?~kKwTh_rznb#0jV62X_ zSmVGe=BQoO(c#q3xA&iaA8ZZo5@%aGvG+`$yI_pz$T{!qgB~Rk3$`s`q(i?p-@w4UHD&Ay4%tk6Y-( z0X|ITUd`v%(s&2EcBfM-Pm^JCgiWE$*k3{fWK}mW)lG02aiZue;6q4q6IfX?*9qy2 zYJb57XK|R%di^ZQ+f@R74&TSqX}^4HcxT=R-{o{uw8itn`={G_@VA8~P$1!1L(Bo(EIa(FE?t^*}jZ8eXs#Ga$_auhGjw3rqd)ezPoU=lR}0a`@afPHe|ea(C3lLmg{VEKZ-`rH@HfyW{aHE{H4~D zU)Yck6?97XO^WkaNbKN0d~V~O$I_6p8BE$&V!UzNwb9w$-a`?$qBcoW{Gcan(hRx4 z!Y8SZ)@;_cbk==M27(8}nzqXx$4;#I6PmF1tA1qMLR2OeYI#AxH@yu9XKlqyx#ojh zlO}K6*4mD+wip2G;w!BrV9Vx4X%MCYQm^4mG(V8Tbh^Dp*HbvckZa@=s<>+Y|I`vC zLhlw?Ky9VCK@(UMYVG~`Fo2Tl{Svj|RT)XcSQHUXE4yl$$)yPggrayrgy(6f{KfgS z&EjG_gkHjI>}h}SljwVHF)=Z+l54D~QZ-j57JYp>z|`+4(Im=nx~*G;ACIj9eOx>2 zRGEpmqnhXnQ5RRmclQ12uY7^RrMU*TTmqrWR~`}~dx)n?K3p-ZmR@|^`^Jm#?=^L+ zlZ#St1Ttn(L}&BYX;2&R)Kj+U%zmn(L?Y#MC5y%vL>}{DO=-@O%4i}3SPUR}!gycy z!VFvA@J@D%4|I1YUdY|HVI&`01^-!4xzO?PFt^-@9h&sw(L@Jd)~3!b;$ey~5&q7X zV!&rDPL+ZT(MkU#$4`~us-I<>w1oYc^F?SxtBK}zY35I0vc{MtslYVD`ErQr9))i* zx1atJ@`xI`oKoKygAHY}*o?#>eCE~mW#gg=v51lueLi==hthX@IaIAKeSC>4u(Crg z0d&$T!$`6!>MJEdTj_~E6Z!HY-GA@B9q!X;EjvahG)y*XO06{tsFYE@&*kzL9xqUD zXH+%)9yl#cyR)6A=ZQ;>!{m(94fT460f%EJk;1Zy3D6Mg*1v_6tGc42<^3(qP}+W{ z0@G~!`8Pc3FQvGzG(CGCt<95zr6293nM@zm6&5z{U?e}Jwn)BuCQk4;VRVri(DR)# zIqNqueA)b*s>JcJ3FqaQAj!vbYx=|!=X?Inb{GlIJ0u00Vf&e(8xi=q(n_}A4?bQu z3Uxmo=L+3uzhjrt!dfG()p=!ys5&K%AyqnwQ;`NpAkT??S3bh5vVn(eZ1hg3fP>E= zJ-WPa(E){)n$*(qh?GR=MN%m6Z~^arp#xgCw|cL-r46IqM zLdj}Fr6wR4s$g~cl~=qnV4JE*-}RLXqeH`rw|A0NR60@PjpT%Ym+4tjX`yt zpTI>TF}G)>A$81y!W1>Jmq5e7htbf~)U?<>(F4g5AIOo8Pvm+<{7?7ssgj>l9fAE& z)F@+f!*gGIue8$q*E027C}yTVMg7Q+lT; zDHRnOa4Mz4D$YQrzS^SbSKZVF19WYzG{a^nX7J~^1$`wU`ad?|FtdG1zXm~(C`4Vq zItGoFadjA3$=DYs*VnT2*Ch<_^~8QZuu|t2g>b%`XUQUc!(w)Ppt`+ld?kQ};UPvD zn-G_2f4gLFsWSfnq&p;FWNpoch9*M;R+rJQlUfrMqhn}ME_M0CB+uXy>o}dP>GLIN z8pgUa2=$c!y*|sexM8+X)xqxZQ2|x`U{(1;sgQJ)R;$-en{J`PyI-K``GJ)x9S2!S zOC)`N_N8*w{J>s#W_r{XFJbZakJfQU(tZi#*Y{Dn0xCS#hq@KPmeeHr*OoT1f!q zrl?UKj;52_!)k)&Bk!}tlJU?+a{X6Eoit{8h|`9glMp=wL7ERTe*p4L@#L`Pay=_W z;YDZ&jnTNs-01}h?Z~2pQrtY~Dx7|*VTBg?WvX+psceERlVy58Wd0?(6f=WMU_ zKj%K7Rk?}$I*bk`xm_y!27&Cl3{k2cnKKA7oMG|!@0f6jR)mfey)Dt)ez>Uz%C);g zv_<=XML1hH(#y&q?~OI>zOAOPLCgqj$FUvNJMm=yqi`8-R%&kEIodd?kz%qGg5NE( zF=zyCwPx`ve2*xHff&AfI z!>YC1CQ%3)b7RuLo>||xJoQw!$Kzl>S$^kbmQS-TItp*ZWS>uNmHk%|NyUG5Zp$no zVel4g_aDe4Qfq__ui{gk-P5^yg-EKEk}26}sxXRZBX`{5O0?PHirBO&u3es)0dl4t z9P~WomsaBjJr1N1=-6RPzIc|;O2fPA>X@54XfiaJGy3@5D7Xy3STHj4ZH*^UUXbvZ zi(mdm_$TuYVx(iK7p)!=!#6nh(QW-82+2LXi-iLyMZi3=-mGvh_UA2p&w{y{NLicF zzdke(kxOC2BqkOi>}Yq>e%eFolC?w5{ZA zW66^QrB&5DirPVWG+m^@*q?>DL%l#A(b^&s0zNdRFJw)AG8-i4ct^J91HzXC z&PiUyDn!3bp{jGpn)<6An*1VVmq4xqqYlOp!%~NlEwOXef9JrTd=Pi4c&YX`tQLH>V7xQYR_vVUg zw%XB5Q0FvaCWS%Ceri7Xc-%93{yw*K7!z?MMv@`vR4?y{{Ss&EQtd~@$;qdm1kSHH zXH}294VSB;70Qe+3~#m6d5TNS1IJO9`M`Hwk8g&&a&n8s_h`0}ISWo(W@*hSIJe{C zNs<^OD=?GPmXz>4jG-!H9HL2_YiUy^4Zvn5t11jB{MS!vCoz2+|1e$BF*4)SDx)hj zZApf8ZL?`%Az^)*?mNdxqZ8J@^8etxRdg-I`A@Rjr_N?wN>ljZYbUM#T$%IQCxgV- z+8n(!B}YD^09|cZRFmo~Zygc1$yBWIRr#dlJsTlzXzn2pPXk4uhhGx;rjqs(4h|0L zijR>1l*``Unx;O`G#5mq(d%(a?5NnW#%sJ$*r4+Q6MIICE{e^G@y+1s#b9-g{^IzF z!S9VsSAJ=1fqG};LJ)^7pDoSfque=Kf~Uuq>Dkh8+Ol!PP{xNiJ|i;eGCmwc6?oUj z$E4V@q1eO*D2Q)^5jMh-9xfJhTv2g7s|Fca$0J3~eF!mL1qQQ3?RGR%BpMt!dUx7> zOk0!1d^!D6Lb7j*y%Z=pA@MSsKjF@ddl<&2Tj);nQR8aJU(x=9kR#SBBuo3zV0Pf{ z_Qu=)NJ?cc?&G1Su520jQFlfXMarNzZVhD=}r0%#yl!@hgO zXV6sfuigm_F0@H;-0b>R;wCic@8$|2;1C`N#ADRn4Bnl`}J+n(=H+|KuBOZQ;IsClnPKEgQV`Xo_ z0s#Gcqln_n1&Y`xn37{2P1d#8@!WEbnlw$qo+>o9zh$a4rt}FQ-*<9gJz5n2axiTU zD79Ss-MuE4qK&JJzxr#-uA2)AMto%Fc3eMx1~uHgyzz4Xnh0D!mcrdK@Ww5W2tWS&CTRBx$iRbuWW2t9pk7p1--7s)Rnt4I zLGMat__(jVIsItB{l@7dPp$I-yY)bVn~cj_T41RyXr(^H^5}LIacsrIWQ;Y)Qc@u# z9uS1wwZTH7o9fiO8?A$7fR8h1K18wiLlvcQM^1nuVlszy5~zRrhnUq%*qPL**PCzZYj6`-YR8 zoj!l8zUPjqvwK+J-;98x<6T8&U@w^h1LAoI5i=i+AOUP)uFEV!P8XY}(iRg7(HXuE zBRm+QDb$<|jao`7dY|Dw%IU-y+)fNJEqpl5-nw_5nDu(!r37$$d3+x$^eg&hZ?VO7 z0H_FzS{C$*1bf2(lo<9bpST4@3aig*W%q#SDjl6h_jRBa{1HN*MIP62?YcXF}qnR?jY z%ruI(yk(K8k^}C_5eQij#R!mf=GXs-v*qi1Ju`i~>basfpDhpIbo@nl%=x%-GD<}q z9X{MI5l1tGyItt(<9>7Iu8B4l>glQs0|46I3H2bXux!D>atrxN#;_Yh;e@5H9tVpW z_&Jrj7pf^uMOlDJY&CxN`jZ)imXl@ty9loOH1p$jkH6 zWsdrHUw&O2w55ACxZ&U;hY^Z0|5-$CwGWA|`VoUv$= z{dsa1+-x|oR5~$W@#F^s0LVZ&BJFK9B_uR~j7<7iOvM;R90g#N2CI=^J#ZV_z}RK2n=n%PRTx;-`zybjjN*~v64X&KG2SI{ z+ErKhUUTR`y7OHFi+-B7mXE${j=N#L8})D>r80T&5GC{;#FFdPt-t&mmD*7vX@Eum zWk4Q1F+eL?FYRM&M>I_O3ntE$tXh>E%TwO4+G53<-$#Ew&#?Vl$Suz}DrV6QkLy zU8!tL!c^}@9R5ra@O_tB>}WK6@oXx{O(^8fyuFlXEZpePsP2anX|g|q4A@^m@?M}A zv^6b;>~xNDov5v)}yf!zb@F$hLami>oJ|JlfHsnvkvnC(qhndi-585)_z8 zIM$m)6Ew-a?inP9F*?CgjXOQhuScSW2A@i7i^o?b$sSCOc7MmU;iA`zwy{1&HzI?M zIPwg;j5+4By$P~qHPPEXaWNY;P5dM$D$VU1ikcqBw&Bs;xh($8FsHEn2{{4G?{x%7?GS%yw z8w_;xG)`+3P~hLZPR54OGcu}Jv@|(_3Gnc=bagq1gs0?Z@WlK2`w#c`IqjDlfTp7V zrkm)pLpv@mF2tNxBG~ZK@m$18nLTFgm6esICMGug*ni9D;ey_q-_^r|JGdJg8J>$+ zUY{BpnFzgKk?RQgZ^@~r$c(}~bM)%`vw0YX7Mn-C#ZlO~Z8T0kSvBPugEU8KcXWnz z)DAQnTfkb3`R5dq`F{%gVXCiaoB8EV8O88{r&aCO4-3qGkD>=KFQXc6O=XvG#no~U zm!Yr`|2t^1J>ZvTi1!8h{G_78YORs>*$GSlYtB3w+Dq0&PFk@2^Rsd00zn1j0S5F2 zI&&dNCj=lPB^@K(zI6WPK@0WZ&w(6!){(J1#qI?2Yy_WE>%1(3@Y>JSY^1T&RDPQR@?R*uqp8KN~Qn+sVRn5{^*WX`juMxqv)9<$jR6=TJ5fd=-@db-;+G^_R zEqYbwqVivE^RZ)uQZPieh}`B*7HhXs=5v3K+W*tk51=}NLAcf>AxR%jQrPM1j4|is zO^FCFs?}sB+mB~`+)d$b(oo7<<IJ=s^m+i9mB}EHyq{`7HF!+$-;;QzhSMCAr zmSDdVW7`?=!Odvj!f6`uF>BWqsD#Y$67JpVc`!*r9;1dfO%N#h)uJXRC-vJrQq$5} zTUt`n)6bUb_g33H!NzUKDCRi4LX0HoHcuXf+b{Z;;APBWnUc-C_~|gW@ubr6ET$j` zSYz7r@C9|Qa{i4EALl_61{GMVxRI8>>%Q8Rl>ps(X>pp8mC1f)R-ufsFt{wVm00tY z^yw_fz?|Z7DfQ6v;?LWD!2UK|aE4!3M)5I&s*)a!AZytoE)x>y;jx#mn#H|(cPPb{ z-(Byn;?g%09n5ds^HSr;f1q+9iO6#R6qK3wR!P%T)0;U%EzcuZR-P)=+g2%y+_^Gz zB;ot!-yF{}(k3|2F(EvKpQ16_8Lyk-&R)i?e6iFy!v|3~q9F~1R#FA%7cf>Eqa=A) zW(*{r8a9A5e}CtZ@mFt#=UK7B3?lHiwXt`7ee~7${VN(Z+>HSNDhO0}3IZ@bK`Tb)0AY zYO-XN?1;Wtg>$1mWM-SIV_W?E+C+yWzj(i4fu2fmwr+)iXH&XIF+O=tnUUGS60E{W z^-5|kvHl|Ix#}-27hz~4NDVbR#6s(k+!N+5 zH4pq!CadV$xg9&3ecmaLn}-3=KR7whA)iSUA$~)&h}Olr?8wwfLd@I5x^9|WfVv@b z5)juBxAREmA3io0R+F|@SyQ+Zw$%(Q(oY|~F3m`AJES{SzO%|7?i7_)Z7v6Zrp9FM zM~B(gV1*pF`lB}s)oS_oT`TqZFb!Sqy>{<}<9$>~)NQ!wMHfRc9im_h*A$eJvb3y) zeRbh{?$CO&JI71EQ}>dj5$)R??UR67-81hsjh63F^0;luMYh%Q9L)|^yfVP)jM3VD z{Gp=tex`_xoXLJ1j#GWk7!PDpc#iRWZo6e!9u=LPN*5|JZ_V~wlkJY23G0$x+S$3R z_8Lwd=1GBZAy=%pO@dM{5B<@}K4|n^zO<3auI$hNrI!9@FJSiyVuFQd!k&72dmBx{ z)9JD!1Mc*NS>No7GRI0}40>n&x^~8sCmmnW+08zsb2ypXJDkLX0NXv8D|QC%a3bRq?stE9dfLnf*3SA83Q5k$%%k<~U0LrCzS8C9=4K1~lYeqrH}ro_N=;pA^E_kH ztRi~*b}UQq@%mtfMw*Y8S6wTxDA1VeVlE9^oawrjk6Dxz!mW*T6=yf|{RtrFDFNEkbGrL>T=A|N$lXtL3MG79>{EKE8|VVe>4LJr9ST+2!dy1t8J1bX8_Ax5W%HsZG31UWL?{* zXd;4k?-N+F01K!gzE0(VW90p*(TWAmeH>8^u7p#2inv(alW5YfeYWvLx;b8){OKm9 zUw9;SzgF|PZ}O?#&LBOyIu>(|MGB>@&SAG^<2soCig+Q{i-f#G_6b}Ng8=awNnur# zm4!|NEw2P-P6&iEZ^Yq#Yej^IZ*FZJC)@TqbJz3M9C2VdPG-^dIE0q(XawN|DoLjw zH=dq_(=KL&1$aBG#j6bsUOjC`SP{WjMwjyTYTsb;_1@=5k;mqlGwX%?haoKVAZ#ca z?s2jn$pZHtc*2lM%>M|iHCfFgQ$%ToAz?s76dY-i|aOx!IOvK2qJ|7mgHg z02rNf^{Z6ENKn!g#0dEUe~6*??OiYo#ob5ON#2J#@DwAZ(sQvJ5oi*)9Xo+F%Ofz9-j7New)4$ad?bO z@MbSV5ngPA4g;47Zc@+)`97$9x{_FellFbQZER{HjH!YR2n&;xk{YZv9pH9c^MTp{ zwPXx31*wqF;+nzcqo{Z{DAe6{Ypp@qbZ_2wFEjl98_0Dins*#(aPs}xLj{3^-tH%h z4lJ3O9S`@UQS`7m_2hQMs~wHyrlxz`XpY;erG&nGO->He1=?Y6j!uysU5l=4i zH)N*qOEO(XactJ%G}q%YJ3x*Y5b%2Y`?M*B<-}#Co*t0nnsq`9p6^~9{8M{%E#`<8 zAhQe}DHs`_fR1uQJTgqrPKB3H23dxs%-3a_GvY7uh2{Ez5-gayYW>C_rmd8MdcSN0CRHO|MeEjr51x zE2rbT5)!)#y_i0DfS+$j+HV>gZ!!oL{&$A+ek%txU-{)u_B=?Gkcr+^@0uw)OS( zFkc&TwyPUx$v8XyBpd(2TE3rXH>d&vStMf4Y_MM$s;rpe^KjO>pEbGFd7jP`Q@|?``Pq4-&=pDa->#XyVvgs*$ev^O&`TdA4JxT=K(FtlKptQx*t6fDmf9pNE8H{MpQMyfs*dAiyf zEi`)#ba!F7sKNoPF$$hw4Ao@~v&U+!R*W}SU|c#3w20+lqcBA)VB~f`!k!Jqoee+G?|%(*w|R&C@sGBx$jw3d}(Fn z8kNh<&ZbckMJIa9nz8ne2Q$Uca0z*Mh{T6_&YYskVn-_*aNX;)>3a+7rzST|dK48b zG*ry8?ISWcT|OO`CA%uI0q_Du;qcgOd}A4y=0uJF|&zj_t6B`Hw#vJ?!h~Hdifz#pP<}o8# zLgyng)SJgea~Qv>;bPWyImneNW5A+p&?JhI>-2KONr8mUhlMWrL#vWE1RW8>YG zq%5E8;I=~7^0|ej@T&%1eXOl1G|{MI8V7P3o8sXCfR^`RzpfY4MTYpY&Vva)9opE| zgB&BO?yG7XGFr+C$zaTG5X3b#R1EQ367%qnSuAN36wTKH3a$HSora9C|^ zT!dqTy8bXM3QQD~i}Q1Aq5RTPYYU719hbS;*=D_}eK=oV-;0}}#KDi1qK}S9Yl0ms zymrB72k;wSB9%wUn##(`j(1p`Iq&W!AX_cHc?q6X_BK~uM|Hgv@NRyiR|_i+ALf^Ek~lVk6)?&V;%!8iQlMD=Dh=6>JkDE5zSqa^Hy?oYt)t0`VqH=c*% z%3-6TJNQ3+7e*b=g(=z2`TZpp)8IOPE?>j{@LJJmzxO5vYi~?AOU;jf1-bLFr(_|A zdl|pioXB148zcR@-Bk$NpIQVE`BmVDa9>=DHhOyYhrW$9hR0_Uz9-+kx%!0QsM`-$ z-jcBRo>t3W{Cjx`4LSq_+l}^SF}i6*_9O)TEZ83n{yg&VXn0H}GuH!^P)NA#u!UxC z4>waA9B-e3V{tqE%0w*<(uBWh4u$7aIaZC&3G(}j2keI-s2H+fLcrl6j%n3x7mU|a z{v&PLA7Qkj2?eAk#>aiGgjtgge>|_WxV~4&IKR58Z)kWr-w-n}FfcMQQc;Pos&a5~ zx!f9vg?dyd*u>1j^8EA!4bB^9XRP(i3=mahxA7ZsY9611+9TurBX1D8&QdnKqXIjLySnCzXfCQbsom7I3*Y;}x#@(H6azh}?8X*;ck7?Ik zB}#rGk2)CW)&BDMwYw%b&@t=Sf#PbfYzqbN=NT|I^SL16tdfVykIYnKY=w*g!1%nH zPh<&xudF;VG2x*Z$6TMrhTQjBEh6fel+25h86+dn_|0_pr|gt;?Zm|BUGhaQ6MlIR zYjN;G_}4Q56IhZeOSs?L_b|9Op~JeZ`*SCh1|z@^@y`L)97a;*qmQ123ae81bV6&M zmkcv&-SHId4%?ee2D+ymm_hF;TqfT|FAbygD%h#f z$@WjEtFKp`h~{Rj{>px^N|ISi2=4HAH5PETc}(cHt#0?h|EPM_6K@|#JMBWk=;oii zvL%gC(lSp)eI_V(Man*?@HDH%To_o8@nw6qFfpbQ_<6E41U0pc0y(~;G--)J+E&SIumF=}c!8c#;xF`Uq*}|BP`>Q(3 znU3%5X-i+Fo(&uio+R zomg#6H#}FDBl2UrGqEfFcWj5Z@9NW|UOibT0_48k>3CnaEX3tD@w9dsbgrN8m61L8 zJpeUcf@(JBGFNnx&WfvDr&#dXg*`6{73wX3(_mkzgHP&8QCx}=Yu>-sT$KDtBA#g) zbjAgrw@aeql#zIb&>9mqNWa?lLyi0d~;?y3E6*o>7*Hzv^9AcAQAuKt=`uw8Kp zSbfTr;VZl^cOdSO>Q0|iVcEOu@1;nl;vk*=i!X&^p-rhvO9yv8#4@%i%R;W|uKcJ; zcL)$o4R!;lSH~Fy8}bRR-`gj^h&`ec&kAgA4=IH>qF;%Tw{xD(f%APN*rIpg9<73|M-vm4jn~(Pi=5> z(_C_YJXY@qah2G+;oy6O!aF|Go;t-`s{EB%)7E2&XMz+BS_0;;HcaH-u~np=DCOb{ z&O2A@kW8RxH56}5O-(H-q63talq@bUmz9)A3DG~6!aIKt%`IhH7_9|`lM_tkDi@Ma z{bHs|7&5~S+CPG+WqCh(Y&Oz(p7m*#cK2ciofv?uZ;BQJvoNg{1|S%i?^ZL6J>ss> zoXKcz_Gvwzg6J*>6DnLd7@3$H&Hk2ZHbgI~8MG;5&V^QU)lgIkn!f5bIo#acW%Ico z=8A>2|7&5A@o~Bz&O+7Kezn#8Xuc9!F*9d>|2{r6JYx>J$$S8%^oAKG73e+PS>#8U z>N>koF>!=3HhXVIj{lmg2Q6uH9@jbbQBJ>_VOxU>qr3)BBtt|j5!Rxe&Xx_XmX^@^ zeD@}-E$ydkCPp`a6Q_bq>7UYv#|I03G?PZmlttEdzY}0QSY9$37?MTe;%Yp9@Rixi_>I(aC6sGvVQ*(< zV_PIE#ah1%MUjb!G=>$sss7Ytem!0;y0w0kY~}~P?Rr*bM1b5WfQ@4H1lD?cX5D9h z2&KiIb-ih!iN9rJ-QG@p@*B~-cCO>Bcel0q@RTMTJY-V)Yt-f?Zhvu6OHy(GS`yrz zu7akfYAq+SVq#*RA8w#MfzyAg0*(&vyW8t)H#fH*QBh2W+Sq#w3(KSbtoDNpegSKU zs*2Ozy?JJBr%)zIS~`fwmgZTq3I)UdCPUFU+l9!^*4wqRj<2|Gy8ic|7JD`)3-MBV z&5{P0#LMANB3!29PG)^-TQeri9-cLd~;w?cK(V#cvd-mCDX1NkXA$xNBZ_Qq}X9) za$ZT{Hc>q!G6U0Km3{vh$e2%&)*hJn?*5&XH`tiTGNc_Jekf&6QP8w)xG6g>F-zLY z^~Y=-M;%i;nDEajWUgm%aI)YaAb5LHFg>_^#gK_&jT` zKZN!^@L81};?tjeTn-m!qMJxlkBYQgwcV-F&{Smy40j#wtRJ@3L||E0 zUftZo^4Il>$AGN{$%pr=ymhlm#mD+Er*Z1IT1#WVMD6>4(VHO_Oyob+wc1) z?d@qUVO3vB6YE*&b|L#)=TkK`P{>gzR})*khYN7(oyfJBT8H3=t}ob`i4>{7UWFKh z8QEUvire=nT*TJ);3fA8w&!~)X53kzt~y@P=V7#1F&pTxnnp8JhZKL57|o0eZ)|1t z$!3;bUtb@9?R~y8LI?rTx!t%A?!UW;{ZV>7dmRKq>qujU)?5rdwdPfe;$|1#ukPiy zE0~H5%9^y0@eT$?CfZELmHC3SFyxW&`S`9b;gk`C0QGVWsF!en!mChV9p4YbrY{md zD=UkP--A@(>qo$^)YMF2|4ui3KL>@}-y44$36hT36k>puxt zL_`E1A765EvfEO-6?%QHH!G`MKP(`WAS~5cgx%j|##QCsB6E!B9X}kv?V!M_@Uibw z>+9E(GTIq|SFXcGr=!rJFede*q_GI?-gRD7LX}P)iWAqG+xuwUJ zmo6mqr6&rq*(GH$O_;gm)dNwA6Zux^uz-LkAIOAyDoI$grL;ArsPVM)5S$Q8YvA+% zb2Tl@EBeQIZq8k+a%{kMd4U=}nrxL*+aWP2cb0l;3$$%tR2_A_|D)_@cKX~e0y2OYdawjHKM6p995Z# zfbS78X?_%E96}?nX`i@W>~Q4RMp;pp-8vpvWUW&;7Mbq-Xq|vC$(25UUDET zaok6j99G`et#r|ul*@lI?Y-O0%~xmZ7Ce39cAbV$?QeD`n?avT2^FS4v>deWEs)o& zyw)&e*6B4c2ie-@rzR&3zsCP6aR~*La=&6zwWSn14 zEhk=9)-cQ|G|+aIeeAk!^28tMle5NI#EfLQ;?f!;#?^C z`oCEF>Yz5aciq%mC{`Q_w765;p|nVGclQ=|w?bPSic4^JcT4d?AUG6vCjBm{vUvP&nvcwJrJ+o>yMUyf9^XJb8l6_B5-Vk&!82k4b+)wX)Fbo2H`yBPz z2jP5Hf1RaRM~Qn^;l;_f+W(ES9K7G;RuN~oza0#j0~u@)RwdC%>eIfV6(nR!eD1Gu z8HmHsIWSPNR~hrWCNaN41Ka-Bwv4?Y+2XlO1%m~SyH#?dWfmZ~!D3mNsWDaI!Q z0(-Ox{y`K$?qp>jUP*5}O$o)MMeMi=!_M_;^Pv!-e4A-|*!3bh`ctpc+v2Eivq#OY zq7Z8d^Ee@cEk{cI_4)O!oGzNfOvP=-hcSIiapOO2jW7t_fB>D>LbEF%vGAU@s;jSe z1!!R#n=$}E0(^Jm(a|0pZoAOJYub-<822o`EI2oAVoE?EE?St+O7*>&l2_J&BnXrj zA8+9z&hnv-#A#CQw8>jXFX9{tdUwgM!)~L9^tTd`KgmNY@iw&i0YNT2FCkCM2 z;x8gQLWu`!jk#RmcvPf#_e_;t6V_v*+A~NHrzbBO=P2}pO0o+E=sy{lw;IjkuH)kg zDGY1pnxLnirkms|RBlxr{A7Vhkb+qa`UL{jdx8xKcTL<99TH|@$gGnvdfO3 zBf`oYFp@vow=3Kdsa*FFDwj7S8tQ&2_mDWO^^Vb`5!9tm=X4N$HP{Bv&S=CT!ip+` zeWa}XD}0~5SdC89F@FCzVBX>~&2u$DN0aU2iW3Bn`%;?sp(?E!*z%Jp6&rV$2D)%6 z%;bLgmnW|_nZ(_TUUXz<)CiOe-{g|A7R{f1B2inNWI8$3Z;0kFlKG0rlCpdi5at*Y zC$NN_{E}FE_o&f_Ku4MR&fY5I;JY#oSwdgs#v75&wsgd_kPwSY1et(g?pSf55;_*= z$L-Nvz{P<5{Q155Ie1X7&8smCA5zO7MDO8vB=bdf2vR~I+T`Eqzb2x(XZmg}^Psfu zEU}%QBJ!mgD)hoMF7Ov^nJBR&|LP_carKIDcU(IETeI6@)vcDP<_ZFVG=J3cEbU!0 z{S})w!V@qq$(ug+(DPmW^5@0-G=Oz#dR2lhY@hl7gjv+|(%4uKgpJ&eVMZk4y%a&O zom6898d$j(#0Y&;G;D7(SXq9gnX6`TyIV+UzovnzIUjHE2J~^Ax$&N#!P%83i}_W7 zA=26gv8Q-Q?+25TVP^Yi@so{lBw4UR*ygX#Fv)atWRk$vFD8tz*rPf$_<>{FHz3lL0jzU{pD`0hUF`&X(*h@r=& z)>9&KCNn^!wzA8Wu=dQ#E^E=&dL#6Z*|>!PX7N7PJA#430q=q@utwVSh%+ITBvs>S z291}$ff^5?s($1wd%gGcYJ?CzczUPhGWH4RtnT!t=S8tN2jKTzzE<%-L4Um*KGcuS z!SHS?30xSs2q8S7qT^%xJXN6Wx*y=nrH>{pBY*b-$wjSvJsOoqN94DXfP*X?^)#uS zJ+?`3cDN~ff`H^uc?ZeR8YFAk2?;ixFmFrCbZw?2Uv9DR@bCaKZw?NXbMucMKLXat z&aPrD+DSz3UTImT2&l8>?)VwWICw66wdM7`v4Q!Pk7kHc?#8Qvu-6#ZJb5b#1JBMvWuv$ql5y_DyzOk5Z zTndULqtKt@^P#4U0fe7^D{(l7w7DBK1{%j(o3|?nT#5HW-jdQG?u2QSti^=7(`*cq z7j!&{GwcB5``SzAe5I?bIqILD$3xgX0lnLe=WjJV;a+S6~m5^+-6Nf^qsT}8R~ zRMpuz2m=F3?wr$7v@-#T>~G{OX8F>SPuYeM-e;ttkwhunbi~88y$UWECrbRD@G7Xz z8j#;yU7ernKzwch^b>Rd&>&!LTUZkN=H7I*5!t5?G@QOpeCT`8_I4K=V60%e!zhFi zQd5peX9Wi5JEPv0c2M%ThX#6^+kzHx9^E@tV_}u6ny7xe?x9vq7urN+{Zh!@^9QmZ zl66_WoTTwQFDUCH(Z`~kh9H$PHVxUUW6s7(`?$N^hVk*Pf&|6w7rUxW15$~+mizir zU|!2IJEljis#+T#wsF3a>9?GxXnr8za#{NR=z?lMoGCd@XVLRudvk5=%eVmD6@7hx zdSqY8x?>I3Sj)=3ZL(l()5olC)fTzFRmk00+3sZ=+*v9lG*sGcZHibXq)JISdX+q2 z=q|nWDk5aXq7!txkTm}YFNaCvBe~H7tVfIn2%~VO(}GH3X(3}q5!p(E;GSPbvaF}k zzdSikzu|g{Va3t6!eMiWNLBw2sv#>#e$pWz`xT6z-D-K+!CY<;rW}y$d#2j?(g#y{ zVrO#NZ8nVX3i0J(s@4&_Jd??jgFC^WCAE>5bVwGeUZY6WMOBfa=kGQeS}~l^k@dof z5E9teu>hkz_yOB}-OgPm*ncuVz;+>oqwjf1Z0<0RRA1I5agG_eEB09^pDj=gd_X4T z<8>#Zfs)V2jM;k8I`};NxiYC9ge3ijU5$3ENxOAcn);6P;Joj|dU5cgw@rG}VkK02 zvs@rpPBFf0#U$+|zC15PbdAB$(NS0!vNtP}!ov!ULm&*0>sBi~qHLM`QL)U|mw%DnR~?aNV8-kDV<%edc*e$(V+X zWqR6_4?SOFvbF_#`3!yblqb_|#ER~w`M?ZiqbZY>lp8s`fBx_=J@Q;@bL>e+%T>@2 zFBX=3cw|V}Q?xe6TLhsnT-F|0kb?;q5FCuSYdYV$$sbA=iX3t9KnBNF4%Hma?RlB@4I>{H4QrYg`8`bG)^apXE{DT%(6D z-z>Xc4nhavK|&Y0`7V#;wLjt_`G9$am<=2;6mA{R;>eXq{8A<-w`adqKhH2H|t&cAu@ z&+&eJ7j-L=cl;o|`qOvr$3p3mMfRR*z2c>h2X1M;G@|Psv~IShU)B|9m#>>I+B7FD zb5F{QT|!x)X+*RA#U9~#j{7qS6STpfyde44lgA`fy3dgJ~x*#zV?HFyiwJn_Jim^$+W9>{7Lbv7g+2{ z#67*;j%NG(mV@f?vya`Hr-(1gk!O}|mKoIKFBqJ5*I!U@ZjZr|v7+p=3oU69Zd_$T zcj9!sn|zwD>@Q8eC2@mWEoFVj-YYkapA}6sTy@pb_-ApZUQ@>jvlWhm;nyZeG?j{-xWPv0e1`t)l9Mj#|9XDj6_oHz>j5@Edd}vDBelS9N zW9z;C>!)Wg9=i3e?tH6FePjEHSvk>eX3hTf*v{+6;BOpG#VVzSi;cYVU_w7E3u7fN~BE5 z_e~*GExDmdZipkByV8fD$iZFpa{toO-F*K3F!0=<9EauAdH?m}Z+G+Gc>7+OTi>>+XJ8G75|8U#8h-Xj<=9Z`% z&tiiq&qG^prFfTb8&~CXKTlWs9M&N*6pdSA2y@ItTPQo88;KYwqU<(IM5LU=q(pd6lxXEzz}3Z?8)u3%sLMSCR%6sZO&jj1qX#~jazS2L z?H>*gq`%rRGtQrCURN(~3773&mf&2MCd4&Bxf#*h^}2j}&LuSCSXM)8>fzDi*?1Hu zn0%Z>sNiyZsV`KG{j*}B;ZZuno{<+C zk717|St77fPc=v;YYAVTKHN+!WANS9=gN;H3n2=)o)Np*+udL0w^&WxyOYTdT5Mcc z=QF#}`MH;S3#oVDjj1j7jeSuipts!~0kLg5BUM;zR~stxNFM^{@7-OwIcVLf{*$6TL zz2tq`MI|{JnLo6bT{Y@Gu+u&GZo{c;du73GX%zJt-u6OR#C)T|t0A6NqIIb?b5{_k znjp%27YDa)Sc51av718~mxd3b89XI-Ysblcn8(TF$-lyapMryh0p@*XDJc9|19 zBf*;7v^!d_D0EUgViSLt3rv?udLOw@O0A)^FuN$o!yQ= zM?IC0#Uy#b=*pZE1L5NW5)*xb!`2O-pd4+V)Jsv=~8^U-dF|qJ-(yyVn+ddeq*Eisjh^Cgzwfi`#Q59brv9m$5I67H`H8O+Bz<)UrQ@1 z4!{tT3VPr;Gl4*40@gSjiVC$W&)k=z3*-EWCuf8MKIHZyn#h>@q1iApd)Hd&WZW?)F2KbSzwCJ_UE

nxLmzzFaB_ zEBTakglA7C-y zIKKwk^jC4mBqZduT@WBAVmAvD&!*dP04-6dme|ri|N8?6m7^ayjC;aHgn=yyT3U^> zN8c&|7=^wn#*i#Z$w#_lSMPDeG~)rT?M*G--(T{w1C%Gv&Is@Ok;lzq4R360h=_;) zye3Mw1jk3M`1Op8SB{RzKST59D@&c7S=rf+)5oXqSsKR!$CBG0;lWzG$lOurMhg z!04&!KVN(+^bTm3*eec>aUfkTz#|pqT-DSfJgo*Wbsq?x60ctcL0@X}>a9YX3};OWA&afPPr}Pp5y(_EQevJ`}+b%T+2=p;x8P zlTQ&-R4G)^DI6D8qg`Nrv@z1V8K!k!GB`li%p2@J%eHR+17aR-x#`kE32NEo*}QzN zB`5bx_elF!NUhR4a(g*Zdzv9Cy|y$bgkjg0xsd(UoDh0v|Wp4@`m|=4J->)U{X+id)Zcml|abf#ay8rl&)RC`=?l zWX&}oK99xa3S7(F^M|={xm@HSL9s;A)}ksv3+VH!;z_h{opb;GJ@A3xUGZWXIUVk+dU|OI4}$Ic zK06mTF{BJWdm70v_V=`!oOZXHu?p#{*(N;CFKV3)ST}vsk(=OxJ+~l zK`%Z&PREs=Bx%J;rj4gnt?Zl{YgX^!7zK$jGx^CiI0W!~qR8sthF1`?e+l}^sF6vA zlIpfDzHh6N$N~^(sE&YN0X%Z@0sAvMJDac12JFEs`o}0}Wmmn7of8=7=nEBw@3AHy zfOt`!J?kqkb0D}^s&rV>rJ1X8=yd30bM_;w*lVV_y$umT+Q2iMUB+hJ=;V1*Vu}yH z3`>QZijBM;F;fc*dJ#~r>uxk*x@YG~LASFH0dvdTU2Zo#!X~m{bF$c5I4dR4}PrrQ9qh<#!B?N`>jq`7rKr zU=i}E(=(8wKSNLGqqfd`c|-nfU}vg8F}LMjRJG4*8gixhLM>=@lYfD@tSj>TH7eJ> zrwT-Uda7B4*Nw~W6?s;_TrhsbK&v~q;zyO{h?^N*^9M1z6Kpv-+Eb)Ks>zK+{qosa zrmH&>0y?R(1aajlQ|u2xk0^lk+uYoh&R0IJq2+3gUuE#9Z?4F)`5c*08>MLBivRFm z!&5f!VC&fNZ9W+$6GRJ);i;x(dsn#YTHK4)I8hL1yBqJ!pw%+XP<>pWnWi?^nDC+e z$#7Ez66`yBjyPHR`A~^iN=uJU3@X-piT09vpNB9}r#R1Tb4S*?Ti!B}^=mL9zgCX% z!tjGaYkaBp6<3MHP0trnkitX2rwT2DzhKdy5*K|Wn^KnUPI23TYb_dUU}QB?OLG6? zpWOlS!$|nPYza6eN`ofA)+_%U3aV3&20_LzZ;LHd#D47%&-%hZk$bN`z zEPJ<4mCX6mBoF=XmV(aTnmo@KbJ(o88>1O<2fM$I?A2eaIMpa|?!+S%C!At6<}Y`7 zpU0eZ@~Q6$zl*MvxAE*3U?z{)B22@7K_8`HM;&kNKPdD z+S@JUcUO*BcXu18h}DMP#^5m#D6k$cohpCGxVP}&8rLkN>g9OzK+R## zf}VeHB`}tI%423TZpE*?Kjg|-s*RugW6j^DwQ{9Q&(F_0j^^mtY%ecItv8*22dkG0 z#V8wflIrj_A(rC4pa{0X^;b`>HGRAsHm$`js?;7g9Y94YO^meOrQ0CCKxc2~;$R7q2=Y6AT)h{F2ixc$rx_V7mP->p3oYC#^rW0Ft}V5e>p^nG4u{SJw-jAte856j?US5BGdb?lJKd&4pEi>H~3 zh_&83rXP>6M-JH)#7{Gc(8VRn$Cj0fE58RuA^1lNFzxG=Zov|YrAp`O$~=wtqP(VT zi`{J|gNy4v7NMKV?Z9Sxlm1l7*+u3$jlMVGA@rNR?=P}q?C0TwoN^~6v6tcD7G9%u zbM1>{s=EsX&nd{G^&Y0)UX{nmXDcUat!lK+o_`jib{CcheJ?L5DWQ}!3hS#%F*X*# zq?D|xs-pkW@lOW}YV;-+V(U0ksJbd{hVYkk>0kf(1__oTglqb~hR0kiw`?rlb+FD1L~A83E)KZa04UFD%zG#1&jBxxe-0 z%a?#B7;1$|rlUEMd3kxCp!zLt_Urv|f}W=wpGLcehbu5c2XINR*7R~1MRk8w9GA!@ zknP6)5FiF2%13jhg@NND5Wt9qg~iKNS5>7{JdrCE_uo7I;w=MCh@YPy5W~9*8IP2g z0s8^rn3Gde^}{>R)*Q>-{PR2TM=QjLO9wXz$&pXJD2P@iS2}?@%VE7A_g^jAv`_V5dcXhEW~ zvQkXss@kOu!LkH}-d zm>UUrJ`%?m=rXoCc0i7oe~RCkvQVU-kkgSADujaRI^rdt``4fz*RtT*W*1Qo;QOMrS0UPKp}kIA3|ZbZ`mZ ze5bU~RwHv6)^a#>x{7ft-R}NtW5Kl4+f1*|`^|rB9q7Oi%Ip^r6yz34IyCRD*xym% z`G6nMPeguHR z*&WY#y||`y?dPbZQtj&7vHC^HpYH6W&6Zx^edJIsYAqT^L>#?(4P84*nZ|#*>USpP za<2vg@zrDBvM&X)Hj8790CDYbbN@5_=kq?)Jd|v~K@ktd!z`_nI!~YBn_YR-UYufD z^6cabbK7chnp-8%(~UfPEcRlyC;iM;vw9HYt|&QNv%&@0M1`#dP6N+3s*Tan7##`d zK4G_Hga0^O6n1=pngv`o@^|q&Q*gQGWMX2H#D}Np0m*rYXY5tk49r`iZK_`IbWaY%L^Sh~6R;v`pelv5Km<`wT z=G=!c$K350b`Ti*UzqbN(>gDLEITieWNj%#lnY1H?SB&qq9@L^}1&tg1O>$vj2i9@fze+I z*LjMV8%`yrDa+@ZwFbsO?(CK4T{^xrncd-b%Cz=+BZH@JI3c8xqS&-O^&LmA6gfyg0Hsj`~X_Mea?I=GV*sIpV}aU!>!y#*&rdDTV^xb|i?CS7CdbRfxKI^PSgd#;V-wMyBx zVR9w`c4RX1O1yS`T3=~uP>^V|mbEq~lgN0DsbjuLJ**m!l&qrSH5L|ot!tsy#QD0* zc9zXHtekyPqW*gQxZ~E8K(Sgp?uF$_B9hWnU2tbTDbgId=;)sURe@356 zmhK$lLz-;0rcrPDzI^olL_yNnvwy8Dtp{(IA2oTnIJ@1_kGW%K1CLc;o0EN|imT;v zaDD?p3OKJcHbA4exc=_2iC zw?6v)C4&DLKG2UVie^l%^6hH9(h$5%mT2ymo(`94l&vZ5tCCxxYg)KW4!=e-^diel zS6yHi+g@IIyMz=#>!LcQtDCk%V@Pm&B`3G_ea`N^Lsm_i_+i91$@b%JNfeu6g*wJ*V4akl;KsHC&=qvmdtQ>5)r|0ao?q!>fS%AL z9KV`rvrMqKBgxaaKnBnIYzx&v2~rnn2C4C|5A;mLu=;;?UC z3i@1`Yq5BK4$=tjKOt8ARaGLtyB)03QKmJ9Ma+HaT!j^6b#;5Rc@w2<=3VN|bfVAN`6O!d6a*{}47%_C#ozN?e=i+ex0Z7GkAGJiDA{O-lNYa0IadNV5iSIAZ zRS-yD)a0yBoX7Duup$d!$N)7x#?tP5=VsDy32-Sum?3S42k4aqaGB7>1n#$yf9>qs z&u{-LX8MS{nK$G06SLNOniJ+7^8f63(1P-R_h;|l7Xt=QK`>sl^hXE4}t_X}$EY~A%niYD@Nwome&RWcEl*V*V{ z(8CAfDh&@j+>gr?OD}C%5gezzeR^CW4H60R55b>sM8z<_ninu0E&Vb}_4Uzd+kFGc z<%B=aLfkgnRHh^JuY3d=tetA>ljr|n%R)xqs&rKIcj=)M!2`i750~@aRVre_UaXrL z2~%jgOl|W)tN5dUrEVN4b{Ir^JE-yH_6culS-IR)Xo1NLSH2vfZqxCiJd6J;$6I{k zGvwV8Fw7YRrrh`W*w{uF7w>d?MD9FR>dU#jbsL>>5yBT-_=C#-U;Jb;z5k1!oQE9N z6?R}8XhH5xETV6X_tblzWh&#zB8(VXw0H-V`v{DSW~yzZDTVdMrsfxvN>vI=88~l@ zPENX<=5uTd1=-883@7^V^Z=R;G5S6Nscym3dCM6*@2S!I1>f9tGO3iC+lRI`IC#%aS zInPu6fzsZF85&+YQ?9JM+3&EfF6`jYLz#7V%S!#spYbW%CL?`68-0J34B_lM9z9yE zfBcV(rzYI@ll4r8ZMo4ef0p{1BT}<*;)I>k)q6^0V8l6TmnZd>kJ}*LQv)IE;~aK! zf$@t%wtSzK7oDXZB9d08@+H4J`Me)Wz^eT1lDo7gqKM0545VK})FQw7d3QoXOGM+) zjeTuw)%$5L_9qeIk=viv?TyPK>BmTd(Bo3jj3aIv_qA?rRb|;@DflonA*Q0ZQHf1X zyipG=Bh!4Km$R0!BkH&3W&_`c;Ff903St8}>!FP3G=_*S(nWon%dtGF1+_wX07Hty z2?}x~hv~~l7@wBToae}ttLiu867LR_Xv{}Bo}2CH83OU+pCbh{(Rwa%%Gqo zPLh+GgLry!3$-DE9HmIHVrI0o#n9cbJ#1+TA=}={UK2~Y*c4MxpjQ2Dc^9fFDbFIo=Yn*(KQX$v zq8M>*?lrr>4;|t?wv4Re)i?b!1HbI_wBmOi^h7Y_=;J~On&rEKANKh3lmoF-quYFR zac2amgGNZU=ANlwg{bizYwF;f{%`_Uz3%!&!-yYwg5>ttU zMK_OZ#oTWXc6`&IN<5n>*v92?u{GX)+1`Qck?Y5(&SxO(8;bDf7 z3nT)iAr<6nb+B7E_eC#T-{W*!4H&>Sfv>iXd2kl&XpDBWm`s#M>JA!j2lyNTjtfU=)i^cC?9dexfDfmZ4yU*)1D3KbAiv+NBXon?@dzVCqS}TEZpw z;Z2**Je9!QO!sZh9Y#_NAJ} zK=+e2ZvlPTx=g!Er;GN%fampI3-+UjGG~8KQ!;KC6Aw$b#!KVZglepKof;3Lel%K7 z3Ug7jpK4&*u;IlUeq~grQ9|ut%G#2tmysNqYf`0RRfMlNbk6Xt{Xb{1>Qsk>1rQdyGn1`oQ2Vl=sRCl}W|Lo#)V#WbMouG9d@>qov7<3;kr#wmSkLg( zi12*8pmmn}sl}HOB&(Xf7U@EG?BB*&-K)%DUm#s|#os0sTCS^0W1r-ol5$mjPkU05 ze$lD7DrfmvT{UQEu84qfp3PNqKI+73qKQ~OMz5#JKQ~TXsKF9`$OY&@rE{GV@Si8& z4YW$a>Fe?snYX%Z+0iA@1BiGSaH;~Ew~v`_*@^nl!aGTWojueXiU(Xu(k{T#zLC+7 z`&>KpZg%t(ncqW&m|ki*7hDW-FQTWsMnA1nq)PEDnedI3M$u^At5YrQr&4`(7P%N~ z9IqBHgRVK74GXf=txrpxT7ziIv$N~p;p(R#j+{F^@Fmc%TlXzo`OV?$=U=jHiRnVPaU4DV9MGvjnaU za~VB9C@GUOhdd$ljMv1@K6lGsS~?<-9A?-BJf_~-$LoSpr;ard$flct@BuUD zLl$c_zVcbN;&@>)eof1WyHQ!?%b|!5cwwAe>s~XpcI?JoQqC7W2!seyV$f#V#`($F zA^#~sIJm*?!z>-08SKRK`gEv9@AN)a<%_so?xG4)&GgAJ?7}a)wRsd=Hpjar6qwVe zH|s-J6!`;t3$z@;gh`rlg)?*QiCA>45;8Y?;}7qi?arnrDrkH@h6NW4)~r*chv^PCPsmX44=n?kNy%=mLcWi%Q@iNkCeagt6Kd=c zR+eu?RmhE@cLBXhU%|YYYWh+OIdCR=bu6Qa|T;!I?vS zh*$G6@>8%6xgVRc@5T$02*Yo(@1oI^h0Y?!iQd@$EWK&Y&l2TI6btqH1pisnf zeAp&V2TkLfH;}ZTdrA}Aujy|WPJ0q=h9YV4Iz%`Lj0&HD)9PL}`fPtgBlZsnSiHzs zYTW>C=B>AxKb8i>e99`_Z(r{&v^KZ4de0>M_cJG<`Id*}bhw`nzZC1;)t~c)pI0~G z*o!_<@+kW1$Ks-4v~>8otmL(n?z>LeCezB8x2p8!s2zg?qvk6*6wnE(z7~@{Pbz7n zQ*#i=Zw14U^)KuFLm~*9iZ%X24mrI@EGz29oc{-ty+?|tjvVYT>7Ne9r7kZwU4Tv( z9-HsktBr{}>dD3L7O0GvLWN#DpCPp@{gsXa{U%DsGxC*| z9Ln17>&aPe;+Yz6O=73zl=S3tfd_{yj=2G*-a&6d6y=1xYlA9@gU+1l1kwrg8=BNItsj06FesQj;$;imqM6UyF zen$&jP63=W6S2NvqjZy(o<1pcDUmxPG>+t98Fc3*mn=+q_4Ko7p{6y|-Cfc`w#%gP zomBr~Qk^2bdGN}9jidk%OM4@gV$r)OjaR)fOqwvBQ%%U);QFUycaGf9oG1kVxLH$e zdo;`k2qMS61_nw;=L}_>h#+C9{3q@lSU~pgrsihgej+Z2%jLJO-pz;wg$WBy-A)Ia z=VXro@!{W!vJ5vPM!C#iUB4cr?mKFp#;@;$bqB53d^Jjdd2)h<)Rt+BikICaP%{5e@a#1wuwodd9}NS%Du5j{ z?tRD~+ji1Qm7{?=Xgw|+`S=_SZNj3KHpKsxfafVA2M5Qlkekj@vMmj4*6U~k`EX<) zFG~W6CCp5!ARD)vJ));O-n^P-lb@_QwWeM5hxk*lvd?;`C_wi#AxK5^ew0j(DdXo4 z;I`CvtP+_T#}>F)QM73s99GFU7;$0Un3A9LLsnjk@VxJmigTc#&*42bX>3!wlGPFu zjUBXpu~_EYFa0ic8<=fBBgW<-l-t`|Y#O-%)5lDb(Q-6QLdnVBqfhl{Jj7`8L#ZgnT&bo z+`m@xWHn4B6Y)$UPT)iAO{#2^(PSl8M#CuqQ)FL6sT{DMAkwluDUH z=YY%Fa+};&s)MJc(sxz1XJXc!d{P$|h1h3O9Er=BvFO4WfNBrSc~X{1eRN(Ss}av8Rt7P7o}~p+6{ldm)a_2di3lqdaKvP zr=1hRT3NF;tt?qpHBV|&9y>D|bM1FcghYLP{!t1=PLd*5D`GEcRvBZQ{@Pfeb4*;P zwadw6=ZI?m7HPNeU?7inM!`R)#CyN@ZoX+4Rld~yr~yeD`(Q`S4Yo}!k_28F@~=OY zl-6Y=-at1KYsY=Zifra>3kbcMF^zcdUiC1Jq_=KN}{` z-`5NCR+w#fq(7NR5_FwAeLqIr7KQH!lhj09WlQrXw`z4gRMrkS<~E`xCy)Ca0*suz zTB!mZA)u^T75Rg-|L`n*O5+MEey(UM^lhp!>3~oES*;Q;1@t$gua^M0x>v_Zda!#; zta(o(W!;J5QnH`|ZK^?x0@S?V>kHhGyie5@D?L}P?uTcwV|s>7GL~CDHf^3d3nn#RiJKQFDt`8JKKQp4X)*Xa}?p{253E zMpH7qO&=I$KY2_1`sFsZ#cy5ScTd2EH_E36e~4cnA6HpfX*IWxI;0Z_HOu;u)@za` zyvxi&z;T!488f45C9A139K2}uGWz9XPCGSB#S5WM?F$SN&Y3rDBXeAnfRq#L%Oq4> zq&T6Ldbwt2K$)biN&i6+);aHViFZdBzV@xhFtUr!JK2jhZz0_naxRLzhPv3OG4A*n z6m9;r*`IE^_=D!ZJ&ff#W6kN4bxTbo&`+eg2OJQh|BPDDLy_;MNv!c%aTAXpQaMn>uFkw?MOq+h7*D8jQnV-CUja#lt%qFquhq+@4+;>c{F)W!B>EUZY+ z7ZuKzN6$o9lyEmpEo)BouXHJJql*5AA7As4Z3p2y9&?R%ex^?vUoy($etOk-m%ook zfd01?{EkZa?ZfY*F<|z~Qi)dXErbV4Hmt8?~WdyILm8n9T z#Ut!|l=ogIF}&=+T@(=u-bh;?(LnhPl3NqKORi*MQli0lb*ziGs#M@n__> zYxWwaOiZ$9fv(3eYse9D7oVKKv!Z(lVYE6ey-V0?nRy@rWay;*iy#Je)wvrI<^wDi zg^VL6Khmr9pvsF0bv_3mk$!0#Poman>&-a?|EvmXvh$BFhnAMmMjGHt{`y^f%yysQ z{huNLd-P|;dAWU0!Fw1+4qQ4R&>m#;=gr@LX)&Mvt!G^_{!F|D^a7{K3+!+Fzj6*i zWW|xZUS7@!tzvY91=I5JU6w;`fo$#pZTB{HFdqVmK1F_1SpF;p zyv#XD=)HUQzAF5QE%4I#w~>AIARy*q+o|c`z)mvyn6O6Z<3gijzEC7}7LXy$)%6UB z@ZOk`TQ)WT(qU~MY0GCpHHrqui{AaM>k`sw_zb8~-oE~$RjR0}>Nl16%X8at;?s;D zWBV8`Zv63Mfm*ScBF@9*>1uNztNXN5v=>}%-We-+;Gp{R1Wmjrr$VwNhE>Zogh8tv zW;pw%`G`OmO*DEyf=L)FCeg!dgNFW58_l2LL>|s$#uolUt^z6`;FFx z1${vAZaYp^qs~fF9;R);2A8ZqI2$rl^*Aqc5;`tOp+U@u8)c6yW5#`Lz-y+v&4QXp=V2+5ITv9ibjxZ zZ~9TMWW7}nFe-c8{ZJ_6nHP>DTydbbxAN1S&DSpb6-MNTL`cw7pQu?L{rj}*|3lbY zKtmId_dyjh*=eXalwlJg*jMaZM>L*U|W0|g|| zt;NI;T0w@*tK3d=X+7Hr2A8k*5ZfYwmoUgEHkgU0{^Yy-ed5i^a4V5! zEh`7Z+|NI^`Rkc~^HwXuLN6wO1ymjy#|KMDROmIb_Lu=HrgW0E8~iyGge^{uEQgbH zbR$%*u*qtkOg*9(CbyoJ^rbMu{$*JE{U@iSPw;^n7;m92QF$T^Qb90qsht5_x*6plM6(jZC&&0h*6_8q@CSHWW&_Q?y zXpk`3A4fpe3tWDyKbDr-ie!PWo+d8h5PJ|tnEm?xnTIo$Qo3{!YwM|T{{VICh%~=A zy(}w!K-ml7-5hKlOg0Ya&OUDasnlwLn207RrBj_cnc|vLAwm95PAoU3KqKkd;K2wA zOZA=OM>bihXjX_5-h^2zzx>o*SOiL_C#`PNhn!#N$#cRi^{VF%?dcDeJ@GoYvT$?X z?tkyB_eIdbzxzr{KY8M$1$$%KGo2X9bOqovP>6pHTFn~=0+_To5EbQa&RShn=p0Tt zxKmYSgF!-g*C;0Rb^JROwF>ou`WT^hJP-D09=ABlJdGqmEC(K@WHwq$0d^1yXQedf6n{wy5AR1m!8_K1AE~i zZSxb}OE_CAa8E`MfDw@)K_!H&_$pM!;{n9OKurbWwz8tZB^XIInF9 z|H$5~yt#i|$?uL{LgWt)ihUuonSTRWU;+h^fZjti5NCv#Xe-FeQ!y=h;^7ly#!O}z zE59E$uI|k=eM=q>^l}j}L(g~S>%ybLpmo=s{vprB5HOX!Vkosz)Re~;1GcqgD-P;3 zCq2sg%GST0rjl&m3X?k2zxU8}h!9 z1N*<}tsZzSJKAscg`pXU*$Q@^lgCC+^Q+6OgXPGCW3@`o27K}j%dsJGkdPi4*@Y2D zFJ{TP%e$HJ04J6_wYPiyMXfe!mgF_>EiCMdP$J1u=uhkAVG+e&XCV_uA5!K@HIx(o zEZ#q#8skspk(@%E9^R>#K`NGf6TD#o0VbM~Fs?+lwHR1I!hjc1!QMixLa~vefIIgxX{s~{zK&YwMHeK)CW|dmZX6s-ngBZg|q$UZ;126jY~=a<*7vU zvnRp^8@f;K1;3T+o?9*EF#Y@UCE140OS<1%i2<@9$%g`y{~j1E1_H-ZUiDJgH*h|K zMsE4vDGwu}h=IXcaA+t%3OJHKu|EqK$HfH;HZUgA_nFA-;bD^^#ifX|b>}kV{w(ik z{Ju{%kKg%=_SNElwsZA2*+*?om$!p+=^s`~Ds`d7YkC;XUyK;uym>=SP2FP#TmZ8+ zPzf*v_zhU@3`zXusH#1!P16j^qh9UIN%|;*0S*6&@VToxjSo}WB_^LKrUDxI{}TkU zJ&Oc^-is*P_!)`qwI*7yU*O5+&?=8u7_l3{3P&lsJGHRI>OA1%9MQATVLhVR{vQ2uobY>yJ=w#@%e^er`q(xi zT}0CrcUdW^chuUEVPPJqv40-z)wD{?g3gprF%`+n#OE$wqQlnvt0#0<)f6TLs9Rx5>=V_X<`|h_5nT zx12}s_Rj_C6t_{@VFZRh-N0gSa$>5BXNqWyGfKhw_)fT374LE5_mo=3Xg(n!BGMgM zAr+8cdhKwX8BehpX<;|BYGXgzoLsnaSuR=On9-vz+kX*Vfk&r|@jP&DVX0hUmps$H zF-C8MXPshyDkG3$ezN$zagJItk6OjD``!um%Rs4UXY+QCO3#t*c@<@vyl*bYMVrb? z$oVV3*V2j!jX^EXG-; z)%tXB&r2-5!&JOBq3?63vTMUA!t{A*7#uLR81tFV5r{AYS`7BY#KcfiM1m`Xc&nhx zJGjfW<+g`w$_XLVXJt?eIT&(e0+>DDzN5F7xXG#IjgaRZZR9klmf_{!errzHXsOE6BE)hS7vzY(41`e;cRZ z72@yl_;G!EXr)2!6mC`RDH%*}xU<>FUB||5DGcKIx({2-sr*{Pvol7u@r@pDvvAYdj_! z4%!BH8#HR8zxex~kbc%yFIg`7u;$0P_(D;?6&@Qjd{J?Ao&u&!H=L{U;GvIDF+EVL zS&L(Yegea9dzy;qUPut~MoTA(?po>zz4CpSzSef0RG@h5U6>K|w0igkmxMvC@2@JT zM80^sz{i|Mu7-WD-ZoUFgyaRU7{0R7XidupR9P1fGWS|aX+WU+S=0NJDM#1Z3EFt- zdR!uO1CKpRiPqYO%vnL1?$@fqZ-7M`yF1Lw=Um=7F5kT6sPN(WI52lx-Q-hRusJFjwGbB)(nAt@B}wG8dd1jb z*b`;Ia%{g*=+2XN(c7=S#X(ZwJvPQPPjdpN5jvcBduFwt#o@d6=wKdxc*U9?z>RV z>9ap{@9C?{TC5(p&}4hm35!Ooj3aBaf@KKkwh?Jw|6IL%!N4I$Vb<|&N(@Tt$+%GM zds+QZvTxk1un;d+X#0ENKJoKc`Kl*E4Z<6&zO*wthETEC4fd_0%9W2OH38eGk__$1 zA_WtZ9U!>^G+w%2^}LRy3V)y3k?pr61j~ZS47)_t9u z28zRdgnSsOrE58*C-dWF*E;ufU9F_ZJ<$b-rq0hYgBh38$1D&1TZ6HJKk-&^@z*WI zaYiOroBf8TYoXouo=q!c%1bqKk9M57f5BjaQx@PF;#->28{ z@b{lVULE?$ShaqievYz@`*g|?s4nKfX#DDHYEWLjtb#(he85~>Q0Z7|z^sf9cJckY zFpy1qp=;jAE!}tv(OhpfDL-pda5}f&&Y=V?9uGI6UoE-pybAdDJA)VoCrcqI~g&?@|O=7C@mh$b$6}q?Mh19_|J=ndxD% z(d)i|v;7$)4(@oXn|ZVj+^VKKYZr~J~J|gG}IKXg}>JL2%l>HaAe-@ zW$Db@wn6N>`@&K7;h{2|Bbudct*N>F=AYK431?8_!SsZ))|k0fB-*#i+n04*u>0?(_-XJ zV2%{YPaJg#FQ}V+D><3m!IGPE@Q%UISjtAtRO0TwC52!kDNStP2d-={sOvNTo**XZ z!KpQhli5_6D`N510&dRZDrtpwu1<{^TN`Oz`_>*ODsv>sV(tejUGj||8^+PajQ9%s zuerNRul+v@$Q4A{>37LoUiEXRpN{I6tk>(j!F;>WYOU+@pu3%B=IA$@J8$&mA6p11 z_*)g!IEun&-m%R^k(r(%<5gAnNEQ?91%fL{0()arWi0FQ&^1kb@GBdOP%Mi-6G}@* zQuVr9pWAiyQ?gY583si)$gX>qO~TUN#=lDx2Qvfj^}oxPo`Okf{}iwdNJ~ot#Gnmx zB_aSv7!vM}S%9hnz|*s{vjZe0AXV1W6@ArS01=RxnOQplctz^+SJ7)%{K1!{e01A2 zKgtsZuG~k*rNafckJ_J0o0_d@%@*#T(phXyI9c?3Z4GX^u(nhHn+@JNJ82PV_-^xU z)FdLa1z*Tgpx+K=Hs3*qB^V&`rkkeplNX2M{L-Aqsg0gc+g`|F!MWiX*j}YT=8Hp} z#3q4ota#7tviC=3i$2f&&6K!Hf>W_dPQdQ%Xa89WukC3_7uk^gyt}QWafU&**CWSm zS28(D0t78w8m~;>>O5`S_{qOSXj)#9m-q<9{y7I|*{MahzSpx7GaPa}Y0CY~y&(0tb5%H$89UT-v zSq^Ai0uPMwMtWs=XR2H`h=~ah6!Ew@vuwMapP6y<^h~^}&BB?fF^|g3H0+Bw+}qQ0 z{PKGV$0;nN?FPf0Yn)d_lsTljGFo1x1X-T5xX=N$hnd~L%jZYWKrc-X{<*(|B zZ;rCETTK)>taVqvVZO8YkV0MlsCXYWEaY=|)4JM73IfSUOZQiIO-%6j2#}*|XLN%E zgM)l82Xue_{CTj{svF0$Vmk`8H^j$Jga{ojwG!dsUA)+O_T)M&GLi{sQ%z7&)Bqb9 zD22mXV>1F!JppyBdO-*tboC0qJR)`W|5|v@7s3OrIG!_il^1wrZ+($*9Kv zIaUQSL5~XSOU$PmOJrKyG+z^>Ko?&_5y85W^Q@-*CQB>b5k!Ej3AodajT)cBdkFf8 z%Xa!ySRaBBDiwmk>H`Gqeyi##|I}&}4p)okgJ=F$_LV%Uz|?klU4!l$-+qdVBxTf{ zvxR>siBjuM6Xj+qiYzVRDtSo3&&BT2EO9mU<$*CXo4+PEp&U*2eMFBjt^Ec3StBJ- z_R+!GG~)1lwCNf;ne+BcmZNkU+Cx`PP7W3p*2&^ve}Dh<^d-l@pS0o0lEGW)x7TL< z)$M7$CvVYv3?v%x~^31v9(gOF|UAo3pbEj;>u3ZkBCCssA84CyHTy#;cGyj#WFt= zkQ`dSqA1;DoOf+*(6k(a(CCHF)E^qDe29!cB)hg%U5_wP0N;&P9yao_r`)sPzfMWVB+b5Q1)J{%Y^@L}0JHs+E~z$x<(vu+q;j|aR?rnTiMU`;aP zk9N6jdD0yMdn_YnaRobd;F)`dFAegewgcGC_|v=9rP@?aytd`Giqi7pxz7GZvr_WR zM;|JlM>hI0ef|>nI4JAGshQczp7LbJpoYFOl{$d1~KC;=J;$7HV*YGFLQzA|bd_7jvaw zT%)H!Gm!aZU#*B(W5seCg=hcq-$IkU#KjB3ex7~?dA3)LAG&Frd8ZrXqux`Gh+8(z9rIHoQQ{( zmi97tTrmLc{wx5Nm)=v)@cPlH#SXr^#U|?-AH|>2h(Hd#fY0`G)p%- ziAMK{9%3|8Imu*qb51T$f2ndI!??JLk8#>R_<%TZTknrS{4TZZrhFn!DoNRz$qL+?{5oqA~^K&;SLk>+7|OQjLlv zKG%Z{`e`6pe+hU20`Q#aFLlA1m5mm2@WNl+$yVvfrX78%&440W6g~QY-GWF9S=}YG zZBKrCi>7$8oAV)8%~Rb>2uf7aN^T$jS7O%#;q^7%Q=jV}lIb5egWr_q zWN4Hjy$0QSBaX%$4+N5LrIW8mSIaY)P&dZh%Qk>S@qNqPtw?8ASGiUd2*@guR$d#& zP+~?iz@8zZ5wn`~wz!`H8hSzKM1U3|HIisJUL&X9uc}1m9^}a#cU?2fx(^5Xl}%Uk z`LZmI!6#r!?kUUhw)kdY#<|+kF0ZF}%rl&VWl-&@WGxSNOWa?jS=1b)`&YItO^YFI z`?jw+O5Lnarw9#DOo&?OvOD{a_4<<7Q4gZLd0JQHd50bh1Z*Qzd!A@qb!}`rkLl>p;0KNsL zQNE)70hKh*@M_3I8U0){|&m+ zJB?5}D@mKr^rchzeRKJeLbWfi`l0*9QM zJ+#h*f^~4+%U+v&l;DiLQnvx&@{D;uAYKe{;BB57gHM2Wk77d+U zu|i^o)7!FIUF&oA`?sQC9_3k)KKk!B<)>4+KEh&QP-bcl62r%j9wQEQ75hG|DyFHw_3vWQMrZTl+FCW`Z0OU zT=4SRxLTpK43`3v-0$x>2K8gfZ|-Wlc)#>&P=NJefLPHSJr@N>k;uh!ZDS1Ba2osm zWbgFbya7O-1Nf1o2za_A>;pCz2L}i4#Jzi^8qQxk6f&gq=%$j%qu)+mA5$J#ss9%R;|5qAjd=dgt22S1A0!dUe5b5eO#g(g9j-? zMldHbory*QL)Ko$6~?FaR!~$#M@I)hVyKt^o)*wHmCEjIZ|^CcI4`J3A|3r;cKaf+ z2jW>+)vSF|o=enz?J=IdLuQ-4Vt?bsd@r;sWN0y;UlDt8*EGDD?n=bp9!^5x{m*cG zGV#6f$bi_CfJU8>=1?XLsG!#Qw1|bh2v#lfLqC{G{$Oo4Pp-x3L3)Gy8IcZa_=QNU zSE|ogW$H;R`kZ>**fRI25_J!QG3zbqDc<>w^>$~0yrR#$mRLmu6dsnFpV4bOg0g~p zY?i-%RycXK!V1xjT{+|<8r_E5=8rTsPOcsj$HtozcAC}M5+?|BbsH|fm&h+uOQ3^h zcxFzBd>^U{Gj$Q8_85z6R5=Lvs`{F;suuT1<+k<4GXxra6n0NVGUqJ5|9yV;#W8kI z?h9}<`O{S!&q#S^{6lD42ryq_`sc+hB}@P~4w?8C*43wzf zO991M9jG19DB0cIG_$iCdJXWTQy5?X!S49vB*xTzZ>DM%@dF-e!C}OSHmmuuVsjTS?-w;=`8soL;&6Du%}@}07XP?$0{Ha6A1I64Z6jBEpJ0p{wgQ5^7qU}|WwLazC>;E(&d3jBX6XUlb=uk`g4 z(s|DTom8(&XjRqm#gH?(%oP`axcT2@1wRp>u0zOWm*y_3r8NT-HNs6lN}nhyF2}ov ztMCL1CKsocz*>|S4I(_2`13fDK(g|g<|AO7k4hNmrj;3-99)AQCI>QS%Oo<5fPidM zLxahkJ20ki-@b8ilRfFx1UwTRP}N762pWOWQRZmZn3*oklxi}AR@2zJUp+EbjQ{X` zZuFOyNQgrxHn<~|!6l36QR7Qzlz+CsC%?*1?DYeVI6B6G7$eZ{5cc=m-`kVlfK4n7 zAWN9n{cQ;pz>&8Sr-txv3hV_d`M0P1%kX6@1+okVCKkthex&4NCaleybBp0BY#}Bbg0}a+LiX5b)eM zW&`jUoqqQhb?ru!?c_k->o`R$bUPj*3iSQnNgM~4E!*;W?~0&NmAaA&>bC8xRb|k* zF9%q;a0v3M9htt&mnFhySh`ch8omhedhE4N1=&-Y`#xX7pr>eo1KnBR5{Ad;J3P;J z1^>tn14z=yjFtF{|L;VUKV~s*pF*EeE$0oA47O~KjG*lc@0OkIFJ*&yhALXkZfd8r z_UD^|PLr9b8|8TEFYMgIzW-(EWa0E0G@*1oMa}x>N!G^`j~_tx$Y}9`r0HS1bIGSv z(`&rGzBNix8EceSrR&uU48U)B;<`RVU|7{?nld0H)e z7}8>Tm6K3%vAuz3DOoj*4dcQ{D<( z+x4uhtQN`l8u2?^cB{)RwoyM~6Zar6l z(}Ybv$v#;q0l$vT^w27~-_-ZXczRm6>#3Ded$*Y}u;waPv}I>s0AziOMCdm=S1<;AmR3?SJ&KFjk)dwU(3XemN1g z-J@G|6`s}{?Gc`B z1POuA_O-@TX9TO3%W~(o5RY++y)G4}Z5D4jI#ak3E-WucAI!CfnR{$rPkC(PnN|ks zUK|=s8P<8*OouiboI$73b*lLLtp|c_QzA*X$eJHg%N>}1uARyH+VPfc-)(HR-nx`& zkF+Q7PCJ|=0jJyV3+F2k25yrmD+SRxu3rIj&K>4;84@0@TV*5;IQp=3uyj*OgFxB| zKn}uf()$&VvIexFQOP(v2M6Ub0)C4)+xVL;om?v`Tw`vgOgllq1opA9?$88N66DwzNS-}XYKmF z&6kLF%yuT7$PrETsNdc}oK{X3x-p&7NDqSkjy)`pR${xFQ54A?Ru$!PQTMwt1&Q{Z zurxR4^1AxCCYc7fRfdMX#MB4$22a-efVTp;7N{lzxKa;5#XB&=LNMTD@rHc`Q}-cc zE$(6Zkk5Gc48B2*)fYv9k8ZDDm=jxG2UwsIW%gPY!)KfIXiGRPwW#kiYcvh@kKXP7 zX|B=p&H*Cc04#KeXQPOdhxg_!&1zJ=SG)EBYl|m=L}wWvWJhzeGT!>J@A~xDLJy1G zZ)P5FDd~;yoG-BW21ZuyXD2+tad#hI}Q+p@ZJ3T zXrj`mQ=vr~f|-2Jv-O}rJ27hc+o{9wN&Edn!$YS*y!a}*5AmpJzfk!m!_rJijJQna zo&k2nh8ue#&lcn*156_shlA#>&8Nt^8-*U|kp)G2vDtJTTp?QOmru1V=<~)~yA!jz{ClJC1NQQpEr^vr<%9$R&p7Mo1UU;OT9D{DB4Tr6qv`An;2-86DaQYB zl$K1is`moT(pDtS)zw6!;PxAn>Webn=8C&bbH=SRXY7zqnn1=;F=2ml#ngrj($6U+ zfU&H|3)F4>qNw2&Bt-`O4w;=mtj8s)@fR75mMf!E8}U&t`KLk^yqnw~_q$(m81jEU zDOZ1X8&JM*o9s&yUe>Y28F}#4Vf=4>^oiS-uWJAzD;q#x{NF<9AD>+KA9hBMzD(!G zHO!l%-<{m=JR9~BTq2&M(=AGUR_fAm%Ul0ok~3DKsddQ;3F(yK5SUzkxai`F5VBac zDQW*G#G&eoa(%pfdlBSWgjIQed_K?xwU*Z(?@E!XcKWu#^>AmZCg6y_oz&QzjF)v+iA_eR|@?kb#(ohJO90^NWVaL$g*pmPChv z)0F?b%k_ob5>U5EqAT~Td2)V}{BU#(2pm3JWlopt0&Y*WKv9yA!-^QNd;k9V84x{1 zMnpI}IRUEY<`6*LUp`?2u+4UJckip_2ZCQ4W26K$w32>>ITCz$XNo#Eu&(X~W_UHFL(6LojyPjC-|A1h=-0;%9 zC7I{S?@@fo8}GgGLcjfL?UbdB5QJ5V_F%G*f!?0p&|;j*Oqh81e~NyKi0U}^f>ftT zQ4K8XvyXO0JJ>$0>_lAFBzmCmM2?TJLg9Z8HsO~dhaov)ApmNv+ZYH(>;Og6QA7Zl zp#1**FCao39~%SctblSn@Hsap2XJeyFlgO@!vWELdRTREu;iytXXyaktU^EaG3&?> zX#O#Z;U}sVDhPPrurJ@++Ss(Tw#s_xC?NwTUp>RamFwNEE-p-sKYsuF@87$+@`09r zGBhACaIw`Bx=peBN!7WjI2nq>rrS4uX})A+Wv6q7eczm)zu&(guUl@%thihW1f4TE zX}LhP5AV|q5TJ6{EpVSEtlqc=k5vMHj){qhz!xxt;9_9dLmfhVa)L`jqOT{0TOcbD z`SjVdPzyk*Hkk`xScZpiZ$Vf(e8YD?9g%(3`V%*0QN9CFMI&qxf}*9U$1nj-tBi?B zDFQnwO1d+|1jMM!YWxI}CIrLJQK|Y8PSv`Z*zgLJ_OQAn zAseY8rJ*H#C$}En#?p>&#<29wZDK{M^l=W&U|G1}c#~`IR-YmRvSBUyI$p+kKjfVL z>ILzbIaw8|p~ePoaNn&jc>g2hOe-+JZBGL;w5%f> zGA0Pe64xE_HffC3xNQ}!0vET$oBt}MwxX04vaH)o>tS(8U~$UXNt+(G+NH$_#|iTd zNF=WeEBZ_+KM5!7b0i(DRFvueSYDsaP{;}h4}gqKdF&~qBTO2r7!;L?tIekZzq}X; zd=rKV?>z>#xNk=(f0y17+0T#?2SKsY_|Sy6IL_=T2UgC0663n%Z9_BfTify}wH-2g zRus~Fv&WM^wkc#6RgQidwMemM7nskbG>* z&`6Y@QOI2+A{K9@IX1Q?tDQ|63n>?I0?_08<-_#a{dRp$&8{aVEV_Mgy1a9eMDwV^ z%xns24{*fka|)`XBZ_Na=b~@8W^XOb?Vm*aiPH_L>VC~MIIMMrla73F5jG`&a zy=S0Up2Q}>>9UJiXM`Q3kx{OKr6IPsT~ZiGCk#`5@2B|(5W~&?A8qIC#lBDAk`I*hpZak6hlQpFU3^&fg@RTUJBkubbZ> zO%uqPFdU*0MiG-J^6}g|U)r6Nwib$mIHJL40}Zk;AeRuQLBjmozRj6=YSC&?IlW6J z?bt}zRi`CRO2@6XloIq#SZ_>FZSs!mBPW7%xEZ{Z5dMv(@UwYutm zOIAhv=d3+8K3+X?o_R6cwVI=jRlRld8dz6AUt&^@hq>q4yE~_*oV|!DjA{&%XOmR8 zG?eaR1x-`z{zsBg?3_>Cd)%7XKthL+zuuUU{n;Sftw62Ye11Io^d=^*cZQ{EhEOoe z72H;RF$$C?X;W5Fvz$Fz4H7mWujYn^6mmzCQc}WlXpuza~cD`#_f!K!5Ap)?sgbF5d!$}BRjf*CwAp<6 zOx#x9BK|F4zUj6ek$%>TB93SUe0%<;6JRPmeOvzo;1aYN-0SUqszCM6ZgbbUXDA&eSY^X9l4)JoEiUadXS!wIPgDYxAW4q@%<(zNRhi|j$R+fHk1g}(9;Ac;s!eJL1{9#O{y9c_< z>E14U^0emk-DZN3y9$ra=6$0y<{45}^flCNOd|hGnX=iDuIC-L3Gr|#6mqdxZmWK< zl1+64!7B{xt9Cx5&8_TOs;AKB?e8jhefq32|)7Mo5YxqPRM( z)jiQgJ*aWjCGTuC?bV~TG^=6LewxJFNE_XIc}3*k6Y-1jRHjRb6B2^C(WLjjpu@@Q zFz#^W+6X*p(pX6e>@<|!ZR)faD55KfHZI?goIY=j{B}pWZ|44+IS<3Fig4c%~f^s?kKmx#uQqi42 z7-s(1@@`MqF{S8Zy*ibE{6f{`m~*S9mi6ft{+r!{Zo0Bb1|Amou9vR!assf%NP9qzQWHCuN5dCCwj2=u<1_VcrQB$5B1rbUYA?UFqch%zZ`< zdyl_3ID71e94YNLtbLY<*q~_Ih^hrv!;Te5FMFZnBsdJ;bRsb8%}K(BkB2v#w8!@u zxAi^zEghxvs8$;b-;AUvFY{vn%UrX1s0< z!%Lw{o``(v?@!{f(Q{c7R5Y}_`5S%Kd)huQ4op%S3LGD48I&@djt3u#Q^)2&PWz>u zIa>_#3mJ{JR0h?`xt%Cn;E_&>SmVkMf5>u5IF{gJ$lK68w<*#gNNsidq3}(cN-iDj5F?~%-abzUFY;@cYywwR! z(nY=1*=b=$kwH+c0~JZ8=cz5`l=~9(XD(YGd_FP%y;#?u6<81B8=Y*zF``+z6_DQkkp_g`9XN|<33XE!%7I8Ym4NSL^`)MX1EOtghN7HK`pw{<98Z4qV?`a~ZJ))**nu$2=0Fv+*rhFG2 zLaCj4UcYngjn|*C3=$x0s$6uvF8reD%j<@_G5mW#PXaFjs!sh!#A9}3$MBQ~?k-@G z3AQ}#G)SY3&|gv@UMi#|4{vO3G>ZPa$?=r5#Em<0si-){cUw)bztL7G z(dLAWUGj+4l;Mt87}!7Z1Iu=`NDUbLQ!Zm zy_V8*GooGsuMC(!SHZo#U$y7n{f%%(NHIxppM$LEV09)uYXTp%hnl5hNR%7iEZ}C? zSM<7jN?TD&D=_!xXR^3R;f%kwrj{10F7t9|c(%1q)fafWmgAQ1w=qmzT+C=}bVmg* zdsC)DtAHbWlZJivyVK%!e^TPdgrS{Kr^D!QtRrWnr{Xb{vW5@-EYO=Dn)v>MP|3r6 z5k;}GZ`yg3nvSFQUbyme*<0mvBLxz9fvQVA;f668av|Axf%!@8<+HA80u`_A)uJxm z`!)7tHdA4z!X{8CT77x{LbIC?ps<|dl8geEJ_*k;&o=0AbRJ&dy?$plv5xRMNVP?H2BQg5iesK;DMjQ5MG-MZX7H&DP|;L>f=5aV~%8SQlM#~MS@@J>m-cn zpGDH*0q5KG^0PkxFEt=l_?Hbf-B+-q7ibCzs=C2}z3Y0U^TBB=bxm=o8*Y^R z-qvoLQT#@vH}6Av96anHR1A- zkI0A96Cq&AB(&YF=%&+y`rYCv>~p$^rkr$XF>@*kELfZ_r%WRq>%j!Jv~6)nJE<#Y zAdb;7W5p{fV~xifdyhYd*c1EKdH6k%^-w|A@YJC~wYj^)0NFg99Hvh11-I=8g zyiRW=jlIkO+E5$|HcmcrN>kQ)mg;LVJc8@3+V!pK`GMkJ@w=6)P`e zP5Fk5U(eGZ5#ffZ`hRtYx6?rM@d6|vRAzHUG))Xh9cm??J-o%VU4HS0(yHM2;&&PQ zA2F!PF<_dqf0<%&S?Lm!>84bs1P#5$%(rB}l#`dvY|K8RN1ju@Y1H%-&ULS1`Sum) zIp8!Kp=4Q4m0!XTP(VJ1L%A)NwRIB^_|mtAAzf~jf%|CKfzUhU*ogHzWWXZ9U{&Yg@DhsWLmLYkgPkzT%6%z=}|GRf%Zz6bPCN3^c zMM=5doEje=Us-u*o%Dy__oOAi6KT{?VYnr5V=-?{eU<|L_H}~|X746y z*4v9@YYN@#hSGSqVv1FC*I~4|_k8f?D(A3!vZx+1ou+kzQtA7WRNTvv!1({20zI*h z@cW|8X=2~}!Rsb1*VlA9@@e@WGz?@6SJ)T2e^!pj6W6@ter0oAuS#}Nba_*##;S5a zjNYDAvRofYLcg7T606$&cw^r2AuWW~effE&>xIjbm!pWPd^AlL_JuqVA=c=)t5Lf@ znO*>We-x0$IH3Q9fIPZXUijgG0tU`uLEG+;Dm;?K?Ce1W_%EFkSk2e6t$|*ZaHLF$ zud0oWjR?B?8N0i2=Z3FFWD;Lac*s`6lN zi@L)?pA>!~PzUn0|4}Qkd2-Lu+Mi7KTm%D$5T!?^ZC`R|-a&vP>Pz^3*x#u~rm%)r zV1k~14grBjzk;FD7IW6@n*{~H$Nr>MM>mqlyFCr0hiZQH!qk%SeHleX0Qf8;&2q=1 zUI;UY)R*DlOS)!0`@I-NX^WA!M@B}ze#P+gynRYs{a@{;O2c+Tf&Pq^llP*-9*6a1 zK6|2P>5{_*XSS~i2;hgA^NfN2X+n8TPD{&pd9hiIC!%<82%hX8+jcC5!x31o*Y6Z; z3rV3?9D5z&;{rBt_@HWVBtW4HYh8st`9q=0P-76wm-K1AvpJ70)zQZ4o4b;9P|1aR zZq~C+QVF&>*mUIZEE1CGJ9v#}AvY}kc>;b=g~-A1(;}HjjIOPyHj6Vkuy|!W)4e_) zMEiGTDoa>~P5}}gjso=5lt^mxi%aTjthylt;{bw@gZ=yLQcg|gZpvh7xAUc~K~G&y z1ThXy+$9oVV{k8lN`zPo=XBfIk}z9d|zkxk6_ z((U`uq4*d{E4W@m#zo*{kL<> z`QyNaGHZ8Izx|Tw+i8*YW?gF6i&I+bV&xJ>eO_;;^Z2N~a~jbS%M!(iG3?_WKL7d2 z(j6P)0>BU_&B`UE`a0;M%jYeAhkw(RMlBm#UFCw!`ek9JDgFEu$$TwGcd6uM3Be`5 z{}*$Ljv5}5nkfbDcj(8k2@P#elZ}$o z6f|og%jDJ`hnv1(K4+aAVqV`tJ;m#ROEQFW_h~vhFC%s3wm)FUEqfpL${5z;{)CZV zp#r$^OcmSjMZlCAr01vhYy9Fy1*VH#dWb9Nk+%11c6Ex=KJ%R#Wb}>d7*35SE1`)L z=mu|vOb0aw8P3roeYo~(E?;nG@Uj<|(Ee@Wy=*5yfwDt=zd2o8Rq2~#$k?dhz^{geT&|c0?xzS%^;xu8{LJVQXP)b{oi22 zbb|i}*pLxIAUQ=X*ye6E?;m(uETLqsh=4ik;d)@{_AO&~pHWwk?*!_j)l6+mSlUet z3Ayjhl{<;Pr(x$b+d`8Nd|9&k)ywUXW$L4WDlF0XWF|b3^d;%}j*hu~Lv+Kbuk1td zB|KkTj2;P$x^ooU+;m^PF?aP=Jv8KbunyyV{YU&FcfYkdp{G7e4x;nf2o#_Kmm;+e z*zUEE@am@Ci()W%V6N1;5U(vrKR?`Euer%67p*+CG$iG=fW(=o)p+^K_Yza)^0ans z;ud55kFu(u66oEM&+u$JvCdp}O&{!8elyqMS6Rix0arFXpw=>Xc6FN=8Q{%%iQ)bN zTFwwt?J@6K0#Ne|%L4>5>yUBv%9{U`Zap+SvZNiyw26(rg~l~cF3%1seC zKOQluQt{^g#Sz~BFB~EN>^GpD7(p1Z`7;pZnzTZIeMy~I5e)Vhud7hyWJEhw##G+f zKxHdry1BoqOQIZ|qf}4SV2Z%5v0p4E58M+tv(cI!_a&|Oa+N7;MY$lAAs&NwE*(vH zsLpYl^{4Rs7L(>V^PDo|^X4SqUj?I&Z=s4dd=gSbxUB1(x-gPQuwm3}Rw`e{A;DZMAMY)-dtnThS{8T)FaszT~`tRp9 zFU#T&F)>-<%gs}>zA+bG(@MLVPq%y>`PPw`v(`5zmpQbXUx05!Ao1@a-JYyFTY?x# z=hq}kCH|E7y%dw<-#@W6H`g3-Mp|500C0xvo)>!z^Ut0=1Iz+X1@z!-?z@-wY3r%G z5~x?agOlyq;V~hfdW3cbe|gSVg=;XMGtn>UUiwT|h62V+w$qJ1zxGHlk8wd4@RUb; zF#f}&UwZVh>E%7ADV2F>uNyQQQ= zdMN2;=uQV18tI&wbEEh?@B86=IlnW%`FPh}d&RY`z4qE*@M>3tcil2eUCr;QYoT2h zcPe1RJ45L9hR!U?zpDd!WVVmH{Wcn{?aJrbGBR=onJ3Co(dLYQAXXE59td%Jwe$(F z4xgB)6BFuny3f1(#$;Ky&Uy3J(@km!Pi_Cor$!V$ym)K*c(JFG<|D2w9$!cMwwI0Frrf?U1GQ;7 zDvUf2$gsEK+54JHsKOa?>#^V=hmxYw%EZv;5RcE(1OsT>c%YNC5MpEe|15RXwfPRE zaG{vATQ7n}>u)q$a=4$lCf121!j!Rv#p3Iz@XhI~8T(Ux^3D)6=O5G#aif0<|K}j$wY$mS3U>V#8#!D|AK5-_KJPFB4urd>k)@aJql7iDFEnSI#9bqP-i@ zG*eTtgl_oKXU0MhCyC$^qU>*5d2*G;L;O(WS0xwP;%NUzm*MY%7HXMKh(|Q{rk&ml zE=tuaceRM4Q#I)MzNZ^6XBZFEc}x1Yzht$R@0Hw5a2-h)86Pco(0s-4Ycp55W_Lwa zDy8{;wd90EL1TYFj0H}6b^=ZYt2N7=``#f0q1PWB@FRmAucuvS46E?M{>=uYcRDL> zq(7|l%9kV!C%$R_L~XUnWwYZ@01*DYr!TJcU;E~zS81Ib898)uoHMXV4yafJ>decm zXMo&rw70i+dOC?0=<6$}6;rHR{cCB7xqElKm4ce-v$$f(U_=#4t~#FI@$W0vhcwP z!<7ZcG}-0f8lrOX*d5L*`?OhnnJ;%?a?dD}MbrEI$OfL=x{+hDznVjU&vq_LYh`Zj zIM%6qxsmeUBK8q(W5&&q7VWisHm5^KO>^_3_;Wm_*47_vS}~S^5phCkGf@<+C8+$C z63O@Cow_P*cT*oZ@U-1g5{-3EQe;VVV6C{D8Xt1EHF8~+UMGV2Wtzc246|$mb3znU zp6N-D_;a6e>XBF5m`tB%F0Y(2YX&%vF|@SbUcSxsez_>hC3U>xhIZ8&{^GG!ol{!M zf3W)V=TCf63DwpEP~6B4s$Ib;kI(vPTm#bkuoS%eg~#(DX5L?F|KW}>TD=QbE*4y4 z^hOiY$KbWN4Ldk$INxEIgU#sT8ZwLmqA#3t&w#|r99v+#`D)p3Ny%vEI+ueEda~7U zNy#5_&Ry`;p;Lr$G3xnEA)%`vU3+t|PhTT4`9&({lk$c$1^t>Ml`x^INnE<{#cT|x zsygs`tS!qq~)&d4>roH`V)uKW3z!=z#gVke!#?exGrq?%g3?3;$)tgDH6*JhUFzhqa(7DvWBcp@Yb<77MU7P;uT60I z+t60LA=QAkrd4`wRdmUs_}odKmWs#WgsJSGb!{I74fs|-O8u>(_fj{Pj(wllKkOm^ zE#|P`eK6hDa!c$m;R0ts`#4W_6uYJkxoy;giLzenQLrzapMhwEXXm41l79+NIlX6}~ zudgCK587R(j~ZAb&*v`ch<(gvJWM3NEIK-;PklH{^u0yW2Gn=}pL}&cZwB}MS4@~T zSMaXrglcaF^g5LO9u*mHRLAhueWbVZhrQDgnlUaHNnRxC`gC&-SQpvI))oauFVY|6bnjXIvQp1pZ zxPswny>A=d$I}C!SpB4&+I46iVdsD>AM~><#lW6=Rv~P$Or$3Q9~7is1e&Cy>w5YS%aCO!oB2?1l&Y3JTZ!w4caRy=FI_zj+(Sy@5-6WRr;6+LRUmb%uN{6d z(7P@mXNU8PW_D*1DZbs6liF9YA$jy>x2Dp0x{9fypwnFN;AF3vRMKmalc4P`_?>Wr zaQ)U?z3~%G#b@nzZEEcoUC#PQsd^c_k!@i`X1W6(Tq7fkiIYyW=So=p%h~b^Uk2vV zSbMZPR0dX2Y~j|h+aY=PEi}EBvzHpmBurFT4(Y^p#xShKZ(5;2qhDuUkoW7fyH0m7cUmDsINv`*~#>}I~T_Fz@UM49AK%PJwn(|MkTfb|ae znZs23FS^PCYpsT#*27zYzVA~p*kgjZ@@370NGqEZuM?+YtIdQn>o>J#FJ(M3M{*F1#=S11SxVe9YVtXOA`{kv}uf_^6GZqv!S|6$c7X$fouq)#2dU0MZ zKh*}YsU&1THgkZ9rMB9u+^WsU-~{Frr0S7@U^ICKdm1Q^VZ8rA&Jt*`Cmr5(%>B!> z|HRR*Y|5ofr;_GfP=r!vMRC~l2|ebCf(Q8BxO|kD*Y5citG@fzmrw7=YYj$*e^||Y z47IA*WZ_{7WmcGiy+70Ou8|4M1x^(xLnTxkIPdjiOpwNL0G(!u{V0x5mJZxcA)R3-;U^5 zFx*U$gm}B!o_E*|@+NFmdvs&AE$5~SSZK=~-Ol7HZBBS>Yy@PXA^FybUp6*6cFlLX z6ZhW{YHwHB?aj?p8);4A`T4bzlEN9N5|VDeRN@kLEHBbAaF6W!&$LLZZohI4w#1-M z#Sb0+SaI}r!26Yl%qKM5we3zaQHXx!BeURQGp!*@#7$F;35%N7`?Gb{I@%Sflq$6J zv=C1zyT<4?r?)WoyNf{ReSDPBg(rNWE>Kz5^!f=aQyXfLySGo`OX}J>*I;j_%PiQn^+-dn-AEo zz@1mY)JoxvGXAi2e{`P(FR`60RK;^o2XdBeSRt&#r67jgz^99KDyu78SllQ2F?BQ^ zd{n;`7?9f*Hdj_Vw6C`TTdnjKS{C3s`PDGtiC(+E{nmT8Smnz%q1uIp({_AP<$wTz zw-pPK$uaia*iFbbZjHU#e(Jt{L;3-tFuw?Pa*!(Y=w!H@OG&KS<)}N=%dpmX#(3`d zXHa>fIOKd|Uh}#v6v|3}-WUu!Tpm8?UESX5hQa0=JNwLU(AyX6tdkgVj}% zaj<&l`No?g2AyA_8_Vbv>f>Wbotx*&_Bn6MnexI-;bJw2)GtV;zK1ie9VYZ@w4|)m zF8t2+c|6^mJIeGXFVRwOmeN=0Uf%UDW5_K@+ucvXZ%0Q5e;!}-r}6m^A4;?E?8B+> zuF#&QROuYik&P`7o!vOLRUY-mR50tz#iBc5w!ePUb&kaF0U@ML%54XdjD2x-`sNIA zT?QI;=Vh-#58NUlSYOqCqje~Syu7MasKsMv{=`8$Mz{V11~c!*=uo(5fx#RV^J8-k z2U|#8+_=r#vpP~|%g0dmQc=F#O6_9p>?lgj_G0hTBkS`q6`T4}t(Jg7t+*P9R-sP0 zL3qSsp2M8@rn%kGrub11>obS-=-{Yw%SLh?NBiTm2FlcXqOg6%x&O!+ok!$74%JL- zer%sO_)GF?>lA+=mdIg^tj0qv_IK33sCt1**|Vuci3L_a;+0 z)_V0%pkRHC6a0?Zd;(<&(J1$8+w=1UrH$^Vc&oU;m_y8|ezXPW(@l5f-}$>=>0H*< zApP9|VUwP*xf->ti;P_wwkdoP0ri}Hn4t5&nG=vUieaIWXk zHivbGz4c?1u!|j^=5n7pCoDLd%f*ItE3dl@-Ov2&v!zbQ0B2#s*h@ z;!~P?CL`09Z)rt#vTPb`#~=-E{gKN{o5B@T`BU%xR!VJ>&bN7zy%tA;7q~;I`o^(O zxH8D6BEzH{_BkO^r_psb-bY!H5V2VCm=XUuTDrk^g>QDTOWAiEx?`Aacw1-~W?Y`I zB16u>>|NT&^_&UR(8-z@CmxMo%-(ig11TN@WG@f>vML^C5Ji($&{VL4+jNA=i-lVh zLKvt!&$ywF`fK9)wKduYm#+a$0kWX2)Y{x6SPbLYEbc(F9#RmR{YBVCJ38s3P!!@Q z#pO7R>aWzGnH}Pi+edWhZ5CFXXt?Wx@Z-tFMVMofi>sbO`523aEfAA!u5yS}g@Sy} zqb=|d{rg(bJ0;6sz-X0JZ?mJVz!F|T{=h^6o5h_^fu#CVuB{dM^mStKArmnjmXOqP zgbnPhkNarxJO4nxYy87m=&$2Am*2y2rFrG3wO-N!O7T@eOJ3;5SDHin{?2Pwe^c@ZrRn^w9A~okv5#Cwyff02RZmjPn^z9{t!J@gg*V5zH{yD<<8?T( zx65|89BbLpbmJNInD;J#n_ia}4$ZcP@5J`$(%NPe+Z~R4N_7OGG+W38*9HcF zJ@!?h9A1@v9j$QKUd`FF3MWk4^0l|2e6Cwf?~!zvE(O#JGO}&7$|i2#bu6b?&(kR98DcF8-m_X;6H zb^R{S#iH~Bwa5q}oo^xC5GQ*Z;(5LlCAB-p-oZ?|3tlJ0PiUZzEN z;Gj@n-z#3K0o6d~`d#e4g>lI+orDE9c{pS`Lf2ZQ&mC))v(SCk_2vV7awm(^AAnWb z_3OoYbqG%ifR%_-Q4Bw--kM{%!y0|6`pCKev6_R3OV!r4XdhpA!}kK5wd{GAyQwK! z@@P8JdoeF3WwOS_#*Q;S&h-O_#Ef0T#yC3|tEhTJ@Ahjsgx_W2kb8=I>(z2yNy#cp zd)|}?zvh7)Z_QXIWw*JNHTN%OYs6|cu(33Y!EN3b*adSvsOsKYAMo&@iHZ1AN1*iI zmw-O^mpiCu?RW>3h0w4vcIJ8O(7w~hY3;GNPEb^}nw4+E>eUu|q*Z>Ha}N-*Pe2^F zvZjb@_q&;%DhEd2x88vAj2M;Nxu_#)GYWg4EmgWH7f?%yAp#P-<*&;bb&XjT^#|cd zO^^G)?I0grqVRl4+9g8Ft1azP*^XOCyo~N=^LOUleUBE z@kM%M&IQy^-KU*?25beoES|sSAe$o4`?Z6|ZMJEZ_@-B4`E2fiXch_8vkdueLYriN z+Kg{yIW3aK5u8^*J&=pjHGnz$=mrj>YI~72yX7Wavjr~15V=>6R#tD3Bd1I$k(AFy zIs7BKLz3|C)83O?@d$4KLDMj~b zx*0qMM$A7$X2y@4NvFFJKBXA#yu2cUp#k|+GhW`kTBfG|ebc38>orm*uRLei$8evf zZOD)J&GIIJ!^#9>#02Jv9n>zwTgHgx(=s62pvz;u*=E11&HX5_dF4V@+AE<>8y?$l zMdT>$Kyw8oJD>BXGq;bs;1FFnivy!%&%5k4rq8!XKtHF+r2lNbTGKUguv<0-t9=OaQG4)LQaubaUU^rYf>M(X#o!FQ z!2x%|=e5+;(9gAryv#`Cj`m-9Tm$*I`CgRY0I6(jc2_Vzs}p{6zXLnG3Ys96k)Q}x z1#lM|&@=Sn3Ii;mfX%)0rM>z*M*eoBDUTdb?epZXQRJEeQ?@WJaR2t%P6?7{Zk#^& zgaB2Ph_#ezQlfKWcy_c%%|s!Vb_LXWsRccECxjS@!XVo}Hob?EZoRV78GN_$bZ=$Y zwrtqcYF{Jrg>;%+B9<5=U2>`6PVA|>?;xVRtg75E=p}6u#PCWNohrRS(wmn99xmOg z&-GXT!JJbH-;ZGmE6T}+_jrsAQFxI96{nZ)9WE`K4Yj;ayZYpNasNHnEjPzHVJBet zw14;JNWTr@=24Ec>T%l&ZFA_!w8+VO4`{-X9^4U7gCNx-!s3Oaoz=(H#USXWije;=JMUI&vwi^v#ta3xHdkZzam%+tV( zy%jzoC!^(KUyW2iP(O8V|JBsx!f#;^w`X-E$jAJ$dCPF&YE_x3ilYm(>SN|T$@{PP%a3dKR&1@x zptHV77Xx}sap`mIca+6)UQK>H;!h`#X z%MvuOlvhvO%5av&8@DG)_Pn{kUNhz@F1hj-YVvdXa`bCq>us_o_9H*1i)_3BIdI@4 z+}oAO!s#+(p=N>B{J;(Nz_DbOPKFo0$I-t3ZLY@R|Aj!$XS&1{ttKB>vJ#!`nu~Fas>tF`ILtmTM^*RZE znBm}Kx7W?fAx7PAejbH7aDO^NGjyu7cW2J`yNK_j$*_$xC3U_bPmXke9>4UZQPPTw zw~%LV_}o6BxklV|TkhD&>IsCveiX10qcYS=^|RR2OU#xj9jBe}bI1~}yXxsOjp@PJ zzn%aUiI;9sK23dHg(Z@~b_OHwHTOfAeFSVDimsb-ie-vKTb}7hCp;Rk$m$CA@*N-E z4t~JTrO~1X$0ifWo(KRQa98fqpz>dbuj?Mw6?y39K`J->6^D?IgxzNG3g?y(F4S!= zvt}PH+;$YnzQ)YmXyfRD7hRU9lnF0B7JI&)iE~-dOV*44g6q>>p!l0ak z1n(voo@W{-YpyAez0Le|vYezCCMkD)z$kl3CJGSa4I7$^+kC3ES?sgW#6cT^z0&(< zQHDh9YZRDrt&fsn6?^KK5voqr&d+&ioXA5wD(5wiL}EcKg~QQ&AK z*fdi+1sNy;Rw(CQ(tnbJ8kDx=@Foz5H%l3`)<@EZ_X~(xO@e$xe_8!`;bT_$uTLy= zTJBQ?iy11iYv!?p4_ZADVeEfMCW@^Eg3RwOC!V@arXJD+v!Uz%V@U?eQ2^uuYco+| zf&!kaL4)69t^4%7)ayBRF#NH-L`fyU4|pZEd)vUSZ9piZ17LW-SLT5$6#;kRH8_el z@d$bECN9?sl&lu~*jyT47g_ zE!A+S7Vqo92h+Ua>mY-oOXug{q?QL03}MzjsEaVpwSVOb7$jg@b0pyNrBA%IxK1j{#;P8SMp*SG1CKjYMO#`KqPYw-c5J?p*7) z?!$&kn{c#byTz@2BsnniZ|?*Gr^e#-){8-c?ir{pUTZ$~=speWT!h&s>D$k|_bYk6 zUgL*oJ zy|GrNeBGFn&AvqQo ztHAA1?mq?e1wu#)Y090UeH>0dA1iZ4Kbj$Q)6-p)qw;?`L&o;pfTz79Eq=!oIN0n` zcv%a9Nt)(1R6;Z%_X3n!dEgyMQ_MoWEOqkY_IJcoO_~78FHNNO?q96b<#^;EA{3g- z#R6QSfCFYM>oRoaa!PuI`=1d5D{SX(J9!@WOJXw(|9s>9*^mp+4?19_P4wf%CWZah zgDc7NGEm$yvl-lvDF z<9d7cJ{hz8S!roa8KD=RZpZsia*+$+-!c16=zc5SObUq1ccuX?4nF#mJ4w&jqKcrc z*{!QiN#P|W{wyp_{0)0L=0OsFX7IZ6gK6Wb``Y9n1F3&7gpB!RiP;~7WLY)yKAm0{ z!CE@aR5}1l!?|^|K#rLX1*2{N)<8u*aS9SVlWQSr#uf>wxLKwXnHgb-?HiSa;*-@-py$Tak>szbto$?lx7wrZF=R z8b1M89Qa9lT}Zlj^ZFtss+ZMZ#(3)8RK)9=@Ux|5C2;~L;2Z4!p+T}&&z&6np0<0a z``S-Cp;FK|vGoHBNT73$g(9AZ=wYIXfqz>92Ec|+pD!^m!};>Bo^b(i821U2O@kS5 z3HJSfU<&lC@@2-MeNXate30tZOH-1(*^<3*6_G}FgV5_hBU^X-g`*3b7fI&DY`9zo ze=%~!)Ka5t<~hCMw2yFV#SGKJ!I&h#m4g-o|Gjd$iY8%-_`pU(f}bllEt5RrgK!E} zlFGe&#ji2_V!M_FPR?Oc1qG~r=p_SV~Fx( z{<0<<@{{EA1&1vE@$wC+Wx4$&9pl2c3*}GRJ?QVG|2H6i+ifv>yh)tjx{!YqJB~ zstgX7g7peQW)KHW8L~jbRsHjKn=bWx7DZ>>MQ0I)wMoqKDS=9v(6%nY*#_SHpKl!V zB37pVLO$_#b$-j9aoB z@1WfJ7=mY`y&j1nnEkjtvzS%wm`;9`%kkKT=mQ6bgd3f-lHYMb|f$GqqCAJk+zWcw{Rb!AB!L97lU)}$u z=-=11cg`f1{P10nE7*E?EL+p|v%d>Zxo!1>ypJR~W2;JH;!+R?e09?CfZHHdmRQFZ zfSUnAPy}uG&8)KL&5K4NKGp!6rN|*jcKQ@{RQvJq6}siNnR;t7=1JUh4|ye6!1HOY zV{3fSf5eyR$J4ToM0q!GAtR%SNmm|}JfO@>l7sJ_Ir_Pi+*f@L=A=jdjKd0^u}@Pe zjsX9*Rz|8{jFO0Y9ug9IAV%^+0A#S`ivI^YX#|i@m{P(!1|85FMyEv|e>`80)}{fQ zMk8+DO5=YwBryqY@)aCud&##|${>?7=o#_he~p;~{h~Qe!+dk0ITVFjZRZ&~wMU8< z4qs`G>sgoQUodk;h|TUpQ22XFqc!nH*}0lMzv1x*J0?q|q4 zCoV4-+3!u1YHrNo&Zp+21}DEon={bWO*;XMI}deRn2ecy8c3`b-w=4P#1&$kkRPWA zIO~urYE@`cul>b{`Pqbk%o51Q^U~RHpySl$z84^ch3Yra5F0uw(Hf(`J7yA|uF>l$ znrr^qZV&EBd)O79l@w3_{6i_mfQg5mWa-n1!(!-UG`Y-~JDq8))mx`Bt2hHOx3vs z>bQG3cNu-02OHwEcIGF$(X1*!L5x{As&i3T&vOUuM>gxNn(=OEdg}HMd_y6?MMb-@ z5+>Y5#{ld%^b+}$b^7_q&Z>$-iLN84|>z&R?k z#p9d^JI$2mXA&+!sqD6z7JI;R%;3pi^<0oF}l{bqb26u5%YIOUpANb5_J!Uwp@!{MleALVlLh(6$=WQC&*Z;PGvjxt zDczKQ!?Ri%0DQzIOvB@$y1gaGa{%=ja9=*KygRf;GF|D0?APxkC~EbSU1H%aXMg7h zim^`T@&8x${wXy+n*ix+HZ7LmbNGrc5Z<-Z>>+l2py3KAj`1?|Zr&nD(?SyUu8mr1 zxG$BDosn|9Zd_<(v_UDxrEcn7+cNK+RRc-){=-^DDfI;^*P8mzGuPH`DN1VQTo>EM zMz~k!gM1SH!BPVLcr!;k=*)r5F~?{VZ)t31KvziG#lUhZ?}1d+{|$t5%XsE0kE9Us zk&O}It9|mW-?Y9d}p-Xi6 zoc&E?BVTzPK0&0?Lcj?p+;T-TAM%f2H@E3l-Ut#gPE1C$pS>KrgN;qRqpQ+Y%Pv9sICnQs6e{kpdI!n{D{8Yw0AbiHfY zKbG5KSRCBLm#i0TQBE7l;pAR=JBn<$9-*0vL#aKZde>%=qkgd z&AdM0HOqaRp@QJ7kE)jM714Y@Q6R;h(~Dwhiv$2h=fmY2wC};6 zs6TN$?YBN*N%NpHHL`r(5+h%@z} zilvZtvQAnoF@@@pm~t^{}#AB;&Cz5>$SUm0KZgamwPn22w0Ii{1*H-)WHl%0D2(I0#L-j zPmop6KT+OOJ+j{;8-GO==eH4c7UbPZXAfJ6<7=6Dcw}1NuXvsAsJ03%+6Oz-pWNR6 zuS}a1*D+O;7~t8eK`2*{#qPF{0kd^$UmIeT7ri<&6nl{8%_tJ}8m>fl1r#fCX-B<* z9(o#tep|vladlp6S6S;)WDZ_b8t$XnCOWt{`eq-3#h2=n?e*FG;HOV*IIfTuEW|T( z^FzqVv`VdiJ|-qxown_PnfD?xt@+r&gxdPQ!=h@xGz0kXbHLRuMJV)CiQkr~zky6S z7qH%Y|8!f{DBBOBKaIL(;&h+~Y+3T~nD-n@?)r$IZo5{6(-=N>Xp?Zl@;buVH{Q!3 z&I#o7_4&Ov{8pE63AnlFeErn8vX4`~|rwVq;V7Cuu0TO}{? zjk&VHJxwSc%^g3L0NOF7r3zn=u;Ck0t@5GsKoX@j(A|fIU zkDDM4|4UCp)O`s$AVQ5UDXuCP60qb(@8s{r?AF)S-@%o{KNIco>RzaBGZ2~AYj74T!q2Ayt&v{Sy}8wyQrJxr-0+L+vH=W z$tkKX3i`S79&395GBrAT^1q zwv}@EpAhGjl`;^L2 zKCMg)nd5GRxZ++xcViWxw4-ibPCpA<_!sSlb|+Z7T@=(Pn;mGEwR$QX6nCzKizwg) zDpPmIH(jK>&uTD?U8;Em*~T7`fzv$UdOJxqNU>HY)U(0xdE1JZN8-1yYox(4OG_iU z4M1^6$8Iba#*@bK2JBM3MM0M%Lr`i8DZu0zK7Vm0yexvH#Wn#_lqBzV{xU`HwHORL zp3q_NdNYXkp;>^a`8HX11(%1pyd{7P?pOLbW>3s9dSOvdT^@YB@FEuPmGti6#pm4-E&Axy=AbdjZKi*bHfQUTN;+W5qUR1*7%L@DJGNYGVDHY} z=6&)rbTyM5%qt{Bvu(MrPB>J=?^dnHEH2$D2NuJNii*C~3UCyZmX=N`fK&x9z1CWA z;Pe6_S-Zi2GA1C`Kv#^#J{ev2jxtL=R6!g|dstT}Oouo;J%V6{XH>R{As*e$q%*s} zWxR=!%@+d71(&08>p{og{ z=j$y@q3BbjfeM*ps_hSLqJ*3da^e`K5u5y}HMo+g?GOocj6cI^i#}$FD@?+O5(q7? zC-IhNo5FFr{1<+F*AVaTnwnQk2YF%ia}j}&p-;8l<@Kr=v7AT8rC&!rydgeBRW_XM zOwD<%XOdpX$#-a!!P5%UI0kJ|VqvI0dEH$Rp{yo9&=j6vL2@tlYI|z_FaQ9mpqDuJ z8}i=jt_0aC(WW#TSlbAiCsYU_msd~#0LkROsF%0s=aFZZ z_}->P(Gf#z_LuiUuQmXc)V-BEf1xuVja05dHZV96e204SemGfpbh;%%Xet$G`Iv|& zce>?{tb^@n*38vOdhRBxNMKVKASc+I)LlsOdqTPCV0x=9VZIEXpH~Hdlj;5^QyLk2 zjClYScxB(ATGa6)cVPt_<#DbBEvj`k51RPFhg~W$RK^IN2X49;2d8g)yKm27mQugI zTghmBt72qA&@^1PF5DY3^z>q}BkK13zqIt4f^5^6+){cmC+gN_;Yj0EM8JF%9tuf? zq2Z#s+uzj@x9JV&nu=w^`m(<_8@N*9ynp|Nd|Cb3YMl$D&L!3=*4fH;2Yt(E2dG(~ zy|l5WoPQ z5BzRLqvYBA!ABG_9;iE=Q3HYgQBNBBYKw7dG-WY8J;Mxc-m?Oz^m&p0vX(RXHj#N) zVn%+X(t!t}(q>cguF_!PG8RpF@i@*_Ov4Zxqybn`Cjvz+-{z>S!tz z!?LnpyylctwGPmOYvKuOa~-a3WReOkx?9-L-`mHY210=^v7L49}&oWESLYen~_f5t&+TrYshyZ}2 zfo|iTN^wsr1tnlZ2m4>}CUj#t`fMlk@jzXEF#SJlUGB|=>bG3Gykw8#poW?v=u?y7~_? zJe4RLO0$9Q*tNE$4xI@nP+VwOxFBcN(=TJI=j0@~9Y7X&=Bthq?>^v^zx8*D>cMZW zfZdcQ@ZSM5=JZbs@}nG&u7&m1!7`@}Eefh%WR-Kt9ogiT=?{HX7Ao|lh!09vpNs9P z{T^dLM}VO@fU;g}1B$zQIqOORHP)_7t|~`KMOvMQ=zVOc;{b+6KFd2)V&ZX#-xWe{AM6s|rYP$7O;RB5@`RP(e{bIls(?ey9ufN4Q+yM0YO`A;#>0CV5Rd_XZnY z;+>fGYs+0>~MzLv=LRBtuk1igxKl6!lhnjj9AX~J|__rspmglJ2ca#nM; z)y3o`c;QXnkGEc+j1I=`0Q%{2O3=QitMVP+UAq{So9jv~%cl*U$ROSU&R{i2YlhdBGuaWd<^3WQUN40|J7;Fr3&=iCeX$r4E@mkwerTuO9a%bNIYArc`@f?ag^5P48bc<#DlG>xSVWno!8qLHw29$E9Wz z=cM7{V>Y@~u68?w30rgj^-N{R%=D8gDc+W$Xik2FbjpFjrssVmK*JQ5O6%3(fQQfq z%x|#T?)`hz{%?DSmc<{u7_K<8xnL^oMB}MZM-94Q!SeD-bTtU}p9GF209fuAP6o1& zV$?B%n?8t7@=BpXZFMFDYdMG|O4}N^LVPjU+#glzeF^b>#%GPUvXC@F&zG+{zWHV) z!=4p2sI8!JP3|XPmH7T7OQn7tPj>6+!*ifdU07Zb0hn36+Tm36ewB@izUvX~kUg))bjS7LHDVi6K)ZhpPY>2$cUxk6hFq z{TcZ0V~48lv=wYSLSYx>Ngip3`=BB9$|kC}`7j=<&~HXWk`Qw$KmTA_ zW#s059%`w|GBl2%;oyH+!yiryx8UbT0}AS`JEpMIpToKKa4azyZ*~oj2|aW~IwwpP zkd{d7(tR?9vn!6~u}`zp8J(Q1e?wTFwZC_cTxTNYjmq5*19OXuIlqJ|rzRn<2>2)v zTq2gyrAS82N{rjWuU0||?n4Ij*4*=0sjGB-X@!3AJ!0e*yZ!|ZH}-*4KDS_I;$)8M z-3qOrU!RM!^~T0@93?|#lrdYgs$X8uKBSlY~Bw>bUQ+d0ocsH%1|-!JErVz1*w{hZsc6dJxEn(;ez{JDEKCheFWx#?Db@aYO;{SgFC({S;+Ai6|jyD z8YwCg^u}<-KPicP9`M|rPt@Cv$#x>0|5M;Vo{>5Wq24R~%IAwljwQe$nmCJM)Yoqr zJX$g`pRBBcWsO#v<|B+bX;}>udarrb?ZV>M)>MHO69SKh68F_0Ba|ZU--q+B`*i(7 z^g}`GbGf!0ViF>hr3rW5qe^13zeW;y1_YqphZu?u9Z&r~?C2sH!bv<0-#e(kvz*2S zXqDdMYk4bdPtf$+XkXV_dHyvTLXa$VD8)mZBA)C>JJwBg#0kS{vCFW_P-QQu`{}o5 zNJt(e3N9#O<_$l5eI!o%nlAA+UhL(;qtb$f;`U6g9bqra1B?nED{CI?n3An-O#g?P z*ykf|z7g{zF@~=CW_o}kQ=7lvb#;d7vD-HiFi-3==WZxU$3FH-L5&#ceft>?clSL5R;ON;@9j+ z1zLq|`EmE@S|4~S(O{@o-l#_g#PLqSTg!HdN;@FFc{e{mx-SgW^>FA)8p)+&=HQB! z?eijN(x!xwho`6S$;cobt*0O0HzH=24%faiVcKKNw9-GQxfRg`hr)HssDt#Kp#!CN z$f{jjI!}eoIaZ44bc$-M-Nx45$V3LbiD3qFgq2_{&u^}1tZW?F+{4@rpdOo;5Zw;e z0^PXGF*v&F@D1%SG_PLB`uh`H{4=%r&L`fanq3<+nT#1R$WdF}kMv5Wv5)rn+9JuL zy7Jw@|2bP+A3DZFov{)zN<>PctcY&CX*%shTj*r|U-biTSXoY;5nnvQAa7Lb69R$w zc2QFdBup1-p2osH;gu?ExA!?94wD@~iFvkGQv9s#BB)st(P~wRj8*uqJ{poobiPqn z|K`y+7ISpJDa4zxzad;D>jl#w`Z?eN=*1lLvSDWt*7jRt`$o&A*8@9u(%rUf(HyZs0ORT6P9yqlI!<(8LsQ`EF%ZMv#XT!1 zVHb5TDakVvaSZq zUwSq`(|6ynGkS;Qi#%((YQ0USyyKdDR#6>%PZdliYMZQ+rpBlXN*?ULU8=~b+Zdkn z^J{6J{ZUY&kIA`cgbxh$t!TiIIg7Go59YnapwPbSm<)mmqX8eC|vKDc07Tiyc6yXRQE%8=UkEdl1?iY=iW+K>3`7VW2*A;vohS-~odK^-~_FtW)>^5BmC zFOAF!uLA;dat2Kco!}2w9^>*QHr{O`)9_He8hkR>}$GuYXpy?`Fc z3R%piHD#%YHp%S;=u=brIr`vh&jR;W=Wc9B=RUQfj4{*69;tBMSw*!Eg(0=^>0D-{ z2Pekp?1BMjWpFO)zp#+UKt!ZM&=3BlB27Udo%2;lNWx*aSFNDz84&78E-1YFpswJ{ z^o)bZr{nuy6JfY9h}D2X2**);jdwg(+**uFW-_}WRuizEHCe`B`0#mbB_7V4u-sRI2*Wm{H zKJ@@ce?tktgb~oYrj?BqdGTBHn^=ZjG$zcA|;w)Feh7JN`!jhsqkoS|wt@W|DmsMvGs4 zCB$?j=oC|Bp$?^!JVV(ESM z+4rvN+Iv%dOj_uA_GW88f49-=Euff0-cD0e^FJw#vGPB?W6>U%UZC*Qyg%^t5PG9B zC;wgr2)J^3pBKPr0y5pSfZ|larL^k)x{8Rxf{3o&FY^B}J}Z*GO>6U>JzqveIEu#8 zopp;8_(#D2PFtUoF^bj8v(mvSa0xAJD&4aI*L-W+c0iR~ca3j9RT))D@&Rr-Sr!_i zV25yBpzCni8qmD&=n!8k;kB5F=fG?~!kC zyq>jw_h{#twRHANgvM0eJ~j9wjI7zRtLXV{GLY?hQHDWjFDx)gUK{=|dwdeR5}{p= zlw|&_Re5YO@0*&+_>#TP&Dibo6ehtpOj>rlDkGzuSGr=8$=21&1X(^@yM5;1BPkS> zGAbWSp3f2H7FqAYrKywYsl_)Jn=>%mK@;GWQd@#=S(J!1x9)b2A{Vx){_gJbh zq_PlRtP6bvrs^=;A2NaHR0UT$)NeeqkTyFy9kI?e{5mQn%Mbjtt-7E4!VU^1^I~K= zw+mzGOmD%lD#7gaF6(VSZq|ON|8+idgP2I#$1@8;`3mJBEXE6|&)G&GunD4rsj1fh zXhW(HR8XEKNMtiluv1A-`24o%q;f^#sf4T#D!608%oo1x&nPeYKl!PRf0Vr{pW9}C zKFR5;P>Ewwzkm=+9X+{WQ+>`d3kx0m=67n|y6R5dlSDxh#@GeD-G9K%(7nr!p52v9 z5+Ym%tmk4|0i_7N7|bVh+<1{(+Tom5kp5k{9LdfRVJJ&euNi2I7Du%{B4d|*M;aK- zsyAcOJbAFrxgP1P_Md~Ymm`&5{U02xZ<0ihe>;)zZ0>o+wGw-M!)*vZh(Q`=ku{T@mHn4=l`%c0`9j@~m6v*(szs#wSBF^(;C9}im zr*}3^w+e@&`WQYh(8Hxu7{ssFnx1WbRA#8W6bvUC92~6gK2vKk`kMk3@&GMJY)?)u za3VFe-snGzThW^Y=9APPK&X1ZD3j8?U0!SoBTK%8@R_y0dS*SLQAt5GuCG=r)2r&- z^Cx`{HBbVtnAtI%Qz!kTC&h+qQ4RD)%^vmsDvN%%Ryqc7<)dhR>Jv9Z z86zkA-YJ!}J$`w-&N-{=JR!{qnCRRVV7ZJ_{lBEl!*O@9i9_(iGOYpCZ}-Nl-YLVN zE$;P`Y6!eLGR*5*(g-4R`{_6s#>m&V!uXEr<8VecXemh~Hr9%|ZXfk`LQgP-Eeh}C zSV(ABScd$O8rKg>hYr&F52i9qHb2l({ushaHlH4H9`YVCHJYbQo-;VT=Bjx6o+)i2N2{DyzJK<8T)5Vi)Kxd0)inUXiXFP89i5ffV&XE;JLG1)s8QqC zt15(A3CFw^f~wq#Sx<+R3e-oJkx22R9Y@vwbk+k?le)q5(C~1fgZHC*$>{atLInpQ>^Jeub3mRQ7*Og|Qa*i=(k zD@WNKKp$9lSr67fwB*_|GQYw9dxVRB&qoXSf3J?uoR~JNWfZ0gO5tjuedn)36PAQn zW!PE0O)4&a9&+oHq;*?&o_!13I$p=CI<==^jwX;Tsi}J)s$b&FJ{{|TDQURtef!HJ z%`xel(o~vmz>INyW0+EkG-}HDXdQpp+W8OL$Jm^M9eI2y2q1tv(W`(~;A!g;IRc(r?=0-UzkPtgFo zYR2XVh=0XQqh&m(Hb(tsK>PRhz`tJY{vpFwC;;Pz&DXG(&rouLRI21C$LN}?tH!LG zj9o;7LQ&yGN_a%{CIW6N{Y6Tq@E8ZeS62yBqr(l#gnu>RuS}eH2Lxx|v@M4oQ17q% zl7U>()>iL%kLlEe&Nm>+^&VdAw^dm70je>v)MFa*&U1g^GrQYi`{`a(jgv~Y`k!v! z#PvUV6MjLc$^2oK#^=QqTp#A&udE!@6|;nv|k2t}z9^#kl7SP(=RQ5kRI}7)|!&euj-IxlPNW zE-#hn+}GTRff*QfDKyg)|4~uuJxzI*{}Y=OAhu&LDeReN|71RVe;++8U;r}boGXWt zC7#+N2P#-=!CT$xgoM?E@osP7A{PS;L196gjAFI4a#qObxU>6ux+$Fa14j~H$$aqd zBekDuK`1$ME_CIC2;TlcS6NR*zcRe@_a*J1#D-aFQcj;MmtE?ggL}5 zanC+ms)v~gCYMJOP`01co812b7WZ z${G{&xLYm-4AHzGH-i|GWjx{> zXTgchoA&{sSmRDogeDpBtrizT)EDlc@FBbXpIqv_-P_%s&Xcs|9bYQ=jS9NFaIEk_ z9%h4%9%bRiPi5zbKt*kjg(*?c2k=vSV=4SfUQyF3V0WCgs^(LnP!N+&z= zb;6z!vC!0#LaZAeSnZs`u8-F}#OdM+#Ep!c?Nh7sCu=4p=$tV@0UHW8?Q~DEa0Wy0 z)6H^p51Wo9r%6U2_Z2yE!Jt5(lo|cuBa8Cz`I|qJ^R=eqV`FE&5StAznlJyIIgl%!0-6b4uKrUK0ah1~5#BHQJ(hU85A(mi{Oke3MYTqt>IG;e@7I+?@ z+hY`F}v-``YDo_PxQf<5oGuD1})!-h=?eGiHbOy1F%F4#pa$T?RPuYL?Z30&ge+PFJ`-P9*v|(*1F39=Ciw1W# zxE*rff`Yw{R!+g&%hi~%t4(p zi9gaN%$9{!R(@L$QH*IJZS8lHm?A29%L*7iSzJQkY5W!&Vv4DeB>GRy0g&`oZ?Fh{ zyV<}mujkmn0TEkII5}fSvzh*$tjN%|ZQ1^Cxm<4TK)>0b8e$7Z((cI+q@UV{gUP|b z$=tHUcUSn0^17_woz*_AHu6OuE<9j~Z?k<h#(ufEMUMONBn| zc{ODRi~461z7!p=|6H%lMU3xk57n9=Ydj?KbI@$L6Bccznva0^M(FaCinKPcR)bLw#s9>DKIvK6vVo8EfFE@ zSmGkc1(3&d2OkI{Y0oB>70@s65mvA-iczHIWQqh<1Cco3z8!wTYiiNDZN5@D!@iTV zWSRQD5M3h;HBD}H%OIyfe4(G$spqd^ z*SF%;|5Mnh2XtPDgRdAE|FojrDhp>Hh=z2$Sv$9A0au%0AeAqLweGhBhjWuKV1wQd z4f{>YQjL46N<%$}9&mvKq8BqEmVSd8L+Y7{=4~b&OU=h>JuOG1xcPixyS2Vp;d4&2 z?$0Yeaw2J8Q!21OjscnmFb*#|d)&nA1$9(04LlUM*rIn##hJQMiI?R)eho}M3sS_YdnYA{1+o(vP;`(KI`{UX18NP?wJha%YTF;d7VwA{qT$7Besn7 zt088^X^2)?lc|;k5q0hh^#?guQ(D!1*GEu?I-5K`qi(>m#D*5_?e9mmc)Ug={QatF zoWjTOcrlkL%kqFq2U>kOyifXyrnRk``iJb%M1z86uV1{3AUm6@Xsn*3sg(^rO=6S_ zJia*ULz#s9*sb*zTj`Kt1jRpl`cp+cYjD*yPZr`LH9a>!k1q=;!!<$aBI|QwfgynX z1_lp$yc4otGfFoDVPH{eYMuh^q{0Y$_$Bgg=fubRXilB@k8S!d`#C>*Iu{L=_V)<) zBPkZ{)jZ&_-u+n$qp{)d+u!o->-ywrclNHit|#zfY(gd8<9YO%zk43)3cbARyqoQy zS@mwb)Zlg~uYi8``{?K>*KR9c4_LE(dtE(D=6;J%Qe_2y=E-=IO_zyYN^0sv<$R4> z)MUqX(n4=7S@GMk#uCd4fGq-SZ2xi&1e#=uoNL(CyeRWI4Eoi-5k#vB1P)Ih4~`cN z!3BZmG&#rnPDUCIs{Ty3t%+Gu0COe>%ZzXRxGcw%rV#f?w&=aHD5jn=hT(o<5(MI| zL}=00<|Bs*h0O6?-!6r@4h+V|@SemW@D5lea%J}>KrU#zwx_67!+~QbZY;i&FZ1rIy2X;$^lWUeH&MSL|;jlGuy?0H{IXpQ{OMm^PM zRRt?`jeT|V8G#TVKk1xnere{LuX)@(_gGq$gl@s6hq;q85H(9lnSeO8ZGEAz6^3R>@aGZ!|O%moy|8* zi@+@XQaOew0*BN7Kd=mT^UE>Q1)tl~Ep)~Ykx=ETrOp#D9M^B6;pc%;*(BPMxD+*8 zwR(Y~*NfToYxda@{MFsnE6&<7M}TKKg?}7fvV;fm^;4MM85MHRL$9IdWks9swierh z-##nWuQCx{UHZ+>C`@#5FR0*=)uAUmkiS%a1&x~6h`Ep{O%>r?%@Fc9w}hC$W5O(G z(x4hcA<%qh8QV!CiyK-IskJV6WYMZnE&b=te81^1|9ikc=^3N|scStKcJ_mO3=4Af zPT!Q{-~G0q$^$6sXeILauB<@Uq-#H_%Pw!V?LF@&XLRF2A1ammvqf?RPv)g87nypp zPz{J=|?LH-%YVWF^=n9-e5f>h3>zZ*qI6YAp&)k ze60IKV!f+9)%L4i&?EMk(kixx{(AzbExE5$^~smY?-5=YIM!nf0>M8UBLAE|w7B|t zi|*jrSZG7Jf0Fj#r@KKc_9e>H29=ZK2NHGd{7xsincG}OjXn4TJ@8iJa5gcCIp}4n z4>-LAXU4ul9j$}6?d?lS?Kg=Yp_7NCoViNx^VI8K3_6QxFf28BgC|0l(xhZpW{U^H zkc#gre(n5h+*s-Gej4@Sudj?}1aClvJ7pWoauErX8p}zzI%STo2$C>- zkQ{3L<-5#c;%p(HgP~_J8s&xtnDQSfeKNRpS{aGh74TluCkam6uV3I5Q*cfi&!;Ws z6ul$Vl&#obCku{5>6j4!B*;qa5DcbhP`_Q%kQSZ~GTFViw*}qe{o>&yD(H73TRqQJ zjDhvda#*gQf41=N-)(ZplhRzMruTy0%|qQ1n{oH-z=>t$nDv{b5yrl!?q=nIq^{L) z;?}Z{YwG<399MmpsOq!i`ruo*QVLoJlToji$q?0DbiPyA;U3(4KHCPfbh$m6-laHx z6=W7hdmO5Ot z7mc3l_sK*35i@OdSv*79duwfdRboVj%=nJC6QYmw4Pd1RL8#t>;{{q^-b zWBT6EbH-$J-qpg$!;rgy$oJp(8QT#b>sQlscX!Tm+09x{PK?pP8yi;;wDaV4Oqm99 zVOz2xiB2qUwb5rTGo%yfXZ#VoKuw(6Dhcb(o$}cob z(-w>*1ly~0^+t*wYNB75l|m0cMKk|w{qV0uB7(OSwi=tFq7{isoLW-GBUHp!EQ5lk zuBV+FVmZb%YeIadAw#6*OR3Br(;^fM**zYk#}B{n4u@Zl7iZ3^=vjnZtv~c-1!gK; zZkRgvVyRWWJ^A!du1b3UqX9qgccA{*x?5SqfvZCz{e! zU_W=2?kon5{W=57gTKh1#K@EKdo>nd4-MNxb__LjVOxxcHHN~+wQ9HRdaqD@9IsS1 z46=@3-*g$kGq(6!0TZU3lzwfuh<$A~+uF6m3oe-ocGwf{1l|>Kq>l}vu z>4Df_bPL?;j>GK}rpl)3?tGM~d|ps-ha7o8Sg?wZL_IAM;eV;I|8-5tI>CGtDT>j>C@c0Ny?XOjoJ(I%^336Q6y}G-;e&C1udZ$pitqw7+ zJU&*}*YdEGGV43W(5LrZLLQT`-+P=#LfX&pjsu2NKdktl``jEJWn(4RqkbK)yVVwj z)L8Kz%b(^NQKfCJG@r^X5dQ&zA(uZ2=4@nd-tPC<7d&WbYh`{S{>BTJzBWebUk1QS z=`t%V5gq^Mx(W4~wiF6fzur#_doEeo^Np6MX3xF?QB4DdZ)kw};oGE$d=k)K z7h6}>TayWdo$-EpUw#28pJDE{ilJfB!l7vHEHxSr3n-GU8J`gJg9ZfXUDC6=Zy3xa_aBGg`hr&3ccyLKL-{lUeVwQO`|NH*uC z<>RBy%Oi}M+e}DU6e^Q+e5!}z{^eb_`hnk&u|y+hO%jLMTGq4-W8h6pek8d(UP_V+ zvM5i+W({Ax|FK$nDgUZm*y*q(ou;LlWM#@hLEtB!*(RIiBSe%`8RV=L4OWy%J%@ST z+kWj%xvYXjAMNCZ0xePkjy)Xfh&75fQq@Srs@$PZ*Ash~f45<84(pG>@F->0Z$#}P z%WUO@l{Mn*XtDhLw0we*>Lm4Fi~{N=!aeJW#2*&C(ANn40!5Qze?@fdzLaa8@AG) zw7Sdb_wA4VsVPU=Z&!;EOY&eoJFImDGQ1YDFy!CJ6Thgnr2dz7UrPe;`F|su6)uFZ zljKZYMU#ld(XY2??37Ymni-fMg>VdXA4o!& z@Ga_>T{I1n#-o&EA(=og6YK&>`>1=72xOR>D3&`{-{?m$=nze=zjIyc%28N~#n{`i zC%;&Vjl;Xg5(V)PJ4fH?bhAdGJ^gQVLZ zE>a(OfHUYN4kX%~wptxNzm?mFbS*}rp$EeiF<-bqBB$(R&lOTgz4PLyL}P~ zf1%@34n`k7T=yOsv1G{4fsdYz3AyEDjA;As*8&lZ8w%i4?1~>QY8^dttGd~4tUi9y zLP9q!NB_w1{VR5vmc4<;TVkl#%0Vu=(u>5fLQasa1ckN^dF9Enx{>*%&*AfA*{k{{ zuas(|HKCARzirtcXKMPGvx`^3H+TBBVU%A={59hLc)2cqE-fr%%AC zxzqW3FUOMCO#F`*ZEhj+4+|`sj(+7;Ygx(DFMEY((K?uPhfdVP!RJB|o`uWXkM9-I z4qD%+tWIV!hB}AEoWj}tan)|VYf?4(EVy5s6H$Z*1}RMNmMX1>Hf5goG?S`xv0<~S zreU7hr-;0MZST2=KzHyxvOksUK5k=dTexW7$&jGXf`NiXE-622O_~LG3;tm6zu`<@ zcRfMkUPQJmla_2J%f6dNf?Qk7aK&&^W=f&`5q@^Rl-wuRWe}J9N7RkKw?>U!j`eQ6 z-?yS)bZH&i-s^teKk{&o$r5??8;@ug59;z$|0zcsFzRXjD6ur=I->l-j_aMKUR{>Y zy2x=4++x9YZiw{zH@39aKZu>M?QPsCN__kMryf)Ntkfqn)j=a>Z=oVk5_8XGrh*CD zpK>jJ`$tuIeMu@$19_@=KA_dt`Q=bNd4cQsM#-bLpzba6mzxbwBHXM4ROiDZ@=LY+ zP}8ULLaxueQ*>tD;Nbl$UB**9FQ#^J@TVA`TyE0}lb+FUR-v?cg(T`cwa*Y@2%CqB zS3e~h6iA??o(J;x`1mML184nuYl5a0vVrU8MDCrHjYTgrw9Scp_)_N!Sq<(ZQ1HbX zBG6rzydIsgu&=4MjS()A4GOmc#)24A)7CHdkb%xkAF*TC_`bl$31(d$i*Q5EU#+dL z2F%zzB%=9o-R9OeUUm_9xHZI`oG)fGe<)ukY*v-$^IQAs`z2tiZ?M8i-vm+Ya*1T)1esX-K z4la!`7Pz0kC1}zMUe3Nn8^Ro)Ca{F|HU3kh}wy@Qv8FsiA#D^~T7}-23aCJxTFIwJC1_XNH6{aa7cDU_) zaxQn|B=&F6Vx<(?YT3QKri_X6uj;~wFvlfGyM1QS>@ugx=mgV%{qSbETh?mWjCT{i zM(=)(H=I{-Yb`_-cIRp>TWwJrj-P$F*e7=Lr>FekMNhDYUCLG4r^rB1XXRFDS(DxR z+smM<6-l9uZx-jP6Gnn0#rQ&&A)=aML>7$s*Y#|82KBhb*wl|37?>aO;A9O8 zJWna<%Y1vZJ_RrZd+?ScUW-hDm=M@1e-r{R$OKM_M`OJdm>-FZ?zAM!5L^sSien^d z-_C+t#tPimZg=Ei1bQ*JcXMMG5WyC$!@VJO(&-v5XnioOtk<@FHE{F?mk{c5uXp9k zmtJ~&P{~7?vzw8t2XttUwHi2wrN@wsY0aQA$x$9>`V?!64F|l4)ID1=VDDY#`t`Rz zkd$HBlf^dY0y@a*2}MbAh|j4_YI{9HrxT)iH&f2cnjvtqG9QU!%bM-)_V%(&o$qe{ z)BY@9;OXqcGJkdu>;B!cJO5><7p!R=o7KatexHipRDjnJX|rG<>^p3EY~GFvZ`&`0 z@^v>Z9NE|9yfTw^n(4{C4#hgC#0I?_bPqvIe#s$qEAT{Z`S-PMi*by0T&Hgl*2~(C zjC=FviyrbXK+!uvG2DK7+u*D`LNv19;Y#^Ry0tRHhZ_F%vpC+5a=UDp9MU|b*b;@eT`9j^x>F-bq_Md`9=9HqZDd^ z}uFv{hbsoX&+HLx#>1$vIIT3&{5oM}tLOx010h^~N zhJyZ!-ajvON>1Dl5VYzYEzx=|M)}a4PU38o140C!v@t~zfdEvLExh%oix=RpeuCu5 zLV&_@&dZb^0!S-CHXSvZGAjnv4iKnVtAzZ*unT9v$kcSB*4OARRQu*Ai9Q#o>OU{$ zga+2Li`o5VH04=dM9V7|U>%lg z`#~66346JBO&s$}U0uQP&%m5zow}KGRf_;T#nK()*TH~nGNgi5kK&{7=9KAzt|Z6C zOyGF&N!dd7PO|z_cf0du1HV03tqH^x51|A7ecmR;u42qDg_)^JG%~pPmg)u{?r*6H z{HwH+)%^Mg^{e^t0;_offH>CA?G-Z9d`=VeOFU^qBc;BGA=--iCZBguFooJ@Cwk*0 z-H79p=LeT}`BM33*WL{Q_5oZ(VV7BLa?Y&Qy(_F2*v*0sJh7M~Ijm3OioXdEF-Ie4 z9X8KtK-iFE=e^yN9ri*1Gn|$%p7sQXKCZO0)00s#b2d9Yl_eJCVSFx<&<~7CQ^R`k z3kO2_76ejoaHpTjvF|e{>0^mjbjB|f5)@=reH{H7UK43Wt(qbzD0sg9Wou^efA}iT ze^_OF7z{hWUft)@6fi+f+}Z+&PA=^y{1a#FGXyja9;%4rJ|h6VwFvU=>am|LfLw?z zeiiryO-mQiS@8TS9X{_ca=&EUp!93)85!`dgvDBJzd>#BHW&ZL1prz0EPRC*?yY}_ zi|jv(Yq-_pp6X)&RJ{=w0NG1^yNgxNA%NR@zQ2(C!Q*mLhD#--*?EDldaeph#h1wd zTvLyZ$K=)>|5QLbPl!&J6zF>GRM|iTjoT@GNY=K9$C2Ry{z-<(GnDGyRkx*!g9u9`CNS`(+^Q3(MTRa6^Y2u^%)( zF5_ZvJPUYYpiV8L#!V@iW4UBw%g+OQ-0Bw&y(C38PKuf2KV(+@g46iP?-LfL)8hmD z0I8pe4J9RSw!dfZv7Dj_uoXFjIUEQ6@BS9eQ}Kk%Kh%nb#1AW7G$~FN9)gm3f-u6x zas!$qL}bh-$t32u8tLrS)b542M>7{L*H1gO80gcb@srk7VXyAVJle#|T-bbOZa$cQ zE40&US+TNWHgP|sAuE<*Y7dF~z_2eWPl z5#a|#F4BHXZP5LGrC7XXco&#r3ZW8+F;a>_cZa;nb6ZV|^6Sb6v0`L#X`HP;VW@(L z9NgUO@r&33!5luOvtV2#h%y#k&JiuZql9x06wMs%C|yTdxy8H#0Aw@;^06KHw&j_@?jgNi7>Ti7=Yb72CwbolHP{9#-=aW)!6wlv_65b6w%ysrc)OktP( zr|faDdjx@6A6$7UK86yiW#4_##&oWUcu^rU0QxVjW{%dzrVe*Yv)G3xW|YvWJr56w z=CNHYrE7zb*}Au|FGJE<5xP2b+o!CDKN|(bGReaz)g2{ES=byin20`>5UItX+4sU* z4*}!*;}ELG7WoKRtV~S6RjOZ{!iga~e5qedWQ#q(@fJswQeq7oLM1t$LgX2`7(vLxs^k{ng>M!^w>ds z>p}QqM6ipOAV`3Rqr>rYP@IbFJh!DWT%)vR@WIFi^y7^5?y2QqB-uR*+^K&x zLg3ezA<%hdNpjB`U)ns`87;FasD~@$8;tgeDm3e5E(?Faw=&^e-JhRrcQSZE9)&?y zSgW0Ea|@(3^?mY`7{BnDNAO2alX0u}6E>Xgj3K~amVG%TFo8;ZdL?X_MZQA5QY+i20R#*-cm*bV zd_RtPILwLl@e?ukF7HIzckkY*XYj;b7&Ao|gQN;|C|wpmvvF~8%@F?gDn-#YxYzC> zA@*u=wu_C@a@nwvvpb&x%aPAE&pg4v*bSRM>>P!*!VM+VpiV|{0k4hWNcY}s=6E6y z#@kHWF5Rk*?fF+ma?U&BVj#c}0F(}PfgJlt)(alz6Q$GcfCe29eNEV)2js;Kx~#P1 zTPEx#7;uyE&sKY5I9>QMPtO|x{mUuTo1F!IYDH<8`x}Vt1p&^F+$}N7$v|9!=TXgC zwLk%3Aqzm?B;VJQ$8Vt`0^S68gf}q%v)i1FC!kNyJ;Pb)SvQ}i?iztBnK!YSO{wh& z#!*FVE!EYJS4ub4XeM&_bLM(+mnk z1F;Oj$G+0+blh;+82YJ56fr)XpP^P#{dwTvT?La#B(cbT@<zJ4(nu^ zu3F`@1RIA4$F~;Its#-tLnpwXSqm)u{7r%I7dqOOe;>wOoPU-*THE?J7d>x0d$<8l zP%N3P_$=ND@%Ry2iCAd}TO5c|b?K!>-&G;=mXolDxQTlqYwdZU){nXTit5x{HWTua zs-^?G&7}dLpJRM4z`i3$p>MHJcWj{C!De4JCLt)5_?;#sorU791w*0R@0oWQxw+L6 zMW(tyip?-GP~#&!nw||+RlBc7Wb^7Mj~(1grIOs zI>2qV@@jr~)|@*uO;K$Hw-VIMfp zdFjS_)9{O;heNJb{TpTR09>*kSWaORa_`^aIk>0_@k&A3lMY>uAs~b3c7k2`%0&lE z6L&@6(ud2@BHc}vzE@Q(H8)E(b;xp6-bP@NNr#X;r6C3ZmP7)BEn-f&aWCX1{+Uj% z)w7`UcY3`FcU|8b&1@WTt?<(;_9PSK+yvb(J9@@4XG5QenB99nXD9Jn7y28VE$iGX z1%+{^lu-Ek*7nrf?A$ks87v~Hp^)s(a4rm3BLZ2p<-+T$cHmEgH_8bgKd8{sWpos0 zC_x(6ulmT-s_iU*6jcU>5ZM3c*4S`K`W3lAba+#E-+e)DAff&!Sw>-zj=Ofgtvkf^ zX=P=l$nNeqhi1*r3Jr+i?GCd<{+vIfvKj!M5$00AaMUv7XoaaH26)60nFyh3`Y;*0 z5yriR{NeL-n?PD19�_C<{HL$@T*;b~N2!2w!s-&55v2j}>0*S_K4D@O=d6fD;-A zenHX;g3%Sfv{PdWw}?y_A~P%rFfSaFgw5nU?u>uPl&^iQ{53^*8ZAjjG7&>Yc2$oN ztu6jnrG|z94xTiF*7N7jQy0FEjS1#X7#kbAdKmuuUYyaaAc>X>>aB8FMQjj7KaEv_ zoLt#^aU8{G8Eh$E)yP4V?mr9r3}pKGiQsI5tQhSCI=C4ur3otgVMN9E+M`MvfhcL~ zjAm#Eal4S|EBqzpjFZ&Y(#UR{Hp#lR<5*@fKD2UPjH@6U#AaH$wsOhlt5!z81 zFdR{NF3|1FzsBy8JbcVz3(( z|A70+lP3cI1I2mS1liIe`J&iS=Y9=302pKX&>I&`$#zy^uXgY6;Q<5sV#2l0dQpx* zLNDco%FGB|TY_!+2mPbK456(Pz1`PBOV2I}i-a74LPLiJqR#HGxn$r$q#pG+6PF{5 z6Q2U%RZ2|ZE!`6_={ev-o#AxJSTaPqse*Vd11JW+J@^R^?j?|}{~o8TUUJ|2E+&~T zbJj^DD-sV>-{z^g=z(uiLOkl#|4Mkn`E!_3cDP?l7b-C&B?ZVbhY>)krUS+hR^-H$ zW`IT$P@L0-;R#uNiC(Y_>oL$G_*Xp_sbuKKdyT2`RLwn=Qv~B2pXCmjWor!5Fmx(T zd+pEAccra+ zSJ%PtVA+uO&7HAWpl-Leg+m}gk7WAR$TZ?vGs{J++2<_(@t6C<}Qm&jBhZDd9YrtAlN zQEXn}7Dl@~y*}JcnApq$XkMP>2gz$tB3XPyeEdCM1W!P>0r!F--%X9%GC$~pV0&1( zI^T{!C}ryRYWEpnZ!&cr_dkDgMge+4u&e0Ep(Zlhjm<>Ng!7A&napca9TTVZmyx*OuDfWZ4>JzddR7!J%716l-o7`8ep5aF6YU8v=)4%3s zz&&&bs$DEu#)GAnTD|ha?Cdd-Ia>02kyF|QuSMTS;)9~eBpmFFMbCwCZJb`cE)c`3 z{-xct42RL9l)M`j7d@Nz#B=V`v#-cT&&?@t6p9EdO);qzBJ@~E71Z;nQP)DOOC-@& zvbnFY{ucKDyuoMZ{jGaQOqbUH)`pbWjiZoaMaZYLvEvT5|6Y`nM3m@C3C=%VXnBh9%Lu&tI9`SeiCbuKQ7fz_#HCT}Lsp7#F`6Kp z%GVX@Czugav{Q?ng)#Z zq8k*yFQTX#BISc>;@2GA@fzcDi7A{w;1{LFoNeD;XYN0t>SZaY5V2hfPS*qp z_%`1>$$vn&t~$1Fmn$keZy*29oJ;<46 zn@A0sR+5a7RF&kPSrV)klJcXYSaC8S{jr?};WOOQN)S&tt$f1Col&4P_+ko!^uG8V zVU<9B^oqE)YH@jb24+7)S4i6`2`G$++N03O9eKf38f_z=26WfxU{b|C3+AieOr@q! zy0h|u%3b2+{s_H-BF6?Q@TSJ{zs23fb#|)ki=S`QZEbC7tW|Y)OQXsQ2FvRraOcRH z%hzfdVl(D$oH|&OY;s<`Np`|qGBCgaQRNbYfQ&>+%spv)u`SXAh<=JLIhevNdV_B& zbUp#$+a^Ci9XG7E001;T9Mr=ctE`ok6@d3zR$lIWbad_wZFRe|Tb*}?@~E6LewuU_ zz1!S>3SW_)oQH!s2u*f56!6)o*urI7H-#Eo=hGbbQO7|~nWlit3GyoyO{0+6?|6hkyFwEXd0W;08qf z((=8CngJ5gwM!2VTib@1{SA+EPw{ZF>uuVbZ#nQsYl{Hqn)z$My+~4QGAC>u01;f! zvwz#-N|Q|`+tDd`FNhRe$UvRkob)L`;i4~0QwWFhN)*TcDT`%m3Z^KnK&=hs!Yb#Fy3CWri! z1+cVX58-uz6Vm?EAuJ)w>tVYsTXF|-d|9rSk$p13>YmDX7s1iw3FPt%Znrp`*H7}5 z<*x72OzW|j@F13)$%+fEw`_Nb_x?2sX*qr9CwaA}gzpnSKK<1|34-9c6iT5^M~cQnmmIZR}#8L0|IQ!wq-r{?CG znwTtgE4yHw*@KwhN@HL&OJDQE5<@?a9BN*2e6tuOCU+Pv77|g7DHt@AKPE1BNDX#=wR-=h;|6A|A_h5 zF9Obv(r6EZK{Q)ZH?WG8x1wH7QH5L{x6~Ju`|6TE5;Q*U z8Ms|JTsW)O@PRsW<8t_mdjD1?ee#qSj(8x_erR;}q^A^h)bJY_+XV$=8~aJ{4$quG z6oZ-Z&1RW~Kji~159lWVXCJ$hZQ1@aDoz{x=j({cB zUw0{Gvx32!toYu#A~`iGICI~3?WYB#x2x`lM4+`YX3EAsabHf%s>BznYpQ2nHHd~Z znd6UAXs<`4pb$xVq~m1}ZCJ0>&WBmN@{q=mTjolL`IBW7p@w?p$|?MQrF+u(vX<1! zDhEkx#8pg{$?*Jb!azu;$A|Um4mn9h&ayO+q^$>l9YIc$D5+5j*^23 z_lL~TT|JYX=K)Hdo{m;U7hT6QVr~a4s)pek(Fd%XQsA4k4H7bPO-v)!c^emGqS2TFVrp?r~6$`LApag~qz$2@wkxvM`MD-#AY=cDF9$j6S z1kjWr_3wd#KIf8H9bVoA#GnPFVN|+pud9zc7B`?1RPI*IL)J|uu4AgB%S310i~GL& zO?CqJ3e89I4JXU=?STeEi^|_lUhUrnh(HbOsRmbjYK7;ht=$Pq)Wi4Zn>(gvVn(rLQi! z>$fUrbHDa9og0#vlXLTigiik$JVv(H?tMAfkVEOG>%FxjQOas6*Fyf8UU2IS-LE*M z;3yF54l;QK31W%<6HhL0Zzf!NRG#0f28-xoOwSe5yla>++I=&lE5w%*2}IIBTBA+p zMSg}k($kM~_x|jVNvHm0emn!mCUH_w)CSYr7u}wlDxm8|(>69$)d{K5jB=>pAd$(M zmj@taz_T#kFT-`qVm+?b&&V{&$ixG&Q}iWSb+@=_)pp(1_gzW=%_*b7YN+GeKvb_* zhe7NaG3aN;Gy%xO@lN6uVkJcbfAH91>R5>yitID2o^Wd6Vx#?s5p!p5og15C9r||V zP1fY)f%#Y6PWpx=k~Svnz*aA%Nl`|c0-kGq7`$(Z!>5^orTd7;6pLu^ro3=QzPuw; zB2s7?Ksjqj76=7=HAR~MkoHaHk2;I6owP>({HkTVY+Zt%3^2KCsHbtF)IARSH)KrZ z`7+|Wi^pvYjJiE7#p@-F@51WPcejkmq|&W7(8<9Ve|wC6!Oa{T_XNaI^%f-L@|ae3 z2fd)oSnzTEyFV*_5p~MoR`XNXo1@#Fvx}?Xkw>BLCj7sTmX!K+2ihUByf^nhsI+GO zN0fK1=e(92N=H?k&NXCR%HjvHFZZO+V(U!fOHZwL)pDK|l|9O>X z4HM@RnZp!V(mT8~?7F4%JD1QW0m0CeQz11B6F&<+68vTQ%|o2BNa-Vgr_Q7R;Mdsr z_+Yo|mv;$!82|;py2aP8`;U-N;($TB*hfus0j4HV2u3A!g9jGdFOP0qv0;bjt@4AU%S3 zPN$teg~_L=_L590{Oj}_k{C>}eco^|(~u7sjMIpt)vfV~+n(EMjy>lAnDx2bgj}8P2s}j)Cg!!S!J;l}+5ib_qkZ#@5QvpS%#7+8qk6lK zIv&_Yx)|7g%V-k47B9g3+7VY#j3k-&1p5B%c*>Ne29Him{B7|% z2|AQ<91Dk92BBAARhDRA zBA?oiw*PH`y|ch}sf1UC2+x1yv*xGUh8FhIx(^* zjqvNc(SJU?qW^6BA-v`TqDV!3{nFu&HUSV-leNk-hF)y`r>6M+U=F=T*DpJKA3)zD za%Ph-nO3sm^weBcp|!jN+1t4gy=-2f)jcUGiNv_&w8c;>j=oIZp1Y3|@L!|9(*=y7 zJR#-+7qIqQjB&KDVS*WvKf`#y;)@@{9lU1|NNbl0Q_Vw0&S6l=Du;53hy*~c564;! zrhKju-YHP%CkH|iS|R(N?JZ(kpIyB!(<#{lKIBhJsSDi@xoT|!cL@YyvW{jsYyO}F zZL#*G0vUqi_C20=`mV1AJj_8Lo13^y()FeLy-EE^i^Hj=gU`!W9?r)~*w~V638|?} zQLm|KJxWreKM<+madUGoZ}k67ja09~Qi9i14bfY#tKZ{cFgOzK@7qfjMi!c2Txoy+ zlpi-fp|3pwJ7i44`FO@w23mGR<^ z{OR&bG%#U+r$;D<_cgisAPG>fi_vDOd@pj`=&iF>C?asw1D0hnq1z`gxe~wRMdVk0 z>p5;(tw*xq!8ma;VnE3{Hn8aB<9l60x#szJv$!P9W1UIw%96ow%3R z?Pg!ZdeF=B@bEBwRR+*Z9Uni{;=a!(@aEq%3!U1Fij|2C!6?L5_nGxh7?07S~ zN$I^ZyPO;`*}e8{XMsX?ilDoSsqc9DSRPemNRFaR(a)bp=ij%RyE&AmgP_Is(xCf; zL*&LOj?YVEq=6K6`a+th5S({p8+CYbA>(ukGsN}kH!Suk z(MeRP$+T*vcRaDA?iqafI$k6^9+#Drys`i@xUMZj$eWKl*y;3WKgoLV62P{DM+#OW zs^vncJ_s7G-U2=M(%%mjV-x}cGD*IANn4q zYV&!hN;1I|u`JL@EU<*gRA1FbZ2+^m>Uug2)T8- z?CxWS=h;!d@*szwk!)s`UDF0evoetAmv#LF`L*)kktjabNV_`&w-^@anXJ=&t?%*0Dq2otkB`k6tzMucY1)v$xnjBuJE$ZA1@%`R1S5{#>smez^^G&QR zV=O!9Tk9OD7CTVaEbs$73&sC4^Fb3BP6k>2eCC6kDg60;c7CmAR+fmENlQ66=TU&n zn_UkUN{)Op<4EdXN(?If_O@g8Y$>0&QY@nr_Xfmyw%h>Hbng>^qGCSpg#nk#n~^R; z`I_+8k@btMG_}8CIn%t$E%gtSkPX+i9)RXasV16tA@8K(PiW6$aFwMBK<+KMz*KZs0ysEX9z^efEAIz0{bAkgoPgzM`WVx1-|s3#X)045)l6@b5K>_TFlZtAl7HY4S&B@HcOXJ>JA zT#9{Go#G%ovH}T1G&r+zBvOqOfzrLUI3ZIWbKxmIGrj`(_@! zZeK#|g6Jf7SpevEZ1Ibw?dF4fQ&U<(-cDWu!)Z?v7Jxh@9cGvBS;l?Q z>cPSJ+knZNI5xhGKWrJ$Rj2qO8D)@`EPF^d07$k zb)|_EDvDFqH}`#xeLhbqZ)Kb-_rfqZ@UF;=AaC2m> zH{wl&{*tvVe=jxhCqe7fqcn6cYB=hQ!P|8lSwFYC*Li2#|H(2hAa?EQ-L-44;DQGhc4-Eo zO#V)0<4d=)>Kc=N&WHU+D5N9)%^3hUn7hXq|C4?&yRRxxJM2A$d6Fm+qL1569ilUz zJN>kR4Dt2P7}DJlR>C7%Alw8jEt^OMK%Dv~LM2OH&OW`3lp4@31)hL;kJUT}tu|W3 zAg;DWIc8OdQxh4F&ivb16TX#P_E2s9CL;P7g7h)7It-$>^`_@Add)$Zj~|_@i^uQw295A`rOV{u3^;?g*J0jTvFZhin|Wy2+)&%- z28Rna{I(ML%_$gA_+i2w>VpewH-i$0ULhF%W*0@R{ffw~B}3c3n}s?96%!DP@~sUC z1+VSr<_zWCZH%hriuPiQp0_!>asB~pisjPwsKyol(pu7Fnb>BNrl`WUG}_@O{O-=^ z!lKCpx#k!`RE3vXJ?(*7ROi`Uk#d%pK#w-)U$-m|2n10OV(f5^!?&k{7 z?m)vxy0i_E3_uLnkEc@^1$Dsf3Q;lV8K$QxoNbmWB*vc@@f;Q0nj0IsiP^3vLCjVKFDczT^V*|WdJxG z`gmzFXjgYxI&bWGtznu@;5-xSsqM6r4f&JE}Ujac@Nofoi5y2?=`}f~T5g2O< z8Nxv>Ar+v%Y8{2&C!kwFHw!*u8v&~LF1rTK#G)(kSmt5U4^e5=`g zDEA3YRNAw#`HPg$c1D| z8V^vZe{!-e3Y0)M>d(_~{*j;DF!yil!!zw~9Ob~F@w!8Yb(@|5Mx^=ntCU8vGvL+% z1=w^n0g6@QWmS8pt7T+y`#G~lWZDX!-F#eT)t)m?h8pb$@~B;&S~i9Ih(erZ|2m2a zkbbA*hYz_BQ8YBPWY$T{(7`Z(`1YXJ2h=Iu1%^T0YTAYEtw6=ZxJl^CK1?uYv|FaB z5!t2q3yEq_*32u&yn1^8D=?LV9=LoMsyW;wo0Cc((xJWOIp{&O5?MY9gM&OTQK@$5<6T;Fo@J zQNomHvb(7(&&d&Yr;S3GK%tgKJarSik(!prRcM$#R1Hw2?mF7}0BDhw61~QC;f#Sn z+2`IA37Q`{TmMXx_3l6QN!>tA0~lR z5%|xp&fcinH{m;10jI#LF&7Gv1>}L!x&a~zKsan7{p@Ft_UH1yRPQdW>t-s>3~hrk zl1GLOl^LA*MwB>84i8HR(5$&!=@W?7_C>O&s-{xDnkjJuQ5JA5EWxoiVU}dCuquK! z&mzPYIqG+m{Vf%s4W`ez1go;#$X$WARY9HAm(4T7Sas+5ZR{_DLXZ6iE1AxZr0(o3 z-aeKr*`8q+Sjx*!_th42)W{iIU zY?k9-7K-bu#l_3NqmuK9?Le)V6nI(yzC`(GS8 z_r#bBW|{(qwqNu*msk5|j{^1luNI(26(uF)%ET{Em67Idm!^k<*@-7Y)N1(%(J9r= z&yORWFMZ1^>B${j4?kAWjK#1EgxhhTJ+>oVvHxaC$Uxn+kJvgDY7kcl{^z^vsuDUk zwO~ukv^A)DAL(Z+pp@QjTogmGDz5Y&nI-#zOADO=zr7{d!!VB2`;(S|AzeerVi%Lh6}rA3bTM61j1(s09|64^b|fSKi0yT{ zT&JPqnVv6g%cUU^Lu>ItCLTjwa{{ybg$5bF-)or&L++D40XujOnP^W)Qyo@)@6HzK zDhf8Oi1yi^+Bc4l#pt=S9z4ccIo5n_+`J3vzM0hrv$b?ttt@0D&bN7gV|AYi-E@I& z@MK#*%<2s-iMiVL?VsBmw>)6$KUV#nVndCG*{7$!+d+czq)uQ9ak$4uY6aQ_bgC}S z8T5fn0f^E7Z$4{<3*U3>H9t24IHPaNY=l$?)7EO(-Hf4G4Sr1-5+jI6h!dZkgLW^i zQ)lf~?#qcooI-(kB^_UU5ZqigQb2BpIR``T@TB*0RO;68szrkI4?ME$N^r&SJ^WH*ik=+TuKUkwoyH%G>+`gUI^7w}l0lH-aC3jnIQvMebHsahn6r62Nyu z^Xj3p7z>9!2l)UVSaUDw3*;=T(VeXX5voB#kYS7VS6B* z+y9PjMBf8t?dC)+P-oNT<4xl{w%81^xvt{{$T?rM8vJ5prn|W}C9scY2D!ue=lA{n&TaxiQZ zBe{V4Y}Tx zzP$S5qVw?CgH$M}Z}C-UZN%{6!N(#8=qD^Ij7ZFjKNlAc6f2c?DFu&TaU{Kih|UiM zKbWIPA}1DA5-k^Lq;xe+t@g2~3P%CmuczvG1O!n!jd#S2LA-XbAH#oLA24BWXJ3sS z1ym+jG2Fll4NwE z8h}{hun3V+44r`D=&NFJ8pF^3^brAiG_$IG0!q>L>a zj?(%eFB{>A1JpVs!yY*sB!^TF5br*|S5;4CFfPFDSes(hdye;H2c@Yo_AWKx_KN&? zo!XXVL&VL+{w}iTX*-9UJ<*$zXutDv;}a`8eH1KbVNs@OzSS>2ntQavN0pR__N%de z)m9$Amw6UKVGsSL?Qh9%ht-BYy~LzL)AtUW=GdoyP(VF;rb@uP3P#xn5#p-1Cu?Qz zZ58n`lIV(E2J28Xyza;R15T$*`wnju)`&!o&ME`GwlX*Ox<5`kH5s&fdCG=g`YyHN zD-2?`K}SA$BNZbbD(4S9D-S(M2bMB9TuYK=wC_6DC)WgbjY3c70PV?f`;xn-$@U0g^+`^-mkMoEavdpygOjsAGMOzw=8y)|a6 zwCG#ya1rG>z1&KAKA~pp0wX@>0|lEX{$U7q!P1101m#42JeXZ{g=#`S&7!e9GTfIP z7t)Oiu5Pw8b)KIWDLkLV>_-?euXhD_*&o~6y%+P1vTtgxgQbS=Cd`zBZnuLoz&aS0 z;bs9>e5-YjEzbA$>+248e0U(gv#K9$5;Tai@dsAB#0fVBz8C!p!my_9b7F6{-JkpA zRxNMq#rd|M<;>UHC+*itV_XA2kN9=^TLbN5{!p+AX3&f;5D`K+*5S|G5tZgd9bvoT*Mha;%TP*Kgvgf`HCuJe?C=F0yz~_i4%sN zBLeo`dSDlRVN%MbE@MK&8^0=3D!fH@1^K{la8P(t7jMqO70l-YMj8jHagDjtf_&1#JA8J(>0P-`?2_kA`VUS(ENaj2+* zwCrx^V)iN~^9dc7t@PNK7^bbHEX1A{5fkN&RKHtKGp6K_vO-$iinM+Vwl?HPkyj~w z+SEUoPB#Odoiasa&bbi5mVBWyux9ldoFLY;7x%b-H5nkz^oc1-=Lg zF|?+Txna&30~>*LtvXsVit?*8nSn593tM zs_5t1t!iHVv$f*o>QFfx6aUlW&DR_t6Tlgs>p;3WR)p&h$ES$Y>*Q{@-mIC~9VN4Q zQ=QMDc2jKl*27UYC@$4C{GDAG_V>=r&*+D^tSh&~U>YjJfIgah9!WSe9Lb-p+ZV2v znYO`e6;98yo{Qr%QxSt)gQ5lvvV4aT7*$vruRzbfz)%*ygN|=l7na))VUGWEkgC03nU%{ z$t>y|x4pCbvmDxS8r5oR5)e3Lzf^VnGQW-ig4}Ll`p0Pl+22Wl=ec81A+*-YSWE|W z@HBbzoVot+#&Y)i2Xsl$4{KEm%^wQ8yjW-4>_i|?tCzHG`XISb>27ONDFiRq?L|9b zAWud|3o>P^9l?EgACgt(&v5^tX|YXiiAJRU3wv@aQ1`a{$`bfLv~cC z{`Qv*F^I_X_z>)=Rp_#Nt0|s*|0!S<1|lD8*&m5BM{@l;jwYO7NKJuK-UxM~*ycPW z_1x|;s6NOTX|n`j|6)liRe3Leq%=F>UvI~mg4mCrdpEl0lBH5ujAdCX93l=n{RkDT z^MN1S#p%ZgX;xa`MTrA_9othzCZ``#vGt`IY}oa|w$0x<4PTyavZ!5TeT-hrP{1C- zqgx1;!cO~L`|JZ{l3@s8a z=a}!~CcyWY(=o}P#kxRH zU#doG-e8aiuoL9NUL6C6rU`MfPb`r%_SQ!jvOyvESzdCXX+B z_XbEW!%?YM{wJq!j~wn#G0%@&0f-D91eqxExCFf^XwHN>WL3`wElU!O$QT5WedmHA z`x17ztsnSpF6V1qZS5Bxt#gn@jKh(ejibV9e)L}Vi+k#`{lImf7^Jgva-mw@{DFby zNNp)PCg*W|SGu!PUU#8|7mb1Sw?VnVM++WCM@7uR0();a`-kXKCuGtN z*~913MRqaTaVxD;MGC|opH!FYab%s3U;P4QPk5ld6B(;j)gn!7S0f}z9py%~^@Jm~~rUI!~5 znlm<@guaFShaVodK6K1B&Fks{+l`MzC*ZR$U#|g8YVW6j2_nUWf~Bef79>TIGv1qd z$3+$T%$0=7lNUvPCJq`2^`E~i6cFeG8-0}99*wxy#x=R>NPAqxtYJQFFn65$hBJ>; zIF7?hyh6StU|@kgKAX%;V5oiA>*&=A{&N-q)xMQLeu?uW=j*q2{FA-N9q=Md&U>Ga zG78m7_coDJr^{By@TLBYb55wnMIsO@6^ZG%it6<R&5fjWlqIzrm1mBw)5T;)hEKbPms!yw}+K6dUM!#XlXwx*y`=xHf8r+lY>` zx^#aX_Kxte3p#%HEG0awv7QQXi`}rNmxCR(s@vtl2n2tyPBkS`8~r zCZ0U=TcB6D=yHB@F)~P<(JsE~WiKRs7LwHH8Er{~FtS$H6rzMJtF9~)ktdn%dBg2XfoCuB05mg-X$XiqKgXk5*YD(6c+Zm#2*JlG9MBi9XMCK#f8j+Ds7TWWpuwM zGbp|z#pTg?h|9Ir=X!i+wu6xf<0zG>Lsd^@8{+gs?^BOyMlK0ZU~Rrh%_8#nFpY)e zeJ;H9)<%;<=ZojU3C$p?;p==U#NGjS>y|8T_1cdIH}m-*E#)=|BAu800)1nrekom z4{2O;W^UUv0yAUJpuxEezW@58P4jt6#d<))&HIDu`v!Nd6q|D{6Pi&Jn?5SzT@*fS` zL;9-Ud{B5vc$n@h;d7fJO&e*VIKO)riU%O?SI2tfWz*3Icbaphj7(PGa z7W3_>nrcd`#Wp)xxAENb zA?~(~XKmOnMkuL9w%>Q7mso*A-t(ahLk3|;R(ynFN?3fi(9^nEG{)lNiSAQNPqdtV zeaPl16R=0-s{{6ZD98Fz?j^h|bdzUGthCJg{Y`Z5YhU_Zi%6-0V-AR3ysx}bb>Q-W zu?`@XlVJ}KMAR4NM0`N8|{rv{OuoztP1X2`=Y`I(gAI>tG(Er>!Z=VgaRHuq{v@NmZ2Dobs?BP>dz>7S| zgrreTrdZQg1>Qd&)=jK1iSVNKRdij=^cCG)(I_z_VPrK|KICPRT8Aw>wlPelsA?h6 z5sP}BE%0&^C|0FyjIq7ddDK+9?U0&R4BtMUkHr=Esg1rI1@Nd~Z`@FIlWa_F6v5 zL_fxei5a$Ml0b$=Z}B7}58niObT6r_x!ZPaRA|%6Mf(?@#`CYq266{}Nu&uY{fra( zs~R1dn(Mme+uD-YQR2_Qc?uspw{@4qhrPp0`>uufO>WOqgT9V(^u@bhyse%QHjDhn z$w6~xHH|wlu)D#ot0y-qgTkUs>jQ+@=>!)8bRlh7m-C#ez_I3~8Pa-fmE^xI z2d73TZ`>=mS|5*_`)QTF=w6+DO}2C`qi=j&@eP$)Gtg|7WqtMRt=JpJm#uJr5Y@_4 zpT4gg^h?4o;WvP#Y5~XIHNUa8s3-9lth(9&zNSQnwx)^yt2Bn!shZToqg)e zOxM_^JTIte(vakaUdB<5>T~TP*lmW{B$G0&Q}Rm`Hz-CiBj_(*83`dr*s^1-i7_v> zS@eMKTE}Cg4w;bH{0ai{eFXweyITbH6v(n+{zFuwiAbpMs6ow=@qBNvWrAOaaAJp% zh{KpxPfH<#r$PE59~-%3dsF?m>`$AcsdPa)AYKs01X=DL@*yY+*{orRC)ARS{B_wF zn@FVRXiiQJVx-Tkm9>3c9RP`fa!}9`q5}(Umx#}~M`|U%htSFwkesbZVycwWJui+a z9g0t1-(bwx)h!X?%a?+0NIKQlVJ2Yz0bRd*nPbBsfHN{I$BhP?h4ot>BY`B*22(Se z#B^B4#tFbY3cQl}#^=49@N)4O_f)xsJk|GKl_rQr#gG}`ZKy&i1FdEvG=dy%?{@@P zUbr{q*X{!z5=O4{z!#$50y<6-J1IcoA2I#?juE@~wH*uv0<=)vuD%|KHF>LxiHYOC zLBRU?8mBW~bfwekp*K;Xu!1S?d1#46HbHB@VkX)1FXnkybD&q$=3yetNkN%FIcsV9OR1gWjydU_Y(>C%A4c~0%dHi0 zuH9s#_Y?zV=l6x4>2W=(Cwg|jyM<|mB&FpKUe3fq{BDZ;hxjnT=vmNHzN46Tl%4VS zfvJ+yo-=~T@uHtiZ*>Tks=;`ic;Atm^~0_b`Zru&D7G=KPBHIxL|FNCzQO?N)DM=_T%Yj zx5MIt)sSK~Tsm>sT+dBlAUyV%8>Uj4c9OTuJb5?qmE2}xS!h+I$;JJOk)@8bfAg3$ z#e?hJ%G$*w7$YBzU#TSS1D;z;uW51QA*h53)9*c^E8ejO44VNLDgs?X+>Y2u(A#4_ z`uCzqHosvLiO>h+BJ=X{j^?*&#YmR!=5yP;!CznD*-x)oFDnkEd3y|MupRHsuV;z) zea0jo7Ag(RT_w!8Cm?4bYwXb(rXa1q>YovOS9y}CV zEZS5_H8vdI9tVmsS5aiPxFPN7Yw6f@Yrdvp%?>uy`iVpe(@$SV5YyP3jyT`EnUwJ` zZgDHPV%Y5Y68ojbCWIigG~r8Y`J$oMxv_+CRt(BpHbK3Qmlm4IT8Z&B_x`Vg9m&lR zV3xMJ*;rWOSRIf-`BNIQ*^Lbm44jGq5zeF8V(WzkS(R~P787<27&PLtvV#lm;w*`F zm#-7$*=|d%Ei+jdf4gr46I8PY4>96Nj(%0INMgaGl^X^ohx*h_GPYFY);i@P9JhEw z?=N4emGre1sEJl=W%4cbcbh_Qc6N8Qy5ijh2<$O@2)PyHuEH_U#F#TK9`fUEm`_D@ zN6U(lsS9DNK5&Svdu^1y6T^713K2`nVW~#-E-^wXyy~hHVfl)Dd6y^8ehRhN{ZJKl z?%O=GeBwTF8AMC@(B%^S-vhw-#(k%2c0+u!?1@rVf8Za&2&YQb4|f4V4u(g@E&=x* zQL-s+m@~|qPCW2PtL6+f<``e6lA9VJF;ih` zoX9-Nbcq1uuiR`f##cmXx?XXvzeCoHx*5hR>aX#Jjfm$;@7QgL8yS!PWHiwE(Dz5; z){TZ!iL~{`oU)?1PATT2b(FI9w}*wiGn6v-=F*CvzQcv1DxU>3oN9YEYDJ^ZTkgY7 zn-F%T#Ja9`;gqe6ll?4?k(N1(x-^E{AfLS{pEp&|wl5jr|JD@I5vRjAVX8qq!LZb> z?=T3%EI?KuWw-6&vCP4(FO4Tdl++5_z)mVm&Lqp-L>7aqM#aXMJWOJAHQ{yG+;sR4 zdbv1SwDugO2AO%XJ#OUO zDVYEX349&>d;qcGQ3TZo>)JVZu+kw_;D~*!jvNQ&sB5JZvYC0fy2e#&mT22cN)dRfjy<{PVwSY#|JE~sp}7+%(HmUN|>Vkn0Um_l&`@Ny0h2)*o0zUyysxp-;^l4I@m zL}zFg&ByL`Aucd7A&@8CcloI5?0y>ys<;*CeReQ9%7oUfh=7#L35` zN9<$qGf1AQpiKJTFAGI<88y^UU{MO?yr2z6{!@iTN7QIaf$@Of{Q4bB^2d7{FE~}u z51g>;k_3MZdGISv1SYSCjxJByg#u11o5+? zI(x{j@#F+ zY%C1Mg`e#2QVW3r`CMHb?8PgjrM+jo!u)cZWH>b=bA-KF<`4XA>)lHnR%|GD@V}=F ztwBO_Nu~0~L49|iJNwQFB#Qh7c@^fn*FJ2pI}G{OEN#=PAiaq^4Gzw9jgM;x)N*%L z=5p^R-@M^tO9I)D5`~A*%GFKUaFO_AHO20^oV*X%8)rjOU@LMplWCnSUOzYZ^{Pz0 zgpK~-XGS#UyKugA2F~cv@#F8t9S%~GM>p}jW@_?swB!?fy35&gIJE+r+8UL*MG1To z(>z93`=}vFs|6~QepXLGZx`TWdUyiTT16{~6 z{%_1Dq6lJOLiv#X6I_9kP z*DVJ=k{I8B8fEK=V+>!Bg`r^fN>+Gl5#{vhuOQ=-SJpo1KN19)MH+?!iNn=P5QBea zpu64=K)(N8*_gw`s&T?L`8qSBImCO6>RKuVXEPDIyNx7WHulOmLo9G*icyjFa=1bD zdjK3)g#Fq*>62di;IhE219yy z*xK9MHJP%D57$J;Q$knBE2O#)rMS6|bGYR|8IK!`pq(3v!BZG8p`247^e>^k$-=54) zm-ER{58(mRjNN_qkFeP}(+N|?m}pbQ)p`wbBkZt#%J1hLSX<9nSI4KbO_Ke3n+f-e za~#@4G#??Ib@RukMq#Bifk|@YVA@u-fj(EhAa-;f2$YYd@_0Z=7Mqa#O@vPRl->_K zN5lh-uM2oFD?_x?Et%fw=1tqy)v~%*Nf#xs;B8T1&N)=h!7EJzMVEzgdL2euJDNFi z2?+^4HVh_l^M6#O-ZK#*p>0U||N*{%v7zLsE)5aeD$jp9HXL_)nm%kD^KY?#Nr9 zcbA}LCOcb8toNmq={eRzI|l+;-?n`gny_w9M=&tQ9T#7LFt3jpDCEcn**Mb?yH%g|_;YF0?`WWVj$0tNuZk1z!ExXv^7mxc2#F!c#KV(NZ zeYvp^*@Y2Q;PMK%7e8#7amfBhCV)h#!~h+{(bAkjH$)-awPvwo%H#BgWSuuP1ZPQF zZJDXGUl}?88|THk$C4H}_6q?t45J*sgN64Frkp30k2J=FG$x2B22OCi5DEUfWc)VK z9*G1IXcQ#9tI`0!zjrI-lC%B^?(6zTn(ZmNo)gxex~!b(-Xt+|pSQxbe%UazR&~=u z7C%8w3N`hcs`EOC%G<$9Cnxng7LM9Ud@N;4Z*;TYNQ5@F2iWcxMn0kPIs%Snw*lce zQH!|&ds;1s#|2cs!%iY%+hgj2_jPjt%4%FXHr^QKynwdF$Wqh5l|aj6PNc)n-}3u@ zg)@@llK^W$CywF-U(6O$RF5eM0;{!?oUkwI$$ z1ZYDR$rXRn^g^0tvFQ@ukk92+=!VLGC?~J4*x8ekNa1Uw>HXyBg{0No!j>-ENvJOy znP>$y*AgL!en*a7UOk*c zUN+zgvu0;x0uY5pP<&X<3h3&PX8!dKc`I0c6)3q_pi9l|Z0DCA!=5YA zIubKTm~$!-{C`iMDjA~7o`CUvqz^yJCftm*&*A6cvQ`JUgqD~k*&As5p1y`<5}E(3 zQ!!)x$q&9Ju5gfZls?T1PF(%SJ;V?bBrHxZ*U6r66Zg+Q@S(o*3pa!9Lr)x8H8KL; z0A@d8!DW4I(|Z&S$KAk9Z>3x>~J2N{*1Ne z%^;UB5{;oQF|gOxxO3XH8hrs!c79G(uJT}@1gIQABv36T^d4Zcb9>ELBRL!srIW5K zeHzm%P@ng~mNiEZUtZQpQ18oq`&gHd324J#hd9JQX13m8PQn_VUqgY2{5Kea?}6p{ z4@dpy1C)Wh4ib7G#RUGC?)MsF1mRp<*E3W&%>&*2v+X4K0X62 z?sCM$!21*pEz!=CZN|C=ZB~^D*mN(LzP7Od%pk^j(C>jd2=c&g#AnO6$dqZ?eXbGe zeT%haW9OD7fc0~ZG4W_&;bRQ_jL)pGLr9?bW1V_MZ0r|XQe2JlX%yV4;`zF~Z$#j$ zt%1+7!o-zEZF7t?INfqU!3Z}@)c4xP{2R>GInW{_%~XmJ(<3YZ5b2yxsQ<>Jp*>GR zt`6hxVv0l=c6SuJJcicPkIA*#zYmooSs9h7s;4LqkCxx_(^(ogu!0OxQCl^c$^^Bu znbP*`vbxk9gBwyN5AOmpi)$ky{ZEUpHNPVMLu&w_PmC>_a*z#->!@TV+7^jY%0<BE{xk*PjGZPg*ItP zLm4IfjM&yiE*X|#w{|G8@+vXEtMW4S_;4I10j)G63Wv+oMBZ{42sB`;si`3tQ^O8P z52@7A>8lp}6w+W=pbk8{d^Kmz10bpESg{_WVAVA6yMU%GE`q4=23RK#LE;74b*%Oi z$G^am0(GetMAoehrkR2olspjszYk0UPS)kW2lLOzK-}|Up68OyFmNWcxUt**ExdRS zZ_kDzQ3ILRHPr7~+FJGZJr|aRCCkVIFHE1-I?ma2IUmcaw(ibi*4yT5H3v9DXl5fQyjPin={(B1g5Ji7nfQKQ|p(C?rDO#mK3@&r-yZ4R5L z%@7r)1bzkXBX{J_HRBH73d5FKWnZr>nPdTCnGchY7#Wd1MuG9s+H$x@cO~y!AWG0p z{Ob7@NNuYr`>CBAIMYnwkrwzR6zHYRIa45eCa1xB!_L;(g5DMF+N4+WK^epqw^53a zO}p)W#t%?lDvisVuM98j?JvK?paXl>vdSqBy@O2N6sBIO++t~bwgV|=Uyhw-eiA;{ z>^{S3K?BwlS<0R}VY)L~{YRxVtT~``3J`-Z?H^etFDny`P>SfU_H`FM=NUFnT*Uvy zXep%v$n=dX1Nwe3$65hi4*ug9n8y485P(pT@uP!PvTlq$j8MKoUo{)XG(d9(Qe6Dt z>MAu5oeCM{7J}R=Q3!CBX|W7BA)T*@FbY1@sEF!8d(qta9f%Us-pcPZ*Gv3fFD`kp z*d4-CBfXSWG})ZJRqiMcm;h{^{fGKyU2o{q<<cpWnNv{QL#qLtaLmwnB94)a zABRlO_ddL-v0Ju$7$6`);oOkQY+Y6eMc0B0fEu;k_|U zIB<)6ck_K@H9+5!{BovLtd@M`Tgt5n?iTrs*G7C_gMcnlPCBWHUc9{3kp6OE91rA`^yJVNou`4t>)Z3dHe3}fh6v017$2)c*xuLV?0=>5bt520V) z3a%8p0VZ2`k)UHv6$84`<^;J0;*al;tuB#%K~h)Yu5JhI(pg7yv;JdlRD^uhr>Tl% zjyG@4l``LYFV?nR$l}D``FgE^zNI<5 zM+Dz*psn8N^(0W*uTu38@6}TV&ALg~^(&={MJJ2C`yU;ZdFK!$qb_6A17j3)RM#PW z7}b$rp{%Z6sg>z2@!oC9sYQ_<7s>TNzu_%QL+y7@P{{HRO8_IxS9SOrM5=*kt2KKvVY%g!(#cS$yC=Cx4lXSv>zOR^@ zx_$e^6P%tdtEU%^-O{1Kk*_B9hK3wO@Z50vi`|t(=^z}|EU~Na6c_ICmt(DW z*IOz&QvOUAWp@fsr3*C_S430o^vw~x22E#wdsKrj$%3}wbo+nky8_mYAm6%LTeyL{ zG2OlJlF6POZc~~M2#hP)xpX{77Uri%LB%_xt%RSOuDq>xvLuWK*q`V|K%ig`zcsSu zBJ+=ECMr6Fg#7EjKdA)zOf8|>i{8r9Dq)8y?9=U6oMdSp{4D9%h36t)d~#R*HHPaK zIFeLnMfE(WNS+5T>b(5trQ`7|k4|jY4djK`odq$ekESy8tsLG0EpS(Pe~+Ws=EH{* zf0!$=i_d8Y~@##HTu!iTh-IO*XF`c%jo_dyZ?u%w+w4*>$--66t^P9wYavp zTPg1DloogQ;8I)*#oevATT5{ooZ{{TCjo+dIp?|0_vYF^k}JQ~-fPb_=a^&6LFM?( zUxWLwQsU~IFyq^P{<3Ia8?O1p(_V)`zHwFih{O8&x5OJq@XlEKL-QGIWUR-Ry`YGC zh*crfj{i#(72wP+Pdbq z)LoS$N#Mxs{iKGV_6i61WP0Bm5_Ira1NDM$PFF8J z*SW$9VfRm4(Q^lsCNM@Q33GQDoJ}z+TijbfqgFj>NI>EcouoQ8s$NMSN<&4_u*{t4 zHudi7t3z4B4+aYkT$LYwNMPn2{{4G*ct{e@*esiC-*i5{@XFU0&Q>(VlZ&4Uj~p5r z#(d3NwJcol+f2r$1{ELD|Igc27TgS=BqfE6 zsoRdD3$*la-29gZ(BmiTvUL%ew_M6Ep7$lRASU9sk_^O({TRh5vTN@TJcw2UvVfk=)ae$l8{K^9+zq~;)LoJc!gb4XLO#sE)T3{+n%r4$}an=gFxup%udv@@S zOz_AcucO?!T4?X(;osOqXg`tje)eQNvFeyuSxjwD?QjN<|9TK_=#ku|XC&E3AlO*% z7F`dM+#BwFVM#@j?A#T4it6b;`?MgI8Fgy9FyP6BOMdrw)>ZY4F1Cjp1RYFPelu}Y zIXs4!;dwX0K}D1=m^F$>`G%TWbyd8@esSx%qb=UenL2{y<&pYajT|#>}26aG+ z&^0)$YL*_C4 zymr;i@G}#b&bz|kk!aN4$t9f5=_ZMl50_02e)sneWC4HyWV@^-%$rU3MP&sa$Vr%x zw?b)5PnPE|3nF{qQ`FHDBPZK z^6?#2tmG<{LDHNPPO3I;t%G9@hD(&k`eje zgmAw5C&4}a1$cRD)kO1x-hrCIn+5Lib3C87|M+>k`1;_*c_isJIr-%6ThQH|poA#7 zuL)zp!SRnxZ2sfu zXG7;kiTX2MM_$)nrXv#*qA%lGTRP7<1e3BL3a}F0^-;V;jwM1|RNqEGCW8gIeDZMX zvq&$uKT?vX3dyMw-Ba{0Yh@@7Sj0-Ef3KXf)1lY*W`rnReGrFyGh&`!q`=51Js`k@W+2%Xf$Ma%V#9 z{(a*y^N_B`+Y|dH<&yoa_$B!G{ftF5EE<)dpr-|Iy=-j7L)N$L<8ldW{ML`2G>J$S z!kKQ(t7&;&(uvF}0n%M#>SP%M)jahZ-I-TzB4n9dFRf1$n2+(8#IZg!tA0#34G(px zMJH2%lk$>#LDt5#6uGyjwRdqHiO;7FR#sNB4_#p#*GdbHN0pD+_tv_Qbb`lPiB{_O zE7So_-(ao~J6+CLG{$DnaoB9uMNZ?M)c`ofUr&OPPH!+?;etV9X@C+I6Egm{gD0DT z(De&`mR@G!S+Tend|Xqe>*Gl@0va0YW}(`G1hwU`-p{-zt6L{ZwJ3>(9lL?apGHQE z8~LmIU#NSY$FX<$9%C`}xJ)|zo{K}yDmL3dLCqF5sZu-wdE*lk6M`LX1&2tH{}r|L z6yFnajd?=MsRqAy&wl!A+vk%Ne|bMJFN;p#VPysT8IxpLYUrp2Y()p{>FcT&!8<|* z3el4f!>g;|evyfCa$Q}W7>J#JH&1EG)wmygm9)!4L%X*>n;0yK(UKzr0)W+bEwy}y zTuq#FwJ036WRAvNCrIL{6(88&Pc0ACjHPa|6;J9{s9}V{0gtiP6<3P z9F&YLmw79^O-Uo9l)XGlh_$~FzqV}o278(GmJ|T@`vgehyu|3DZqZpg$jZEPBZiz8 z4||HbEPLYey+xOvzPwGfk{nvi>8=8eSPqDNMwH)-btV$LHqs}38Jttc_#3A}oruN-Wu>N~-RJ6+6SL#FwgY$>tK_!EVV>K)5GpFqiNo1p0XuUBp2JeD6j z*ITZ~je2vbJ`0eT25n7P;*9KvF=AcNA{dhl;criFhz6drqIRD_4LB^3X)y!+)L5if z=TED#H4pIq*JsjFI$g@o-Iba<5KL&Yu8gc2vbLvE4^u6yPCaf5NQRky;$M`*i;9rdBZrgq zC(|m*@!cU7gH9Yt3%~w!qN0du`Dam8a-HOFJe)5^R*O z5!TZS+j=}xOroigib{mKS{~$yhav#T-5w?i zXJd7_#QFeX(asi2#bOv2J6GjYa`E!Z`QcHT**cr(=qpu&@82J;VEzIDN1oAdvzg+~ zMgiJD2Ng7teP0{|QWDZadR*f4(&tP=VJmgZ<~Uj)Gz5_f4SF$>PDrRgQBt6`lK(Z` z*Z<|B1jWpfphH>;Fq3ft))Uqp6cg>;)1%&Hbbe;PIB&9=xh||M&WgUZ=7&|wQNy{M zP|C}JeE~m~>Yz`b`7;NAiiDi05CX_Mg{)9^*v;ym*z ztY~vW#nRJ~*MMv$RZ0TG_Rs?u``b zw(1~avu^e+4bZNsi36iiJt?WowzCsJF>1@M$Lvr8%bJ?XTA+1!K$v=DeV7R4}0wa+qL{tJN_HG#Z}F^**;FevlzoyX%` zat{$hP{8$$%I*yC@i1LKuqm+yn8;a&%uR83)}@59>3nX|CYFKJsk6xWCNoVSTOXjE zc6EK0O))j#SnNRXdujXhDSwg-woEHVCyFX6%o2zAF@uWI0@`9;4XSzqZghY1_Yji*i0#E8so6s)E zZA~Rx3Xjvb)vhP#I&L`=@cSqtk>GQ(&nVqs$(Yhd#2M?n9tRY_0{i78do@syq?;(M z>{}$FMR!WBwONSOXKG+c57yfK?IiB(q;`L}!P~i_CC5MdPlu1W-d{Iu&FX->bJIvH zfW-upl__MiJDBx`3IAUTi%-J|frJIyD*;_cnCpg(aQBFh?o`0X(XHCS7rD>9jgHed z(L5Qaot$aV?u_33jzI-bfR}Lv)!4x~(0^gD#(Frg>9&KKgwy7id1y54Q#CQGBkf22b}+~hDP7A7u|>ZCWfoa2i4DE zIk|$w*FFgMEpGwR!WglyY4y`fS8%A`> zdG(5~b3_GQ3Mf6q8^7yP+B1{U?q-?ZkYFybd}PYdmnIePx3V6mR(d`j4ijA?>Cp3e zS=z{Bd)3CDSa*LlolXxRdOmz9YfHIYj!*rSb$=JG2D?N_X~}B+WQc|?*+L~yn2Py> z{anb#!VJV&EZ0nLkj`Kv%3CS?MB3j1-EP73^TFS*UNNOw9#Sj4i6^;vOdm&av4_oN zj5AQ10;Z;sV5sV!#Bcqe{pnd&liLzKR%Se2qIa;Q=l5%dnxDk;Q}#DAapw1vnI5`A zrfragkKx~9kIk=^oez3le;_01G@h5XSB$_v6`a@5WsSf}{-!sKb~YaNFoNmHr%*$c zwTh!ERb&L05vUiT&U zY60hak29l{GdjT8Rp+aE;L}bd(Y3g+F>2fBf9wVk`Ir4`wtb&A58k)KOvc3V6~-vuX<>>!E|aGdVE+vVVy50rRXqEVFc^Rp?@YGtj&p8jvf z4|#VFUA~tZlZTB)ZDVUdqJ8dY?A->C_~LLpfaZy5LdDMVJV1~lc(_20(T2I;tz1G( z30mLQ&Nd-(Aq6)uR67fG2%{~}`6=^peWKT#wN-`-^HA_%PbJ7venwxFoc0T}@U)>u4YM=;9Y@z46?C=ODnQVM z+C`?M>@*<8*w+EBSBvz8yG&}|?H;*egsS6^i1i~Gcg9l^$snxxjoqw!nY@A0YWJ-F z^}m7=sbQT^oPt?XS-N?_D5^nU#;2PT@dLp3mnNv3YmaAhXJoi_hmi?3XR7IfSsgg2 zLDU8Z@8M!6?M~;}g#g%Ea#mEn8dgd01jKi9B$-b4)vo}Z#ZYw?Ikv!cyfeOqFNNpOy~#I4d;*((CSX3f;nh>whmZ@^y+$8NXl z4!;iIdOGc&Eq<9O(B%b;bS03GmT9&sk}R1h0MxSri~V1<`?pb3Zj^CSPyWX(snLf! zrhq{m0|TfJxAvLYY~3v%#Q{9+UZK6pp)uS|hsVWsPtDZbzOmN+wUi z&_i|_85cp8XT`C>H}1_mU$x#ItB1WgaOTbZ5mBZUquy@{9_T#Y5XLfOmba-4XORbS zN75>!9FTR=sS$WfB1sw=X89zwlhLBg0`R)Lz%hx5&Zp*|o+IFc=uwP1nCv2tK*M49 zy{zggD}nB7XtqWVL6n>)Vb7EYRNO5lNnQa8i!XnK6jfEv;9d?-x6~vg`cI1gd&#g- zkeC6qe278-#3>}#Y#I#ociMfGuXe-K@ubhb&ZP``B2K{J1gBcAYkET8fugoNVb`O< zxh5u&#_npW?(<+X@eyn&$5e}MeznR!5S@^7<$?__e`cRyt*)_ojbWPIt!h{y9CYy9 z@z*NfZ*>BfI5+E;6Ts9!aDU#Q#}ro6PuJbu@~9xnZLln??ce3sMIK$rjSoHd^X8Wqxrapcz+G{5vL_T|k02X*xUy7IJZL{^69%^{cI;Q&!KTS z5@q9B;|3Laoh1a%Zf6+H8cwkMhlt_5BGKoH<%(IDV*TNkfU+1qg;*V-_Y)`!D z|A)=;{0|l5TJ3ksf&E6U>5tLlJygNzy2d?Xql<^-)<}0E3eAq z#7UN=?7HGJf1);@#GEiz!>Ph%PerhcnBdBsRQrDa$#i7SXWgMym2_WW%5JmvcGvrXR81KTo#58ezyyr zd^8sly7Y&@g$4^-f9Mr7|9o>|ds7MGXOmyowDTn5~K-2b`lyTTfQi`*%jt0}2W^MnrFO8gR438BQl}vVTr>Pi1IvYv3RY z8h)HJt723O^#DRohYe|~Y<%@@i@qIIUW)0v)^Am6GjTVFEDMi00ljMnlN+p-a$QMTy%uxlNqU!*y!o8JGysPMO^yd&m@ zogE_qoLC7b_2iQ0*ZSgh**AZCVE<98SFfZKQ9iBvbS>)4Pxkxi2fMw?_deQ@G5#YE zOHoodD!V8%`Y+}HAd-|Ke0I-!!TtOc)u}_q!-qOCW*T{rBip?7387oDsdJ^Q4eoMb z#)jdv*Mx*g_3wYcc@+4nbUuLspWumd-`ar2|IfL_Dw~$%{7OB7gfMqbxLV!#Ra7A* zLqR-T?ll^k$O@+Yvr4DvwzP9eG#w%UnP|xh6FG^PgytYxby3NYAKH#8oX$*3dG=vY zHO#y`&6rJHZ|J}f^?CWbECL+*te!h|gf9xM)=S%twOD(#nyzrho=PkOb-U} z51$D>+)I5T`CZd(-0%=EG=6Y-VROJG<={}$-eBuz^1G=h#5NettUFo?^}LAft*J5m z()%S%)n;njU>aHFa-PmMG(G2n1Z#g_0MUb}JqJkMMmf%d2w=T)wHvo;aL#wF0z?p` zfq~*PB7V~lc)OIc0vGG6bj#~# z;}PKxK`N;S3hw}b<~`qrq&R@+nN&5K6Z>STH?q6V(zT|2do?n56g@`nOaXcSor4Mo zuMPY?D|x^Iz=7s}RzGcPJ1yXB*rqQn#IDfwxwO8$Lf*%m>uKo$YtHee2^%haVX`V& z;mx~zknp#rT9@f*-STEkRh?u{{qsbf=XQXzf}FG$m63*_27GyoZ*X1?)13u#%gLdp+HX10cfYZ`7-$$8*3%`t ziLJK{R}ou{rx{R4LOZIlekif-o8%txwsvu@f=gkw+4}iYWI3CU28>|Ef3gn zH@*gU;`Tl_aJ|$4)f`URoz}X%&~Wd<`vknb>UC>E%4~-SspcyeFK&j{M<4Vclgey$ z_Ru=YTJb-;m~y@C*4uF}U|aSLN(*@gAx!5pYI5^d8Kwl_X;(mx_56$Q%n?Vu@ihNU zl^Vr&H90(FDfpEof|9gNUl7b%B6&+Bh3JB)qpF~b{wUDy2S5e{FPS>0Fo!b2xpKNp ztGCY~&q4hgVw(dmKl7;6NimpK`n?x_4bKix;zSam*r}~;M2~b!nJuP}M#it)8E^Ey z;uOzQl2_+U2J@JgR(%aC8nUoVj#ZpKb?sms8;ilj%*Bb)l^hRLU+F6>>YWE!d(#Bt z97eCW*R2=gun@qMIo*v5n)aLJZi`UkpQiLVD3;lqf<&n@oE|%RS1Jkor9#Ba%4fr{ z=;AWw7QTVX%$$xSn5t)#!*lB z>x{Zii+yKdzKegTX4&=%=b2;xfY$S3HupfE3hy19ID4|MQR%DP=707Rpn=VgC%$jh zf_N>rb53LW7b}JHV12_wrs7veo=lgboT2|(AXBjN%u@&0CD zu5qHF2O}1I{K^&l8@GQB^l9Fw-Aai5U?3^}Vua2`n0d#c*t{cz^_Hn%7J1;Md%%_5 zABP8voVXSUXDCiDtmzWFsuQXc0_Z7(c^TPa7yWHYapWq0nS(%!Eg=X)`8p@O-4B@; zgIQQF5K=&mt`QB6p^;nxIT<#Uhumw^U|7$mCe(rYuyoK@A2BMkj}*!#_3s^DMR`RZ zSD;)g6{&gJ4tAO$3NaoxJOGYtZ{se=3q`r zAatcKe$%jBKV7*3+n`lqt3_jZ`n&B8d_ zH0xc3oWsex1rq$_vXv2-_!`HG@z$Mly(%TehVYz)Ev3NbG+#LbphCF&p@UqjQ#LB| z?GDQNqah?>p?$p@YWgzCdq1gWwf4^HF-|}tcm8A(H8y?GX&KU#;D251-PbH;zA*N2 zX9=@w=O4#x_~qvM$$q9uM;MW;8z2hMnmsusmVjhBe7D||5gAd6Om*znL~xCw?Ifv^ z?$1O1Y^GtyaC92{dB- zcDqzH>X)hdCoblZ$q9PtDFcz`nvZ$U-p^I}`TD8T;P7RXGy7o{FwfR%jNm_`V9rFm zrKUI_j(1j1$e>)+D9EyGzL>uKjyOd#_uZ+7U`c0;pt9dNB7?;yEwR~&aRj7U=Aw`F zF)2Gc)^ZBX4FQb~L1ozZ<+-h?s5evmb`5y^VvLEp-eW%TrGwI{`+ByMnmCT-X?MXs ze`6b=^$5@5KP~{EK%`{-J#>e9(Ru9QYLp6fJ;(3ddRPW>tt^~9Qjek!) z%k}sFd89+lC1HBPL;f<{oo)SW*L6MXY2>yLaC0+<@P5~~px8HyC8^?GXAzZ{Q~ zj9@Z-`kTG+nA78WyM1z~!@~r6>cIdM9AE64wMCf1{xtGsN(Ay-OI|YZIDPLbh5r>W ztECqgWKJ%y(>ESy_&oaPKg=Mjp2Bl7{azrz#cI&q%=+o!=!sH5LdcClh(p4PuH5WD8lD>g?O zz<7;v^0#kDwwg=_lF641T(XWdXW!b2>hhX|4}t4=timSuI9FO4GO8`a#OU{aB(-D2 zYJ^;pW}>AVNN zB$=V$-72F{*#)r`tY?A>QVNO1@_or7? zt8K&<-Z>q6VK9Fl01J@#B~|Dy+qt#p9nEj~CC+>oN&~iz*}n0Nz9blNkUuI4fLUwN zoInm6U1Kfk;(Pp7cbA266kZNX7Czr_jj1zA3>y|ddb7?(!iWP%fwzK^t1DJWcVl6PYDRbm1FSchzm4{ne9 zlV0x`@=yTp2I$Z zFVpAl&W##?Cjupb-|LwTkh!!Y$76v%538?Z5{MO&dzKdh9!iQ=u5D}eEpi=OzihEvdz0h>NMJEpHgA^Vl+<%mf_#-#-X!E%p9IM z+1$NJd*sLdEX)9aPG^2MS~T~*FO@N;;{nRAccSOl8*o+FnTW;LV|tbFNyfg@Y+VkY zVE8FtQeIvi*L1u=fGkBOjmJ;`A2~F2--^55_dI7mn>QxRkGGLp*XlFeT9-ZsUtRk{Tv^BYU-Rj` zm9{gH;pmXluP|$D@rFKv9{ zBc`g7yEL@*HKSHvVO;X{kG_TjFlc_4v3210c@^YB_fIWfUQnPhP(&%>FD}1K#-z{P-t!7{UiK}APCYTO#@l7t9=`Kyde%-lGoI1 z^rDp#v8k(6-_Quxt&ZQp*VG(xF%H<=Aw>xOZa@F?+OW5}gR+%08E$_u)7qPCne z9Py_YW|TF0U@yjgB@jJ}A5vg67y=LHGy2Hc!6*eqOud)WSa&W%I}*87$t5ZDA+8tK z+(GN$`b6^q*f3^lS%5n4VWrxF!*cU}PvzQ)st0+yQs?)(zP9r#p(3HA+!AbF z1_jTjP3(f>dX5#bAtn4B`}6OmFR6WJE4ORKJqbYWFQ3}dmdJDPOT|BM=H3Mi4KfMH zsQP|c>df)n_(M9qJe+FD%T0rU2>4n=A7WUmlwz@27TBsI?$!0Oe)|i!#`!5bqL4#@ zXHh%-E0Y?bQZjhC@zxmipPU$e8Dbz#`P;&Qwdj|}g#aB-e^OwV&SDx_4`^lim z>Bv2i>H){Fnk-xKB@!|r6KsM(ks+z<;o+f7^J>WucIuJ$CFLP!DK(?qb83u%Dq}n& zEd9%$Mn6WSW=g(=5qY;l(l*V%V6T7UsoVv+4PZ?8^Rpaor1gZay?_GAEZFbXj_GX8 z(s{PlAA7CS3$2)bIKdJ1sM$X+U%1gsGf^A~zxX6jRJ;0pYJDS7;Qb8h%OSH(Ow~er z;1<+*Ol$yh_)R_PckSx!!YnnBOhO+x3z7v2Xl_~g3wu+$ez}sG`|NkJW@hpUhwsC0 z((=dX@Qpr4xsQ+7YNEXFOT82Go*q0J=ZKcA@L@NfaB9uG~2 z+SfWU3gu5xqGBKKu3g!Ckpci{s6jArQpd}t_>f;+*uM!x68E=B z5h~3=ANF%7c?(stN$_J6zWz8`u>SRtV?({rbBZdXy8VaxeR(~%%{MPTDw3(C_=%mFL7W+ew4h_35jzB>M zFV}6)R))RZ6&<4N1KZ}ae4ZNJXSxkRPzrUO?GFyKw z@RV#{#N2QZo83M_#S_E^?fLU+P2+#ZAUaM}f0AWE40A(0a~wW>wM<;uoGE@C-k=lR z6S2yR!IPtEO!D24Xb>?M2M46c@a<^6L%dx+ukb<;Mpg{P z^-#S;v;S2DE_FMk!)+-2-NRCEDhhpq$>RwwWnLESXoB3-L(!ZPUk*g&1*^dEq%0j8 z#0!FEu#HjY+z+L(sWs%zlmQ`2N*{g!WRmDLe{B0x{+Awwph=z=XL6A|Mgo+mra;ZP^!x8(lGmjOrVZZUkVgfN8*>yS4u;AMNUUuQ zqvPqK0H)56yMM&4`NafoqaMeOm(*zdxT7WcL0Y5wom^GveYZ<4O-r)u3l`VGWn4jD zc09LOJ?$NOXUc0wu?Og4k9jU6v+U@XNmm_}@C`hF-i=VRun?W9r=F`5q?ucKt|L3O&m@eL-bJ9@s8~<}_mD$mx7WwfuR|E79}I z_E4s0_9hW7HPT1aV9lss7W@Q#6W0MBZCPxy%}FBBaTjrz(xxjne=HRk5KFR6tHOna zQ-Vo&Qe=oNUf|{TUxtiN*U-GG7S^fUC!dA<1w>bc;md?)w3+0V-9^m zACPZ&oRtQ{-wghmD^;Is_51RBTHPF>nxICt;FSwf&V+fKd)yq$@y65`sO%?h>gI;( zCwG7+idU9RWxR#!ul~MIe_%8Hll{jkQ>4R<15+Kzd3kkLpXq;%{2m_vfTkm46Ke)T z0iZ;h$H}grcoGszBqtZLZ}_ltI9h9`iAm(6Ib~jrDc(0$1%1f)F{R$OxJbuPy5J3Y z{zk;L|6F6@=-F3j5H^em0Qs}Ajy1FSh;jm4gemXuyB`0}q@@w+?D8-%mD{4*Ol8xQ zW4A#LlWRn>lPxEwr;pEHU1d47Rkyd}*>(AMiM?!N*i32X6QmUja%^qw|9Gc?7oK%Z zKvep0zzT=F#9Fe8y$|*nJkQs$Oi4ltfS8ikz#nMaQPLkX)sWDak$L}@1=7f4$|6>M z=N5M+tRo!kEh6NYMpRj1@q4S{TwKW$vmqf;w;LF<-d~FYU!5_N@cOZ4mknns9~`+Z z5<42d=i~F#lM0y;%n+t1#X+5(dIs~T%%T)0m%&AwI@*B#>Z2n?)F(qP2vI6yrIRPl z^~t4^#PS}z22=H?#CSij!YEGe7bHxJO<;f%m&`T2EQ zN?3Z|A<_y62*7`MTCwr*eWO3&S}>)RPepn4|L#|k^fygq6r{jX(kEQXEALo;UqsE+3e7m&>WqP0<#H-EI=2B(b92iwn3M6+EcmS(|0m!Y8J&gWZ_V<%UfB%EB~^LRO|gGqiuffCv*`9qzKMtUgF zV%&A@HSifCx!`jn?ASu(QDr(7koLXu&-io0|j1+#QgCmUJB?F0H3x zB^Le95&G+a>!hT6m+f$J8W<9=oojhp!@;flxn45mp_#p9_bLyVmN&q6S=Z zAbN;sp>yaMHvc>mX9P0IsBt5}R$eYzInamn%Ml8;Gj4^xPzS*xjz4YD|6}*jJ zZvDn3_t#-s97QGddlPd^5luzi3`UnTXP@!?0a+XQW2?l;P`;;kv1-85!SF+w-Gl;egh=y+a)-T^% z+8#fjqy86hMuZ3ofRIx0S>%variyvtAubht+1M`T1Yro}}; z{YrxsPbC?i&-#wrXr;C3d7-K_|D(zjm4TJd51)?suVxVe#>S z$O@?)7>m+xmOF91>c2OIhB#jGl;;j_s;Ot4k4i1;^LjxQuA!a+0hvwFEV6n0O3%=a zEjuchT`wxO=1nX$Y~o!UgQ&5N2b;Z3;?Qg|gAxJ3OH51(F>99B z_+A@hnCKr1y0CLZCODmJej7 zdTHP8y{FPIT&~V8%y8H69|SCZV3A3Ysp6s8pdC&5kNhzI6^Tv0+^2->_*J#)*?x*a z_ux1xRYcA}I*!rkV9sdcVJ8k5K=XLLWTI!h&LEt_mu2Xgm*T34h^Ja(CddI!shCQ_ zbFao(LxH2GCZ2uC>dod`wZAyQc;*RTI~-=3B$oCn5p>9@k1YzAW4KN3`|xi^fvjmK zslx4%b5d)DTFWpZuNUaCl8C;_P|^>GSiPUyy*U?Lc<6Rp(=fXBneM}f?@3?(hRnVR zXumjf1qxP=TEtTdf}bdf_`J9MH?oKjsPK;B&Sodi1H7-2@^XuQ>c1slIGdUF?tAi& zc5|+-c}$9B{Dj8VgB&694rw64+Z?$0iR`;{uHW6 zimqo9jBchaN&?G5csHs>L&p?0`&o5 zK^a8s-A59!P@SNf_YnW%gIqXQY5De`Yf;utg7GV&Ss0CCCsfH>zURx?uteQP+U;Jd z7*4m)?K&tS8lbtysooL;;Woe_C=oaP2Ja5&jKadh9{BAS#ksK;1bAtY4y{{ znnEQaQ?8Xy-<^4n7sS}O#xJkk@um)}@}GA4u(EcR?TGnrpRq~JI4BO3@s_QB=5>pj zpqd!#Gy7Y^aWr3%L;jf&8_*sF3+wha*G<6h*aSE>;4y`Uk0uV=4@3Hpu_fS%00>3^ zma3Q~Y;-SimJK2SrW|1=zIzvccmcuMH=}IlXG%FOx3T4ZWC;B`ci(+uA5)DWvnR1o zdI>0~=%|6Wzh8W&m2WYiNA#tTX$KID;kZ~Ur&;rC%@hcFeBQsG4+<~gT zZZV~%lw&}!k-#l#sg=|kYWUT)ha9xy^J>K(-njP94qR2|Qvz=u@6?B|7h)fR|L@-8 z?H19lSev9toTq`AGQS_N-C+TC^mVKAbS%iRmQavL;tOm*7cFjC%w^HrIa#z(p3>4& zo@ZfP@Jf4(wUHNG>DztPJs>QkV_dWD7WfRmxBoVor&|2OhsZ?RhrkQsD%i~+Wc<*D zZ{-aQ!ib$qNvWyDcBd+E>(bHD>z3Y^=>*Sj&c?hj<-e&Jiyz*{sF%S38Y)(K3tnG2 z{hz-)L1QDBEeCFZevkvmN?BG`*3Yl=IG^k)HpI%k6-DX~!9Z^C8#O1torGy%XLDOi z%(2@FchsSmuZMWM5A^Y}yzBb#eRNh3&;27au863QZH~fM+wIYn_bAt!-!LMF*WM;yXx5oUjwK9N* z)>gb_z5;j80_VN_=7T`_<`%>x z5jqyIC}7Y_hx`vLoW$1rgZC8(H{6x|k~?tVu5`qz@%x`l;Olu;D%2Q}WVo>kC~|=3 z5k6VAf-aeoCkk3z>ZYwXI~Li&0>A^a!zjb=Um9W-l^S4oq8R;kkJwP&i za{ncM)`7-ys!CGq6AqcwG2Qo9ynR6{2{Cu0aHO<>8flZ`#G>#fp5A@5)T9z_(2)?6 zF+4BMGfaP@iov$=06qHK6&bnESvE#tm!4ytgFW><<;!qun8$L?L3sieYSL#oko%1Z z+T+ZTDw*#T_)@k?;E-sFKG|6D-v)Xtfa6$cdBBBQ{PfYXqkGvMAw5$Y1%hy1DS3jA zzG{yd;Wd{&%>!FYrswT`XPTZuvL7Rwx>w2GFmkm;Mz~TOZ29IL6qdP2MwZz&w1Pdm zj61KFGZ5xxVm8Iy%`ca(Ll*6Nt-r8$8Lt^R9^V67hF}jA<{h@8eM%WjoLAFC}`; zf%^~snFmZzETPWlSq`dpWB`D!&Tn_UWDB#*)c(28U)JpNZQg1=HTPp)bOuRWbOsc| z;Og=^7Ph*WE$;Wz@1vjLiXS9dJvoE%H(GwL1aurnfL@l2;#Ii}TKzB>cxLqERot-& zJ=%u`2%Yn-4301BflVKNvUTm0^$0h3=F)oo2U0oMC^Q0^)9EpT5hM#L6oc_&SaECi z^nKk?B#|%F(^8965k|1x)98Q8Yo?unhyBOZerb@;;fpQPVIsN?^m>)T#ai__EekT$ z5FQmm9ld!0WR+9*+-i6|n>hY4tH3skpCsP2$2@Ks14rju$e6g2UrJB!rL~zH2;{!& zk+%R&s%Q!glSIMC&!{2~+HXfLzi!U2i!Os(5PbxEYB8)?IBp_TP>7aGAoLZj10-f| zT*Ys~pAnpfqbb>Be0Mh^HwBk{aRPeV4j_TLbHr;#K4#WxfKz3M4R4y?&O;)hdKu!EgW1n?u_Cd;%&|WT z0Ukl_=Jb_4G+4ypCo&DFk|Y2%jR@YJ1oPgaBOt&D-nIAZNxXcd1c(N!pFjX#wkGI& z=qb5(BLbV-@`ny&vBVb*E~Wm;&tAvNHfC`}u>~z+iXzuGf*?h7mWX748rd%m(!8m` zP4K#e(2mk*uZ30d2@W^8Pu;eF>~FMvkU)4zUa!{MOq&fIsS??Q4G*%vt(ooy{V^pd zZEhB2snk`AowuV8BNd~{SOH>v+Qq^De0JbC%)^pLKVa>{={1wEll=eRWXPUDWQO zLAqN&8YHByU$FL*!nx!JlSZccVa09Iy=TRWqCr`8c`LY!KzEoZL6P|$qzdvqIV zOqAG^UWS7CnxlEmD#1`PZf)z7H47Mf=IWcO4~v4X=(f> zoq<;kPv5_PziM#$`v|0SCCp^+Ic(h{!FWaqNT|!wGAblA%WH&8-U;-yimO}rqM9ls z2>7&lTs@*iIjhgSixPMv|1ANJOa-Y&q|HXpSVcL7!#BW-pi-o>2(KLb!KzqNAvLdB@Y=bXzpPXV#E?w`y|p@eKbzJU@mIOo_I4zYG%<)9*pN3kP}~ zh##`4rA6V>7B}(d46)}S9j}H&{uN;ewvcFWo(f4!G_g5KniFeOuuwLp)P+X2Dldtu z+Dr$?JP<32>C<=Bul@5wV*n%I0{^tO>GZag>%0H43pFB`G%p*aw<3W!GT%j#yEpEQ zAz2>Z@)0dv`eR3HQ2k2EXQ9=gobba@3mfeLZAi5vPF;7X3`ZDT_uZ* zlg||=SL}JXQFvzLMd@d|l(We@_B`qMlmI4(i|dUw`R_3#K~O(_6BP^^MeK3l22@)i z#2$e#FU-!7s|JOHvH3AtMis0ujieEi!H?fPfKCFGzBbDK^5f@p9-mr*9vmo8H$eg< zgr{{EFX%Q&nu z-NB5A2pc$Wau=J|n)jVfUIZyw?LBsnuLD>6AUk-zA}Yo5fdUjqvj`Yk#1ck9R3Lkt z!t9f4R(?mZmaZ5sxnV$ z=dxaVHVu|Z{0aEPAtfbOsgRiMVH*b~xl%9+(DGGlgk{=KR_u-ddDeDQieic0PKIyv zN`mKDRyO!B05Cn6Gb8yg(t$6AlecD;CubZMpDqC}M{~7d<|rj}(?(uhqetf{poP_; zT@fqWTqO{I((^JwQo89dAEKP$8s)cs&Gq0w(YO`<_#%NJ4c-;)OL4%_Jjrk5JEvPs~aDz>jWUTa65c%$oAIGhE~bQ@K}0e zZ~&grUQr-4B6Y9*-AVsF>CtmJ?tk}@oUj$GygCRU&rQPxUsatRL?a({VHb=5A{1*f zXjg}$Mg9TPZS{Z|C4c}*zO>GYjLZ95=~{_I{$+Pm2$)g^k;=q`sG!5cO|40h_5)QUruv z6AskPR!rmkhJL@T_?E*ZP_$?mBfDFR2LIngONJu%`%EO)lv0KG%w-CZ&Y3g{QtyDA-d`IpN}fbwTr z^>wpn-QI;2GuK;+WHrPX=o`|h5`u(>#E&e=2luuNRV@B(3ElX;WtLG`2T_=;Y*o5k zqS;W2;!DzQ!#;7LJQspo8O04qH}id%Bf~bO-kGebvWD^7mct(CLkh@mP^YA_e3?c@ zQGk}|jXR-`rB2W|PXJzId-KATOckTUr8$zg5i^dAn74}0`P@&W+3E0HJ?yQ&_2z8p z97+lF;go+ZpAZuhFAZ`Mt1mdKoKr@yiYEl747;;r@jr90PJKqJlIk;b@B13(u089= znLngG9p772%RUL-%*n6`YtAyuxV;<95WT*KyK=>-^)b8zW!~%>a!A`aSDLccE zuBXe(0&)$lfYb4(^&Op;cxC73>-)sShrW7_noT=g*_FD_8Hp=WeD_cv%&$kYRNbGe z`~NgMoA--6G4A|Jz2=3$vcsx@B$U;|UI9*^&N*2z&LH-oBR?|A70X99pf?c{86){k z(Xt5UFA`(bU(fPIbe9_7Bh0(xA>U$NyUzG1sg1zKF-x<871sR;r)Vx~# z3xf93(hMrzI2r8zRIe;7T7SOVV%E^mwwwz6#ADZdJ*^7%d%n*-njat+K?6A>gxkL$ zUN|`~BYv^8^rC=Wd9h8WBQb2xHRyHva>6+zC`i_)pf1<^6)?28`(O{y0_x6>GkJE( zTl2xcn3J&t$&+LL0owfhuRsfPVhB&_b9uRaT*HGj#*Q{Q@Nq0dnl{I)jgAa9EXOP& zc#ajY3HFh3O?9J00m$BbHu#eRv|_d{uI(n^Nr2t#<#ge5Lp?^6p(F`XaarxxQ(tK6 z`U=<*1j^CxOM}@DAvS*WH#4hKA&B#bcFuSlIQ1-*KDTJM`_F~wi`J~(AI|GYAN%eN z>Eb%XEYx4#sBryjv;SfW@#Eq>7>#oQf9Jqn+HFfQ$By$AhNc7(ZN>(s0w z{&7ZqvLjvg4SU<$@iR3zqvF&onK|qZkJ)ad(fWoB+cg%IZ|D!{v!D7T?oZjWv#t+y zNN=(VsRc0u9+u5+4fX0DzD?c+JbUD7A|EYybpME6Ypo1m9t#&c7@fn+PQSW2WIWshv{a*NyGRN^G@6CgG1radH{!wFMQ`ucv&OxeRPT_ z_ucMXmigOt-c`%bAW#JvnwL%COSX?1(PZ$!_4dP4jl@?jQ0IbC!Qv`FglW9Fw$kaK zQ21A!)J;F)u^TeH9Y@$=1_N}x@y zxu*unz6YzusLkTv6!my4n=W-s9Dod_Fzbu!1tFF~d;NQq>Ja#3!1Bx`KFG@8m@TsE zF^FZ{abcX6ZjFMu&TcC4*cFTtj^Q=}p4xJE#7HU%3gcsT zu&i~Pd|5`KuzG}mAZoJ*=%y##8zI{dW=M8`W2C*P^|h*;UwyHX7`57`v`KO5h=d%h ziLeEG6uP~z0^?Ja78XW{3$WY8dK`UREA!bD6s+IO-sQTx9yMNtnA440>3=*HNxq!E zij*RJJ25(>p8C?pUT`BC*ZsxAfrzuz^Y^2NzXHY>#PeZOztU{$+1Co>^M!&~BgV7( zr_?L#%$r1f^5qY%BEM41+U^2M^;f^SIpjTT#d|;tMTIUnW!$M6sxgRH*W+T3Pi7M1W3h&hZUjjS-riZ}yToSyzT(#fPTSLk8*&NsUC zoy{%?y5|Or&(JqXEnTi;0%CSBEC6O`A3l-VMJM%!&n~26u4E15>sj9Kzl-XN!qQW5|H-tYu>Bf-q<< zMwAd}<_LKrNi1o5#p(YXTh%QR{g^y)PUAvMb1GeC+JUv47^MnX;-0|f$*AOgKLP{v zu0N4q!6>^-ufMpSvD~f!>pwz&OgXfC>aUIT%Oe7vQ8;werZnw9cTflP@hQ5|48zuE z0Ivt)pJX0Ce*Y`;mhU)~k4f6e(3_y+Sk4At#{dUJ%7U}s0USsHS7Y^ri1}QWh+NL& za`pmwhR>x|7phvJ{ROL+0S@gP{yP;@`a}^t1Jn%jw&$ zmdozgQ(rzw=XFxBCA{&eE5Bcn0fP1lRVdglL7Bqj!1n07HJxYTKYtQz?CL}Y6vs0O zU;9G5c7E$pvlGSr(_PJ=NGGe!pvYG%XvhWzB+bid2+CK(crpwdP0!?_vdEKr`IA7_ z<<#AOTnGo7nkk=M>0-Zy*?}PdeK=R6gaIK?!pMn5id}Wamu|-lw?VG`q`Hc;QJ7$| z=%RG$tm}Xb1OSLxuMpet*jy7Aqb{)965YS((UE}g=)A3NPXp?#YFgZ3YQKUd^Odbj zvk^3U-$~)+?#k0}rTEn^qaGd!AAJ>_FEh8ffkV-qL%T*3XD$VsrDyulNiEm{^h?6X zHhO_C?z^Z?04Z@npp1cZAMEOXOOOkyo|c+DSSAP8FQ1SNzzA687vRuHBF8w*w^tpk z2L!yFkDm^tt}Tk@u4frj{E4Ek-+i)?d(Gdgr$`<}&)eoSurFe`w5%uX)?}9^>DnSx z2ceIa7IY^oUE&N7`~H_-Udc4rcv;7-_1tqK##W9Rm&1B9Hdt0QS@5KzLv#o_mbGJ&8*mVInQQ5;V>T@SVkj#_2?!PKrKzq zO|s5KlrnUahK5g*%G>#icQY5?@fyWa$4?Rja{O}d&{zxmmdcV-9KDSISZ{7Hg@9zQ3jPtsp4g#MyDisD3==MX#j)>=YjUMdFE$k<) z5LF%YX;}27H6_dMcwc>|Q!EI4=K{F+Rvvx19A+Xp&`&OANPZB?J*IU!p>&CARc?9; z30Qn}m`DU-lasFw%YJKS_qO z;Yfp`O0o=uFYdoas-6;azr>jR_}#-?W8C^|YPXm`BX2_X_!xFer)xu??ka^w;AmiL zsi<@rVC3bqUO5!qKH{$09OkRB{qlHtY zU%Y=~X9cH<135kHt?|5+s=`ZKND&&-IM}_%rF&b}?BcZ>Eve6JB&l%$iHmL9Eaibz z81h_Q{stCNDfV$@>m4D$?(w3q4>WK#1x}SRom}mZzRqft;Vs)Q{Ps zQq|tSQ$EXQcylKq?G#9iRmQXV_9Axr}5;I{v47${Xg856Q=M^&_Oefs& zx}z21V>nDZn{9L`wE~2^(GO!6Xq%HaPYgAtO7lMh4#3usZC+tkLdX?>_02faq`&QY zfhb=bxJhoER)9%36c7m4#aV$omht8N-r`P6h69)Rv@4(pFGs+BA$PpDO5Wna>+HXB z06*m%X~A^s*1z8=Mv<2vYVp|PhJFbFxIMSewN#eIvyc`K-jh6>DJxuZTsRQEnHfMI zPL-RM7>af`u2xK_O=K#ozv-aJ-JM6l<{>4dP-Sh{9txp3AR{FmnXND%0GjA2WI7nb znB1O0^)@tPLNdNJ^ADBo-I%(hS&5Yi(j5P2+{lTplHvAVKvH z#_5~xKGSX6b)3Q1p*@P@XEzdQ6ouY9bdck)cJu<7CRx|v6J|>}H(V^}Br`+MoytYC zmnJ4MF}}NHhw#y-y+7|@13iy31Spt(Pq}ZaZAAwpFRkUxIFk|2eV6NO)Qw z*|#HpQ>q{LU10(M6=oRJjbQqn60Pu{9I=Nfiiw)}>XAmgF|@FOC ze2$o{BVy!>`uJ8s@pMtj(!#jjH1wi$QI%#EBZ`H`t58opk|uy5!>;PP5;`~pe4zjs z&l`NN%|w`PEm~0!83_>GQ@y=|V;MfFNrMBjUO7qYv=M*k!{vO~lOaLYhdJ+Cg0^6{ zE*j-lLkRM8%e6D?>)wGJ4S?+Ru@zEl1TIUm+RDqALd(5m0K#`}IWJya0Zum{N`%i6 zwIGE-i%MX9R<|aNjrq!rO*kRZZw%G$3ow3RN6ZCKxOzn5R5|zL(H5;vt+x>{k?*kI zFK#MRKwh*Wvfj~9xt>4875Y8zlk3O|K_|2#zxiI6?z^}^vLlau)>(Y%ufKG?%Y9rQ zFqnNIFY3YZrPeb;P zUZ?S#4W||gukEH?U<=bae-~O9;Y!1J zUafiVB0U`5+DFvB)b(J1#L|}BPuA89vhOdWNtf3$-$jkDSHXcm`@dpWaq|wje-r*w zNmkz`{a;ij)41XF`GXMUoAXN!X{*^~ za8eoOyzsNXgP5URa~YecC_l3%j?BK}Bbv!M&-|+00r`yAJD_M_)5q6=jO)piPDqANr}Sp`J~(C^im3ixn(6!3&wbe zv`J&O~pT=a>Q393Z7t~X>A=t4@U%a*AUKC7qrqFXLgZcZDU{I|f_ zjM2OZh~7t1N`*CSR4-JP01Q)(;GI0Q2pSfL6LT`9;xE=z*EZ+K$gK}1fV)G2$K#%m zvPk5r_0@{D3;N4=2xw)0Ii1^>fP_CD9v*7yt!{wcH!um35Yr*HRZm`L^*YQ7mc~zL zax*x?R`nOWEygAYw8wl4<^FT9=pZC|orSZ8Gwt#KosVg|UM)bt6uNSL`1OX+tX`&0 zm4w_T7ex6dN_J0WiT`$JFQD0c_GFdfk&5}x0e`e{vz>gEV7^;w`}A7tN&nh6qVRSG zIWtg3yEWQEKQ9QFCMb)BNowKsOWj(_yr#4{fh;g?{<(DnCR5U zeV6;}z4Ub^yF=e^;w&o=Nb+&jxPl?TahFuHLa5JOA>(Gzf(;!V4s_8=5kOW^eFhfU zxJpOoh*W)Qcku_q>0c_8JU^e+Jw5BYNDppEzu0;?1&n1G(G zKYW942?*X?&RIvXJVMl@$y5mvEaQ!{N$9a_H0W5N};2> zsUQzB5^@Awkgtr`?5ZZBkR*1C80V`vnB6Vy377Sp`K0^>$QYoSq5Rh@WUqsp;5O*VWL;lb4S@Sz>DZqtR?|yZLe{ z6bHoKLDz5;0BxUW^J4D=4EENx;_mfiL5P7m)6=(BXc(aQJIn3J{eculLX z)m;V1dK-bOF!HOWhLLWupT?uBWk_gPkOTCsMX9{~1MDc(@g%jbidaqAeS+feKmC{` z#wzW*$1q}=Y{4q>>WXmyqA}x)w3m47{G!>c(Oyh}o`#&k!pN`Nw4Kn{xF3PMgTve7 z={rhV#=x?JPwxrXD9*iiXm5P48!J{uM`acc=wd5^>40g_pXT^)2BnLBsdeNWkacd* z|3^O$BD_(?n)4L8u7><=`AW18u2G->a63tZex08o@O=S8@?C%VGmX?JmrH@iVz{(o zd`P_ z8<4i9!PbaK=}*>9^;W?TW0n)hwxNiC34Cz!ky_?_s}MV%I1rZPpUYAlYgFLi(D zhW{@|VOb_vtGtjacT7fjWC8V61j+J%)9|1RZ%doLvRu3=k)mf~fxC&O%!U^*9%1u` zSaDimt1w3NXvs7|mrg<#u)D>z&S}SSrbPtPDNi@ItnND+=o_Cv^nCd(OK0bP$X2_1 zO-l=YSNBoM`!UN_PG|UZ94+kSwM}kX_o2+xbhy;B?Ts68UdGUJd?w6CJO|zrED6^3 zG;lw1JTS~HiXlKty90ZM8Dv1DCid^aMGngJsJ%&>iWVKYNrMN=>;3{->nlx&0?;YX z*&2OIFENml0O%;&$cPDoNhWMhBj}ZBVwcHf`K;>}WGT3iYqD8(&96e0#R)5eGh?jzs+ZdUM|@LRHZ?J9}HO8=Waz%AzE?=NKsMFYL=D3T`%Q*T3m>Yx~6 z=texXzUqt%R#8@#MvCE5{J(!kW4eJ}%aadO!H8d_q{>)4RSoKV^Y1cE}6lHTblzP=N&A+NpMKUqwikM~1$23)&U zcC&2BpD<*lt%@r%LVlIq*fE6X)Zvo_QduGZhdxDy6MsTua;ZtPu%j)w(nsq*6*K_kRLj2+seQtTxpn6I(YGt6fn?sr0V%?KQa@fSMWu-zMz6oR*#TA{xB)5~f zYG|AjIK`6#-VsA|a%6vr3HKK7d?QXt8=*Knd_a}bPD-{S=K_{1q;OZ4xeF?smAOqU z8O5fc0gzRCQVF4U|IVeaq2t-5ACmd;fB%57mXjq$^lI?Nm5lOvS`N;{XVm9e&LK5k z>1#BQfv-?%e2!itC(~i&PlkI4FqwY161%+fW~_cZ>XjYxl695X39O~vJ>txJQJb`r z>%XSiE!0L3n14_7gW(3O>#U*^U??p|a?0oA?yCdP%b|_PeSOx8B&5sry4s>ha!#h3 z#lJr`933+#!u1g8rU3IWIZr84M~CLNn`%KABv$dRtEVA znW4P5aWU-rdAI{2H-_!tN#=x4Pnu8VN`JnN0{zR!i~i7tLib3nnw0(1AE(fDV>3^4 zn17BpiaTGdPlI6#BNAqU=o36JrkG84rzD39U$R^O+#p7IsOzEG6=%?rt2drL2CVN* z`ym4ZlAB#e01|fY*VAQlM>Fy9OKh5!?BHtJjLK27_ateLD*m!s@^tq2n*!p^Qy+ZM z^ic;$PukV>>)b3)E{A1aE?W}~W9N02%D@-6@auY))7Krv@p>&*rPNR?tIkUi6d_U#jE~!O4k|exZDs!d znK-uB^qtmB_3f_84}0{Z7NUBn_YSLEoA-uo&u7q;*0S4|Pj}C!7jb15x{{&)>SN+! z3JOufB2aOUQF5wflL>#$sa3s1ZAeb>YJ6mDB=BQ8w(CcxvkK254{(*u#7b{QfZOEK zqL>GUoIux zdaLWD>*hJ@!h0PT%|$HvmZw7Y@Y=zCn$f@F{|S&8Y8I@F@9)XDT|4SXqwBaIDkJUx z3clDas_`a&G?~2ATvDCVm>fo;?^xg6amYTV4M0m!DStWec#fhsZn3*FYeQ5?=k&1N zOU&Ro?eTW_=a|uakXKa&6b6ja1ICJJk+|tn4TLFR`q(gwfpIP@V{=7zB!q zFUnTrwbKXjdt`{1&-gX7)>oCe(b1?w2rY&zIpV65JoL3;eq$wCfC=?7BjV@waMY{z z8=K@gpT(nC3aQ5}phF@H2hJKI{I@_>i1*&s4{C~bpYukfGo=;iB$Sl7v=Rv0xu3Vo zoo}zPRo;yQj}faq4t*uvwJ(MR#j8AfLL!dV_$ID4F#{gCuUh8&HN4XFV}Gi?Rva&r z9auTdi>Q%EBCbz#Nr?!M;1AQKMxn$Gh-nJd>86q_62(`RcO zr(2js?(ednl9Z)gBjawKtE|U>NQu^P-aYb$YYJC+%_qy4e~OpOB7(88ASVzQ&nO_) zP#)E8@cI<9tlW?GaBs)3=vm)2;W}Gme}Z_hGEtZd3Cn>2nJ8(efbVLmgW&M|U^&PJ z#A6=OX`WXaZ_*sIqxkq@QCpt?cLy*bR62_YQYrd$d)m6PGAitIDffZzC#9h7o&ccv z)JT`62xei#?H!{QN{8mu*&Eu^t|g{gKp=6y7V|!R1OXUUD=GQHtxY?b(Q1{%(hgM? zzCRC$(1;862gc7bZgsKp7jd~@^_cW-PB|{pTPkf--wE5d*hFlVdg!ENKK(R{kZ*S$ zjllj?5pcJfYH#W0IF{Zf6d3<9^vI@y;bnD?glWv{y?O|Akm()CA{M#e3z6At#V5}eM((QBm z@KBt%1E$E0KjUs6 zIf^OL`*3o}s`gz4-p7?9gypzRdYb}Dz@g(H#?m~NMAMS=ZA_WgoMN@()4)1 z68Q<`o4NciWXp?Q4QJiDYGjbdsFepd!e=ATd5{j_KU9`{kciXq`@TzJ%EuLq0;@iP*PxoH&v z>qzWhdtN1(o}l4r-pp642JnAHC;JCS$*BQQGdn$9!1d|Dl#~Y^$CnOBx~TA;YfH{A z%FoCQn?o0IK|yK$CZF~r)hK!=CzHF$Og4Ye}^Sg%3Zx3GajpXUTD;|8=03_buqdWR;uK-9%h zOm+BPuozRe*7s*{n@gNc$@9ydkA;OT+~Q}ZbUrC6Ht{q%y$M)#&9d6|SsmuFY7VH| zz5BhMJY(+q#O3mi{<{4->-s3GD_aNgN3X7(>iySA_(bm*smbk;KiTdb-wuS6WA4?X z!XdVS<6aB*FD|*hYtKsez{~Rw({N1!$qEG; z>hgr`D>LX_Ou3uUA`l%<8y*8q>#kx?FkuoTXAU9oKFezIPq~;moSPv7yk1 z_Fn4W?1)zFe93rrxYk_mC~MTdp1PJkBRfef`VRp~3=U12*QC`zU>`YBn+`3^u18G^ zem3cywB=23f&FuH9ws{a!isa_l>4yML#}Yprdb{xPJ*oT)Pv; z@UbiJJlIB1XhsOJ2jkcCyv@_^rMihkNAGy~qvWq=@Y0=VFUtIjnSjm(t{o|ZC zX^i~0)p*m^-}aU*ZLxA6VBjE6L)Q+DM&BtNCqNsneDL(d=bM-fNvPt%`wV#Xj*eJJ zEW9aLM||i3j-D3oFUr-iJe!5Ea2W7RJ?xVA z537wu11ooe2-*hLa7s>!pne?5f8ck$9*rTUDJTDZiXnn+W7*&B8SSlY6m7$sB*+U2 zEIbJ5l`=F5ZLa!cGw^k@!tj>|8+;+g>-#54773OMcl7=%(*Uj^^Qc@+(oohLCuoT%E2SC2tuK5 z*)X4=RQurteFlq*LdT}`?ifDaX`-ApbsJC3AH7!Pu)KWs$RabKo$~rC3z@GiPlf?4 zmkA!pL3nRSph*2z=zM_i!Edvx!pz}!Zkzafv@egtSIKsl4L?*3-ThuePsa#XpC51H z%61^4fArk;Ix^o+O;DAHmN~R)`i10b5Uja-Szm`mv+6>-=M0lu*4TU=MJaxxb+1V! zw*B61txtWfKL(#2m))I}EAsj#*B_@`g_kV!rxK(mayYDdq0RKGZ^cqj4iaVOXkhZh zk#fFAbt)RmHobfNmNDO91}%KJI#FG9g%I4{=^|KtH~BZu@_|UB1qP&JyOhL+UqmaR zNozeyS&q6{V$mfWl9#))yNhD-R>{Z9$H%LsXrN%kB0atzR(248 z#l#%>$&_Pa9%;*2Sk^EO7IGxex%hW!{I^J*@N$uN6fB+ZaK#@G-cjZ}#oiiw&VRd4 zy`p!&mnj%&vwV(_bP(wnV+_!Adx%PHSm6zSS}#Ghz&E;foUP)+KcLV+@A$c2k(NDg z-~93eLydOKZ@Z`A?E6aN!Cds-XnMn4tcCjwc^`I2Tcm(r-^f|T*z^4+?bWz(6U#*u z;d29(0~RQ79dqNBxt*v4J5}Urtta%9uu{aGkMuC1{?7bIJA z0l8+gidc_T#IP;J0 ze$C9}H+K;b<$!!kPbaz8?k947BE4xAIAx*k+;U&GvAN$NWs!}mS9EhaUtfA0$@HE( zy#C$L@s6>ZDH-Og1TEKns%0QKo;V^?iQRJjSQ=+hB`-A-`|MGn$|{%3{OyYn+{tG& zHDhCNO3K{4{ueYZCMKprRq&e2EjVvMDB|xn5Vn=d0XW$}h0-*|QgkY)f9!j!A{kw! zfycOy?9r2SH7-@2V$Ed$L3}qZ5s`Ea2U62k&>>P@e+An8^Jmm*I!P14rEGKUttYaA z4x(;XTI30izvOI86b?rDV*w~!7xov-GtgS203(~I<;7=1Yp~RZV9Nv>n;7_{R z-TY|!{Y|CLDWz1dHt8t_CBM(F+)WP^F`K%F?QJ~Jx#x;XQE;X4n7QdXEQkTm3G4Vq zuceK(EasTs+4*x_*xe#64UM;ueY*?&!pX;@rEeL6_<&R?xOaPdy2`wWwR-lU$+^H} zs6U4EUi5NZ3Km{AuGYJ4`)pU8!mUhaQAQ%xW|vAFY3$DY)?X-zrSN6zHC;mG5Bpm-|2|(5T9`V_o@kl ziuovCGdbLz5_4!CKekpmuSjIiC)0ksR-z1huOdn4)s_R>-;I|#LSNaE@}Y(xrHb9! zX6En=jVkja8;|bCrPWi4(OnN0X9D=lk)Spo(M*Bl4wa&?@xcuX{^(XCekj@(opO(3 zm!<(~FRfl^V6`7z#4J!~21%KjnR&-Kkqa>hNagYKDQ^Q)Y9T5`pU;#a zt752+0t?dt9T=EovbU!S>VIkVL1ojE>`^XpD-PKh-I@qZsVNU!H zrv~~ywksV?kT$kk`|wbZ!Na()Cs9t|Y1UqXb?m|rN=l_sGKm%yN4PZADO0xAS8dH; zv^<6s88Uio%i$ltog|z$eSE;$C9kf@1AcLxLFZLD;7N78d-7hekj(gMC89>S>< zIYw=PO-ZP_jDSdeEn3}jRwBjyt9v~|)*-=nwDg$rDgw-Z@!obDb`H zr%?a_{R+=R>>H5m6e$h)_7NrTXZC#=bIu=^TH3xTQgs8^kLb#}jALyi=N|8N^2>f? z5GfUA^1Hy_4*=iLxX~n6R{ZzDI8~;NE%|K^uX?kg+x6(^zYdp_eBv;webZgMSh39X z^vz;7`@qr?o;B|qAIhP{;Mv)A+%wx6t(lqkLyKAxJ}qU*7>7AE)zzQ6#66G@ph`b0 z*4RFLJZ*HvR>a}IJ*5Mzz(#T@N2J#CFGYgWE z*Alg?wmWUfgbsxOOv^%k0IKEx5M-}IdxrsYzWh0VN43T{BV^WkD5TjrPS)11?_w`o z4e~XV>IZ`G&TG}CqI@C-M1`mVozs~K+8made$1$O{6mJ)b2h1i?EUz6-<4?Y-g>cA z>FBkIbeX8x`_if56--*+UugLwdrxilScyI}c8lMS-dvXs3=8@agNh?#Pj+S{}8QWJ`QM8cc+2c-c2;s9x( z*1U4({N?RNT_XCkhi@uxKj>$8l7I1wZT2ScwD`i!s!RPN_X*_BzzX9L8h)o+r^Vtv z@ijEkwp1=mJ@+mdjrOW>^(0RK14c^NrdIE^>Qm4uhCj02I0tI~Q{)!JO5@v&<)Q^@ zPf|m}h@HOaMx*p+xp7)lCfuH&45Oc74g!`nx(u|zOwI`D=}9uSPQe7UK9~=ce-X&| zZ&3;a7mRc)N`GS6Sf=(+eW%@bYSB$8;3kPWd=ygW>!xv>KukR7O;n{zjiIXTf3c!+ zBXedW11h}=@qg1ru&DA~f^B@qE6d>1M9@V$4a(=btAR?3YBe&0k{Mo?9cLk6p|{y1 z&gxcAYDM9?8Es!%D}-h<1QB51_@-nU%1j(y4>2+hF=pv$c8R+jrhR|w8)(-F(-eQ^8oGroV{@^Sw_kd=jx*3DAm)DP;#%n>fq_{n=JzTiwA3={qj zC-a!LDZooPai{dVD&fWpQ(Bj?WMykp0lX8D=Z!HUh|9oSz%pZvT6cRgE&r7PO>O(S znOP{vet%Gp4=)IUn8?UaD~;uYCusS_8!=EjRZ&P}e86sDhfeNvsn_(NYXTPUpSl^a z3i-WSn43#g=0ll?f`A$seB;$-aDupXb?+5!G{bSmsKQHMlrN_(@d;Uvct-%^s|58s z2_}4$$Do;l>9a)WzW1MIHcgItc+ZkCc{sSGABVdk~E;a*C zN4S3)#RJ$5mtYECL`G$Kj$VS4o$hky`+dvey;DyM!(0_Rtc)|l&UVFR9gk@&jG_C?&!|Dk^sfC1%V)O=GzOVaLZ=^9Mxk3tZb^q`z zgsGUpwYLX^5LZg(d-^OXH~#uP>$)1NAV$=r<)I6b9T(k201b(rX{oEg!J%o~K>7JH zkoJ{e<#bUwZ_9Hl*h2VlCyro%5#AWvV*-F+^cOjt5g*h+AX>JQL4cv}C8-n3RSiH* zE1xAU#V5~hG(K-&+LC0`|hgN{6$J1PpG@;h{$(^Q>NWD~aGUzufJm=<#u3yKZD* zP~eN@eL8;JGNkb=#>Y92Q{mqSgP77Wi*$nf4voW{Kk4Ua_I~l+PfrUNnh@r1H`j2k zvlH0Bh^J_uGCi)V{U9*uq&&?Ol_zE1I=hqLi|4#qwb|1Yn(0dLUQ|+N>+St3R?&-I z`}PlQSiW>}<_^@+qHtn9KJmcJ%cA&**K&5hC0E)Qv8gnGzTPF2T3gd#fI)$)_Jo4% zD=RDh?|Xsx8F7R=H!=f%-3oQt3PfOn=7JIXkpKftJX~&KDCB4EHxU{ccrH*@`(rT@ zDtVl7+vf}XQc?1N`5F(^xU(ZWiM*Kgr=y~b?8Vb`$LA*cNl=c;h}=~G^mz`B9Ms9< z*L)Tz0{xmeq^|yQcDCYqZ-e_%cfYIo=dm*Ea8zp!u71xUgP%#|#_4;y#q+%psaD%* znR;P9_SRL3@Z|+?Gy<*95iK$oe_?u{n!P69%8i#u&95!n z&C0d9ELYX#{b9M*eFCBiN5O?9U*}I9 z$jMTXb#v1K5}J7>=ftr^xl)}l3?-R$L`N1ag2v2AiKNLUgJztN*EXs#^zecTtpvJE z;#*%yPGIM3g$*7?r-nI zH?n(8kztO3%J)-^GxVMnRxC_+Q*Jr!*t~HeIBH*L7K(vQex+~tZz7AzVAD|MAaxz- zBmSFTkQFWLQklPalh#~bHcjm)B@DDlKE>{Jy)O-8l_8G`6B9X z<(ju6-a^*tbj9*jeuzeoX`k5@xznBF!hK%7+96F~J1Q(tJer=O+*Y^!IJ~?}JIg8M zkWVH1p$4f(qI4E1c~a&F3T)_Wn(LM6HQng^_LA{Lj| z2rjW*??qU#Xk0%sA`Z_u_+2H|hx9grjRMS5;ZVJi zh|+83PM&)oo_BpN1M~%bPW_C%Kp-I7&%fnmJGz2_j1ZW5mNAWVu*(6N_0? z-gcXr`)&W@O+#?_Lhm$d>+cm#U~_`Nt%GVAf6J#mMSTpJ?@RwC;2_dGj-w;b*q`gf zAGxN~Kpsn9)h#(T&^jbZ?v;1soF;?_)gC_$+@+p^tj%nl{%N;PF zw8h2UuV~J?k36X(;<&Zm!WKY&#GGZX5Ba({?wOJ=?`=*58OkB76E=HEvj2Gj zRTxJ15WuxG0-6`Q}1L#*`!uGjCue0IJ zPxdRcXp$pXghgLI$!2AlO_fO1c(IdN34Hy}s{w=MW{?O>@<}KWfQW4u87s}9JA)Q>^Tk0joo2WTX zypC%rE`IlCF4mHYVEA_+Cq+Woob~mJwX$-IGjq5l7{$!YEQt2$BZ;ZCb%}|5@4FAq zA@Yv?!6Tc$=I1WCYX?qt8yZ|vbT3td z0jJMW#63Z$ZQiCSzV_LcSZC&4c_3ig|AHc2+<9~jdxznBeNsiW)sIeP4Cl7xTtw#+ zz&|nAyHozM-E!#A{>JxV!@$qLzxX=1rD$Yc-04&IhL%-;c{6+i!9b$VX(G17LKaU zz4oPxAkSO1$26o4`~AUBgbhSPL)7b?`qN@u#KO!hocp0NgD6Hmh;|q@J!ksBO`uJ? zlpdmp)6&MXLgvwtA;Yj%)iO=|QAr`eW*%EA*G~jIy?K5i!U_~aBVBe!uL(z%=jG5! z+`=pJH#`}3Tm3P^BtR7|H@@=iLEfmty>!N`O0^)W2`4o=wrcHCcaT$G|&Z14f-7mnv%$&b4tX{-TbO^9H6i!W>$*n^FJ}X4og>N zvvW|Lvh|GC{bmI0S+9SUcsNAyy|B;c#1i!o?X)49;qfYCPYc+CWW@Hc(}z-QOH2Q~ zFrsoJ)&8V=-}Z@yFF!4C98-=j0xPtB5rknMnOsIi7;7_210WY$kdMOw!1~P6=)e*~ z`}4HFDXCm4CXcnXwSzxR^AVo<&bm3-{N9V=;h~hh%F`sl;va+ZR*jhFmGZ=Z&zNXc zc)&2YuDbL{i$IMm}}cOD1Q;4M|t{(z8VDMi|-*0B7r5VAo;YqmtVF^z|e0VyK4Hg zN!NE2Ux8v?Q;xhAn4BQR!L5zNIneL4HIbb=FVqxx>~_56Ue)QHX8%xmZ;mODHKlIskIvPgRx~}$#ZnA>reor= zj|?X#_SF~pNx_x5)PDiI$>^Oou|MM|YUgLQbhPAO6TpJv_IpF;QV9MJQ*Rv=<@ddR z4^@0mYYi?v|x zbMLdyb-k{AV)FQ7?ypyg_#Y21KyZ<=7_y_5kCjQOfo8(}$1lfuLC8pE>k^(dNE=W= zr!GtdAMJq2$jBxNHI5n(8cIq#4PyU<`fpc{DK-lxr?>RB5Z{aRD}^G$3LL5)nG0GpQV2=Z?G zasFYbV<3ZlGKvO0F5g_rPWu7^S-x4CtmU{+cE?%DK!s` z)#=$-o{m$;rWf3E4i1n`OHJS8t?Sd(Wdv_NLjKh8)Jsw631N0icu5}F>7cbBl<=UQ zzYSe}{~_}KHw^f5e}BIbAgnGsJGdSjabKt|3!%GDtcT5QxtxuFq)tap!dDT`k7$^d zn0Ow&Tt?D?O?h$ou_m@dWZ4}?KyRQSlFVjDI?#c5hz9B;J5a|7 zZ)Xomf5i7;C&6ks#YZtMn0ElvEyk99ly%#Bkum&&EG*6s83j5G8v4Au!Wf+&0JdnF z=bC=tG=xu&qoM#{VOZLC`Q#4>YX)>$%CI;PU=&r)vcx+)2J|`L^8!Cs4i^Yi{!h$$ zNyP99=k7%~jr9@(1e&4)i;ytWfzc$9yY;A3Cip^@W0_cfl6#G!TD|oW^zOL_#2Z-a za@a7*Q!J(j0*b*&}-g3-mB z9INnV@B!9IpJ;)s>gW~YD!aY)>`e}!R$}Lkc7c-zfmNJ&m4iq1s&95{B+^VH2{;$m zXvWE)6#&g>u6eVMYgB*{VVK;|SiS-#A>G11TV!{4S3Z_{()|j#98P$-koE7|7?%Zv zYu~d?z@wv%l|QLf5po=;C}l~N)dKGMtdOskDRIn+@XcbX@P5%r(?&uTf}?yGs-_}4 zr#_(EUG{#Wd~}>=Ojj0(g{Fm1TC})KdHBThcPO`=X_AHd2t-*(8H<{hX0kfUH2 zEyx>90-U4gGr^za*Y0@Q0*dpkYT!KPaAhry)m8JP=Y$_bS7Ua8r8f2Fk6b|X-3$*% zI4f>$ZZ{lr&o=$(0Ss?#V&|NnYh{mw7>_PK!!jb*Gfce@6O^iQ{nC^ErKILh*7cR& zzt>zr{Ea*mo`JKEY|?@u$qO^PN?}~asb_!OMI*d^%#-6PRDLU zvJSRthA;y%W87wG=dtmYjZ-saD7>LE#Cz%zHN!D<_?G~WbMHdKo&QrMAS!}nE8I#x zjU`%xt-i%0b9VX$YPjZ;HvQ&uHIij_+5y?{|Hzay+v$`|dgLMce#rB0xSf^)(@QkN zW=YjdQC(e&Qblp!%i5D1M~+;BoEZXb(xH1(H~-geQk3}5Uh$_o>9r#4hKeZC_S!+R zSj*QKj^RhBiqFIctHO-wDt~SYIe(p)u>TpE@Bheg9mKgI)rk53q}E&dfn6%lsn^ld zj;+y2zP@?L_)&9|jW<~cz0?M#8?2iZ#Bh*GnqranMYdY={_7D(Q9I56Bb3+uom_cAn6dWZrC(5}lTH0h`=2$(et)qhuRcvTz0DA1j<}IhZW5(HV z!u0I&$vxoG#ISJS^$yF%e*^7DkI8#fjboR7c~V-VUa_?+{u5i&n5eqcl%dnk_PtlK z@XMbcLMK}9Mq=!HZ9lnZzY~5~S@mviS&yiHF|9AWL14~&kBO|%7#S~W%uD-OJb>x2 z78g668R!-xT}aFS=1oVfM$ptvnE#R~rG{rqq~DC*yy&&}Ab)F9K%Tj~_84Rx&afFD z4{feI{+x)BHS*PMpxIdGxFUf7e@xs1foE(9Mq)m7N{ zjjegn1H1&5$OGq(ApM}SvOF0wkuOejED)%F;YpeX;V@lkQBiSG5%HeY198JsTY~(t zZwbnRe@j_5*A~7F79)Lw-`?)-Hl8{uJtYHh)O6c=JTb9`*$pfbC57g}6s>R$I0c+tG z*L&4n4gvFnH)b9gc+NI9IW@nhySleR_j{kw@Q`1e;;^+6Jyjh0(RnFV$a(x^aq?)U z@-%Z}-gvD@I!h%$Km+atr%2-vZ1$--iI1n_SgJp-h{A@#-QVHuul~2+D0*mu#lA{~ z!7RULV+SBqPe)cigr)duYA>YuZ6Zcii9wPMGljI2Jw~5$BCX(Q^yE{Vi%m<~t+k#~~z#LueoibJLt;X_R zJrQ#HG;psVRS`?S&ihsM?b6p5@$-%qWn>-~$BYnhth`Z>)Q33A#FdD8q1BhM zD)K#2Qcrfk>6U8+c+3>{!}H}WGk(8^#Z+)HNQ7Y4U4s3l^^p0g%_n^p>R9`Pt!OZwrqg>n4GCv+?-7oy!EK$xnftXYS85#4 z>%(WuaM{_mL#Y0obyziU1fENvc~{5SMAjdG(a_iG zh|Fn-B>Jk#j%^n}E@mr@8?9e)Raa?@?w=UINPaX}zgEveU!}okjir4Cc%L3G*2|9n?op;zm z|5FHV`J_K)i=3jx!lWPDDs#Nbk}z50Iz?5K%VvFMgr*e;*o_pl?KWghpOowOi5uQ~zzH?X)i^bVZBODv$t8)}%JARXR6LGY;?vO2<$jSKo zM`Lk}`)JY$v!V~7q9J$26q)wls8 zUAAO0xiTUtNr;0(Y&V=SYSh-$xiiuw0@PD$D6d##0gdBBfZtcXmzl%EGx&>Y!ua?x7o$INAKSc< zlS1oKYrGgUF^5_B4<{XX&TBiBH3Ji2T9;T@=B^3b0^uZ{g^M@0z6EPqe{!0tmn%y>F;Km-@u67+W{eAss7IL0`9#8epPX+eruWOKfQGR&3%d4 zoBUi_`G47k9l>0G2uQJ{0#;F~noJ0Gm%v-SdD(PksgM2h3qxFZcm_v3VU8xp&{u-1WCD%n0Kpdpba{Y#Kl>^&J41q! zw6HqOe+#`VbQ8GdwtO=WK_I${Lx7H;S)}^V><3zkdCH^2<5f`>GFl zei+#w_nBDrK%l0xoY!oiM;a0&M|gRz0dh9VqPDo5=Sp_6xFV2d;1hc3p(gr)^HK{i`_e)^>FFQl!D9;2r08M1}At$Hoa zP;CFJL$c@`cQ-e`8?ycTlkhhz`9R?Yi+beI`F^o6idO*Qa?F60OkU#>!u}|5&Ip2C z-u-f$J&cf-#IMQ?4jhc$z6G3_mD zG0%x8nV)(o(U87M)MXy5I_xy_6aTfo>69((+OgE4a(Tq2(#MmGm^{&dZXvT-4*)Ub zkxUxmJ~*w zBbh`8E}C3R2A5RU1&=p3HE=OYFphE2KW-3 zFUPW@>tGRjHC~8yPDmX0`Wm~fM9uPZ{;^=UH_B4XXjGTeF;{J$2Ak~U^A@O|lYKw+ z7mEwV^*ES&ck#9Y*f9`pMRb9BvvpeyVr^D0JvF$RkAoX{oEq$>uyES1*49$Z8v8ZR zQRX23?8k%$>H4Kvr@Hv^3K+a){&&?tC-_oRw@BW~au(pyOeX+RMD}C^l{9aZsPymm z%Bk|4i4!EHrJq&K+tqs@@~*g8@g6;RrHf0)A#J{azAdw*?zl)@@A*!S$k7m&oo7Q= z{Dzw_AQ092u6EsBEv*GbqXKFG3kA!8d#=6-_q$JIxZ6w>6zk!z^~V%NlVMp^)4;c< z9(PSUHh5!SIKik+6CIZsF8EjIm<4nnHz5{@CvV*`K*tIc@}q5I(U)nj|F!5=x$n_H zT`3GL@q;T2O8_V#9q0UvzWz-BxMxdeqQ-|bHzyJemC;r<=XJWpfOOx`NO@7x;z`1L zY#U`pZ-DGNTx#+6KjXzC*2xKx_xtdxxW(cpTgAvG0%EXXMHt{XFhXM&l3$wwTSQd3 zuflo61%B%IwcT!$c+as;D4fRm_N2+jZ?y*S?rWAkcT$|I|I@+WUKxXroZ-8xsxs0& zFt9)Yfdp*-M10CMd>Z$!co16=9pQzJ#A*WJVc#Zi3VLDC%i1;?IfI zrf-zWQ;G|`s7FJEy7`sbpAAD|X!$!0LG627s34{+E0WgmLx*|c;<^r3lt5btiVpzP zM^z!z@tR?Y3N`Bq4FDQ9)#@Fyk4Ux8nwxOMC7%iK8{Bg)p_GQM;fHOYUT7TNaehfD z-DmKAqgNtbECXEbR7bJupF~&a92ncXMoz%g@h85I>}IK!B@^a!1QT#OeV5$v(|)cV`;!^vy2;R|TXak~|KHp@Zg z^uz3#GMuNu&N%0A_UQT~8m?zYWtSU>yt+SEnp}xHqPrjbqk#5tbtJ$xcw^Y=C-#5g zT$ZO;b*ogUkSZP#mt`ugbG@W$h@DsITTpX}cV&qRi$2l(mXjX@tY7P=8PHrmAId3W z!spNC?yb3|IzB3=apg-oXKs+1ne+y49S7xg7Ye|5(^K2iyXFj*^jDSYE3@4+FHMz? zV1dM)>I|`6si{$K&8vLTP){HnuM!&_Bd_^7e)AT$XT8TH!_g;?miN!?G|+~h2fdxz z*wsh1nmjErWXf+)&y zb`5{~4>baN-vuW(BX!y8JT#T0d@MkBYS5tUu$DnpXWqAynI2tN#KV?D(|5nK(*z({ z$B|5tz!s`L(6`oBaO`wO6oXc7Uf!GA^BoCqwo7GIn_scPw?^ay_y1nm})>; z$!lPr=@_adwYNmc@!=xHtcHC~(KeY}M>0C;Z68P2rK)jZLHMsKZj7z4^nv4XD%NXjmfusTWJtqt59I!Br z#s{!%PgHn*!rmOgya&jmR?aIp0^HwgVVz_Y*2EaxP<*p!jnom&w<> zz>(Zt@?GuiPvG?4xAVF`G(tpV{9V}g+xV^P2P@vM>!c0eegZT4a3<*`1_n|%&{g)m z{Nw3#6Zk_U8uy~!*H1>n1uB+vx{nEMU4? z@gc?xHu{ZbzeORXGKk@8_@O`G8ocTIhibVI7$eotY9DL`2}Z2@CDBcCNEolIuqN~`Eg_9{Bcc#i@V-(6luhq*95OFeqgob4A3 z=M_vY_{=`bQ`Ao9*|R3ZC>Tx3$SAG;eLltbdBCm99RoDI__@2EXqv1dL-#0(TBjSnC_)eTg@8;!z^kDu%5=o+nx(H>35^#9Xm@|3)r`4nFnZR}TD zu+p%xL!i^cIa9+RN6XJG)vtqcLQrRn@a#W$fLkLqlQ5f9a_Wgs!PuT{TJ7@g3r2?5YUqT`cnSeSK^^pr; zC~!MTKWyUPqWOOg3w(NROj2Wd;coGPGL%;T2Vj01mrU0E!Wq>WY>ID~U`Tdkf}Lp(tz4#>@yZc_dLc832=6lTHcizU|;MoT@)VpP4r z%ahs4LQk-GR_XSvtic)j^ttE2$_OEgB_uR_Bzho#eR)@yeV|z1q#rpy7l%#9oyqyS zj);W>ohY7eAT$nLDWCJ+jQeQ*g=iGGaVuacE{-7W+MV6x)p_M>q2sf1 zGSg)uJU&vXL!hYSTq6!@i99~(N}joj$`*%S-UMJ{Q|FKUncH3UKE+|cncr~hn}sB3 zNa33D%|4e#=k1%{+TCphE@a6VeoF4rqK`q#d;%fxH_HP0q~lQ8^c<8Bxm;=2myFVq zwh5;JGW|sSKqU!Oq)y)pB-nUrExgkXz8D{?pS_`Qwy?Q*@F*`Fff{7zQ8sZKE)^HKb5r}OvBg}+*gJX7-Vc%JEB z=^X6Sxu@`S^AjICVQZZ4U7Ita*Yo?N6)a6KY}Mj$?;u80A)by_+~?=&^Ll3w*3C;$#DDnWECj!j-&=R6{`G`M*UW73hgN>xPm!16*URA&-dlf5_RDtO zjN!A*;lbhI;emmd)Umk>T>#^mnmX_BYj^iu>Y$C~*FsUz?A>jmdYP0yFv3?wCB|~r z{a9u0#J&kgz@BU*&O)LpukZ84M6*wC$h|$pyLmqvO|4$V6I=xW>$XurAgaKk<|kgT zZ#EKm6`SSgHPCPF^U=rC@=8f3iB4oWUh}5Ctg6!Hd%2zzW!w_fcf3-t(h0aAd7+e0 zLXd6j=IdRQ)D!l)%^y)OFbd^@Wt!#>Y~L}VzDKeHiJMH3s_Ci5^bA&^*CwwW7%Ql z_-&}kC7PA(96{B?#`gX`NRV3{7qpJVo7i~}r>pB6TXzE*5Tc($+^NT8LX@g*VJ0P$ zxYSSqYA!W)8I{--!?|3bkVdYyv_j`!}z?siWWg5U<4Wx9cvNH_bJkn)7)7Lh;5n7zlbkf zSbGMU#bSm%imB56tXJ|E(e-SU$twS;oB!<3yD~EvRo&11%3p%qJt|r)W7iJALaD9> zv@q6im~o4F$uvODvJ`%^edPqu%K!>e7|fsC<^oR>>$(EikS0_s3^M}E=?2Ds1z_o^ z-aTiK8UU05MAU*zBu_a&>TPVe4*-s}43qj_}5M55X@_=X2`J+lK45#YIZysiEaey}pN!7&=Y3JXvK zT0fIP3q|!L7g3sZGzAwDr}iS_U6SmQ=%?=`yFl%kiI&TOw~rC3b0UprrU^d*ZEpRe z^fp^S0&zUBVVvU2xp{FASF>YpcSaLN`w2O$t?|`9f3d4IeYBg-T>Y`tRfpF=Nl!?--p{bk1qz1dN|}>N&_sW=kpMztoix=U!VQOH-HCS^T|En zj)5s_@*PKTOpaa|_n)1vCp~&f?-dB->mr$d_&r@R(w1=dSvbs<%;YV${PY{GwrLU7 zeceqso%%_rkUtUV(bNaoDycQ|8)lpV%qOL!tV{HYCxVI>3b+ZnKI@#PPE60LtjYqy zJ9j=`Hh`h9tuqX6f2y8Ap5BBmhmpRap-rAdju4Dz4MWm&eYX6pY=y^1p{ioKGa;?N zfoGPSVHubg^=jx)<;}jQ=dT!?4$QEB#FU_bpeQZDVW*thgy{v}E3H*(+wJEC8@G`| zJ6Q_Scuz?T(0+5t`H^G{%kz5}`g10Zt=lW9tE=mRlN0G)?KtFL>`hk~*S^~x&Fwgf zqV{?Sr_cN|g!=Q+pxok@h|O@5w+TP!x#IxK@Yuo2I&EnEes}zr$hI+Bg^V~}krEEU zq1dZmcdpCH({#@zB(K&W;6Qsj$^y>xu8qa&3wk~@g$ccI`9cNvUtW@!SFsNb&Oc*q z;#)RMj(?|6Svve2Fg%VwK*yP88*cKQ{W<}?)0o7+f-aeydHm}_cIeifn_cd)(zvnA zVBB@QcxlhrOij>1Ijc(6<$GxiwgCmDp9^%8+nx-(BEyf6DbqLIe{y)&uDJ{&#Jkt; zioj`RyQ$R8fBZ*E!JZ&jW}467gyy#8g}L)?2VVL8&FftlrVin8Q?7(l9m9?)xqk5N zv*0HzYp{)j14yJ5^ahb~eJ+hI^bezZ#Ffy!=p6Q?Bq%OXXRtGt5D@^3qE~D5Mw57= zdnhqYQirR%gZ5_(Kecy&FyWBF`l2WD6o)Zi)ujTSU2Aw((mEE>hnBIE#%O!Q*a z-v`IqPu##y9u*=&M=)o$T1kS(W|FE_hc?&B`tFA zvi=(W^oJ!dta7ApSPXH;0bF5af1#^zGvPc{4H`O1A>f7c6I)_d=SJ!Hy95+iWG*g6^Z5B)#-(u21v<{Tbi7+L80g)fZ81%?taO+dtrb zFbnq{R>E<%?^!{!l4ZdO7FAt5zfwB_^Cf|LBWnVmE0I9t&B_-EWYqD{Q>C7Gn=Ho{ zTpkQ+jAk33;!ji_6kCc8c1l(+`y$5WfZS@qCzW45pzYE&Q{KZ=@1CZCm0;A~D(Li)>m$>*@hd95WYWi*{dY^z>O`~bh zm{?Ylh({MvH5peLVgrG^h2WCo%!wo{^}elkP1|;H{zyw(`AHj<8kIow4^0i~2?@8U zyUv5+g|ira<9+r=gRk~Wt#=XJkRAWa;Oi-Kzgc%@q^HNii>(};8i&raR9MT(M6wen zmlzvuP*K1yj|z*;5;QVN_Rv#$Pyf4Y*pbB5f&%~GA-u+t2{Adrfowe{UW266#a+?g zS`T_5BK*yLPF0hSc$2?qU(J--TTCsSTX$P%e6laE-cu++2`NJ!vGN%Nxb8YWF^3BL zuH1rqTS)o`&-aoE#TL$5NFrWa^!moPH42+eoUV!O9W`Ibh~6V0o2*_=q0kfbhg!WN zc4f69(bmQK*Xk#^Y2K2zmpdOWuY{IrzvW~XJ#XTFWqvcbxc)7TPkYLF5fOWJ$HzbV ztDu_UiY9z;bz2AhwRm$jdPIUPpKCAp7&OCl-OW9v?4qO%7X^)7PDs8Ut8Z zZ@azrJom9(;P1NwJI}g%p?rm%NBi<_5oNc4KYiOeh zRWmwG-9v*+x~@?IJOPhzAMTiH?k7(J8YO{!eOrH&tU*1ylaINyuJ%_R-GL=Yj@J)q z83tD?ZDwH;7j2c>m<3#LIvrnv5)I+%=I7{_32>0Y;s>X!hn;vDhcfriPD#u6x` zqFJp)MOrstAlXQ!TV*H(#6-rYR#O07U~uDKvoqtk64HKxcXHSzX-h$l#{4j(Kobdw zG&S-Q0oS}D7(IdHiR1)=c|;y=$~f54xL*MJ+5Q{2Bf&iCtL>?y+%Xv|>CjugE48SA zS3A?rF(^_*DEJ_SI2zy0G{|A|*~pF}%bG+4VMyKQF}lN?_UC4}|lZ0k9Avuqy%kXzAP+Z6~$8+)Ps&=1}t{kHzd z7=?FLN3+P$DqWoAbDeu=DipaZRvX;JObgNtuYLlZo~fYvy*4Jud&^s#^EhKD$~C7vs;jD(XhbF zHBVf%=OK0^X7t~=dFH*W`>QN}TR04bBIG#_pX}3LwAJ(gQ&7(9nGdT9B!eG@BBtxU z(6bMSY8{l!8b7EEh@7#VNvi99$bb4a4%H?2B)$ZxBV;#xh>06r1OnN*&#}+A=7ggB zcR(MnOK2Mg$Q4G_#i88gEa}qhZVS)5tid~NcvvZ^=Ot(CElq9to|`YCG#y2Zqs3R- zAX34)n>taec+Bvb^78h_+()2m0@3GyS<#nMHtNiDIYM*bbhS?CHrV?mR2e;#JnpgQ z+x}C0&|fs2VoF!I{;S{TE3gc;4<;3Odpz=$z-VWX*P3g>5!o1JioT~Rdd1& z#D;BuKT6;n8e5)*^hX{8@D0z4kQG+r2cd~!m^@+J&-n^88( zH1J|l%U^0BVAU||YPukw^F0eQz4!36q|_!^VTN_)f@?)#44;}f;>ZTsxW_-~eH66j zfP9#8Jqc#xxS`^4|J?yMB+4GkPxBk5JzHu%2`k;jP33C4On*gQO)w)14PMF_$xean z2lPpcRF8~Go^@}v@m4pEOy}_R#DAwzi*As9H%E09f0jiOql`*Vg`Q&v5amg$(xH(Jl9bmTQTqg!c@^s zU|dLYSaO#~xKtp@a$h@}i2|zJ$;mgwkZ50pp#qNF-^n+^f8!dN1kqqdMj)Y;A&V8m zXnW{El;Aeejw}5H6`H9Pq_6nRW%X%KHEA};PrUtcdT_N;(ZsPU7Y<9a|*kQ*#=K@ zog490OtD92&v~-1H%+~>;sgQ_^&D(YcqkZIkTA-0uqkHv_dE&pM19 zjR&81=9M4=&+jO*jRh~SJ8$Oa7joiLJ?H;(4X}gc*q_tBmu}%Zo~%}W5R0SNP1>C$ zlv*uumD%bWCL9VS4#_HBt2;*f!Bh=vp>iicccoPT>sI9e?t$mfC#+2(YSpJ!+Qjf` zqD%q>H|3ahwLS+S8-T4AA9;_qDQk7mB^}J)l6PDZsU9uMnbYkFqZzm~Vu-ZaGK``M zICSfj!V>)vei($+XrU`P_>ZO)trjtJd(A)*_a$OI$Ba8#zl7qeZFz-}n@6rSW(_D_ z;hBV5-snP2=S*lo9?m7ZHU{m~0|R$F9pwomtiyU>U}W=-2RSjcIJfKM$eMDV#6>e| zG_$(qq#{?ntfN&j{qbyMfnUb$d_-UC@kL>j2mR{DegtdSSmdM1B#i77c~;t2pC5T> z%xoo$Wr=UF%xIoSufe}$d?$buCH1I_I4aAe+IaMQE0yjABg#cC=9;g$rxo$Vby&Y` zaB&QqRPE;)u~qn;XZdeh2-pm;Z`Nk%Pupx!f0B&}n@` ze|+mr7clOp7Z~VZO&yXYEb{T;=JOpA3Rx*Hm9?Dgkip_?}Eid|LgiS zt~dl(u)D?3UWB(Y6hS~B$&li`4$mdRfR#SpZ(pZTn*|}{Bd9YQgxmId!n0egu_Do^ zzPF+59$P$>l*%EIu`3INlBb+K|GX0%8eqy7A5=f}W0Uwz_`<3EAP98#AZzu6Ahy=u zK62|fFhyo#73QW!{SczL$wL~^bt6XbpV7unKSa&f283xEMKtcFGW_$*Dhf9+20te7+Sm#sq$R2^vq;`|J(IkkQ* z72hM9R3Au!1*usxa`;}>_YMq=kk?=^R$|N^G(F1~;bmVW0R*7dY8WUd+h@}3W43Yq z=>kXQt5h{H>9yM*Q?&dM?}WF$AP3VcPfpvm4J?EZa`{*B^!96SO@)whiMwxtpCMsh zur8&1lGy@{HsP)=4Z1u7yOH{p5u*%e!%AM8&a&z#u}ksBUAtbYJ?HFP5;ELJY?a4H zb=hx?>a3NtcWMg>MXw)v#NgUc#C}Xae~6^rHqj*gl+aR9wuj}@BeySiYEl9|Bj2~S z9~xJr7fabjsLJ!AO?^6!@9+r`>WzD8O8g+rXSmKycTikGQ;!dA+scF6K3C3gdK$ln z$!d9mz9h2+AwNs_`;35F>tY}Hmg97+YJ$-#{~kSq%=50>jG#Y5KIc_Hpy9&=)rS>0D&(IVc*Pt8#_wogNx0DnHt$P|ok5Q5o>8+1?9;GtBxhQGJ0Ce^{ zXe+1lbR@#7E(0DqI{W)^`;JRj`0*aINVqwk1^ZdNQG!`GGJq@$2Fi-$VsvU_>CMOq zk7e3d$1)y|k{hiX&6qi;Rfq7wm*x&Uldx?Qib6N7_|p|p)9Jm)KRdXj&=SeqiI5^_ z!e=4iMb2=#nUgKm?7&ST`|T-U_RtsdGV=hXSOiuJkxn&K+en%xB3#jDXQVKcXy-p^MJnDHai3$SjNXHx~t3RFGlG zXG%BCf%oT0j`OM|Q+HeCgLH1!=bakj_fa}uR21dmNAOm}aX3ftZKoP*+)#SMZg(sN z9!5x|L26(Qw{gSC7xXLIkMt7vJcN#I&fQ9hw2JW=9=%_#F6w|{Gv_|-^NH$<%0tr{ zeQMe>kmkSPRdp4<*9C~J%&Xr4OB?7_LMWilOdDK<*3;ibshO#zsH3V4>lIXlPW)U= z;>qGddgBWU-~j*iV$TexmTP)-WKJRpgkr-&z}{MJp6={_Ma69ieZslzs?3aQD~m&@ zRXcDzWqP1u*wH?{0CKDd zO|t0Ug+f}aG58}%36hyIsUx6v!>7(hTlfZ%YWv=}F3Js^CVgck3TZobUGYQ%IQbi*$8$RiR)B zw&aPrp7L_Cfoe^C=&n z$;(G-zXx%I)*pHJH)ZI0+1C0IYi>}BU&|8UV@Erm@dZCcW;H0Svst|LlgvP#A@E_@#}=8a$ftfVCCpzsmm-<$g|C zC`R5xUNwO+0xRrJNef>jc$hX`we9M%>dc~rUo?`c*WqgEq3SY*Yg*pnAJA&OJT@`* z7WKxS?elYp$b0X%Tn^@}q!iKLvXNR+i!I^Mc=GI*dcey2`E-HHNMShVHSC@K45B%G z*67CvbxJ|^xrDxI{q=OEDjrfyH7(sHb|A+D zbUbD%tiyD3nZ92+i|B8d|9ClttOMa~IlfAm=|#2Mu}GC~_`ta)RwG{5P0?>9 zM_|-+9xy@+?HX%S*0lxr%R)o^HaV=M#W0~cmkk94k^-0V`WO-+YrwVfX0%jjKXP)r zWB>Z|6Bpam$b1dWfsW`5`Mx%xj`uP^UE_6e<~}r=a91{NXhpltO^N$w1uM#G)UWI) z5VXDMf}zUEN+GBMdm8Ma4fzbsd=h`jU+eZ!v2rS=-HC*7ARL!qfZdJWF$q9)Q(EX! z20`^bY(jCo3(I^4r6{0xwHIJetpW4TWMI`fJICuY%I<5T+AF^vR%h>vUbI$9oVK^5 zL`So)C}Bo@H6nJV;Mo9&zb$L7o5qE0H0rg3Vj>WQ0m z^R)=T-tJ2|Gz(F$TCk1B!B=~E=7rTphZ7tCFNvvUPfSew!4J4Ix}bZ4ed93ZqvD|1 zeA_-B$>R}{}KeQWr{T6 z^>sC97 z!Br#OnucHTl=(zMMZ>`GTm&GBfKQ9&)Z+-M4aNUs0sbgo5iEF5Z-@OKSVOgZt{Gjm z%;?8BHx#^Zcy8CncsxRs=XY6BFXv9Ddl(TGkkEo6#HFcfY%C$UGbDR^)j-w0|Mx!X zkhX;F!C|Z3=T5H3p?YO zRiv*_22lrPrq3p*>gL&BF4EPB&AtYO15?1h-TQ=9wAO;lvQ1Om>;|@P$HFdBX@uM1 zK9zw>;$EfSTg|zzn|=2UPgNr;VNMJ)ECjfN=IKe=lE&AhVN6)xmFI9yv&kx`4y`V@ zFv35hJOY8r^f}z|RVHY|UXgC(+v!&rbRw(0A5L8Vcs>Ll?W?|Jv-6s_%aEB+LN)p} zDnJR$~uul$M7= zadx!g9?g}nC>RSaswL0%-_0D+L-)^v zpF&TTi1ZYw!gD7YIAkYttzKh%zyr03y2T#nW z2R2Q`f?2LTp`Lqg3yNb^!ENf2RU3oOKE7rb1R>eo4?SgWqY)Q3 z?R2%9!dMt6pf6l#A-iakn~dLnl?)TA#Xx@T!`nubF2*~b(VFpsXv#~(M#tUi%SUqi znJkPQqGKby^aA^eL_44K{=&ySlV@Fzyx$M&;BBv(@)itjN3B!yF+~UECQR1?=j1-q zP*lJ4ZzT5`U{~vYnl&m-c9K|_9-Je}TQ1Mhf{`SbtG0+po14SQfK~n=$q--%&-4=ZgY>CL z)U}5m{On}D25=nHPiHj@d9zF;{oUH$qn@4$+tHruinQ%Ty*A+W#?I(EAiUJ}{ksoc z#f5d$@a65(5(pvALw!{-q>udwb?MpP#vpUkCzf0+=+37+;{`@rTj!lytJ>+s3&iYfUDBiYSkyz4+b%1MhOKytrOV+mfd&oqb&Bb%rc> zb}U__y^K9@nFe3Y#ddnuiWwh@2k0DJ0@Jq}cXBhF{C<=ly5#Qjt+Y3KA{-lC7DLgv z5LXn(=5Of-HFl0yM9&atds7k~6Kc_W>Rf4Oy(ZrE<#BVeXQRNcM>ii-pV1eAqW5;` z8g~j%=eE88G4G?96-Ve*UCsVX>*8tktG|Dzb-E90&QZfwHW2c3>`!8y73$<{xom|) zB^^MNmC(RbSwaK&OC`S$RQq5t^WPVtum)0 zuT=_(o3&v(I>9@mMUXz?0ChAni!!umF)oHP0ZcOk@2{65(S*}!`nN7-iz|(yqA;wXwj!F|^@jz~bj4x;U(I`+ptQ0?=y>31TCl1Awae5Wcdb`_e>(&gZyd45 z)=|gAqt2~2Z$}6k9d34O2T?%h6iBhY>k{gza+B1e&w3a^_bDbvx6_h$&Y32an`Y2@ z#2(bB=@SaC`OR!0*zM>jo8HG$c*DZ5uHd56+hgH$glv=Ug^Ipl%Ni{i=x6JN1pVzc zJjm@}6Xtk7_r1lt>=|0fd4@(X^4I*si2*W@zxH_H!es8~{uH5)@o;+|yJ9lX>R-Rd zJQx7Vk9R1u^S?h#rH6YJ5H7FtR9KumbkIg$B3s68`ZK&A9+n5gPbzC%-ga)#BW}H& z=3Ow*a@x+rjW7FYB*GdA|q~z&CdqZRe2{ z-gMjaMZzUJjV7&ACo2NEH;1(+GwgpV6NB!B+IBa2;1?rAASuz-y0v`oL%-sq6f3JB z*I|kvU&wyru)p&R^0!dBFev2D8ok7xS@6OXV#u)~sOEMK*>oR?1~q!_=Nev z8pI#oIv;s>1u55yY%_a$o(T`X^Zm0&Kx62=+-{2Q!-Z|z6o|3Qe&R!-`{TYsETDd) z9R&e4{K|1*O5EE1q)sbBoX5I_YtZj|BEK3dhi&@1hL|BX7MA4B*{dpk5x;Zx^{MA{ zAG`Yous{)VFW6(&pY)O$e!0+zy=*K-4S_GYLL2m}@p*NvMOX*VlMI8~ZdynQ<|)X( z_#XcWUGFfxZwo%lfOGySsPd4~=#~~s248Of!ausN;FG+agf97e?apG>!N=zO-dJ3j zIg@-^gB=9A*7wpC~IW?^o(g$s`X}~Mr zatS@$jSOe}YHM9lf#1OD40?i^&MwRL2=`jDj!fz-Q%(-p{5RrF%?NfavVESv$i6;; z=**WBO9hs1#TU8Pm78=>2KxoUlVvHq_8XCJ{y)OrGAPRb`yXCHKF$;eX+*k176Iu7k(St{8>DOL?)%d3|Mz)%&+P2@fRW|ecf9JHBPn(g?y!8Z zu~)Bv{&?EUbKY)%D^}FDHa}na;msrk>U+Pt5sF8vE);QpM8@<&ql~!kAMIN;`}~G}ksa6FdLxzoPwI0WR#f3Nv^- zUl@Zu42svi4kkRQ4r{oqtn{^nWs{y4qlpJzEM%i})n!x)EaO&M@V%`+UJ@5ut|&pO z{SenFX@@MvT9F(}}Mb{uJ$^@UfknwX%83|5`N zlQNI&vxbR_ma+MLdX(|0jt0bT+A}d>ZBIAHg)R|XHF0b;@vJSB{%F;}a?0rnRqprv zqGxb9m>~1-^^ZpH<%?aq(PW(@x5<8b3^T?(Y?j;5#f|M91s#n&Ar*1#d@?P1i`dMj zu08^eG4I0Coza0^Xnu8~TLK%2Mzsi707Dfm{QXPO7LR#{!S9gI5lA4P>EQ5dUR>@$ zBqHRh!>mnhbPo_#(R=Dn*<<|5}p>4t8^WS7p${KyYlvy)-?Yq1=1Aa88g{ zT-@s;Gwdr`ds1vQUffOL0Fpq&@Mo&jLQgUJLPuH$BW-HUV4X3j~s_>E^EEbEf1#4ITK|W zX%8r)rk(M}>+RxY+6KQ{YY%_^IXS0*G2_mVewcOc32UeZ?Tv`mSFTj_WmC2t3q2}v zoCUjHr}MA{WS)?=+40`Ckv?1!Q>B1FoP$f=8(+R=$xdlxqaS_AaXNs8DYI6hfreIj zGnPFj^>hPMj`n=s?|UK!Mky-S9&cMN5t~bogNClHuhvm!j$(P@4B_5~4VM9D=oBbk z_l`=G|JFQN9}W#Udu6$Svo*8tr-tt>7Hc24ML645)3J#=u2iN6_p!IG>Vi9Vgf#pn zc}Yh*R@;9QZ2C5<>Zu#YR;6?q>LDI-GU+@Hoo za14c7%O(&;Hs<$t<^shp9H}ejDZ_Mhcm65HcLfCseKsgaD?r_)mqQLxZc9r`dAVK1 zWxkot#aPXcUsy>HLj?vl&V;` z;Uw(bYp`|dq8o3zVtiDj!xteTJ<+5A>-01O9=E09mtr~XMqSOya`v;=dwMB@0lR*k z?opB04$XJ$yE#5N9-`M~`RA8n89HaN*fvZHnGVOzF{E4^_plt*D~@L8@w8x{3(B#W z>B~c}okW=bYiHZTY*IH<$3vP2j~!y|j>!wTu#Qdkl|XOb?e6XzmUd)P6V5R~NYXw< zrTFQPdcaz5igM+zpyHUX&-wt_H{#<=3mfs#OzLV?0yPCy@X51IJAU72zB&W->#uUu z!X|Nuv%eU3OU{w{%J25%WP zw;~OLsIellgj#$Blq+t-q#1whxg*UBK^|>*^>cEb#)R3?F1J%(8?WmiiCkVhOF#Yl zws60LKaEooMkAt?1$qdLn0q%WhXe8`{8@b_em5IMrpu5%|@hoqZJ!_k;KmOLT zJJ`AQg={sY@gSuaC&b0@V0AUFcLHe??qi^axOc7CRrT$AA^f-&-7jvp#+CDUN*=eA z=BZCMHpWGq>6%sjpSJG1p!cz}aB$@Mp@DEaD5HBe%Yc9JKT)1Ig~MsNMm_~fJYa{) zB!0fQt$Dn2GbsOtF{f3R-!Cm4oJeGEJ;$JMKJJIrqryhAhd{WtxKroM_Xlgm#KhK7 ztbd+^|H)+>R89wD8C?2g<2=O(x~HubN68t7OUy%ph;Yyi(k1ZL!3@!XK(Cu)*BhW4 z=$+L{4M+8gDOvAV)fVy}XBm&Deg12ozihoek(@h!=RM0fUHe+}Y<~Hi22i~a&{uQz zjk~K46^k4l54Xz?uwN>N%@eFvL(Xj5%}779YO1MCU?R6+8@MDJ9BnYGJHf52jWcw0 zcV;Vl8hx61D@f9U0be;_Gm&^-1DYpWD^FIw)fMW}u3TzfR6xOQ)2diju09k;LE*RhFx^f3E7* z8(|xl(aNGg(|$fBm!96=<6>F`^Kkz-zBp`gRKwPH8rv}W&dt@Vd(|=mI2Y1J2%2ZN zA}TysqYC`o1;`UWWi}jnzST{WK1akfh-RWQ5a19GMar~RR`Qbwe@WQ#0=m+UZBk-j zG=XJG#>0%sKyTIY3#XYcW`SS2qE+^Mt0645$7FGF(WQ;FNA)eyqGHa|bp^JmWe2gI z1k_slGS7Nb@p<%mi@2jFqyo*GVZCo$;TTc?9|-*c`-D0DJ!tEank@auW*74|zY^_z zrLL85pIPhF>AF(;sdmnm=Y>MRT7$d2fTu&#>t`6~{)O9h1eVL&Dm1P zMo$?Bl)VauO!7>GPuW?RFSW>xccY-Hpl^|1=XwOULF>_KTFw8)aZ8ER?@#aK6pfD1 zari}?IH&*pWyk5#Mw0(!pNU-Tby4$1$xhY3F%^s<6>?`0l3tKt>v_k`WN-KL5vxGg zq}hLq@^W6Trs^L!rKwXu0e~qL_N7I71p-4bG4;; zRqD^eVPc0{nv4Af!^6eFXgLn2nrdw=4GnZ;W`e5IU@dhlX7#duZYmc(h2AyT+X5=n z`}+$wTGJdPCT2z7P4Oh!GUdls*@SP9hQtsr@uQ#Ffw4U|xYP(0rnOD2!T^+SE1y0E zzSV7l`wX7FuokjOgw}s2e-@cY#CK@^aSUkdGQ$)njjtS`KVp86Q<^vYeEU02`i4MD z@aB_F@Sw$PZGlb7?jBW#T>Ln8CG5HKyckMgz(%;e&ob_u*kv}%y20=-Ag5WbI)z{7 zJS^4a zlD2l0<*Up2sbnMx^Sv#x7N(Og<$9!UzKDIyhnx8(CJ~`*6l%N@IAyR~6iG)_9s827It zAbwVEnjVx3-T!eAh|iU4F8=-W<@dt0ZEttJk&^zoaEej4hEk`Vg>u`&U?v>zbg%g! z>CDh~hKE^y=)pKr*o%=!)e3`7Qt(_?d zrxzAP4k-wRo^Q+0`5zf^)cMYwXmW+)B@&QjlY&(y&k@&}APm%y(a}P^H90oE$J<=0 zxT^a4`jHXU2{`J>1Q7*U{O;bq9hp19vA|Qwt?J`I+HI&cRUvECfM+I-VYo~Jk+R-< zdUN<@tT7kZ*?W~Sx5O?73FJGtf1{@wFx#GuB0UakFdVDCLgy1ZRV z`NOY*4q~x@c@Hu7^DIRc%BF`-QA58DnF=;BZkq04~N7B#=C z5e`F-YtIc`n-0$h9|J~uPDnuE>E*+Pp2tJSu%Wo_N1uU~j`OSOhAcxins=FgM>7Jl zs(olRcfUK@)=xbit(W^-D%>@D9!|xtjt37GFBX>l?nEIUE|q*%svf<8Ru(NTU7;R{ zjOI3v$3=cQ732ZC+Hu$hj;FkQrvC;j_Alh_;de#E2jp#lKtC_`D|(t$ZI_YeJp#A- z`2#ZpMr8P)e$Oo`&65%K+Z{bm;!hjd;=Jc{?1YEeAAQ|YthBY1kj}ts4WT`D?kNL2 zqb*@^mE0WuM^hYuEw1%EE4e(j+H9WsMcLhkngraU!0y6J_J%N zj(g<|-ul9aWxXZA2GXZNZ#T|jIY_ZZ)0IC+!HK_oiDJ_u5faOK4}f|xKj%@AhHzTh zk=*?d#iisx2Pr%=q?W@oe7q}m4ydWf zN8e3$iEUMz#)|ho-9eb;RQ5L<3x2KGio8y%(UQw9@I!-L?cOnwQ2cnulcXL(0{ky* zgV*;X0|mf|1dJ@FB_b$;G9gy1Omb?d#Sf-6EK7GnwY}v85l)J@BBe+XuD`6tF zgzKc|dPzEd566kjH#dGu z!Efyo%n%`hP4zD!^DA!;-yp6~!=Tvp{p5wF*H)5REW!u z;^OC&=eGqz-7RREwtx;HGhI@f)l`&91tyQ$aAz0YeFnr4Yi@-dBFu}K3GD$Ma6FQw zl;aiVi@aEVGwak8nc=4jY0pzYS;*4nY{Ho2X`J5zNTJUQhuG{Ju(7Z2f|KB&GbO}N zj$6nYI};fM!|crUOrL@D?_Wux@5hwp?N`qrdnvk(!)xvN2*-h~4{c8WC_hoNF_3xY zynY^tSICgo^$f=>ndL-i;lw|~C z2jeJ`UEZrN)pw0iCD8?u-kNWQo=_F|IBrc3+h}J}`M`!BQ`RhawWx}`m0&SFd>$S- z83~1PU|!L;+9fmZl&0ds=l6NIMgS))F2|*c*gn;BW-B|JT8>!0BK=ES2E|`B#+}R1 zXFuH2-`O&mv>z_TKO}?$e1o7UI$Uh*Uponb^)$BY4B-X#*_Yw7U|@7i_w^?C@fVT% zIUhlJ{BU#33wIpZ6a{jyXc3<66Dq&9wli7o3eHRPP+A`B_m05c{`->WlIqJ;Beu~& zoB}h)tOCJ==f~yd8<@XQ%I})*<9SJ*k&AvcTP)C1iHGi4-C6^_UdmE4vKKBtGH?GZSJ!c$$Yo_q`Fi_XE z(w(IaV)BAS`=RMc%1N6Rqy;lYQI-kDUqAb=>Ei&6PgPirYZ$8+q^2*;6VmQ0>6ObX zp#c+wLh`qs5g+dV5r}RMHK}fBGWCEPL~(1!1#L$Hybw5f6;^(<2~MnI?Ihzr><#jM zz}d|)CX4oCVyV89Fj(w*rJWe9hf6g_9y9hzc|h#e_G0$4cnQ*&7$}fxUNUa|jPSL^ zIo5$Jddj+$hev~7mX|G>be`-wg~GGS4{nOjlr;S4jNN?M26vjLM{URedP7VsspR_H zmJkCeH!qKibk87PfSPC13#YFOi>j7_q)Z9y`n^NEEDQ}wovy$BB=2*>RL>8}zUnFJ z(|DFSE#8@vX|v@auSlKYPea=O4Y%)~aLlIJ)~S~49}q4nt&H@Cw0~ha3^ENby)Hcp zhY7 z@@MhCy5aaeh{hmeGN{n#1tA7TZE*cO_X8eP4 z%R{JUk1Xh8t8JQrvfl4p>HJ1$Rl*DenJW5CyjSq)H{E{@0kET$s~ZG`$DDuGEYIdu z1*(ao0jW(|kb;clyGU+*baar65TP@|J3CZt;eB>PvSbonEM2MkNY<3Z&oT7HB9?Ly zacObUd;!a$o&f_&_=NHJzU{k!3 z)^m7X_t6n)mee@voY*)!jO13CW=i-VgvtXM^lcy7F?kKqt2Ka;6i+nIFD}{{c9fP{ zJ!qW?{Wi=mWMuu$Qk~ylEO&9soXvtI-9Xb|aa*H6OZ$VZjO8T50jFtFl$qdI#>6u{ zE+6AKLR|0loG7m@_ajdIj)d3@{{O&e9T@|jouPfWF_~=2J=-2c*UwoAEA5TE_HNRH zYmVKZt;WW! zvcMzEL<2_Xv3}{{n8|p)PytmBOVblfMR!MEtbmq>`Va{!LNFCF0-1IM#rw(ygfFJG zt^0q8U$*kJ?k-~)K(ZztExC6rbHdTkBPsJtM+)^rDJ^om*J26>YbE4vZN+nU7}dkB z=f)`mkwI^|SIAxypJRaloRr9*OVVq?#os3<1y9KU^YiD3sd7@b1D78=F{K3&III4l zWPaaelPNP_!0h_zsV7dJ$K7mqm!vS$al*_`5Ed3l%gZ=XOFDxbvRIl+2|^CaEqhtY z!LMB(Z6yWV&%U87x)L1EvpgnTvvy5s@x*TeBJfNI-SlwmCL!Fnmh#(%a#B? zsfEP`|4~*2=7}tJNOqkf!!Wh9CTqnkba{~MfK5oIeUND~}4AGg_!G|aH2(iukf>@F+hjg{e~2*8d`i8PW~8tw#2xNk5xll3 zhmTG)A&D+ql~=`ed44@qQZpQ9H9kGJe>%@Ea!rG~AkofW0Egzo`Okj9iYFX1xa6mu zTv-+6n4Z}^_yU%;pUwIovwW;b@g$PiF%1|9J~6Sbvy8CISvkXy^hxGGM51a&yZl9pS@*slooG#H;YQ;x}>a3Pf3=Vikiwb z>PqY{Po$eN+#@D!@jS2XvWbqYmS5#G$Z_iTm)g|&cP=3^>d?wdYOHA5B4nHwGQg<; zyj1CnMa1FQ+}iM?uJ%ErMSpMqT#9bt43{U12$vRU1us_4ni~ihJTmk5-ZgH4j?7VZ z{4z;XkT>(Do(I$n`=sxllC-1s(A`}?_hh9^`DJ|KCr>m`cXo4uYlHGLswQrX^zr6| z6tmX&`zOSa*Ty&aF$pMkU4v;y z*dMS!XLk}Q=C5A997eW8PLsAA5Tgj|tj=79S*HsL37M#UMwZ~-5s7hJ;w-x2X$vZ_ zbhnL@M8r$D!VVUz9{f+eoTbz*FNIa9Tnn66r21f$@7}!^V#7jXhdsVfFJ#68aACq4 zhQ{uH-~T30Gxg}X{L4vmMTnMN&YLAKafAUbnzYvz8>f0$BzL#43sq)@2Oth1D%^K@ ztstaHvz#qRx@ws-FlyN$IKYuXdawR?Q^^fvEZWcCO6`)1?7PG!X!H?$?6XUu>&&$o z_`LB_Wn3qv?7RNmZF3uHmYiD%&1a7Zre9^ZVxsC%5`x% zo6>$6we5Ua3*&Enpfc9H{_0ES_MD~D*vrg&2T*S5Zdo|){3P1CdCt?q9iQ@H(vni* zegVZ>e5FS?(=+~hNd20NfVpN!AKyO|e85WlT!2qfDG`kO0beRlR(n8vv)92)yJ;JZwZ>%iC2y6;Yn!OXC{-%0c2;Q@X;ZcwO^T{= zQCNxpgA$Bt#&elGoXSKXfr>6b8>aG62)3(e7#a8wnoHEHSNycfB1N>6M3 z!dMlfD&GAb7RzW)?KdA3Dpss_7ZrB0VH5U1}bG8fZxw?1K?Z7*|T<~~g? zPMd{rhjXTVCPXi>f(oYLfq(}wtu?NQj{Ixe(%I4yZi>E{7Ca*SU>k(f92id+l~NT# z{d^8qZE+ozv-WwQG7fc|cbtQetxxOS``9^3a1)2~=&YnLyG;Bl>OZ>hmobcWef*vf zkii4$k|AgMeOfNE{NZDJpwHIEk3(+RrE;-{aLRq2#Tv<%*{3r=>0*B);t7pQlqtEZ z_Df!7VNJYhcPIJt^B3w^UcG<+fVLMdWuB7XzJ34x?K@Vai3Fbf@i);o=%4_GPQ;WZ(%LwZ^)O6U$)w<;x&5Dxqnh7qo@IyYY$9QHDY1L?ZWB z3-N`Hn&V7|S*$OL$piSDh=x!9e9Q3LUd61z1q>PB{;Ek1KG-n&#th~;aro3|(bD05 zN2H|X#@qJxSvdP7W#AJk`JKS0mj8ocgk#<1m)MnTwAzzRtL7sIRHqXv#0qjj~S*e?5tL$A)?Mg>nh{ zgGVX!F0y@DMnqN0rS|hkn=gI-UWZE*qKIdM+)S##E8;^0H`aZD%M9wz2e+g1k|^*f zE{_pFl}V!AJUpf+Cgc;%HZ?LbGN>r>w~%71Q!`~=U{jbqRZvJ8gY?fpPTGn~(~EV5 z_(4DIF8i;$Nib^Jr5kyA@!U8Lo za_14*yNWScl$y=S3-f%>5Om0Os()1V zXWNI)eNhyAW_dVq`asfX%kh2LCgz%yIMjOShmpgIV@st*XF)(0eu_D-3hzG83p_l} zkF*L9P5xI=fZ!SqICvPLGI5>3r$*d)_nzNMOVdWIaQi4-U0irJb6q5%l?}Bd|hQZEe$P?{{W=IXixuHzPM;=r9BG5Ba&6ovRb6XLv>iReetFAp%!&}seMJkBnRnFD5SD#+3~P4KxLWX zt1>0)aO2_*nG%YtqrMF-C@l=wpgI;M-dhUszhYv9Q&HGKAn!tXSn*7T%ipD=BF?1< zfX`4@+UDA$idI@H^XJ*5y}fUSNpPO0Yyjc^TR{+@s#sb&T3W_qQM)cw%TdX(Fz|uF zDV9{>1w>-rXW#sc4|0REaR7ZrCm9*5u?_;$TJFl)v<9Zg6O7P&6$M(*My|v)5I9nOb$Chhf-4o64VgA_avjfQK}@ zK|YK4?g=5(z>(r$eZX_I+IM^}LJ6h{;&XG+0)_^<)e+$&IY{NFw%FA3q$`gRc!ATv z9n;`SP5i2d2Q!hSuL&bfGfDp}In$j}Lag!Mr)RUFII(*1ky0pu9Gb%`Xp84VZpsUa zb{xGmtSTxhu@_BmUFN;Ly%C`lJv2c$XtFJ1S=R7W4D;K(GAnC3d~G5@JUk#zwJW$c zRsAMUX+%;Or!CX}fLedV7bLX306^1jG&FBu3PT%=+9pvq6mW!bb3ey^W>|I7l-84} zNsF`~3(L5BDecG>TrXgGB4yfPCr?BHm!$7`=Kg;(Rcc}?2*uMNwP|6-`JkUpRG>dh z=~RN|oe{zA)t1W1thOC42d<8pMg94y8M#P+b1fjq_l5&d_W(~BaIeP01uSm@@(i?= z8(d4@8Pec|e9sv{1IeZUW^%zmVG+tZpwWSrZmiP4Nj@X`@J3gk_Gnp}0nAK;#0=90 z1ypM5E`sUe!E|UFo@sj|=0RwliW6Hf&$qdL$s&h1ZwZl_g-8LUzbNJFQ0S{o)up$V z2}Q<&WJLSq5JFtu?=0Md*+ThX6)GyK7lX^br`RbQL6W1kUaAbMT3R^%>^0gZw6u6$ zb{+2%eB`A1yUrFlClbY(%UVUX=<2-I{JWRh5FyJ>P_3Z{^Z5^BA2ITbemy| z(i=i}f}v#7m?JxlETR2Uc8)?3=LF~RC|{O__cIN3reiyP*S2DjJ+W+m|C7TQ%k-4Q z4T<_m)$&Sc6q^knIZ|3@7@(i89?L4>r0;rNUA@dNWKTk?fkFs;(MaQbpB#!XbLQ{u zLltobYXRC)k*$)-Vk(10Z?cWw=IMKe0F)(KO?3A9s{Rsuf?MS%4jgL4lfbu@qi6g! zv6Kv@02hElq0%q7hzJNHJ-Nx5^Q^Kx?iXM1zj)c3I!bIeqU1~Bcq-uVn9N_J!o;*R@!&$hN?o~ zk)}V$H41Cpt33g_&1WadQg^s=_yIXXtG_VwBq%e$L-CoA0o1@dt?su$N!!vqcS5Rc~g1|0#utp?-P;}u^h z)Wc@qzn@Znzj+~kAiPW8;juFZZYg7lHN(9XAvAfNAP)$3IwWCIdF}1(LCe!;35DJ~ z2*9f^{(R9GDQ7#&iIrkb-m8YF$?vaha}Obs-fJeoz+j-E!oUC~*i;u=5fkH}%vuh8 zp{iswr;1AaT{LT2@grn4Phx|Dq`y;NQ`1y;2@c1L?n!(%fSX7R{0&`Qn|&(40|@%g zuin=;dF%u-(oLz#$~@)zyfUHFQ_a>yjJ@N*Ej_+|-oyR!r#>Mlv8(H%tnkMB=$g_Y zl$ON4X(L6-4$AWJ{C`XzPzn`9A!Si@i5^vNVy_DP33^cl>I_}7z3cyw1!Z^L4*+K& z{p8Ed#8tLcTKxJy>)BykB^e;f8cc%<44VF8S0$`{8L5|kS-60C+2AFHe?5Nm0;oh0b0xjbo-L-4k^V=r} z7fmfKK4B(#g-O%SC1%f!6;Rc+%e^T;jiIrk$b(F!$(hQ%`}^dsTW?qx67gJLx5#W2 zFIKS63E}k7ZIVNK90w&E>gtB!J1Jgjwnh@r%DD5(trHEvWs$&hRT<}vF(#wwO0}|V zpu^EXvm5Q+Bv)~1lEX=FHJdS{Ep*gD{+W(rmcn|$`7a?xi=ol{&D!UUgtUc8+AA!= zjYb@R7cYyKCt^DcC0H`a3Q!Dx{54-evZ(su$Dzw#jO(+CRC)qH*;oRgB=K~0N;C=Oy9TA4FYHi68ZI%6DdIW|;%7lFeuUy4Lhjx_I+$sH61Z++*GE5F zdB8JV-paBKRR!~tBy=~;L{z^w?Bu%GzGHqlE8>Z`5EPmf z0}4t8s;Vd_U0w?tnTQ|rFxS@AjT#IU<7Zpl+Ac-=<(ZPX<2Zrq3lr#x2ozq`ZhX*) zSV2>V+3#2Z_(U)vV%%FOAyrC*=dW=DU1R{raYi~H@s}|7iFO{pD?uSkg~X^+BKZVU z8u`@EeSf98$l|Z3L4Rg?WROR@Wl%tC?>@f6$4bXZUyA6F)Yj78+RoistlzUjO%wc& z7VO zLQ-vW#`$iQCu%Mq0sAUVV$Q+nK+I7>Kf|1W*6L>}72tqbg`|W6?MhSH()AGjv(??y zLKpH9!o}I_BBw)0(b-H|qk{YP7U;k&qD1#>-?QEL%^Hj;mfY7B?uEB^2y7YQkFv<4 z0G?eBW!hr^ndC28fbeQ;F9%b6Ya4<;PR?MwyGv{TT@5$=P8Xz%PAL^JL?jS`m-f^V z1BlhhTP3JYe;`OVi~r-giB5v&!jP_TJoJV~@HZ#EL4&gYt4;Ng5Cb+PCFSZz!Fuoz z3osFm14AqjkdC5^;sH&+^Q>oGNxy!mB2g{dsW+OJcQ`G<>6Iy0?_mHVrNy29$%cD} zRhQA7e+~>n7RD!*Jt>xCts3nYrhK@?t>Cl2ZEhCX$3c`vDIZr|3*4sLe;VyXaQW2s z<nUAizJB=WujHrmHKwD@fWYnbkN|L)H)b79PeL)(I8sJKv5)vcgZrC z=pX>if6Y%NRVa|<>eqMp;FZ0!@2)j$u4=Fp-xRcYd8TDA3!`pJqXw4VWqqArdrgx5 z!e8SbvGn7`9=4knFIkv!`tKef3DhG-Xo7-*DOKVOht3^bHq2?;0IqjDa83j2x1Wlz znaZJ?bN9nQ@N6gjnqbBOtgxnLyc)1zfzcGh57{$MLrG>yh0rnwk~{M9B>QZ3q#*p; zPd^QqW!Cz_^=OxWu0Z1fo^(ghzDB?40T+rgca~8 zc|J6*^k>!rLs)r^FP^i~{-1guPhQwB4ZldR zbkS1TQ#p=1cj*SYuW)@%bAb<(&YSfppw=XDVG6Msz$z<0-nV5qpylBDih-`K?k{sF zq7zaepdafKU@gX{ys{~BNeaNl0~U~<-=d^RDB57k-%DY_UN*b6P2|1OcRaV1@;|iL zM?sJM9mlB+q!K-Dr5X&fctv_~z5gZ^CppQPx2yc=@WnlUOee~yGOb;725%CWP@biykPH&I!sYWMkp6{bFoK4tNp$(PQjL|9R&7^U zM)ANi6JCIDohjs@49-AH^L-+l;H#yj4V>qMXD@fDw#PEiKF3W~@3BK-s!#E%bC z@CO|FKrS!KqNEi0l!1x_;8Tdv-0vpPJK$gg1$aPWmbDnj@agXJ^tq)jXSiUrXs|Y4 zpk@Zabb+h!6$}>d&6K*&Uvu;c1^0Ggc2=;#kJRiW&peMop=a}QnqkHLe%dLf-|aKLlnb%6q{H#qH#bF_V^O#C`NW=)6$or*yA@FlP)t>qN#aNlO2 zVBwpk8=?O{@qs(oQ9nH2byUe!)TDBg<>gs~ePwvIi(>85bRs8sbE|=tUP;yb6#wMA zLzh7BEs-MUtyYLMK9Y)cF4CXs<%f&V42NQE&N9Il1*yckz&13$WV=Wsid20{;9JjD zi=N|`{aolbClw|CI65(V)};I7vQV(cmR(M?@zMu1H8r4pR9ln>j*sX5Jw;Pjbtd06 z>gP}yI%;4rX@pT<8IdegGoa_X;L(l30q|ExCX^6y+DfZ%?xNTJLLt%gx_5y(yjxQE zP4>VNi8QMhtI2c=(`L9s;<11rkK#w71;zXwZI+X^gEPHeXUbWOCIPMwoYWrkU>9! zsfTmC&dObT^a*b)x3bK%&3MV3v7J!cAS0I6JDGcbZ`c68W_6~dx_*s2`;G_Gfcfd5 z^6R8{XIajE%wNeN&U2iRU5G zF|b*C+BCSFj*MaXRrTFm0)4Sc|2>u1ea1PX-ygXf>cMB-V&l8BU1Dpi3gpgQ?Y!?EoXQP&0@lXrtbDLl^BiknRXX3x%F4)qg8YAk2CgKPhX)!OpjOmq zYqKkW{%+EkGV2VATua;jBVi;(qW3KcNo+-w5cAH5i_bBeC7VF6;y!lrqZm6bq!O}h_p zfpE%&o0JyxJKGx3a)~HsUoWEJ?iQw7nK6*Z5ptE=JQs{EuzEh|?dB}5-HKvM3Ury`y{G&-XbmP*w0T~&91O`WE#3Xy@j%RtBjo*X zeX`Bc^gdxDuT%2IuC>BS=4(>f(1zyl*Bx&&yPKonqdeT7YHZr07qgJ0Q7}(=Hv3ZA zgDgE@E(w0PYO%MmsnIb&9`IpG8VFi8U1CU5Xt^ybEd_RdO-D{5QGLH*3r@ZCdon5& z=x$>Z10LQRIk_RXn;Y*qDj(jjes7bLWxf8#Hg7XkDa`Gm+S>n@1u#z;a-qi^m6 z2P#geY4S0tz$?!Fvp~y4D#F+J}#NCv3_(^rESOv+h?%P zjQ$M7xL$}g14i1>wXYaWTXCE*)>rOVEx|aR*~z?AwfC~_P#o{!xjO1;Iz}LeQiuv1 z%0sCCZYM>2m3b*l%bY_?^{19ULUYIKcE}S=#tU7g;UGM7vS`tqvFyJP+cIU?(dmHG zKY$!|%R<(XGa$ijxsEwzCFD_D3KbE8#>RE%Xrh1sSO~%k59iflRAP&|p1|f+8Lt(X zM9=Cg$v9Mg+>47r-}@6`-V}G!>vTtJ{ASYS{h=*4A&r0|Mcx~Pi}7I@?abd_{46wr zFjHkja0_{mAe*%H2^faSHW(Aj#J)knHkiP94u=~B1Q;IN4@S|cv7*{7Q8hi~8le`Q zFsrnf{mVFYQ-=0I%5o9rZ_q`h8N$O$UKRjLgAXtrh;=X24JfS ziyBkS5JN3tG`7yc*Ms5Qj9hk9WaPo>6&@cD8ucv9IOGYY$nV@wzj>2L`v87G zEpG&I()yCKMu`bVXpL?zjdAF0ilFt`;G_P>#cI^5hF_e?-76;#sHY9Ht9OV4)I%{? z)unjZ7O;!GrouP+_T3}VPWyoQC(AMg0dpgI7wKxupccG&W z;G~>-_hn{lSX6Yt^A6BBY8-|qh9%Vjicd$KGe&Xlu2poaY*{_GMXmw6_JULdze3ci zDI_8UHKn+Kx|ucbFCaRdCG0UWCpOcEix#X4#JoIp$^n2Zn=oKeQt3Uc9+D1R^t;=+ zynm(86|Wa$L^U4{rS?<#V-41Ux(*)ilJU-A$)sftSNM}~k;gt;?l~uCT2_zeROBm9 zK4t2;l}%$PXG8iigZQ{t8=1`J%5+kw+&(aqqTAtbyQ5PP$u{s*_gf+VCwW@1zMMv& zO?R>ylqB}N>4wvL8}IAnu`B`*$^F6R%a?{X&MMunsuB1>e8+HOYENGgKqn9~2R0rZ zFh7#~IVFSG&FH2@KSOQoA4)_qEO3BFDzchH2+tsqIs~1DNa|Cg3xvaez_lH5FI{TZ~#f#mP$#%-@%#>Fj*A1od!8|8mK{8nlE_sS-3iO!02KL@tQtIF1~ zW2ipHhT9H09hcKn)l>%{y}J>-JP(i=4&h)l%`7g2~H_TpL2lxwB< zd3k4FeNmG7(`!gnE|dMr2)qCAsO=aFSxa6$mO5XZbd$s_8{ej z0Fx)GmVfS#5|j8mzVXMx##XI6o=x~p!If2ATpB5}uvUPZ7oS?EB$N0nmi%Z(;`snO zrqXum8QI+I)YPVqZ4A*frGh7;aKJ6f>+F;f$v#3<(^h_2f1;$R1&E1+I6ASXEI+va zis&_jAX?R+9;-JWnL77a+Lo~Dh@AESMvI^HzWusRYV}zh{xqjwfz$r zh!rmsG};QH*ySI?^82fFI^?DrD=R$|LkA;6&b7lnN~Py&vU<5r)Xh#Y0CL)VSf9|p z+QDR{eYaQvoG!LOEiCg6XtepL-T zk_N#%$^bE4)~4BD>c)G%yx{B?g$vfs``mNBTB}bw3o3)%;nbfjfkrtFCQfiBz}BQz zxAX~|BZ$R`qT4Lk;_8{P{@11oAgSVHOdm2kAe(s6oI;4D(0 zh?{#VN{IJqc{om+j^^oCMx`O*?aQ_^3agKJIw@{t8HH7qret9UR=b+j-%DTmN%zfR z`=m4hN1i?)WeyLhFB{ae@o`E}TYSy0J@JiwlmjHVGDuRb-P4t)VO52Lr$&k{Pmls5 zxp~0aa0>ogpr}+a-*g(K&ng5^5bgaiG(&6c;NBiW_Y_fd%mhxj_?fo|NlfYjjA3DH zRMhO859)QZ&-UwK7ddLw$*$L7SwPaJZ&{$a(3M6TKQYILv5ulJC4&^T3i|stbd1f_ z{rlXHN(8QN*{~a8daUNz@MJ`g8W!%><-m(V0m=V(JevO_15!D3 z-#=iF@*s|0AHBpitJ=RXw7@cHl!{VL__w>3U6v-2odRDd3HwR&d!kDeed3sk5h4i( zzm?Ew+p*!;3Mh5wYeFCe(q;55pFl;+4Q3rXYNjy`7CkLC(A1JmVYj1RzvpXXz>fop zc)uG^qM*D`SMFW|?lfFyN;A4$!3UbUvX@j=z{C47y9K_wkRF`;ByO?TNKv$!^%Mwf z#zq>&P0bMm3Ajchk{A>c3tM}HBE>aH)dZ(@&Ky{x5LCXgJ!r+6PpJTebP@6m;*!xV zr{-2;mT~6JraUewycwi)Q;1>4#v`5^l+;GV(_{`LW zR+ByK<^l)3)iT&`6k&)$lH??uO(AmwvUYm~veMxkje(@7E_p;aO7#P6@(RKK*ZV6C zo2+;4mwE_b@F-z4r&fjJ(uZ*|zt{$1-d?TJOd`HZUS$P@=)Fx4-PdH(BDVpJ)?(%xloUIW90?;byp7y$9dX#-49jTcn~BeeUie64ttmA6a7NsI<5JP^mbUZ6;y zXBmjRWsYY-6Q{r`<6!6F^a!I5Z_s7A?8vA&Vo`C?+23nfrEiiYR6r}3QfAAQo-@hi zc}X6P$U%I*%U7)}SDPydH29OFrV%i!X6iILuIL{=;a(;qBh#re=^3(nY`;CoXo{i# z+oFkcNL|a0pQCuZj&hnS{C4e4GoQ*}qpMx|;{V6gTLwh+ec!_%2uL?bgOo~1Hv$7l zg9u1UcY`C{oze{5NXHOTB2pqSGc-d=H%K@Bul_!MpXa{f9e3{8=j^rDT6-Vuj)J(q zwW8iPDuLy{`^HweY)-5MJ0n>tGPOM zsUO<@c4I4Bl{krc+noO9?e}f0ZD2IU&Q9i?QKkrS6i8MUtus{om$-N-%e{)DMpZ?H zmEP`lb```-E)jU2`WMsN0rh~7BVg&x#dxBL1}-`}Ky0qu-T4i~cUG`J^(GKdt^9w0g0Kn=Zx!8aN%dGef)~TNVpN#bfNrbp87V@VZg;Sm7$iz@SkHhGGN97ziv z@~Ua%%ojVD@ke`9{y43GD4p^1`F!0qAX=PledDks(3awm`s8Atzy zAAf@ll^pP6zi$nudzG~I={&!8?)^eWt8FO1a=MPeF-&i~*J3e0tB~acqf9SfMOKh3 z=8Rrk_(lIm5815eDhlKzp2k4~= zBqX~A8=^w+AF8|rrdV2GlOn#W1pYaxi;G_fJPtCAzrO2xi@PtjGv1Q@x~*^VTQ?7i zNi)WD={Ud+{ZNsn0{Z;`k|g=7CZK?n8{z_5(R%@+@m^J*$nEV$7nHBm>+66uV!{K_ zO6ppS*E7O_Hd$dx8D8|5?Kwi3gN3@SG*Mk>&RJ}PS1BgMNq3U7%}Ez-;ywZ%e)V3| zNZB9i`=zKcFc)(X0+`c1)>CywjRm;(b05`vl8;behm|s4GM6tp7Um(Zu5Iy+n zuAC;`;kFKFwcqsn3hQ*qs5Kz{8qe+MRA>gVX5-Rs4mKJ14t8>8`gSix~z3J@i ztXjl7xS8w^PNRzNyjP9MdK!HVRZ=IxGU`t~ikK)TvW>g;AeL>uPZ+Q`hV(IR$Akdd zLMd(Ex?L61(O8av&EsaS$0v|+`{FBO1oRQ>A9j@FPbmJevVMFGw6I&@D2&1w(F4cq zmKhL?TU{J_$4S-~FXA9PnPb;$L%6Ebp*>{XCUQJmo5GS>nA>UZ-PT%5l)1(IZ-ILG zdqHGReOSnZ(_3_soYZDGbz`~%^U9HRo@a2!Xw#b*(q9sG?G;n4zB>>d_}q^l-{)n9 zL;=2F%bU6LoJahU@hpNn)q4@r-y`_}45kzJbV<9gR&(K437jt_^6t&+ww*Bnx@R}h zh6rJXc0vsYirw|GOh6Mwa#>6R@0Y4rOcXxseF-Jk3IKjz$#alrS%#q3}})H;Qmek2OpNRfF>>_~~>rPzd767~=Wg~3rw%1%)0R(Wg0iUOF za*;ksC_3JmBEa>iuaZ6>+qbK=Y_l&jlVV}B`e}noStE_P7K+KWjWRC)ZCW3Z_o*mU zVp{^7-o4m`I~s^u;c;omYN3CC?la2-DT6(C*2DRgH>=Ap6E|~InH7&IKTji(Ue}SF zWA9C_G(VOuR7s&HTtY3+82}$FO6VIUR!y5R)#c{@G#Tb1YtoxL?}&W8G&Gdgo;gZ` zgBJ6v1&~*N2tK_Cl3aW!roOO^`_=Gck3+BTt;{*J(=UMUr{R75zitdGg7{sH6yjH* zsfIY1Dquuq0(}?2B5bB{1UXnzt!3r!pHypw%}?zwltQAKm#|S(gn;f7dRx2M?0T|A zIhs;cu)}1&;$TCKzLd9f`NFH-)%qaRA+fhm{bHb4x*2ig0(snlwcqcJqhtXld*_?I zMW`vgHkO7cP%OT1`{=t90K^__dvC7;7%Ikz1DL5h14xtJ9J*F7Odj9%azA|<4w!E^ zDrWHp{POAL05Tom^Tzp8g>7V>v7B^#TT5)FPKEA0p&b#AJLd zTIho#>;-Edpg5CoPEHq9H2;4{pAWa_6$x;|G3fE^!8VcK`T7FjInJOl#<<8xU_tM^ zo_WEPFOe@5VAuMiFuZKFRD!{o)>f!#4HGTB3bsmK*!*&Sre?+axH;3krHL+ry>WfJ?Lq2unnsFOHpF1X zKszPxquuq%*I~<6IH9!rgQ+1lvLn_l$FyN_(3 z4sqDhMah%YXBf3Ng5RH5!*qCoo2dUh`ECzO`@VoP(7%6~65FDt54g=$ z%`#k!7U^)%>A6lF{Gn>kNz=!`mV8s&Rk&hOHf`etvyB!ur(ny*pc!}JZa-!r(VDiA1wx498 z3MM2AwRu6+*4{qn+h3D?jE9Dg-&R&;9VQi8DJSz=*V#KWvhBkjLNblC;mS7&&8r%Y z8G?_W8L1;6cr6TbGDF8vn)Cav7%8s@o7KQo<+=y&k~J^oTdqWyeJ!0j9oSvni>y_G>j>xYZ`<58lw--&t*>{>?Ucd0< z$*ic5-TpqO0x@|`p6eG}X3=gE5NQ>#4Ph2z_ky*W;}RKTyZTI;-) zvy+Z<(I2GOB8Je0s+0S?0wn-|a+Ur<`&CkH`lEc6xoX=0-1 zE0J_kxr${06mfR#vBlmzcpr799!)4VPj)^-l0s#ocM}R)4(9hzkmS?ga-gSRcT_i=tB>f!< z{Ki-EeEzEwt^O?PP*B9)*vIW{RU2E$f-3?)bLPUsI}`ZpNOnqmYMm+ErXEp;ras1x zl6m0v@VkjA#bLO?eJoX?%_$4TyI~#jLd}S?rQ_xnBF&-eGdQi-M#o6-)vpLC!wOYK z;10q+PoO{=Cru%H^jx#z_;?h>yT;)%5AgeXZVm(9A0rZ3f(w_ItFtW>uf|9UZA8!z zh~ffuE{fP}mCX0QR?fY0Pr1!{OdBBd-vt|fS5(d>&}<94g+|uUK8A?zRkxq;AeQpTYku_h?%fLyendL9Vg~u6B z;MXh-+1XiHlkY4Z2V1R8erJr{ot>R}OkOhs99^rct4Yjf7Z+LWLs5~O7Zb8s5~U!` zs???Iu*B(0>7f*l#*#1zM=bOQ;DCe2;mZ5C4gMJg?xeGZ0|m9!Wh@E~-<8@O)(}$` z1}3{%dBP%WrFxqfKK<(&yUW=bf>p!!?>{9U%r}JHiG4WTny)v9(@Kcy3O+Vs{+9&` zDedw*#Ul_>JMVt~hDmzgn{CxvE_k~RwQgp+$0H_~9gs4hBTfV2lasOG*!wVP-*Taz z1{PW97>wlM<1mq3AFd7!cf@pDoFA-o>MO7mEctwGi?P09{Janq)*P_EX2n9Zg_Qoc ze_jBi%A)3PehUlqqHdvnJ_|E5`_o3&X+wKt4MtsjM5;8Rz2r*c<9mFq>z@{QV(}Uq z;m<}9V;RyCO0`LgIjn^a&S0_8p#3u1#u7j9)`zK!zc-dWfIj2+XoDm*G@{wSBi@7J zZ7|_W+YtA?Px6Qr*~&hipdkc%GV@YD#~M92pd}%R5dTy#!bzhajjT$t6nQ$NIP^G{ zic6poDM@n8;_)h}(Hc%i&Ly~t6phck9MR*6dh6i(+yA`DSl+&=uYY|gtSMXNnQ|VB znKO*<;hwcK&u&Vi@pJo(y9TeOjve7!9d*IsBAk&p8hlw&h@{o-T=i;I0Wxa^M#}&s zX#Ll7pf!_1gQ;3)y{_D52gbsvo`@)$<6ovi)U}lV)@E!=0Fu5*NIY61)$V(Ebx~iN zko$YMWcuBr=ySmu{U(=VW&?J9fqLDFBZ_y~-g_^uQjXB}F!-N4ifAI@QelI@Rxtuj z&8o=N2a0BlHW#|nRAf=)?muwT&1MHWv28k{QYB0qsR|VQq*1R;7QDYC&$Y|suLqi)CLPMFH|ct8^;b%pfk=Q zz53?otBg`X%qxNqfK`~vs^SC??{R*JU;>jx8nW($3dU%I_h)emZA|ls0t8nLA1we$ zPh5Ntsn8}A;GTwk#}{V_7j;OnVWuL>%o>qpIOR>}BtU<#T*^v6;OgHc{et?o0p72L z>A7g?QK0uCOSdjo#(vvMh-F%apUR`7Ap34qr1H}~f8+ffN=zl;Xi`+O!3bf@d1O?0 zAjaPVDYgHwHclkeitfvK%l^AVhQfaB%9*aRv271gzh^n*nVDR>J4}VR0}merU49F8 z;Nu&JMJm}RBXi#Uo^gGr4o{>1o#D4n7(A8C*Xr=J^dwq&^9@`-NS=qr>T%(Xw>MWx zF%EN7q?7OMQIB=*)%V$^aQpgna9R^}xPY>K9^MY5YL8C~UPRNvM{1_L*8$Dl$5abg z@cj&l6kLSXUnP#$zQW5RpKip06AT_3GiBy=6}Mgyouuv8yfw|X7h+bVqNA(%#WhKu zHjbr7gn2T=$yp7?pPj#Vh%&lwfkKBuim>p23MDE^HYdj@Expabi}i-xL!54RyS2BD z_rVQV80ZPJppAf#y+$mnFp-mFW>Kud+oV3HeE>02NfedH-J}seD_30>O`+k4tB(unYBdYy`|bRY?mG7y^d82Ss>%oV-? zszyuR+0PGiH$%Fs3TG7U!bQ0JNMXZ$2!% z*S!+NM?rZRvT8N9y)fGn^!0;?Q)%?g>dVbE&dPUhCC;MRW?Hy&T?_Zi-HX_&M&!`o z5wZo^%XJB>w=@bBR6jpY#>D|f3uY=u!=~s5s14jgjR4(Yvp?(r6T7K>L2O!UEwfyg zx7lQv(0o+Pey*ZYS3BLmYMzq=6DqcX;+^X;&n+mIspp6`xvYfVM~pc?OIBl}AYXg) z;{e*|#``!cOS#u9yq$#7z(^PQQdOuh*zWrAdp1Qw8PAem@JvHIllkVDX zq15ZXd|$#Z`1x@K(7#Y)(c(01$ymU!g6phCj-DtuF&DnETR>X>{&q)Zps%0tnh3q1 zO0usNY<{@dnVg)w-hSpSlT-|YaTaKV0ML$~D3OC(a*B%jNkjIVl<|bB{{Be!2l{Er z^)rUB*k7+D!uB!0K9A*Kdy;6wPMVt`d`golsVpL;s@yd5b#Bz7X(;Z z?Q(Q}BE_-OwY7$LT6dww+zuH8)xv_r1~Mdazr759M|jw?c=o&4nt{6}rM{V{wKc!2 z@(X+A#sru3Nw+jUyc~C0POg2#P$Kkm5B|Aq*t})obMY3!f1m1c0-TYVX_Fiulj;HL zd2Q0jGb9J!C}^VD$w*$?V5-JQ*voBsO))|;&UY^F@!tBtePzv#=g!mSwYaXU5h+6t zqVaAeQPt9fUeReGZiDeNQt5UwnhCyb@rHYn^6SCqKalKw`D?u*-zMs`9Z1@owI9v3 zNuHn-kAin)=%SwaYQGPiuglPA5e1 zo4%&+X~513lNvzIxaQh&St25GW6O6>6BaZ7wC!>bJB1b2Lo=|g-IT)tUX&1;cGH^I zWW`hU%CxBfNLehKzj;^VVWX|>8yt5m?mOhV54C! z9?+=)`(c7)>Y#;oY6CKGiC(|+I(D*BnJ$L4P(@Ut({**iYx4!>!qJ2lP&AzO$AO0A zvAD8@3%a6DXudrt#hR@)X?fVG5InyiwH;3z)nwWMihVN6i7u7dv>wU1a_cdq zwJgcNPZYexOmpb^FPK$4U8l+2HCv0W6zZlTiT)xz)i_hFyZEgQ~ z9s}umTTF+vk14?2JMQT2rm6Nxo79MmJJfUpU<~f&rP}dCrIy%Hn!B^{GgT$|XY6#0 zm*ppRUOcxtA<#C$Qxzr2;l=yd*el*r_vYnGpxg$^s-4w!kx&b}W%i`-lEBz6`5}Ae zqr;ozV1xg-9gBB|oeql*c3_ z3Zh~{nY4`zzm6`qUEc;1;$ie`#6pK=<2=Q!*gtv_gov;z4n!~X zr79Usxn?~5DO7ebnxzp!Mm9IMY2~&VMW6GMzGQN;yqaQ7oj{U!gy1mx~PN|F07MEC~tIB5Qg{``V%#rKcR+b_i zL;++g5N;hWCsbp+zes8i5DVdi9yf_k)FTUXlmugo-xghw#Q~t~CBx56uZVja z`EL5#XJ0|-=>I;OpSWbi$76?O4eiMTCgox6QBZMTAv6eOX@dE=5^J*Nm~A?*zG9i) zWVj^y-HzW4-OeH0i%dST+*&6;QA=XL{DrOe?7@3doSUuWQCaaW-L%2d$RbK`**J%> z;~;P$+~agH^t|VLIh&i@jD=4WvKOi9do&QsZcYWV(h)hDOaR`Ble{0+m^2a3B}ZRv zSJ<5jv$9fasD*To(lieJbocYrjvxdOtG#VKJB}I84F^_S+PRn2hQ~RCHpSET3s}{U zto%k4AC0A4@R)BD{PB9-i`O}C!b0}oY2W}4qaMOFl^vmh5G~d|ZT%M!_K8+PNR)x@t z3JWOec^*97(dIiwNCo@@Zz|I?HyODsLLr`T^x=W=I{CZL-HmS6y6Go)5PKoq3~t)9 zn-3Tv!_w&$kv)16B#Ce(Ah>?Dnl0)%XK!xCy@QTYY6o#X$9HDSqpE zz*I}Co!Wf!ZyU~S%Z?idh0dP>)x+1rEVUbzl?n?Ms*=|~n+O}us8KmZ{&4=^PdzIy z;KC1g2kwY{WWzTMg4Xg??6AF#6xLpUlNyPh3wJRz=h-5Ru~L3LSe&Hx`&aaHN$)i* zgL^h}^9y9hcen*_$!qvtNvUacKI+gco>1)dT@j6L5>tHk4kYrs!bXoRzNBuy7##kN zSE?)QF3a7rhvu8_Qxm5G_GrNE1Wuo-l&N6exa8v;p^P0E?`ELD<`hHId+hP7>GGRY zvLfFSRTOA{%}t`*Iu6Ly-Z$CKXM9v5*x{3|!k~ikcpza0Bp_Vne?mLp`oI``H zt$G_<)73GJji6!OK@m^FIGTs6gkd#9z#(yFgwT8zyzF9nMr)ntQ*&PJ9xl2h9SQN6 zrN^=uv#r*h?S#UVWs~D5xC+8qbE3HXwW$78WOiGdgwLX3TiLr4QER+vE9k@G<{@l!{y)1Ok_+8>WdFP`xOU0KOWo zViGW}8)~*IJPcwYI(PQF{pOK-_cJ`wuRR^@AV%y~TwS?Fk7VS{{faFUc36*yeNK}n zZ{A2!swMu`c^7lgRuam8Y_53F#U>$@i_@|ORPWt=C*gUP*5EVs5u!x6LNrs^xRT%y zRW^lMu1bz5OWAm%FJ>d*>BA(CspXz7TL*q;jl)b%G^K0hg$WxQAn-Qv$iEW8FB%$M zYMAhG&N^-nEOKCIA|Y7)!U^^{{A;6>9J7U-IwB%7v*=B6Lb~%qh`2a`htcOu z>cxxh;4zFDnVHR%`iXLUON4_?0i>-3jvGOEnyh|r9FS;v<}RMw+>Vw*)Q7LrhKH9! zA+jsHBZ*C$Fo2}?ywtY+YT6NshL307II+PbUKXBFA>I=VI!hX0bMz^Gk*Orsmw>am|efcJgE%yg>rvI(~msdlQR-k`B5j6F;O_uZGoi}J{;lKAMHhFeOHUH5{T$%1 z3~~c<0d8=w-l&bRk^FT$sAywP-E;?{DS0!@L*bgO0~hROP?fldLj>)&{e&LmlM(t_ z^|xMT@D0QfCoW0N&ih^_DOW}CY7=kdK&Hv%>Z_|qOf7ZVQ6Wj(nSO#|TfP92Xy@J1 zVCNGMus03}6Sk4X@-|!f$eM_hlaNTys3l7%Yg+p(|ALAtj^^rh?R%O_!&j(SBV{+p zRb_P^{^`A6DLsBQNL7QzjRw73{Yd%L$;y+nzO*QZ3!}*c)AF6F!cWMmtY`uzvuY=n zdCY&XQZ>Wge4-cl5_Ud2hN==`jV`27Nh8FX`kEOY8@K*f6Xit%@s@xiZV^J1(1**1 z614@$)6KE*NnGgr^9h=<-ZhkBvIU*xZ=40&)zh?@j@NbIAmAfxk36{Owyu5~5*;Jr z4oJ{a73G^HVMK+n;1)ex6(RdYNF=)S)}F^K#8X^SP%wNnIIKW-*y*o=6K?sqk%2#I zMO0DLs&ypwXMPi5gKu3(gGy2Z2AoY)+pInyOB))z@G=`P~FXs zN6W)`iec+5T4vA1h%xH$_R|1Tvfbe~I~~wd%k3J%nltpmiRd4iAnA0iNfil|=<=N$ z_PVI61)|}N_SyQ*249f{)K;#bqz;;`QaZNX({<-qS3cp>1KU6-H> zW{51@LbSdB9zj8QtRu2$_U5cKkKWajC{R`1CA5D&dwz_VU)VIRcp zDq5cq*y|k=CUmhY4g`0Dl$9%c1RU9i^?KHHhTEt#3yd;zUQ(tzcdG_P$Bs?@&4)tF(Vw*Zo8a0EAkLW!Z ztg7-hB5|QNPhew%*wJw$Jj~H?mpF=I_2}VwwFr*kQij$dSk2vR1&gTO!<{E%)&1yt zb;Tv1rqQQ;En`=hS<$TCMw1jtvFM6mNB+XvSizT-Z3LIkEas+jTN%V~yw4%q&ZNB- z8h$P2a?l#5vzqR{A}{(!iSxST@w*;>=&(fm-+uT>)=^quFr^n;X!hCmPrl4E52^b@ z4LRs&pDl`jZ-t3QXeI1^eILdVGbzswjKed>!fW=j#NET^Y0Z455}xKclz6lAQi93^C*3=eOA^c1Ia2Rs=(c#gUR zcsGW`Z)qcBN!xa+5x-!@A!Hv&e;06tbXZY0(&TF5u48FHwhiyvUe(Z ze`piRqNOZ$L?eIxN%EL;VON(fUo(C+;_|2Ucd3dj6&th2P3O&K5=~KUct6BcufdeT zdQ(0Qc5}>-hDYtKudlzkVReQ-t9q+fmK&8eD~OA)Pnd}wL{A^#S9%YO@BIdWm|v$6 zgVQ%sC4|(UhWc@F>XXjakhOh_qXCv#_-fW#dDyU7^(mp`>4pBzg|X9Z1^D+<0vJ4R5)Z^^f&L&h+-i$&JakB%wxFv-UiP z+502safq)doXQee!k^==@rlcOm%1bRDQ@^@B4vioYKzgHY&-VtEnP`=!h zX92*mej3=xDUH*WB%m30QRxriL>kI^_YDS9J@Rx2>qJ2Rdy3ENdz-uteK0tn zJr#5U>+Q#If*0iK#r1bH++{0YSV3E8G{E7P#&Sse#+n$_QOt5@FhWe_+X=mo?pK@fijm7G{h7S zFc=)(ZxfWPttqh8e+0SHVy0FnqOnk)DJf1s-A6nIM~nH0T2EoAi7@Z~fCvgZdOLZ% z);2#8XSO&*t&Cc?7XOzoYmTw77ccns^4nl?c-&e^t{y}lwRx6U7Hih+(pVeeV{NwM zg-G?LTfYUZ(U;^fO2vrp2E+T0LPPj@UbVC>Rc1zt@U0wq@=!7l07s9A*#F6JTqE~E zEc3m2kB6npUN;Nm!*(Dq_?`evGc2c8fa7p`Tdy8-`n6tsTpSDF(fNkgZW|g*s9F;1 zxG<~Th|$Mq=xOa% zl&ej3<}QnBykt7EfrkN(x1lHN<3cOs$sgZ)RIh6b0vn!51zaZ8gF@1AS_WoJvu zpO%9jLtYmUNb9d!<*qGzdy{R87VozEsH{3kSNc~C!&JuR!K-pX9euaSqGI`nK zKh7y)Ac09-!|;^DBO*o~lHT3j`JC^$F1CoiB$aF5vF;%TV$P@XYeVD{fIY$-Ax2!U zV&NHi%?r5^0zbhz5)L0Ap#8B+;!Jk|`$vO(C9x4e^^7nW{0p|0pG(mRO*ox=d@#Xh9(wJxSwmCcXnyU?~!>+LcjhZ&9iPL#9$d*Fh5rv?2l`z_7Q8^(_SQqxN##aQ)a zt^VYjg`B~dWNt1PCGG)k=0gwFy1zzFl2MpRT_~fC^`Q!QN6$!55K+*C#0Rjp9nXd# zE3kLa^OWPiZ0S8WgCXx7zNGZ!LA+rWyt8gl#IUZRzJBYqpzFii?+Xi4-vadjZJ&?xU`@?J( zl=a~$A)F7@2pG($cBqoJIJ>A>OC~d>VaqoaN z$@{i34XKh2q>?nWN4uYKXD!d5s1byXrc{i{e~b~~7L9b$k!^~y$xcd){2q$mABUBe z@blB~qpSy3o&$3EpQjFMJQCFVBj5g^zs-xoetqGJcD{#vy(ggF%zT`=;IYc$^U~Ko zTF1snkuzTtu{*b$BtIR$nBUu!#i;S5);GhhMdDJVxCe$!6;DZLA7k&I-q<^&nLH$v ztMBSslKvbU7q^dumT@_nzkfj?0W>4L_b}Y^J>) zl@XH=_1%!b2y;eTYO{*Q^;cI^@3zQCz$rMJg(~tvp0KcRX4$ai8)08O0PIA3dV-XJ zn&n~-Y3?=42aFX4@6S#yEEo-TJ}_Yk{O`p1h3(%py-BG5x~Pd70~=o&+QCO8qL3Tq z>-S`5djk6OaM6Z@sokcKQjH|M~c|PJ=^)ve0MMFqIbq`;Fx|JG5n`H zdRg>XtA;2}6HsQw_h}AiRB4Wn^xH%zaTS;}q1GPb{a;N`4P>7x9O1Xc59M>R6fr9v z^qDacL2(5JR_g}`Wi13gxi~pZi5DVJ@A}>CY}`07P!9&n3y8un^8bl5kp=iJ~H@LO=h?i%do;4NKMr3 z$9SE_69feO93K6zC3c;?-5Op39CA-jPdj*@m%~DiM!*jSM2=V^iUE`2c({2n(wZqV zLwEv-Ea`famfVm%+`~rcq`}Qcu;wvH zQf6{FswGHCnMsVl&`=>r?VXU%v&&2dhe;;{Tl2RmoGZEM$Oh_`Dd^mzEE zaR?MVry}XB)Co$?yj#FMX(!);mtseOQRU<_G>KrTI0Sx3I8X=I!7ckNpI|O?N}wEL{)a#Ui8U}e zY5sZ_TT^W=1eppA{2{b^@7Hr|i)$0)F>DYi-a1XS@*+-=&fi7m2tT9lAhU#r=^B~K zGCgW@1+Z&^tY%WBweT>cVru;bzna0KLYp3{F`FgvTMASn z7vuwMY!=0a=gy}2DQJPdNBh9ZKY(xkP7A-o)N7!<=+{G9mPh`Gi>XPzB`Y;S%UH zCy%-BgtgNe`clFN61?xuLx~^u4F~5@X9!GLLd?Pq$I8K>YHBEdzanqQuRTqU=Ap_H zejcHgt-#Z=$NV0xgUIjQFR7?dg#Mie&IOY%r z|D0D6-jWgH}b579n%}yoJ;$EFOlavB*ZUMz(XV;D8F(pBg zV6q7`QOVvuZu@ET$IsUivR-c}G#!Mv8?z)nDda^1s(cc^_WQG{ZWueDt3>f`CFx3S zD%+M3iFPqEM$;k?soknC_@!mhObGt14tbMyyJ>zjCos!_YI~tKmd|`t%=yE1PE;iI zI?%X4Pfh*f+1%DW>h+qMBuE3E`f#UJClXY+aS5ylm_C5D@Xa&8{3&PyyLv{Z0jC0^ zJz`Njc0erFa26!3GqPmMZ#Bd|q-x`> z(~yzX#r2Q{V9FQ2oAdpd`l8u()SZuIdH&u#;dp<09`=^H0(PgW*XR80?H|d%0X!J& zbig7BAi96TGI2o9JF)GTf6BKaU>Z?EPLJKEzR!tO&VS0I$DWBg2I}JHL-^AX-dv0t z@I?^m+*`8MCT}-D zz{|c2EGuCUH^`{<6J$`-I=b|2fP+@X%L=_jO%Q*uPCr5Uj zA*=>AVfucOPgd&V$M-*z*oN{YEb|7fsFne*%T;#bIx`8PKtq@m8|dp{+UMgeEl^A< zjl>GtY6#}%NBLi!nk%a;F}(ut3SmtyGvxM^F6%kkcS6Hr$u$5AAuH~TB`qtFPAIf3 z@@dnq;7klhW+FR;%k$hs4W04X&>$xLZK?usRTXY#?XM`w1e&`c*i?I5ha?nclF-SJ>h!X8p647dvz|HYjfYs+A6`%AlHaV^S=sUMP9| z=|N+FwUg%VvyG}U=iX7V%J4&+Uofg`LVh5Yg1pZqz56(#X|L7LhK}*lp_n;|>lWg4 z$?L@o{5}d)v%uNi#KP@m{wts5pp2+t18*b0$p$D9t*qaO(-oCy_?osa=a7_t0S>*d zsQ-9Cx!ZfHT-i@eF2Yr-f*Vx>Q)1L{d_|OpRo0Pz3^*F_k_S7jtb~2w5LIB*4i)`U zmq)qWRd^OM1fS=ystJWU<-_|?3fHajwvc8Yey_FVRe!1i4mO}434D51S4m-2_#(OP z_$9E1|J9ejm}pvNz7?={3J67fOp`$%7ptbeC4Lyz>-i>TKy58w-U00gI=M)8T1j6@ zOk<~^S~JadwA#BJe>A$1?>@3_hb_TiHGqGZ&K04OtoLWcb%k5M=#2H@D+zZZOq|v% zcp6}B4mo+6QX3WSSHqMU4on<$-@2IQ=lA;AgN~9y_P-x*rzvW{v~-JoKoJrKYK>b& z0{2!u?%-o5bF#us8mK}l$yfRd_Wa0?fk@aeY)~p5g*Q}06D0@u_rmBGVjbrg8C1F zmV{OMKH)y&P}Ev151RVa7D6sJDo&KxVV4K^tRh6k+E0~d<|w;OW`4$VmXU6N2n&M= zQ`aq?rK&KS0b5rIx|Huxm#me<+}@&2i9qBV|D%fN!Zsr;ylSU62zgic?ELeKJgiuz z@Aq5EK9p5&V9y%jEFvp;R&mb^$7d$(ZEOnl2n&Jt+1u6lp86bsE0Dxfx8TVF0&hSe zs}eGbIfpnz3$Gl#1sIX8ZWECb1YWm^FeUDgo7>3-S3;i5b8?*wVD@XleWBg^Dl`rK ze_(F9{F+7vs3?#3$AxDU<^a_Hv6-HMDW3Z5MnS|WrI}XcP|ey0s`nu)=)*a$mt1ZX z)*smP=KnGG)=^P?U)VSTf=USrh?LTjN_Te%NJ%T*NaqlubbM&(?h=NM8M?c>yN0d- z=6BI={nmQd`}cd6OV`M7&$;)Wc=ofOy|<7hgPA_M--^=1hB>DN!yK zl{>9K*l?LXZgxJ*%;BhzypF{EAE)*+hblE0VLp7zb(G73gBfee%7ZtE-KmqcwLe(z z<7NH$;L%`eXOoM`oAZ6U;a0XE=Mo8SIlnoNO=%?+ z-Uk2#IfB*4tTb0z2T4v(_{G;+N_eR{8XxGHq!b?hidIF`fkc6+Lb1qE4O(a~epT&Z( zSAZfU9q(+JHv2!#(dzTd0A_XkPnS}Rlk-8;^ZgH;0661X-(*}eGdJg;O##I1Kv9tw z1?MHH=hHGPQGDCM3rdIg8@&hJ+^Y0=13L6^!00<06n&^?i4`T6^ zr0+*kJHq@Yzj&)0nLdt5nwgpTWc}>vUy0|k?q@8=1Wvt*Uu;~m;`~D5;+uufb5j?l zOSj zHR?Ct2Er-%s7v(Gea)0!{2T3+sT2}~_r5YkxqZ$8i%qFUgY8=@RVi};)BYtN`*|Gr zCc(;`6WJFD_c1a*FCQGo5&V@^IZnr_+5&i$y2;_&opX(|I?Nn!>p>fj9gX7G#q z7wcy&^QJk(K#HHtkZZ+6QM}ymPCYvN9cpHiAFxN|9?v5c@(7pwd$u)(^sA)_lw%88d3AZ=bz5c=!1=U?^M!^bDve4Lst<@PGc@-uLZ~bdoPm-Xb9t3%|_K zh`Zz+ddn!&U+3AWxudq;#M%gs7wK>S8P1&aXATUy53FTWD_0&X98w`>eNY* z9xx#B@zK%V$`oCDfO$v?fNuPlAS@O>FV4GKw>OU-uaa=7IiMXsCnfC{RKcaCuj2$_ zZBjc9BMs1#)RZo9D3nBHfB9St3=PFwXd@vh?L904A1;}ki#V!H%r#7<&z8EMHqzoAx_zCv$`I$+zNU;UDovl7bGFT!RY&hP_tA?Ow>&IY_aoj;(; z_)ipdqYQ6Tl5v{u_g`%9kzkFi!2Z#vWA=q-SD`POw|Fgd6Lsx)dVM|P`$bJDUB5_3 zrdg_yG()E#8{?36*q8TK7afn2%h4E@{9Af-v|p;@g;`)PBRv=cF^?a>!x4=Yc1GK? z_k+z*-<#N&oNRn%J4!vmieJ!xRp#RUM8H>@haDq8}NPoJSigq}VMuKlZXCuQIPHl=L-v#(vh+^t|}P2RpNl!MEdUqav`` zsy@$!So1U@e+q1|;>C*GtRL7~mh1myzoTevc*mj8LOo)(h4g?ilnDNur#^{d9=c({ zrp@2<@2qJ480HOfx`n1_!QAZjyk?goJF$L{z_t?|`b~ZpNjSR?+2pIox!y=u+)|+~hH%f8p~uFejU% zJOQwR>bD~N=J&(uRt8RC6l|?Fkq>~BKI5H9AG1kA;r41@Iu;ubR=Qp;HeJ8?3tnDz zvK+!;6%`f1G?+1qhh{-F#{B897!IzoheyL#9&FjFX58a9&gePoe|KoIfS|%wNsLy$ zDS^kp(T|Gk+u8X9*O=A3$#1g$$q6-Cgv=;AUKVCUu&GScm$ZW~!7~|sIV8rz%!;n6 z4&&(lQD%KzS)~7rF!+vQYzL5g0eLCQREZy7v$C?<@8rb4CRj~Z#U;VTF>q6o#eR5A zNXrV#DUT@ef@WtvGzjPSefkb8`DaYByQ=gF((TUz`NyJMXejbcQGnpO{!{^v-X^xH z?`=k}3(yR6gq7cF*~N%-ei_*^0rEU#L|W_T96**s)opfP$NX z40V7O=&ZRn+h^qa(ct+r2kST|)csGVt;j$=m1y-C$FDz$1Nr&V@ol)v{P)4B$$8OK z3Q3Cg&Ly6tfNC6r+auwgpac8Y_UzAdzKDnjwigSNlW{O^eVQ^4cXuk8#Ds*m-DY1X z(m{{Gn>1bHBS$?8eQ8}R{$ zX+~ccXT^``0{r};0pB3fqm|eEic|&}O4IZFSxg_GP`n62C+s~1c6P_G%mg#7-Jn4Y zNw%K~yhLF;KYeh!o1Q&%1vFJuSJN*+5L4mjnf`jn0lTJL#5ibe?&rl!jy6I*F3gxF zS&Zas&((fLO1IO{U?;#$SC4;PzkSo!)7d!zoaN7cvL&$dZDAypn+MQ23ky#@k{8=E zc7%|UCWg{bbesJKa*8cz;(H3Fwf%RRzI^C;oLNg%7CuYe&j)7dt+Z{X1Oj*Isue#n zCoTa%#yky(%o=R*18haqm(3 z3MFeDuU8I*0y+wI5kg5l<6+>O2bLzh^;;xORuCNvQP{;6{?EGiyi1=eSLo#>UwAsE ztS(@iU3;S~9Zi-c*YASTZf_U{bz?o9PrS)=!MS$SGh5HHXbgv_)phR@;DR^y-mDk> zYv|CsYn;QYj%XpGJ9%4`s!MC*@07?7Pjohus@~1YN*-Y!(}XI~aoXEnsx7wG%dqt2 zU5Adk5MP#U2mTL}C)*TX&kr{@;y}aShJQwC5CNc7^Rx8TUE^s0(n-|F?;(b`RgA0w zjjy)+z#yBJXHY9o#<#mw<}b=_PnW|61Sv98Y^e-9+&p1YWp~S$WZpCx?A3bi2k^`J z>(st+4>*hKB^wtx@72obop?4Gv<7i|NoA9EHPfK25`kE*R`guyT2mxBErH%*kuRR^ z)YulJJa?kT36`b5zB*5;(X*34!9CY)I&Ez4u)Q6ukwVjRQwSVi!?`;xLD8S{Fr%OR zW}}Gcf;Ar8oQjFh++v?gzhNV;>~`y|48h>ig(-Q{+KVau-}I+P&G;b1Sp`h!c)*f4D3BEgN2mP2 z19Yk2nZfd&>tOTskjZyuL%+M2~c(Do8PV4!|Ktu{h3BAaNs?KTf$XKR>lP zg2}2mTuq+`i4Tw|D87GXV{Q%vC2`cgkDnNF{!GuQyf3`t@F6gB8X%n)3H4g~sqKC8F_MqNZR)%XFUMpRf2zAJ&8kYEsP-rL#ZfWD%iT}8m7-B2T z<fc86UB<|r`Fh1zb!V5hfio)9?(_$FK#!LX&)j)wI)KL-P=1Z98 zRk8Jg>k^$)(DO2UVx7;hPh0S2gLo+D`j{7U!C%~EF9k-FG8C(z_8g@?iWzOCd=i68vTog20eU=jzg0C{*;H%9G_j4qe|g; zv(bcM7-nEHz&Um#KYq*0#Z|=Q2%sQIayQN_a*rn`tw6$uk*llPoJ<3rZP|ST&{qvK zYv$E2u!7I^JIUK+coAKx9yXk0X)KQMA|QjqZMx5rZ0XsSuZNzQ1vehDEnROb!0yH` z6cA^BCz;?=6LSUM~=$2UbJQ25G&HcggR&#L{YSHw4wx zKt+6dyfw3JF#qV@G0wW`t#bKsSqvnTckYgBw{o@-6Xl-!PAV<2RJ9ZAd8uG zWd203%j9r`0IJ)HRT>ds2m_iBe|?UA9YCPd4A>ojZ`}VUz-IyHZKB`gVqH10>NZ(! z^-Pi^BYK!3CK3wu&h~p0YF#ncjEQEn(v9ATrAs)}Yri?dABtdUD1%sTJEh$(YAltz zsa;$jH`tQiOhroNe0HC(Sn^btPx(}bRR&aRNxQmIBnxb+g6<3}UP8b1G%O9TDBf)! zt>u}}F1ijv8Ex2-cse-v9dvTO4FI7=G5h7-UZ7K<7r2oT`p|P0#7b9`-?#(FlzHng4uk4i4>8od}JG(t5oaiq{_m2NO2HMC8 z0bxP5i%REP@Afm=?40`gmdi-bX@;{0_+!VMLlu zjPHnb>k-A1V9%kUrhkm51Rd_Qcm=)rSxxok4M7J1Nv=o43#uJRkWmi`a z@2eMI&8^96ZuZgC)W*l)GTA3sSlLD~#f3M4w^)zJjqxSaz}cyKL7)w7o#A1pJA^qr z5AJn#bQl-leU-#fhPW?!t;SJQ2nU71aB@h;x>?zS~;@i<4ZsgWaQ8h*@$&2-P6mn0adD%c&JX;fil_of-HO10Z!=?v&#FjZdC>|^FG030+{1^j>)x}4BnTuLI3lfP7!qEN6<8ln97Y> z(P|O7I3sqCY%xg`%2_tl3#6%rwcvN=tx2n~t$WDsK^z)ZP^%Tat;$imvl>5)62ZSP?KQ!Z zY-34wFA}e^(u#iaICINMZ+=EN33h)oUQ~v-QqbSODZ|kxv6`8$V}`f&2&Eop^kqRd zG?Y22ikagG(wx)es%N0bIq}7U_j{3T1x3s_c#*H+u*fCjArBAJAF8q5Gulh;BO1`V zrj>~RoRqswMF?wgVP*MgX6MfUvNYSfB8^hk{jXKW-MGhdOA>{LbY>i6^aVRo zDB!5O(5SH!Kk3(OgyjzkTcRJFX+NtM%fBHR^zEG|es~vjp~)kgpPHJ*nu%(qz(fA> z<<;|#`hGc3;aOW%RvW&4ES?%fM;6h-M<@xoNB~6qCfEvKuAb%e(~eTi+0wI_3fe?~ zfDK(5;^LGHq>Gis17P>s@vlB9bR+iepnFowgJZpf81|iF_O}eWWN~VAu07PorjVMw zXsGSn{Yi+{6zZoT!CRRA?a&nwp9jk`8`s@ifA5R#}N?&wv8)8rJoN9kg?N- z%w6d7_!O7YWna2YG%t8xE=_qI-svxvUy3E^-w#4T9hXA)8TXrpu%^vSHqTQO3lkuA4viB7`#DR z0F-0=Y-Y)B1{I3A6xd-V|H`t zDAi^LUesifmRF2m&iSD*&}3m67Ld$Mp5~vP()x4jV8<+7!re@p*ynWkp%_A42#Ev zgosm8mirk6jS>^>6|JS)sxoCta#PAk|OM5M?^hh3($< z^#c7?><1<%!F1Q5M@{;7(4j@oEn39BzJWP{ex)DGi&)=Jhil`!bo+z!)7w?kt2A+t z2h*v3F@fKRQ%2^$VQ(lOit7#SsSx%7NQ6YQ$wIV~l39R7NCm9*K7%xX;OEld;x;=_ zVCCL!1)TZ^zHR&9uNl6{*jiAf=LF=j&I4pTBcN9XALOx!u#)YRMpfT2D2US?cM~q% z-tyxvcq8sK^g&LXNhKHe#p2xI50c6v{X2^`dy*InU&>XHeQentbL#;^=Z7?QN*{Xj zl9*l$KjHSX{}OLE8DhvsvJYMiY&vTFAkp(u=@=8HL%+X&dUW(n4=NAL3?}b|x*%l~ zl>Lmn8Phvac+qG5Y=PBJ1=$-}@^R6{xmmx^Uq+Aox_rtkjWgz z&MPyJ4xfj%Erk1h!v7}D|K!ja7y(1TGpQu=I-6W~w;t3+|C9p*6CTrOtB>&Ho@`^D z0=k4co|>|_1ee@Zd7@#%8MyrQ91vefP99IyGvDzx*udLch{RFvH>;Ug#dO76Ex(QQ zfj(m%q9>@p*0SKi-?D5F0t5#pgvJ?LsvRIKgodC+VygAzu~G)Mt+*n!ckto{KC_S}q5=KA%4TMzQO&TW=!TNu(MC5Iv@8=k9<5 zD{jR&;GfM_QBjp4o|?8>!a~m8M{?9j@p4h@oSf?YEXgY?UmHH+#QAmFf+_6i{7fWv zH|1uux#I*zu(xa0a^JsJ7*1#X%qgpqu*b((Qt8%(DaUSVT@&8rP0svm8z?ku#kqHS zJ#4G}l{>u81Ps(U*$nxnREQiNh;GMChcu3g?;xM9-uzBE3nOA-^MQkd6WbzcKOZQ%tU zA(?dlCqI*Q*^sEyua<%tZZ9p&$@84G`_2bnAf0M>7w zkdjWmFtJmj$9cGSLAsoc5dB+&$2NcCA|IwnbD!rj3OU_G?nf74=sGpay9r5=f@YE9 z*W45jKmJ#%4fu}|_h0{$uZUcy@n8e|ZTXy5Khni89FE!0G*|(h?~5R}E&Nxx<(Y1V zWYVu9Sh)2iqH=>9m67O$5AOBojURX2T`oZlyTYwFwF{ZlUxlw-z?PQg_t~rQk(3m5 zoM((D7JrV7ACluKVe@n2k*Z?c0-CvT20%;lWI&w#gI%}VW0Xkg@tiaum(uf*5Ehz# z!Vf~R((UuG-&6`+Yi`9jB!IRzFR$w)6HqB6Yp@)UcL4+$AJ&11sSoMG0w1Ovz;W)7 zJ0@|tJQW@H>;UFx-8}WND`Q!}1zu4VgY2kdOAR&>9hXy-k07k^6v(ewb!kA2_XIW7 zefOQ>QxT-#uS2N<6N`VJWdud=fjE|2LOUAxP!rN>P7z6`tQ6?@=t2> z*-z}itW=`Y`G#HZBgG~5oS>uTAyZI!kIdd>Clb;`&PPfo$6k%||rY-*aFW zHAU*i%E%~cC@UW*q)xR{P|&04#{d*nFDfh~eB(3NJ2*^Qar8202vEXQV0Tk9M|cfa zaLLK=^u^IC+HBnoC|rb(^0aq!bl)w@eE^ z8tF}1=9#7>fpQO4Mj#zxhYi;_A{7jK%g)Z7=Fz>22qY=YkGVh7qtmqMZd_PLF{pfs z0$&_~m-u@~nNX2raUL0CwYL(o0Hc3A8r^ zeEh@0qBD>6yy=0+Yzc6$rRClR?vJ;Q>Zw49gOHBZd02ckFnUh1C#>5B>OPpf%*>K1 z;ABSN+Xd{p7ory-0rT+4oKd0B>_|bB82jxxJ*X zV`ioi6r^EhCddFs1$G$N+QL|41p9vY`!j1*O550kV`{mbbf>Sa8mxQy#s2#BrY~LP z)B5e<+lKjq%6VyC1T-4SC+gG7N0sXW1?j-&QIb5^+)O_PE1FWVW$UD zq-|)5X=e$naPGbBZ3%JD{&F|voFP_TUiUJ+$GHAZ z%mhG9KN}$fij&h*3@j|B&68V3At9kU$^cgnkEF!JxU1qID3t_J<^EV9ogee`6IdOk zxh9;FKzl{*ozEyErO%+l8;rx#NoN~F(ST&=hpfV*xw+A)K4P~4+(C##V`LDJBs3xQ zb=f%fdJCI1mv?{$9=x~;u(yB@_sKPzj@%Dp&wWb~K9{mFID z&x5@#$HwF9=F)pkiI;YS$V2%fp#ovD^?zJFNJ=La6r1xXI&_K3?*od-r?!64D`{)9 zz?At;6sw17Yk!T88;K8fWEJNPu?FW-$E2h{q28K2k*rkgXI1kGQd?thiOSep#79k<+@RUKZ}NndIg7XdFjWA^pWbKKHKSup0l&F&s@B^`ZW*B z%cTJ#>$`Q&RE+eMHe6Mtq!bye~9qI<?8=%9#%OX?k%;z!uBu{9t9wK~+X-Muc8 z@GP}2C&v!m72FXr_X{fGEJ+xZ-xxhh6{`-A_Wn)h{fa{YOE4!l+rC{wu=d*lSPj;Z zr3=iE1Weu`G# zMRpIK8`ibW7H^kKP98rU0)Nkqo;sLkZKyh0J@a)aqk4`Te{|OSbIaX&%XYflVPRew zi^)~IeaxEk@(M6pE|+?kP)H!emJ%ag*|yH|iSF{VW}85jnQ9i&siyj;k|BTc++M{3 zk8-9>hm^Fbn42bT$Keo{(}bkmR|Fz||E>ZZ!l z0&k*tgYu&_ujAbXUrMfq2NbaczP(5yz$q>GD9()EYQwGtqWI>%fJQIgp0DM4?e5Ww zCKCyvr0{j7Cf1(oS5_GX%hF*f|4!pAj~p4b=O~&g+{_>N$4~ofDdV5@6~k&zX;MDD z+Y|lkHgCvYWiuFm;3QR^k!yy;IEH7u6DO!+@`|G=icU67?li{lI>U?+yS4I%?2Feo zS|dKhn$YBKL2+!t? zO?l93Y_ujKm1@N(>`tML%LeA&qhb$y*ocG0LG zdza7=pL?p>y2j0VTLAv3R!Q!AO76Ftn#xn#6GB7U;J7p2n)Q8G@!-{;=Pk=1feQ`~ zPtD4b^5SJ-kOgp_Z*H!$fx#^f+xGbQdQ6N_9cl8ZSX?aO7qM=?%(w4)-Ty$n=dWMW zyO`k`4fj4LCqKP9wyrbWG%_Bp126EingxlsZeeh6RIwrYr8A8wU0+(SfTczsJu(e; z-a>-b-J%U=e=0G>iFXQdNewic8KB$QEfpg#@wh0?xVV$GYR{5N8%t#>v~1))O*v!F zP^pc%G6{RFky^E}+EhtUdQS+O!G2}f02=G?Fjq(^({E%dZmOt8gX-jsq_|+c-c{Rk ztq}yloeFFVG_~^B`$L-TnrC^K#OWG$P4K!Eh&NZRM zSu&ILq5c40f^`aUe0JGZv)g!4skkfyJ<#5Co~wkcRp^32SRXLaA0C}BQM?qoDJA6# z;LpsDFK*p@0Q3R?ZV=Vm%V#rNc(*(Drcvkep&=nmM`XgK`h1|c$S{i4gM$>fe5442 z7#WeHj*fizBhL!k*u=zSjs|n*id-=Tg_JaBV^huP=j5q%GGe#N0$3i*4$)S z>XhBWstLnKYnV-fluuF}ytRFtUrb6W@@ze9PG5U!jDkYe{o9&IaA}R-)3h#)+Q7iC zfuG}Q=Ve&3G&3rqRXWIjR(rCUqL(*#!GHk_;sY2p-r<*G`v|gfraUc~|&<%^i!y66yQ5RP*OFxT)`{8wLBX9Vn#hjf( zL~clR3h_jGk+SCPzwBk!^^q2yJ*nfu!d*91E+P4}ca*R2x_M~{thYm#S{eL4GsY$L zjF!a;_I0zG)tU3Lni&U1L;ynd!Mhv{@%FCa;i=%wm$6}w5p9@>64bSa+UuF_tkD->u08@F=ul(g{H6rr|2O+l*)r8?Ze|p?^dQ>AL6UJrw z{O%2UE{ZS0kT<}IPB)hh_l6U-cD!p1wdVf1_m^pGw>KE|CaGoXD~r_HZi1Y=`sDkX z6?_#Z!!{FYLAGP%P*~|x1ZHv!cmB_ijOD$&c)Lx~*?P+j=0}Q4iy|=T=9N7t>2X^YB`0H;9(&U{O=ZOb2nveX128{x7d;>M1>Ew@Lfr_p?~RW&s=1qB6Z zY5GAiyBgGe-yDpFE9}@_o=4=~8V}>i+~8>cnlEs?=abEXv-z;ziX$mxPkfOk=Y!(= zZDt4GBwIwXeWjuJRPez}JZ!-`>{^V)^D~ym?IGd^UZ8H3U2P9dVS+nUd>|Ov$M0xkhiz%L5R=gDG2Ce z;!RAgv}}{rS)<+RAl;J3ZY+4JJ3P4yP2Q8tyo+C8Uy8mPuZzM(5H{-Czs=^x@8!mN z6VxoPhX%__pia{2rb{G=P=qn2p;Fyo;JFGKPvLW1#c}tMkN3e62pc$DTpUlaL3D%W z#p{|#LgDE2-eot+#r|o*92hplS2trbH5Bc)fUTM#B;eQfQ<=y)6$ZWrSG*u=x)UFYoI|80)Jpx2{98*z1K*=up6b z>Yji}>zhs~ZqUZ6AYk_io&}$NpELE>Hu2BdPr}D4x*f9dK6Pr-b6KS?yEK@OyC zPRPtOU0Gc7_AtGUGYt%!#v#_O3%g_Aw_on3M_x6+adg@DXlRQ>XV|rTE|X@vGiSP( zV44QCe=S+f!FN|@CW%g5#orrchm7g4+Wr)X4oFLJs5_J8X6@c%N%ZyrSq?-o_eMNL z{jO1_r&glHA1#SYml70|%rf^tnDvqXcB}*l(*ZDmDj)&Zn$f@}`^Xq0<#ako=ShlO zaON2gJNx+35@PCO8u)e)*YmjVwU1y|rI#C~JPRe4UmOSNbpm_U7YYhNG<0-hGK@7u zGwg7!iyVO?kmkke!wh;Z9MAY~VgcweUHYE(En`lvL+q_5g{)OZ ze?Bakzm1M@F+$@V#^<<=W3NbucVa-|p}va5MB^{{&;R`uBswo5f%Lu`VFFxSTuDjE z3b*&^)4v&sadCZ-{#I{#_~ts^_Rc%YlVJlOe_dW_DH#Dl+^=7sM~$zW%q$*SaK~yC z^B*1LpX#Kx-05dJym{tf`r*526(@wx+O z24)(X+-!`~v9q%?M@PqhE&acj6P35JvXY7a?=2&Fi8Mwr|GmVYzi$(t|4r5W=abK; zH-BUE{(%9k20cB!5d1G4RPhD#Z}7ymk*~d$)~sR^T@T*hJ%;rOAQJy~6Mpv|^?yc5 z_j7r&M4MXo57z(tovX(g=nt~ie>J+F>Dd_n{s8=&qvh)ADl021F5Zqa#m>t5NkfB+ zl{M-v=zkt6(#vN!I8$R|52Tjhl#tV|s<`+MMnCme!hqohbvvb@prCm7E+~+lojo)( z6rk&z936wR|3xxA^rdu@lby|OJsY!D>sh)~X+EZq#Mz_Q_Y|o32f8}?DlIL2!37k` z0h*tmACSgTS6A1KACv4a2lH@&qrH&8!0uE*@VkO?gl^yoU)0&rJ6!Wx-dE1%+7KBK zP!aAzp})VM&IM_pV*h+^ijtBNAnZ!Csu~*`<>loAw}H3n>+3sJs*CaT>GjQdQBBRI zqRH?(oJp)SkFuLewYwCxXI_O5ef@1p{oLWvK<-Fci>pK?Tw-UL7tw)hfpjfG?{`|F z*O$3E#o)kM>i@NZv!6&<$n)wwD{F=4^$De9=<|>cO_;XkL%Y7ZD%PoErJz_H$&#|M zv8n5`Gx!vuhC{`(WPGO0I6Xc6JE}Iym&X0$pI7^*=a_ezkIv%92q`)Dqr4PezTVD} z>UbWhq|YKiPh-%=j4#L5G^t>3b)}0$3gm{y!=rfl44gNF*=BTJMi9~g^#4o9+e=zH zFefLcy4pE>Vd53{(iwwPJAmbz)*HQQh;&m>#Y2^rLo3mFbV$%?Q-JD>hii!!L#8guHyqMfO0>L| z7aN8~o)#o0MuM6+&(FTI=+~c~jA=l=Zrn6U;S?KEyrD2K^uxBD_1e_?_PN4;x=9B1 zR#yP?`e(zZ|Bm`d1qkeI4^RxsI?Mmn4eFu~BNcD=)F~I4#OK{v8JmBB@5MzS>FUaj z>*nsh33|`M!a@-o7)WPkKJ%jnhuph-_iSqZ@oDba?+Ae=n*(E+s#3$eq15>f-re!h z*gQ&Z3R&+e)0@gBa;CY6H0U=AjUq+#Ehg?8U#4x5|1QP!H?{Ihiw3VK{I}=$k{c%= zdyi6*ljX%LG|^ArXutjNq5M6y3A+NxLW=eEy4eNw(X7_js$3`j%2)RIKOfIeA8$)o zU{D@jWMtV|H`tQQPY1p&wCZT87dVw|&f`p>|4L&1pL_N(h{k8ItmXB@s%09VV%wiS zSqsK$w?`w@_G-F&Bfu-!Hu2U4XFECidGAH+TFO3{U{g;^IyBDLmlrO`nJOI;I5IJ| zA_JkJav1%!%oVf)LmW(5h;>G4J}n}|Z^J|WyZJoy=d&7(FTCe$m2kE!PkLae-^xlHi+R2~aZlSEE$6*SCJI2$Pk-Xj9j-qzs>5`> z(NHEikgOK#PW9hwD=`+Kvu71%a-}y6x1ROguk}Qv;zrgN`Pp>EZFpKn2P;*Fw|+VB>Fl4|w@{`N%0Ku*#~L251lU+2yJ%L+EJ|qgcoV zpXzF>aC{Cj9&u(N|cpoy!S>N)-%2$6FD_C`iVMk>6X-dF}PF);`7 zO(0DJgGOnLG*w(&98iB(!VS$nU-j^Vsf~V3rB4Y)-p52%?}c)07~W@U@)!TTpNbFf z-~S_F&lUNZi28Yi^W?^Pz1okWY^WBL)!CEi{NtbS;E098RWP19SJ^HYC zd&Pd1RD`IgsJ)_4_xsS;*jO-_ZPfHX7w}mU|NQy0y}iAv>Ns$iynjDDJp5125EYkC zTu?-WH~hj{TwL4$NQ+`_Vey)XC?P3{!F&C`n>^AL{*#wX!;_QFc6RRuGyij0q~NdGfB+5g2ENHNHd z{`XY;K%hlGQ7ILfnxejj}6GNL`(q3?b@E_tQBs**Ey_Os$W%*9)}A{%f<(QW~&<`q6#iX0_HX5~MW(b~Kk!=J|9|1RPCqVR=L zO1vGUwN=#VsrcFL#QG_2DTJZlzT|L-Mi=uXQeHWcIM(D%kfqzN)D(I0%*6+ zb>*=fn+OFF0_1Huwq<18PA~_przBc<_7)SfZ6f+!%x)_Nwk5l3)&)hSxj;6lgK~_`boPpT9pl~ly%~I%K9d3(wArB<} zvdZf9Pu!i&)f0$A6OV7c)R)MAuU3hw{l$EGW1#3_{?oitukR+|pE<%l+!GMRY#6ud z_FnP++vV-gbaI!2m8evGZpRxt)kpBE4O*X%f^4&OQIU|;)KuT{pjf$*>NbKj%#Xe5 zKicEF2(YYm+ZI)gbXr<-KIWBMGJ9WL$p5<8T%TWr*r?-&g^F*6b7*7hkpB9|No#*g zp(M=7Va(-~HDEBH?E>n4%*kn~TVD*l$TC^e zAm?xJuC&}lq8S}-6Kk@>-ly8^7x#e;Xdo4;K zTYsT(I!L^l$Rgx%+8h40Grp5^uWmy?uKiWD{)=yXD$5COVVL7qN$iy?eHZv?Z;H8w z^s9^DF4)*$LZwaQR0-&U3v1lG*1Wg?V#>ERKSYICb+2*OOE{0M?o}c#aC^)_P7 z4JnJv*#yxUw(uqDKg=tiiW2e637cvwEKUI!2cSfmZv|x#% z5pVMN=D858r(nZWw>&i#Dy7q(1D!k5xopXFS~`|1QdJG|0Npir&X6kV`~ta7eUajj z#Y(=EN;@}q3Xs>-T~MXGJ_R>#@osQbP#C9roz?{$Kz@twcloUaz}1p#Jv_1A;$~^J z$Vh0L?ql)EpuC?X2rU_{@ShCWoCI z$cW4HIDCgmO8Y1Fo_C^nRb6nd^b@o7BEcuO_C=l)9aM3fJ;KGx!+M*`KD}sq z3@q!SS0*vc3+zH3jUy}TpPgO5SNJ3oUJ?3U!L~7~J z#i*z{;ih}kQP?+?mbS7W3tiZxW%@}kN|9-T)hooeuv(0G(L?S8iTLnx=`yByCWSWO zoX^EJGs)yQWyn@|e?OZ+0KTosO9b#ycDU$LjylYw)wWKwxDkK@Ykx(hT9kos4f#Gw zVq0Km_}GgPmpVCZ#v{yec{3rbk4>DvtyfgdZ^dH}lcmC;hnyWME}pIIv9e%_jQMQras)qSLsO0_-^?5M#ZIF4TU?|BFG+EA1JPbx2_r;&KnI>`bScYHNFw1YN@vt=M~E>i=hzU%UBI2rGhNvPJPj_By+qp78n zU3nd$65F{>NZ8!jD*;;@mpLmOC3=dyM8Su)sMcTU=7|Cih4L3W{;I^FES6B1f*1x( z*PwS+m+E#5su~&5ReZDM`FdB4z_M0bD2*!bo^R@C7b^p|HdkJn5}ui>4s?ne9gco$ z?j=@c1f2b)mWGxS-;UeJ!#7)s*q1+dH-W~q=gd4W1>s+Z5YArePj#2(MfInKE8OGj zwgh{f(7|P`OQ0IOf~l zjo9EsO=|HdYv;MA?zG1g%8Q`D>HH(Jj5iyn0l#9bbUR1aAXHJM5Sz|}QRfm1xgj#a zyF>I{^UJvVI?9r^;-`8<)LW~R6rZZDf?$FjIiRJC;4sXHRn=^}jL4v1$cmC9sq~G} z8sa0>G1*Y5u8g9FkwzXYm^f!yYFV}@EdkDAs@GBEPQ!vj+?0HbPUzxn57H5pO-ee_l!ri>}rA~KMO6gyT zQ)3V#sKdw4&)5!Wm#Tw{)LWyaY;(k8aJ`@75|R_7W*eAC7pXL~!UsV-%w#|Un%o{!qEMErv}G_|&s0G5uUFu}bMO@xJod5q(ch+5TeM_HjAcOz`f;$8c z5ZpaMgF|o+?oQ(t2=4Cg?(XgoTpDQHT^fh!-+k^g_nEck1hrD21vZ%YC+R%KPv?)?{%&c0(i&>Kvu7<+m|iIBix;V?b>E`t;^!_90rFuQ#u(2h zD#-_#Hg4|^sj#^adn(&A*^#q%{mTdKddD-ZuyUO+AtRes;T|I=8vp1jDN^IrC9-Ly zi$;MIM|w!##d3PoysXU1iIviV%8QktYlOB39x5%AyRFSk4Te5xo_&BQKp-ZJOd_UK0_&yV;mg)CF-I4Y7zYMS&Qz^H4ya)j-chQvYi)Wvoc`t%rzc$>|{GOXQCY zR_ATcsqAT86)hBk)z-=44O9@9($iT=;NJZF{HiV5jgkEDM4L;G`oA!>)%xw#X=Z{ozd%@E*xjgpp$ zSe}(^;k9?#DyaP%}zm72dLL`%?c zTwVO8a{63hn+R!*Q1cl1hCF1@mc6XS^YuvH^W9YfZ<677vMz{_r zQrml@cQ+52Q1k^6mn{BLEJ~b@r;~~$D&-R!a zUhmThb0x3JR8oD)xIaG_oQ9AczmK{`rtgiSyt|!`IPOV!EC;*n9GtmDPz{-egYK6N z54MP(8Yjw=oLpzBRpco}-R9OkRTZH|!Bf3iL>&n(ns$8szy*VzgolGOgr_!sBv-Eg zb!M+uC?HAwNy}3uKEd14x8SOACvAb4)$-+c+#9j>G>F-*r~A+p1NvO|_B=JopAGi8 zBU);5Q}yToA@emo96JydWy2?SuCKPefPd%ehTW0grOki#zWYmpe4dYij(ZKhhln_f zc|_>!H@UoIMSPrzty|;xZ%Yl)o{pBfO;hKP#Kr>jZH}&4jogwb5y#Vf%U<|z=vnTA<)_Sn^|ty z?0!@h&$g;g8%GKGX9pMEmq(!>e7>oHrqkTM!44miQ686rwYjUc63as-d21fdVVB@K zq#<<0MvM5D0`DS*DPDBRE%53RpG*Hz{cQfc?#(3|(gsj3xfWraxdPVybj#bCZHIUn|#4MpOl=4%9rM{wvC zkyuEmMU|{~SuuH+`8EB6os&_WE)6{sPhD+*{-D8G8?4e~SEvq)isHyM6$;(g5&pu{ z?JB$| z&`W?lbzZaiWTSY+3uULi+x$17+G;WP$@3MA94xtfQveeayMV*arrvz17>S0@mr={T zkpehbH_;uP%ZZ$AK4ZQ+9nbx>s42h%(?5&yw`CeG0*n<@ZO9@%xP@X+P?nEq!Sm%z zHO0{Bi!0u=;{Az?Xg`}1v|6sJ_!eczeJ3EmmAUCNxj1OB?K`mxOiUDT?l$!;y(MO@ zC4w3qJulZ*ad}S`^1BuvIeF8izsqdMkNHN>W4HXYK3UcJ zA2D4L!-?68^25Xg-yb5VCoMVC^_FaIWVH%Ym7B>Zj#`K$B)pI{7aV?B%qT`=H8huC ze&-EM@BKMtMf90PCVTvjhhzr>d$-WYF9(##Vq(j;N(a2X=e+|TP1T%=qmTXj#MiX> zYONW#_>kG?oAie|t4nCjTiOOnS~xFQet6z&B#1UZe5dCrR2z$@-RELO?kHwLf+@+O zGW(0(%ao`>yA*_ol3!Q03pyVjifGhZ`rD(tzW5XAyzQGwFI(S@vxY%)`fqR=gzhr+k{ zj@Gsf!;Mq4uY~SSdfBpNiO!Q1S{mzX9$!R91Hq`CReOqkVn5=qjxNSCQ3Qx9CdNX1ycGu@{ zj_aFp^$Yrle@D#5l|G>$mOnA191zu8o`W7|O}N3SMq1Z2Y(JZiNj1BJYB7}%R|k}jP7j8`U($YYz6x zYaPE}dK-Es9-1Nob9OdX`pM(;ZC^uWNWtu-k%A5&pC`MasWu7D8#Defp-hU%ZM@S$ zWG15p@G%UREfJ}n?2nHuqUr59Lf$xerCKAs%Da>8_(4Ct0wF-$Pw02M&-c#TS)8lR z?kbj;4=z71z0?|98VeSiVA%q{$$Gs~CigGk9QdeV;rVLvZWHu8kWcR{z2nZu5C1|ds>aTOJeEzK!~&~Bqlzpp2EuHOiU@s9g|p{sO(Iso zLD*SaCAs0HHP)(dC#o%e?vvP^y2&fXt1OMva}g49St|l{Eg`+{larpA}RE5 zM`$XIUy!%1xsz zjY90|MEd~2@wdXa+DjBifmkX3#k=#Co0i+|0uQ-NsPy@>OM|u+uBbOD9DW3nvz%Ol zt6T!tr1$#$R8CwwQ@OcKfBg07g1D2z+Z*TIHJ&C<9W-cJAXZl8Fd6r1H&){zzF4Q5 z;6TWP5G3^jKk5f8A1=acW%i=c`efk;gQyeb_9rwa5Wnfx27%^w85jM{};C>#grf<+x5bJ~wI2R|ONkK$JPjg99zSde7tjuGKv!M~1uI*UByz&*Hx| zIdReVoB~6QS}QMAx@_}QzZ7e?r~fw*C1U(yld?cn?#G{4w!zHp+|Ih}9u zuPWt|WLJ&R?Vb2|IX{;bIYaQ|L51Jn+)!G9$!pakU1?167nS=v*(t7X14&X|?OpQf z`H__g=7$5)SqOKk@#W8WNuM6?HHM#Xf73KouDdIBTqjQWS3HPPdNt^;6c)E$KWd7; z7YL>#H~90Ih`Qx)$W^3b+nLk5YB}^?i@yCl+%T%=HW4L@1=scNVo5rOw zPpn_1n&aNa7cp_-d5iq%IG3hcS=j^moXgUCEe|rO{WxcQ(_ShmPs;z9oLtw>h} zKM!K)K4s0>b@#5%oS~kyf~1S4;WZQ{RO@(4Ay$RG3_j7@_5Mq%XC9d$$i3{7qzVHt z8TpFySD)>g=fsln`wbqgjfTib@sk)D(pw3&C+}2^NoY{K`Dt`u!|84m-fHFFHu9XC zZ`&C0%J#M^p!vlnw{IA-2og)d_9tOPDrBpYFC6uL(Y>`9lHUyjvb-Iz)o(Qg-yAyhF^ifmG-p@8fm~LuUhmvx zE!S^0yVoaHWtF%5U+!Mo9t?yh@Y4d9kb}LtOt;F13UAwqWJZyH3JP&IKdYyEZ)>8C zx(RNnnDMobjaEu~-0lxLmyxN;Bl5Y+<;XfT#DZUl z1&npu2o%GIJ5F;kr9D))(9sQ-Y}Q7Am_v+2E5FQh6M-Et9*q;FIdY=A1WbZ08ird! zn40CmGAbPP*JquF{i}hRqWyR-+CJpYC&TdmnqRX+NitNk)K?dx$#U!OtA~abt5S(E z;wlSmH`fo&^Bjjf$}rIh_qeJT@;_5(ab=l=F-DyzD#f27Nr8oYQp#1AAKT1g!`?6+ z?an6~l)zs49N|{&nqLJ4Jd)wEf}8&oo8qc5Xx*@qYbfZR{B-#PUZqWOG~G2U6|ZPT zmOuN6FK|6&lD4fZYw5IZca^mlK!Bh7gSN!m;gan4>mt}BgIXTEFs7@frWe)W=?;z% zhbz_MUMjWXX|zzf{XS1$ES>2yDHs~G1FiZ?4@_&tD-r-bP1Twf>X>rQ8|E`b*|z6x zL7ho~m)ZFumi)Y;u_A|vpqo0|76&`DTSTv8O>^m7KM`e%TWgDfeULNhqK!1z+~;Ei zDX6CON3z|u>>%3G@)WcOrkv}F$x}c}gClV3S@*G`MOO24Q-)Z8@Z+@>TXTU9&+f<^Er%nau>lQ)zaL zr-TnDX`C#2tri2E6(*KiBY~P5At0v;0n?jNxb&C)K^#wmQMJaZ?z83E1K;8XYd7zc zG`vWoyy2^xk4`O3NoYDJzgGT|gDfqrjXi&1&+AgZsVL`w%N}HXJg?6d^QYdSv@XsTF!h-*P0Y)HSiTfjOx@QQi+#F^4jnbAUg)z@mr74 zF=9V}HGl1oIkw*jf;2cxyjj~0Qn)cx zOWnfsm7c$N2y=A=lgSd@q%3jC&#u02bi`mCJQcsw0B!oLJ^rAET;Y^aAqY(2K?1^r zggU+7uICf8^gx=gOsA~b5C4+-e!1Qe6LBtSdrNnmIz1m-vzDDriiEb+Nf&Z~!faTW zwC;HNSX4q{ilPBEv0Jk5Oe*DeaY(gV`-5&5!jX1Wj(=^NjXm!-StaSHsfo6Vf?;Rg#{~?rDFUbSu}cJ=|#D zls255|5#DRnci-@+WlytLT*sN>;63Cv48GOjKictYippFcYcI|8NZ;PNDKbe6O)mf z@^+FkbL?}OUN~I2uAW5#6pODiXO#841tbx4I#Ru6sBI8hr!Yz6j<>I=NF3^b6pPYBY5oT_Vt?| zTgvX%JZq}j;URg9f1(~=1$Y*J&sp&@@-ExQ_|3$#7tBrF481`tZ_k^$RMIMaTH4}< zd}%Y_OuuH>S1%t<>m-)@u-UKAbTW`D;c-|CK$$ct0(=jBcGoPqaZ-LEnV;*05MSAA z>UmlT?bV^DAspMZ%U5Y$J&BVUyOlsmK{`=o>#N`Xt#y0WX>7k_%ateo&KPDZRTcKr z3>FX6V)A`8d9l5|x2ePA=2#0&|>Ks+hE_pL$a*vLAy)%jpLy~E&7cv z6*vP$IFH-T;*=+85`u&0PFlb6fsIrA3aE1MN{eq^)~Br@-cMQsmXj4qedBcv-4v#_ zsr=@HiJR7YG!9T`M0{cX>!>M?xGcxsRj6VZm@0v-YF&Rf=g>L=Z>w|E@;83kcfP37 zsgyeJk!owj5@7+yrpoKK1|Z#(0#84#CsQOS%o)Dp*DU+bX|mr@Jv0AA zf+E1^F_DpzYi%yjTZvBMb2&RWIEZ(m9VMAN{RhMW73cm#^N1mT1h(CX{OhWrtxS^t zFpJpP*=cJNRf-=%uc9n3&(PXhX9k`&PN7MfZO&R4n_*2s3>gmC#{SG{~# z+}4)lExR>HLSQ2i)`Ei`Y?8QpWe*qy(2Lmtc^R>dh4V=S03)iRj-X zBqSUQR7wc2|MLwSO+Dh;I;&-s{v|az!{wt(bs<7+FHMpkq)qTcxH z@{Di#P?PhDGm*c=n{C~^`+hy590_mj*#yz-2ozV>wg_a$#1HwZO)%M>{)1BTBbxU; zIe*75zW8_6Pma&w16q}y(HJp1^NBV#CJR97tSD8i-8x0Jg>mg>_o0U*L@C*)*DePta?5kgW=by|nOm#v*+~JkW^*8}K8qB_(^+>rEukOfZdf(X@Q~^6 z;NThCs)Kp!?q)X$J!uDq?U^m14%biVcc@r>8C2x4?Mtln(p`$P&O%a?_QZ}}l#X0c zGdsmxQCZ$U7=Js^Bjb`fY~Lg#Eqi~BcQURmGQKs3p`}v$^6$yFYw(dkR-3)XG|au> zxQXCqsyUEuGm3Pq_Z#EcYI_Z#ko)AS;E2)}A45heTAr858;kd?&@l+b6yn$4A1}`vt0P)j`EKRpZ*$8{WodZFM+D8UKsNBQ z{n46FD@4ovN>M$vFeb+W!#w0&6z*I@^_?02t+wYn8E(?W*8Nrtu|=D@Dmy2Z2KQ6_ zk&xs0b`=k&RJ+gX%+vh=O%cX&L; ztHqeM%$H`o2R)^j9m5y8!^0y2uA74RV9F`ROt)Jq#{2Py zA^49^$n*jygNa=pT$lB1*!To0wPg#{V@tb9g1bMU5MN~`YG~-2-R{X+bM8~%=hH1S zEx0sY1ab$}WJ@1a4lE!fjJ}q_OXAVl5`liZ)R4&t{z-c$q(@F1;)Q1X*8BbO@n937 zRTkvlnY?ZIwY2NrysJ|<>p-xzfF-+=EfenzO>NWDD@J9aCI3lwFtLHkJlX8k(@`in;QvfVyh$>2RetMcM6^fz(mF;W-)yuxPx5Z9uvu`k^$k^QIv{%BNQQ-j-=rGE(gQzbY z6L|v9ugfB>V{1=Oj?oHU|5zYuOD6$pOshrw>vzYIpNwhgPuAqRERIf=Rj>H#>QzC; z^D@Mpk+E@{BwuHS6Y!2NC77Z7g6?XmziI{4}YYFDkS%kzZM5d5`NlGW5_LiM== zkSfY&dJzf&(5iGt5#^&CRA1m1Vb3KPC&Bm{r9HWrw3u4FLrXvHJeO0)>JbfZp&K+l z&8(Buv+5@eWJEl7$ z)|t=bT?}9qSNglKsAfAwV=n~wg~3ZayRy=T=`hloL59&XDD%Zq;F&eAb4XkzI&0sl|F*cn%3T$d*&yX|aPCpTp!1nzr zbiVJnr-B)b-+CfB?5TQRd7%L**lzP%{c5(>>Y$eaYB}CmkJvmsy#`1+>yGo%NQ(di ziA2_hSJ*0peZ&oM|vsgnBnLmzCj0b8)+G{s+ z&{^TU$T}&jK8Y&T?rpMwCH?EM@JHQoEw9m{vJBDo^<;@5q;KJe71hH zq#YS!VSfU-5uLK4)oaQ7?k$EKXOzo6(b8I=q#t-ZYUu3>yBbp&^8*02EXNz09t;40 z(b~M%&^71>;In$xXzC9@?v2!NBea9^dCPqa0^qNzlX2MC2QO@Rc%afgrf1u#gc28n zZCul21LsdeX62heIV~^FuB6|Mg6rFz56|w=T-3uXaT| z+rPdo_2_^maq8s_cRgG2_gH$uODLJD`q{H;pBUf59*x9Gr%116W*o#T?Mc&+BgdH) zXNk5F`h{K+i@%luG^}Nv$0ym&d1>NeRYrP(^ynBskvOnKDk*(mB|w8 z?d;j$=lKq8N`T1n}(-NY{{X;&TT7YdZGq%c)0H z8?Do|lL(Q|cLR`_c4&A}vER$|4*G1rdmfF9K6wxLOdr=2BsiyCYwfK!kis%uVk$*P zHzu@4{gwF3M^R(B;W_5EI6VTII*1J7KMD*-J%^W4X; zI-EtG2dp}YMp=#q(7(=n7k)$_zUQqXW}tsg76HwiOTCQo@SDSIarQ97!VDh3PTDqz zvG%m8=T|X)R4S=c$NjO~?To0Z4syDQVPRFy7bf~D3!^q8aLUVAQ3SKHA@f|gRZ{x6 zrQf>UH4`;XeKgj9`OvkHnyRX|drHD5eCF?umgzh^gzw8(pz}URM#t++4D;KabnPOD zVqY=4yymIC}4*yw0UXCHlLO;Kg*d;LMpQ6vYX(N=%rL{blh7Y+w&9?Nj!gMX}0pfq(y z5S85&ssi})WH_xDo1~;LP0Z;yyBm2OUp)NLzJXI&DO&Bs)M__w>8{=J-S4D}X@>r$CTU(k^eEYh6 zbYS_P{PNJ>1#h>HkW==Ka6LBbJS)} zqrZ6u^SG8^C@K8R27H>wRskCs5jesYwFT;qFztVkM5JPVq12`wvujtLOYj>F>=tZ8 zf87Z;Ed&Fnm^}kdu~zB1k-{Pmog~q&ZOM-sguq{cbjRxn;aiWbi%C_xml?yNKw}g$ zZUpzEeUc@QvKPON9a3aTbm01txu1*4zIzDueD{KQNCxoQUZS;(oBrBAKjHLq&cf=3 z2Ac?&z>QQ&O0Z#c=f!&w9z9^~oH+S;CnHC0Em%b5d(Q8=W2?=Xu%@hNh8lq1AG=62 zVisLAx2dIXJm&@Nn?c1z?CT&_psL;P#;4BYB@w~FbF|6EyYu2dGnSak3a(to5uui% zs{vuAO(6R?t_p5di$+Rr)-$JUpwbM%)C;tFG@ifY56NGEcV*1`XU7((a&cVsjlZ0A z9HOmCZF3}NTobBnNN!Wxw!P6to*{iN6Q}5yi7KYhI*$w-=HGP{#Yg+D0!NEzo7OKP z0@QRg{PA0D(`Xz8b}r%|Yz?$*o?yLHo3wokeHG#iTWjl(Fe)Sce@8@3@a2 zXTTk#zrE!6obB~vqk)Yj%cDZl%nUr zP`CKM-I+HAJ4Eakn7)%eEB=n5 zn06pD@0*&+r$IZSp%qi~u;)#W&F>I=roNdv!A2A3w7O+V&#HG4i-@BDKyrROr5p|y z2PWmTo#icMQkaDxh{C0W!zid~g}qM%^1U26kIwm_*FVejPev3oj^$VHF~gZ3v6Q12 zt2AG|jrO`ICZ!7b8O#dK*@X``zw;@^zSADO?A~qghX-KBPiMbMD`mEAbVRJ;-$qgx zb#5+D=?V0d<_GlQQm^x2r#0DieD^@Ryd={II$3eFSS^AQOU&#WnyXeRBuc8Qy?(-s zh{}6E=o_+1V!x@g z)K8E3;TUp(0vS`jo!e7VHWgH!%&*n)83_Fyx<@O5VP9YEdSfxPADzZF=>`1a`EfG) z>n=L(0b+>)1NidO!u|14PdBK@EZlAm8aVv^GU9PrN5X$Enrtb2m)Wj{04Y#NpAx&* zoCf^*b+8}aml+lwOZ;U0w3Vu+*@^iyp>0nrr?_$a-vv)`RqlpF+~7-DHhX{G8tCRg zYn)Q;fq9QFat2Jwk9RrilzF|zimO3cWw~8BNwx~$sj+0}e~@FGtV6~Hm&w$=(!++gC-MdZaXf!Wdv#8)))!IC?m~XVLziI%6oKtoUU|Cp zlL&9I7+dTjCg#(}=ZNyE(#;Pew3=@2TH^3$(z*@~r8oP{7x#&m9&2B@AB=!v*l4~h zPx^}Q0W#_!gVkaEQ&R)b8u8N^o!k0S+i)<_FB^gzUa!>vWcfwZquS4~`_t2Z)8-CM z<*f1Of5WJwC>E1&dY$K#3yFwt0er^@K;a}Mk^Th}W)$NVy*U?UXG5pZiXnNl%(pix zyf&CRll_9QizLKQ@a!1f4;p*ZI!h~WPE@QB)ymFI4`6w}qW+pg3!oMtQT`tukVFqN z5k*V7UPBG4|KEwkihW3TP(p(xf z;l4B9*BN_WtXy_M%36!n9`p@u(DcA!-)~0&B>Ohy3%|C6HU>sc_<~<(TGMroIHP` ze^nTV^Cx}q)_VNehi}STc!IS2N06_~PoEfJv*>-VoAaGFTnM7Z?fa9=Mlt1d2W9U0PI_1*6G!1mTc_wD->0)nrN%jh zu~*_0eVLWs(RcD*SK(p=km{IH5A-zuNfWI2IR|qCb>f_vnT1)#206=Ci#*4$ifm4pe;4OZtd*!ocSF0-ICPE`?E0-4j-W@abHeOWuO?qNjB60 zyxV0){=M623yVP?AgmA^>eW>OI!_exRvw4T<(wE&pDemolDd2{P;Kw(1SLRPVv`T% z*leTl8WwBGHur^p#IL;_3*Z)ymyjsU1;F@{(?Nh-!-47fWxj|g+UPaYr7xTC)B^n! zPQzRvGD6E^ZY)Ge7Fwo?6U9qm?Q1_Z2>u9rXlZD=R1Z(?FluW?KMq zhpVlfqEud3JORP?eFqc^MXwyRJiM$B&#O~E!XdaB!);FkChPk9t7kwT;7`POgjls- zU}|ZqPlen&G4puvZ$+@D%-nqKH(@QmT(i?-B2M62Nz%6XAn~}WV+ZGV@q@xY%tf_@ zG4Gxw?udPh$H(X`J@8pIsmiZ0oHc7799!viu!a@ALbc<9;xXCC~ zo|{#L7-9W*#}Ex(_6FNLeF`6*<1?*nQTLt6H#o$Gf#-{$NsYub* zOb%IGb)`7wBh3wWl+D(^)PD~4-4;DfhH9SZ+t`l`0AFEg(!6u=*!TB4t)Ak~iyhu~ z-VDME&0`RUox*Oa{1Do2}{ZdnLYi)yQA|{sIsLp zf7%W%Wc|u!Daq&FC$T(O>!|*4clef%T*4xh1H8tz_@=`oAPHOio@9E+#3kj&S8}kH zB%Ghh7&RbI>W3sDh>^hF?qMR#R1i)D#o4Z~of`^J@x0RY&w7hU`k zmZJNaK(*WAkrbqrrDsAnBa-Dz*%panFq+G)aJ%;q&e!fabyV9l_0&d6Kn9zi{O3#c z@sg3=^t+tzvnTU%1={Yd;$(NdUL}Z%iMaquNdt^+zn`4yo;uxebR{bt%pVm~t1XN% z1|DuEF4auOZ}o7Dy`3xFhvxr2ex`j;>N-TFe&!;Av2J5&)ygzq(uDBiX8D90%#tJD zjh@%0VI_i9lT$Rt8&u9ZbIpcsZ`X1m$})>Iv=`^I^Okgg*C z6uF{h^}HFv3j3+=!@Oojx}t--c;c*Z2t@}5m_Lzho#~U{*LvOhd(7uGO>toWDwCV> z+Kp=@KfP^w+4^A7GWWkZ9Egrobqpl@X$3yM$~k#r7df>f-(<{u72+2z1z>;hL-3W1 z`q&OJdz`PMAxCAZUbXCG*-THekFpK>kE=awD?GR8<%!YuwlpSh^;5JF+|6>l{et^; zNx`A!5rBw1zq;PU-drrHZ8%(i(I0_&g%^#Im8p#+*l}n`97JAXVbHdDK!E)Hex3Xe zrKDds0Nh`mo*s^u1;frL225^YO`w#F{rn>|bT%eD9rf-^=$U>{mXL;JmlmNmD<57K zV`N2e&Fb$-v5R)>4*E9^ZH%<}g1a@5*&SZi4?@*4n`oFUCsiWwwH37*%j>4r-@bk8 zwy5IqY2`V9B+m{}E})mQf-s&`(4UuFoz2gL{baQ=|$evYf@5#aB_1{A-@ zL<}6C84Da2hf6K&83|Ic%Y;+1WQY9C4jFj8@?Yg@ag!xb@?0HCAw0xSCMffkTmYWa zmfMd1xpN~Os880rRUm4E8!@T*(QTHS%U#J2tm%M7^+il$N`4FaB#wzauyS4Xj1W|6 zZ1FV`j)n{3DmQ_~1p}TQ#EyvArTtc0hA2{meGCg7&p1;lTt4BgJ2wZllOGo1iPFBj zV@G~sap1m?%7sb^TAu5hQ+4#TUib7ZoK`GR0SQttfZX!pW~~5?bbTvId6;!jSW#tC zBMhLvW?2tcI8VbS1Z2U0QtrXG_f(`312CG<3rd>O!?QaRb6h_Uzw9{lmSdsl1TU$;0!n$G4F+Itov1Fwal($JZs9r;+f1Js+ zrV>!!!CUJNo;|w_DB%@vg~eM=CB{sdve3u%DSe44BS?yl@BVE?>-ic92hc`UJITV) zFdJUqbSX5SnIuL<(otH5eJm88%RMR2jf9hpH!;RB2rPUL>&5Xx+`oU)PahSkZcXXy z`zJP+67}2F(Q<^(b`J?7HPvs!ZhG%mKUvsMM5t)NGdBXdl_a2_q4#C!b;s(T$))-L zb`2@(sL=!oj4Wf0vHT16p^J+(Az8~V+UtK6GF@Mu8IEiHXoB$odP?cY!`{EP#G0^N7iHeP)ZQC zbua&*$RuAdR{fA^leWc{MDnfvfI`q_B;d0oXZbPpi&Z% zXv(T}=;|3$vT&d5+n~cqT!F0tGG3!Kcr6y;&>~Gac@|c*?k4+?mc$n{Y(5Ywd!*A*h zzLi~nT&B9%!RB)VoD@roqa(8~r3V_eBS+@;95N0kgKKqa$*d zj}vVB$)^M3*Ce{&D`Y;-3>hizW_LaDMg8cATNFy!KY=iS52$v?+J{Hz&Es-NZ~z%m zWvn9&tK2FxSU>=e~hmOADz`LF-qUhlAXk`S|FKI&yPGe$Y z!gGenzRqQOljt;)3PRAv^!=2_@PV+eilS}COM{MyZKW2>GvA4}x z-+0=cP@_Wr;g;|51T>iEY}!{&<*{95YP8;p;mG{R#Q8lo`CnFb>-D>ai){u|z5uKK zW#`5;meN%ZojGk59VUP_yCzqUa7 zBZP7KXekXsAZ33aFs;ia4n10J39Z0tUQ;MVF*T9q%MB5h9j}PSe?%xnx+OB#ws*L{orCL) z>~q4y5LOP&4z4eaDd@ZDVb%UQYycGX?E@Iwhco7NXN475Fa^tmsPmdW8n7W1c})}Cgrq*@a;E)P(KY(*;SY)`1FaVBM0FM?`0d9^*-9l1 z-bg2QJr6duwWcY>{3|HAf4Cuy_}y%ib<0m#PGf4F5|&g}ji)CnOOKCUT*-5ILSX$| z=x2z%52|opIq};BXzf9(C)R;zb*apK;%P{}h#!z{bWnerG`#LC;QPl91h>{|%IIR9 zzY@W1G>IpwInloWEiGST0+gtMo6Rg0kyv$0@pz{dI@Pw9>_Y)6^Y*Fg~JwAL6X_W7*hWI}$X^+_GCz0iiD}E7Eti2^51IdjX^nf&vO@^U`uFoCM6h z#!`*QHxXUs1*7%`=S75qiCYxyayA$g<-PjuXkZ*~ZDVq9@`t&)BgFd>uOe1l37u6o zF?Ra?*^zbq$xyEnx81dU$87>fc}n=GeI51VlZ_o*Eg=UFgZdyF(?87U&)2)eXL5Ck zCu3?_PW;|s3EY5RNV83+&Ocq-9W%GXsoD%ly!X1eUYwkQQ*+xwv~cA}tOZO~M#t{s zbrASbicirWjROk)hnLYssH&xf4B)a^#p826;i3{J+}3$yC_(XbSk@^J_+OjuP}5bk z=|iolu4eUjj*Hv+uREE)wW`+sFFac$^+m*bo2omZ{Bd*RwiGl#Wybf#+Iqp z*R8X-nH?^#ZkY=_$~%3pR{kNCsl96XHnNXa^e{(G-FW))`xA4`b-MN(JhR}(gOgk} z`H_!*0FSA2@0a^K-%5ew)Bc5uSCbdKww^yHWPM$I`m{Iwim&a(w|Zos;AH-wwfxgUIh-G z!~X&;Gh~i)HZ8dPa(^|Vvj=g>3IEp~4&Gi~z)KKbynda0!~VtAiYA4)Jr#25 zBiRa8|7S~|kPJgWM8t`-&HMj+pWooO9H==fJNy5;Ms%a?d4Id7&Jje6o`T#s;lKHZ k`?d_If&x$eFaOURe?LiY$E{~uK?|-tUHx3vIVCg!05ntyyZ`_I diff --git a/planning/autoware_static_centerline_generator/msg/PointsWithLaneId.msg b/planning/autoware_static_centerline_generator/msg/PointsWithLaneId.msg deleted file mode 100644 index 97cd0355df831..0000000000000 --- a/planning/autoware_static_centerline_generator/msg/PointsWithLaneId.msg +++ /dev/null @@ -1,2 +0,0 @@ -int64 lane_id -geometry_msgs/Point[] points diff --git a/planning/autoware_static_centerline_generator/package.xml b/planning/autoware_static_centerline_generator/package.xml deleted file mode 100644 index cea18e5605921..0000000000000 --- a/planning/autoware_static_centerline_generator/package.xml +++ /dev/null @@ -1,57 +0,0 @@ - - - - autoware_static_centerline_generator - 0.40.0 - The autoware_static_centerline_generator package - Takayuki Murooka - Kosuke Takeuchi - Apache License 2.0 - - Takayuki Murooka - - ament_cmake_auto - autoware_cmake - - rosidl_default_generators - - autoware_behavior_path_planner_common - autoware_geography_utils - autoware_global_parameter_loader - autoware_interpolation - autoware_lanelet2_extension - autoware_lanelet2_map_visualizer - autoware_map_loader - autoware_map_msgs - autoware_map_projection_loader - autoware_map_tf_generator - autoware_mission_planner - autoware_motion_utils - autoware_osqp_interface - autoware_path_optimizer - autoware_path_smoother - autoware_perception_msgs - autoware_planning_msgs - autoware_route_handler - autoware_universe_utils - autoware_vehicle_info_utils - geometry_msgs - rclcpp - rclcpp_components - - python3-flask-cors - rosidl_default_runtime - - ament_cmake_gmock - ament_lint_auto - autoware_behavior_path_planner - autoware_behavior_velocity_planner - autoware_lint_common - ros_testing - - rosidl_interface_packages - - - ament_cmake - - diff --git a/planning/autoware_static_centerline_generator/rviz/static_centerline_generator.rviz b/planning/autoware_static_centerline_generator/rviz/static_centerline_generator.rviz deleted file mode 100644 index f1bd110783009..0000000000000 --- a/planning/autoware_static_centerline_generator/rviz/static_centerline_generator.rviz +++ /dev/null @@ -1,459 +0,0 @@ -Panels: - - Class: rviz_common/Displays - Help Height: 0 - Name: Displays - Property Tree Widget: - Expanded: ~ - Splitter Ratio: 0.550000011920929 - Tree Height: 386 - - Class: rviz_common/Selection - Name: Selection - - Class: rviz_common/Tool Properties - Expanded: - - /2D Dummy Car1 - Name: Tool Properties - Splitter Ratio: 0.5886790156364441 - - Class: rviz_common/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 - - Class: rviz_common/Time - Experimental: false - Name: Time - SyncMode: 0 - SyncSource: "" - - Class: rviz_plugins::AutowareStatePanel - Name: AutowareStatePanel -Visualization Manager: - Class: "" - Displays: - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/TF - Enabled: false - Frame Timeout: 15 - Frames: - All Enabled: true - Marker Scale: 1 - Name: TF - Show Arrows: true - Show Axes: true - Show Names: true - Tree: - {} - Update Interval: 0 - Value: false - - Alpha: 0.5 - Cell Size: 1 - Class: rviz_default_plugins/Grid - Color: 160; 160; 164 - Enabled: false - Line Style: - Line Width: 0.029999999329447746 - Value: Lines - Name: Grid - Normal Cell Count: 0 - Offset: - X: 0 - Y: 0 - Z: 0 - Plane: XY - Plane Cell Count: 10 - Reference Frame: - Value: false - Enabled: false - Name: System - - Class: rviz_common/Group - Displays: - - Alpha: 0.20000000298023224 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 28.71826171875 - Min Value: -7.4224700927734375 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz_default_plugins/PointCloud2 - Color: 255; 255; 255 - Color Transformer: FlatColor - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 237 - Min Color: 211; 215; 207 - Min Intensity: 0 - Name: PointCloudMap - Position Transformer: XYZ - Selectable: false - Size (Pixels): 1 - Size (m): 0.019999999552965164 - Style: Points - Topic: - Depth: 5 - Durability Policy: Transient Local - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /map/pointcloud_map - Use Fixed Frame: true - Use rainbow: false - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: Lanelet2VectorMap - Namespaces: - center_lane_line: true - center_line_arrows: true - lane_start_bound: false - lanelet_id: false - left_lane_bound: true - right_lane_bound: true - road_lanelets: false - Topic: - Depth: 5 - Durability Policy: Transient Local - History Policy: Keep Last - Reliability Policy: Reliable - Value: /map/vector_map_marker - Value: true - Enabled: true - Name: Map - - Class: rviz_plugins/PathWithLaneId - Color Border Vel Max: 3 - Enabled: false - Name: Raw Centerline - Topic: - Depth: 5 - Durability Policy: Transient Local - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /static_centerline_generator/input_centerline - Value: true - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: true - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View LaneId: - Scale: 0.10000000149011612 - Value: false - View Path: - Alpha: 1 - Color: 0; 0; 0 - Constant Color: false - Value: false - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 1 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Trajectory - Color Border Vel Max: 3 - Enabled: true - Name: Optimized Centerline - Topic: - Depth: 5 - Durability Policy: Transient Local - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /static_centerline_generator/output/centerline - Value: true - View Footprint: - Alpha: 0.5 - Color: 0; 255; 0 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: true - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 1 - Color: 0; 0; 0 - Constant Color: false - Value: false - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 1 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_common/Group - Displays: - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: false - Name: Raw Centerline (Path type) - Topic: - Depth: 5 - Durability Policy: Transient Local - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /static_centerline_generator/debug/raw_centerline - Value: false - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: true - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 1 - Color: 0; 0; 0 - Constant Color: false - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 1 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: MarkerArray - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Transient Local - History Policy: Keep Last - Reliability Policy: Reliable - Value: /static_centerline_generator/output/validation_results - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: Debug Markers - Namespaces: - curvature: false - Topic: - Depth: 5 - Durability Policy: Transient Local - History Policy: Keep Last - Reliability Policy: Reliable - Value: /static_centerline_generator/debug/markers - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: MarkerArray - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Transient Local - History Policy: Keep Last - Reliability Policy: Reliable - Value: /static_centerline_generator/debug/ego_footprint_bounds - Value: true - Enabled: true - Name: debug - Enabled: true - Global Options: - Background Color: 10; 10; 10 - Fixed Frame: map - Frame Rate: 30 - Name: root - Tools: - - Class: rviz_default_plugins/Interact - Hide Inactive Objects: true - - Class: rviz_default_plugins/MoveCamera - - Class: rviz_default_plugins/Select - - Class: rviz_default_plugins/FocusCamera - - Class: rviz_default_plugins/Measure - Line color: 128; 128; 0 - - Class: rviz_default_plugins/SetInitialPose - Covariance x: 0.25 - Covariance y: 0.25 - Covariance yaw: 0.06853891909122467 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /initialpose - - Class: rviz_default_plugins/SetGoal - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/mission_planning/goal - - Acceleration: 0 - Class: rviz_plugins/PedestrianInitialPoseTool - Interactive: false - Max velocity: 33.29999923706055 - Min velocity: -33.29999923706055 - Pose Topic: /simulation/dummy_perception_publisher/object_info - Target Frame: - Theta std deviation: 0.0872664600610733 - Velocity: 0 - X std deviation: 0.029999999329447746 - Y std deviation: 0.029999999329447746 - Z position: 1 - Z std deviation: 0.029999999329447746 - - Acceleration: 0 - Class: rviz_plugins/CarInitialPoseTool - H vehicle height: 2 - Interactive: false - L vehicle length: 4 - Max velocity: 33.29999923706055 - Min velocity: -33.29999923706055 - Pose Topic: /simulation/dummy_perception_publisher/object_info - Target Frame: - Theta std deviation: 0.0872664600610733 - Velocity: 8 - W vehicle width: 1.7999999523162842 - X std deviation: 0.029999999329447746 - Y std deviation: 0.029999999329447746 - Z position: 0 - Z std deviation: 0.029999999329447746 - - Acceleration: 0 - Class: rviz_plugins/BusInitialPoseTool - H vehicle height: 3.5 - Interactive: false - L vehicle length: 10.5 - Max velocity: 33.29999923706055 - Min velocity: -33.29999923706055 - Pose Topic: /simulation/dummy_perception_publisher/object_info - Target Frame: - Theta std deviation: 0.0872664600610733 - Velocity: 0 - W vehicle width: 2.5 - X std deviation: 0.029999999329447746 - Y std deviation: 0.029999999329447746 - Z position: 0 - Z std deviation: 0.029999999329447746 - - Class: rviz_plugins/MissionCheckpointTool - Pose Topic: /planning/mission_planning/checkpoint - Theta std deviation: 0.2617993950843811 - X std deviation: 0.5 - Y std deviation: 0.5 - Z position: 0 - - Class: rviz_plugins/DeleteAllObjectsTool - Pose Topic: /simulation/dummy_perception_publisher/object_info - Transformation: - Current: - Class: rviz_default_plugins/TF - Value: true - Views: - Current: - Angle: 0 - Class: rviz_default_plugins/TopDownOrtho - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Scale: 10 - Target Frame: viewer - Value: TopDownOrtho (rviz_default_plugins) - X: 0 - Y: 0 - Saved: - - Class: rviz_default_plugins/ThirdPersonFollower - Distance: 18 - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Focal Point: - X: 0 - Y: 0 - Z: 0 - Focal Shape Fixed Size: true - Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false - Name: ThirdPersonFollower - Near Clip Distance: 0.009999999776482582 - Pitch: 0.20000000298023224 - Target Frame: base_link - Value: ThirdPersonFollower (rviz) - Yaw: 3.141592025756836 - - Angle: 0 - Class: rviz_default_plugins/TopDownOrtho - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Invert Z Axis: false - Name: TopDownOrtho - Near Clip Distance: 0.009999999776482582 - Scale: 10 - Target Frame: viewer - Value: TopDownOrtho (rviz) - X: 0 - Y: 0 -Window Geometry: - AutowareStatePanel: - collapsed: false - Displays: - collapsed: false - Height: 1043 - Hide Left Dock: false - Hide Right Dock: false - QMainWindow State: 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 - Selection: - collapsed: false - Time: - collapsed: false - Tool Properties: - collapsed: false - Views: - collapsed: false - Width: 1920 - X: 0 - Y: 0 diff --git a/planning/autoware_static_centerline_generator/scripts/app.py b/planning/autoware_static_centerline_generator/scripts/app.py deleted file mode 100755 index 08bff8b80dcb7..0000000000000 --- a/planning/autoware_static_centerline_generator/scripts/app.py +++ /dev/null @@ -1,178 +0,0 @@ -#!/usr/bin/env python3 - -# Copyright 2022 Tier IV, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -import json -import uuid - -from autoware_static_centerline_generator.srv import LoadMap -from autoware_static_centerline_generator.srv import PlanPath -from autoware_static_centerline_generator.srv import PlanRoute -from flask import Flask -from flask import jsonify -from flask import request -from flask_cors import CORS -import rclpy -from rclpy.node import Node - -rclpy.init() -node = Node("static_centerline_generator_http_server") - -app = Flask(__name__) -CORS(app) - - -def create_client(service_type, server_name): - # create client - cli = node.create_client(service_type, server_name) - while not cli.wait_for_service(timeout_sec=1.0): - print("{} service not available, waiting again...".format(server_name)) - return cli - - -@app.route("/map", methods=["POST"]) -def get_map(): - data = request.get_json() - - map_uuid = str(uuid.uuid4()) - global map_id - map_id = map_uuid - - # create client - cli = create_client(LoadMap, "/planning/static_centerline_generator/load_map") - - # request map loading - req = LoadMap.Request(map=data["map"]) - future = cli.call_async(req) - - # get result - rclpy.spin_until_future_complete(node, future) - res = future.result() - - # error handling - if res.message == "InvalidMapFormat": - return jsonify(code=res.message, message="Map format is invalid."), 400 - elif res.message != "": - return ( - jsonify( - code="InternalServerError", - message="Error occurred on the server. Please check the terminal.", - ), - 500, - ) - - return map_uuid - - -@app.route("/planned_route", methods=["GET"]) -def post_planned_route(): - args = request.args.to_dict() - global map_id - if map_id != args.get("map_id"): - # TODO(murooka) error handling for map_id mismatch - print("map_id is not correct.") - - # create client - cli = create_client(PlanRoute, "/planning/static_centerline_generator/plan_route") - - # request route planning - req = PlanRoute.Request( - start_lane_id=int(args.get("start_lane_id")), end_lane_id=int(args.get("end_lane_id")) - ) - future = cli.call_async(req) - - # get result - rclpy.spin_until_future_complete(node, future) - res = future.result() - - # error handling - if res.message == "MapNotFound": - return jsonify(code=res.message, message="Map is missing."), 404 - elif res.message == "RouteNotFound": - return jsonify(code=res.message, message="Planning route failed."), 404 - elif res.message != "": - return ( - jsonify( - code="InternalServerError", - message="Error occurred on the server. Please check the terminal.", - ), - 500, - ) - - return json.dumps(tuple(res.lane_ids)) - - -@app.route("/planned_path", methods=["GET"]) -def post_planned_path(): - args = request.args.to_dict() - global map_id - if map_id != args.get("map_id"): - # TODO(murooka) error handling for map_id mismatch - print("map_id is not correct.") - - # create client - cli = create_client(PlanPath, "/planning/static_centerline_generator/plan_path") - - # request path planning - route_lane_ids = [eval(i) for i in request.args.getlist("route[]")] - req = PlanPath.Request(route=route_lane_ids) - future = cli.call_async(req) - - # get result - rclpy.spin_until_future_complete(node, future) - res = future.result() - - # error handling - if res.message == "MapNotFound": - return jsonify(code=res.message, message="Map is missing."), 404 - elif res.message == "LaneletsNotConnected": - return ( - jsonify( - code=res.message, - message="Lanelets are not connected.", - object_ids=tuple(res.unconnected_lane_ids), - ), - 400, - ) - elif res.message != "": - return ( - jsonify( - code="InternalServerError", - message="Error occurred on the server. Please check the terminal.", - ), - 500, - ) - - # create output json - result_json = [] - for points_with_lane_id in res.points_with_lane_ids: - current_lane_points = [] - for geom_point in points_with_lane_id.points: - point = {"x": geom_point.x, "y": geom_point.y, "z": geom_point.z} - current_lane_points.append(point) - - current_result_json = {} - current_result_json["lane_id"] = int(points_with_lane_id.lane_id) - current_result_json["points"] = current_lane_points - - result_json.append(current_result_json) - - return json.dumps(tuple(result_json)) - - -if __name__ == "__main__": - app.debug = True - app.secret_key = "tmp_secret_key" - app.run(host="localhost", port=4010) diff --git a/planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py b/planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py deleted file mode 100755 index f3d908713361d..0000000000000 --- a/planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py +++ /dev/null @@ -1,207 +0,0 @@ -#!/bin/env python3 - -# Copyright 2024 TIER IV, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - - -import sys -import time - -from PyQt5 import QtCore -from PyQt5.QtWidgets import QApplication -from PyQt5.QtWidgets import QGroupBox -from PyQt5.QtWidgets import QMainWindow -from PyQt5.QtWidgets import QPushButton -from PyQt5.QtWidgets import QSizePolicy -from PyQt5.QtWidgets import QSlider -from PyQt5.QtWidgets import QVBoxLayout -from PyQt5.QtWidgets import QWidget -from autoware_planning_msgs.msg import Trajectory -import rclpy -from rclpy.node import Node -from rclpy.qos import QoSDurabilityPolicy -from rclpy.qos import QoSProfile -from std_msgs.msg import Empty -from std_msgs.msg import Float32 -from std_msgs.msg import Int32 - - -class CenterlineUpdaterWidget(QMainWindow): - def __init__(self): - super(self.__class__, self).__init__() - self.setupUI() - - def setupUI(self): - self.setObjectName("MainWindow") - self.resize(480, 120) - self.setWindowFlags(QtCore.Qt.WindowStaysOnTopHint) - - central_widget = QWidget(self) - self.grid_layout = QVBoxLayout(central_widget) - self.grid_layout.setContentsMargins(10, 10, 10, 10) - - # slide of the trajectory's start and end index - self.traj_start_index_slider = QSlider(QtCore.Qt.Horizontal) - self.traj_end_index_slider = QSlider(QtCore.Qt.Horizontal) - self.min_traj_start_index = 0 - self.max_traj_end_index = None - - # Layout: Range of Centerline - centerline_vertical_box = QVBoxLayout(self) - centerline_vertical_box.addWidget(self.traj_start_index_slider) - centerline_vertical_box.addWidget(self.traj_end_index_slider) - centerline_group = QGroupBox("Centerline") - centerline_group.setLayout(centerline_vertical_box) - self.grid_layout.addWidget(centerline_group) - - """ - # 2. Road Boundary - road_boundary_group = QGroupBox("Road Boundary") - road_boundary_vertical_box = QVBoxLayout(self) - road_boundary_group.setLayout(road_boundary_vertical_box) - self.grid_layout.addWidget(road_boundary_group) - - # 2.1. Slider - self.road_boundary_lateral_margin_slider = QSlider(QtCore.Qt.Horizontal) - road_boundary_vertical_box.addWidget(self.road_boundary_lateral_margin_slider) - self.road_boundary_lateral_margin_ratio = 10 - self.road_boundary_lateral_margin_slider.setMinimum(0) - self.road_boundary_lateral_margin_slider.setMaximum( - 5 * self.road_boundary_lateral_margin_ratio - ) - road_boundary_vertical_box.addWidget(QPushButton("reset")) - """ - - # 3. General - general_group = QGroupBox("General") - general_vertical_box = QVBoxLayout(self) - general_group.setLayout(general_vertical_box) - self.grid_layout.addWidget(general_group) - - # 3.1. Validate Centerline - self.validate_button = QPushButton("validate") - self.validate_button.setSizePolicy(QSizePolicy.Expanding, QSizePolicy.Expanding) - general_vertical_box.addWidget(self.validate_button) - - # 3.2. Save Map - self.save_map_button = QPushButton("save map") - self.save_map_button.setSizePolicy(QSizePolicy.Expanding, QSizePolicy.Expanding) - general_vertical_box.addWidget(self.save_map_button) - - self.setCentralWidget(central_widget) - - def initWithEndIndex(self, max_traj_end_index): - self.max_traj_end_index = max_traj_end_index - - # initialize sliders - self.traj_start_index_slider.setMinimum(self.min_traj_start_index) - self.traj_start_index_slider.setMaximum(self.max_traj_end_index) - self.traj_start_index_slider.setValue(self.min_traj_start_index) - - self.traj_end_index_slider.setMinimum(self.min_traj_start_index) - self.traj_end_index_slider.setMaximum(self.max_traj_end_index) - self.traj_end_index_slider.setValue(self.max_traj_end_index) - - -class CenterlineUpdaterHelper(Node): - def __init__(self): - super().__init__("centerline_updater_helper") - # Qt - self.widget = CenterlineUpdaterWidget() - self.widget.show() - self.widget.save_map_button.clicked.connect(self.onSaveMapButtonPushed) - self.widget.validate_button.clicked.connect(self.onValidateButtonPushed) - self.widget.traj_start_index_slider.valueChanged.connect(self.onStartIndexChanged) - self.widget.traj_end_index_slider.valueChanged.connect(self.onEndIndexChanged) - """ - self.widget.road_boundary_lateral_margin_slider.valueChanged.connect( - self.onRoadBoundaryLateralMargin - ) - """ - - # ROS - self.pub_save_map = self.create_publisher(Empty, "/static_centerline_generator/save_map", 1) - self.pub_validate = self.create_publisher(Empty, "/static_centerline_generator/validate", 1) - self.pub_traj_start_index = self.create_publisher( - Int32, "/static_centerline_generator/traj_start_index", 1 - ) - self.pub_traj_end_index = self.create_publisher( - Int32, "/static_centerline_generator/traj_end_index", 1 - ) - self.pub_road_boundary_lateral_margin = self.create_publisher( - Float32, "/static_centerline_generator/road_boundary_lateral_margin", 1 - ) - - transient_local_qos = QoSProfile(depth=1, durability=QoSDurabilityPolicy.TRANSIENT_LOCAL) - self.sub_whole_centerline = self.create_subscription( - Trajectory, - "/static_centerline_generator/output/whole_centerline", - self.onWholeCenterline, - transient_local_qos, - ) - - while self.widget.max_traj_end_index is None: - rclpy.spin_once(self, timeout_sec=0.01) - time.sleep(0.1) - - def onWholeCenterline(self, whole_centerline): - self.widget.initWithEndIndex(len(whole_centerline.points) - 1) - - def onSaveMapButtonPushed(self, event): - msg = Empty() - self.pub_save_map.publish(msg) - - # NOTE: After saving the map, the generated centerline is written - # in original_map_ptr_ in static_centerline_generator_node. - # When saving the map again, another centerline is written without - # removing the previous centerline. - # Therefore, saving the map can be called only once. - self.widget.save_map_button.setEnabled(False) - - def onValidateButtonPushed(self, event): - msg = Empty() - self.pub_validate.publish(msg) - - def onStartIndexChanged(self, event): - msg = Int32() - msg.data = self.widget.traj_start_index_slider.value() - self.pub_traj_start_index.publish(msg) - - def onEndIndexChanged(self, event): - msg = Int32() - msg.data = self.widget.traj_end_index_slider.value() - self.pub_traj_end_index.publish(msg) - - def onRoadBoundaryLateralMargin(self, event): - msg = Float32() - msg.data = ( - self.widget.road_boundary_lateral_margin_slider.value() - / self.widget.road_boundary_lateral_margin_ratio - ) - self.pub_road_boundary_lateral_margin.publish(msg) - - -def main(args=None): - app = QApplication(sys.argv) - - rclpy.init(args=args) - node = CenterlineUpdaterHelper() - - while True: - app.processEvents() - rclpy.spin_once(node, timeout_sec=0.01) - - -if __name__ == "__main__": - main() diff --git a/planning/autoware_static_centerline_generator/scripts/show_lanelet2_map_diff.py b/planning/autoware_static_centerline_generator/scripts/show_lanelet2_map_diff.py deleted file mode 100755 index 00d06ca2213d1..0000000000000 --- a/planning/autoware_static_centerline_generator/scripts/show_lanelet2_map_diff.py +++ /dev/null @@ -1,139 +0,0 @@ -#!/bin/env python3 - -# Copyright 2024 TIER IV, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -import argparse -from decimal import Decimal -import os -import subprocess -import xml.etree.ElementTree as ET - - -def sort_attributes(root): - for shallow_element in root: - # sort nodes - attrib = shallow_element.attrib - if len(attrib) > 1: - attributes = sorted(attrib.items()) - attrib.clear() - attrib.update(attributes) - if shallow_element.tag == "relation": - pass - - # sort the element in the tag - for deep_element in shallow_element: - attrib = deep_element.attrib - if len(attrib) > 1: - # adjust attribute order, e.g. by sorting - attributes = sorted(attrib.items()) - attrib.clear() - attrib.update(attributes) - - # sort tags - sorted_shallow_element = sorted(shallow_element, key=lambda x: x.items()) - if len(shallow_element) != 0: - # NOTE: This "tail" is related to the indent of the next tag - first_tail = shallow_element[0].tail - last_tail = shallow_element[-1].tail - for idx, val_shallow_element in enumerate(sorted_shallow_element): - shallow_element[idx] = val_shallow_element - if idx == len(shallow_element) - 1: - shallow_element[idx].tail = last_tail - else: - shallow_element[idx].tail = first_tail - - -def remove_diff_to_ignore(osm_root): - decimal_precision = 11 # for lat/lon values - - # remove attributes of the osm tag - osm_root.attrib.clear() - - # remove the MetaInfo tag generated by Vector Map Builder - if osm_root[0].tag == "MetaInfo": - osm_root.remove(osm_root[0]) - - # remove unnecessary attributes for diff - for osm_child in osm_root: - if osm_child.tag == "osm": - osm_child.attrib.pop("osm") - if "visible" in osm_child.attrib and osm_child.attrib["visible"]: - osm_child.attrib.pop("visible") - if "version" in osm_child.attrib and osm_child.attrib["version"]: - osm_child.attrib.pop("version") - if "action" in osm_child.attrib and osm_child.attrib["action"] == "modify": - osm_child.attrib.pop("action") - if "lat" in osm_child.attrib: - osm_child.attrib["lat"] = str( - Decimal(float(osm_child.attrib["lat"])).quantize(Decimal(f"1e-{decimal_precision}")) - ) - if "lon" in osm_child.attrib: - osm_child.attrib["lon"] = str( - Decimal(float(osm_child.attrib["lon"])).quantize(Decimal(f"1e-{decimal_precision}")) - ) - - -if __name__ == "__main__": - parser = argparse.ArgumentParser() - parser.add_argument( - "-s", "--sort-attributes", action="store_true", help="Sort attributes of LL2 maps" - ) - parser.add_argument( - "-i", - "--ignore-minor-attributes", - action="store_true", - help="Ignore minor attributes of LL2 maps which does not change the map's behavior", - ) - args = parser.parse_args() - - original_osm_file_name = "/tmp/autoware_static_centerline_generator/input/lanelet2_map.osm" - modified_osm_file_name = "/tmp/autoware_static_centerline_generator/output/lanelet2_map.osm" - - # load LL2 maps - original_osm_tree = ET.parse(original_osm_file_name) - original_osm_root = original_osm_tree.getroot() - modified_osm_tree = ET.parse(modified_osm_file_name) - modified_osm_root = modified_osm_tree.getroot() - - # sort attributes - if args.sort_attributes: - sort_attributes(modified_osm_root) - sort_attributes(original_osm_root) - - # ignore minor attributes - if args.ignore_minor_attributes: - remove_diff_to_ignore(original_osm_root) - remove_diff_to_ignore(modified_osm_root) - - # write LL2 maps - output_dir_path = "/tmp/autoware_static_centerline_generator/show_lanelet2_map_diff/" - os.makedirs(output_dir_path + "original/", exist_ok=True) - os.makedirs(output_dir_path + "modified/", exist_ok=True) - - original_osm_tree.write(output_dir_path + "original/lanelet2_map.osm") - modified_osm_tree.write(output_dir_path + "modified/lanelet2_map.osm") - - # show diff - print("[INFO] Show diff of following LL2 maps") - print(f" {output_dir_path + 'original/lanelet2_map.osm'}") - print(f" {output_dir_path + 'modified/lanelet2_map.osm'}") - subprocess.run( - [ - "diff", - output_dir_path + "original/lanelet2_map.osm", - output_dir_path + "modified/lanelet2_map.osm", - "--color", - ] - ) diff --git a/planning/autoware_static_centerline_generator/scripts/tmp/bag_ego_trajectory_based_centerline.sh b/planning/autoware_static_centerline_generator/scripts/tmp/bag_ego_trajectory_based_centerline.sh deleted file mode 100755 index c170e24e475d9..0000000000000 --- a/planning/autoware_static_centerline_generator/scripts/tmp/bag_ego_trajectory_based_centerline.sh +++ /dev/null @@ -1,5 +0,0 @@ -#!/bin/bash - -ros2 launch autoware_static_centerline_generator static_centerline_generator.launch.xml centerline_source:="bag_ego_trajectory_base" mode:="GUI" lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" bag_filename:="$(ros2 pkg prefix autoware_static_centerline_generator --share)/test/data/bag_ego_trajectory_turn-right.db3" vehicle_model:=lexus - -# ros2 launch autoware_static_centerline_generator static_centerline_generator.launch.xml centerline_source:="bag_ego_trajectory_base" mode:="GUI" lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" bag_filename:="$(ros2 pkg prefix autoware_static_centerline_generator --share)/test/data/bag_ego_trajectory_turn-left-right.db3" vehicle_model:=lexus diff --git a/planning/autoware_static_centerline_generator/scripts/tmp/optimization_trajectory_based_centerline.sh b/planning/autoware_static_centerline_generator/scripts/tmp/optimization_trajectory_based_centerline.sh deleted file mode 100755 index 488091989d1fa..0000000000000 --- a/planning/autoware_static_centerline_generator/scripts/tmp/optimization_trajectory_based_centerline.sh +++ /dev/null @@ -1,3 +0,0 @@ -#!/bin/bash - -ros2 launch autoware_static_centerline_generator static_centerline_generator.launch.xml centerline_source:="optimization_trajectory_base" run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" start_lanelet_id:=125 end_lanelet_id:=132 vehicle_model:=lexus diff --git a/planning/autoware_static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.cpp b/planning/autoware_static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.cpp deleted file mode 100644 index dc950f190652b..0000000000000 --- a/planning/autoware_static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.cpp +++ /dev/null @@ -1,86 +0,0 @@ -// Copyright 2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "centerline_source/bag_ego_trajectory_based_centerline.hpp" - -#include "rclcpp/serialization.hpp" -#include "rosbag2_cpp/reader.hpp" -#include "static_centerline_generator_node.hpp" - -#include - -#include -#include -#include - -namespace autoware::static_centerline_generator -{ -std::vector generate_centerline_with_bag(rclcpp::Node & node) -{ - const auto bag_filename = node.declare_parameter("bag_filename"); - - // open rosbag - rosbag2_cpp::Reader bag_reader; - bag_reader.open(bag_filename); - - // extract 2D position of ego's trajectory from rosbag - rclcpp::Serialization bag_serialization; - std::vector centerline_traj_points; - while (bag_reader.has_next()) { - const rosbag2_storage::SerializedBagMessageSharedPtr msg = bag_reader.read_next(); - - if (msg->topic_name != "/localization/kinematic_state") { - continue; - } - - rclcpp::SerializedMessage serialized_msg(*msg->serialized_data); - const auto ros_msg = std::make_shared(); - - bag_serialization.deserialize_message(&serialized_msg, ros_msg.get()); - - if (!centerline_traj_points.empty()) { - constexpr double epsilon = 1e-1; - if ( - std::abs(centerline_traj_points.back().pose.position.x - ros_msg->pose.pose.position.x) < - epsilon && - std::abs(centerline_traj_points.back().pose.position.y - ros_msg->pose.pose.position.y) < - epsilon) { - continue; - } - } - TrajectoryPoint centerline_traj_point; - centerline_traj_point.pose.position = ros_msg->pose.pose.position; - centerline_traj_points.push_back(centerline_traj_point); - } - - RCLCPP_INFO(node.get_logger(), "Extracted centerline from the bag."); - - // calculate rough orientation of centerline trajectory points - for (size_t i = 0; i < centerline_traj_points.size(); ++i) { - if (i == centerline_traj_points.size() - 1) { - if (i != 0) { - centerline_traj_points.at(i).pose.orientation = - centerline_traj_points.at(i - 1).pose.orientation; - } - } else { - const double yaw_angle = autoware::universe_utils::calcAzimuthAngle( - centerline_traj_points.at(i).pose.position, centerline_traj_points.at(i + 1).pose.position); - centerline_traj_points.at(i).pose.orientation = - autoware::universe_utils::createQuaternionFromYaw(yaw_angle); - } - } - - return centerline_traj_points; -} -} // namespace autoware::static_centerline_generator diff --git a/planning/autoware_static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.hpp b/planning/autoware_static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.hpp deleted file mode 100644 index 2275f88184c6f..0000000000000 --- a/planning/autoware_static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.hpp +++ /dev/null @@ -1,27 +0,0 @@ -// Copyright 2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_ -#define CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_ - -#include "rclcpp/rclcpp.hpp" -#include "type_alias.hpp" - -#include - -namespace autoware::static_centerline_generator -{ -std::vector generate_centerline_with_bag(rclcpp::Node & node); -} // namespace autoware::static_centerline_generator -#endif // CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_ diff --git a/planning/autoware_static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp b/planning/autoware_static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp deleted file mode 100644 index 51725fb8a3799..0000000000000 --- a/planning/autoware_static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp +++ /dev/null @@ -1,187 +0,0 @@ -// Copyright 2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "centerline_source/optimization_trajectory_based_centerline.hpp" - -#include "autoware/motion_utils/resample/resample.hpp" -#include "autoware/motion_utils/trajectory/conversion.hpp" -#include "autoware/path_optimizer/node.hpp" -#include "autoware/path_smoother/elastic_band_smoother.hpp" -#include "autoware/universe_utils/ros/parameter.hpp" -#include "static_centerline_generator_node.hpp" -#include "utils.hpp" - -#include -#include - -namespace autoware::static_centerline_generator -{ -namespace -{ -rclcpp::NodeOptions create_node_options() -{ - return rclcpp::NodeOptions{}; -} - -Path convert_to_path(const PathWithLaneId & path_with_lane_id) -{ - Path path; - path.header = path_with_lane_id.header; - path.left_bound = path_with_lane_id.left_bound; - path.right_bound = path_with_lane_id.right_bound; - for (const auto & point : path_with_lane_id.points) { - path.points.push_back(point.point); - } - - return path; -} - -Trajectory convert_to_trajectory(const Path & path) -{ - Trajectory traj; - for (const auto & point : path.points) { - TrajectoryPoint traj_point; - traj_point.pose = point.pose; - traj_point.longitudinal_velocity_mps = point.longitudinal_velocity_mps; - traj_point.lateral_velocity_mps = point.lateral_velocity_mps; - traj_point.heading_rate_rps = point.heading_rate_rps; - - traj.points.push_back(traj_point); - } - return traj; -} -} // namespace - -OptimizationTrajectoryBasedCenterline::OptimizationTrajectoryBasedCenterline(rclcpp::Node & node) -{ - pub_raw_path_with_lane_id_ = - node.create_publisher("input_centerline", utils::create_transient_local_qos()); - pub_raw_path_ = - node.create_publisher("debug/raw_centerline", utils::create_transient_local_qos()); -} - -std::vector -OptimizationTrajectoryBasedCenterline::generate_centerline_with_optimization( - rclcpp::Node & node, const RouteHandler & route_handler, - const std::vector & route_lane_ids) -{ - const auto route_lanelets = utils::get_lanelets_from_ids(route_handler, route_lane_ids); - - // optimize centerline inside the lane - const auto start_center_pose = utils::get_center_pose(route_handler, route_lane_ids.front()); - - // get ego nearest search parameters and resample interval in behavior_path_planner - const double ego_nearest_dist_threshold = - autoware::universe_utils::getOrDeclareParameter(node, "ego_nearest_dist_threshold"); - const double ego_nearest_yaw_threshold = - autoware::universe_utils::getOrDeclareParameter(node, "ego_nearest_yaw_threshold"); - const double behavior_path_interval = - autoware::universe_utils::getOrDeclareParameter(node, "output_path_interval"); - const double behavior_vel_interval = - autoware::universe_utils::getOrDeclareParameter(node, "behavior_output_path_interval"); - - // extract path with lane id from lanelets - const auto raw_path_with_lane_id = [&]() { - const auto non_resampled_path_with_lane_id = utils::get_path_with_lane_id( - route_handler, route_lanelets, start_center_pose, ego_nearest_dist_threshold, - ego_nearest_yaw_threshold); - return autoware::motion_utils::resamplePath( - non_resampled_path_with_lane_id, behavior_path_interval); - }(); - pub_raw_path_with_lane_id_->publish(raw_path_with_lane_id); - RCLCPP_INFO(node.get_logger(), "Calculated raw path with lane id and published."); - - // convert path with lane id to path - const auto raw_path = [&]() { - const auto non_resampled_path = convert_to_path(raw_path_with_lane_id); - return autoware::motion_utils::resamplePath(non_resampled_path, behavior_vel_interval); - }(); - pub_raw_path_->publish(raw_path); - RCLCPP_INFO(node.get_logger(), "Converted to path and published."); - - // smooth trajectory and road collision avoidance - const auto optimized_traj_points = optimize_trajectory(raw_path); - RCLCPP_INFO( - node.get_logger(), - "Smoothed trajectory and made it collision free with the road and published."); - - return optimized_traj_points; -} - -std::vector OptimizationTrajectoryBasedCenterline::optimize_trajectory( - const Path & raw_path) const -{ - // convert to trajectory points - const auto raw_traj_points = [&]() { - const auto raw_traj = convert_to_trajectory(raw_path); - return autoware::motion_utils::convertToTrajectoryPointArray(raw_traj); - }(); - - // create an instance of elastic band and model predictive trajectory. - const auto eb_path_smoother_ptr = - autoware::path_smoother::ElasticBandSmoother(create_node_options()).getElasticBandSmoother(); - const auto mpt_optimizer_ptr = - autoware::path_optimizer::PathOptimizer(create_node_options()).getMPTOptimizer(); - - // NOTE: The optimization is executed every valid_optimized_traj_points_num points. - constexpr int valid_optimized_traj_points_num = 10; - const int traj_segment_num = raw_traj_points.size() / valid_optimized_traj_points_num; - - // NOTE: num_initial_optimization exists to make the both optimizations stable since they may use - // warm start. - constexpr int num_initial_optimization = 2; - - std::vector whole_optimized_traj_points; - for (int virtual_ego_pose_idx = -num_initial_optimization; - virtual_ego_pose_idx < traj_segment_num; ++virtual_ego_pose_idx) { - // calculate virtual ego pose for the optimization - constexpr int virtual_ego_pose_offset_idx = 1; - const auto virtual_ego_pose = - raw_traj_points - .at( - valid_optimized_traj_points_num * std::max(virtual_ego_pose_idx, 0) + - virtual_ego_pose_offset_idx) - .pose; - - // smooth trajectory by elastic band in the autoware_path_smoother package - const auto smoothed_traj_points = - eb_path_smoother_ptr->smoothTrajectory(raw_traj_points, virtual_ego_pose); - - // road collision avoidance by model predictive trajectory in the autoware_path_optimizer - // package - const autoware::path_optimizer::PlannerData planner_data{ - raw_path.header, smoothed_traj_points, raw_path.left_bound, raw_path.right_bound, - virtual_ego_pose}; - const auto optimized_traj_points = mpt_optimizer_ptr->optimizeTrajectory(planner_data); - - // connect the previously and currently optimized trajectory points - for (size_t j = 0; j < whole_optimized_traj_points.size(); ++j) { - const double dist = autoware::universe_utils::calcDistance2d( - whole_optimized_traj_points.at(j), optimized_traj_points.front()); - if (dist < 0.5) { - const std::vector extracted_whole_optimized_traj_points{ - whole_optimized_traj_points.begin(), - whole_optimized_traj_points.begin() + std::max(j, 1UL) - 1}; - whole_optimized_traj_points = extracted_whole_optimized_traj_points; - break; - } - } - for (size_t j = 0; j < optimized_traj_points.size(); ++j) { - whole_optimized_traj_points.push_back(optimized_traj_points.at(j)); - } - } - - return whole_optimized_traj_points; -} -} // namespace autoware::static_centerline_generator diff --git a/planning/autoware_static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.hpp b/planning/autoware_static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.hpp deleted file mode 100644 index 88def6fa7bd4c..0000000000000 --- a/planning/autoware_static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.hpp +++ /dev/null @@ -1,43 +0,0 @@ -// Copyright 2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT -#define CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT - -#include "rclcpp/rclcpp.hpp" -#include "type_alias.hpp" - -#include - -namespace autoware::static_centerline_generator -{ -class OptimizationTrajectoryBasedCenterline -{ -public: - OptimizationTrajectoryBasedCenterline() = default; - explicit OptimizationTrajectoryBasedCenterline(rclcpp::Node & node); - std::vector generate_centerline_with_optimization( - rclcpp::Node & node, const RouteHandler & route_handler, - const std::vector & route_lane_ids); - -private: - std::vector optimize_trajectory(const Path & raw_path) const; - - rclcpp::Publisher::SharedPtr pub_raw_path_with_lane_id_{nullptr}; - rclcpp::Publisher::SharedPtr pub_raw_path_{nullptr}; -}; -} // namespace autoware::static_centerline_generator -// clang-format off -#endif // CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT -// clang-format on diff --git a/planning/autoware_static_centerline_generator/src/main.cpp b/planning/autoware_static_centerline_generator/src/main.cpp deleted file mode 100644 index 71a076ee86fe0..0000000000000 --- a/planning/autoware_static_centerline_generator/src/main.cpp +++ /dev/null @@ -1,59 +0,0 @@ -// Copyright 2022 Tier IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "static_centerline_generator_node.hpp" - -#include -#include -#include - -int main(int argc, char * argv[]) -{ - try { - rclcpp::init(argc, argv); - - // initialize node - rclcpp::NodeOptions node_options; - auto node = - std::make_shared( - node_options); - - // get ros parameter - const auto mode = node->declare_parameter("mode"); - - // process - if (mode == "AUTO") { - node->generate_centerline(); - node->validate(); - node->save_map(); - } else if (mode == "GUI") { - node->generate_centerline(); - } else if (mode == "VMB") { - // Do nothing - } else { - throw std::invalid_argument("The `mode` is invalid."); - } - - // NOTE: spin node to keep showing debug path/trajectory in rviz with transient local - rclcpp::spin(node); - rclcpp::shutdown(); - } catch (const std::exception & e) { - std::cerr << "Exception in main(): " << e.what() << std::endl; - return {}; - } catch (...) { - std::cerr << "Unknown exception in main()" << std::endl; - return {}; - } - return 0; -} diff --git a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp deleted file mode 100644 index f172e3e0cb1cd..0000000000000 --- a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp +++ /dev/null @@ -1,774 +0,0 @@ -// Copyright 2022 Tier IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "static_centerline_generator_node.hpp" - -#include "autoware/map_loader/lanelet2_map_loader_node.hpp" -#include "autoware/map_projection_loader/load_info_from_lanelet2_map.hpp" -#include "autoware/map_projection_loader/map_projection_loader.hpp" -#include "autoware/motion_utils/resample/resample.hpp" -#include "autoware/motion_utils/trajectory/conversion.hpp" -#include "autoware/motion_utils/trajectory/trajectory.hpp" -#include "autoware/universe_utils/geometry/geometry.hpp" -#include "autoware/universe_utils/math/unit_conversion.hpp" -#include "autoware/universe_utils/ros/parameter.hpp" -#include "autoware_lanelet2_extension/utility/message_conversion.hpp" -#include "autoware_lanelet2_extension/utility/query.hpp" -#include "autoware_lanelet2_extension/utility/utilities.hpp" -#include "autoware_static_centerline_generator/msg/points_with_lane_id.hpp" -#include "centerline_source/bag_ego_trajectory_based_centerline.hpp" -#include "type_alias.hpp" -#include "utils.hpp" - -#include -#include -#include -#include - -#include "std_msgs/msg/empty.hpp" -#include "std_msgs/msg/float32.hpp" -#include "std_msgs/msg/int32.hpp" - -#include -#include - -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#define RESET_TEXT "\x1B[0m" -#define RED_TEXT "\x1B[31m" -#define YELLOW_TEXT "\x1b[33m" -#define BOLD_TEXT "\x1B[1m" - -namespace autoware::static_centerline_generator -{ -namespace -{ -std::vector get_lane_ids_from_route(const LaneletRoute & route) -{ - std::vector lane_ids; - for (const auto & segment : route.segments) { - const auto & target_lanelet_id = segment.preferred_primitive.id; - lane_ids.push_back(target_lanelet_id); - } - - return lane_ids; -} - -lanelet::BasicPoint2d convert_to_lanelet_point(const geometry_msgs::msg::Point & geom_point) -{ - lanelet::BasicPoint2d point(geom_point.x, geom_point.y); - return point; -} - -LinearRing2d create_vehicle_footprint( - const geometry_msgs::msg::Pose & pose, - const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double margin = 0.0) -{ - const auto & i = vehicle_info; - - const double x_front = i.front_overhang_m + i.wheel_base_m + margin; - const double x_rear = -(i.rear_overhang_m + margin); - const double y_left = i.wheel_tread_m / 2.0 + i.left_overhang_m + margin; - const double y_right = -(i.wheel_tread_m / 2.0 + i.right_overhang_m + margin); - - std::vector geom_points; - geom_points.push_back( - autoware::universe_utils::calcOffsetPose(pose, x_front, y_left, 0.0).position); - geom_points.push_back( - autoware::universe_utils::calcOffsetPose(pose, x_front, y_right, 0.0).position); - geom_points.push_back( - autoware::universe_utils::calcOffsetPose(pose, x_rear, y_right, 0.0).position); - geom_points.push_back( - autoware::universe_utils::calcOffsetPose(pose, x_rear, y_left, 0.0).position); - - LinearRing2d footprint; - for (const auto & geom_point : geom_points) { - footprint.push_back(Point2d{geom_point.x, geom_point.y}); - } - footprint.push_back(footprint.back()); - - boost::geometry::correct(footprint); - - return footprint; -} - -geometry_msgs::msg::Pose get_text_pose( - const geometry_msgs::msg::Pose & pose, - const autoware::vehicle_info_utils::VehicleInfo & vehicle_info) -{ - const auto & i = vehicle_info; - - const double x_front = i.front_overhang_m + i.wheel_base_m; - const double y_left = i.wheel_tread_m / 2.0 + i.left_overhang_m + 0.5; - - return autoware::universe_utils::calcOffsetPose(pose, x_front, y_left, 0.0); -} - -std::array convert_hex_string_to_decimal(const std::string & hex_str_color) -{ - unsigned int hex_int_color; - std::istringstream iss(hex_str_color); - iss >> std::hex >> hex_int_color; - - unsigned int unit = 16 * 16; - unsigned int b = hex_int_color % unit; - unsigned int g = (hex_int_color - b) / unit % unit; - unsigned int r = (hex_int_color - g * unit - b) / unit / unit; - - return std::array{r / 255.0, g / 255.0, b / 255.0}; -} - -std::vector check_lanelet_connection( - const RouteHandler & route_handler, const lanelet::ConstLanelets & route_lanelets) -{ - std::vector unconnected_lane_ids; - - for (size_t i = 0; i < route_lanelets.size() - 1; ++i) { - const auto next_lanelets = route_handler.getNextLanelets(route_lanelets.at(i)); - - const bool is_connected = - std::find_if(next_lanelets.begin(), next_lanelets.end(), [&](const auto & next_lanelet) { - return next_lanelet.id() == route_lanelets.at(i + 1).id(); - }) != next_lanelets.end(); - if (!is_connected) { - unconnected_lane_ids.push_back(route_lanelets.at(i).id()); - } - } - - return unconnected_lane_ids; -} - -std_msgs::msg::Header create_header(const rclcpp::Time & now) -{ - std_msgs::msg::Header header; - header.frame_id = "map"; - header.stamp = now; - return header; -} - -std::vector resample_trajectory_points( - const std::vector & input_traj_points, const double resample_interval) -{ - // resample and calculate trajectory points' orientation - const auto input_traj = autoware::motion_utils::convertToTrajectory(input_traj_points); - auto resampled_input_traj = - autoware::motion_utils::resampleTrajectory(input_traj, resample_interval); - return autoware::motion_utils::convertToTrajectoryPointArray(resampled_input_traj); -} - -std::vector convertToGeometryPoints(const LineString2d & lanelet_points) -{ - std::vector points; - for (const auto & lanelet_point : lanelet_points) { - geometry_msgs::msg::Point point; - point.x = lanelet_point.x(); - point.y = lanelet_point.y(); - points.push_back(point); - } - return points; -} -} // namespace - -StaticCenterlineGeneratorNode::StaticCenterlineGeneratorNode( - const rclcpp::NodeOptions & node_options) -: Node("static_centerline_generator", node_options) -{ - // publishers - pub_map_bin_ = - create_publisher("lanelet2_map_topic", utils::create_transient_local_qos()); - pub_whole_centerline_ = - create_publisher("~/output/whole_centerline", utils::create_transient_local_qos()); - pub_centerline_ = - create_publisher("~/output/centerline", utils::create_transient_local_qos()); - - // debug publishers - pub_validation_results_ = - create_publisher("~/validation_results", utils::create_transient_local_qos()); - pub_debug_markers_ = - create_publisher("~/debug/markers", utils::create_transient_local_qos()); - - pub_debug_ego_footprint_bounds_ = create_publisher( - "~/debug/ego_footprint_bounds", utils::create_transient_local_qos()); - - // subscribers - sub_footprint_margin_for_road_bound_ = create_subscription( - "/static_centerline_generator/road_boundary_lateral_margin", rclcpp::QoS{1}, - [this](const std_msgs::msg::Float32 & msg) { footprint_margin_for_road_bound_ = msg.data; }); - sub_traj_start_index_ = create_subscription( - "/static_centerline_generator/traj_start_index", rclcpp::QoS{1}, - [this](const std_msgs::msg::Int32 & msg) { - if (centerline_handler_.update_start_index(msg.data)) { - visualize_selected_centerline(); - } - }); - sub_traj_end_index_ = create_subscription( - "/static_centerline_generator/traj_end_index", rclcpp::QoS{1}, - [this](const std_msgs::msg::Int32 & msg) { - if (centerline_handler_.update_end_index(msg.data)) { - visualize_selected_centerline(); - } - }); - sub_save_map_ = create_subscription( - "/static_centerline_generator/save_map", rclcpp::QoS{1}, - [this]([[maybe_unused]] const std_msgs::msg::Empty & msg) { - if (!centerline_handler_.is_valid()) { - return; - } - save_map(); - }); - sub_validate_ = create_subscription( - "/static_centerline_generator/validate", rclcpp::QoS{1}, - [this]([[maybe_unused]] const std_msgs::msg::Empty & msg) { validate(); }); - - // services - callback_group_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); - srv_load_map_ = create_service( - "/planning/static_centerline_generator/load_map", - std::bind( - &StaticCenterlineGeneratorNode::on_load_map, this, std::placeholders::_1, - std::placeholders::_2), - rmw_qos_profile_services_default, callback_group_); - srv_plan_route_ = create_service( - "/planning/static_centerline_generator/plan_route", - std::bind( - &StaticCenterlineGeneratorNode::on_plan_route, this, std::placeholders::_1, - std::placeholders::_2), - rmw_qos_profile_services_default, callback_group_); - srv_plan_path_ = create_service( - "/planning/static_centerline_generator/plan_path", - std::bind( - &StaticCenterlineGeneratorNode::on_plan_path, this, std::placeholders::_1, - std::placeholders::_2), - rmw_qos_profile_services_default, callback_group_); - - // vehicle info - vehicle_info_ = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo(); - - centerline_source_ = [&]() { - const auto centerline_source_param = declare_parameter("centerline_source"); - if (centerline_source_param == "optimization_trajectory_base") { - optimization_trajectory_based_centerline_ = OptimizationTrajectoryBasedCenterline(*this); - return CenterlineSource::OptimizationTrajectoryBase; - } else if (centerline_source_param == "bag_ego_trajectory_base") { - return CenterlineSource::BagEgoTrajectoryBase; - } - throw std::logic_error( - "The centerline source is not supported in autoware_static_centerline_generator."); - }(); -} - -void StaticCenterlineGeneratorNode::visualize_selected_centerline() -{ - // publish selected centerline - const auto selected_centerline = centerline_handler_.get_selected_centerline(); - pub_centerline_->publish( - autoware::motion_utils::convertToTrajectory(selected_centerline, create_header(this->now()))); - - // delete markers for validation - pub_validation_results_->publish(utils::create_delete_all_marker_array({}, now())); - pub_debug_markers_->publish(utils::create_delete_all_marker_array( - {"unsafe_footprints", "unsafe_footprints_distance"}, now())); - pub_debug_ego_footprint_bounds_->publish( - utils::create_delete_all_marker_array({"road_bounds"}, now())); -} - -void StaticCenterlineGeneratorNode::generate_centerline() -{ - // declare planning setting parameters - const auto lanelet2_input_file_path = declare_parameter("lanelet2_input_file_path"); - - // process - load_map(lanelet2_input_file_path); - const auto whole_centerline_with_route = generate_whole_centerline_with_route(); - centerline_handler_ = CenterlineHandler(whole_centerline_with_route); - - visualize_selected_centerline(); -} - -CenterlineWithRoute StaticCenterlineGeneratorNode::generate_whole_centerline_with_route() -{ - if (!route_handler_ptr_) { - RCLCPP_ERROR(get_logger(), "Route handler is not ready. Return empty trajectory."); - return CenterlineWithRoute{}; - } - - // generate centerline with route - auto centerline_with_route = [&]() { - if (centerline_source_ == CenterlineSource::OptimizationTrajectoryBase) { - const lanelet::Id start_lanelet_id = declare_parameter("start_lanelet_id"); - const lanelet::Id end_lanelet_id = declare_parameter("end_lanelet_id"); - const auto route_lane_ids = plan_route_by_lane_ids(start_lanelet_id, end_lanelet_id); - const auto optimized_centerline = - optimization_trajectory_based_centerline_.generate_centerline_with_optimization( - *this, *route_handler_ptr_, route_lane_ids); - return CenterlineWithRoute{optimized_centerline, route_lane_ids}; - } else if (centerline_source_ == CenterlineSource::BagEgoTrajectoryBase) { - const auto bag_centerline = generate_centerline_with_bag(*this); - const auto route_lane_ids = - plan_route(bag_centerline.front().pose, bag_centerline.back().pose); - return CenterlineWithRoute{bag_centerline, route_lane_ids}; - } - throw std::logic_error( - "The centerline source is not supported in autoware_static_centerline_generator."); - }(); - - // resample - const double output_trajectory_interval = declare_parameter("output_trajectory_interval"); - centerline_with_route.centerline = - resample_trajectory_points(centerline_with_route.centerline, output_trajectory_interval); - - pub_whole_centerline_->publish(autoware::motion_utils::convertToTrajectory( - centerline_with_route.centerline, create_header(this->now()))); - - return centerline_with_route; -} - -void StaticCenterlineGeneratorNode::load_map(const std::string & lanelet2_input_file_path) -{ - // copy the input LL2 map to the temporary file for debugging - const std::string debug_input_file_dir{"/tmp/autoware_static_centerline_generator/input/"}; - std::filesystem::create_directories(debug_input_file_dir); - std::filesystem::copy( - lanelet2_input_file_path, debug_input_file_dir + "lanelet2_map.osm", - std::filesystem::copy_options::overwrite_existing); - - // load map by the map_loader package - map_bin_ptr_ = [&]() -> LaneletMapBin::ConstSharedPtr { - // load map - map_projector_info_ = std::make_unique( - autoware::map_projection_loader::load_info_from_lanelet2_map(lanelet2_input_file_path)); - const auto map_ptr = autoware::map_loader::Lanelet2MapLoaderNode::load_map( - lanelet2_input_file_path, *map_projector_info_); - if (!map_ptr) { - return nullptr; - } - - // NOTE: The original map is stored here since the centerline will be added to all the - // lanelet when lanelet::utils::overwriteLaneletCenterline is called. - original_map_ptr_ = autoware::map_loader::Lanelet2MapLoaderNode::load_map( - lanelet2_input_file_path, *map_projector_info_); - - // overwrite more dense centerline - // NOTE: overwriteLaneletsCenterlineWithWaypoints is used only in real time calculation. - lanelet::utils::overwriteLaneletsCenterline(map_ptr, 5.0, false); - - // create map bin msg - const auto map_bin_msg = autoware::map_loader::Lanelet2MapLoaderNode::create_map_bin_msg( - map_ptr, lanelet2_input_file_path, now()); - - return std::make_shared(map_bin_msg); - }(); - - // check if map_bin_ptr_ is not null pointer - if (!map_bin_ptr_) { - RCLCPP_ERROR(get_logger(), "Loading map failed"); - return; - } - RCLCPP_INFO(get_logger(), "Loaded map."); - - // publish map bin msg - pub_map_bin_->publish(*map_bin_ptr_); - RCLCPP_INFO(get_logger(), "Published map."); - - // create route_handler - route_handler_ptr_ = std::make_shared(); - route_handler_ptr_->setMap(*map_bin_ptr_); -} - -void StaticCenterlineGeneratorNode::on_load_map( - const LoadMap::Request::SharedPtr request, const LoadMap::Response::SharedPtr response) -{ - const std::string tmp_lanelet2_input_file_path = "/tmp/input_lanelet2_map.osm"; - - // save map file temporarily since load map's input must be a file - std::ofstream map_writer; - map_writer.open(tmp_lanelet2_input_file_path, std::ios::out); - map_writer << request->map; - map_writer.close(); - - // load map from the saved map file - load_map(tmp_lanelet2_input_file_path); - - if (map_bin_ptr_) { - return; - } - - response->message = "InvalidMapFormat"; -} - -std::vector StaticCenterlineGeneratorNode::plan_route_by_lane_ids( - const lanelet::Id start_lanelet_id, const lanelet::Id end_lanelet_id) -{ - if (!route_handler_ptr_) { - RCLCPP_ERROR(get_logger(), "Map or route handler is not ready. Return empty lane ids."); - return std::vector{}; - } - - const auto start_center_pose = utils::get_center_pose(*route_handler_ptr_, start_lanelet_id); - const auto end_center_pose = utils::get_center_pose(*route_handler_ptr_, end_lanelet_id); - return plan_route(start_center_pose, end_center_pose); -} - -std::vector StaticCenterlineGeneratorNode::plan_route( - const geometry_msgs::msg::Pose & start_center_pose, - const geometry_msgs::msg::Pose & end_center_pose) -{ - if (!map_bin_ptr_) { - RCLCPP_ERROR(get_logger(), "Map or route handler is not ready. Return empty lane ids."); - return std::vector{}; - } - - // plan route by the mission_planner package - const auto route = [&]() { - // calculate check points - RCLCPP_INFO(get_logger(), "Calculated check points."); - const auto check_points = - std::vector{start_center_pose, end_center_pose}; - - // create mission_planner plugin - auto plugin_loader = pluginlib::ClassLoader( - "autoware_mission_planner", "autoware::mission_planner::PlannerPlugin"); - auto mission_planner = - plugin_loader.createSharedInstance("autoware::mission_planner::lanelet2::DefaultPlanner"); - - // initialize mission_planner - auto node = rclcpp::Node("mission_planner"); - mission_planner->initialize(&node, map_bin_ptr_); - - // plan route - const auto route = mission_planner->plan(check_points); - - return route; - }(); - - // get lanelets - const auto route_lane_ids = get_lane_ids_from_route(route); - - std::string route_lane_ids_str = ""; - for (const lanelet::Id route_lane_id : route_lane_ids) { - route_lane_ids_str += std::to_string(route_lane_id) + ","; - } - RCLCPP_INFO_STREAM(get_logger(), "Planned route. (" << route_lane_ids_str << ")"); - - return route_lane_ids; -} - -void StaticCenterlineGeneratorNode::on_plan_route( - const PlanRoute::Request::SharedPtr request, const PlanRoute::Response::SharedPtr response) -{ - if (!map_bin_ptr_ || !route_handler_ptr_) { - response->message = "MapNotFound"; - RCLCPP_ERROR(get_logger(), "Map is not ready."); - return; - } - - const lanelet::Id start_lanelet_id = request->start_lane_id; - const lanelet::Id end_lanelet_id = request->end_lane_id; - - // plan route - const auto route_lane_ids = plan_route_by_lane_ids(start_lanelet_id, end_lanelet_id); - const auto route_lanelets = utils::get_lanelets_from_ids(*route_handler_ptr_, route_lane_ids); - - // extract lane ids - std::vector lane_ids; - for (const auto & lanelet : route_lanelets) { - lane_ids.push_back(lanelet.id()); - } - - // check calculation result - if (lane_ids.empty()) { - response->message = "RouteNotFound"; - RCLCPP_ERROR(get_logger(), "Route planning failed."); - return; - } - - // set response - response->lane_ids = lane_ids; -} - -void StaticCenterlineGeneratorNode::on_plan_path( - const PlanPath::Request::SharedPtr request, const PlanPath::Response::SharedPtr response) -{ - if (!route_handler_ptr_) { - response->message = "MapNotFound"; - RCLCPP_ERROR(get_logger(), "Route handler is not ready."); - return; - } - - // get lanelets from route lane ids - const auto route_lane_ids = request->route; - const auto route_lanelets = utils::get_lanelets_from_ids(*route_handler_ptr_, route_lane_ids); - - // check if input route lanelets are connected to each other. - const auto unconnected_lane_ids = check_lanelet_connection(*route_handler_ptr_, route_lanelets); - if (!unconnected_lane_ids.empty()) { - response->message = "LaneletsNotConnected"; - response->unconnected_lane_ids = unconnected_lane_ids; - RCLCPP_ERROR(get_logger(), "Lanelets are not connected."); - return; - } - - // plan path - const auto optimized_traj_points = - optimization_trajectory_based_centerline_.generate_centerline_with_optimization( - *this, *route_handler_ptr_, route_lane_ids); - - // check calculation result - if (optimized_traj_points.empty()) { - response->message = "PathNotFound"; - RCLCPP_ERROR(get_logger(), "Path planning failed."); - return; - } - - centerline_handler_ = - CenterlineHandler(CenterlineWithRoute{optimized_traj_points, route_lane_ids}); - - // publish unsafe_footprints - validate(); - - // create output data - auto target_traj_point = optimized_traj_points.cbegin(); - bool is_end_lanelet = false; - for (const auto & lanelet : route_lanelets) { - std::vector current_lanelet_points; - - // check if target point is inside the lanelet - while (lanelet::geometry::inside( - lanelet, convert_to_lanelet_point(target_traj_point->pose.position))) { - // memorize points inside the lanelet - current_lanelet_points.push_back(target_traj_point->pose.position); - target_traj_point++; - - if (target_traj_point == optimized_traj_points.cend()) { - is_end_lanelet = true; - break; - } - } - - if (!current_lanelet_points.empty()) { - // register points with lane_id - autoware_static_centerline_generator::msg::PointsWithLaneId points_with_lane_id; - points_with_lane_id.lane_id = lanelet.id(); - points_with_lane_id.points = current_lanelet_points; - response->points_with_lane_ids.push_back(points_with_lane_id); - } - - if (is_end_lanelet) { - break; - } - } - - // empty string if error did not occur - response->message = ""; -} - -void StaticCenterlineGeneratorNode::validate() -{ - std::cerr << std::endl - << "############################################## Validation Results " - "##############################################" - << std::endl; - - const auto & centerline = centerline_handler_.get_selected_centerline(); - const auto & route_lane_ids = centerline_handler_.get_route_lane_ids(); - const auto route_lanelets = utils::get_lanelets_from_ids(*route_handler_ptr_, route_lane_ids); - - const double dist_thresh_to_road_border = - getRosParameter("validation.dist_threshold_to_road_border"); - const double max_steer_angle_margin = - getRosParameter("validation.max_steer_angle_margin"); - - // calculate color for distance to road border - const auto dist_thresh_vec = getRosParameter>("marker_color_dist_thresh"); - const auto marker_color_vec = getRosParameter>("marker_color"); - const auto get_marker_color = [&](const double dist) -> boost::optional> { - for (size_t i = 0; i < dist_thresh_vec.size(); ++i) { - const double dist_thresh = dist_thresh_vec.at(i); - if (dist < dist_thresh) { - return convert_hex_string_to_decimal(marker_color_vec.at(i)); - } - } - return boost::none; - }; - - // create right/left bound - LineString2d lanelet_right_bound; - LineString2d lanelet_left_bound; - for (const auto & lanelet : route_lanelets) { - for (const auto & point : lanelet.rightBound()) { - boost::geometry::append(lanelet_right_bound, Point2d(point.x(), point.y())); - } - for (const auto & point : lanelet.leftBound()) { - boost::geometry::append(lanelet_left_bound, Point2d(point.x(), point.y())); - } - } - - // calculate curvature - const auto curvature_vec = autoware::motion_utils::calcCurvature(centerline); - const double steer_angle_threshold = vehicle_info_.max_steer_angle_rad - max_steer_angle_margin; - - // calculate the distance between footprint and right/left bounds - MarkerArray marker_array; - double min_dist = std::numeric_limits::max(); - double max_curvature = std::numeric_limits::min(); - for (size_t i = 0; i < centerline.size(); ++i) { - const auto & traj_point = centerline.at(i); - - const auto footprint_poly = create_vehicle_footprint(traj_point.pose, vehicle_info_); - - const double dist_to_right = boost::geometry::distance(footprint_poly, lanelet_right_bound); - const double dist_to_left = boost::geometry::distance(footprint_poly, lanelet_left_bound); - const double min_dist_to_bound = std::min(dist_to_right, dist_to_left); - - if (min_dist_to_bound < min_dist) { - min_dist = min_dist_to_bound; - } - - // create marker - const auto marker_color_opt = get_marker_color(min_dist_to_bound); - const auto text_pose = get_text_pose(traj_point.pose, vehicle_info_); - if (marker_color_opt) { - const auto & marker_color = marker_color_opt.get(); - - // add footprint marker - const auto footprint_marker = utils::create_footprint_marker( - footprint_poly, 0.05, marker_color.at(0), marker_color.at(1), marker_color.at(2), 0.7, - now(), i); - marker_array.markers.push_back(footprint_marker); - - // add text of distance to bounds marker - const auto text_marker = utils::create_text_marker( - "unsafe_footprints_distance", text_pose, min_dist_to_bound, marker_color.at(0), - marker_color.at(1), marker_color.at(2), 0.999, now(), i); - marker_array.markers.push_back(text_marker); - } - - const double curvature = curvature_vec.at(i); - const auto text_marker = - utils::create_text_marker("curvature", text_pose, curvature, 0.05, 0.05, 0.0, 0.9, now(), i); - marker_array.markers.push_back(text_marker); - - if (max_curvature < std::abs(curvature)) { - max_curvature = std::abs(curvature); - } - } - const double max_steer_angle = vehicle_info_.calcSteerAngleFromCurvature(max_curvature); - - // publish road boundaries - const auto left_bound = convertToGeometryPoints(lanelet_left_bound); - const auto right_bound = convertToGeometryPoints(lanelet_right_bound); - - marker_array.markers.push_back( - utils::create_points_marker("left_bound", left_bound, 0.05, 0.0, 0.6, 0.8, 0.8, now())); - marker_array.markers.push_back( - utils::create_points_marker("right_bound", right_bound, 0.05, 0.0, 0.6, 0.8, 0.8, now())); - pub_debug_markers_->publish(marker_array); - - // show the validation results - // 1. distance from footprints to road boundaries - const bool are_footprints_inside_lanelets = [&]() { - std::cerr << "1. Footprints inside Lanelets:" << std::endl; - if (dist_thresh_to_road_border < min_dist) { - std::cerr << " The generated centerline is inside the lanelet. (threshold:" - << dist_thresh_to_road_border << "[m] < actual:" << min_dist << "[m])" << std::endl - << " Passed." << std::endl; - return true; - } - std::cerr << RED_TEXT - << " The generated centerline is outside the lanelet. (actual:" << min_dist - << "[m] <= threshold:" << dist_thresh_to_road_border << "[m])" << std::endl - << " Failed." << RESET_TEXT << std::endl; - return false; - }(); - // 2. centerline's curvature - std::cerr << "2. Curvature:" << std::endl; - const bool is_curvature_low = - true; // always tre for now since the curvature is just estimated and not enough precise. - if (max_steer_angle < steer_angle_threshold) { - std::cerr << " The generated centerline has no high steer angle. (estimated:" - << autoware::universe_utils::rad2deg(max_steer_angle) - << "[deg] < threshold:" << autoware::universe_utils::rad2deg(steer_angle_threshold) - << "[deg])" << std::endl - << " Passed." << std::endl; - } else { - std::cerr << YELLOW_TEXT << " The generated centerline has a too high steer angle. (threshold:" - << autoware::universe_utils::rad2deg(steer_angle_threshold) - << "[deg] <= estimated:" << autoware::universe_utils::rad2deg(max_steer_angle) - << "[deg])" << std::endl - << " However, the estimated steer angle is not enough precise, so the result is " - "conditional pass." - << std::endl - << " Conditionally Passed." << RESET_TEXT << std::endl; - } - // 3. result - std::cerr << std::endl << BOLD_TEXT << "Result:" << RESET_TEXT << std::endl; - if (are_footprints_inside_lanelets && is_curvature_low) { - std::cerr << BOLD_TEXT << " Passed!" << RESET_TEXT << std::endl; - } else { - std::cerr << BOLD_TEXT << RED_TEXT << " Failed!" << RESET_TEXT << std::endl; - } - - std::cerr << "###################################################################################" - "#############################" - << std::endl - << std::endl; - RCLCPP_INFO(get_logger(), "Validated the generated centerline."); -} - -void StaticCenterlineGeneratorNode::save_map() -{ - if (!route_handler_ptr_) { - return; - } - - const auto & centerline = centerline_handler_.get_selected_centerline(); - const auto & route_lane_ids = centerline_handler_.get_route_lane_ids(); - - const auto lanelet2_output_file_path = getRosParameter("lanelet2_output_file_path"); - - const auto route_lanelets = utils::get_lanelets_from_ids(*route_handler_ptr_, route_lane_ids); - - // update centerline in map - utils::update_centerline(original_map_ptr_, route_lanelets, centerline); - RCLCPP_INFO(get_logger(), "Updated centerline in map."); - - // save map with modified center line - std::filesystem::create_directory("/tmp/autoware_static_centerline_generator"); - const auto map_projector = - autoware::geography_utils::get_lanelet2_projector(*map_projector_info_); - lanelet::write(lanelet2_output_file_path, *original_map_ptr_, *map_projector); - RCLCPP_INFO( - get_logger(), "Saved map in %s", "/tmp/autoware_static_centerline_generator/lanelet2_map.osm"); - - // copy the output LL2 map to the temporary file for debugging - const std::string debug_output_file_dir{"/tmp/autoware_static_centerline_generator/output/"}; - std::filesystem::create_directories(debug_output_file_dir); - std::filesystem::copy( - lanelet2_output_file_path, debug_output_file_dir + "lanelet2_map.osm", - std::filesystem::copy_options::overwrite_existing); -} -} // namespace autoware::static_centerline_generator diff --git a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp deleted file mode 100644 index c591dcfc73bd8..0000000000000 --- a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp +++ /dev/null @@ -1,187 +0,0 @@ -// Copyright 2022 Tier IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef STATIC_CENTERLINE_GENERATOR_NODE_HPP_ -#define STATIC_CENTERLINE_GENERATOR_NODE_HPP_ - -#include "autoware/universe_utils/ros/parameter.hpp" -#include "autoware_static_centerline_generator/srv/load_map.hpp" -#include "autoware_static_centerline_generator/srv/plan_path.hpp" -#include "autoware_static_centerline_generator/srv/plan_route.hpp" -#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" -#include "centerline_source/optimization_trajectory_based_centerline.hpp" -#include "rclcpp/rclcpp.hpp" -#include "type_alias.hpp" - -#include "autoware_map_msgs/msg/map_projector_info.hpp" -#include "std_msgs/msg/empty.hpp" -#include "std_msgs/msg/float32.hpp" -#include "std_msgs/msg/int32.hpp" - -#include -#include -#include -#include - -namespace autoware::static_centerline_generator -{ -using autoware_map_msgs::msg::MapProjectorInfo; -using autoware_static_centerline_generator::srv::LoadMap; -using autoware_static_centerline_generator::srv::PlanPath; -using autoware_static_centerline_generator::srv::PlanRoute; - -struct CenterlineWithRoute -{ - std::vector centerline{}; - std::vector route_lane_ids{}; -}; -struct CenterlineHandler -{ - CenterlineHandler() = default; - explicit CenterlineHandler(const CenterlineWithRoute & centerline_with_route) - : whole_centerline_with_route(centerline_with_route), - start_index(0), - end_index(centerline_with_route.centerline.size() - 1) - { - } - std::vector get_selected_centerline() const - { - if (!whole_centerline_with_route) { - return std::vector{}; - } - const auto & centerline_begin = whole_centerline_with_route->centerline.begin(); - return std::vector( - centerline_begin + start_index, centerline_begin + end_index + 1); - } - std::vector get_route_lane_ids() const - { - if (!whole_centerline_with_route) { - return std::vector{}; - } - return whole_centerline_with_route->route_lane_ids; - } - bool is_valid() const { return whole_centerline_with_route && start_index < end_index; } - bool update_start_index(const int arg_start_index) - { - if (whole_centerline_with_route && arg_start_index < end_index) { - start_index = arg_start_index; - return true; - } - return false; - } - bool update_end_index(const int arg_end_index) - { - if (whole_centerline_with_route && start_index < arg_end_index) { - end_index = arg_end_index; - return true; - } - return false; - } - - std::optional whole_centerline_with_route{std::nullopt}; - int start_index{}; - int end_index{}; -}; - -struct RoadBounds -{ - std::vector left_bound; - std::vector right_bound; -}; - -class StaticCenterlineGeneratorNode : public rclcpp::Node -{ -public: - explicit StaticCenterlineGeneratorNode(const rclcpp::NodeOptions & node_options); - void generate_centerline(); - void validate(); - void save_map(); - -private: - // load map - void load_map(const std::string & lanelet2_input_file_path); - void on_load_map( - const LoadMap::Request::SharedPtr request, const LoadMap::Response::SharedPtr response); - - // plan route - std::vector plan_route_by_lane_ids( - const lanelet::Id start_lanelet_id, const lanelet::Id end_lanelet_id); - std::vector plan_route( - const geometry_msgs::msg::Pose & start_center_pose, - const geometry_msgs::msg::Pose & end_center_pose); - - void on_plan_route( - const PlanRoute::Request::SharedPtr request, const PlanRoute::Response::SharedPtr response); - - // plan centerline - CenterlineWithRoute generate_whole_centerline_with_route(); - std::vector get_route_lane_ids_from_points( - const std::vector & points); - void on_plan_path( - const PlanPath::Request::SharedPtr request, const PlanPath::Response::SharedPtr response); - - void visualize_selected_centerline(); - - // parameter - template - T getRosParameter(const std::string & param_name) - { - return autoware::universe_utils::getOrDeclareParameter(*this, param_name); - } - - lanelet::LaneletMapPtr original_map_ptr_{nullptr}; - LaneletMapBin::ConstSharedPtr map_bin_ptr_{nullptr}; - std::shared_ptr route_handler_ptr_{nullptr}; - std::unique_ptr map_projector_info_{nullptr}; - - CenterlineHandler centerline_handler_; - - float footprint_margin_for_road_bound_{0.0}; - - enum class CenterlineSource { - OptimizationTrajectoryBase = 0, - BagEgoTrajectoryBase, - }; - CenterlineSource centerline_source_; - OptimizationTrajectoryBasedCenterline optimization_trajectory_based_centerline_; - - // publisher - rclcpp::Publisher::SharedPtr pub_map_bin_{nullptr}; - rclcpp::Publisher::SharedPtr pub_whole_centerline_{nullptr}; - rclcpp::Publisher::SharedPtr pub_centerline_{nullptr}; - rclcpp::Publisher::SharedPtr pub_validation_results_{nullptr}; - rclcpp::Publisher::SharedPtr pub_debug_ego_footprint_bounds_{nullptr}; - rclcpp::Publisher::SharedPtr pub_debug_markers_{nullptr}; - - // subscriber - rclcpp::Subscription::SharedPtr sub_traj_start_index_; - rclcpp::Subscription::SharedPtr sub_traj_end_index_; - rclcpp::Subscription::SharedPtr sub_save_map_; - rclcpp::Subscription::SharedPtr sub_validate_; - rclcpp::Subscription::SharedPtr sub_traj_resample_interval_; - rclcpp::Subscription::SharedPtr sub_footprint_margin_for_road_bound_; - - // service - rclcpp::Service::SharedPtr srv_load_map_; - rclcpp::Service::SharedPtr srv_plan_route_; - rclcpp::Service::SharedPtr srv_plan_path_; - - // callback group for service - rclcpp::CallbackGroup::SharedPtr callback_group_; - - // vehicle info - autoware::vehicle_info_utils::VehicleInfo vehicle_info_; -}; -} // namespace autoware::static_centerline_generator -#endif // STATIC_CENTERLINE_GENERATOR_NODE_HPP_ diff --git a/planning/autoware_static_centerline_generator/src/type_alias.hpp b/planning/autoware_static_centerline_generator/src/type_alias.hpp deleted file mode 100644 index 2b7b99bfe81be..0000000000000 --- a/planning/autoware_static_centerline_generator/src/type_alias.hpp +++ /dev/null @@ -1,47 +0,0 @@ -// Copyright 2022 Tier IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. -#ifndef TYPE_ALIAS_HPP_ -#define TYPE_ALIAS_HPP_ - -#include "autoware/route_handler/route_handler.hpp" -#include "autoware/universe_utils/geometry/geometry.hpp" - -#include "autoware_map_msgs/msg/lanelet_map_bin.hpp" -#include "autoware_perception_msgs/msg/predicted_objects.hpp" -#include "autoware_planning_msgs/msg/lanelet_route.hpp" -#include "autoware_planning_msgs/msg/path.hpp" -#include "autoware_planning_msgs/msg/path_point.hpp" -#include "autoware_planning_msgs/msg/trajectory.hpp" -#include "autoware_planning_msgs/msg/trajectory_point.hpp" -#include "visualization_msgs/msg/marker_array.hpp" - -namespace autoware::static_centerline_generator -{ -using autoware::route_handler::RouteHandler; -using autoware::universe_utils::LinearRing2d; -using autoware::universe_utils::LineString2d; -using autoware::universe_utils::Point2d; -using autoware_map_msgs::msg::LaneletMapBin; -using autoware_perception_msgs::msg::PredictedObjects; -using autoware_planning_msgs::msg::LaneletRoute; -using autoware_planning_msgs::msg::Path; -using autoware_planning_msgs::msg::PathPoint; -using autoware_planning_msgs::msg::Trajectory; -using autoware_planning_msgs::msg::TrajectoryPoint; -using tier4_planning_msgs::msg::PathWithLaneId; -using visualization_msgs::msg::Marker; -using visualization_msgs::msg::MarkerArray; -} // namespace autoware::static_centerline_generator - -#endif // TYPE_ALIAS_HPP_ diff --git a/planning/autoware_static_centerline_generator/src/utils.cpp b/planning/autoware_static_centerline_generator/src/utils.cpp deleted file mode 100644 index f84fe79cec288..0000000000000 --- a/planning/autoware_static_centerline_generator/src/utils.cpp +++ /dev/null @@ -1,263 +0,0 @@ -// Copyright 2022 Tier IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "utils.hpp" - -#include "autoware/behavior_path_planner_common/data_manager.hpp" -#include "autoware/behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" -#include "autoware/universe_utils/geometry/geometry.hpp" -#include "autoware/universe_utils/ros/marker_helper.hpp" - -#include -#include - -#include -#include -#include -#include -#include - -namespace autoware::static_centerline_generator -{ -namespace -{ -nav_msgs::msg::Odometry::ConstSharedPtr convert_to_odometry(const geometry_msgs::msg::Pose & pose) -{ - auto odometry_ptr = std::make_shared(); - odometry_ptr->pose.pose = pose; - return odometry_ptr; -} - -lanelet::Point3d createPoint3d(const double x, const double y, const double z) -{ - lanelet::Point3d point(lanelet::utils::getId()); - - // position - point.x() = x; - point.y() = y; - point.z() = z; - - // attributes - point.setAttribute("local_x", x); - point.setAttribute("local_y", y); - // NOTE: It seems that the attribute "ele" is assigned automatically. - - return point; -} -} // namespace - -namespace utils -{ -rclcpp::QoS create_transient_local_qos() -{ - return rclcpp::QoS{1}.transient_local(); -} - -lanelet::ConstLanelets get_lanelets_from_ids( - const RouteHandler & route_handler, const std::vector & lane_ids) -{ - lanelet::ConstLanelets lanelets; - for (const lanelet::Id lane_id : lane_ids) { - const auto lanelet = route_handler.getLaneletsFromId(lane_id); - lanelets.push_back(lanelet); - } - return lanelets; -} - -geometry_msgs::msg::Pose get_center_pose( - const RouteHandler & route_handler, const size_t lanelet_id) -{ - // get middle idx of the lanelet - const auto lanelet = route_handler.getLaneletsFromId(lanelet_id); - const auto center_line = lanelet.centerline(); - const size_t middle_point_idx = std::floor(center_line.size() / 2.0); - - // get middle position of the lanelet - geometry_msgs::msg::Point middle_pos; - middle_pos.x = center_line[middle_point_idx].x(); - middle_pos.y = center_line[middle_point_idx].y(); - middle_pos.z = center_line[middle_point_idx].z(); - - // get next middle position of the lanelet - geometry_msgs::msg::Point next_middle_pos; - next_middle_pos.x = center_line[middle_point_idx + 1].x(); - next_middle_pos.y = center_line[middle_point_idx + 1].y(); - next_middle_pos.z = center_line[middle_point_idx + 1].z(); - - // calculate middle pose - geometry_msgs::msg::Pose middle_pose; - middle_pose.position = middle_pos; - const double yaw = autoware::universe_utils::calcAzimuthAngle(middle_pos, next_middle_pos); - middle_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(yaw); - - return middle_pose; -} - -PathWithLaneId get_path_with_lane_id( - const RouteHandler & route_handler, const lanelet::ConstLanelets lanelets, - const geometry_msgs::msg::Pose & start_pose, const double ego_nearest_dist_threshold, - const double ego_nearest_yaw_threshold) -{ - // get center line - constexpr double s_start = 0.0; - constexpr double s_end = std::numeric_limits::max(); - auto path_with_lane_id = route_handler.getCenterLinePath(lanelets, s_start, s_end); - path_with_lane_id.header.frame_id = "map"; - - // create planner data - auto planner_data = std::make_shared(); - planner_data->route_handler = std::make_shared(route_handler); - planner_data->self_odometry = convert_to_odometry(start_pose); - planner_data->parameters.ego_nearest_dist_threshold = ego_nearest_dist_threshold; - planner_data->parameters.ego_nearest_yaw_threshold = ego_nearest_yaw_threshold; - - // generate drivable area and store it in path with lane id - constexpr double vehicle_length = 0.0; - const auto drivable_lanes = behavior_path_planner::utils::generateDrivableLanes(lanelets); - behavior_path_planner::utils::generateDrivableArea( - path_with_lane_id, drivable_lanes, false, false, vehicle_length, planner_data); - - return path_with_lane_id; -} - -void update_centerline( - lanelet::LaneletMapPtr lanelet_map_ptr, const lanelet::ConstLanelets & lanelets, - const std::vector & new_centerline) -{ - // get lanelet as reference to update centerline - lanelet::Lanelets lanelets_ref; - for (const auto & lanelet : lanelets) { - for (auto & lanelet_ref : lanelet_map_ptr->laneletLayer) { - if (lanelet_ref.id() == lanelet.id()) { - lanelets_ref.push_back(lanelet_ref); - } - } - } - - // store new centerline in lanelets - size_t lanelet_idx = 0; - lanelet::LineString3d centerline(lanelet::utils::getId()); - for (size_t traj_idx = 0; traj_idx < new_centerline.size(); ++traj_idx) { - const auto & traj_pos = new_centerline.at(traj_idx).pose.position; - - for (; lanelet_idx < lanelets_ref.size(); ++lanelet_idx) { - auto & lanelet_ref = lanelets_ref.at(lanelet_idx); - - const lanelet::BasicPoint2d point(traj_pos.x, traj_pos.y); - // TODO(murooka) This does not work with L-crank map. - const bool is_inside = lanelet::geometry::inside(lanelet_ref, point); - if (is_inside) { - const auto center_point = createPoint3d(traj_pos.x, traj_pos.y, traj_pos.z); - - // set center point - centerline.push_back(center_point); - lanelet_map_ptr->add(center_point); - break; - } - - if (!centerline.empty()) { - // set centerline - lanelet_map_ptr->add(centerline); - lanelet_ref.setCenterline(centerline); - - // prepare new centerline - centerline = lanelet::LineString3d(lanelet::utils::getId()); - } - } - - if (traj_idx == new_centerline.size() - 1 && !centerline.empty()) { - auto & lanelet_ref = lanelets_ref.at(lanelet_idx); - - // set centerline - lanelet_map_ptr->add(centerline); - lanelet_ref.setCenterline(centerline); - } - } -} - -Marker create_footprint_marker( - const LinearRing2d & footprint_poly, const double width, const double r, const double g, - const double b, const double a, const rclcpp::Time & now, const size_t idx) -{ - auto marker = autoware::universe_utils::createDefaultMarker( - "map", rclcpp::Clock().now(), "unsafe_footprints", idx, - visualization_msgs::msg::Marker::LINE_STRIP, - autoware::universe_utils::createMarkerScale(width, 0.0, 0.0), - autoware::universe_utils::createMarkerColor(r, g, b, a)); - marker.header.stamp = now; - // TODO(murooka) Ideally, the following is unnecessary for the topic of transient local. - marker.lifetime = rclcpp::Duration(0, 0); - - for (const auto & point : footprint_poly) { - geometry_msgs::msg::Point geom_point; - geom_point.x = point.x(); - geom_point.y = point.y(); - // geom_point.z = point.z(); - - marker.points.push_back(geom_point); - } - marker.points.push_back(marker.points.front()); - return marker; -} - -Marker create_text_marker( - const std::string & ns, const geometry_msgs::msg::Pose & pose, const double value, const double r, - const double g, const double b, const double a, const rclcpp::Time & now, const size_t idx) -{ - auto marker = autoware::universe_utils::createDefaultMarker( - "map", rclcpp::Clock().now(), ns, idx, visualization_msgs::msg::Marker::TEXT_VIEW_FACING, - autoware::universe_utils::createMarkerScale(0.5, 0.5, 0.5), - autoware::universe_utils::createMarkerColor(r, g, b, a)); - marker.pose = pose; - marker.header.stamp = now; - marker.lifetime = rclcpp::Duration(0, 0); - - std::stringstream ss; - ss << std::setprecision(2) << value; - marker.text = ss.str(); - - return marker; -} - -Marker create_points_marker( - const std::string & ns, const std::vector & points, const double width, - const double r, const double g, const double b, const double a, const rclcpp::Time & now) -{ - auto marker = autoware::universe_utils::createDefaultMarker( - "map", now, ns, 1, Marker::LINE_STRIP, - autoware::universe_utils::createMarkerScale(width, 0.0, 0.0), - autoware::universe_utils::createMarkerColor(r, g, b, a)); - marker.lifetime = rclcpp::Duration(0, 0); - marker.points = points; - return marker; -} - -MarkerArray create_delete_all_marker_array( - const std::vector & ns_vec, const rclcpp::Time & now) -{ - Marker marker; - marker.header.stamp = now; - marker.action = visualization_msgs::msg::Marker::DELETEALL; - - MarkerArray marker_array; - for (const auto & ns : ns_vec) { - marker.ns = ns; - marker_array.markers.push_back(marker); - } - - return marker_array; -} - -} // namespace utils -} // namespace autoware::static_centerline_generator diff --git a/planning/autoware_static_centerline_generator/src/utils.hpp b/planning/autoware_static_centerline_generator/src/utils.hpp deleted file mode 100644 index f4d15d3dcfd4f..0000000000000 --- a/planning/autoware_static_centerline_generator/src/utils.hpp +++ /dev/null @@ -1,67 +0,0 @@ -// Copyright 2022 Tier IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef UTILS_HPP_ -#define UTILS_HPP_ - -#include "autoware/route_handler/route_handler.hpp" -#include "type_alias.hpp" - -#include - -#include -#include -#include -#include - -namespace autoware::static_centerline_generator -{ -namespace utils -{ -rclcpp::QoS create_transient_local_qos(); - -lanelet::ConstLanelets get_lanelets_from_ids( - const RouteHandler & route_handler, const std::vector & lane_ids); - -geometry_msgs::msg::Pose get_center_pose( - const RouteHandler & route_handler, const size_t lanelet_id); - -PathWithLaneId get_path_with_lane_id( - const RouteHandler & route_handler, const lanelet::ConstLanelets lanelets, - const geometry_msgs::msg::Pose & start_pose, const double ego_nearest_dist_threshold, - const double ego_nearest_yaw_threshold); - -void update_centerline( - lanelet::LaneletMapPtr lanelet_map_ptr, const lanelet::ConstLanelets & lanelets, - const std::vector & new_centerline); - -Marker create_footprint_marker( - const LinearRing2d & footprint_poly, const double width, const double r, const double g, - const double b, const double a, const rclcpp::Time & now, const size_t idx); - -Marker create_text_marker( - const std::string & ns, const geometry_msgs::msg::Pose & pose, const double value, const double r, - const double g, const double b, const double a, const rclcpp::Time & now, const size_t idx); - -Marker create_points_marker( - const std::string & ns, const std::vector & points, const double width, - const double r, const double g, const double b, const double a, const rclcpp::Time & now); - -MarkerArray create_delete_all_marker_array( - const std::vector & ns_vec, const rclcpp::Time & now); - -} // namespace utils -} // namespace autoware::static_centerline_generator - -#endif // UTILS_HPP_ diff --git a/planning/autoware_static_centerline_generator/srv/LoadMap.srv b/planning/autoware_static_centerline_generator/srv/LoadMap.srv deleted file mode 100644 index 02142e60c0035..0000000000000 --- a/planning/autoware_static_centerline_generator/srv/LoadMap.srv +++ /dev/null @@ -1,3 +0,0 @@ -string map ---- -string message diff --git a/planning/autoware_static_centerline_generator/srv/PlanPath.srv b/planning/autoware_static_centerline_generator/srv/PlanPath.srv deleted file mode 100644 index 3a8d0321ffb9a..0000000000000 --- a/planning/autoware_static_centerline_generator/srv/PlanPath.srv +++ /dev/null @@ -1,6 +0,0 @@ -uint32 map_id -int64[] route ---- -autoware_static_centerline_generator/PointsWithLaneId[] points_with_lane_ids -string message -int64[] unconnected_lane_ids diff --git a/planning/autoware_static_centerline_generator/srv/PlanRoute.srv b/planning/autoware_static_centerline_generator/srv/PlanRoute.srv deleted file mode 100644 index fb50c04b0ff26..0000000000000 --- a/planning/autoware_static_centerline_generator/srv/PlanRoute.srv +++ /dev/null @@ -1,5 +0,0 @@ -int64 start_lane_id -int64 end_lane_id ---- -int64[] lane_ids -string message diff --git a/planning/autoware_static_centerline_generator/test/data/bag_ego_trajectory_turn-left-right.db3 b/planning/autoware_static_centerline_generator/test/data/bag_ego_trajectory_turn-left-right.db3 deleted file mode 100644 index ed3448772b794d73ff3e094907bbf6343b59585b..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 2740224 zcmeEP2Ygdi7k{1UE>OxIrK~d3LFr(GQZ|JGWfur(^4f-Gv>6>hfxNVc3W$L62?)p* z1Vm6&q(x*12qH^x0*WY06j4#Y@7(uZM#t+*Xo9WW{J!s*zTAX&&-tHo&${QPj7*a2 z$dGikMk&#SL=kle7Z;*WNC-jrPb3J}R|(6@1Kzq@{v=$i-gCT#-{?ASh(CPl;jbhD zUkVHinB;#L-r^Ug0Hy$@0Hy$@0Hy$@0Hy$@0Hy$@z<-+p<2*bYwr}oIAXmxAe4SiL zYIPE2wpcF9hqqcu2C4N-9MwNzbpMdS!~69gA5vyWNb>Ly)3A^*^G6{GDTy5nLGFTv z&6~Rz3Urb*1!)>)`mYE3tD_V8CiOS}NSIs(|IX zmP_HG%pVR<9vw1#Oj1&3%Rg%Rp82B?nM5ZE>6?_?H^g+WgCX2a(6Di17pe#SRP^s^ znX7x5Ct~h#J&#JFBtu5`9}f>U6n+)Rz6>4hA<@hL96jLh2-FVoH+vuUnbNHr?fVaMS1FTvDTjr>aO$(};3U zA$OtaX6QmcgjSkKDkaR-waf!B_rjR}RQOk{d8&aa%j8;}MqTcoLcY06;5`EVhhLZi zm;#srm;#srm;#srm;#srm;#srm;#srm;(PL3V6G@5sfqTN(dDp{~wb6_=PEeDS#<} zDS#<}DS#<}DS#<}DS#<}DS#<}Dexbr04nP57#N6V*gf#?z~2LZ3A`D2E$~X<*MS!T z&jg+fJR0~>;J&~;fja}Y25tyk9r#M%lE4Ll&jcC*X9Vg4)q(OrY2f6*ae*TPhX(c! z6a~fwMg?{WY#-PvuxVg0^TYpP^5Lmr3SbIg3SbIg3SbIg3SbIg3SbIg3SbJxOS%c!L=h557!PcM1FpuC4><|G+!^!W6(1z!bm~z!bm~z!bm~z!bm~z!bm~z!bm~ z`0r4_wf}R0C~n{v7zS5YecoDJFexye{_wvuX*?550Zai* z0Zai*0Zai*0Zai*0Zai*0Zai*fhsBBI?&(E)3xDIW#@aXfBV&EFL=xi**l$1i@Kfl zJ_4EapV&Jcw+k;!@H!25_Of?6ymo!Za=|ZfX90UB?4@_V{#F2G1}9-f36ZXOY$eiUC~Q*gI`=>S^C}M;-Lfv3J_YKK*;5+kCk58hfYp_&3Ila@`7d zl>)|9-?DM8He_U3?Gvqi^}v95WOY`6%7_jvgJbP#z|^a5`{2>)Coyd2DIYT$w^H&vFQUbj1nug8CoG+ zg#GCeDLRQxua(L)T|zRUwW3;65FZlZ6A~gLvvrxwTMem@OVZ>Dxz6;NUSs|{k{&CO zDdZ|L9^Qw9Xh~^&NL*xOR8&l4cvN@#o{GL18{I7?COS4e2JR{3>7+JWqO$Khx$r0| z=rYPYm_ly)TdW`@T2d^72Sc4R?fFqju39b=qt=qBMJGIxloU(Vs$5cqehL1ibcsSs zQklL2B5_>hq*jue3{oX6sFK>IL73Ehq?Y*zh`0%rl3J!#YpSAhKlmIY+9pJg^Y$bL zs)PJ1st%c4lA%&-b#f{EpId(PVR|m&}w)6;%>`EHfmL`6|efGMkiP zF7R+c?CD92$*D|`q|nMajaiYz&?Fny*(zag8O^A$1dT>gfCOr~hkzKDVPdmHuT$qq zG$g&u!@89w$q*~l85wd_hFGbVRmtH|^zbBR^e`Cw_}pcTg#Z4+pYARo63p7H4Dr?3 zByhLt6)Bk=^Z0~*S}d$|H*P|wL1T32KVFsiB(q~Mp?UNbMY@95U^ZpTAe!+SOt-}7 z4RmCu7mo6d!{gKWY0(^+F4iuCiKvWsX7UEALUe!AAWUi=NF)E>m-vSWDDrppeZ?o- z`;3>=^Pb0a_qwjL;P!w0Ma^s|AaX{U3L$Mn*zYfdIDl-h`%+=RwXy)B6{8wou-0AhqW zl`aMfH3~$sXUb`%Y7Ly&S4CVu$!d5C8jTkSn-+)ye*uwPxh0e?kt@VnNjgc}LRCg+ z2f)x27>U*jbit;O4WE1H3==l6W=nT<#%sd)Kv>%XjcmHC{&7 zHUc6`5>zx)D9J;Kc5vO&)8TYUg*+ouN1M7T5(4sCo!In=R-OTgc$2#!uFR_g2OIrJ z3O$nB#}0=T6DQ!c z{zJ;R;;|_(GzE?9&kn>(24BtA;1-@l!UW_((jYHKc}qIJj7~{FV-u`mfV4iLvYHEs z9_9$IDY6CeTR7Ah70Q@?Tnr~ILy=u>gk|wzgIhz*W4Sqp*LtSdPS;F843?Xm8B=ls zN?5>^fht6Cx&-AeswO%!bO1flwAACEd6hwPUDHa*4)Jj~mK>@}_{pBa4#i}*J<>%f znt*OGm-kpK%Zip~1>J&ELslilwna*k8+#HWQ(%z^_Cbb@uAE}L^D0z1Q_KUyP0?JG zATkn-1jJ;s<8R8on$`%$dKE%RF`Qekp#L4qzffs?MItj4{TrjmY$z|n3x+NEf0z2m z|L^Aaov+mUrkC3DPmkx^eO>3l?WgiZBPr?3po`3*kT+DqIuF$TWS1P$|)5 zL4B26tGC1n&Do-1^oMu_wIv2@U-Zd z=^df+qM$N0&$6K+&P^Yf*VP0mthum7LzT#wdl>V!V!i_x=E2w3)BFFbzSR?1#4(5Ya*uNQMnR zuuB!R2Qo5cbTz3~C$p&azG}6C+fKx}CnonaupPt!#+jqTCU+fW{1}&=Su`sKhuL^8 zC=MpqWF*>x|DR#CoP{Q8-Fu3`zy^MizP!}FtMrQ&N*ur~px>})7=P^=@LPH8tBUVAo2U0<# zP_5Tx>vfEOF2?>jZ#x0ol&CQ@7B~_|XFgej3>9s=Y| zrwSRuo{;l;lH^1~NqU)Bi#Ai9t`ozyZn+E=794Sbgu1N_X>3$Z?Ynsqd4`tOzJJ*y z5~=}IX=$q*7H$>vv0%gO5dBSOcV3thPL+*Ct$E7inMRv`Zy57){ZP=J+rY;~1auLB zF(67n=*t9xO?CcACyANH7?1;z>NOf@_G7+b)kL8}(564zV#yRdpqp!`H7Hew8N!pK zqa=~A7htHhDR!L5e?-i3N`}C1}k-23)yRRpk=n|A!I*Qon<~9lW0t z{Ng#n{is_HmmNeXn}ANK z5-_OH4x~&HrDfAR49XE5LBC$hh zo9rw?3K~NP_CUR%mZ-KJSD8p%4gUam!t+1`P zO#UB*gsPEUeoB@nqw7EcQCKD*RDu3-tvFq-fC@1&>=cmaB2%2*`zY2(@|+p{c}kc- zO&WucdKWF$Jy`c(-Gg-xcD#^zSuu33ki($_ zaI%9|8y|x5%$C2!3P|k1?jWbN|G=vGu~f5to(1+Q=;{doahhBKM{mT3JS8b*EM1Q! zUH^{R4E}#zte@rSq&8b(S8CI;T;b&lukIKgzU{}J8%?|2qixUg_x;i~CDAMpQ)5C`>$=dyjUZHR3{xs3O0buRee z-^*KxiA=PPi&f^$9nj|6?N(}kTb8=NlG|Id#Y zNCdp#AL+Z-r<2!iuLRG}J(Asjb{p&R8GK;d%P5!tJs#cY9*+vO6b@mSPFMa3^*Xsi zDAho>hBS3P+e3!4!83P5N8G2@=03Hq;|0VFyBHxYkSgR-d=MYBrE^du%-CQYh(lc| z>S~sYjxsuy%wEm!n9Qqrpck?Q6{E8&y(vi#Zq;yL?f4|q+|xER+2hR zfu#Z42>6w8FeuSHrrMo;o|4+MDPui}oD?{^wjx*99Ok>OU zxOJ0tvst6Z7y+RMz7MVPUvL_m@v6_ZFwGb(Ad;b{5I-L(7cX9c!jxtxos%MflY03? zN<~UEAYkHLbv~(J&hA43M%xHtg**!?!86rrnQcNw=|%|%NirXE<>)|D9n!HXy|U6@ z9<0(?3ol2TM$Bo3(?JR}N{0IA9@+tOiCphAn>EY+L-Bk*=pSl+{ zLM9-hBZ7*C39}_qrCKIT*Qk|ZsYE4C(`(Uxpvk9Jh&p`^&`6Zr-G!sWvE9Jh;)A3D zqLUCQOqQge9Mcq}tjt*gs9){ltH-CMQEh6PfQX^p8kUq&wK7|+LWeMGvUSY8C<{d4 zuw~}cQQ109;znYivOt|65fDN+W_hRysA(EW7Fj7}QwrcD8YPf*fI=<7wB;@Cp(afg z5Tb+%v{kBga6SuQR~%IVy~EIFK;kG2T@9bzG)c@u-bhaJMq={vlXnUac_TQ<8-dBo zOWyI58O3Y15E#V^$3IjcE2DT5m9nZ8FER);5LGg7zJ5wKV^isq1Vkbn?qFWi;OKg> zmR`Ns^VHGSS7hm0*$oK_1w&_af`(p8YB7d+F+3r)obf>Wtk`&PK=~OpequTOz|a=! zhblIf+7``X{C{^MV6*=a-#b1_y(0u?J!g2daw`G<-~H)u|EWo8@cFIne)^P2INATd4r+ND>_@2unQYs)JW|)?=Nj6cD{CMXp4jUpabN@+Ro>aZtd9 z0x4>o0@fbukc&1`o?dyl#T*oX#3CnlakwR(1@G7_hO%a>pP_7}N`W?5K_yg0S*#UU z!cLq9Q9@9-W}BZOET>99fX4d3HiLC?shL<-1%C=FhS=~J z+cT^aG8z1u6$6|x$e#RNsdB&;gYC2(mjS2f4z|(_nQD!ya!bJ!;;u3^gO@YYa+aE2 zE;o}&N@NOoMkY2Es=q;x8biXF8zW-r8W^BLClq=tTH0@{9HP z)_b~F2hWc^ly2)?K8KrSU&amvP}JN>O*?X=MoMO*;yR%^Z5k;Bh?7!v1}go6TQU-k z-KF126?$;?kUJ-oLbhBZfnq-yESF62Gy7ewM6XllL4lwcy%A@df7_DC>_`71DNCmR zG460AHUSwE&^RRDi=e#eZ2%T}R*P41r6hwy714;@sH!rJu2^R|DI?SL8AA9}3JrZx zn`cgJ>Jq`YsHyyKprsDXdAnnB7{Z!kG&Er=4bR}%t?jX|B4sxCxe-Cn`kHDG!6UN2 z`WX8`j330+Qw$epvvQ35e{bR#5zx=?1)uZYT?Ml|PP(^nRl==W_A<6KxI%oQp< z$Qi)63C?63PHQ;aN{pKhOzZ!+TCs}6FxHgLZe2_J|1QBqz!<-czKy*L1qVF^?pdw} z;nvgpGIlcf0-}X>xjorxxe9h*!-d{Bpq7i-;s;#p;N(U)#?}TOU{}k>XO}P+I#$YP zBOgb9oEH6QWbg(yc~^r?*b#M>BN}J$0^VfUWq6g*ctUJ6|7%8bv_SyO6FZrC*l>2Z z;oQjJX}3l+1rgFn=%7fl{bO+jrNepSZSW8fO1l;-ygWH;dFo_v2SFKXmxjX&(!aJK zwKuo{yAmDFF1!ReTFo)_|0EHh@w@Ds;(frYo98-@V7DTd-wD!T0RW@FAsAZ6(rq0r zk?yLi(KTwhwi|m=fLX)?VvAVH&%6yW$cPrE3ikDak?;t`3(!)fAC=W)a% z5{rj(#3S%=#3KTWhttF(;Bmww0*i-p#KZq_#3LMwhttHv?{UN<9E*n&#DmHIzsdOj z(cZ;gE}jPWOKv?}-gKDvkAKL46fg=5Ed)fClD`6xE{;cy7i^A7kEZuO;2sM$9t2}- zWoQmj&KMh_oMv7q^$MMwt$#P~H^IFVoLI5j+|Ue|BywGykSwu9Hq!K;X$Xsp#DipNw(=gS-hw?aZw2~ zGy;D0cRauF`r_#I1#*uKAIJZX#{R$4{Qm}zQ;AMk>{3!{P1);tUNKX|Qe!>1tZ3Lampvo%Pfe$KXZX ziHmw`Lpxwqj|z)=MK;*ZD!iUMd_8Y$XbWs=Ux7_&TAc)XV~Mq7h7!(0WHxiqCw69N z)OwW+8^&6(vv-pjgAHwfIW4Qn94s{smzpp`YhX+z9!q6XQ*q@HtMxjCoP@@`as~AB zWo={J?$s&PM{NwDz^h)i36ZV5!ZPJ>nQCBY1$=5{8=s^ab+$N7osT8x2`oeP3?aao z#?|2rmKTT1OI<@th{V{Fy3|OZS-dbE8phike8x%4XnW3DVe2=y|nYponAskeUcUHN)31oWH)8$e)=72u;!|G53XbeDVR1$^IG(;=U zfIlr=>nzzXOC}4@jD9YK9*PrMHYK#`8-&0a58FAz9$|p_q9w&njIVSybOpXtNOGCT zUQuGeWYTK$B#JClDPbj5B%CUtl)%~W*bQ+ezZx650Ke+WZPsv1BcJZT71QxA5O~SR z6r!C&+`)TR#U&wyIZ7?ZO3o%F7i8#+lw9?ggV_Q$t|JflFg7uC0=5KIhb?4&HXN{n zg~kcnx>^}J0(aV$--lXub+JCk%B0bx3OL?T4u%*LRW^NrwcvPl8#do;Z-8%%F?0YX zjjT44OgtlHP*)}cn?WO&sLC7Pm~{?3-pCkk2m{t7I+Ar#@c*&6InOGm_y4B|Bs8pz?K3k&8M8|T-P}ew8NFN;x z>3p(WA0BqN#h)Jm-^1Mrc)Al%d4@OvF*&si#ieRB1W3?PX^^qf>9uC9K>Ll19@prk z7E&jgzK}wX$9{z^eg!q%5Gx?0Jfv5tfeGsDY}Duy%1*&3A~oH_nEK&S-RUD3RJ2bK z8{I7?#;#y2)MCd72sID&=|Cd<3#dF#4Cy~OVin$D9z;e)MLFQ0;ao#^0g-A44>08& zM)_!d%4ewI(C2Klu#y@~c?VHG-_T7!h`h#PHIR94G3jSpF%MX7C18HLKPYk z!Dp(H@@9&oQy#%|B*oH9i7Ep}YaHS*sSJH9kB?cPZ)Sj5eWN#w8IOVpN^OQ#2p1ua zkJ+$go6;B(V9RzTkher6AxNgtnfxS7bw>mS)P_C+BBg4o!|{7!ZKgb3he_@TlII#k zm9MH6pj)YPu?E$UV9Gm!@_IvWhzL{(c5BKjNDO(0*yB`=p%?h2RTADh1cuS>2(;%K zdh+QRY`r^UuM=4BJu0`}EgIfzJYwtJ@ikG5|L;KrJnvu6_kTWZy>x?KB~=oQ+~TGP=@n0=fm4>@<1{i;k}Fqh%wCMu z9aJ5_<|x=2WiyDY(XuKs9I}fVIMhRuCRfOH1@R&1ykArsV){E0{Y^?_5Vj=k!HPnj zPHLeafqmb}{kP5+ftdL)uuhnsVZaooB!hh;X3z42^6*@_MhE@D#85-7s0Q8fsmkoB z%I=0F=-k2-w^l`V^I?i?t%gaYtXM-k`|NLwWyY&DOr-{{kKw70fii)i5JP8nH&($1 z+%3d;b#tJChS;Kl7#=9;hJ;uJMOL>$20~whD-V5Hf{i%z<>;Nel-e+;^3azR)p6*{ zp=pg=!@$a2QVYpJ^_wyoIP?`C66crpD?en$tApa*bGNI!9^tFpL1<%W|U9PHN+&;2*{F-!$0=$!}! zomvOETxk78Vk|fX3&uo)7t>h;vggd`TLo5P z5p;kE4lqmr5p;2)$!X0ul&i-Q=o|@*GK>caOm*VwSDuqt0IM&6jQ>BH2p9tW|Brfm z36ebKL;k-mG1@-=-+Ht$&L9UUWH<*3P<}5-gLA$R8ni;}i8#0*#Ms@C3Cxo`5$0iY z)`6XbjJ*sQz&Z7k;GDH8rgz<9U0i)#Z0u=B2L>viGy{=Ug!$(H{>2(d;2-%U_=hWT z9Nf9TmqGTVlqas^uxq0soxv5uSukRiM2WU3N}=jqt;&T%Ucr;mnsSl-3{qfV;gb+P zoKtq*#wug9Ar1J5Hg`HFs%*Uu zHul5Wd{A7VPEXg8Y_CuAre$+;vLt3yGCk<=HxTV~3T(sC9mnho zHg+{Afomh3$2A<&ad1p0%Ajzrdc=_&XQ;<`Ll&@2?mR&=`~Bs1c~rxn#Crlvakx%~ zX~4aqPk?)vUDc1;F#dl!s{c3o9Q5{q{Qm;CbFNK@bVvI9&=g<>fWl!-0ig4oS_&QT z$~D=u9M@3|XyC{YyW1|tFdcX%b&4Qccjm)>yuS8 zZ_e2cS%z=euXm2&ng{H2j^WD5KJ4E+$iMGy$OY~>r|_)|_pqPuU_ZZyLH}gbCieH8 zp*H&(bilp>=Np>X?{{L|MwCGdTy#$Te;M^@=3+IRJRGiJ!!^kN_aZ(c0%Cn7-rEJ& zJcaI3*Y$9tw!VzXlpE|Q3UbtrB92glX(dpn!43o|Y)3!`qT{Va&e>YjgK`Dcg6g6j zQdwjVORJ${a3F~dBn_fmKq5VyEs>;-l%k4I`gm$Aip~+mZWJsRbakdvMX?Mou?$wb zZ$7kknGJk%SZfy!6>2`F9E+cG#7}6L1#CpEU7RU?W;SBUtG477rx*$ujrpv=5oOU_ zlBZTE6T8}c^XU?jDF>roV>)Jw%+_TxCvM>*xU{6PpJ67zy3ol+oh74- zR}`nLC`|sp8`}TB)aRJjLqUQ^j@urWpNMYU0RUqJk)K!=t1pX# zDFN`VK;m59(dQMx;c#?tQm2umr^}`6HdgcT?b)P83LXY>;LQ6CM>9iH$z zJ|%|&8wXIHpjaK&N{++Pwq_SPu%WX=-9 z^2gVJBa(6lt~qS~zYX$-m%wT-fsFsJBm!dmp7lBJ9Vi&@vB~XPQ*0JgL1S$wvSMIp@ z$3NVWLoeq^6j^za0&EgF$0X`P)dMDubejAz=hU-ItcKL#q8C=`qNuvSFti27ISP|u zn8}+|$TKpl)58(7jb&RRRR`GS>^cclEGSmURX8Z;q@bLT3IsMfyH3K)MyxQa?T8pV zQUSm+v~S#*3Nu@x%f#HOKDYW){=lu-PR?RjrGT+v=@i3~@&AVt0SSIHd`i6j7Q}nZ zay#hiNeq7+FW=aWY5}l7%{!eV#AV#X>RYSWM`X>Oc&a(@4Q)Jr0(^6n(Tcgpa<4np z47m4%!fK8%dNAi$&c#wqfpgAF9+%OVR;y_>Od!lVmUq3VCcwL#C!;eRSc!uf$TCnw zH3kOip9}*XTEKx>$g(hwY6L7q9XFnU-C~{k#|pIiK4f32Auw;olVM(^8+I`ltIx$A zR0H6m^ET&}F=1qm+8Bs6D5F6c{~z}MPxL$H+uB1=$+4l+aG{&8 z%4K|7aRhu}9E?wbgRTc-JB0TDNIxnB*yKB=`fRd=GkB%qTd6{+mcWlrc9|Cy#ineX z8*})dnLl{fRCrW(C{YgyQNjMQ_>kD>ZZR>@vEear&$cy*@&7*|0tWg$@AHv2AsFqk z#_d;EIq}Kk4)RH*aBGIgFMMTGh2cs|Bb9e|Ja6~l2Zb=HX=vst1w@e$_|9DD>vG!=%_ zD4**^hrVRckO)G{Li>1UPfQxSW%l_0K13Q3kl}aH=SRr@-}F?t-*QvC+=QDBc^N&a zcmbg-8$C4}qUjQpA<_yfEzdE>c_cDPwp^SWVM!T{WlsPcK!2Z3*y4yBPehKIO~nZa zF&`(&l-OVvIMm#vrc<#3Vhj%p%$+MR^&Lz78B~mb7{^0>OZN#(e#er3Ce>X)Oejl! zt&Su$DACNU1VZZ~+bZav!hQ|wf7@gI)J!Uxm;Tm=(_#8M7XSHFH=sXXC=bWvoDh>+ zQ!^i94lBZZH)A@qw0n@c}j@V0I5JsaZISL86k9 zVkjU)(utasAG!E+xqw2RPHM9ycBx*492f*jiLam|Mzi;AOdFl{pqXq{@F|I`HM%E z+fS}axQSmCDL}K!u$Zmy#<7XM+cer3o%91mY07 zB5s(q$0b+lg&74JwKz>K(PofpC8^UCSe)9i^roCBzAk$ej&pcgecEx zN~H*hs4~U|y%d5LA!U{B9qp@DD=>L&B(Ihl1=UR4xr^>5|45RDlNRy(TPSTLJ4ubK z(lP3e9V3T0MiAy2QKkPMZNfLs&Dm3;Y%|Q0tAu$phPgvvj{JXbq7xCY)j!F1uTML{ z9QSi>gIxB&t@1CU7nKG*96abA4yJUq0?skf2o+?yPDpogg3>*OoYa6Dq(J?pnbRAj z1yThZS%Z%fa@aCp^rs}ii$E@3$iNj+Yv@A_rD_c-AAr&Ud`OV<0+vQ^YAP^9@E8oi z(t$RpII<&jaeGS4XsTxg=E52)O$GfGv&CuZ{IXigo(8k{&@)>b%-}thRqm-Q4yC3* zo2rx`dytAXhNCqGMroBOHP)pjgF7oSwY zo1U%R7rS}F4g7K<1&n^wG*I3Cm8_@GbyibFCEORe;J3;cPNe4BcF_ zNS)UFw|Uzw+I5abq)4ISP^Re;l1b;@U>_~*Qj*!aOn6(N<=0bMpbVam6xOfGJRhDU zGWL9&;rTHB{~{vbMc?b*y}|!);r^l<;j+ky&M*GyDkwlHC=DD@R*5>&$TKo^LbLwC z`p6;mFW_zFaCw_F!MUqiutIW%LIQ6yo6FneVF{9KrJ8X!$4(qm+!Ysu+!-fvz4TryKGRgjkLk&xWFAP}8A;sDR!MTAtoe)TPs?6%|Qt`oJ8LOn^|O1_-W7WWIvQZ{x0` zX;cC1I;tf20w<2*&v_Doc_e$-qIECmnS0qV&Lz%62~T@B_<+qh+JG9i?N`RE3ZW;zi|NEDqH>BUFz) z*(yER;#QPaK+LEl;KB`5tS=m`FEB`}1S#_WeThqO{-3{_?<+p7y>lO7+=L15_|jBgdf*I2*A_;2C|59>AF94q*&tM|f2A znwJ~>jqbpXR@G#OBo_{^fCDQqL#oS=P@|hC5fm5XFVv;$(jzTuX7qqzaQp{zzz3CY zbcH5dW31wZOqf=zgblc;=Z7>~U*^3YeUoW^M&?6@7L`OHmSoEsI?W-o)t393{W%M)F0T-enq)!J!vXm|Z zu+`Ouwt?Atolu_*-ZmU}C&@$JwN@vyNY?;`TB3`J9Hv+3Y?2x#0t%#gM}t0vbw<#qrm6~dbQ=MXSo=tny3)S~b)g%Te43FY}H#kI(3B^g#@HeAzHF1WQM?r6a)T4a{g-4e3Zv z*OKV4XVV!r*b1g&D=ND5(0VV0jZ3{V9u1~I#k@>lDtsXLm)7cQO zIie`hK)EgUNz`(gn9tvbG?M_hQQb5Xk_j1^i_=WiwybFX-z9_yDD=DPtMLBKYmp$t zW3_vG*9~wJzX+p?v5A0~ptaT>S~_na)af-Uq!{GT|5mNhRvII$5ThCmUm9%w&L}b) zLg+Y>!4t`#W*HkpQv^CfYjT-cCO`<5q$|bqGD)c8VD2(5R|VRquw%!eq2Llj@&~Rs zPHThSrgX+e5F;-Wv?$L3=I^pGa!wv#VDWG-bqaSikyVeQLI`F7TzH&{`9j3b5sBRaM2= zWi!TFeMSZ(!^*_U&}pvNwc>HDkpJ)M-;D^E2N(Rp6u=a~6u=a~6u=a~6u=a~6u=a~ z6u=ZHLjh`pu^Dp^-C$uJnTFzIrg~?{2d1mbc%dmel%B$VD32cs38tnT2`1F?Pb$|H z*p^^L$1$MMI3{UROcMG39xhu5|4^TPf^_$J@D{&nBn667Jv<2)&*$4DH$18g37@)h z8{t9_kFIn`@BLn;|JdF;QnST*YDJp`*S|(X45=cYffC~wXsN4oa%0c zZef?E-A(Ae(yx&(7rLYVntTS#N z*`|547erk;vlO8lnmL$tcbC6@j5eWr{s-5+xzK&)f%GSYZl!-a8r^{&mjo99-6VPN z^6OiQN+-_h;MU+!VQKgWT|B=7bd&E9*@FSyf2B^z)n5~fTvM;UJ~N9O-9J5gS9)?u zXo(9uZtG9=do22a8{K`vRzI8ge$7MoEp{ILd7iJ`oL`q36YUIkmX0G#JqBYK893NBSQ!p*vvsE-x;0Pw0H+7D9L5c9*rt zGO2SrDt<*l$Pg~>F>yFPm7h1A}9XB`d^GlQ7 zOR8nJCh!IC7^dbE#f{Twm3=kwE82#P zezDt;?wY7R<6Nf23roR6DiUwG|5;(_sbJNauV9tExuNxgk+8~+ib-(@PZ9{rnp*y-w%qvcJ$mrF%zf4+M-^g6%)|L3-N@AsCyUF*@E8`96Fd2H*g92ma{`Tt&4=#IMm zd!7m1!mi&2a-n>LxE;!tN!XrR;tFdm+4m?v> z`bLRoe}wL=`_If94d@{%^_y5~34%_nZK0mr=d@ERx zzI$D**WHSoU*_8~54YA+zT8-}6#M^NCT)$oUz{3frH6WsDgDxDDa>-IEtw%|+-|F9?nf0d)WHevdCV>@6z&epmd#NuL&$zW(!bUm$cp z%-A&)p<7*=b2{30s%XIO>rpqBaihEU8&~qri&~ZRWycxwC(PXM&%Mh2{8@|47NVMm z?gVxo_jsOf(Qr+D%~AXP|BP1adNv5)kFpcref4wp1Fu?dL(Z9G+dM|Rwfw`STagXv zZ-wr-Yuigr=vK`*9n6L9l6l{LfY9wD`%#b3UGI_GcPMt-?C>a;PWy^Vk2jWf&jcIt zliiDhz6Nx!SCo8&Vz*zNSMG1^HC6Q4qgQ^6TFi~^ZWCVjxbl5S$w_uxKuF3nJG{8j zeKGC+?N=|>t8ua0Sau%Y@;u+APWivx4zgc&d;4A$o#@M7yLEQ7^zyQ+WUWW{2wj>@ z^Z2KY=*RJNb&H=Bx?^|#*58Eg=U-n{p9|fm)_!^lp<6ZaH0>ej2VVGN450g6W0!6Z zN{UL~xwPh!O^}%gSifx;LU(q%Ns$QMVL_>H%nzC>620)}qwI~`=>8${?wxuaTb1-; z$6fyBYRcs%+~_`BID7fYb~R6TUuWlWoagxx7w!)IP+~v2Pw#iRdfcBsc1t|?B>yYl zO))jjFt+!B-uc0{c}zY&Dw4KLe67$OLruP5LU-po>L4z3H*R@~Mt6RSedum~cFBaF zT*RW6Z*-owV>NelYv70O}3-VcjPN8kIn z`0B@nrA>m*^f?QwY+lP{>!-ph`^7VZ*C~^xh&*2ZUHsc4c`4Vdhko=+zhAG^D{*1R z9m(1A(-*6_b4cHI?y>XhdLA{-hBVFNCeQOd7aunDh{}FFv^?VSh^0mwa!3lZ6&jY%9X~!&@4Cp?*vSJ|KeW3o!T18N+)+p+U#$@6@F_G@-r*u{Qy-})dkcFrFD zC_C|^`}q4Qb!xqbL=5$^X&&(}pTE9rFY^EES)p6>?QyvY-5GCv+>{I5AHF~2cjO`E z95}5(=x+Af*hv=v-NS`9vyOoO-y+=Of9sAFmVWWms^ANN?%&srNSg@gUNe8)nRh;% zBKluQ^bcz@xY6CTm4Am7w?jνVt})$~97fLnKq>nRNLzOQ-ye=~L-B+v7`eO=J| z)8Fk!_j8?c3%Y*EkM5c0S3R6i@0nVU?i0J#+cb|EXOI4~%eWNKUDpcTy>|%xOz4jO zdPNg1bU)}Kq@!Djg?H)bR&vn_*QwHG5}(?o4eesx9@miDf#D!W?ulh#Y23W zj01Fkv%+_eZu=BbhgnyTbr{Qy?t(Ol>%NaeOIowzF1j6P(dia9x`QN5!WP}Dc^T3f z>^vItJl|~T>T`!8>__(}=UNJ1F68%+=1lJTX0v&7YdyN>wCQfsJnk$yv@YURq`T`_ zp}W`Y2Ukt#UKy6&mFz5NSLY+$?O$>##RZ~UyDz7%6unnex_15_Q{I7n zw+nX56eu$hdVO&}RJ-+ScHt}WtHh$$?rtByrZabR>*kQ|MQO#MB`eu+Ug;+f&Dh3m znWU}i_P2CP%|rLk>^w4gp6}XsH+#5!Xg|7FUH{;@@3Z)$TX%XU2lstdSL^NWbGorM z&0|dJ3%cUxu>a5H*VerI#i@<0^w6NlS$j=-$j`G?8!kQc=Z1ktkRF=<{3?2tofx%d z@rSU=UTr??*Q1AvO5gwV%*h0*UuZX?bkyy zH!W%UeQ*9%cKr1or(bV&rq=5rO&HL-)t*JluJn z@4@}(-wwWIKf0HVSnZYP!@tTBYa?2Jzy8Zwk8UEji*54=K4I)c=a3p&p}YT?WLFcq z1)c|5aiP22g?oJwx_|IHuR=DY@-UTv(0!xfx3N187L_iZEJzOmbVD8Ao-=^%qPlZO zNC4ddn|zNQ957Y%+YiB`R=F!UW48}J(Y$qb>e*huvg5va{l4LC6?ca8=SW{N=e@%< z4&Arec{JyFzD>VeoH#{mKe`J)YQ1ET>oNY?t>yKvPW?bq>pdjG!?t<6+kD8SxOGT( zH?Tr?zZEeBCUg(jN`-Ktd+x)SrGV~x2@wk4({4wo&1aYJL>VUraTkqf7r(?&h4LY{v;tXzd zpSk~;;N9XMYn)~B6FU#@zp8$|Kemkwo88C${Qv%TUmW<%{WveW3qAk-dDg?6TCckw zEqi3sJSMHYs$5izqFcdM=uT8E9cx0j%d*s#Tb`vPuNsH$F6=x`^E}_@L899a zyV|e2=bqX=DDx`6W%9J4`_#A1?@nKU{r{R~sdGP1acT=IJv2OS(*TnmdNVtuBbOfP z-s$R51M-lz<{Qx}dqQ^Y)g`dX4*zA{H&ej>@Ak>FuRQ|)-|dTY8L0o?&?8fB42MxJAN(uRNHi|So&R?>_ex2dtdRsIfc59v%pa4?$Hsc{+7jqE%w z@;qO3uU19xme{X{Mm=g2zUc~o4(UqF+U=ivUa9q~Y{$Lh-?U{OZ~g7_AZ`&_Wt&@} zdzkN;-%aSg9daX#3*GZS8~O)A_npi~a}c`a%|H1Z?IB$s`upoQ0Nv;7{utU4a!9@& z?@mWi_IJ+uwnz2^vs&JYTamw;THXQis)AP`su8J`)GeLg?-`ms+w7(4GBJ zP~wY6ib_{5-rZsVp!@B8eP^Hy>1_4Kv&R6smyzsJ2)-{&808&a{fPH6lK z0VTh&{)F}IPx7(Im?b<2%ZO8%l zdP^EK7*p&0|KkVlr`a+O&6^t6A74P|Zfb?@A!|p@Frhna@`84p=>F&a6ol?6Lq^U( z=w5gErH_#R?>aK;`q+<)O8X8fDb@qJFE5ywiK<&f56=8P9?+e9>Oi|RgIJ_|{;N6d zg1L2fo!R~y&bRd}nZ}OuU*-1YcgwiZ9i{$o?!kBdtZ^PvJ$4?$c%IMO`0eY(`SzoG z)*CAmXWFteQM`0bnD$)lum2Ygw{0FT{;(mhuQzv^&i=m3*8&{e7A_s zySe<2&i@yA9N&h}y=?#HX{$hY?`*YW^#icG|K2iT=;wg$vHgl}quQ-T^TMUS{V5i8 zU$sB7$sBHUzkO=Wg~Ks_?(4>m+jnW)H^=|rMz^H@jn*?gZ`3$+zsJsF3D5IQO}IGg z_i+2s?fys3TR}cH>`dG}%Rf9Rqt;s{bEd`GG>KwNoS`>Ct{`twSB?H)T^_xw-)~X+O zl)c@ZuT}}eTh%xlaxpuP4m{5{wrN15tC#&zcDFS@zaJTMl;5*D7Suhd?RW3iR216$ zTmemOn#aPwnp~($ci9QGLiea&rxlrONJafiUAfR5ar9CeLiZmJAI(GP&fD?8clIv@s%T94>D=T!5{NOVW6S~*SHh1Ad_n5Rj zN`&qSgETa{M>Rcs@GzkJJkM=yz7qa*I zl}6t7qx+LNKP+j##|9g+%l1a!bsb#m(M_B`VADKSj7c_bd<*&iAy()fvG~Fo6S}|F z7k1`C_r7M&7a(*ePW${Bq`QYTB-R@N-OHb?7c~=Vx1u{vx_BHsq*2TN3Ah62e!fB1 z!-D|bKA{uuH)=3d6t|@9w0=9d(Ot*C?XAEL?Mk|{;|@KXld!iHH@f?_xUss!`;BTG zy6ds?7{v2@^=I_^?!gHA(e3xuS7Rm&ky1(eVeswR3vbVYN#<5AFsiJ*<-RvRw zn_CZgpMN;^z?$%qci3_3{{H1r1Co1{ojPy!rB4@x*0@zxz|KR=^L%$?`pFl^H{kc< z%Q5hOA=~~qm3Wf(d&7U6@&1eA{912A?*0A+o96Lmi|)M^99jjdY^yRKo^M}}Amr90`&Ze~O&7F%w>7{2A4aWy{Z^r>)}x!avd5-*95_^*_yg_#x3fa` zxKrJhn9%+5oIO!o=svt>bvi=#sE2NJ?Dm@#N&D+U>~>Sr(Tyh_Eh-&#>rt=y+Y3vR z6;nP&)h(`n?C6WCTW0L~zH_JJQ$&aME500{<3_hf_?sto{~caZ%8qL(d2XSrfE(Sz zG6PD6-mQ7)c4Oy}#PfWsFT8PW>3sWhNWnRi+cdpugAG~qT-MG9np%(UIg+I|&13D3 zZJQF;BM+&q6}rd1c>cBt-KSri9?6C7UAI<@L+I}G*Cra>zaQLktuvszp5~jqo{*WC z-nj8{-Oj?&+5T(SpvuHPJ?fuEm5JvJRPNaWQ$*LK=Qb`^aHHF0^yrJ%j)a$7VaFY- zKQJeP;70erM!)u&{a(#OH^I(h5YO{%CNB5*{FwddKAmSIPk8d9dy(h8pSQc5s`co; zI+nO&%RC13{-E2Za}c`QSfP8&sJ#tM=$7s36TyXU-E+SrBXp;=|Aj{Pui+ij;{n~f zo7VsI^ogRCaTHXy;QW6%N3F*GS)AI%N)JtKoG}IIp?|J)NY6Z)MsVq& z24k}Fksk7Rxhd@-QQ37b4FEl)Ty<5k7+#GyEZ0wdDGl3CCk`xw@aG5F?1}q9$KdV$Mu3bq{jLGud?%a zndkX}_Z+$)njOsR$CrnZJZNUVFqVInB~}@m{Z)T_tzTt{&x2doGLIt7yZs;171Eup z&^_hy=Fd#4YzOs;crJ8*J!y0yLicOO@6pk%sD-`yqYmlE{C2s#4Lzj4SQgzbZ$n|} zjO$Bf$p8N|{@EPVLrSy$bImzIEZQdDo&LWK+~|%?oVWBsaRf z_qW|QV{^?zcN9AhFP`Uf6~xbd>!AJUCfeVd{lY{3RrYp!(c3#F9IEx`UNtc99b4wH z^>&HRhbxc`*~tpslXo`oHlcf?Y-Jo5y4RmBrVzS2JUULJ`<(Gi*H(b;ADf=|*>itU z>4>#obcxznSo-Uh;j>WecK6AV7g6l?SHC%z=iHhia&I{;vF=iCbPrsxYma<#*OCV< zm~o0*E9S(J?5^@ zuKgYo(c&xH=CQ5cVdnh5j#lWNRIsP93Ef|fNsr}1_p0vx^ANiI6tB|ge);Z7qX(c{ zHMht4rO=u9f7b)<*4b28TDNh}g{c02M{oBeR3W{-{mrw7CQTKsefYwluyF4E|2g}T z{|F2gmMmw-MeM$I>6NA2nThO+Fa4T2uI5!HD%g3bd7f{#V%!H?KDS?YFKv_(v#%w8 z?3RdKHSe{%6W%Xx+0?qf=WVxX9!Y+w4^m%4y1RoFx>Ni595)>`_qPd0Qvuxv^6v|Onk*5; zDZ>7|@IYD0McqA7%a^^=F}x jAZL>$$lRGdS(iQNlJsjeKgJ|Nk~SkC8mj_x`yY zZ`YSva?X#7PVth}6DGX*8SnSr_-*7$smMl9h7M-s?IkZ^^xeHO~Lv#LnXvp6AOyGs>@Zu>Ce<+p*qtN+0p}kaFAf>T?aH z#kF1!DZ&aC+A@z+Idmwe_y0#&p#eKv3to@n0%Z``#Epen@(;A0vDLW5$p64rC;vN(_(taC~C^2@t z{5Ag$>3|8UJ~ulrul492^+wOWw#;Mx%BG*LUWshTa4U36*F`op>F(G%f4Fg>Tl7=^ z?FikCmN%hmNOyK^6u$w`-RQNuz7fzNePWNrFFXh6Zsu8MBFd1?-Kg|NC#1Ezw@2{% z@+qP^-hGcW9?FgG_ms!FCcoXWM8J;QEZDf}h0EON_USIY-TOrI8i(#(rg`u@-}M^> z7hA2dAKlj{b{>0G!ynxu8fy**w0yJHqnkMO>=B#h5jSpQD|&~t&*@aQ`axzQcpJml!D4?C9xv*R9|I68i(f!i{fBHQuY2;Z6)-HK-C zF`4K2Vqaa9KTu^qx|25jFYSK|_&XC3Tc*6bY-`Wj@BgqpPm9c;hdeNC)8-E|8;x z_QI(8C31FLALVDh30JsnNX@S2y9aOctZ_EvDs~@$Vs>lRT|y!Y3}ZewCebey&aP$m$k!`4(Lv9c_hf`Jz;V3Ej_!T=nKc z_fOM`e?jObUYtv#d%^4`y@mq1w+E?R=70@ZH)B`FkHACHpL#^skj5zyP(_p3>D zzZmW>7PSald3)ho-00qSNxNss7mZ6AvEvfwZT|T|FK%?dRr27okc)mb4&86D^Vr1m ze663En%Ute`_Ucdvv|RvUi`INJ-Yq*`SJ78T958so10#+WgZuHd9OUW1bIl^tk9jQ zK1`X=?XE5L;zDNUH_BoEl_uh z@vp~>Lg<$I%~uVhE1sT=qBziv~3=5-niM4woIa| z(4Eoi*SjWkYs2RXxX>+$Tz?Otd+DJOG`c(Y{HM?NfbK8O`o8lqod0+3<}3G)uPrQ1 zSkh6A&@K6D(+#x$f5D}R_h0duD!Mr$e%%|Zxbtq`?>YKYY`xHutL(S~_fmT9smop6 zvc6N?LBEbQZ~y-{>^#=+JfCXI)=jVXw;$b!kvGHq|F)sJR=?(e@= z>us6G!jD>J_<-)l_5Zbn!^NpRt@MzFIB>?Khu-{WSUoO1H29OYden#XrBw^3Bme)| z1&tLSfd8-mLNmQ7)R6ufI(}^u)R5-v3XMTsb~Z=-^f&4u^?8?ukB$hYil$B6J-6cu zZaow?HfeUxIrsLF?6?bE8{Tgez^#XV_xK@d+{0@%t`BJgb{=PVp6~k;Q~Px3ZoeK{ zIBre+mr48{(qEVI-NJvnQtSQyJumBRnn!Mv(2;ETC(Go#`V6m=^nR-^!8mt->wNY@06YT>^#=- zJl{KYIt@-}+T90mGlE}7s>@N;n23>ZFQ{%1Bt$y*x zUM6(kns6zQ3*CjgdbB|3?zlU2HbS?{=^^hO1$3{QwQurLK)3F0zn{hfx>N4V`WQvG ze9r%$y*m%5s%swyeoBTUWoSYfGewcgY|B_kQc{^^D$0-{m6=GWOi2+DQbb6Jvx_LA zl%WifxsnWpkov9d+2_5^Kf8T=ulM_V&iP)w|2?(d+;`Wfd#!t|z1NoTMLMLde4)FD z?=7Iut~&Ap$FX&bMgJB*8nK)>fR20L(Q>n`4_kMxa@Y-euZ2|C|MQ`F+{B5Gsp+R~ z!RPt+|6hs@%zkObKSL4}6m_V%Xh-uM(x)f}it<<*#}T~K7rEV1o=o@g1A{>%-IDs5 ztXR6APUn3=IwYULin$Ic_>L-DBhY=eb5V~H&>fR1Qu_$(-5zJ%LXYU)IHT8$?A;n( zy3=GiU;%9z+`KWy6I*wGiO<5Y2W&(sbe!zXOM0h=uywbXOJ5qOq@z0BZD<~^aN=9z zReYLVYyP^wXFqD&?uTEy{b#d}a)gZ+)5>}oGtOV@94W~o-~V;Nt2kt3B1fkCn8@%Y zlJ1F(XO?2=_IQ;$r#pf9>AZB;R@mORXfTJKG4jRA`C;$fM(yz~D@$W1R-ofT#`D_i zmSOAeowX}9sa-^Mx`WU>T5;mrIyyK1jzm)eM3hZdikNK<;SRE669dR@^x*m2^^-?vGWE@1w3sO^Vv zpgaryENgByGGTojfgVrS7t?G=cuyh~0 zZ`p_FPI9qwM|2ltYG&O9x-In-#%_TV((N_^ANUJ>V6CSH5Bq@bGX?5B>Ol8$hdl{47hj7Ic!LJjOPZ{__nfh)lPKkEZ}h_XOSR6{ zIk9xVG#Do$x{DO=dm_4rq<$zC0^JJg@JC;8GEp_ScFh9t{=Z0AepnCCU6u9rt~Suk zCczYZL)Q|zrpoX`d~1NO={~Wp zEdL9t z)4l59KY3K(#Anm<;Wk_Q{A>3)%`+L-i}26g{Iy$a&vkp!{>sFvlcGF`c0zXsz?+GG z&;S3o>-T@_&kr%tBCA6_eZI`3S@wn8)^%8QsPnaC0aAzDeIL)wvMu=;FOGvcRCJSW zu^H(9GspQ7=n8z`rmvUtkPgZ7_BT!qP=}U>_A+aPSU_CfooYMzvFp&0yJGjOV|i6p zqT_@u9*s+-V0TDbtFryhC9_f88qyWbV<%30&lR~(?L9XCI&|@rI^*PX{5nLK%=KCM z;{U)G(#^m5Qj*7Bo#~B=_mMTECYkOt#ryvAgmmNiX&x-yd+WA5M|A7{PMYhG3UB&n zoCLautIm(V2k-xj40q<$6#2la+AR*q?v@hE$9iOUt5w~O+u6VZYA^UP_IMO~mwnr< z;LAgT{3HGE^D&2!q*+u z=x}Sv<^weUlwEXV`fW<`(3t2K*gN-ybPY1yr+sQ0Nwr&lRSh?mZj+x&I}zPK?f%)_ z8vmRo9s+a+YcJla19U&IpT18I_HK(8dEJCqL+d;JI=2nh>m-INl_Hi#nvtVJY78tkp5qdOt<%{8XJ=CSUtNnSh@wy@23v}y1i|V zxFNe+W+xsqA4Zj_|?*l(DRyl$^WjC29 z7JxiMdauATYKGksiqv6wy!0M+9s2gX@vCPIm&!SGoVM|$%=|xmW%qY%$U%-i>O23R zLGxG`_viRp_dy~JZ1b-}rIvOhTgvgDAtiJuiZyho9!>yYUV zOfIS>=|0jtEP$o^dPv0F`TqmAy16xE=`I_>N}zk~^gzl(@C@nE>S4NCaQ-iALhL}E z|1VctE`@w$hsjlLpBJ4a56OQ=Y$WgID|M+R`alLw;{&JZYsz^STLPjTGf^ea#s2 z!@1hMgG{&oj!P9J-G?ed`LJ}aX6d+&=nk>3@j^PJth@J`?11hqva9`HfRhOo4d&}t z@_b+kr**%Pr(49ouF*rDZb=-je@hSEOx*Eeh4<2H*t%IH)w=gjuTjxJ$7M}T4+;O_ z&BRlSMcBK4vQS;^=0x-G!-?;x++L=lYxCFrZp)cIn{@mqqyvYuHXiw+OY@>TA{`RjJM9pqra zOTm+gMDfzHDNCByO<*=CqbQG#ZJ)*de*f=(yJ`O~{`ny$24r>UTn(cTsSYtS@`z*A zq3Ea8?#L{A!%<`I{eSN7i+QxbEZcu-?QW?&aE27#BXJtMWj8ds^9r(te5?QX8}b~| z$9GCC+NaH-zIPU;DO<4XkZ+LV``5$VDj(2sS!0cl5?)~6|M&Z1sP8@r>Z?N`Xdd*J z{v4l~bEL397stHs|NAJ@a&WeXg8Tn&xUH4C!1v(42F`1;hP3E&GmhQIkMR|yB?bx=tr&}rxRt#SOx|6n4bEOu6cSzk=F58;z19yBp zQG)dUUw&;2N8bN;jAh#+$7}(;tC2o(t`J+d>hBesKDF?vG@|2dn_isRp@KcjvVD8& zn^nh7b+fEGng=INd{TKC`xGC{U$-dNhMa?P_~-wGc<;xLb{EqAEPJw#qCE6m)2sL0 zLe`M_WV%Cbgat{uSqqCruyk+p+&qftR(DxDx4RXe<@cEp>~2MuipeboZ?~9!Ene~+ zbV!gAXF2k9i}e+SQpgw5<6=Gx76ILbr^BxC)MfRhUT#YC%%FMmm_Ac&VLO_$NuxccrbqdzeUP`d8$!~=KFtUt5}Ni&>NNI zH*iOGw|0@~KD))km884HEmRmw_h{LK9C9)NRTG?%{{Macsfc8t+visH?>z8@G^Xvz z(Tl*-Egfswa*+G~HLi#B8UWqw+>0YU4x*kjS;nO#G5#7^oJY5joZ&{d&P66HS+}fWb%Y$Kw zg7Z6H75l(4Crap$+O6%$R)*AWUPZCvFSc4jQn}F9^bu^`-tSwDD<#&cNTB1cw}(F| zIf#8S0X66swlyuMy4oFp=CK_ozJ?>O-&}by|Ju!7^eCCt9sj#q4u?IL!y$DvulsCf z7DaiS3#$%gjsAQ8|G(25{ZD>sh=~zd9lG$u_#UYa1wUq!!m2~lQ;}`5_u14w@r>9Qim#BkHxNYGK0j-x#Wmy zM_{ao*Hm!xdcJt4EQpSC)EwO7GvPLvZ0a*Yf+^UC9ppbH>CHG>5hu>_aNyGc-p=ZOSh0n z_)0{#=-G-n-L>qaub%_m)(cXC`P_ry;K>!tl`TH-#=fBnWOwV8+{^&d|3@w4+ATb8 z22DQs*=A`Zv)|SjZ=5?J-AkrB(oFX(Nq4lv zZAmQM@A~aI5Z(4sLvy-~PJ3$90NtylMPpq8gJJcXH8aM~ePH3m*{_fj(ycxvzR2CJ zwyUhe0$-Xz_QxzG&L?8)K36HZ;pi$l6>D^y;9_&}o!hZ>NAP>Z1n(NBI^8j79#?VV z`~B!boqNRmJESKpF|T5}@O2yP*{h*)U|3s<+3PiUGm)pc>=W{4;sJr# z4lSTNz)LW1L6I4>;qEtg{~&DLVQUBOMqXl75kbf8$@B5Zm%!HTTY9;Nk#zypbx5&j z9w9jK)v`QUF!px-wL4+=qrUV|{M{|WnUk)vskt<-o1lD&qC6bbc4NF6%$Wq*wxm}QfP%K7_# z1i{R{@#W`F`ofZ|R?m=K_D!~%tFhP%9htd*c%!5_fi4N$v z+m|*mZ%oCmLt}TvZd@>-zI#Zoqj`MBi7)Af%-NQ~`OmV)LbfJd+KT^{-R9fD{zYd> zXnr5^>qDPlO7bY#Yy8q899csiB-0%m6{kzmt-P^m3zqJyF+b=DumrFeVQt>M8|O`N3E<;!miyXTg9vWh^=xk+1kFt%=WJFU#aE4#{$q2mndn7cdv(EpzrA;g5UHBg;yJ~R&qC%$0ib;l!X=C7M8 z^qmh~F9jzPKTgg%x^AX<-GoznDa+%;hm9NNo=n_Nru*U-rHv%rr{1VYW9cTomE)P) z-D>ul+q>Of-Cte>bU$x;ZY*F1-n%6h$ybbn=We$Pzd@c%%$wvwXM{#;|VdbAge=H zZwxgfb%@X-W+#zlO2Dc^uNj$M_=8zC^=?))vW6Udx9Ob%s6!cA&vSLsg5cx=&gkTR zU--&4iPZ?^(@1-9eaO*X zt!PT}SU(i^4)-~J4Rd~b>GF6RHxe?&EpbIe47Z%H4ih+Uw0#2)2Ux=_#G0#Sv~c9V*<_V zCiKN0p(Ky*EhnNI3y}`Vj7;|xb#XvoHUiOoVaaj^C7^q! zoc5=sbwTj{HSB&o`Mz-5_SpnPx4HgctvS%my#Eg0>Nazzm$ND1djz)bAG!Bd=QHyY zyU=mI(7lFbT-drB47XilT*N_jx+l>*>T%+0VhOD>**AaP*^6|9WXABxgOSIJxGW#U0tMtiaQ|Ag3)%0h=FRHr)#&Eq0Y ze5xIvEhpB_U-v8N(EU~Y_|I+;R8HGoWznGdlLu zh=~nZ9ZJo7d>g4lNdKR|_z(kD9kLkrk30kFkb|n#D`b}Ky`*|O%~?iOIPqd>v0)Ib zqkF`TYrh}7rQPa&J(y)}cm<5Tz%1Jnc>UlNV{<5>#^-hVYV0~xCLdDE-|9k)L&sGK zsB5|8W7naUlcI5V>a3}*4iV8jT5;kldKLbnkh-<6({cLut(6&D5}XmCI^EaMJn-VX=MdoFdvE@_ckf}}e6*Z`+by(jSk~Xx zqx}<7?IeowSRTdKBangAZYwg~$t-!>NV=biRxQNR&AXKE1)|$$>{$w;drI{48amMb z8;x337P|+*dxc&f{UqcEJF2by-2!y4_c`Td2Xx2xD~w&pHHUT{eIrb;!`3ZQ8NayY z$tI#UI_`ItrpdqrcI{5>C~qt)=BGN{>(M;$;(NsHwlIHY{<_UAu!HHFtL_vhE(Jj#_}F+x{%)Rpews?}}_3qPr<_ zjVp5Q<{$VZ^ksAq+%Ns(O4*Dr?0bs-LmSY&Nl8P=8t6V4B2&|S#sad7+TVY69rpYG zk}OE3|mQHB%W5eK7-0vG20{QuG$-mH|2O_WAtp!2>QH9fW+l=r3zhF+ z!Ky>hx!a~5pbiD^h~6d*>JYSdiT7u)hOFXRqxMZC2>xW+uk$$G5AI~VBJKj}P;a;R z51uU_pp;!7=?fVwArbqJacN($bSO(cygIX`=LiVgc765rs?@5-i0R9A;o z(LDTc;GTw{PTZ;zM^S}TNUlsA-gh) z@_2L5aCUhob|>jR`+e;aEZyHf?_%--y4wm9*CDzs_e&5Pfo{hK+np~- z2f>fuHl;9!`N6tr=M6)E?urKjxj(=xo6>Hf|FG8r>dW{2s_cWU8_NvF z*#ze;8pWPvhuwpp=%~k2o$kkI9(eIFw(*}HapQnEu4LV2^u_Pz54}ja8>VapN1vdp z)p5bUWvBM7ARj?Tk>=Ns52UIn%0t#DhSBak@^p(mneLlf)6OK_3^^YcW9jx4(g`~W zbjL=lSd8e_4M-yv1KkR5>;*n51;O_+S`zX+{a_x#(WXS8+s|lSX#>#xbnE(}15Yg= z^=N_eDGO}fvLYW(T|Rk@sEUr8^^09p*^I5b#dK#~LR1Iqn@U%J*3w*2`PLN&?JpJYP_7hU8ajqquP!&FdyKlu(q%cR_;)jTcDmwj zHW5B|{*QD>jx~3guyk{re7yV=(CsF*>KoD_`O9&cUjVvC&aRm{p%VmKvMc0ISoy(b zp(<=eKzDia(%cN7n?YK8D7wZ1a?>p`GqT0jopYgh)2%Df#N+5V){*L(*fwn4Z?vB2 zJbN5Wb-HuWJn-Vn3r`Wbeu@K%=(Fdi z`IU)l5i3P`u!@c8tPezLw=J3O8?D;Xq}u)HMIyq!<9k_|w;kCb%~dwnCj?7yb$|ZRbMb}9KA675 zw_5rp1^xd_t3uM69W<|-u;>#-dDPoxe6I&L6aDS~|BYV$fATX!OpcS)p`5UNVWc|5 zxfNo^szXa(4XZeUI;0@F=sB{6>_{(sy$kF^-eBWZ{{A}<{-OA?)41Lb-ll)GbtR}n zgWTM5_d)-!=yG*g{A&y7<&3NU!(-U9Y{u1Pam7QAiKKB~p7+LF?!lgATW&ndH|)Ac zb#;i82VQ(G8GgbtitNy=u;swYm9KH@P#rh@2{$=AI7Guf+kzQ?zkqNsBYDZ;H#A>| z{AC9y%0qUS)3c1Z8`6%E>ArI)_7_RFR|zW{mTnQ@D<_Wu-Q!%dnTT#KNnS@~pnJ!g zlo%pI5FGZ<^$FpbA8g4Z>$wH!_9{MdB?#zNlF6-na@PV{{cFmFcQ>}~9d8;n_*Ke? zq;V$p&LxYVW9y!6`~g4J&!alsI%pnv@m<;z*}Wm09jZ!G65b(MkE?sZjp)b&mkeON zT7JRH5dJJ1ywrX$xK@VdJ0#BKxfJCwd*ji|E0IWtIH=Q1qaTWlDT zoPq8!Zjp0{?v1K>Mj}A>+MvwujjTbiQtuS8`jH=e@#~8(5YTP3p`pV!4|a#%raImBXdaF@@i}+u7{l%C zP|JE=t7*1ZxVj}ajT~=|Gk~q#9&J-xg8%$KA?2#~mMfApubW`NPgx#}_wWAmbc-XI z?px#e7fHHZJhNG`bTc}|&8A-e0AmWVR}-5*zESNpCGf+Lo9Ewst?gI|tR zZq^67>$b@#7z5oq%0BMs+G`2*r7FaCOE|$;YpIG;PIc3ng~WbzTzuy@&9o@&lZndB z7e9G3XHuPRQXWrn;@eoPG@X{q4ka*XYyHf4fvbDZR_`T;w;Y7~u4*j5xd?ynmO#{C z3$|9L`IQO5-h-k%l(xM6xpVI6mZN04vtD!*k#svd_%6lLeUvxl!3m(d&u^_hqPt6a zAJ+`n-73>BvCQWUg14V|_u4$o4`yN5{QeNoUHJC8*LI+Lxb8yhgoGt@qHRx7Q$Kd? z{wdM@+mV<@bVtWk6w|d;?8er;s627vQqB#k(>;skffwJV>~_Yt;AA4-#-?t}3;!Ig zH=TZlADp}8JTMH*X2Ac~a7U)f=*oVW=5?n>Z`)5v9*IPSQU<@j_y1$f9@O{iAtoot z>QF&Y?juqi(%&Sz8mkWZ)=G<6f;u#^`=tG5P=`VUo28K((sI6DO@}@N!Y{7~E##W; zgNwd*zsrsvgz~u*6`i+!fCQ~htP#3x0X=12^eR^myAC~bHN1b}Rvobd9XIe$E9Yw! z_8PMAK)i(JxyMvjhpNy#@Zy{P6&5+E&kiX>^&Ci+ZNi;pCCmka=}Ii&zFK4~Cr^F;<{6P@)=P@=xNL4HJNK5I8=3BVyYE?$bZ=TizY0tDvd%~&YoPlH ztK1Gm_w$TL`Bp&pF3lw&O#OlIz_E~TCfu|FOZRqSv%3w@{Zp_|4AH%e;TiK`p!;e^c~9q;K-k0QeXH(AKiEkeJSz=! zr{#u4N&?*~QZ2z(z%!&WSBp8t2Qse0OjPw(i46&vUqRLrh%Abl)BN?n2V7U6Rg;rMt%Q!b>}#`#`{FMntz~JMT9{_sL?pM3(VD zIHOI&!?@EAUc+s(s~_l=KH0x@G0^?iw6V=_vn4bdbp5mF7`ARNz1K2Fo>daZ&~cpl zuQRd^VRuNma=u)iJ0DP;Zc-k2@!k7TFzP1>_HG~Vw>)_B4X$oO34W0)Etc?R?%wG$ zBNRN{GU6pG+ighm9TMTiFhzMp+_KCl$VO_nGnww(Ql$ct?w9LNaA4_vZU14}5um$t z?8E@l|I=^!u6YRPww_L-6PON!&uVbKF?#0*OGbFBOaa|{f|*}^1pR;KDz`hvEI@Z* zbH$S!Y~8o@TY8drRS?I}aqTxpCxq8x>y9Z2kD&`KqB`BAJn-W4eVA5I4Bl=Di9L0+ z@E-oTo7GQP=}J$7RV}Z`vAq31`hRyn?o*39d^FZ#eNP+qN;h{Bc~>!GdeD; zdiUVsZtUlf?3b^ZxY+fK>go_F4+ot1z86Fd#oS_prUfoFYps2UJImU&HE?e%Is`Ms zyqXfEWDU7GT-;FP|G*d0er=~LkJldyH_fdfy~uPw&}P_0((S50%Y&u6wIPzh80cPO zZ}%BlLpEF%k<0_S>rM4)%i9Ct0-u~;9z%Yx#Dn5UU1SaUA^a;F(5*(iSaea`0;;PR z?rUtt*8NT7t|xWr6m0*5trhZHDqD9X{eit2QKNAn26iSOgH`VAM3ut8N- zv5ajJZ*g@S_R(42wzh+nGuL{_e4=0t88L2KJMi-1zgR~9J3qQAm7+XKoK#&OW+7`x zPcq%btif(1-69rM+*rD&9^6qo2y_SDcC0~kuS)FpyasfuWtI|`wgtlXrB>5_9P@)y z?B$YA0Nqtf-WS$^4oUjVazX3G7LZtsq-Sj@w(cbdPYfT;dP5XN$8nweqEoMht$X=$ ztsm*NPpM8fDGxTB_@3@JXY<|44h3mxZ~2_ojH|nJfs&Z~)E+q9z&B&74E`E2eDu~x zQiOKNe}~w=_otLrAEqb|6=LSBOAzvevCZw)}mF30YLZ3?>ucqKzCuEeBrk-b4cf`49DRt zY~63Rx@a5ieofqoj+?o+bFI`CY~8HWb=zh2DyU93DG$8(T;5&3(&femy<7NGphz8G zH~SI6i-wC0VOx*E7M>aWXSWD8&Cidk>(ab#f_xA~d0cvGDx8*#)NXe&-Gw>VdP%xt zp4hCx(yfv8m0%8ZOJ4Lni|D=)mlkXebn`4-O1}%#?xasSj$Si<@BxiWX3;=*=M$yX zSAgy_9-SQO?H16pFGlAVcw_hf#O>i#9Ln`X(zp;;=cM7U*t*A}hpmda%BfCw8JY)P ze5G%9G>C(niKT7p3{Tv{KX=no2&|qdwS=EMWB+8c0blp?`oel!CqbIuyA8VRNKqck zPU`ba2mXEj|KFQs=lhdGOnk`d5bQkipEsnX3WS8P>d>slD$5<94o$j-lp_8A_#y?5 zVNi$IM@z@Aw+6zjUl^D@!7M93_O>!RZV(b*cTP)C_5;LOlei<6$r2g}+kd<%8@mpz z&^h{{Vb6PFFFNj{N3`-vUhI8Hqj1IEI-`23t3xZ%Joe+n7rT?~w{Si?bkO#BdxU!{ z?i%vmeNMNDH5PEq$}fB;DY#|l=!eIKM&s2q-yv;*iz&+EGhyY%nqXv>Jwv9OsP^hG zX_obsm=VCz{ozpjPaU9pZ}j5Jh;A)ugRKKVcTWA&w1uGmS3O>LAnBVQ4EZx}f`RVP zH}6vkK=)A4f~U4)7SP*OLn6~r*t$KYzb(3z+eU0c$Js9#Tbn?St$T%5ZR*;VmsF?Q z6U}24PJ9AtJ0_>UvqScg3~ha!_`17Ob)-cFE#T8O3%*-F#h+yfT>bPrLSNIoZo5EEK=(G&2^U1S?NCEZ8_<2`-JOBV z_kl2jh>_X7FMe?1>Py)TK=;wgja~1-?$!yTw5`Lf7SQ?y*85Zcu!cO%bFN%eyphI?G|Uchn^IQ)={1AGiV;ZIPob927WLFC#1dYQ?FY+T5xN(nnc{=)(R)s zKKNJdP71!=vU-{$*DX(n<~t;%ayp9g5GZ+SB0u+r^eHmkkKU;mk#z5Cj^xAAU3pD& zhXK%iKyI-vqT7P2zOn}B))-Yzj_wSE1GV-`MD+T>t{tO7Q$Y7g6>)`Rp!=|7K)?cU zcZ<*ai*LLGuxmHF-22@P74L|oac53n-52r$yFFS}_PyW65a@nFxF`2|w{pGjCMz^uV&yXfqK%=z}Ef5-oS_!|f@30O#0g(|Iu-;=7)r;OF& zSXIc${b{2Ds6wIEcYL>iIo7|&^|+j?jH-9JywGG_Agr^j#`p9he>mycw^lVU$8z)d zdpCmqh+VB!Xm2BUKAO44h}{Ewj@>@C=f3O1ZlV}EPDZ^l%<~T`ND1 z;XU<%@Ns@Rl_WZUcvs`7ZS~1G|$^VhO#_r?axK0Wg<(+00J5B@~Pw)67O4@1tM6ydH1f} zp$d3=RwPLwyt$2t<0}Af^K%Ej8aD>Qn{M7)6T8qK&U;&N`Y_;KkP><08sPoOz|P_K z4GSp2KZHl;dYB7UX>O}tklQ52hHOsPJF87;cS`5 z*rBD#uHt7|@OfY83IC>g$Q};b?ZRJA!M9sZUf~$ByRJ|3{eM^qCq;R5De>g6%-!AM zN2dG9n@#UXx)WW`3uEc#{4w}b4d@sXBFt`3}eJO%oHw+5F4=XZhd!ESyRa8>%bb#b_RSIPqx)_*I-MWQP(Rp&!~MZMbWbLH)f1IU{>m>77oj2R8+8w_NXQ zRJD9f`~AOr7iD>jS%&k@J(=iBru%V%vm8lx3culcEZvDWraImFXdXs5@#((!bf?{!9a0PDPDvZVKbg1+ zEl&}1HG%gPdtDrQO2NHbEe-ay+pTDRX+mIsMNuAtRfglQ?~?len}ntO%xa8>7X>f4 z`TwDt{re;4_cs96kBnqB=*6LhS4cHT@%C~ltQw>zy8D#`s6po6W3;z|8Wg~jx{epD zAGa+qPLO#N2zysOS;7z2k6H_6CE8*Kp_~|RowITuAfCJ1XD_N-g0H3dz?>_wZ`e7z zP4%Krem^l69k*JkoMBT4b`832@~~e?vxVwvP&k?gUVO2P+K;cWvO|ksoeDm=s1tXF z9gupQId1O&%S8%W)Y4OM!_F_>gz3zMG{1f%Y~!aa4{qykDXDYq5d#_T8WH~8B;G5! zJ2ztSZannx_9npl=IcxA5Zm6_{XG-CG>0O>;&C3_7poX_Kb!8b06_1I_|)}jkAW1*u1;s_V@VOzoRRj z@hQjF1P^qvLvq2E?7sdTxV-6KLv2 z@u4Zz;d7f?^klrBPl}F^cwf@JC5gpb)YbRYX25$!)@TChj}}B^{zUd}XIafTiz@>&^++sgR2Wgq zPyZ9n<#pKAy3;&wf@uLod6*kK6K0=#wJP zQ|b`jj**;+x`4O!mdxebtHH%YALN$x(fh+|I-Pwb0Ppkld&;LlgEW3qm0m;I5)vM# zH=Ov6&6}9BM!)KCFHsO3w`rYlu8%D?Z-Z8L)###Ts^k3x%>yq!{*M=uoPM)Im&TR{ zLyzC%R_{Vi&u`il`{2lMF9(5R_=}UT!sXMR%a71}gS1(LvOHeyG8<-|d$=Wlj*NFz zv@jEix7g#I8?bm!GnFrs1H5Gx9>_p=50vdQRtLPh+&b0>^e|`q9<6_Yy&mu zzC!0IQ?LiQ#v_P0mK6xIw}+>Qg6BuetmC7lL4$NjaLwH;`45o5?X3>aJj|iC2UE`F z3fRve<;b|N&y@X4Y(>WvyiH%3_#XS+e;;j&RLxEAsjdc*^1zGFz$Yk##fc5tvP$-a z^SckYQ>;;0z?gWvEzA*jN_n*_{xeAX7@O-H^1ji04cf-tL{T1xKPJ<4rp)#KOUQWF zZxl!+@h%T<*@DH}IxwAuAMn;aw08vQ|3%-9k9Y&#Pns<|)NTjD*;-ty#Yg;Lw*_MY zx`6kq1$`rD0B`pC2Yjz|%%LnZPF08#n|FqSo>+m+Ct@aP+@maiwGwRJL83Fpbeio{ z$2$wn11~-`+l?F6<+4E;90E(q@8R=ysM~t$^i^BIis$e$cl;3-D(69Cs|d-yE7S7!N*}g3UYqfzbJgq>n_> zI96Z%jxbs5hg+W5`m4OQZ=*Wi8E77O@r~GO*To%UgS1SXw{F>s&-+o8SlEXw@oD8J{Bi8WATpcXnG+G zc6O;x2g1Q|0j*}!ez5H3n?;uZ?{BIErA2_ZQMy_F*$#84 zqv~*%*cEKvW=-3>#v2ES@6mCt-u3Uzq_BA}|FJcEBCM6_cw3=)u;IiPJi+`py^syM z6F18EgbSbdgz07;zCahaBlo6jfg=91TM0AzUzb1qK=Zt-S$0#DM~>jgrHO#2Ti6*^ zR~7@_st4?9%E9jKN*;HuoN5awvt?t(6G!a+AFl5;Njo_}B#je#Qfz(y3pVeDMC$~Nw_-k(h*XQ<{CI1Kd z|27Kq2w5Du87xlz`TpPE^Z$RTv#0FGg8rY4tOmW+Ed~EYAS?i1*cG_%K)|X&J}gEO z%RmictOyuI`v2T(169ZkyQVE&HZ0cyVawQhk#N`#7UvR_IT14m$(=jm_f-K*9X-X> zEWa%v&85@lM-s7X(6hpevb)>A64lUge%V(-75}gYDLGz0X|ZVvy9vgAu`)I$7 zj?Doakn$GwydUVoZFmCC+{yo1>k7B(ZsAKT$6rAb_L@hl6Pam#iY2I0mdExRdKXL^ z=BC)?WW1ZXb_$ZF*v^C13Rt}9KSmj`1K#zC3!fsqt(k|1k?pOs*A-(|UJry5`poGT zyzqmQY!5l50^Ttx@rSPi-V*K=iI3h}K*qb2w(|O5^FD5`pc(vgh`0|O*Kn=!VZcJ{ zEq1ZH&1LF$KTsWSQXb+s@jc_Pqjv@$kaD{wbf`TWpZA%>r4K$=IKyFzS9B(I@p&t) zI=$NUf(y;_Ze*q`5ApC)iM+YTqXU+a@os$2ZBF9d%M>S%#k;fI$aw|eZOCVH8R4y( z_VI@y;63?4eAj~;;QeTA?#9F52I=9>YVR7rd-|*5_yNG%tg_rfdpA=bZ&Dt3@wFdOS$boV9ol4k^4)VkeBSD+ z?`wjeIK#&u9u)X>4ZlGmglV0)XX`}sya}ch=3$c>8#i~iMF1-q?}p5>CnVn5p;mHO zyu&Wrg{=m>pU%8KitrAb3gy)RytSEgpRURbghkD~j_v^$6Wbp6Eb|TUKEg;p$_{v6 zmYwFa>$HHhR}S8O?u*U)Ys&fQa)U2KEp%M$mX+d4f2iIMeJdj02X#_i^&Up^cz_e1 z+KG3QtSW%_gPPtGa`?PgbDmC~>2`qc9Zz0yo`S1edE5e)yT7LW2FXd&pQ1eW-#Kx) z`O4hWTT97!zd5CxN#bpjE+dP@TRr5-UT(lU@qDZrIq$sbmRFM*f$)_^Kf!B&_eTS# zLJrXX-%Cs`Xan0@v%mFLRTP;+J*(r^3c6!&Z)tGOvJWu~5=rBBE_!kOGaGjG*3kWa z({4ov)$u0fffwIkkHuuB1RIoWtiK_T4WG9+$FyQhrvu!*SyfuckAmu5YBW=GGmQ2R zCl2hRC=Y3ZH1qSAzvusyHQ@j9DA50}B&$L1)gP%KH3;edm1eCNuxikQEt0Q)oybwm zeGuO+3#Qn@rW_|aum|}wo12{x^#3tT4?GVC_`wT~YIZ)39)$e4B@KC%K0vD$us%NX zzyb<^a|5&wVNbE+yF$&GuZOB4rRfN$B(Y*!R`OWwy*cGO?HBNuV$5dexaZSP5BOOt6`)06{Np1WqFu|vLpvT znCt&nknwKkxj6S}3xs!7oDe-0@A1_AA`8J3dxSUV4#HbBkn2PzSV6k^hOlQQ2EvQe zjn3#n&%zAn6f-x{|eU%iJs%lNyfXit*4Asy_1ej(qZuyzQ4$m9`G(tmG(h+ zkAC03;V$4^b<)C%`AQ(%D6Gu9_?jQQi!FVc2{cISJibEdfcMSL`p~d=3#hz(m6Vba zHg6}-r5(~yxXRwc%l-!sjhk-NAu{!iI1ef?Or<={(K_-CMAO?N&%@8{D$ z-|HWs{daFKt(v7Mk0DWqhx^ZvzW?|4{QqC>@c;bdLI2N9R)cyrWpt5hkkA1=7OWbi zHl*}v2=xC=zo1ugpaxkTEL(RO)S&LV_Vm_M;1N4*^;cOoZ+|l2fq-wEv##gITR!+y*JhLeRKE*8@IKl6Blz2mgT7ZD;eV6EB2meg!EN z`i`PJ`kltUREEuMv2&5}?)u$rOX6*1&9elHx70&|+9=??zgpos!u!~=Q^rKV8}9lj zeK$A|-g<2NO@?EB@X|@;U-E#r{I!S-2EhCJ5;arq*XEGpB;RV~Fl^o`iv6|gJ-!ib z(Q(~A7d!?xVe=OIF{A9C+DCP~Rna^);KX;tqVMN2P7X-k{Vrkb(wDov&Qs(*~O7O{f*5D36%J?LMh@=KB9NWV}DTSk+469jV>77>jpC{K2c= z0dJ^g6S#6}Ox5kD(en|cde`h%(Y+W5m#PhV9Ra*M`8S8#0p11j4>pv5-P``6H*d2# z&7qH{?w_xU!{*J#=)5O+c8u7Aj%$oRZuVONoA<|f*@IixQXg+lG><`?_=Zkj?^Lwn zfLMdGZl79+&-+ow=eI}s9O3R9jS-E_<+#=UdyxFHnYd7z=l!%&nW8+he~Fh*oS);p znv8d6M*ZCNf5`5w`mPctEZ*iJ2EQf&?-Alv6@<4=s&3jAa5&+@MoiaE2JippTxY{Gr)kdeY|gSSffyty7< z&=R`p1mBl=mYpez-~Th5j$hU9&P4OonWCLME~39_)5Dz+!f*Rz3LUOt4!etF1E{O zm*O9gs_`iDb~p0Vd<}A1Ls=gC4^Qk)NSIqe@{;i$_;KPbi8uGYWo%fyFV(mNbOPSn zS34ymykn%Ablm~(ujg}X9 z|Cc*;F2my8=y!{+2k?%nk~xa--rJIP(;4t~`4#84$T|>?Zo3{odC3ok&ns_w0eDyX zJ>z)_cn_|XD^xgV2I)M?JUnKB&HKL3ouDVf--#ONINrDRY87JGyxnXKHd+} zJWk@o_bI4y$MQUO$o7^!mlE@mRK4$vm$72;7L-4JzaQ{!1})f80kLWz}1;mI`5oA8*zJodbMB>GSF<{{(VYiVCZ;+>M@vlNSWioyMW&wzK8 z7!LvAt>5K+9$9;{3|t7^=@tl=7wh}PfU~#iZ?H5y=>Jp9oRX{n?~?m0OM-YUAYs?# za)Wi)ySEp2Px>9O{Z8aZ$0X-50U31+ zDS7$g^WN_!*S*@+9^NeK{wei7{@EKL;nVHlW4W}yy|w5IMS0XpF@>D~kGK4N{~xQn zrJ`R4Q|x-O8Z^A#e(nxZWQ+Z7!}ir!HAupfadS1OK|g*fe^3B5$kNqFE)~=uE5{wS zj;4XI=4kJ8dT@gj*Ly>sgh{UbjkPl!5*J7x;6sd4Aqw{UV!bb6}i&h z%}y3j2|wEoc2;cOt}Q!N7B2rmypN7Mk#w%-W+683NQHd12M<0|9q$up9+z<9`+DTF z$U+Ma=-$(rnq3n3yy<(&dwC1(;8pSg+Qy;yH%JScH4@;SIGX4E;4Ni>(o#*BL$c zc#9wz?=O!zQ%JnqvYJ<5@gBbQc(5MurjM(4L3p21c%OG3@Q%<_m-jgo2)8rr&6IoP z2cKHect{8Ewvw=QP6E7>bP2iZG%X;e&#x*M4`Qz%+wLE!jk!5Vq(jH4T^Jc5#$fYS z-^8|St2*`Z?m+X<#)(fqcXD-bD!4%^g7JXOZ~XpWMfav!ae*ED$)<8rqvJVlwI?vQ z9DnsJn&x>ESSZUQ@F(L>_J8jG6CmR~7|gzj#5+hjnG=h*IYUZKBjByLgdmUb4liET za}w}=V#=*(a4-b7!cNdICOgk4gvVLys*it|%la)Q5leM$pI}PA3-8Ja2zx%JN`qJ8cqi>2Lo} zMO{92D4+(3lhvScjwvrv4YDtlT8CAG-Yn5RRs?F0-z@*EBA8<3pQK6kfGM`VL2hlg zT_7wT^M!Ahls|mOhSx^=;vf{sl>5kC^#kO;!tAH3mL=q&SL?07g8ho!s^)#4E)P!= zN#l-1xQp@KzbtNdZ% zOv9caz`G*sOvz`kd+T?L@tO#qB{X>Z%5vUnY~BVZhx^_voF;xk$EkOJ_bar<=3T;8 zXK2{@h3cyJ9yE_qocJna0+!t^<$$U*pd_8Rz2urSuFgnKQ5AWRLa3UM<_Kqlt$OgP;-CC<+!3WY8Ob8ZitHk4l!X@B{$1AlRHzkR1emoy8_FHSh!btuZ?xEvfl zd+~4oPZM)8=>Ip7)u5Th4RhcBL(c!N4+slk)u1Tj&#|eX29>{aeX=)fYmqi;YB z+Ow=*euq;a93`>zq1F+9ctbaX@P-S6(5Dl+PLgULprh&h5`CvFpxI-Z!cUiB*B~AX z__L^RlBX+e_cg(}q(R>XeJf$#?AKQvy>lMfr`$jU}Q+-a+ zq$!rJXhZ;u_q5FNOE&@Uv9%ptN(gTOrd@4-_vQ~O?E{X1@XrFxS4<>{oB@Razax zRL46M&0`EFJ~4)UkAHzDNaJ%vrJk_k^Umd(w%)|x32zjgh|tcW;DEGsWt3(>ChhZn zPgx$lPu^tsHwGcRCCPaI$o&nIc;D)%;K$-UwsF$x7T{fXuQD6q-IIN>rVsEwZlJI& z81Uv9a6Nr@k3URU|3xes@OIqAz1JV`uI=kvoVUUfisO8rlahzc`{=WsS$hqC5-+3U ztPO;vAN=74DZUNq8cQ9ikGCV5hY(JDH>;DM^)_%osZSQYyYmsh|F_NSTCzp>BwT!A zQ5Yv5{_gEHW9}q*_7ybW|3@FBERQRudCr0(bGx?^WV|N>Bfx+Cb2)MIvQ$1S-gkCx z*_{J;JM^z~LwI*rN41Or-YK@nLsYwa1i{5>RpiN-Sn+@hWH2_$9F(iC1f{t^)^l1JM(btE7eu+LNpHxocQ!C?BA%d zaX=+>dU1PR;qyLtUS~%G?@3rR9WKd@$KT!}tW`M?Hk(fK{lEV@%JPUi)1{LQK9CNo z_XaZF6Pn+JNW4EYTk&G?{(tP9c{r6_+yAeZT?tZ8HP;d}L)S&k{P4-*JGG z0{Z{_oFe%WusLBadm%f|%N@RXl9Y3OIriS$>YytgR{nn~&^SBfYGG3oHr{;HwF-$_ z*bi^ihX77~mTC#6rcT0euwQ*_{$YH)LmH}T8i}FE)?*%#4$}D58yb96&|auG^Cu@? zS@U794)?51`nUhbY2n!8$Djsj|5pu?hb98z&>FN-MOqE327O(rlNAqYP~Out10zs_ zRLqpJv_K7d_dTre7uX=Z@vHTd#@WmNF#6m?Z`Y?M_$y{RB`Y*iYCLVg4 zqj=kqx>T|7UMtO4b{ycnFJ=QYi8rA`{E`E}+sEQr;6h&p;!~TGxcLYj@o!uy77g&G zX>C?n4e-tsIjF$<99*&UR7N(;3A;f`qe(PwelcE=$&6de{jz(bAodXZ9DZp3RE+)b zKF##ef|Fm^9_!P?JA`0Wmm1X_UHJV!xxDC$ic$z-d@(yY_9qK7$ZgLC>P@v~{18hI zWzENt_aFUhE=|oKHK*Y{esahJ#e4Rl>nd1y|N2~BnFR2@xO!F1V#n7xUnrc2tMAen>TaH^#ve9 ztHP!4$>HPupjdy-@~_8cJl=-4So5*NowFkJ$Q0fh)9@bKLMuh_ZrdNLjD@#QghuHp zfVb_J7e^-XCb_3E?gPAEv`c^Q2b&Y64nK2~cF_@o_TxNt0PoiCJKi;d%?Wdcw_eRx zH~7;L+o-Y#Y`k4>TN_pgj92tC|BZBop@!95*FU#b-`CM0Nw#x4*Uo}Xc{JpjStw94vX^XIGkkj!OraM6msyn#J z0|qtd#Gg2-dJtG*=S^=Cv1TAv*8cnPRE<);QhZ7 zA3qIm*T=3wNlD!wZX`iS3NudQP0Ll}A6}52lQBr$>^j7D{eLpkhaygXiQeT2b83X( zkQc5wkE`(e|0O#%Y*iHBj5Kv~E8Jpb4f4#ctdb7>8DE3GOR(qz-u)@>@BROJ)9~i3 zTk@Y9q<`kUS%`)Ancz&PJpk{kUuLUJ;+;-Y_wxXF-*B}X9kpd3*X_9S<;v-ZREoSP zCm3S)%~@e24e(ZW_09fs*bRn?m)>?3!p3`(EC>034}@?q6y1KHimww6sO}HzRwB>6h-l!f%l1I)8!>+AN## zcth_-Sn`q6c{q^&@>GMQI}LBr5#?~SdMEl^T!4l5K-aI(7=ZVewJ-Z7m$yXttS@8( zystbLx&G4;Ja6H&)P8Ou9l7qX_`U+b+d6Br>nG6vQzQF4e;;szhv|L$)C95dt}U(# zzNZ5rBh0u5nU@kjKf}hGI`|_bV3_@uw;nKk2;$_IaMR%zhpiACZ|}ZLD-j>>gWn>D z-@JB461pn0J`Lf|ARE2*Z4^J8KI8GW+`pG4AI^z}UBQ3v|JRv@H-}Tt1{CiD`4RK6 z@cuI*5xXDYohACDXcF&jYt)6t0p3<4hZvsV^A-)+C1-&zbrC|F;LM`7j?hUHG^E zUpx(OqB`L*ig$3i^*k)RjV|p=JqYl&d+~kyB;LQ)zwny{`u}>y^B4h72Er9`B}D%e z9cdgSuQdmF$DXfwQULJ&uCHL|;OqvsWZZfk^$)kV+}rr%nn3nM#cO6<@w)uI>kF{) z-gjX{lpM!?cvmrf?8nJ({k`J)+nz%3?2}p!56toLPX4W|w0fa8^3$z&Vyz#3_3rtx za>IL{%o&gO*;lOj@YXF-z6%~F{`dYroZg!qehm75qiHpWpSDaGtwAvt7U^KspcBa3 z0#8tbcHH@qwhYvu)|}yi=YimWboI%FmP!m{-nJX3kBP+~Z>r4WW`X|Sir5*QZ`KC; zxLv=%lj#a~9C21mUyQx~Z)MnjN_Y_g>1M`_1t%p6OJLU^3*w%a8su+m*ZEa3>{?l`j^auNjoxB`m`9dNAImV3Zt9RI8 z*@1n&2qxWd+y!1WvPv!$if6@?GG0E zf9L~WpYFpIGrmEB#Q9nBp>WK+H15V!|8F=AZyv^O5{maepEFumcsJA@a|r-=>&ffN zOyb>qfD?KP@J?_w>DsQrK=#~wxuA5Mj;wYI>I(#TPrM+divzsf&AK;Uhh5=wFXXP? zY{$l%oATI;-UJ~z%sA0}jls(gvGE=yF5UJsll}1KW%?My$FUfKz@I^isA*qY+MGY*@g{F!&43-4Wrm)r~nc$398yqjFTwXQj}vklzXp)0(~(nsNG8#dm_dS~Wr%Z3nJX53!i; z{rZ1XrVlBc{4TU@XWVF}!P;X@6|Tm8xHaWCt#EVZ0e3|5Aj7py9KZi}YdPcbhGbat;TBwc`Ek}%|G#`1-hz9s_@a0tR;To_@Gf>< z|6o19TXg%Mb(46nxPL+BDZqQ#s~nLxGzKE{>3+~&?HGhhsuR8h@MdgX`Q01foubEk zSWUteHl6)$r+hIs-l8KXG@@@25OZeS_T8%`?_9>l+wQmDC;l|{!&`#s124b!W|>2- zt7x!8akEoP4}OC*E4x8_U%Vf38qy_o_T%^e6pD~8WIR?_KyZc75+VR_LgJ>_S{>SNNhN| ziGYkV<64^!oRVFSz4tcs$ab%-A^YLIgy{n>zedBc!b2NqaNOOEqQ?^O@eUL|GhEvq zibMno2^hU)q5m(a{5-07f9Ci9?^yHE)~hq?)XjhUf1J*nJ$?-Oe~W1~NW3YmJ%o zP=g-mzrJq^hS>Q;uBJUcuCVpWQoFNXu!mULo|62UVIs1I8P`+H;r62kdj>hasyz1W z@OQS`|CeX_z{{^ez+tT(l?L}nj@*&m`Wd(XzbY={F>gQxR#~}hW647N2FYGDM%i#& zW5&-QO<>l1q<7t;du30}AXiMoTkK-d)CK92cy|vda$@04-ON{O0Pv=G-g|2d@D_ik z?y(Nw?Y7xO;R=a?=#D@1U1}DC&?Ly+1px0)HT)XR0Pm&BdOds8UE!8zT98r&Hr``< zOc%bYA|kJuarX4(#N}n!c()d1oS;;)AKp;ZUmtk+aqawOv&)7C^JTtB(YM0Ko1SX? z;CYJ*oF`;@iMyAD8RRk<^M)LQ8ILz)%Bqjdx6Bov%1?SRLS9I`rttD8TzCwI$**z&pb9WPvBZd+t#68V1o7 zer)rOl$wH#x6#@6!6_+3mJr-d0BVe{Ylc_!YnZCp}oM(xGu}#^Zghjx`?|?inNVQ>Lo7*)+UG zjdlD{yd5szBVys*{*5ta3h>@>K*Dhn?;jr|%P9cwoYyNQ(l{8%CP|`byLk-a^LeZ; z7vQZX&a2@E@NVLQ>uP?vz#{tRkMtbF##`ZQ%hHa`L`0k!*YWhqi>9O4czeMfiMO2D z4{v3r4^N!@_7^nPse|erar-OK4Vl zeI_yxcln&U&nse(1e*TOvjFc)@8!2_2Y9Dkjx!W~g*`vY7$pZBMtESZ;*+wlZbchv8UB!o0 zgY4&(a?A!b=%f}U+7#5FIm+9=Om2{_arCeh?}%<`Q#YmS6K@Ix6xA27v zs6hq3qA|~O-C$vzfiwE2v1?G>;K0!;JrW|yjO(K19*Il9u0g>^Y7EOAhS{$FuV?xQ z!O1Ua_?vK-EDg@ogpwBKe8KJi!+IXwTkGSCoYxmpzSN69gB-cze$;xi>WrU323%*& zhZ=We@8`cKNUf*gEt55S>i+-9AvUgGiWdv-Ly>vk=1k5YgSP5U;(f>=$z&AZ{mDBc zLVYj>34A8+9kwI}xwn*W!9#%eyGZ4i8USytMy(UuX1T$g$A7ogM`Po?&hU7@I2Q@| z#EjFw;kueX3>$A7?d=4AdG^EGk?8|3zutHQy&P8>JZt%G&mBAP@!nx4_+ezdFEY-@ z$0K!+h5lcSr}g(i^%;*hq{yO=r$5JP|2}VFH4SfRzx3;9^_Dj1V?B%2vmwLV$o+CN-xDN!ll!2R_H+g0yROdojp5kqyvAA{;W z>%R2T1|EF8ADqga{d$f$TzrHQ)9{>y8Ki%#-ILz`4;rK`tog_m%IJC9H}$-Qn z-q`(&2Jq(iyiT+j`XY=#@fO_{ZaGf1(y(Pfpy7R|F2Ka3CYhxP1?n zm`5pMPfnTxW43$EXFt3>m_G3GOLe+i9sNuY4$qXBzcmLR?;j7YY`R^j2Vd$?t}y$9 zzxM{sf1#pwe&+Z8^sTJ<5O*>;QFh|r{vW6FW{)3({@-p|4N|;U_5iIxytiN>tQw@Z z>sk~U)Sx(vIUQzTh|T;SB%%u%qyguC7ry2ggmmX_9L6vK_mzYtV%(8DstDB;-0XF0WWFF?bht4f?VCS6~I>+bD2Jd zaq|1Q6k!Mz(BPvRc@{aA^yBvb5e@a$Duhk2do*zQOt|f0Tx4UA25p7ZZ(xYEuW`Hc1>il8BX(4_*A?EsOV5ML3LEcvcEioy86*Ua zQ`Is#R%wNew`Bcp*TgFJ>;D%peMsTtcj3kco3<}B*r;}$m+UTlyand>=O@m0hi!tN z+gZ5c;~j7&Z}uCDTQeSSN)u~7&ULHIA4#6Vd(AYw6&#OG-QGI6yv0BEhKhwZRFSY$ z5a6A?mb`8f?>RDO95w*Ft5#c{8E=U}cHJgl*gPi&d2rVy@CCp-tMb&aG?+oE@qE5^ z;GQdd*0+7vym{DoufH#D<>gI6GMRDQr?iYVEWpNFD4{{g=m7iS?a1^Yf|H-i&(dY` zi-h2M5sg^~tnl%UJ@w|IlCnF@vw!i%I~6R60=&!C3sNWX9(yk19}Mu$e(`)^^UD}yi5H)n``j4h zzOd9p3BbE+-szLp0PkQ8x9f1WEBtiWec-YXHr_AXD4ef#NC+C2eAWBa2~ljkbHAV5 z>1oe?c)w!$xP+76eCdyOjr?e^r-)3O`#Apc*4o(m9SM4x$X1JiBVEGy{r~2e&Re%Q zbY}eXmOOOUeDM0Uloisa`hS~gc+dVG-j3ouV6~GU3-7zphxsJ|-VHRUc5-u~|A@Nk z6@a%i`AITQdkjMOBntEEn@8Lq>|+sSv8 zgo8f`LF0DE1o;M+V&g3}Z?Dylc=p5Fh3P{EC%=GgH!hU73&L+Fe#|v_jgR-m<8xl8 zb!#HVW)}|!JY}JJ-%i-twQA;n|4+Zpnh)t6OXZEh-230}|JkF(|Hmvq|L-uZ2C3ar z^FwRUc!HidRt?IYM{4*Sn!jxCt|RMLfEtu#ANQ;f)S#^&HJXcBV-Ty}{89qAL5jZD zfu9QQAT<$vvWg1sAX&R5?L+`_o*WPm1N{FGmfbDaMm?Z>?QW- z#EZv&rTt>N{-471u@@&l`&?UsXE6;P*+CVtr3~Ws^TLF-V2SiFxHw>Lh;S7PJ4ii} z%}>H-{`db-Cu=?~L@&FabaARdT0af%xqCgPp4gpikg7__Vpw>KE67oY0N&wU-aM0d zUnt{Fx%D$D`i!O}mPyaC?l*UtNN4)p(3T0NsL!1b1=2h!)I0=)SJ zAeol{Z{#5>8Qwlc%wdy zaq^S9@!+@pH5z;?<3>e(IzHZv^TxJY6e8fqht?C?&g0J@>5<=Wy`|lp`Tc)5Yd%c+ z&$V`)pQ_&W)9_Z2?&(1Bz8#t&f`#{2;$ZYBz*{|+yloP1&--xNT!6QRK_X|~vlwJ= z)a;Jkvtp3i+j~MC0N#P~bezq=>TS7on`g}(H+XSfc#>0=pAep{7g6(0Ts`~RNSA1&75N z|8Szk@JNvjeda$-oH+jvOFmBaYG=;@52S;+_u6TAEB$N=L-9V5xl6zs_nc%zk*UVfrY<$o#%7vT!&tIa9y$Vflbu1RQM`W!j7VeQy?C8R;|qYd z#rX04lX&y12|vCD@YZ##)QcO9LDmKd9hlurM+V>K&Lsl8-{%;8*aq+}vuTj%IqwEP zpZBCr=P~vW+msSm<#maSykN#P75eCTHee62UfXm-bxG`p_j9I?%{civ-=R<>s zKb%o0--nMkS5;hoX<0Drv%}`kHtsrHydkeNt^*-%GahfK^%P4!G|y}QNxnTbgWNa` z?}Zjl=TN*k7!Rbd@V;Z;DE$`Ty~<*~{v_Ue-Y>{52Y9DPzpd;09)m1HCIm`a=}79^ zisnYJdV9NrJE9igEx&zy^@H8u^A@_;2CD*Wys0HtKfXthksfB;x+l?8m#f%#H&mQk zfAul@_5VUlAJ1^|dtDc?zgJ5L9{hZ1?3V*R-anp1W!bic!E;@12S#w=SMLDchay?t z&u2W|H7O5R^0B>n^Pi~wQ`LLJG`ttcdI_O;o4m@9#KQaV;J8@_z0=Zpzv93IvH77ic;lDQi)qX8@s5|< z;IaVVE!ufV?(_xx{eLK_k+fU6dB)=nky!Kb?BO@c`@hRuj??g-*H`hM>b+uUvji62 z*L%(%>jro~Ua=!<67S{jd$-pDyrbl+%y{0%AkwLfC7QqJ$Y@BAzXibiW*g)%`TieS zfMygY;||9W70%6a$DVsf_?Hxo#*mRi%(&F*r>)|)*mG}#+mRuQU$GzFJDEOUoc#KI z@-(#e3Bip5GB@YT;^Qq8a^Um5v@lpRYOJX!0Dp4QDib(-^_b3#$9v6>tt|O4IQCeI z!Z`VF|Buz&veSPL`u|PSYLHI$!_Vjt8@)tX5vv9{O!&AIgBlbaZs=zTYLI2%ya8WO zgS5r2MjxYs2huivexQGej+__??dSjv(wC3<8-FcpgLgNGo+5s9g@@`NgjNx-huDRQ zu2J+CT*wb*T<`Db#!e~hA=YKQ`m(;=2;24li`p&z9Stt*Mf8)Mzv4DL zR#BZ|+^Qk)%jN?I-#@*N8xK8MDn9Fn(u}V`&{`wbd??RVl>2+dj{7vc7l+l4pm<*$ z8&bf+`>ceWY#G2?&Q@J?67SUyc76y2crVeEyk#o@uD5i(l3!gwM;529<-Q5<7D#>C zWVXBwesiiTXtkdk+*f~=wFf`v+3HSqCv{@OogKJE+O`@G^+A`SoiKh)_QR`mJC%*Wfqg(V+4 z0gM|VC#U*%UfkkA0;^Xt=~VPE$Kjm{VhsgT1(*LZJ?#LH~O<9Y~kju zBV~)f|DTrmgwmHNJ>w5ZOB*z@M2EB)fNDZE{$;jJaw#Di9EJ^xd3Sa=hObAoFD z-b)u%g-qftBza3F0pOi{;`_oMJPgDn+CPY|oQ@PV2fq&kcsu6*{BjlGeYz%EVPLTv z+&foqpScq@-h+z{bUGSwA$`oa(@*7isQ%b^H|0yqRb6C1yoZ=RUf|?cyd>vX!WkNz zO&@)dK7rpLm2%gYUH;(+tHwBl{1C(6|A*2Kn|r#=e7vD#7JcOGvQz#$IdPeWw?=#A zH57087p}9h@ZQ|btNR$>{oLD8b`oz#r+lMKfVcO}9N7vA1F;K$j@i}Fk+Z9Y7On?) zpSodebuV_y1j4 z^D(k5n{(cUf6xE3Q=5;O3+VrSrqv+B)a3uX|L1Klu7*{EO7-U#p8_?gL!HKH4QkK@ zZ=&Q{P=kggAm@=^G03UY^4p~HC1W_11}}TRJAbqi ze+F6c^NV=7K@2>rYuPqlN&F@DIMGFw&^oml-yq4}V9m#Z>c{8XcTepgc~8UJz_*fu z4zcr#dQ`FS?%m-OaTefh5oU1B3gDfPQ+j(nz`H%8KPzu62C0c#lOBJNju>3`u@MA# zKU=xmZWQ3XGD~CPy@4A{x33IcYJiRRLjSF59$6G*KQm6V_4DAmwb*zkNbT#~sKtJG zqdtz~voL?_diR{}UpQtdG2`*} zOJU8&Ip@RKcT@lE|1o=RcKQM6|F=x5LB`3oRcHa&1L=%!HS#CSd5{8T+?gLzhWog&*C2)D=3mU?8e_Zu|18so7*2ll^J}VXs%Wsq zv!HShn<3o&{4vCO_~6>ZaFWT>KJgCx52VcxTfMRzqAp=4^!_`!Trss|$;VBjSF@P? zzyCD6mpf%~qj;+%zg~!i_wKYxc?Q7yrSl!fNxUhtbFY{IymR)IEl~ka>_|oRaH|J_ z&s*~67al#)2iGjL<*HoL2Gf^{MZBZ9!-cn+_wc{Q9%8dOvR2rM@*p>vaSwmwb@+E< z53$z^{G+TIN7)YV3rrukaq{zB(Y34ommqv)Uqf^D5`4T#c8VO~c8B42Pn|r@9menf zp$A!JPcKnsJl^y%)_fc`P_>RvpV}bZJPq$<3!9Ikcq?8kT!4jlL|&Cj9Kc&tmWw!v z_a-yHL`#78hcEj*+yBHMzc^(+NQ8qK9A!-qv*)_haS8U z0B`Lzx9_AIw!vbm_kGJ0+~HsmrNB`U>apP!St~hCqI{EA0tF!Xz=BZ(v%SjKHh!;IfttQ55b3`wRX*tz{eYMTm9SPrQpop zAT49j$6eyJ&t6m4Tl!AJdue?E7mByvL92OKc%Sji>^%YS-kBfcI34ev-xo8=0N#K0 zH7y$3Lq}#on}>$L=7hx?HI6+?+hAj#fL}N3+~A15bs=i_w^c)5{CW}G46 z!>`vB*prh_aEGkSMfTgA*v9nn1t-7SwSh_TErRe)iSh&4ukic-IoqMUlKy>g!S3qV z)K~a(Z^-Z9B8MY+Gav79)_h3r32L~J`)~jM-|27u&;K1T#0F2RK^9T7f1)+$j59$8 zs|KxV=&ExDHRvn3H+VG|V&}fv{@e=;vC4mP%`ZqZkUez&j03Cb$XZ{uZ1t2rSfpF! zZIX5yT)ZGAb-tuKJloVu{q8?}AiXYa*7r>@yoeGrj<#+O{IM0g25Hssq+azOXS)Vz z1Jj2NPJXdwCJ`$ngy7jPtt!Re;}5aE$4qYciNwRY6;D+koWUProgbA@><8p$e1qhZ zRLYW%6>k*YU;6w0U(htXS2)hyi{kxDv_%^W@0&|%=6eFXRaN~(C-Kg09TRi{c+b&R z^%0j~AeI!#KXUeTBuOdG<9Ko({L*Ht?)k-Sa7Lp@J(F#%Ub~R zA~wvpklXE*O%Jj09_0{#UF6sgZvm!{37q`GwdzjvItanRZ}|zdI()qO!t*>g0KDIX zQQqZAu&{%)J7n`bHKiGkH`KwR5Bvg{@gmQdaT#@`TJ1jA4bsI0g@-lYvft|M9Hx&vocuJiJCe5v z3&Cztv#NR1@bMlml_vNNAA!d|##5@U;(y*kzny1QByfJl<4rGS&Bt4QIX@Y&g9Iig zTc_b|I^_Ng#oH%vyCxRi?yXPxg8|->>yn)(@eUfWYgi2Mu9SM7cm#Z$n50$0vDKZ9 zsE7*{*aN&r6y=7>b=%;?+*$PPTijtEOIq+mI5ytfjny8cKIB2RFyoX@*mvLAj*a(k z{dX_kr?DU25lkOrIQgB{xcTtTdLcNR?^gqN3_jj&#}`_3xgCM+;-zL=uEfV%r;4_8 z#4T3;|9tZMKl}%NX9%+7!|{MjeNe&_-T~9_HmN-D6vf;0B&>mjw~JVuX!vCHb{^)O z#9M|pa;X8pdrf*xTs<%NdP~6YPrMf$Atm_=mVv!DG01o4UA;E=8MQ!hwV6A-uJ-Vd zlRh@yP^&;l5Q7KV$c#&lzP0`HQf$244Hs(;zB={rT7Sdc|Igeh$G^JnIDFDx z#qG%@{PX{i#qale%WP--3=%S7&Bu_mShHo$)DRms4ewPJ-E!y^? zLWSUmkCVE?7UAPP+k1TU?v-Qk1&z7iXunNFuKK z@OZi`enM9tee&Ea1oH*(S`~BQb0I5cs(Ob^!+T|caxjWF zVTG117T)p{CBO9m@26M1>L)iR_6HD_ZUK0&j_n)Hn9V@8ONR>PThWoZ*AiVCz~0+e zhw_XATHy57^7N%XI__|mDmO9p7k2d~`%_ay@AD$L%sBTkK6h&l?EYW=Mb|$0o9u@- zH`9kAPJSB&$SDio(%?Am&}Fn?{Qkd`kzpPS@K&q%c#6VG|DU)4DOh)B#`pj9;*Bi% zxV7BH;d<7;`~Ux!rRTr>XMz5I*R&dBAANpm|9`UoSMPBrW7VLi+=9JQpaxxj@58?q z)F5F_lk#LxgScawq^?>qkX^M3zf0HBk+=yZv6W~0;GL&lFRoN>gI}e7QSy#*hc|m4 zmM&MtUW2TdAV%*f=SQ|O<7_?_X9}ud*PxNN+Wj_B5c1#td-z}a7w<8B{KCmkzajD3 zz0)*UE-Nz7^b!6Ld$fIM9;a<8oX2CH+aiU(#7-A0HQGd6Ipb%L^x3TW2-h6DvGUVY z|G#q@-fNfNN}n8JC-Kf2SLVdRTbcANOab6MG1gdQ2k_o=;?Z~*!25RE_Z@{63}k6b zw{@%y9l5uqIn3ZpAN*X>4T)C;_y7Oq3%~B`4pTV4ZW`vs#(VEVzCAw^_z^y4+^MmJ z9PNDAcvp?y{L<&aes~{X`nZRapVEdsZI3!>u+S#n7pHFG<9#@Dlf=)mBzPpmB=-u8 zzr-$bbWynP>Vg@McXJABJ~-D_8D;!E-m+sF-gbhqJ}BNf+QS@Jc(-WSeNhE?&)=oL zZW8Y!IZYMj0B^c|&$kz*45WJZ=C^k&=!jDM*rAmfeQ;?*-rad>ZSZW-aQK9qI~=Zd zSZbVvjkihj#_+67{Kzh5+=;d~A{GDe_15`sJl4h*?1%RXrjK(t`F*-`YxiPs|3B@Q z6ZeyBe7sHRd0Wl`yocA`JCe$Se|igo=k}hex;W$UhL*ADgW9h&`GORfoJ35+d(8{G zLnz)Kib{!Cc&`k&7p)HPE|C}gHMu!)##Wrb3GjZuns|qQ83QR0B0MC4)!SoN6BIV4 z_rb>dpLiDjRbd|osPGW*DJyZ zz}wv1YxkdJbfm+79#7EeK3GO<*7fxZ0N$;JOPnp-;cwShWD@FBmL zaV^!tP8Wu;S8o%WZyOsNWWT+)PfQ=jaq=twQuFK{LkONAq&LL6;N!j1u=>*nu=ghH zsb?j}jsJQ}eQFXoq-Qqct9QK_Yd#F(=UdI%_wW7x|4S|9|Lm^?Lu~Z48nn^(<~DSQ zU3SKb532^n_uMu36OzA-Ec4`*Js4u6Z!E2!d_nr*Dt#+2F9sr840{%XFGzVi=x@Dq z`ryT-Ka)(P!3Al)S{A;C++orJow*nPp+VZ?NPc)DO#tCy#wiA0jGZ8053%)kT$a}m z32fK@$1r`=;p7*&^YEsO1|j&sN+_~-#dqBO|JJ<@OXnRt3r84kUD|&Zzd?eoMe;pQ zocaAfbeTmTDn+L0;0zMLJ8Bx<8y54Fqj;;RO7mjj{rO~Z0|5-N4ZeYUCh=CkTW$~q z@V=1leCE3=1KB8~-aa3E{~z{}imsxSM~<%F^Cp53%-KM7Nq&@T)hypiM7atZK&NO~1;Tj}%4a zqD_DA|KB|g@AWT(I??J~d8U+th4&Jh$Yue6cMBv^Gr2jzk-ts$KET_j>e}khs~O0Z zC%?Z|JA>C-)M!G-&h^1gu4jr~DYU`+O*fUAySu~gYAT`L|4_Y2msRr(WCRcoW?Vnx zf*JJ#cJ=ldqcprNWYgFIa0Rj;q5HFV52C& zo0!P&KZ$pIz})ddfH!Boc!rP-IK3s%i3B^+k%nT$X3xw%css`cf2(2}Y|0nd5n$*J z55i$K8!lm2@3TA8KE(F&Bj1^E(q@kmrEXy3{aL%}v}Y>&;eDRz;}cGPBG3F8882w? zvkE7{gM;{Zm)YJlT9>5BSgGahf~3X49zicEc+`0x4u|Jhdk zf91FBcVdvH)gX6Q#%Xkjb+a@T!m2?F#zb$t0{#Cb*{J;Wpa$uG&8_1BHR$7U-(bD7 z;0#jo{`0Q4=!i&{Gxypneef(-=P*0LHn`PWulA#qJ4|1B>25kdb`7#i(#va;r6PNo zaURQgPlpI%*PsKH&m=@PvS0si&-4+ClV5kZk$b(N5KMG=^ggZ@e+H@D65hw9lL>op zCq33Lt-@U|fMU|>%BsH4{2H{6MIWznpK4F-ATc;PI!#j}agNB#i!k6{O zf74*;+~e65srYyoxh=|kejpQ`v&UaEPltuiTgYuEUWe_S@eL9rz?zSmmWm)%aK#R& z-o$BmyL`_xM60({!fPrP-qnRKR&)crA4$3lt^;^Kb#Ff;5AfbuP*E*=n1S^24vz+9 zf)}J7THlDd)CcdFvqeB%6jbkk2UN%o+}=7EaCy~!Y`g=-3f&jw3m})7aSwJ}uWgIQ z#(Q(*;~|nL`{5nJ^x=b(-&jvj^~rlea3!Z~^ZRIgydU2nW!t_x3r8yCCv#lG$D1tk zq9yU`uNjZG_yX2^1|7w>++Y4+HV5zZ&bGNJpqD&ACb!`{3pEnsx`o+ThaR{^D0l!N-ZbdFyX( z#l~Cw^3jRVT>^+cGmas`=^+q^jrSKNo#mp#?AIVkGkx^oC z_VHukZRI~Z=R3eVw{yA9B;G1F*Gt<1yfr=AMBn={ke7Gw4Euun|GYxJij`dGgEJmi z){IEB!Ctx<+rQ+w!y0*%fRTUr{=c6y?qTUm0Yr-#w;)jY)+IIUy|*{5Z^EytuwV5a zV)}T6lV8cIdx3?AgkVGMF69Dee7t`fMy~$^_TJorpOr+dz{fkQGCOM1y=5~VZ@Y5V ze4IAfuDbWozvut|SNiq;>0b(lSng>x$j8p=Dq4d)2erhpYLIPjZQw0XgQ&U#2OU8T z;^JNHBnxWLjx3FW^cn`TZ|_{GgKy}_u=m@7rPsk4N&W(HechO2YwAQmYWs%`t_R`UxUV#So87KdW%3o;?xjJnTEHw z?3Dl%@2V`K7#7~^4RjQxeX5DU*&&(hdX?_An~^IZfv}FT3a|*3{a6wW?bePg@R~LY`j1CG8y5&h*ialV5+c?!5v7Vfet7f!=yme7q%lzxh4@cy}J|DA2CO-yns2=2&%Y>74O+ zv+SdQb|-D>cngDT8s470t@}~DKgvE8#ll;7LIkb`czf+ot8)N&-yH0;69agMnLgOk zcL&`6=O)@x|AdYt9=KB;RMZF8nMT;@a<{>o?!5mq&%qsD^*m#z#Ao{45tN?1TM=td}J7w!s{E zhuc>fyTjFOpVzeNV&iSRW!1~ehp0#$GcH1_s!l{5yLu}MKkvy%XFt4A9|}16-LlBK z-gcD+*Blij{rG|3Ag$DSY*cVI6E6DsTXD|^{OV0FTf8YCbkmH-n^hlqzx+HSr_TQ~ zIH%#gDfVSOTD=zq2MJ^0eZ21LmuCR)=nYxClX#~~Ey{ra-T|I#E>dzCNHj0S`fVj0 zX|tPi<7$2%Y@_*X@H>AST=OJ0#*&?4|qpiH1pAWI-gAWk4sAW&eFfW5#9fh7V91mpyS1<3rr z`9Jf&=YPgu&3~IekN*t+asGY$5&ZuAF8piwP55>A=kiPQQ~8N}Klpn1-taZ>-Q~N% zm&=#N7tcrM+s5a^w}H=^59ZV4Q{ofnzQ=u&`y%&g?gVZ+cPO_P_j+y%?j_vwxn;QpxrvnTlrG9kN*$$) zQb5V1BvSTK!YO`~jTCE&5oHlYfg(a7bN%A_#MR2xz*Wh0jVqfgnJbQK7gqq6E7uw> zV=iqjWiD|p9`Y!;pWH@%My?_klP{9f$VbRgb&x7~%NL@s6XB;~vKijtd;A9EUh|a|Cj@bJ%g1a_DfVa!7LU5yy#x z#13LJv4(h?c$t_^Od!&Up+qm@dZGn!32{DA_P-V|2-p7Wpa1KcZ^tG3O7cntJ=T164ZN4?jcgs9GFW zKLWL(O54~w5qgg*Ezu?(=pCvw+AFU?Z&9@<$LlxLiYoQpVuH{cR4ue{ItRT*)dE>B zA?OvV=Ji#agI=Oa?UtG!^a53L_j)KoEvQnpEl!1=qe?}(rvqw6mD10qFsKPtiucMM zK+jM$=Xf3jJw=s*O6+3MWvCWavqD@hKsBfmHP-Qms!=7vTaW}* zp-QOB>?L#`RkYlRuh2bI3GTV#3*AK(b&XX7REa79sX`?PK@~r3nJ`p=D&8{MFQ^<< zJdE8Ws0>xyF7d0OQdCh?a?d~|s3L!_Er9NzinDIXOXxPLNJo^zpL=p}8M=b1VYBawP#&s&2>*_NE~Dz(#}``AB~%Svk-iLFMAg@5 z#2m^+)u03T-{=CW29$g$P!6iT3?fURY*c-&6v>3nqpEM8kUErws!xu}C!uqw>Q(E3 zp-fbD|JwEfI*Y2VTHbQ#45~UaPc%RosQT#cdlO1W)d%$p?a*mdwNG?-LusgLdnEQ6 zI)$qD7aCtesi=Avuy6uOLDgH6QX?oCRjty;6rdzjy?*nd96E`rS6Mkcl991onE9XGRP}Tfa$`v|_s;1oXyHEnEp6yzi3&o@A>8gru=m@GB7b={C z4x_4}Ger_QgsR8oFP=jOQB{A4=L!^usz)1%r=SC_M`7OjiRn-EoCMX6~_kN!_0nzz5$OKTmmnc?*yROH9m#|5I| z%Epu9TTziW*V{Az6_5q!sBu&H3sJP%U5ax%99P^PNUsRkQJ|yph zimcZwG`vx9F1Iqz3l*6mM@XKiI13}`9;i6OSEREE73nR%FS?`Rbk>&^H&mq24OhFO z;*^P+feR{9sfqH=s7P)PP;x>=(zWHr8&PpGA<1e3Do(7~r|F1_M7a`Y2UHyUY`Abe zDvsWDxV8=z2?_M=_Na(=v5H-biX)mg&)T8l&{%w19VaV09~7RT>fpdy<3{KyJa?CFf+ zF-OJjTlO(#sEFKC-)xGCT{h;aCaBmcR_A4miikg6`pZ!fUef2W3>Dk=ge$ovNsC?6=KRL4`x3 z_6cQFtUun;uY`(qcBNv9sIZ@XBXSNZ?1udJDWJl(>?x-_D%K>v%#=gLYDdG}vr%CK z&S}b`Vij-Guna1!o+MDEQDK>78!3f~mEN4|B~f9a8C5EQiWSt{K5gNnt9x?i|aq18VeK|zJ)OUJ8RsL+T% zQbI<>BKP!sPE@EbkkTQcV!=qyVh&WyuQjVC@^X;5Cr6q2!g(Yfz67X^C;(B1s2`~< z)CbfO>J{o4>M<&V8bq{vZ(C?u|7t{$$}T=iTPTt!@2 zTqn6=xpr{*b2)R_a4qA~zvOC$1Y)aN4 ztCA(je4OK)gPa|l&73uyw>d9!rgJ86(m6vpy*Sr%T5vAmoX;uCDac7AeJ6F1UXtoa zWuyX9CMl7$j}%VwBW)yElZ;4JimB8 z@wDh zxP!Spxb3;kx%If!xTU!T1eOVC3MdN95}@#pfR&eb{Ehtg_;2uE;7{d0#J`(Akl&r( zj^7llyQuO@^7HYH^9}NK@HO+*@ZILS%$E)jVE%_W8<8Ko^Cyyk&VJ-a4`?nTptB$O zKMq=l2>Xnh=euuW#bl5TZ~um_|8B*n_G8U&T3u-Kgp}yC6u2MAhf9qDzEb zsOoDJH6-jr)u&UUuLwI()w}JdFChX|Jto4Agm6@K&+gJDY)4gRd-iui7^*&APm&~T zL)C|<0cS!esyd=Z69^%wY8MXeB?P1DeShg6LJ+Fn-8B402t?J}bdKGGt*C0Xy&p#i zK-HT$@G8OF`Rh8Y{c7%1PLaNRY2==I|IOa(utVLD16aOlL9jeM^Z~sQHMODd9(UL7%T!Ia%Zn?bQOIU@fVr?G|f;Fmcl5Q~wR;arEvSvTQ5>?mE{y+BK zJg%m;?f>6PgU~!jq(LPW5|xIN5-A}>DMM*el8Vr{8);O^(16O&oJx^WE2&T@C83El z(JrY(RDNq`t?Rr0S=ZX%`}cjGXYc3bFOK^@xQ-8RpLHDPd9HJX@TT z@-%+2K%21W_B_9h&_*oE>0Xut>0?p$EzLd91}w^Q?OFrrVNvF$tT9Lzi!wwV`l0n$ zl+G`63|fapw?Ty;Y1M9W1)B{j?;cjYZdG9D*S&EJ_*LyA8Q=3tfRqE-NU4 z)?(4MFwSO31B8DvM6tF159sGipVo|uh2MLnLqA-!u!jK#mo$bo%fn>4hOuj`g zv;>Pn!WXeZGFTM6HOCN=#-gD4!-kL)76njFHA9kE_QN%rmG zkO&r?X!xc931iXml=gFw5Ei*RFCK#gvB+)1#Ry0Mi(JLj7eV}3SmbbDSrM9tMfMTJQqWv1qMoUP z=Ae<3;hcg(=m{1XJhk5dJ;tI<*ZjDk8Z6p)?4v(ajYaypZ6Ba2EZQJ^ZW4NgMY^wt zE1^m(T7P511?V9btvmU1A5?)wK>vgy1Y?no(0o>?9E-F*?(&7out@Wc$PefN7Ojmu z`UNV*A`N3W04l*Eb@A)j(0wdgGdO$^D#oJKALGWMdsw6z-Jk*8#iCUQS`R=)SfnC# z@;6k7MJvWDjG#MMw7ljC8&rTr%F&ZNP(BtZ*>vked03>lqB{k;jYZ4mj<1Arv1n;a zkvf!vMe+su4p250$sNDi1Z827tcLDfC=-j8a0`b+8CWFUxyKnw$0Dh$r4OMrERyt1 zR)B6{(PI5~Y0yn9k`Smig>GQc!k)2}&~+>lFZwnDrDD;7K;s)w3Kq>jaNsPIj74Hn z2iT!&SR^w1bSHEbi-gPM0dxh6gd&>PSUa=jp(re3xh-n|MPkvc<7z9R2rPn(pQ}OPSVWRA z4S~YYNOHQX@-h@kBK_TO!g_J$_!0ZtG+Hsb0D6l3ZBmbLLL68`J@E$3#vio^{otughey=qy5IBnd_vcv1sP@ zohdAuxvXRoi)QY2_=QC?x2*rfqM1vnC$MPd4&NVGG;`(YcPyH@A#xmxX1>+-4U1+z zZ8e5PGhYH4#iE%Hr;K3H%y%ZfV$sYO--oei<^$PZuxRFc!b4az^ZC_5ESmXRB?XIg zFFvj!4PeoFi_|%!&wt4R!*N zZ{^WJl2%~Tp6;?eM)+6kF6cegZSsp3HbnEZU$5_EMO%*;V|cjp^|oTVhL>j^4b(58o%w;60B9 zZ|WiohIgOt)%kdMuk77Z&1z_YkYQ7#`kPTWwC}A$Y5$ANfpuIT6EK@XFrceRTow zgF8DrQ;_Banx|ouS2zHI%dACPq4%I^l;^ua-9hkJd~_w-2>$v1wy zhWOoE68Ft6;TOl4-n~iu^y%=8=Bzn^Tu$_N{%4N)Ux3DgsQV_E2etf=mBI6%!6(rV zTo4ZmEqZQkiFlCCna}}kq=QucRH9$}HUReJdeE}%a%=pm{@rRh{hK`18L^)wkUu*^D>;|3Y<05!B~c zZXrgpM?C0b8mWtOoUkLj_EO2%EGi91{ob9tl#Py0>`cD>5$gQE;DWRt^y!$E-S&#qLCuAmH=3z|ETrB zM&$ng)eds=b=*(vu=uR6il%|X5I7p=gwaL|vdukrB~yn3m#-jol9ME>NtEQWfE z?eX!BO3i6L7sGgX^PxH-2`Ma@7LC zd)1*39dQKj1ii9X+^+)Q*1@f;pWcw+@J~0ZO)Cb#oZTw(^jbT?gWESMzxi1K-mQaB z8jO#3U1Gb@iH&@)0GhXl?Rw~{z4&-dAO`KS6bDBB;;wUe70K|YkO!S5D$!lh&Ao=*J!Kj~=kyjAMsOpiCcI>HWrPPqE#dP`m!ys1YuFudb+ zV;1A#ty#WOD;UB1B)gY36>m}-`NPzaRqHY`T`imH1K{ap91uUUymc_XW|4dO03b)& z1T=j>@ZPE2aSOp);_mrJZT0wge@$67A*aR%OQCuBM;DY`K8lZbV9ZT>XB)=D`wObW zpP;^&^}n;_kj)8u+3njpTZr*?2v*(Rzv%34NuM=pVd>;TdS%HCpo{l&le7wP}{PP@QeDD`EulH@n z5W6Bi-ov(z2g1VuDlKDZ13je`3HN<#B_w_z`B6uh65#>;*Al`c; zEpYzY+6^(kd&|f-L?4pYYcphYS?60_yl+EN`is9k=pH{543U*6n@O8mtVr|4%`67!uSMe01M# z`5``VrGt~T$d7pbC+RjW;pR#Qb{jNi`PvijAeEnC^?Ji<&Ga5L8AYECxBcSAyZ_w( zCqjca^*AwxcXaWPJRaUFgzGo%K=9rhyXEUX1aBovSg#qu+n`(Em;f^W>w<&HW@Tj9 zGc#^>dffo1A~y#W-01`xE|>OPT44n)bUjLKYQ)Do=jLAZ*F}8rB{a{wzqSTA;^Qqb z5U<)dpYia{M0G48sIT}=Z1iq51&hhK^6{XsPDZ z|F&a#yh-cm)G@Nfd(fKtdCLG{8oa6J<1xH18y3sq;hnclr_3C|`?E=X1QqY{X`wes z2;S)$nOeih>MgI0PYvlI8Sd5jTzl{701&*MNAfA@1Tq$FDZ4_fz`obdwZC}acaUbh z$|^0_`QZI%-WXe=%d#naydyWPU~wlg9^R&?j&Oqd>Z0vWO(Gvi&no*77-mY0ciS=7 zSiLi8;N9G}H{_tlgsZ)z{;Fp(^?l5bH=R0C*PaeIt2(oKD@21g^@R@%?2vUqq8 zLc2Ju5WK&3J1S7|Zeq>2y#>MhrFb?p*cJc>E;QZVQH^|@_+5Te!{Y&PIZAt2=3yuB zTxOiI>x>nM>#JPr9EOj#-Rstsda-=)1vJmMwY!{62!BAzpEKJ(rH}Cjq(i8V+XVHM zuiw%ozl|RlW=^zat|!LZWr|ZsE#nqg?rh>MxR3bs7VkuK%@rx;zaULzm_8kwpEUKZ zVhN_Yw;&DP)Hj$gyz^kwC3tw}U2(T@K=2lOmsCUDoRD2*GPV)Hn-Zimbgnf3mN=KP zL-{Egess)d@_Y3FNI87UFX3?~P`L2oef4fDa6c_!ulFW=yu&%41)F>E!6j&3$%h{= zf4;|e@7#2IiIy71!}|=XBb%T;yGtA#o{9XR{`BPv{Z+(x^Oq*R$VKq(^BF!aIFGpZ zCS@;asCNEe@a?Uebn5s$6|@XF-tu?Uii)O~_AO}z#Yy|ZcFX6SY zh(jK+oNFetn~6Q>v5C?n%Ki+%rc}C|^B!>rNp=h{yju3Z;DGcA`g9CjIltsx{!9lc zPJ=h~rDP26{@Ja{cz9d;Y|T+b@E$y4)OP^Edo%xC(ZdMd4cz@aw~!7pYJW>pgIzScYD|IiBDD81#Sbrc`(<)wq~trzjbSl%>us-u1#KHjI5 z>nMlsFdp7Ys17fJ`nHQcpPSTyEU}Lpg&S59<1IBOVxj8R3@|OG_44ONV!TPcd%Y;bLm}g`*XQUNycf{mO?}HA!@F+ZZ6!Rs+wHcSs3Lf)46z1K@ouhIsjv&d z`}E@q-_+Lua3h#b?YU2eSvDJ5-EJBH3;b>fcwXuRwp;TXyz;ET9@h}*I2(MtB}sbe zt7h}VW@sMg_8;xgzu;Zqu3mW}hVk&0Ky}<9s81sIr_uLi0^q93Q;+BZV!T(UmCJlF z&H#bGj&)O#hzBInj!+xQP#5#h|Mcp3EY%wS=kpfxY4E0A8-d~NCg`Jxhqrp9(-%zy z?{VcOaVp;Pj%tLfB6zpko&UgsY><}Qd|07|e4Kc~e}Mba%K`A#Et|XTYA1-+waX5? zWd+I{W+`ym>c|hxHJ={hgi`Q}^EH9k{r3A%gddH3ON+F9YDkjUT+}aPJK3?Uyxv zFg@O+Li%)6EFY9TasBW9KNC##>AIltX% zjd+kcd3|pl;z6wG$cO%>0+6G18ckd;$uOtWv%8I51K=B{o>-?j+8c!GcPBM5oD<!`P`xFXw9v5=EP1mf{3o)!WfFPqro1jb-iP6YQNHv1@K!YM>%P7FfBE9$z2&I( zKJx>Nhqo=NV;ezzP26`wj(YQh16eNC9SX#F&x>$66MZKOMBh)2NS;HC_vPxY?6Zl? zzd_noNuLh;-|BC^pPQNg7t`QPy{iwyo8w~YDm=VLwoPB*Lh#N!A>dENd*s?=b|Qke z;)}XAjjsW4N4|$Y^#f^T((C;f6 zZZCdV0nIaCe)8)se|)@wWte}Z76amq>d+;qZ~QBGvb}~Ml+O2WD3Tz?d-byD*pz}S z;I;h8YRUU_ydZrm<(T7}Zl-r{(hWLwY{@R5?jRwX6B0CdQ!k&y@Q&(oSHZ&@u2=OD zLh!zKZ<`nuZ^`pbQ6UK4J+_a3%Jc`oYrOrn$W>&x|CaI>(Y66F+0yg{KHUj~EmtYl zZn6dz7o6_diyXmiChVogpImX^ht1KvwmaL^*688y|0n8ARj^Ai9^N*nj;jRq#Z6CE zE1u&AxI(;>g6;JCm0|IDxefIMR5Xgr8|pET8jSU)bcNA)|5JYz)~JqK z1oZ`Q?9@JEDFCt`dWE0OCGH?U0`u8qg>kod$ z$J@?yj!?c3Tn>aZ*A!C{t6iZAoi?fJSKt|Z)N_uTIu<@VEJl(x!x)|_Wxbt zrI#fnGe6#R>ey3bB;b-d(?Kqw!JB&HKZdu6{{;;^ya#tgL%j&zTOp-0RJ_$+KMUza zI!I;LJ$eCxfw1uRjW2Y2$uK21cg4p~17Mx)!I;|yo#4#s3xIOU8dO?;eYlr`k9U}H zxP;OuKU|LHIc;v?68aasubz8ZEH}z{15z-mBblH+?bbP$XP*!N3yfth=A0zP`>@LS zR}B$4V0ZVqQs@vd-kg5YD+W`dkEf*rE99k*aBg(;ipbz$n_Q`+NR6=`v$A2Ryb{g3*5vM)S%Kf2 zklcduY;H0h-s-3h7J~W?>=dYQp5{k7YQcpm#>9BH>7J|}eU=UOe2pGql_Q@2J7TU0 zRZ5>`diPF`qEE-YN8_C8$nloH=l}8kg)z|oj?DjxG#*6#Dizg(sPn(kZcBDN5BhCU zmy(5e(32E(4?Dzz#2>3HYeGCoF9o)5G!2Anb2UR}tN6n=WjSI;e<2;D{JgETvpYfW z)A@H^_gVuFz0kPJEci?830%r&`@#j_<7nPVlFgO7_wYUF*lIyr(ILhgkS?M+TnXy? z%5~j;lcxZ95?QQuPZqEaK$ZTUJuv;lC`gAJJA?Kjt9-YoK|(B)6oU z@%VUO@Lc{fq?YmUwnuebB&bg+B*TP^T(KJ^7xSrgfEe#D%^lr45xgB&`09V8=Zc+? z=Z<_^l9(QE(inX@I71em8~t3)b9pjc&lZPv*6*qV#Ff*0fP6&&I3ud2;N&L z20OWtgkN4RP?4|i>jEDDnR7WU5eVad2o(VlG0Q?iBQ$*ho z<1OQD(DG(Z9(bfa_-p(-@d0V_$H_epcFoabpuXWhDy6ZXJ{^X-U$2fLJ4i@#vXlmI z>W45fyv+eT3lHxLyoZ&m5xg5$N-n43T`jpQPz}MmAan5-FSS5;*YM|P10H`kKA9Zw zdvpL81WszX%OJP6I86!#U9bk9JbD8j{0rXob6o7wO$6XxG_T;c-I>~(_;|;(lsx`? zmhteeLv;|<_xx_y6%g}=oHeeFtf4-(Pbh{%E9>VJ*LyGI;nAnq&fo11Fa8D#_06FG zn^gCSHO(EMW$SL$(_DwZqIjE?$7=CCsJM?!x3^mWUV!H5hi<86-HGo($(cd7RnE`G zUDN#U{$s`ddxfZu6oUHVyACJC`0#`5E0cBCtbPFO*W>;8t@vEoyaffoQE}zloBG6$ z*w;gKhrd^xV0sVQN1;#0XMub{!3`muHl?+{J#d3bnlpZ=5@ir_sr`s@-a z-or*tPd^}dJMU8baO_whyn>V(cxt;p-2X%Efxv7EaJ;%E)Tgrp+!e2|dHC5H7&zXV z#gc`O_w|yRuIN_+@CG#RMAz5LKQ`dw9kDq&|D+q^;e8d=5lK*=jceA^SI>|Wq=Bye z6}yS?W(`d~@??GiD9pDE37kvE6+1(db>n8^8Ez4=}j!jg3f#K~J z-ZKXeZ@*jI3(g~Wr>%AsR{o?X!qiZ%OHXLPkNqnICUD zb@aORSZqgbkVcvlWg5KCJ1PBhIFWtXeGWXlQ%*lWm4M*QvvA{fD&F_gzd_Wuw;W8@ z7D!kH!cffbr^`0@!y=m$B0?YvXo%3Dq>Od|@u?@R2P_VO)&j5V!sqev=3OYE?@%TH zzeDqCpLD5=2;(1+zMoorJzt0M@a9Byln~S>DaM&~*FylP|6p4fvzQp~+*7MxK01^S znp(ph%Grp&-g0Ct|9DL%FVo{)G)kWi`|8a4XMQuwTS_!|#~4b^e7%Lb_r?W<&&I>M zd-YB3>j>U`iRK@vn-jOA%e5aMcyA2+CC6(S2p_zgAs?*i54R-nuCAIM03k7_46aUf zfG3)7bEIfjH zPjGm1dR#6)*s?`Agolq9Z`ataURwljmdD247B`6Z|4Gq1TL!ennI3Oa6n#2Io+LQW zzw~$h$D7?4>VHQbv1@2NDDj)gHLQc&>!QPt=RwCjla}sAJZM+^taL}jgEZbOSb7He z#7@+W+{miHK$utmh}sbYfB2zi&uE`01^9lvA!T#50~Gx@Anjmu2*fKy*JRwrACNjd zJF__C1>qz#udpoAb2SUT2h}a$J_<{5Fx>p#it2bqP~X-10L@9{6+5l#KdxVSPV7M% zGTSGlw?Pu`<{|{|WJglCc0eHfz`P(SVXHr^@v~N?Lx=+Qq#G8V z$>;#a>7A=v#Sek3Bggm#{qXT#`LR=Zk+>k7i{{DnKE8bS(@ETAAJ)-MS+&`Whqp4S zgN>lRW0pc+w!Yv4PNoW*0%2mj!*C`e(0aoTh*X89z4A5dKLuOBY2NV?|pd~!TW|)&f6gb??al`=Dqa` zgk$7oGh&g|TkCCh{f+z-a32Vt%_{5w4Vx;y70*5dJY2(i3{K(WZEZ4s@e!{ed=kww zoV#QN-!MMj*Onjqs!w6O4st)LBblJS(Ye1NA#r|S+2?z)HIo?cdS#Bi#%_1Oy2lM` zLyr(IZy6lC7V)injOp=yzmGm0Ze)Mb*q`(Nt7!1PY(M`t)|}Kd-{!`{`|vUs(PIeS zJYUY)QSr{;-lMe^S-rhi5G%gNI}pwbtY6T6&>s$d)?!x8LjgroG3y%P4iGBo6OqY! z2<-mO6Ms1pA8)7rnhmvVf-sh+(4M!cjtjpzIV}6dBJCyP;cbuVa3rWtc;8n06V6C; z@+e3+Es+@Sl&alBLx_7X&%Czk^@~TiPqlv<;n%gC!2#aPzyJS&P91Ve>lgpI-a>^2 z?@P<_xiGx98GCZ!;ce9BT5<}(yQbXgCv|h;dBe}e4hY_IXY@QzoeqR|#^=eNv+#$D z^W~>XZ{ZBT3xGk(fwOF14)~UVKk+kUm1ICnR zUW;sis`cGVVea^AkXJL3)`tWL!fI&VSj|KIY!8B(7hd}N+bzSmu0Pz2heubd80qhk$n^Vf|WZ{wKXgErEqqwP*s!pp>& z9i+81cqf+?6k&L~xXl&8!&}ejRFVpUcWOr9J}Ta^s*7(mBY2N#N&j%N350E3R-bei z@`pR^?>;%QgaXdSDp1!TVYm=gjq%)E%U#qSr!rc=OGfbyE|;JIKXl z$O*wa`up)o7G(YxJCT;);vNWZc1}0HB<~MrKT|E)C`ADsBJPU^y*hwDwEykwhC|?| zrQK$cmH2okhaMf^J0u8Cp?NY~rMxzJ_;|lG@;eiCf${K8LUl9|)TjDL!hB^JKXACU zzNT>=G2TbF?ce|LLLu;+TyAAsNJj@Lp2ha@-fX7Fn=D43j*U-WHn$@;NF&XOIt|`e z&3_AG?k!_}OArt5jS0?a8xXt;T!0@HZ_~cQS?dtI`=J-B?*|3KMPYsy*RJ!2-=&qD zS}Z{UJEUKq3p&#QWUM`ZDApVT4_C;hjceoM-CkS}wQ#o}{0PkxXdX#x{Fmlr)NA?j ztsabr_ghrQ7(soZx8ptq@CX2*Q_}1eBg6xeZEgv>`6RNu6~FIkqX9AAhDL5ym(6D} zeRFcxfIc0YU3F~OV`uPIqrv-%T#PJ+x2T_+03P18UgbxO5xkeiCkjyU=8jTnK8WD$ zyR+3W7{U9o%eJ|dddTwD&DM5SaSGr#G`C{xdsH5Z zL0A>b8?oBr@*95#$t&+n`lTCl;D2;6$WJ;^9Ypo5&42J__fCEge6FP^;yQ5$soK%> zJ%{%m2%l5YG5Pfg;d%i{L)Gkcz(wZwpf&XAh?paglQTT?hy^rw->M9j!0V$ zyw6Up9ata$Zl~Mio5vF4?Q5qX93XiY#IH*-TPQ<3{|~*(u)DgPi|GfX%dhFvF)J`n z{X*c({I5fU_f2mVV+`*cnVJQ7cv}P*Dsv-vTOT+mO2vE4ccUHq5xnO|CG=@<2g1j< zMBdAYdiD5|4&*+pN@vWB9jxy8>C2cqD_PMjqRr;F}yj=6X)aM?b*9RMg+loL;dS) zX9RD-);UTi5WKbcZdgI<0^zv_R+-cck>S>%iTk^kBksLIh%eTt1H77hZMmP87{acJK35>6R+Q~Wi^8@0Pu244Sn7y7NOJYER`X{n%UefIg6-9xPwZ@< z!8`kw<{k|1Nw|4SSS2u!pS6@MutyTc6-cgsYu!#&O z^0IAIH=uwTztXP(L+v2A{##kTtSxZS+qhVP9Ut%7?>uAH;X<%0npX!)1KoZ2ct0AY zn3fbV9^Ow;9YpnAP^Fyv%E}L(pD*^+`%V0ajdLD?=IRs!pT4rYxoyM;q@#AO8EUnS zW_rBIbn1|M!5Uoq=YX^x4c=L4pjj=g(yKDv|Pd)L<9_ufDOp@oJ$p_A>vYx`;8_u{so@J{qlq6j|TvF4W^ zmWB$!MQGkv-fb}O!pD2b`k?yBORv23%7 zwGq7a<(I3SpreDFue0yy2U+GnAT3Cz4vvLYi~byt)}_Hab5qtBhPPO7>|#8;P4Da| z|AgROXrKDjg$8e#MpMbnfdOzaMdSGi7c$JA(h=LUjsm_U$~ExJ?EubMEt!{lYyjs< zX@UAy{P~|ZjN7w;M+oLZ^J3mm*47!~<2~iC1Wo;7ya9;^)iFs>AFqexxvnNY;LH~5 zpIl3fcU*sCk8kol(0FgB_QAL(gv|{3yVBZ_pA}4xH+h6U9oElk zZ3=J_Wvh=AL5{aj`sZsU+W^}h<^DP6@bNx=XFRxKLJ+n`^JFbGhUypM<9*%YLglM^ z#>3kU)sae2U)=T4U~7JUus67j#UPIu?_e#yy|?)8ft^kXfdzMn@h0hLoSB!U$n?z# zX$^fkUKD1X;Bo(Z{{O#nuKa)Ydn5C|A&m#!c~kSx8swGDQVMt;H1w*gCjs%GCl%!V z?uZAqH;(!rLI$KlzU1^nePsB-?vGh(Q+?rI!R03V_fvqW{;X?f6WYOLC7bD&IkrGS zXQSCK4*U*s;br%Wr~ew)zig2HS}OBxWeMYTkm9J034;0#Syi0;KFJ4W z@yNQ!S`*Lz3k412xE+c?B{=x#J{R#7J5gKMMig({WqJ=H8`GyF-@^Lz#F?25(#W+kfq*fb8riUvA$;mbbPF7lv-L1^R4Sq8>0l z-V5B0vu&0Wf;Xdi^2!y;X|M6|zL?W`wDK(D;Vp*hxIj?fZNr{#j@mYgKM|F2MMt-z^h1*SjV@ma6KaU&fA(vI@T#zS|Qe*Pz!(5IvD zyY}tIt26WeMjE_t&-2@e;hhKXSb~SQ>MP0AN(67$zLYrX-rIYxm*4_|_geuKQS~N& zSZ&L*vo~1C@bGj5TaMz8k;*KY>Ibkp;SFiye@4~{(n#IvVup62u zbr{}t-w7Y@IXvU11-lpz?*dc@QGFqo2Tz(E;|I;;PpjG%665`*BfR*Fa4{$=aNkGf zBW_MQHg4S+@=S^8o0GN;^y%1cf5Gu&$lve({Xd)0|0{nZWd7eq<3aZu5MMyQ|Cbvl zx&qIG#CS`NI3ONmlpGa*0`Z_zV~yII5f5q*Oqss3h71=cChsh2^MSYAY;I_BrGUNC z)}2?kwF9?$(^op2cHmID**>@L_#I^QV4XWv|K4jT-!ZwtbvXzc6zfn7gupJ zy$6x{>D19b$583d4$@W{yo)cK|L6X{#X)V#czAnkcPw_J4oFatEEVquk$V^IMDTvF z^}XWvLu7d3vWjXOhcA4wEJ?85nF6|_p|?v9w1bd}6{cg(b|C5bF58Zq_>Wj&xeQa6 zav}ICnipWUYBW+A{}H?P!#1@=FyrAZi0aTFs87QLOo}Y!17($LTn`=+LHJRp1d>DK^oKGeQ#gqKllG>Hr-Of!#guq z`KLF6_wO(Eca9@?`#tQNwI9J-(tOFO{s?9etl4xAGwG%t_O`d1qnzd32D7TNCp zo$&@FOvg)t`pO)4UAumi4`|!nYzEUxKJH{e!azr2Ja%)djVMQ&C0uN86Mt~nsMKv5xlodb2U)+-sbD>G_pe6TV;8D zP%lh|(_pJ$Ne5q8m~UUDsx<|Wntunigtvn&YEn+KDYn38+3eUu|1$p{+PV9UteOz) zhvv!haMePDHxe>0<1T! zP}lq22C@{5b2RO2fsmU{**7gS9*=G@ev=`LS<31P5=d@%c|RC^RxrqzFp-X^ld>^#G@iv6MVckkK|7L zJ|zS{M)T$m_;3C!j*s`kv(3Bjw=v#;q>t(lBdE_&Bk=Gxc|M?~tGQfMj2LfeyU}=A z1n-~`YxY*jO2U5*q{BDb-I(01W=TQE$ytRV{?=lOnf8PI}x_WaJ9^N7o z+m38T@Xj>i9ri%*u97|#brivSyg4yb)yNNK;eW%j$<+roC=8gA@TCB&UdiY>iFR<@ zW4U=D$qtC-sgL`5;txpcf`32x?j{7!NAvs_EvXv)jgNP2Pb?w!a_{H|4*V*hvoVmnuRxK z+}nf(?*|emMzQ9EEObN#5AUC-aT#8j%M{%2pPX~Tw$F&H-Se~03-_1p~ z_ydyB(@j<8QjFJ}^r1R76V!Jh{rCQiQ9dvc7+wC-{6IQ(PXpW9ou)8Jk5eSF6#^y!eX_{qOJ>hJuI&1ww&BQpP+(|AzzZLbGZ z4`M@Zkd9owkA&wz%fu`?Nr(q|eoi2HA|CYBWM%y>>N`lbhrA85ec+B)LOZv1`M~b} z8-+6yDL{1Yl4FutZJ;^-V_$8ZEy#N#yYaUU{(#i3r)F!DCj{R?^RyD$Mj|p!;0^-c zGhnfz62^PPzC(445!81kJU~;pkQaoo%{Jo-As&#D8U}aFk1hi{eN(JhHxhf$iscf| zIvN6*-hvx*2+tCM|r`!9BB>H)5Lfy zYSny;` zgEw8w7eeqZ6M>|ucn5@^D-lKT-Y!|DlgH%?pYFR;;CRsoelY>Pn-@y~^QKs{jy!Jz z7x$NMX&T9E-o$MPq`ulSE6~>_bWV1 zTaS;oS-e^Iu3e0WcOj}{7eReR54$X_5%;c*p55|kBQf4m#-ue@A|8Ojxi>_gco8=z zNv7O;YSq}7-n}_?(x)SK-fK_ikeTMhlm_pLzP=q8-rE+asNvy#DN@K)`iHYb1Y|6}OM|4(tq{J)>Z zgX(TLWl=qdI{#OtnX=<~kcx=cuDYW+>!MQ*t@1`Z=(hOnQR)|@mLKR{`b60W9ywB` z>pj;G9@!Ug(I_+f4TH;` z7KI7MbR3XQFZ4{4+synPltG`49lIZJC1=h&V)xPDT^lCuh~a(MaV;Aj-g?vKD_v%!t3W~TTE@fs7OEqQpuUmIHA)fc zyg>PLoc5)c#CRJ$=Q^oVUJf=lvfHZMBp#5YbY_JNFUn(jyc_7$p%gLuc6GuG-j+0Y zKLx)#FuV=!j#sVE;2m;9 z`h7YDm_Px!G9GQ9|DJDq3E2)DzoWDAQ!PH;qD3dvcoDp@yvW=f-}O!Sc)tag#C|Sf zJiLWb9j^)Mi&o$KWu*@<*m4Duv#BD+`(V+mRqP1f&2!-~on+zxiL~FdONu9l>G7sp z$J@SJYJZluENJk4vSfZ5hPScM%UO7MpPk4q8$j^hTItqF-JIZU3;uZ=!TV5HVeIey zKCr^4FTBzczVJJ-xCfp$C}8e+QgO?fHbCBXHE8=@I}npvqAFj8k9Wv*Ax)cVA^1F+ z_ozetqi_d4-s{r-kGyVC0avps;_R1M0dH%V*WiJihH65)K3~xEx7zhvV@wO*s;|Sih z+3hY=ygjdMG_XhTW>^23c|Xtx*3bReuw<4mJa~OXh&>s(z2#I?RbhM^7;-e!>*TWo zxoW;eN4@d!9&O!}7hEC)=b?G~V_&oSSK{McYJEiW?gz%3|A$c>#RT*1kx4nI36Qem4h*?s{BLDS+FR>^e5m3hE#i>(ESlVEpEDuhvfd`Jd0@$&m*YLa-58{|R9}iR7MsHNcqpJ*dKsE*+K|CBuXZW(Fi{8oV2hUKz*mZXa1N4-apP59<2Y z5WJ5U$$a-g@ILoAQ}h*rw{(B*t=xOwuwe-Q;WR*o#n;9-@2;W%xfjjs``Ft+TceNa z3Tu1dvDK*I=zM&b6yL$CT5Rxuvl+fg0!3F`YbXZBIC zKwgkDNJ%JABF6jRWbTSZODe$0hsAzrUBr0To_xOe@mM9(;~l=0J{=!>_{ZzKXRf!j zqQSdvw+(|Z0EmcDBDKsz3v*&AHBtG7( z2_CV+IgE!lC#nM?s82O@JKHOF9uUP>DjzLHjCX*O6ZaAX@0NzAwfn+|m$%5gK5`|i zE0`W{(x5k8I+XbRMRHS2Iy;1GS~|KTERM1NZYA0=Ne7 z@wRALabbQf^7R%pZ;=C}wlxJG@0NV6>(4JT9^U4tj#mWrMb0j_ADH3+4-b4jW5iF4 zcd46-|HEY!z^8ps(jkC&d27r|!bBS6G5!2M>`k8z#XCNtA1}?|eSik!_jZk6#uW(Op5whYse5lvzMRYwNAT|AdX?EL;RE+h$n}=!`@!*d&WNA7O93wu zzSRhWHlSIZk?wli4!GwH+NoT{$9wk$Gx0v;?kzVoPuJol`I|33-p_dXD-XLf9^R&? zj#`5HxVQ>+#I<-qxb$lE0f-pyk2MnQnF!vblJz=2Jz_K4 zg!u6A&N%h@fE|Lj))&Qel4l7)@UAKvb&2lsg5%3CNUmV@hu?n}ofd4P01FFN zqo3DXfsg39(={CqKre0fQOSR~Vn<-}zz3ZgA$UES=LWe6fN%JCOJuYziax}6c=Mw= z77)~TPew#;YN3FoABBaW;#RQRQR$S^O$RXeSztw%v@@>TR?C$h9Y;FI0W_~y zY-*zKU+}hl5PjntU_895P#snT^(9MxJeT|M%u0_bj&@4CuD z{Ph;srS-b{ZHt-y{r~u7^y!GyOMBezH?zEDOM`dQcgPyU`-osBHy++sB*;ZR2;O^G zJT_7B?(QS-DOCCEF&X~O*=8EnNCCO)x03GEA?|%P3P4D65;NP< zOpy~G@6vrg3YH=69fjt7hHrQOn#6bS(}wTvU6o=yyh~6WCkW~jzj96{^)e4wEZ!qB zVNQ&<`W~(ID-gVwhFyQDllqi+b7H{7G_j(F`3IyD`g9Zv6i-~ZJTw2>(BR!zqaudk zz0T`27arbIPx48j2;S$eym?LCd$V}HGBy#xn{<)oafORFJnwf$#L{Hs`+sI{_3l2W z02j%n(}kU_pfqhuTQ`>jm|n4mP2x6w?=4XrY3G2P-kL=7?q=_@Z~K?SiH{N-Qs@0< zy!n42s-uFSKAXbShaHi;AmBhv~p_hAr! zxBT1FOZbo2;SQ4Q?RP>jmNzV#Kf56Z{}IbGCqXk}GY@V@`hNuf_x|h)s)MM$l;l^l zPF~{$UmiHDgX)PrC@OBk^-6jrFbogcup)%mgWUAFcbKUQGJOX*zL7p1<<9zrH=|}c z$Rjj(x0yUTi{Wj&okau>Z|hGRzbhbkX9zz(PQ^Q8?$@Ie2;RSqd&1)0O9d@F z{9)_V-=06mD4_DP@~kCzla#{8(2as!-DDB{i|A>8~qbPsujS!6GWgig{sOQAT zdufuz4JB#D!@C95Ax}_W-!1Vi@|N+)ozHhX*_a;h zoKgC8>`P2kF#B^sniCD)txP)w+&|zC+qY>-HhiG~HJ(k<-?z5{FlM0Me8T~JU*gBpw;vyGvViV` zsMkX9IGVS;({6`?Fh1T#KR8bDO)=hp|Y`mcB)Ys5D)JQA1_Vn zB6z0`?T+wA@RoD)ko80GW((-_Z?p4)e+62<$k+FWopdPKC7&rkzvX4pNxN21CY}AQ zN&GPA9)2gQEP>ygNH{-#9s5=Y{($Cj%V^7(+`z}%xN)2Q&JM=Idl9N*3qgG+I&HG= zA%_!(%AP&FmPL&B)ZDv~KiDdPnT2V)$KwL{`Vu)8OI4xnwom1ifwjPG=wm-plZ?+p1?Yb|Kv$tp-M>KS4IT;`C z$567!!ve;`n-$eTRNtliB$3)rJYdiL=yR#b#CT6ij9gdP{}8;8{cti@m>BQ8{jB_Z zUWqgP{J-%aeL9RU8(c~|7WjAn|G#(C{LlVt$o%g{<3S&NzgS`(BxI?$2+xDAlxdlL zaL!rxbyuK5FycY!dnao6kpU@aS6211veU4edFVh6O8^}4O3-y!a1hvq-I(u`{|>C( z=c5tp=md6DFHcL3KZ-lAzioc<^&>?H-i7APi_lPg(T49qp5B=&TX}eKf4~3i59j~? zuX=;(@FJ)$AjDm9ml-ektoQD$q{I~AlKJ&bS#PyoJ_1`s`jQ&6=~!a_;Z%R@VJ_2q z5NVn|9mnFPe@KXU0|akZ8oaxFC!;XDHEUEB;^D0l{k(Vp!CP;nrZxz{`?|8ww-pH9 zTORM`^&C76mxYxkx)1on3U$wNj`I!z8`GAM!K!yaV3{A!P@ofdf6=1zZYMt8=97YF z-v1PWyU;wZcbV5dEyTZK=j7*G+D|zc4{tM6$0>sPPS!6DQCH>zb+#-^M!1OamK@ua zQl0(?1b752^jQC#@SlU_jR=bV78E@k@`DFkP;q#@1{OJ-a(|0YK=Z2_&S<*Iek;H=o@_ZK2h!Hw)iRIEpG*) zIy?yKyV<$wy&2L$X1x~Ku#rTJcU)56`CtTZHI|E;_Hxt`;!TQ6HLf@)%k+4Y66n*B zdREzeAZ2Dia-qSybEtIY{y*ySR^rN}`FMDXEp~+2kpZbTpX)^+g7=ox%@W}V-a1CZ zIZBS6u*3hy-kpb2)wU1g-<1lPwt31JnF*l`mnoT&iX<75vB*5nREiRcP==xzQ7BC- zBJ(^)N+Oa?QklwcslD%aAMf#9_uAj%ec$i1_wVTW=kD$~k2=r#+~;+j>skYQMUY#5 z6m-^C(Y}Cc5}a_Ht{?dE8gv+@Z}xq36ijWF$WSyw=3P)t-)uO>1`*;8?Ax-x{wp$X z{~v?NUDwEucRs!jUzGf2d#H|{e8>d$aPL18^a*`HqCb}+{7d>J5Exz5FJx>$<=wus z6|?1L0>y7mn2boPBUt$QTID~tw;U(pJy@#t`|}nnysKNBxsZ7Os=7164D;r&#~obZ zJ#OVYe`{s$%{)|AlpGA*zeumFekBTu73=x#vHTf4jQGN4%g_&2LHV_tHIIT9%XT$t z?~pHVo!xtcie-omBE((4+Y%=D3YoX!Q4!2DKl0-pkFNtQzxXRv=CzfKpt{Iduk9^5 zZ@a-86^~%v$9V4FRVg81?@hJ#oy}Z2#q-8clU9ePWWlIe`rr5e|DR8f{{z1Qyn_rN z>Otc^Kb#3W$N{;{n~-`?*o|V5Yw!*-Mel@LEZl=8q-=(xTop8@g*}t>^8=x?(o%Fm zFQXytj*-0?x5GS6Y`Wl?4v*Q1(bPUWwk`IC+kbBU83HH+HYIcYaH~Y%&OG%9{ z;!+~gDy4cLmiz{!etaEbDEZN=oWK78zW<+jT=8~@J^Bt(Ba&JxeS1pB4;a4zh94NR}cGZZZy1$)-F z#iTkT^WNdSRyb~%4I;#8IBx&a)Pl@=LrrggjtBYi*2UMsfRf)eZmiL=6B97p_cXrL z3Z1vzu|v-iVcv>^S1#1ml5jw}=O|r(U@pb;#_S`pj)++4!+#D){fKyf*YmeJe)XuJHYdmF8T4E!q+j1l3#sO`oi3PCh%CiRgOUuop*L|dC8N`mta&YlJ?{j z`sPHBcE0YFF+0U~?_N66>UfYa(cWNt?^jSp=dI^{@?ts6Tc*l?lUFhc@Bdqf+gv^^MDe^aOC;98!ptyk^Y{7x|AFcK z|NOUrdr&A*51Mk`BuwZ*p4D6uNIhuNfxU+g!#ya*!1&e~xCaHC$tSj1ls>G%16{qt||b?ipT@1>?;dv7`xj3%4w>s>rD88Ymc1a`sS1F!e@ z0X>0HT1deid{3(naic@#oh9ZRbd!S}BE$uc^klG@{0nbun$IV`lHU@Wjjv-jN`BZh zsC{!E7U=8v_!}gk^ETZlktqxFKJfAip9T#&Z;YINs}mIu0`D&&#ha0MZ^79Whrql=ei*{f!^~(}@Y71hxhQC2uQ#W06$e0TUNdyw6NrK0 zKHXYV2quAR)2Cw-U;9A*?CEC`TaJSY@pVl&8BfG+`)KCJW=l49s1hHy+Dl%j|6jf! z+?NXjgXUG>_oI zJ*Q4<4G&0FTgp%DGYN!3*lJz`(8NHGrK4+Aw@-rPXSrV;>0X0MJ4>H2+2f#o*n{b_ zJ~Hp-$MSc_c-Wx^e4I&6+we9!jt$*FId_{h|Tkv&Mq2%}BX+sX{S5{!j<+z9T z2s&@V;lx{0XS$bXTTpq2GT>_7U#0x7x8N8_tK+~@sPKiPtQFpYM7%$xv-J^pzd623 z1c^88%Qb!}FmF}vw}UHZZyWdZy>N$l?-f5BE)fz4DX1KE%^Zt{yjb#L=M*QwBL@ZL zMd8=LFLH6)8)rB0*5S(6um{MOw~kD#&Bjo(L+|i$cf(|bn~xxGP8QxuhuY_mA8$e( zODOq8ck4&HuEK)oEpu(v|BbV^GiQvfE_>CZ@|IDjYY$YoN%8alK|op^vr?`z3|4=i z|Nm$8Cg&fVw2E0p)Pug+2b2+dPz?>698wPw+#xi~5BH$+3cI`G;T~iMWdyE<2c&bY zqBCsKTSK{jkLCG&wZg2ksZ!9=geAzVr5&9Avk~TD; z&hiQjZo|d~QIjwrO0O)T zd#4ox@vq;@*m!Ufly6RCat-VQK^J}%&m1}q%GmVl`z|5#cIj#67nWs*2yqVIZ7K@X zka@>b?R}-u-Mzzzcu!|gpCRzRxXxG- ziTA4tK1nl}cgpi|t`*)z<~gVMR`%W+ZLel``$N2e(rkU^G0=n9;=8YRPl7utqgvr4Jt$hxg>LqJ=^np$BPwUaN%EgIeG3jeX-*pczQVJ9iH5LAJPF#=Gzm zYqwJ+@T$HyR1-BY#9pGvQ`zrf|AvANgqj= z|2yfQtqHKM0eXD&+}1hh^M9nA(Z?^Ulz$B}Qi`-X_{6R>=KT0Q|F0$Dy&xjtM&PX^ z)v1WY`!Y-B;wPB*Y?pHU3U8lx##gFf-oe+OZd$nN4VCXb7H7O88iGF5bIycLf|Qu^ zZ9jW^!Os4i!$T+C!NNJ3z`9e&yuIh@B$T(XL-Y8!OFd^ddY?n)-F!W1z2!Rc1;Sr|x zf!-!OG>A=%hI)%e)g=QaK|f~r%#PV!@R(=0RL{j7_!q46^2tEvJ=igK@x^v_h!AJu z7%r_?jLbVNPT|#=8S>jfzQNa#j*?%4ooGuzITo0UoT#XLfzF#lDSAl)=A9TQS~jk^8%QuO{OC{rpK; z0`I!Vnp==~@8^cwp*ePP<6GI(_VE4Jo1+2iz>*xwLJMdd(_#Xjrcf`9!93ot;oC+L+?IgeL;S_ z33Vi)0=Y3{KMDYQ9_BK)={bBMV`riAfdWd4hK^BVd-Wep; zk)^xZHa__8`9GPAp#Po*yu@z!Up+`@)vhMxl^(PXeg{d-!^0S)9`rg;M>iebL00go zvn9ekDB_Ue=vnv<(uX72E@GR!Aiwi^a%O>%(68Cbx86DMBX-lwLZULgASM5`%pH&8 zK*qE1@hT(a9b{|l&Rs=6*dQr<+_HGD@~M7r#QA@%WAuHdAo3fK8u4||qU0BTQ$Tul zFBaHIJiFI+9lZy=x85e{#a#=+e^h)a9VOuzq(wwmx*V2Y95iy?YG{@)Db9@>=KZDt3qvchn$0ros|=K>E3H zi96Ma{CJi6%|LJXd zmbN-sf)u~RVs?^N$5CPWOS^x+|38N2fAJRl^}aHVzs2V2IKRWk<>@4>+epSc8izsXh zph4!%)mk&GLC+3B_&A$pOG|zaWZnXSuBv=y`jj+_jS{2c$97M7)2NFNP3! z#~gD~LE`<;(6O!(<}D{K)tmtHuAKDvauUA0m6~v+IpKj9)Ridv;?3142orp6{(8bB zIK3xM$M-}pxau`X1=YBNfP(`u@@mMNlK`7I9g~glNk)jT^?*hoY`}XQGGwmQh z-hTKx`cd*z8M~9dz=s8Q5?MSP?~~5^)Xht;F6>0VddqzolppP+r})ju{&dpnuyWbY zvUv9Q{J)-v_fo999D(;Bd3%nO?OB-jf?~eE zoRMjbf=qZHRz5vF2`2TMBf4{X!Ge;g{;<0{5FFDp!TrnUEje+u)}IB~A%1*ZtWsT( z8y_<7Xvfs7Hfi$X&5p0*1WJDPrb4vJ_VD?CaPxb261ukxkp6HR?%pTH&5g^`Nw|8; zeQPM)fQ#aJV>n2xqlGO~8s2-;!@IM!tFB|{1!=X{AE7z{|M2hs$n8%6USgU4R}T_e zpESX_(t}p!|E?;pbx1uZ*1D~DFWiFyPwtXQhI^1*Q}#zG_!}fQ*B81Esdzze4nMm; z?jH{Adv7SK{d^LHyfEXE&*%a6H%(u&IC}sdy5y^Gw2+tB=itdQJN$`VLR_I~zwjPw z;yfK`$sYPE@XQARMw#&b`9;XcCCL@JKZ+?*Tlwek=?%dw?5XL$CMs zBl9-&IF-=X$OaMOMpiB94!uC;UHjSk!u~4quyAeSZ?Xf9+;M z+tUL+r1CA!$9RBMXQeJx)gbf6-npeC34gtn5O-Zgbzz|unYXb**Wu;+1P3pPq>KntP)91m4{0FIOY+E;2e39R~B>`0(Y#%Hf1`b7iVJ{D8EjB38ev-xFd| zvKwKXh=4xEZ9cFqe-ilEO`lYm?EztXZjM^*@BllQvp;H8AoG6J<=93Gf1F4MAD8P9 zF+4wp%-g@B<)+nj^5b2JuOkE{zra&(lxkX-fPcum=lUG5po^+F3cK!mt-Vz`8RBF&pY5gU{Z|;;u!MY(nSVE_%&KKP{f(dFyQ^t&Ynom?VSfzxV%>+o=Cv<^#|F zY(zbXejD{YLJulxGoeH3LHDQTs_5Y!6tVuB@I|->u~i!{kHGUkb@3+e9|V6(5&$S?$X` z733at>WgMlBZTzpU{;_>(dCI+9TG+fHL}FK-G9#$_zTk7c0uAUYcX>q{lI;3&p| zLuxPjEp~~+y$lUPl>hy|q7l;SuorXJyYuG~J1Y@yx^*Qu0`H-ZJR6XB+cg+x@W8xF zCw{)T0P~K@uaX~zc}whIpLZGag0MmBdj~bcAjRjYo}pcn;Fitv_-^4IpgM2#aLZ9o zpk>@vTHlJyn=|*y;>-m$h!7`ye0JoC1~P9G3H5T^Ci3IWimziYN`Ciu4h-*;V+O)! zS4l)%LFau<{tj&x%=`Tfr{2nY=u0eyuQdG8@&k%rVle_F)-gXKdgbWv%Udi&ylLC{ zBnZ5NazD`^@jh|e(^eej{p%}ay~6wCt_PRiz`QTlvPy2g?FBU?%NKOUgh9e=c@J;3 zOoE5ruG95eJz&D`wK7J{6I6`u=5pP7g^%~f?10`H4brPN5g-xX`|D8sx(8rChW98P>>PDtxmIh@Fp zt)sQ_f@W};JfmG_dFn1-kjf&S3s2s@JqnMA(+rg#M#```S zM2M3-T@B{#k$Ioa>7={9iu`!n;p;eul3(cC{COn@cj$T?LKE^jGQJ^v90^S*u^zI#*O~-$J_Q|&Y;6CmD&TpMbS{)T*GY_Nx%>P&--qgp$wF$i6NW`p1;;pDD zp}zy>y;mdqGa}X`yfU!y(pyxz&R&C&6WJpNYY+96sZa?`a-dh6-~NGJ zPi+U8K#D!pk~;}|@BNsggL3fMn@!lFWaVx2+gtdYQ@%h;n<##BqU1-Ww|6>yD_>3x&8M>Ks+(CV@MHiuft_ZZJ*#?tmSa7tjlpe52Zd+=Bw1 zIx!tS&Iak@xr);0VThqJq|KX3i=Mx z>uix1t9BjOdQvpVVF`T)S#VajPB!cX#rL2s38d9=(o@dlMC$JoBrYP}%&QIs5_rEz zWX2-#ZY$&w?t*#$GT(bY1?K(vY~0(+FmIR71>;9vdPBUnTN+;+35CiH)wg=iOoD~g zmOSQXyTKJ>hn>!Yo?z!E*TVKJWZr3Kj3+1kVcz&SixXqdw&o-A?#O65d#8Z>cqilQ z=tjveQQneW#SaTagTk}&Ncg-($BCcVMy)#V>&A!cj8{q6LB7cop1@U6Ja5cf(&|`c zx*9C~x&NP&h&NM1fINZs714K$NW5iVP)85Lyl=i#Fj?WPraoiv6y~j2+4^npvNz-$ zsh`*u8w#!OWiQYDJPCxp{%EAV+YNG0Z+Ni(i6<~ny|vEvU*6ubEi%gBV$DxLKHv$Pjiq~N7?31r=Q`!Z*Sos;>~!C!s4 z##as}1_cw3jKaM4rj$NycJ+qRd))5xmxe;d?y0xljZT8_isz?o>$-vK{#MC@w>;s` zIOG@i{LB1*E5YuY`B^rI5T_b(BE|h9GVhS~k)@ze^5dP0uOl2KKSmSTQu;+K$TQ8` zc_$rxbE5J3aE1%a+v(V2p*B7eZcYrmWAxVW0p-vCK_u4Ezs^|c&%=rAM7$YXwkHsH z2MGkzBk?Y85PGu=^9~g&J+;F7W2e;63U8-ag;CF8|3CCaW4}}Ee*t^+=;H$Sv zJ7Nnzc7yKL+XWpxo`K=*>_RjY{-xI zCVU-^DEa*=W?gbG#sb4^%#D^bbl$q@DRz95wO~5)IPc_R^s_fiW{WIug%0I!PO?a= zqv`Z5wc>d=n>OovWw(!6Gx&Qx{wjw7|4>EYRcqS6=K@GBJ zahKp8lr7}CSPJ(bXWByo1+hMmxNPXH?vW5^mbc7GfDH#`*0fDrXzcf89nHI*1Bo{$qo`d1%sb`AstYT;LoU?|T!ndC{4l$D!^H=BF~#;>`fCU@9>3td zpAiSTEd9b=rn|s6>sLwBX)j-db4A7hTt%ermMz-DP?V`&UJ?^457_OhRK!2DP?vmkW?;$=TV3(UD-EVFS? zh2jS!>QvI|(4uM7Dv$epd21sPZ}w+mfWX`1P#YT(?^Bg;#jn7;#d=wlS9pirV}B3> z^JdC5w{g+(feaLOOi`^3g=n8(PhOzGfk*fBgohcsL3${=M=9h5X8kec5*En3HyEy> z$}?hvzT@Lww(&m2UPk6^Ji^N*Mo)gcsql5|M#<0rb9woh5G-g9b9!aUpbtZVNf4B0Q0tM>(v=z^ntc~^!)6@8ww?z=Fxk+1_!>Z6Zx4d+YJmp z@7>pT(+dQg$eMlQip;z4!^iu1j%-j6K2EgGT-gWy&w|j6{`Y?#VLwweh#^1TH}Q2i zqU7gf361ydVFtAQ_IEi*_UI z3Cp|5hh;;d5_N$Iv!ikjLo^nI%w%pHN<{D83>V7YtH8W(b^J(P zc#3}ZhB-G9|Hfzs#q-7_kXFa3qZ{**;H$TP=l}nGAt1wlhv)xIL_LU~rP`d(g97Iy z_>g+glH|ST%5V=7*3W&F4)-9H`R%cE@DrpFXFqJ&_Q(gaX3{!f?iB(BZg#U~lg9y} zoo}}*%XEPs-5sZ&CV7MKXX$yNvdBHixq6E#Zv`tvh^tK7^gs>1c8T;SD3*`e=p0Rc zORPP<4k?uU-m~xPUjx4&EfJ$-Awt3>_Fduby(%B;freXkRmThoJ*X_)u6)aV%I`rW z)-h@x!3j!!&;P zKmsRDUGp9J_LlN9k6s&mWQ7QEd!gv>Lo>*{_vpMy_OKy8-Vg9~n4#o%k5BsT3>y}7 z-5qniPQv`ZQES~7VVL)Kf4N)gg5ommU4*1?hrBym?}F z#0E??$G;(hiFF317qUCh97BMs)=r!(8u0`orEb=UdU10QJToRuV|D+E&0K6dV& z01mKk3f<c!NfwNWk9-^dZyIw7c10+kGr~8VaS35dH%;H#w2s? zCO_Wi@O7}FtL$&dH4@t->KQSz(#;(zX79v1kg#0(XLqVuM%f0(rf z<~=>vi5a3rzk3TKU?`SqszC9)F@hx4(RWu${O|k!kVaMV`gwT%7bogLA`I;DgdW79 zA-oBx2W>KV_lAdXd1yrNSTi28D1?fw-?iY0jHh^naXX4K=k*K(^7YA*P?{tDQGb!Tbjou)0L1XKzV*9%ixBY^*zx)%p?h~7h!D5u^PI`?eq`R|G1|%ZQpt}u4Ze=&DEY-Qb{)2Siv>e`>X0!BueVG!;#Aau z&)!B3(N4UNt4HO1dV%J#z;(+1_I4_XbwGjcAz!2ae*f>E_D0S>faiZ1q8=nk`~9B- z(ofog5=cF$q2uG3EOgpQ_nSieP!N>kV4+I>1YvoinVSKEUGrP-(vj@(yy!#O12`Gz(;jkBc+=buxv{1M$DLm-Te% zeX?v2x&2Xp#@A7elHYzs6S4bYOyEgaY+(=yUyxo}?rNWCYy^9EJnSqyg+3rf)~m0M z*jY^ZOKcr!b@V)ccYpNp?_iZA>)47u_4$JgP3lAp!YS`+6NOyEJZ>Fx9<=sQU0 z=KBpI#~Z=p3eTJ*cl66!Vw~UJG73`u{6D}!S{)hYhc0O*{^l)3#9QqC4i^G%eSwkzzy%)!1>o)z|inwx1Zos|^R8$5Df`;J5xfd_ReISj#KL& zOZ~ZeD@nwAvu{=hfw%CtQ=&+`e}3-~Zi0EAx_A7*3UBTa$KEqA??%JUfn9n&kS=Zj zQnU+({2uJ%{Aq~;>qS)JC3kd!wXBAs@n?O&jEpEa@IIr6NDx`uIAAQ1WxSb*rSXjtP{7-(LNNgzx`lWUMXb7;FHKti^RaHlW|$ z5-G*;V3ULd#cxg`B}uEJj`~OF zx(K~{=N04}TNBg(UfaH=U(`h3dn;CO-9Owz`QP47C$SFO)26tv6MygjC%4V|f0++F z|0@vnAi3`^j0io*J%&*ZsRx_sSd~v-yHap~oIMDD_Z!CJ4!~#v@<4S|4 zRioff^Zu7Lz(2WzI(hO6{Kjdd|NlSr^W6A4cB150<+L}}uLBDP&ld{Nze4Xp+g#u2 z^~*JZr^3HN#koj0K?1k3-QR0c{1S`NB(aWkqXR47Acc9$6Y-XPRlAnJJCXaX3=;3d zEgpLh!@Rd2;i%1mdG|A`X77M`<9uh6pB(XqmR_{)*R%|R2Cd}0WukFF(IIUs)&!pa zWewMQ==p+2A_6+n|MLF76a9*TCAlmRA+Bj^FuN)0I3n)`jIiBuEcx+{#MjY;lHcb7 zk36IESm0C4jgcbZ6T4>9JH5r(nn10B#=Qq6=sQSE^(0oKrk?V7*N|4n`UCdVseew8 zwh-}_NnBzi@Sc#mBaOtnCX&k66Xs1fY45wjyVPND$N}bU$rh|qamE|+7RiWhj0l20 zUs+ZP4#j~A+h1khygESZV2cwF^aTpRc#b5%HFG_^^Y(yGT7;3W>L;1oN>7nD^?TA%PX%25Zk}or8HZ zcNeLjD)EMJBa7ah_ktisBNM&H{y5;+r+Th0r2`n>)9_?q@C7V>=lhQT%gu?$1brlv z8(APWe4IC<0rMpWyVDWE$qdXiA`R}9qi;@xhUI+2 zVBYx$2AnOj(FY`qi=SnWjv(cCZ&K?x$$T~A&(~XIiFixNeYi^CT_wI#5{b9o{mkzP zFz?Ls`)XDWCw@h4HuQ#hW47JlxYFbel}|Pai@pkiY__bnnfHXx|CKiQhnIJNXqAID zT#tM}=}_dcv1sJ({j<+r@8xS2=pjB%D7&z*mI|47Z(rOOK27rDy@0QyA0@wcrCmaA z46wjNZa%W^B|7hQ%yW(=O^slutFQ*k8}w&ym%_&}!wWYko_AsxX?57wuy%XFUvK^U z{QrMy>ilo~zVLvgLeztlCZ|&gJ!nJxdL^VDq&mqILIwAr=9=y0IdBiUBi>Cd=?;H` zWOJhareoev@tm@%l4v0GivG^K`dl0^)8Aa_<=YPSkKWcw^!5ey(q>gG2FUaOp29=x zHa0Osb@;fdS-H48A0Hi;Z>9JiWa>g%9akQUK*_PcU$LW1#Cz-T#qR{()y6*+ zk$CUvPt#?Ec@I4mbz0%=cxX&M-%UX?xk0#t*V-G>FB%(P9Muk4yiz2VlmS#BUbah6we!jBdv~Z=FDT+ zw|}4iD-rQlOl;jo;H}4UM*)d9uLbvlFwA@8XCdza+B7h4iAV#7N<(i*$k{4p zIxG;%v+#Xcn1%yavW%HipS1(+121OoeewZgjyDb;SdGkE*z)_Om`P^nBR_wf0AB}MeuqUy>g3*F!Exc)h||63yo*I%3*mH{Kr{`Lb}R{RZ&@xn zcqYZml;ZFIk07xQ$BeTKHBrC2_f{g_3by^W1m0`=g5;5S3vKiAR)Be*jd~8P98UDU zQ-b8+2c+p5Q@&r8_l9PqIG$EM3WU0QSYHcXzyV#FTl05^+ChE!7Tb@HeE{#QL*&5H zF~q}!Nc!xMlGQ8_H$HA~P1ObNv&g)8Z}izN!0!wEZ*0r{M?%B!b!S&Bg!?0cX-Mtlwc*_d~ zEE9O=8LMwW;$8NV?zA?{J4;Q$bA@+D8SXF#JpaqP32Su;dPASOilFNPLC~e7YtEtP zaKPM7!H#KN2bkm&>&X-M1q#ijsun+yySFO#I?az57Dyf+=f?h^NvHt%>}@gwW3u}x z`SDi4*MURHZ{nWkYitS@oMZbC?bU|PJA1(8#W;NSR@J|FUM>gy=EUcjQN!--TPc2X zay*-~IvVatiif2BJ^%k7>EZvUzX?45s}uDgwPCaHl^(QySlmfJ=nw{}2T_ZttuJvc z&}3dCZgLIoLGeFiUKGLezhSQHGF5>O)GHXzxtlQ%QfZcxJp2NF|Nn&9h|K*q@J^(- zAiCcd+-4nW-S`;Q{d|Iw)&L-$$P$!>}5!PgOqlArgU z{$XGE{eQ!u+h0eVq;T1crX}AjUlmd$HL5k_5)e+Q_ zvFcL%?FtyMA4TdDnG$|0;xe>l?`kTl@Mz zFJF(SjL`%_5BSU4uRexvZ&@3v^1ZJO+$bnjV@vl1Ph4b~#ZMvgKJ>1r|C1*(^b{XQ zuT4WGIE&1?IJ~f{{3rP>u?O*W+(XGP(et>{8w)J3|0p-iqKeL&pDJ=H3Fh5*CTBY* z9r_ZBx!SnKWBo&l=S^}Ql21~%{JFhFm5BHDbH}F$yxksL+=j&aNX+dEoiOkDO1pv; z-dtbSvE6}r2iU7!YnJtao+$*SNvsQmFb->T-k0FO!82cR)~njVbZ~FqETbQo;A;$Z zvq#=R3fdRm{cxHYBE*G@b;q12J%-rTRz2q)UYa03-u(DFmY@B5eszrwF?nH zDEzFrB-Rc>)25H~jrxMKjPsRi+>m*Do(r~`zQzm@;_km~SFxT%=FO+CdM5of`SCuE zuY(sQzf%u;oKnZIAkL`Z)B`4T-UDN2tt&K}!6E7`&goR>UvJr;oFF%0S4{D|t4OS4 zeOattP5AH2Tib|utMKOL6L^P`H-eVTWWOPDW217onYQ4=Q%_g z^6L;+HNsvUV=tWX;?Z8p-<%vKt&VUeJ!O@Lf9L;y{{G4N2k`u_P1J+5yQeExdeF-J z-)O#f9a0Z^Vl|Rs2lpT+-;M8b;U4r^?PVzrK0(rFcz%=fg)ijH<*9SgJP;aN{lbRs z4Gx^st2gT!X$4Vyj60jI`h$*ZPI`2W$UP|E;L_y{Cd^PLKCU~7|4GRQXBd!okS8zRl{wN&e!P$3>xe5f< z`$z5O3KGxaQj!{{v}{2T7}AJS4#gO8C8l)Fk4q8L(hY;BCM?y#|T*UZKaF z(J=2-2b;B4c;DSm^W6sK?PuSK{V3xL)oQ(6UZWTYWinMBxZZ{XIl6**2UOa?3!e)I z+hYB|-88P<@>9r{x3tnP#MnhML;3i)oth6`P(MNL-rILGT~w+eKi&XehcZfj=QR!| zzJ$AXsE(CE;eUhoMxHCx$2>{6yk#4>Weuw!#SchJcBIt->2k|&`qRAu5pS@=PwF4u zW)-WEc*{iO)Fi{a?FTM=Svj0ga+5P$Ih+U-(mp5I=mXhXu!?S`PygnP&JPE%K%>q&>_aem_iomlF)xI>H(l7#pWB*Ac)dl|g(uScZ*3#zeKJY8 zky?kZbEEK|tG60NyfxV1FIwRD-k0){Rw3~g+p2LP7v?QiAelwX`!c4)2iNZd6{SeZ z$+8DRCu^5B$h^XVb*!Hb-8|C<1a@AraFp@`e%Y4s>pGFUH(lan^lC$9h!B_R9LVe6 zhTOfoaXb^cQsl>b1HO(9l>Bl)Z02MK6QDa(uW`y8op*I?jrR;_1vZ`g@+?Vsy#>aD zc2oRqEsEcJN0L}ac%Ravrkj7~f0A0pe>w=B|92AgApJULT|y6%xS~&o)PwrO1I9MM zJt)MC(e^sL#8z`Y3Fd=uvD+S~WvdY82iafVvD~sF2+D04mhPFuf#&YcR4ukv@WoR7 z*eHDfV7pj;>Cggl4-$OC_;J@OEX0A2lUr56W#I3Mc&+VKf6?O%Lk{Ra{m1#g|NewJ z(DHj|uX@=GenA@cKyTHLYV;oT{k!~n+Ll%zsx4NLR#%Jo=kiZJ(SaG`_ev?g2Vr7J ztE0AJt+7J-?-L|FBHlZ*Bj^ddFIMqwK;msQzV9n9%-d8R!@9ydaWGvX0_HuClK*tZ z3Fd9@dEy*R5Hz>(>2aH{IPmNI#!*FhN!T{^x}T=QADDay+@L&<%=;P3;ftN`v5+Y~ z?$gEoeEI9hys4HEBq+JXUT zm^Z83&DuPe_t~Yj*hQH4%)zs?4hDWukhNTyRdpcb^SD5)cM=DNKkvcuy0(H|hx}pT zY=1C3I*}&$FZciZQ2Usxtzm{f;NvXLYew!KK<2&0+cY9Uiu`zcRbl&f#tcn37hTf9YoKswU1=TUS41dsf^<36oUF7*+ZL}lxx)?J=h}$-hvno#oc|f|b&ud$% z2>J2ej;|vbCBN_XOOEaAD~A&^7cW0T=Y8dN7(4b3JpYG$wiHN2=e_Bx)KGNqCW_yj zT>M5_9myksyKi%!TH&oj#9NpB{1SopX1&DqNW51)?#~s)PJvJj#3X+2Jq~=F647;g+6s~_g>rXp^9P^&cl$_eK<1sY)y{re znHeI)sVJpGO8}X-`f9aKH!AYueF0yG8cKdHe8B@4bNK%MYdIM|OVD}CC2-i%!Mxue zi*zo-k?`)V4FcBs{aYxWH-?_XI{Z8sR^HzF_xb;SrZ4jS0o;R(iF%Mp>*Za99whhP zh#9E|HD%3vl)4mXO23n7y#e>2{ozXbHZBU9+#lb>q;K?tw#tl6)b0p|7A~v4RAHS0 z=0b~x)`87nN%(xTXkq}67{jiQ-GV$IdF4dewr#~iGWfW4_0?ZvIb0Cu+)Uk7E=RAC zUk~!Y*Kq|UKP^#dtqeM5z|Qb9!FU$E2T|$PW!t=K1MH7fLvB~0FR>VI5O(JFUCQr4 zq}EX#o^b8YD|U>Cc<)NAxk%uBxtI})#QXKj{^?gR@7t@fu`9gO?lCTnt?;H|J(8&7 z2d(E3?7hty47HdD9xY{<0#;U8ADh~mfx={!$dR1^pgito!OX^mjs_0osB0y-ii1+(DGZmA?aSMCKilUCPd4Qp!1%8D0s{!unkBgUe4y? zLZAOX6z$%B*Hen(=l_fMNvmW1q*3VRGr!OO4T*Rg+wMvx@P4HIh7pPP=1_jaUYPgB z+?(nvyhTh8x?X|bAg!eFL0ZGj4=T=7&^SIC1bt{LF4m=)0(7^ZjII@L0b;HJbbibM zAVvC)kfb6q@AACuipgGBC>B=?nv z!28<#Jq9G+!Ut*-$6?-qPcy!*T)jPWg+uZ@{D5@lsj@pX>3)z<`(lznK@hY{BE_(3 z%@pW+X|{fAWD6K??5_Q|><=bYV-y-(k$D@WHN|9I#6r{fINmf}dz*S>-d=p>o-sb; z$6Fs?2U>nNGj4x$tY88gbzgn$?L_B&DQV+&d7(DYbo78L#{~NAE$_Y`&E>4;rufat z(i~}ZuyN>?>z@04IH6C(+mPmd34yoel~eRcynV|qK3#x$hnO|qUg7=2W4CrI%zLcw zwB^Zjevl@0FAFXt2r7x1hfIFqfUn}^&Z@2!aD@7`(7Sv7fMKhfT9gqoZ_Fu{gZX!{ z5EDMmsLau4&oDCY_qo+a91oEnZ$cet`85@+JDIl%3w9<;m5#Qd^FFhYvu_>D`&LJV zhu~Qf=KnOEb9)CxDV{eboy0n>=go`!o&U*q<|ob!p8xj{^&qpd<&%US^pjPQ6R8K$ zahlZ~gnLkvckK3Ca1ToCj6dNB4@fyL?lrM(^@T(ZNsP3~hd{=2QM-T0Oo5-JD&Gal z8bQG>u(RGG04(?Sv=kq6MLe%B%P8Sauw;VP4*ZF$$-_$DqIW`^|D)6*`z-F0Uk@t5 z*Aa=5pP0mz%a3TVAo**ix1{s8fE^iMTYUtX_tCkI*Nz@c z5C=ZaBDn%1q=3xZ&Q{CC?jrf|cEQ(Si;^EtRm_*mJF(#Qz%GF_IdtBN?c0l$SGR-U z1&hPyucGfDf!3R=wGwg^KOnu(CasQFu5s=i7k=*`cN6j6d)Qzrf%kis0X8JwR;!rL zM8LdrIS$@g;eB6@*Ki}ud;5;$dm5*Gp$#oZwJ(kYL$#{on|(J;0T-d{q0pmEU>q9l z+B)D5HnW)N#(N_3X3)>LnsSN>lEKH}429aZI3n|&sBAD__9s8yboe?xq2#A9Q?R6Z z8Vf2sd&*`7(RuTokl3dP^H#MKUa;XMVFy`x1j23FO7XlgFG;K;H|l}dpBto2h zr(oX4gBq8W7kr_-1=GB+vi=__)t$_eC>jka^Qwxsbo9lKgmUODkakJ7MCX0x?ZXhu(5n=`_iiGwj;f!=8fw0O@Bb&vYGnOSxCiYg>OlwZ zYe^H9Sj(+4d`LYAt5>@Amoxl=^dIX}Zo@rDvNOj=3En|I8YyYiV!bO zs#OD7JEy=ic9zCRi}hgjF3$#o8-YORo5QHRDe?~T*x@R5Ts9*lijQl>@(f+ufD0`d53pOLmEF14|lCl9n{+ zuhbR^ryq)5gSW@fQe@ir#_3ZBhQgb5Smf;3r1m01$i@Zp@&GZtmNW?hQsO==y?>Y09%1;2NYW<YZ`UI=tGKV&CHV+!!; zi_O*EZ2*#4RCGDCf#68*r_j)y$h>!zUE5nj#RNIw+n{Xcea~h&C20KO>SI@GtB$5^(wK=@aBZN?CgZG5qvlyW3-KF+Z0%(DQD|M)d)^b zF^XZ^13;jY!|S~Vk$Fc(2)*kSW`aWTaX09{$uSln^Ujx77&!8Q{CJ1s>$r=O-|_s6 zEfe(cfHZ75+ir`_`$%mu=cddyP|bVd@x`aLsJt;l?^}-Fctr8MG4DyM;{^4yf!vVa z-Fq()Z}W+Vr3BvY(au~*ymN*vcj?2t7b7F1R(M+*g85LGcS-LH^)yCb=vpc7XoOh^ zWObp@Q9yADEQqI14p=pUwxz504W0*pWN-D%<_pNYRq_Qx<##YasrWb_wL|ku^T@pU z+2$ET+Q^T$621;Tl>EMJI6kv)01MoYKJzcxfzCVlm&wP^V{Je<_-3W>FLd5n$+!03 zgvu#?{#Q#Ot&Zy_XA3n_|9=0EuzHjAKjHb`il_(K-R<)r^q}qwVw;e95KDyffh>6b zznmK|bO-K1spn-fzBnmpChXoY%qZ;(={@dU{<$U?iaKvFo@p}$?w07?Y0|C(!rBj> z<*p6_j+G;qF-Khx=k@jd`32fr86hWpoHCUz_a<%!#HFNHLO|n^5EtUF_n-PZSc9*l z9VNf_U-PSz;7jc4DUu^eKhb;8lb4Nldcp8LNXsks7;(HK=mBczY zrDzrZoFE+};%)1f`1=b|D+AIGm02Mq-g9yl#l_n!XaZSM1Qata-OQh9tk42KlHUIYx(vpa`jluJ5Lie^Cs}V%v-I``WUk&q4 zri!##;mr{CfFTd&ee{D%EfcFR^u17wQ@be`N*AaMiZh=Am8(RJTxRQl#+2alC(R%b z1)WQ2P(kMX;|$H2PmdU(llZtBqF49Rv>@|7P_ajoXNmkSZ+*enVTO`lhsNTnP!lYe z?zRlR_yL`_t-@oUXJKuiQ$(6$Q3L(%tq;F!-|Ws4q4)ub17k;09ot2nmrwk;LHYm@ zZ)>()3;*zzN)$liy(jB|S$9BTWhXjsPQOZ-5}3CDT~l%Qvl>12XRyUlbiId>ElX ze4Kdwdasyu$h<8~D?v*e`H8*qxwM`IzP%-L=DB_$I`6uY$B9&KZQ$dY zolnbGqhGzn=sk{BoqJC4n-fy&XpK^RdNA$p`Tsxdjhue~&;NErJ;*72-C9Bqf^0b? zkb02FqwhLea1Xl3catt3?m!(K(1E7Vysjl07r$9+4 z9lOk_8X#{Zp=ZV)4BFy8s-=8(Mx589w$rlnf1`&w@o}CpADDUBjvy{2A6C;Dlq8Vf zfE0nRV*n*Tz65nARSXtb?x!|7{}sIl>0fWWKGfR=zFxFloRdV~L6(K)s%vKyQ+yAy zB(V+^`K@c!&i)>dY>9X~dWAL-cylyPi6QZh7IC?@59VFrzpLXe%sVC3WQiWWyye(_ z-K^=kWi#b&( z_pPaeM(as=#SZr%L(Ldcq=aN?L?M|n zg^+~IWG0CsW13_NnUW+^)7g5)Jz8Q)j=fbA7IB|MvO*uJ8BzKHk4q z|KwTsrTck2y7#)*T6?XBw_C9BmXuUF7U|4*cn?y2h~VT`EG=TWjadLl7Z@9e(1CYm zLVU7eWi#Nv&0E}8OUL#Wt#LEbhWWpHi$JH3Q{ReM#0vgY?|n3QJ3>BuDBhorhRa~# zeNia8^9X|XXwhXm3f|x#r(pA*oU=o|=KH=FVp z1R3`1*moot#L7D!mXyJ6knFPf=F%H@;W%pC{w>i4mzQBrZyAZy4Xig~JiM)`KJ;+% zV>zVq^HZ|`_yB~QIDX<+?~Er8hc_aN6Plu%b$m|ZH%Q02HL~2+Y0mq>$tayZhN6#* zyNCVR-eN<8_x`r{6)4^&r}nJC!h1||g?K!IcX!0JI0bLV5R*BJP7wGxbM|46J$Ch0K6{t@!w+6~jv5zo zvu{dz9J_jZt@+dxvyt)eUQP9J2q(XLx=;AWm;``9@96PcKj_E%+f(V|J#P5ZTbiEf zKSUp?%zM1s>GbhRXoIkE^uPT-Be(tk}GOKNAh_ z*~A8efz6{&M;n|m`~R&OO(qqE-0%l#oTbOXOTr!dG5deX5cSneQ;b)GworX6#mTRK z?~I;M13#E%m3ov-AZY*d^TGJSnbax!$-M>i?w%k%`hj1AUbAlQlwdEM_cbVxojxC5 z!=;h~{w|O@(ctaot8fg(dtcr78Z5lk%AAtEAb4+mr}UXJy)|kmGUSBd?IdTQ;2G!( zUkRRQcvj~RXVhz_GaV;`-F#BzoeLfUhwf=T7o%WsQ~c@%xewTQ?<3iNcOB-2?@;3o zY;4Nm<8r{nd-x~6`;RWh!yEO{kCPw2%@X-nNP}dh#ePp^4*wA=0pIm~hv3aCcEJ18 zg$B&e<)8l@eItS2_ms_hyb1ku`p_rXQ;yh0s<$Hz-mdbO15vyq9v831!dvi?dKf!0 zf*i~juA$&9muj|O7{NPLMwBE`;0wpxV4Z{41;7H6NwwXPWU%FFduxIBL$L8uWwGu^ zFi0C%{;jj@ApFnA|3AK1GkA8-Gi4t595pUp^uU6X$FT7x?a9f|ea3irucrE_!O0Jb za!eSw&kv-Q=lDm_vAw0E#%^f6RSS3_xlhq;2!97DL9dKg_{;o1-hy5qpQ{aLTrd6U z{~c)XcKMYmi{c$C8m54S_xsFC4x$L&2FYAu6uf5}7bg}YixbS5o4i~*ePNBQBRfm) z1;GC9o?3aKWMIK34XY}@1Izwp=IBGp&Ab*#{t_jnWN^g;9&7O=_vxBveigCfS1$OzJv zrUv=MbDdWv6<%~Ikd{eJ=ENu@LY(b4ny;^AZ z@QpoYBjCjxP;O)|g8BXaQy)I+!v!b57l+$!^dOJe+bmCn9|_|3{~JF9%9wh!0Moky zrFZM_&mbWb_U?XnvTpv@pd$Kwyr~;_yW;N%@(>N)-undqIYCNr`|EXBcyC$wl_eFy zd)3s7AC&1Wp}Gi{7sw7$>D*-*!#{lBz9%b>+FbR6qaNv{R-7jT=-l(SNm>nH?CSoZ zokv4}S83_S=R2_R?%Lm!zCVo%M&qsrY7dpA%AJn*zjfw>XU2MFU z#ML@vuVy^F^Qb-qaPnKNHY|5-u^JXk7xMr;g28*uDq*z z)aU>Hf4Y5m^;@0(dwa`48oWKekKRKEC)>f014GF4 z)}fAs#)OY|#wD)N zyyGok$MF>%Rl@lFzw}oR#YEAy^L}trG)Z1WC zzk2AvMV=UbFkup<>j&ZEjm)|D#36Vq?^&j^pq-BD{e+mRDgIyZ?(I|hd@K&VHk)zm z-~RtU)pPzY{kus2?@3dG0>h*-DUVooLi%Thx*(-Hca*;;BANaq<(n`mXf3u>hEGve)j~ zieH2DPG^m=IJE$U!`&sib#$yCJskZYb@#uZ|9?cE506&!-A(C#R**bs@IJD$@f13O zbo%^Q0}F3|=3Rbk5WERLSf?n{TMGvFIxa@=zSbhFn<(K6+dRLyP)^?;_OBm{I$1&n zuXE@0jos=&E00Va7(U>_b+U`c6adv{-25h_?jxLFexX*Za zpQQS*#>tPr-hK(^5<$>8GT2_KhL86}_CyJJ?-t;rnW)J(gOB%@9)}y>j5f^s{=dAJ zJ|Db`{T@pFz5nkp4c-BZnDbD)Yvj(TW8wYg$+Lnj2;P+&it8zO4;ExUmqYN5t?;(k z!Qu-~6#+mV|)3U3Cf`s}EpS@1u8yHvWp^ zg!8F!Jp4*?pM|k!Z-thzaS2~zJiH^RK6r5QGxaX1xVBpWWS(4Gcug4}@1KRx_c>(t zwz@l7>Lwkxw-CN6gesq3H}CPL*T?OLi6-Zf6(nSE;!cCNANg20innK;iy9W*56reU znj?7k>bs>-@K(|uV%mt{9idRObg0({4(eO0ua@oyS2pG)oXsPHbyi1RKgrw&u^E>t z9I`_|#w$o~MF=+Dx!GT$F1+D{Gts!U&)teGvGJC>+`Me!BIDtGiRwcfC%^D8^VW$o z0${M**~?iLAMaOo;;~0`T0qIc#h)xf9`=E&T*SOyWctDN zb7^9nIb<*rcMW=W>^?BOQ8yT%7Xl9FRA;2bV&lDh%38HSkPAlRT%TG$t&70MJ9vo* zb89f;;k}IN!v`n7lQX;c<=O;*TijPoPYHaykCxr-IfdY@@2dDXYB?R76NRS)b05wB z=`8}iK6c49u0%E`@*s^U3-L06M}l(;n;HtIZHrQVcg=siN9glmbol7Y0n(olqz?_=q1+#WP`sJO z$xK*y4{E8;yhZSC+n{olg15@FLBKNv?>U3Y;>>toxYUH?As!I`H_g7kbhCyGG8&h? zIs5q@$Xk&k(HDs9AdSje|Lqz!-nVTYg`5pyhY832#`V~)J%70m8}E4bs=k%cjE8qE z)kh3Yeiyg(ZCUzU0Bqgr*&6SLkN3NogR8%0qFYWyJs7f;EyK+nU^X@v3ds*W7j;UbqN&n#GPr8nngA=85ud^RL zVTZ@5ac4|T6;qDx!>rzsBg>c69br7Y*HC?g;N+Ls#1&PGod0hb?W3x@A0O|RkLuM# z5WKgZ{o3pP5x@T@h&x$!0F!x-H$jp<9}d;)_gUursoq{Rcn4kIv=GJHVqp>y3vc#K z>v~y`{(qC%nmrV}S*v4jen;@`Klr`3Y=b=YJb{;2JFQNvF9^G>UTKckJPxhk50R@7GN($XV#fJVAf6ISz&Alu$X-?SE#Tb^AWpL zC*y>!FDqT(dk1>WaYuu=szRKKpMP{sRp^A zczHyegyA<+}u10-UbdDTsx3g?1K8sB8v@tVN<=)Y0_)}yjLMB@W~T0 zxJp($@p|uFU^{MMuv97pyxaV;ZeS}m-g}nAD%Q7H;UQ`q?=h!S`z~VR-K2AmMU%{U zk61&hk0&_!ZE}im_*upe0vCLk?o7hR+iG>rGe-n(uG>qq7uDde{}bds3kqM-ocDOs z>%*q#oB>DPpAqB{8oZ-e9yOqN8>)?PVBsBghqS>T!8?+vEsTOU(|bvl5d?1;8_hHo z7hiap6(LIfR{-o9TqyPVAsI|w+(o=CLIO#vv%|XH1%uxT4QE|Eu<=&q&MR_ZW`kK* z|BYMtRL8qz92@T?(=x0J8F2TO3f0FVocs>e*W^A86aZ2WJf^Ep;p5GpP%83sq6IWx zy05-x5FhU%nW9s9&no6U-p}atVQMAe{NnEm(g8GhN4AJuL-Fo%t7ON*+of)~@ks>l zJ1nw$DR}cvcaPjfHb@s&#@t#L?F*laip;Vr z!9aLvar@^SY`iB@Uq*PCvcY21xTNkqk!m}!7bn`5$qx6vWW4GMz$Mh%qXrxA(r?XH z*B&q)-f~nQ1vvSI5RFc3n&SsN%OIY)Xneed&Zp%BBWrIt1LY2tp${;7613+iJN1i` zuzJh9Uz}*6)5r7evup32`gi|7`txV#-;w@5oTdiFIhq-vHAv;%Wl|kd^|<+hby`oZk~NZ2Bw1sKl3VT!QRY< zhNR|D5E44G>U@wrX1}gB7;kncjs=dS#tFus_wG=(#QeXO@%VuKwh6}T|5d3zF5=`@ z$u=C)hm0VbI&4<97vtBUmDl+WlM7n`U%8|FT2=g4>;^C8?aA3zKksYMc{+W(6x%$g zd+JaBA4Y@s$@R5=Ua_NWZwad96Trf|IQU!McLeW7&vPaeygMQeNP8oA4|24V_+xzF zne|J>+!qJH>Y2itA{}J#jsMOiiO`!MuEilfD<~AOC?2mrc?lcun3rb5cCT4rPHNog zM9!U>;n;Y`N}FFl+|PJ;M^k;o;N)k=D;w8)l^=ZN5tAkt;Nv~&amcX(!MmC({mk0$ zbc`V5NnCYikLEqzk#Y3-sA*mpAanW82r`rg?-NA(U1;^5di@h5I?|u zza$qQZ#El|HPGQ!&;`pDrO4pp?U$c^#`CW9yl;^D^XT)z0bfiBPX2>;2o2sb&$+gs zc)vbT%!`HhX?FcoDFkoxi8lfiyfqi!4mC#>CkB@mKeFZYg;$bqMZ~fnfxEL;PmeW| z0WasoNm=gOAV%0-)rP*CUqJ(Vddpnn{ddvF zjE6TT)rT2Qe*R(4p54|E04{zDHMV8rZIEKksbnr{P{C(NYi@epv)VzzWZ7#nXPEr&r}WmY(s8pm_$ zuKp`QY`pU>kC&<~WjwqEsXi{@M<$<_sH{yo^HsN80kZ!;zWrrv!gKr@)ZP{lm;SO9Y)yZpd|4X527R~bU~TljKksYM zB07Djho?39ou~Bw(GU&ZNeaWkDBfnR?7~=htN1?VKaJoWZy}Go4>PH4{Q0W=W(4og zQnO!_^S$AU8DYQo?0#^{Nn53+elpNe3>l3*Q3cEwxITqg!T^ubrjA?L*myTLju}`O zF~bX}aqWe#>^8MwAr=$N5A(fqq zs8;_^4buL%{k!z~xSZ}S^SA$xpusyn>GA>;?BY4ZN_>w}wo6kU^ zeGtL>ip%gjNiiQd^`%s`s4sFjQTVClgf23WSR7-0cc=#JD;DYwSse!0@|-Vlnqkl0 z?(^;1uCtj1=BCE=oF6-;I)aV&8tHaUZdS&_+lJ}`FTcTE)6Foly(K4Q!IIC{@bTW# zx4O5#x)mG_xqHs}BmV9!f>uakOzeNb`TunK;N%W6x4ZCf|Np9tzo>BozxbDgbDCq0 zApJ+p$A3O!yc)Eg>cbBwKQ#}*&bZS8z(cU&(IPT_4caC;o;||X26lLLk{z<~N088+ z2gR5C%IAH9lz)ppAMf*q>!BlmMv!bYc%KpFvPSXlJn>r;3-9T?AEI&y-sAPqAqw85 zCHqTPAb6iE9=`p4n>XxCW-e8<_JO}O?;xHTB?I{f2Xrz#}J%CjXU?F<8_G%^F3R;09_Ohr}g~%~jZV5A;c7TsY5ocneW| z;N|D&^2=5-K>&E2A7kn1$H%+<`Q$zqs14{!DNr{FCtyf)qy!P{h@;6%HgH*7EK zD#VT)l=jJU@3+1oGLT-AH@02&26$7Pz_MOG9OMQkc&sbL#+%!D)z!z|OmG1;uI{3> zX$2?t?5*Tyf7QY$#>1P3>H{x7B~S0}x|agruB-8Zgid_CKYyH7&+lmkn&al468rE^ zZ+Y#v*aA+R{|BV0)9J%!ucAp4azHvV_GYHRJ0-I9JBs(U_fAW&@NPHE)IWsaof6tE zO2IqUHn(*-f_Fllp~TJu-f;i+X8UXEzHmp)2x0sK8N5`u;@~rR1MC~CR=rpk27XHc zIrj-{yaT0ol@C-g!9?l5an?awSANmO#@pUv^X}s|jE6Vs124Z^k=&g^+=Adj?7dH{ z?f7^Dmz#UD5xkQvC3}S$=vbUk98J+!u08L^-UNDmd=$K%iQL}8$*WE1gLny?6`c8; zXE{%B26MV|+Hx9kZsAR(gM>@wTj&Key4hIfXjvX9o z9P%8Z9K5`1d8K(5@v`%L=NaYc;d#kZ&r``$z;m7_jwh7IgU6o7m}eW0DvunG2oE>+ z9QSALe(pBzhupQ?CEOX@i5vv>N%leZcJ{~Yx7bVBv)Gf_quBk}o!Kqecd~1;uVEKw z7i4EtuV%Mq(>x%VkSri(w07b7iw(Gi1|dTgxWRwup_L^*ie*YY*#7)_T@T z)&kb^tZ}TNtRAfPtj4U{SXEi&SVdU5S>{+iv-GpHu{>m{Whr6FU`b?&Wbt8fVlijY zWzk?!U|G(>&jK-jVgA7Unz@nr4s#iE4s$AVG;;v63$qooKC>3H60;=pLS|N`8Kx1Y zE~e*9_n0b}@|n&uonQ)Pa%Zw-GGf}ow2n!JX)zNg^b;C~`k)r50jh?IpmgXI6b^Yo z4v;Cd15$(JAyJ5zJCfUn+lkwpTbEmdTY-ByH$OMT^@ZyL*K4jut~*?1Tsd5+T+v(s zTrONzT>4yETuNM$Tno8aIcGRWIJ-EXbKc{dGhq3WcId%yvNz6oRVdiuJpp zU{r~IIky1{Leu| z{VfkNN7bZAd^Kc-s?U9DCm~Z*k!!igkO`{BV=nkW#;6+Gtq}ObGp z4(X!moqhRfNC#DY8jm=k9jNLh48=j)QPth5D*|mpRoC^YQfMox-g^C(g|?uobE9r7 zv>8=zc#^+E+NkRIz{UXqRJ9j>SO96E>Qzvf2DAxPZB~V?kS3~H#p72(8&TCf^dkb& zK-J4z4zD3~RJ{l*n1s|&^?dh;4zvMP&m^QfAXQW~%^FWa>rvJC;DtT34pmRigiS*# zsCv9Vw+32^szg9xggx4k@9kq4lW;q=>5frxi?~HK?k0J8TK9MpfO0#g>o) zs_wBK@P$^Piqu|U1<9l8?xpe(XeFxdI1MU8a;Un!EmQ%LMb)h(Z<-+)RMieGJPoZt zRZUr*KO~K+>Ju3`kQAz_cCqS0lBlX&;-?HrpsHfHv)CH6u~QFZ0siF=R;s!Gzf*g{KCRczf62rWic(Hc7gNElUx zPy{!$2vwIKoKJv+P?eu`?f|q9Re6V=&q51Om8<(p1`t>_gQ7@6cz&UQ{`4Z0I8Ppvn>Q;UjjVYJXe&3St+k?617>B)&zJ zoqw_&u@hCcdZcXP8&vHRGWbq>jVkMY_PfLmR9RJQUQKLAm1VeI81WUVEOd3$iEXIb zySV8Cu@zNjpK7XzEvPcB{(YR-j4G4kM?Ml?qRM!`-g@E-RPB*m4_7R_< z%JAhy1L9Lu86-bSBQ{Z$l=;SPGpHCp6{5=c^3-#v09AX!c@v<^ zs508Z;|}GcYWI?`V^AKd45s8Hpj=ex7m1famr%7UJUtxBLDf#9?nWpZReD0hR!|nI zbcWiEpiETlxbw;n%0Sij3qPWvi>TUW$)W|NqiU;MhAMOcRhuWWoyhVX5~@_W4zGa{QMInwbrqC=DwP7Q4bUl6tqru*g5pu7yzRLR6o)D$e$}sG=+gKy0X@%%4K6sG>|aK`f}EbmtH=swn$pAtqE&wiQAUswlg#AR?+Ln^qtK zswivx#NVi*ylqRILlx!aMB*=0QQqYu{zMh!)feIqR8ig(Abv*`<;*VPEUG9+91&+w zML7|M_zhK*12l-!sG^)VK>Ug-%E{lvFQ}p%luVpL73Ex6;v}jl$8ZuSP(?YlkoXx@ zl>5VoWK>bETOy95igG&*aSTUO%$}Qx?5dwi&fp!o7{yrZ*0qW0B zYVUz{iBQSE`~T;`&kUJ^ORUIY;FA(xG%ggTZZ}l{!>4R7^;tMocva$|77lT699fM zk1KxWAZp{~yJXQ}u8E(mV3ABs$i*`J{r`kuv8&Lz;BkE*Z3!OJFT19?YFOdL0rHST(*LWEnXaSN_GkEhLH<9#Pt zD8x;T@$lBB`nZjg-z_(XeQ(zY0-~6(bM)j1k{NpX>%nGiT z@7y@=Uyxo)r;iZLge{qoe_n6lqQRTeg`#+8_1uxb!h3X;;@Ou7-e4~19tCfk!R4D? zA$UIs%4ro^>kaGf-@G@Y#T#Z0DOHE2$RKVBNmIC}6oeShU0!@C9FQ_D*i?MO#=G%s zQ+`Ms5w4@gSx*?>`L)#yvwDBX4c0g+$#{4_qxyJ{lb^7ZTwaX>a(k;h+xz%m_;~B6 zSFApR;GKNRP1EQ;9Xm+VgPvrCsm*)533U1hu*hy}zVfGfbJE~VnN~sZ-ZYXej)iyQ zYzOZL1aF>uKT9ci2i+h}79e=<9?@Obtl|ypq-|X^{>B@Y7y0aRe1Z(P!!{;-+ExbK zo!&CXriO#f-S)<_g;to=+pKW1|ScxlZ0!O3_DeLf~{cYN&o zbG&6V2Mykoc|sI#)hpIwSa?6a)FAc~!8*n_0GQ^zGrjp0A8)sv`t@oE-WF==3r=3bU;mH1 zwkLJd!1j5MH=&F^AKFR+iQ@mh|Bu(gF~;8`{l6eh4Wg`+pfzZdj+8uB4a(j}Sf_^6 zpbZ|bt8O4QXyduoxE!Sa?;2Jgi+SM%tMzP^7!C4)>;3O;7yCg5-XEP87&=}8r`X@i zYi*7I5n+X~DyPgaAF*{0%s2~o&XJB%)nmsDWJK`y{}cMfKJ9k9GXHB3y*{>AM6LO| zL0W(YZ_3giiubzUk8)UeSD(_`Xo%pgqU|O|!5c(5u}33#yML*1vj6A>CrR}YOLcu< z`R_M6RKAlzd`9$+5Mmw(|9yvJB}XK9P-?qeBEcLJ@7}>Zp1#E2q=(eFuus3HWS?N; z&60f1?@J!z;XO$8!HkpN4l@la$wLAl*r0Fkh%`RlGRjsXIx=m*3MgsTDB$=11V^_s zyHix>e}hD)k1W5kuOc;n8YF%iyeVthDBdG0D`c_ozCD3lxrN|;V5her1#ezg`L)&v z-naTQHzyOk;U^k;j-UB`;4u5U4QpqS+gn$9B$9IS!C@J_u-g+6K$}oLBdN9*6Yuz2 zLyD7ize!uDaqC)Tn_Stkr?+?qw5!9?84vH%R3AJz`Ry6tVmquM2%hN#xSv^ukN2^f z$>UXv+rZ)&_Ql(_Heo*1&>=$H)~2IP!};?b?^AU8;Bd76*&Fs}dW(++Z_4Hj6z@+5 zj>%x*oooH{eGr286}cd03f{wORaC_gyi;9%ZL?YG4KGhy@NoL2H*7W636{?wv$s!< zExoa+0KCuyKUzB@0MwS2uS>?pn-u9=Q@(=$GgIR%vc;MB4Y2V}jM6DGInQ`_*HL{W z;N-XWNMWr(xBw_lyseqM7$5J^`z#!V2;Tkoj<5R#(NVoat@nEuXwCn@Nicmr5_cW3 zlsfmPdh^oYP1$XP;+=hF?+PruOUe>Uk`TP*RuI2Z`u|+<$UTb?yk~k2o|suH+jX?_AFnhN)}X*B0VS*&q+?d` zzR}^T_S*^%Q_3TDSIM$>amXBG&&i%wW=}ogm^tL~jTq!6sZ;)|kIs?7kxt)Ia)dyaF z4Rfb1*y#&^0;Qb%bH?~JD6R3yx(3r_+aC zv!2S|{(lh--jof*DBgsr&NWzg6FmK&^&xn_yq#l6!JG4D@!mHG-bxV~x|z$oV6$Bx zY>9i2lcYa7P5$~t1~dL;`imZ)0X|7_!*8HSP-+|hICQZICf>VKr>Yeke~`+kalg;1 zZI7+M##>>Fe?@ga%UW$4-2_XGH{--Pq6u#Qd~EWEbGS zK^pn6R-@v=x_RFq5gya$|Bn`;!JD!p9>rVqaM5Zkyje0yNz(}4&Cl9& zD0l~zo;28mj374;@CR30d%^G3QmcFy`oeyDY~-8~ywzW?{OQel0kEoMR(&0f08tq# z4mppo@jidZKl7RNPtq}JoU3Q=g!)Hpyep2R8f$bi9^M&LA9(rISaLs8FcSdsCt4SK zY{SP}tm9f+vR)f_c7NaPX?^?^q6}Y=AB1$GJw%5cha)Y5kUNAnrU>5DQ5Nlz1PLAX8b2fk{WlyF8K0uaqQV!m40s< z;a0}Oo5|v@54`-wRPGb`E(w5YRkfjDZG617=dR_QK=AJTJ^DmcoQ}nbGv252mr2k6 z!O2-VeQ*~ZQ20AISwMp~<((xIZ`sY;S7G7pkaA$XB!c&C?H#HVyu(uEvMLe0`EuER z=hb?_w>R9B5-ae5IaG*Y)5zM}fzLo_S8O&o*I}^!(TNBk9OCyu5yD=33sLGw`E=nI zX$dvXRy+FlkP$ZCtc2%>1@AE)-VszEc=?^sY|?GrCjfGtJ0B*hvi4S1 zeXLk|7k>3ljq$T4Bwm{Lc$4V#k+hI(RdV{@^Z)+oy%_lmvyEopvWO@c{QX#a&C5Li4!{vt6ffZe}2*rmaq`xYW+KW_1PUxesIi$L&;49Z(AE%fy$KuV5NoZE(a(ABqVaMy>B$Y#M?eXt@`knX;M5j z&b{s2&gGHVc;^{wRhb@Syhp4P)yE~g{JfN}^M>*Rz1}{7u7mh^OYXgDePJPjcVy3X z=?eTEq=e+>1rwq@^B?b2`h1*9oOy5|_fLZ)LW4Kuy?PYy7b2Hbu<#BJH%+j#W%E5!w)VKRlFIG;Jw_+v^nPJQJ}E#qeSVOaImuK zd&BR=yD{;e(k(UJUHXkAOO4wbpnULm0XE*|%QigUYQuPV&rp4s;^ZgXtvx-lRRD;{ z2^z>d;N$(I)d;rJYy&4HXN`)w@bPX?bh(!N&Sc*A|DsCt`IwRZu%bKa&-(uo8oVh7 zMWA^1AMjg?g*ShJUv?IP_ovBSHWa+uK6nMmAb3A5xgvHp$phAZ$1?53=?CW;uNKoq z@b-*ao^p%n1ZWPF85_P64#syp-t4&12ovvy(Exry_ZiX{HID0G{(X~XY`j;bhWsX4 zFdp7ds6M1|^5f-hx*rpU+}<)E@A=vWA8&8H64NjQ??$rb2A^>J28nRUs^rCfUps7KWv!5t6hy%GG z-TI>~0jma)77Lyn+J9AhVvYTu8noO8TQEFUoA1&Qyr-YOF;d&$1~}WkZ*-sY18&OC*bX6h+i$na>sAt#BAce}saj~{xBhxbaVj~1N#e6&~S8!r$9&gzQQ zE-CnUC%qXnl|%48BJVL#LZV{?`Lf`}fz9)OiyfhbP9K|$AEhHl>>|}$j0SJY>3k^O zY|&}zSa|PtB@!1QBgn*nfc+G_W5RbO^dNYzHOL9#>2d?!9@o$B?DhkmX;1g&B6z3B zTp}zC2?I-V%Rf83i2&!vl$z_Z^f2*0(lwC!@#z=R8EV`Pr^=3-o3Zh>y^!FxU5oMX z4yO9B#>r2>bX|x2P64po$h!OT34FZgrrB>T6KMmwZ?bZY7UG}YvM}L!&$a%w^S(hU zrqc(+TDHt8`cMDAoCa^oag!+C)0wtvSa?^xuB%o+@UA)Z?9bxF8J!(Al*I{w#Eu^p z>F%IS+(lfg#t%e@wrV{>@Gdwm;(sF93%D&`8(7#L0j8KUTRr4JzRciA?N zxy~1KRBsv4t(Q8U&;R@XWa;y9omc(tj=$GiETh4ja(*g`_Z9cG8?f-+V)lINRs`>$ zMqwvP^+xe#cD0ntzU>Z<7a5P#T=4@Z{f19=Ab67+>n}`PGyvpa&E@Xb!@-XW+y^%) zVB@_*+2Whtg|DRV)HvBIYxa0=#KwEqnVUr_v5eRM@1*+B!^!UzkHeCnqx|5jP#(TsXQ+=4@%>hzXm}WggCXCR*+D9 z_lbSJ2>1IT9VkyZ4O@3l`ob&(xVx5xkEa zS5c$jEyn62kc!}~?^^g$|K35cYx?Yg!*TwAte?JS*)KAD=F6Jr7D4G??-qytQyt*| z3S7M^d80Na-uw3swRD7%Nd#(~*J!kE%wcT2`8L%bXXj)*yq%~%IC1iej5<`WBqRXZ z7x9KhSK#CQv`4Ejr~$b_%Ke1R@;o|5kRY(>ZRorCkGD2`KD^zE&7S;S|Cgr0n{viK ziuc&fDJCqu3j+^rEky7h?ql6T!FwG?4(SGhH|eIB`)*4Ykl%IMGT+}H9Nb!_eG9>x zr!A)NrO`Q%Q;|32RS^#IZw0+eKerhZ@1UiXj`D$@NjcQGkxh;%dJ))o>mRx%YxI@z zMv%c&A38YsdH-7XNZC{XSVSgPTrbDR`!(_R%)3{uAR>W}9VsvayY-j>u$F|LTya^BJ^r2Iyqxg6Kza$Oblv`L(ytS655V7zk>_1x3jNr{) zo?}A6d&?E`YwF1C?bD3b(iPIKV7(`NL0Z)xctk`Q-$d}vEblVe_bnO3`R-L{Rf+^h zT=EOZj@vQu{uVA+zVio(-P&4#q%8+a#CvCh&AcH(6Q*NXNT}xRsL^*?`&M;F)0eQr-?iF_o-|PgQ z-wf`J-w*(J)n$2aeIvtP2|0#x&k8_XT*;%Bj}btk;lsn3bIO=CNHAj2XiDTq(o$+% zu=!cfLMQAR1hPImOa5TI8nl4wLjxzjm`jHH=5z$WK-9u759{%3&|9meRmB~x;KPs{ z??pNM21)vf@NXs3?Rj5=^dHmb!-oYv8SJp!|5W)= z1o(Ml_`PHJI!wGzz16pyXr25du$!~kTk>bNt z0U(oGT{r^c<83gbw6qGrJGpGHti}gAMv%MXB%hkq&wIQHhIIPSIJ#ri-x1_W8oVht z1)_M9E`8*{!h1XSXp1_6cT!&+8)XE^Y&^GYCxW-j)1wpdl?Q;bp~#BqA%76w>8#i> zONL*`D{fHB%mYJ-ja(xpk$|9XA3jsAii!7Qp*_*lc_XBsYJcNgf-dbN1z_VX*m#%Y z%PiyJ-AMJpi<93e(XB;SZ3KYk*67n+H}Ub-opoQ6FxCp5ByA{GDZ*d>C!`H_=iT`) zXpm0R=c7L5mSk$dpXx0~gE!^sOBC-j`%2ic@V34|jxj>;4ikAVM8TW9V3CR~f_H5} zWsl1RXK*s2NcBpMKPZf1<2d%6U>`h+jdv)=jdk!GLU;*zkPe0PA^?22okM4*BaO0!WA zoH!dTup{9x{`r5oiJiWg2Y1Z->b;6iAA*jNPYAJpwztUA;7z&96~+68u!hvm6 zYfXOgMohe?PIkXgsU9U+QRB`qRjvA9gpK#1%l)e-H5m`@X{rxrocyd~`W76K6!>4p zJNAUwbiEP&?Ct;G@c#Hp&E$3Zzx_W$_4!!IAPtfdO%0;lW{uV$AEupxST*QTkjuRc z`>Wc^b7x{G4N{(6`SJ$j5j#9ltk)H24|HUS=|^*p0BH{2NzDl|yda^vcWZJPnDaEh zcpYhwvIZU=NIlMnS%dP=?7sHBu$SadjU!3?zOJ$#y9UjDX&PU%SPb*~VcGvb{pW>L zAG0|5?J23;acr6&9KGfgZ1xWS5&J{Rm1n(FEAV+$sJ6lfzXpB&bl34i?EF9fuVsWj z9}~9xk;6HEMv#g$cvG%tNAcb!yI24VZ&g>&T!G*{y}&wyg7=9|=QrsTymx;W;@8{{ zYC?N!Hs~J#Zw5%#{Hbe0-dvKTzRZHJ9_AoO7HCJ*D`eU$3M4=2Bz<=N|B%<_XdVIi-< zR(!lo5-yXy4z>cKZmrjQPW%-l!cHESy0Q7c|36ZXJ|CG24_B}GyFq$24c_%`hb>XO zODnGOV&NVBShuPN!Fz6`_dW%0A*QrsAq4N2kB%HCi8_M3MH?FCd;`Fo| zNAS4HR538@bXlFE5eZEC9=g5{kj2DXRLv+v;n*NahZ^_j))(d2{};S}aV-|tW5DXY zjOt?+C%?fXqMMg*5dhDWI$WQ>z{mR|M@ErIN-I!SRWjw;jK4T>_vy=@cGm0Wef5r@ z)5pt4CuXgY4bsTiTY(1ex($o}!TZ|RKprf-4aX~@zan^l4~}c6;BB%u-&h>Mo4D39 z&#KT7?D=u;e(K%;pgYufI%%2=4;xr^X6-Km5kvj`!$OfDVEl~%=eE_Dct43U@-CQr zPdY@6`x4{rF=dZky~oad=$;}lUiEII`WV8=Z_=cJG#4WP;(T}tA2s6Roqe*z4Ip@b z=T>G}!i_)nCLHc~8+>&0yvLhvACt=rD1#Foq`6`tUMBEJaBg99WR6C@{P!25eF8`g zT2E7hnr4kB(MN2V%ErZ5HR$3|HmlW04JuW>%1Nm~Rif_}$sl`>u4vjUKKsTJOsvie zeqk5{k_HvbG=|Br=kk8>jl>&Z<=xS%UTY$Oq2Zi*Qtt|Y^>Ns}`F=l3|0T(S8aHj( zIhTA9y9TY}Z5_;0V7wZ%kLqJBPJSt$`0eJd@&iRLIkk%fNE_>OLH}GMQ`P)PObgH# zEFo9T;Xh&tI;#&jEF#VS8l*>`kG^`LD023nN9;Npyc-|9ut)KZGUpJ+!ux*4r{=8) z-XUclR#5O>zAv3=8G?7LGiTd%d229trQu-U&p>c4{|oQe5i-0^dXo3|)(UXTvtZg$ zJQDaD-`jZez8EInoK-zn!mV3LC#Z4Z;>$V?$7AE2K3!pJvWoHWMtz*a$#0|6r@ohy z{D4D6xcAZw{v&qaUACR{sTT0+-OA6tiuic<5u6u;K&g4ZgLI5YpAR8jo#GdNr?*sS z@P2Y8Y#PP;meyM#EW9~aECf~v-Y3Qdv?+M&2?+J^A$UI^FV4*Zz1HneO z1$Eh@WO&s!*=eDe>tJxLHS_D`kzk{FW7f<3!esFVo(Nhfput4`}zWF3R-nlpLy;no_Lj9Yct75sTZ7^~n00v}7Ty-?dkee}ydNnlSyJ#mY0+u-6KRkZ zUh3D`X>SWEw{9xwk_!a0rdwLn$C2uN>iW~FN9ACNR9OW8ZawY{ndkoV79dBT`rm^AS4~M#`@` zm_j0q{f%o``EX$D7j_M@>plQ)Qf9mw1XF$3x-{x?X|^!fO@ zWM`RK{U5y5Xz+d!R`Ad4ZTh~4OR@0g;oa&!gy609u=F|wZxQMtL=|FXYX^ z`M0v2ox6fTf$JpG2Ystv9Dg^KM@*B4%ZC{Itw@@Be)P;#Vq+x2D zf=}-|$0lsNOR{}CLKqNlZmJKw{BqX5DzYEv2jOQvvNQ?f*B>;Qf5}hz>e9S>kj~1PkvAf?QGrq(LfDc=M8i z_f3Pd*Oidzt>j^a==k)#;8KeH@&48z!2Nb^N!oidoZ9hwKqJs-?*~~!8`GR&Nv0{xM~h31q5#&r?WycS1iD^jOVG|GeLk9JGRK{ zBN?u1F~4&8?hU}(%WZ$UDFVpHl}~#2$YJ8W%cpS5jhl@m6>3~zv5G5x>O$kC%=#DvW~Ztk?OsJFaIkqKHkF#TVA|I@D7Lwy}R%+9h(z1yDq=qqcrdF zCTyb9N9<(U@_*O=3G?C?(*FaR8r1QDjRUPg>W+%iST$(R3Cq}R$O!W4t#>!eks7r9 zrlU}UgNpW(-(tYPOCR)K^K4n*5DLC`x9jM%k>PKWBf!KNzmJa+ zw_w&FA)l*!gA1N%O;O_(%DonnPJH%^SA#^UKJfC}>tA0kc3%LH4WC5o z?!d1>2k+~qrZ+c(&fQf>+{@?~LFV&5=~dn}|7%bIoj#UYc_{xKL2A+9-Cq1*0gAVx zJXsP8@9TNrNY)76L+*Zk6ufOqk1G!%c$UJ@@vBZ$6HVHy>Yeyoo8};hjVE zftR1gVEmh1;R3)*_oriHQpeLng= z`xdDEeL;E?4c@PU!Zc94*OtN(Sa>^#Ax8AFYB>h;Gc|X0ilTIHa&$$~obpJF+nlyN~SrxXTcprUzQ5*|zX)yBYB!c&y zJug>M@Lu6N0TB#W<>}MLIX0-l$26tilj29Ng{1CnM)*; zBvR4IkfHJ2NBi9OeA#!O_uDz|@A`84{aPQ^%KxtYto=ND@0mB=55Z#VXPGmS;h)`^A>nQULD6*)ZSD+_TT)g9rrVx)%1mYtHGLNk-no+;h;Z;Uu?g;5o!;bf7RO4YyC!V0Eu%M zo!xiQ7yTQgrl&LB^kz}sCH4nW$1be=j6aEqujU5#J|4`w=78OUUI(piv|)V)1n<3J ztMp>S($+mqDgSL|#h;XQO`wwTB}wP;KhjrV-cVebi; zcf)89A7TDy+&b9Z5A)uBWzPGO@K&%=|JZ2JKroQYe2dR*#Y4w)4=J~-sRmiw;;V;^ z!@!T&l#?Q|J5YIpO`Ly96$kZxA#sVqHYX0PM(53Q<{ryJBIWVkhSb4FOc_t;C=r5^So^q*gHs0%7WL1-q%t+?*l62)zRgees=2b1JYYacn==?BSYlv zs!}0?##;c=a{dGJepGr}pTPS`?mBB(`1aQ1>}%zH&~_k?%WW#?36h%qw#hbUg5|G4@haulZOes*?xwEB*DCgdia7t%T91% z;6RFEO)yxc7c;qIOFI#@8k6q|Q0=dqKQ0-u2u(`+|JuaPnT zTWIJtO}?Q1@Bfim$D5%34gG(+w>}B)S8Nx*6M0XUo2^CTt+aV-(0Z76j$ZI30`CT+ zZ$gDIZ~vH+a+_j}0Mnf#X-AWS!Djj`664SC(3`dXSp^(b0Oxl3coaSiboLaTb>iNJ z+P%kXCJ(5UKGS=K#9f5sQ&v4f=Pg{DH)VQ~^1AmYqz zTc-`H;CGM~*5%!bt^vPVgWH1Z!oW=4@rW0AQ`8>xMJg;;>+`tYA`%xS9p$fYV}Tl< zZmenKP(gV;=qpmkWsLlKq^_@|H{k*wau4H@gRpy0-^#SCpC;X4B7Sa@AHcrEo}FKM zVpd#C{VT{N^6H>*XUu$bZg~f3CkgL&X>a<7ysy6=Rz&0NoML9}3-kU|7@|htP49lx z^%TszB*#;-p;Gvgq->SJhfq*%0 z{+8gPFmNWh`m8IL2`X>9oF|a&%Tc{}ByO+LhJE`#px@qVFl_*zDk+b*15(EmjQslB zCF=F9xPa&H`1b23uz9;YY*ak&&<#WeIfB`xvAg#q&8{_GP1Jw>f035FI{wT&kKOY3 z>n#Q(yx(d!uO#y3c@n08#(Tb?w(L60yU~~a5`p(iv8Pd6VcsipAFD?dY61FK^_@134968FQ7(c}3; zblxG+^x+0|l*juaQpYKb{JaxFdIGL-0T<9(3cRs-uP#+udmrZghLKU~%{wv3k$1t`9r9?r&xSm@S4mi$v|B?2-hvh9q&;BX ztyWKDJdbVy-vV&tcAim#l}mJ7UCyCc}%4V!nwcO?() z{BAHExGF9!4}1R~7pB5I{l=2|7bj%ap|4U^6&d;8{EwrCA9()XP11utR*KdVd(g~z znvG~ZXv4;>)}I|p^s8AIX-nZABvQ!34-p2WixKb2?Ny=R$q4=0wh&N%*|0gj1P^7* z*lgazUk8k~e%lly91cV)G_8EA&$$uSfXB%Urt*Iij`Ad z4{Ap0c!rVRmvs_WALzM&%HH@2hD_`p)Qi8bRUFX;G`BXpZg@mS4;qPYoHwO&>4H~J;BY~^CK`oyH3 zJrcLY`0nvhTXfz|2i~3Sxleh#?-A?3$WK!bAMDl11tec(%6BAV^M+r~)p26H3j}B| zJI5wqA8)aYPZ1q%)TjCb($Z(it7DtFw-eXd<>M{JB)mV^u3JOoo%KCi4UKom_Vj)M zn0LQU=Me($ceUFyiecUrcVBdhJr;(zw+ppz%nbn%9lOgU?%|<3L8Cl0{*Tb2bZ3=sQBDIg$pc2S4k@B5_kaD-7=rqIY}GV`l{Pt0<569;A+g82ODPw`{Ux z-~zMOJAy|354>x$RP{@bVc*_5SM~9!i{3h_=l%8(d3C71rYrNxT<+exNO+H{NJ|oV ztH}7MqVaaopea>?c{_yQuMl`^3i7YN3iHM};u985^*ouhk9r;(8v?xiB7VGkfQNQC z{#fHJQwx5Tu9&>#9tLzr+I%kdp+E4vmi2+}_17Qu^oVggCK3~Fq4Pevmn9&sp7MCh zAa%H6<=3>nm-RpVQVjPXaoV_3PVgBd>9BKZcmo6I)`t%p+TVr(ZS|9oVKyFezWnCF>XdrG z5$k!9u`3i5)ehEIn_HpI^JV5-_79)U=-ol$4qT|NICvaAJ~lmocQB9gde9xDj!2CB z^hTK#u(Cy9JuJ7vT0Qu9-6A>=hE65k?I2VdOQ2+P;aB}3;amUTJ z=I!4Xr0*f&{UtX21o0B<{JujQjrVt-S+$EW@5*8}nG%?{&9~&YIxz2BYxd;5sND(~ z7j$g|@TYYBJ)QQh%f&;t&PEw}?y3i0D_^^bw}pZZgZ1C$OVQ`~n1S05z6s9gy+Go= zMltTYydIr5({=|TqXNp~9gEaKkCETE{1f3<;7e@vtoDRuB{uKG0M*D#FmIn+wpa3% zWV~XhtIyKCL&2#JxP$dbL#sop(%Kd6hi{-o2GY>IlQgZz^fsi9;Qnz%8oaM#LR# z-ZvPyQWmW`fjxcnQ1dJ7{eRq3GUk@4pOTws1Kbw@%8Ht!4Z)B8A?yTHXA!JU?!afXDV2)s>6cz;?PF(C4u?%J$@#yhm)_xT=}_l~2lo)UQL{wTC>gn7>^5C3*% z)qo_Uv#v!9h5%t1x6K)acqo@sgO}lO9f&LU+u?sc3~b!TTxgtwKF?oa2srt89IvN^ z#928sRnO+5^VaV4nN6voJl@$z9qJhQebkUhFtp(Ut~p5^_ithIX1TMtWDN6`2(}nf zlE&tZQ#|REJ*r9l^S?Zqb&TAv!o!P`|Gxi+qx>JZ2icPJpl>(Dj}v+jVg8rAZ@vPp z2iaXX8cqlIpfp$c$|AT2T?&#}Ckn41`35<8@xtbi+3Hij@p|C^Xo{Y>aS;#g|M5DU zowgA;YV4}$RtyDSYrdChh}ojf|I%hgPZa3p^_GyhrI;5gLpj!{@v2dKH+OZ2K$P|m zPOL)_BR_!y7hPrAxxnLLd9mpi*gdFJ>vPH${dOSzec&ofEjcU5+_e_yd_F$;RFH5wsD<))3nO*ZVdQtbtv{(@9-!t62c=h(c%1v5(WdfP!u;X0W! ztFe!_T)U@Lef;$ns^1_DCbJH8T!QP?_~re7YZBhG`U}^IytxLy(xLG#RZL@3gL&g_ zJk%oGy`7#fnlprXx8i>#BqZ&I_P44FZpDRzH#<@sFQnih=9rQ)u@en|(ZzIBcQgbz z76<=$nu^XfI67p{)f;nqZb%%xy5vjIdGz^z^P^q2;<_o1cMwv?CXDZ;{uERU+QTP|2A2SDCUfAl|q1Avhfm zg__$6I<9K~uNdb0SigpVqCJI0TUVml*&%Q9LcNd8Z9xKSi-$m!`=c_i@JwSQ9 ziFKU7$WLmr+de*+6F^7SRyMa{^EL>HS;_V*RlP1l}ECF*YGE?_imY=Xzpy zLaGerksDWs0h-gPxo%nT_y4?u^u*uRgKCTGj+?)Qf}s_`iX8mtykkertTdu$^+u7n z-K_3E^=i<0D?e}_7SE-;`TsOhhXO`^OosgvDok9Uw~9-iyAhlBmbI4jJ7C_Q4xNpf zNG9X)mQkMrCX6c7KmWfcvyOJl6B_@`|2V4nf#-h*k{V{GO3(~@`kXHx)w9)vU zzb8odk?{WRnVL@Ioxewj1&#N84P%3wFz?BVD-Q^~C0^c;359uEhWAJ8w6cIqHGc$( zkbAe0W1dG|Hv3cJ;^84j>*EX=SeOI1F9`*{- zK4bHzFNM-nzk&?UB(IM5E{UyMGL~16dr5dN>5Zxpd7D1}#Eizs1G4A35gVj54 z41UJuEiRvs5C!wDJhEGCj-0Qz{GxrOTrWlSym92#amlJo>hJLudlKG@%qG4>-o;jT zn9z8S6`N1JfO$*)yrM<8duw@h=@$pgTPN6$#a?+2Bo>%s8)6*}Dnc7hmYl^y-%eNX zC0u9(Ijbut_Z$lYi7PGk4_l#k?_%Z9vNx|5^sHk5Jz2En*!t82RNrHog*`zy;2XH;a4rVe@vTmx*GB_ugb<(-_@duz8<+6|&{f zUFtua*g$3-pHkjgKZnoW{Iu{&)G`9wbSV6V*iQK^ZHJxzT#i^Sm3GtKlBx z`mknI0ep#NZ!g~QhH!~psh$2%-WnRS_I=fF6#;N@-h$sw;32-)d-A>6&0zBtyXKsq zA%J$*72!S14yY^0%M>S^pz?AKeoaa}X*8kkuEEG6=`NiAeY<2{^a zKH&uOF1UaG6M^@;n1r=GFmI!Ly7JsQOK8uL5UtN&!@+`NfcuLeJj8GDxPks{6W~2w zJ3b~73O1R2H$8Z2FY4l?Xz){%QrHi@%}8AG864eM68b>(Yz?kOm;#^wzm3%K93#K9 z(D>iyEx15SrH*ni8NAOSyuatYGsBr;-@P@ey1Z}ESeoh=C%dZ2t7B?USDV0#KI`kx7DK@G_jB`ZkI`>${ju*<6RZEOcMFNj9aievs)f#* zpK^5FZ~DD|>%huS@W|7{KQ3?qZ@+GHuJ5#%YwzikKUO)w-TT|J(n^8sRA8@8S9X;Q#g@Nyf`I5U~dx=G-KJ)`J`!n%@@g zEzuV}|Dxa)+=HGURXuhU{s!qjg)@F`zP8ZrNuhfExd=cH7R`oS@zAx;rgt_sw1Cz~ z!`^)%A)qiuzdv)y5%m%~?r9)rbsPsuk+}Mnum&l0on?3J!Cu}ope0@)JJ{l??IQztb^}Zr{drF z-<^c_3iswuMBZDQIQY?cmnqCB)WWj zldrt}nM#4jTY`}~GBNTiiH^a0{N@C959{{-k;dlznlqs1Sw|Dduy^^rl?(e8JI>pr zMe9W?_4D>5ua1#}<1XbT%PUAX65b370rN!O47t6$XuKJgZXbFH^Db1>*U5)@@5sGk zqYm>9zeeY<7-a)}S4!Wp?sf#2t1xA?ID&^(`Uyu}vupuZ8ZLV{%7=pb6MnAlU(vg_ z)v+_i71v*x!pL{8f&AZ%3 zDyZ~9GYDo$(jPUzKD}joTx3=MIa#Wo|0lf3tK(>t)icNZW!|nNyy@n6bcwu^kLIjG z<9+GI{nRO#x2o3-_>F2a`T;aHM@HZQsVLNX;_ad})L!?pNhmS`OyNEGcQP?UsvhZ7v7^ftvyLieJop(st)cp<$eE+`$Qb#04 zezzP*l)=+#khvqfU z2oQL#WC!apJT$Q`Md#q_X0XaD-Qfm*C=j!G_G8y0^t-n|`RPpZ4Sws1B600?H=l-& zpx?cX91BRBe?)onKThCp9kCesG49%t{0%;Pd*oDpuazJ+?;DdF+;_oyZ>rf+Rbcxu5m>#baLF+-4 zyM7$hgfFqmOq=9x!aZn7O6N-myn?*2!i`76XD{?9Zs$?Cn~|VtFe+uz1`lP6Ein`| zJOwo!+FlPBL%{ucvkPaOolpm)biMW)6Xvv_9En@Qvqs{Q(mvGq$xwV#`6T7_pe&@0 zuNe82t}|)8CdUi(3a*?qH^c5h&$P2+E)>?o&;L)ea7;p||1SUh_TT6q3VlcYZ;;L( zB(Dyx5l#Ldsmm)!4-($2mfMDiyf3x?5JuxI0{J~Mg?aC_J{dsZy+f2OHyP&rOT`}_ z(Pa;nhhM(c5g7^eJXgth*yEwvWT{@3q^Cf;b7Ke{e7vRAEk`WwGdgd+HT1$^uV_FA z5~pr+AoYGYI`4pcNjD>&P#$kVq>d1b{Jh6M?Hc#w1z)y(eeYq2&D%K8JzT7)9_$Uj zzvuYl8f@NWqO2{qH&Fe6gexYqj%YToJzl(oH%J{J;myLUx%~AO!rNPvKh~{AZp_RttG5qN4F3Fg*+V6WSUhiq*#Ma0~ng0Y45 z+`}DVAbxVgkrpu*)L#o!(&#;gS#<@81`S14Cin5wwDQguAx^RVwnsFmLG>DRv1v>>$q@ z+due8!%rx7{pkzd55ND9-PlM(`6=isPR$L<2nAJ#cdLDUjo!T{epFU!0X=#1?X3c;2YP5eaxx^iL|g;Gw#qQ+8{bR{oqgfkL(m4Q=iO>YUL7pB4l^B}|K@+<)tjRK3twW7lk^~-Qwx8H zJ&3PCN(!w9$%Isd)Y+Hl^Dw$!%7c4QT?GgXhkH=Kj@6TUOejuOM^3HAMLz z5Q8Y~-+BtE;|4~4Nt2OtD<@ZhE*TzK+$ro8fRjo1kh>dp4+^(q`L@s@ zLG>$0CwubhXgho(MEb(={C|vuH@Csn<@f&+2Be|fSqU`WJ^nIc12FH0O8jF4-rgU& zFPwsTr!uVnuIl9o?f1`F|IjK5bOl{EezF@6y*_<~-qxoTNYZYP&$JH)ZGOJI`gQ2M z4Q3SV=Va(XI}&%NZbcIVBRX%b@N<3^#+1j~2&qE{BfnSR;Txs(yugTQ|AUB=*t|u0 z*B1}Ky#F-Z*!i`AjN>h(+2>qZsDFbLcbm*Q9&XZ9`Fp&@n}jzPcjGQ%_Z~Ke#L;+r zU3)t;4fEC$4AHm&^Zw!ChWCJZtEIcS)g(ATyyu^`#EC|M(hqWc^JaL6Jt*ynVm>l*d~VspAGle)!A- zW6Ymc0rM-}@7TPsd1pN7q8%-*1rzR}0oz!xpWZ4S0I_W!Q>eas9~>mFj)&Wr#zikJ zcW*Be-W*>V-Vk|vNTi9O@&0!2Og=L_Ai2dIjwA3E|L~Q6AIv-D*$1Jc=l4Mw3>RKT zyom(Gr~GI(S>T}oi=;2iqOD-Gi~YL!{b2BiZHebz0y^)m$A3m?_2~c&``@^rO&T}a zFQN0c(R-mAEkk*{dyqQpF!H+^udx2HGB2z~Xkedv6XtboiG8 zHt#1dc`n>JR|hgUX)E#{)M4{pxn+d6pZedug<~eKj>E_7wYlKeTm1L@|33|ma{mC& z|9&JrNYJ}%9kB=9dnO=<)`PCsFxH#EE6AhoUw+Mndywbj&fu+Z53=NE#zk#(hE$A~ z5~|#z!LWs#`P(gcXuY_vikDd%=;kWB!gwSY4C?Ck|B^u8K{`aE@3Qa63NVbs-FH+| zKFfrD&vItbK0Yym@_LX5QpX%de(L^$<@HLdzy(2BHSUYpJxDuY(SnyG<@Cx!z zrNP4w&Zw7$vZ#lab`mQ9J+5jw&c)NGM&lm(iPOMr?ik6_l*junQb#aGe(BMdvY(`{ z0x3^EeEt%L&HG6XOY*n!$KVWI+@oYoY~CJuA*!3ZsQ&|LaXIAGVL!Kyv!H32w+{(# ze%9OnJiQg9ULk|VJJ!WbDj4Q{#5pRBz66w?`4?xZ05Dk1l|gqM@-Jc zyh8&&P5A3OL6>q9bkDa(fh{Z2J3Mycp<@M$0coFF!HZy}jPA?9ASIg5_e(lD?*gl{ zs&eNUKspk~)Y$h6CyUOz_0rqTi>Z{yyBMjX9V0*4zFa5%#Z^GE&!Idt5}UVensmeS z?GTtq>)5ku277Ztc=y5a+Xb0azc}eLC9e+k_|eJPxaIDBf`s>~Jemn2Z>`{Arl?8motqSKsZ2+E-rrURnrmPR#5&6KI5oKG_$}TQ;ez^ppEb?L!r0fVz{fS)rPLo__n?Rq zd-u5AeE>2-_GVrj!hS&7I#_LcOaE%BUqS8*BCn2l@tQwe{>zuxKoZ^}N_D10-gtr6 zifFu#6+b;T1M|+&SeZlM-T!W5@=chxs>h(2{~8yFPHUmG;8Qe6_++nDt_!aqtHVyr zL2W>oD^ciPM=+TC5W6sJgwC7W2uEC z&szqN@D`p+)gbZ?9=g6Bjkm=!;m=I)3ergG^(=w+f$>2a!rNPM8h0(5J~~5(c8sd@ zbwq>3fbB1&^ze{QxWa(?%{H)4?ZU3m$HCyu>#)5~8PR#iD5ZZrsL2RMkvM%WYrB-y z=)C*Vx7y13P#*6%q>g@!{Ni{%cCNX+3dD@>&Cbrp<{j~e)j#C)L!h-~R5dsn`+)Sw zwJ6oZluWAc-ppjyF*m9EeO1iz0cn2{-mAM<=!m?ND*P4DczdO{ONhd}BXpe&2%8fw z+76%B!2^=}K$FwDQfKJA&;g?@MbTia*GsDmz#mBSTQOmEwhj0g1^kI)4h9N(dv8IC z=$jJ)KFwbIKUV-1B<@8a?;c+>^vwwz|DNJ!p_Ip47^#B>Bfnu&?pD4pJfQwuGQ;`; zY~E1_?Krio*Z^U78LE+o$Lrt*!WpU`h_)m=OJVjzU_cyC7PsK>~! zrtl?i$?jEPzhLIo_c_?S*U%}9y*Tp_R0asCt!g6UaH5Y~AO8rT{`udF%sOQEZejm# z{-@lTpER?Wy)ihF9<D?1>xbE6CCxXTqEWDX#}vBXyKv`cVHYT$d2Z*X<1rwehUuQ+Mm+Q(^NYu3)pqdl z_wOR7*dQ=_%xrj*B0BE^**vv(_Do<7iIa2qmO%F}x3_v1zVGMfraa!akvd*teT+U0rfWFKb`DQjJeLoW~%3nJ3?k1ob*?f z|DGTXCE+cBSFt2^Z#CPiYG}Nf0&WMU!MtS{ON?`1-bJH&i%anQ?_AWI^tRCjGPR8{ zzUvSJe!Z8w5}|>IHjI8XxG&rez6zFVe?A%n&ggDC;xUCjAT6oHm2&ejfjA^i$!_FE z)h_hztt|@G_fX&o(qBj&x)}NON0r{1hXfP{baqd6`3*;{@24O^$% zz~iIml=4|Zz|zktq1ic9`RYUh2KG{RQ3J}+=Cn+ zY@^={4@i9)?^KfE`Tw*+|KN`57+{;PEqqo94^1v?r9YkD4wxjwOoQZufYYFctm-55 z9@O3M=qppe4D69OZ=aL9#u)$Qp5=XGiw6vpcZuyo>d?o?4?k;JlKzbwcuA;*D)wOa zpq%%dDoPe*;G^5;saZ0P*ojFUs4?oSqWS^JQk=Xx%G!hk|13ZMA45;VTTb|{7V#3R zwZ26gjkofhtdkt@CAP*%Oz$epJHNc0&jjWzo`0NmXvqai+^Msr=6(!_xE^*QR~Zit zeQ|H~O>PHUoOiyz#~lRP>JDzY5r)oN$6;%Fq%SjQLgE~(6L;==i++jK!Z+@C$Vhp- zHzRfEVC46G$jw1_4-YWc&EU!C!sZQ{rZ{)QyshH4hvLXNViz^~^=eNe)$_(hkXgs* ztMb2}w}_!5;VnB}V@Txv;(D?c8t)$lGYN>NRv|Me zZf`p%d6tp3_$mlAt`hmYu^FBBM&s5jfk`G%kHlRB59f^s(0R9B7V%FLr##-9kUH8i z^4s5aWkJWE2MpFs?csv3c@G#a*jjMh0Ya?84*(u}?+xdCxMhp*9;#oQggcQ}hs+l? z){z_k&Ht1<_WzR`e2HC2(t}jCbxIR@5Mlm*9cQ@$tp~kk=yr*O=YOZ)F2Y%G4~l)4 zY?tT?e?fYrHu+7I3v@H@4sP#c4DcH~J9AVH578Y~Hh+if0DYTJ=y~1?1a-Nl^-m_y zdyvPzj~ds5R)WV!oYJ`O1~)tO`JbbYx6ADX<-KCp3#o$_BR>`Tpy7NSZm`InbFq9H zy9e!Ke^sq*QUd&Uw3_%#WA7lvMjf;-ET{fwkQB(Q!wo#$BeMJksTgJw-pZUCRf)VM zgd`czc+*@OWzB$jr|F9N6L=ry)zP(wc_&P5e!VHp1v)WMcdhAt3@|_0amiI44~ZMj zb?Sd@2Wp%Ln`+Yo!KNJi)ZV-3yiac6e;>blCD1_Pfbwm6c6D^#bZzD`T`wt*w;xgm zGe&-nim)?a_Q`o%EoIgPCxVr>Ap7U9SzubVmg47kfA#?vO)n8(9yvdCs#?TD61H*hfou#-y;5nvfeL4!AcXof5MX&Tq;Eu!pU zgv|+|(mzw>@PL#td$(?~+XZ3>oQt!576U><4bFS6$3x?L^!%hc-~s87^;e0kK#)=P zNMi5598SC`20iut%?y%|xZBNM4=sM94@j%7X5ZzQp*-G&NF72L`T2V_+-9xe2K6kB zA?5F|dE4G`8lQ)G+Zlzt(0){p-MtUr6*tNkSpx6bsjq?>Fz>sp?C0s>%?Zoi5aX9Jx9}PkHnI zeWVVY(7)$bQKGQ4?+Q1l&E3KMupgWEwQr?gZGYbeC#ugYObwDT|8J?cT<2#-^^22m zee&v{<7Sy+z5Cz%|Ids~$$x+^u^c2lNMi#Fp4fxFGwx(X>p@G+KjYZo9>k$nX_^7| zppu}@Gl$?6WFx=Fp<5}=(1!=NFErp|0NZ2f!Qr)dNZX@|u5xz=7-E<@7b6-3R!i`m zDR_+DgKE82dh)+u0Rl)|x#l}zeP;9{c`r}bD#U40UJt5A>KMStFZ2B-v#NP65PQK- zz=@7tAB)WF9iL#Hn+2ea-lco}B=!ojLcivQ*t!g=??H3g&egPmsmiPwhpgL zdA!|`I<{iu*ZJA%w4Wh2@Qc&ax58obR$rfQ83gkd+sLrRGQI(Isq)YNCb8T1tc$-! z^}KOWWYz(x0h+%nNH!AQ>d%hI6M1J{7-L4`{pk1h6S^>O_PM*vnK19b6?zisFz?0v z2j=7@T%c=dyJ+pEV?fe%hYwjYc*uCennoU#4v^Jsc|Ex?2;62|t@?Vc8|tqmeOr3l z@kAC-jKsCt_9!LGpm%TacyYg)?Uctm3#mg2Bfo+-8@0QIxxokJoQe2F>=mR(j=RUx zqlG}_O&s%sZtN4JxTu)5&MT#;e?W>PuZ|22OPMUYd{CLfL{clRwIVao8{Da|L>D5KpTm>G?pS+E{M)sNqu&v-Hh^hb0Br7VdR&v zB9zPG7dK!$c$C|87Mpj`3%_k2w-kd+&%vJ~@=sCQ1hIR6TCGxFk|0C%-Fp?8bYTHfuM)lEqkk5kM&z6TQKn02W<>%Dh{Vy+6zZaKyK*EvodJwUWM;Q4@ z|50mi&EW*m>|HHPCj>n+$Nj* zj`hNqSX!5dmn86z-~p2-P;3XF-?CetVI%-7eUp-jXF=z^<$hr2g$x$3fW+;td}til zfPRVPX&z!)$aqWZeyx6?6Q|B5ZVcwM&iW(k>H=r(6 z{%Nh9x+>df_fb7>TsN6@(8WDh_&fh|lknDVlT0J>=8Ag5fyO)UiK%Q0%=_&%GwpPk zw@X6l%VwDO%f~u)0Uw|Tl;^b7=iQ!^rs zVd%Uso#VGqiDm)3NL+~b!>1bG(0Nz$j;i(gQ6BFkq>g%w{64?Rml(Up39j)9bFARN z=AGF0C;wJ$KCtJi-M!R8#_KILog*^NjZ;1Ea5C%AyEza~duzFSbCK}Y%G|S>$otH6 z89N$pD|30eVVHNW5laezcdX>n<=-%GMZ@#=1XnmiJa4+Q|G=lW#LjGK(3XNfkZwBO zcjrh4@WX3bfTMvRStnE0&lR0_&FjslwtBLF%ShZ=wvH>(|MEh$j!#=M`{O8&cO6nk z4@Q0`xGU?M=(#|+!p>y=mDs#x75RqR4iPq4r24JIiNy!;O#c5zrCgJN?slM zyAEEc{`+tuCkb!OgTo0#-l3HNY-qgGo+k;s7yKy@Q(0kBa{xRd%&8*-s5_cIot(-K6-h(oy`Wp@V zDen?Hi`0>gk>BV!{MJ8_oFJBOiR+LYb`QGwPPB&I@j6K2KgfEh82c7Gj)AT`WZ0Ja zdk`aeb&Q|(tsl6#yn+-U;k|kKY6p?`pw|k1G~TbLcR$gCd3WZuv!}wm4S)CCYlC?| zB)wP-;Dv6lw9>%VBUo(f#$JI9iZc=*o#r6AmHcgU%XU+&Re{@!2iu1 z)_>w|SB;6j??LB%!+GoWyfMn-EsE4pfRUe})kFCk7F^&h&7Ij@QrNs_Z7vyxjO2ms z)+&n?C$V3UK7O%vskpzJ>UkSpBCn1Qh6nXOr7rIv@sse@Z_1P+^2T@e@}luJxNLaQ z3g$g+aK(eb8~iefxeD{s=n0biTd!ULzU%|9ykntpZ(C&l@*DUL7^snjR|}m%BF~32zXu zxRc2HOK9dQG~PZVKRl1Zyw%L*=diPz(gcS{OT8M-r@e)8mgnuwEk_K zN)3OP6-Ztk#}kizUv*-+d-Ia;*4sbjOyq4i?ahP6`+n2#i71$N?QNU2gv|*+!y8tvwoo6VdfvEZ^6HTGmhzR)`fvZA8d??(p8rKidXORSM|)xqvg}$X zg4ToPfo<)5>k|EXRrA3lxCdRm(Z@ar--GNoY5ZRA=M0@a&nxN*zk{TcmDwd{H6Eh< z3Hh%7(E-wGt$Mv^g1|h(jM?`Y^h+#l{L*$uJvOk2#L3`9c5jqLf8x|N!(Sq!i1K<6 z4N}J;jQp;1T|Hx^&Ix|BGBM5SVfUcIHTCI{ZfRisjKICNmDsn~!y9(L_~ejB^(#nn z>#)i5D`bP;K??I;L&AH`1=}&K_=!Nl6hGus8&AATX5hz*+CIUfcv(IbVW^~?f4)*dTtz`qx zkT{)JnqenbqVsO8uRKwBhw^w6>*&PDPjG(IXIVc^u<2a-+7;T^ykj4AZIP0`0yx~E zZeM-uODwC%ZEo}8l~lijG(ct@+q}Y+9TJv#3zP6Rc--ql*YD%}&)k0_5fv5pXo{6JOlZpJE3@MYso z)`MEuyvNd$*?MKJ0JB>Tow}@z*vDIZEP5dE*Fem8x=HTU_iOst!lE?3)Y7VF@5(^fV$L`)4Z^xdUNUx^)0cmlBygJ-< zO8T=im%FzR3GZ!o4F8<}*K+U>MB^sL81nO=(l-eYVU=V9InhK@jFumkM1>Dy&l9tga|N`<;@(Rr`lvL^V>YgXWm#5o?w zT2ie-=e_k?UY%qIv^qBLJ#I(+gw%7u{k+w7t>X>Y z-5Y3CR3ty8dfvFrWY#fvp;7w3{eP+${|WQIBuNi46%2_YUSb!eq@>V#P}q$kH$C_g z8~6y!U4na%lE<-w{BCOc4}RliFQ~gfZ!hm||Ct^G_Dqxrs|ewt-|6PnlaX)fh@n60;rMXE%Tcuxw;?5uu>(If-Z+(#A z*VS7%0asn~&E$R9J?P5@!=t`O698}X^qJ`?GJ4R@2X}8LWm5h8kNZt#9jo>+uK#;L zT7rbP$*in6k+;+oP7;lG5YxfU)-dnvm$}xLVczeX78L|w-X~lJsx}F_Ko1^Po9s@F z0j9OA0>@$Aa;0lZn%Fx*Y4t8<#~Xp5Lx0CF*>C8)xsLhorkiI4-AG)+hn-dv|MI=S zotq!s6{JAk#5#;I@_YB~SD?TG2Pl~q*vD;-&D&JxS?%7~i{RsX{{v-}WE^kF``Iw_ zT#ot&Br@wL*q@*_0J9>G8RE&i8uF#B7B5%6>L@_kpr`CG+ z$H2Ue1Pg@-n-j;PWL^uxyw_Lo=W_QtLlHWOF9YGtiSp!26MtadTWth|FEVt3eS%zb z3Qz#R(Ovzy^bvi7^oFi3*Y2mRfDVb$8C*=yv`)2*oU;^)<{a*ur!}Gsr^$@dWk~1_NpO7$jJ_d*%GoIN7 z@4d-<;R;$!(+QYPc+@eS4+P^+w1N(tNAKQt345}fY}mj@Bu@2s@j}rLbl&`2wXMCk zC~y8J*0CBRzZDzg7{3H?f@+iGfqVmO-glmu{@T7T30zu`%W3K+c&UHw z?N4SMYYp8A4=4V2{+|kN0l@RWEJ+Wt;!Bz)_8_iMm9N&8t!@bb>E;gF z1}^A5NKI6-PC1kfWFv7NJg0csSD>#T|2S3+H@8#XB~~4&1GoR*^GnL?Ju@M|0rn~G zKd<16-Gi=Z8c3$Siv`Umdp$iOv2U^Cy6@Qv~efZ-b z%zKVCa^bybCva5YW{b!R03LA+tj4P7yw^b{T3+sK;208TBPw@|X9E2ayFYVluvHu7 z@g~;cgpuFMof^?G7dgP|lJ4HZUsbC zMqV8i7uOV({Cz>XGzsrLH)cDDyfeO3$e{85?z&Yd z6E-K}Iu=veVBS{mPRy+fc7fj8UVc>r-@Tn^Z#+~F^S1B|#QhZP1Ps3GBb1Z^fl=Px zX|tQ?y!VaqJ-h_iz-}b&@VN@b>jLPDleWlEPSIY<>)ymVIx+IAdCpdUBbEaQ=A|Dr zKZwoSRj|j`H2yTGRV;Qg`H8(a2_G@)_mAH|_49xDd-Ccyx+;5)BXxOkB1OX6Yzx~_ zB5&(Xi?wLH(^LdArD5J%)wnJZcpJ5T$mfH3cj5(}B^$dy>PezzyR%}z^UZ}%W?|mO zzx-?l`8vV8#_5+gw*>;Q|5%Ai2|91f-)&(W%4}dO636Rgc;1~4op-xCt!(96%HwT? z)X{~J-)5#3t2c1>_T1>OyUZDz_wlPuegYl|K!WQE2e&dd@BW;*Q+;1AP<{7)a*ez? z2Iig#r2cpQp9+S5I7N8=Ur*A5?0@Sl5_?dE6RR>>55m!`FSdqPkn~>!)h@t2C^^%5 z>;XLgH;CPdc&>Q>@_LveJ{cDSMzd_A4++3ukczU_+NazJES*dwKEvn#b?L?4<=4BT z-Ws;Ich0u+VF&t1oOXZjw}{W^J*Xp8q5e4qz97v3siO-szcnx93^~A>F(#mI$;YsJkkC6#Thnd>s_#L@qvX{gn!ph%7`}XoRUqMQ*YbTEk@rsT zAw@La)!$V%d&0bXKHs@W;Qe5KacL9GTRv~2tIWCskg;*rdZV*3pwHO9FAnA{vyR0< zL$MR2MovW!Pr?VJotYHwT}S5~QXTF2*o7TLB5}_yOv#?_L+2flI^bA&nDTD1hY{<* z$geJyduK{L2Y6P*Ro@wd&3lnixT4^86ll5j)?$x6_WX})*fHfXyqoHI<66k9V~iSaSP1>$dk*_Q9V8eXq2?iJ%@RB8r+PDT-OQ2RA(oLX9K~M)U?mK%jmrC z{@5>9X2K4pk+|ynYHP3m3vUa1>-5nG%Hw?xsly5*za)uk=V=~s0BKjH{R4s6yzQas z@#AeV!2YOUY&ZXMU;p3DF3-s?zsTkE{GB6jam31fLQ-jmUj z-gjW$L+fu9lJbr(v41`A+XZT{aW}MvdDHgXdCCOO|4!eJn68xW1c7HVq#ykZ0Mcxx zAA54q=YJV~n!@>HHXx70=|0#d?yZ2{z0ds*dv6{W;}`z_kGb2InTd$BQc0AwC?%&- zwo0pz_Dz(c5>1P?$&wVJM2ak-m26q=XtC6UBubGaTWPU{%I{3?xqasG_$I?y?DCLxz0KFIjps^Th%H?EiH*YLMsmVqvTX zUDObshgXAAR~x_TbSg4^dNHUlT zaEOgub3;4^_Ww&ZZ!r;vHE6haWoPCO{2COy;Kh+&QWP-4j$3g^`^xGV{2H{Y<;m2T z9Nw!ziEJN4`7NG3Q2%ll1*n}?c{_BOxCTkjs!H06cmV(WnL6qt#6#?b#bsxo$=dM! z3{u;QJ0Df^eSEwA`NVE62i_jf@BV$>Vo<1A4-fA{&rSyZf_Uq;j+C?T7TFUJJPc=$ z-_|`Jv~~AEo7^m_ijx>%R?GczZ-}?EVc`5*5bp)AS2s95iv-7Ci-u)Cz{gwmhp5M# zQAv=`j;ovEX1B>3A8#v}yV0Ky^B&%cY#-JH`7!Ob$vBKqz%H5RaWy5xc;8GX(cLH> zKzfDT(nrU+_`GGkz|{!SD!#{?w2@064SBz`|CvE*bKvcMEhviZp$W# z@o)y|Ik9xoUWj*Rlw9Ili1&nj)~i;#_@HIYCNXmd$4eBPo~YH50$6F%NLvx{dhc_#_(vEx*Y4Ch#%z{lIG zj_R@IH1FZ9&-UR%klz;B^WPi4P(e(`qz76Di1A)fZeQN>eGAw!|MzmLJ@MCD1#{0$ zN~AgP{r-QXE_Xf(ibC|4$Blj7qQ!x?>uiNG4DX>d)46zfuk<=T3LxI}+cHmCc-PLU zIamPkz7rlUn`!BTHpFKwJ_YyQ42mNv)Li;Mn$>t<``A69$LGoJ?zaa(Ip!H|=MlON1HEG;JnD(&?b1>hh39GJXx(7OL%<`jZ0M*>SCIha;W)@rT%J7Q&ZN zGu~Tbk7oNI%5Un;+1GzoQ$YRIMt_Yi;uD$Rp{;JvBm#yF)o*h z0(q-Xe|$$UAj(e!9i8e_ zOaVQTN2?kh5aX>a+&7gLZh=}FE-%>D!bSh@UlMgtn#T7H5{XM6qc_3^R_BlP|9TvF z`&etP!|;yS?rDgJx5W;nvWpP!8qb^QEWF(nR@KTuyhZ+$%Ov>upxuk=+v5@#pkE!K zJ3zb}GzNMezy@hmkl8+;*->ErjbOE~nfQ3mk997!Yp48;Ykqj;Wri_6-nDrHYQv7a zhxbCZ52F0~_UMMslB0q2N&OcBDv9y-%v^F?d|M!RK7RFcJ2~S1|EhAyfaT+QzHg8w zsdDGT?f%1=zhlPwe_al|y_GKNVtBtC(lNlpTjfB5a~;IHYS>|r6Yu7u>wZ@I`k+Tz z=O(8>yk8x3kn(|e-@B!<^BP>eWgL{1o~}a&qy4Y!Z|mbvP89XBKl`dt{>Eh)?$T5_ zjz2j`a+%w4=>+dBZ>g|-5asvkXpW%GROmOXXwm)~#CSKxyw5BS3%w zzx|(wmr4g|GxkKO91cw0QdhFaMYln&;4WP|5^Qi-%4L0 zyc(45-f?`uvBP`i42?1Nm@t;m!sBy{OyTfgO0HJ$gEmBlLQzBpzE2hWLbV5Ps#k-Za0*U*7tyP`(&(DnG`vz%- z6L&slpRx%t`sW0xF$dm(We$h1<*mVXH9dlF z$A9AHDLsBL{v|%%*>)A)OHFwXZzZ;mEQ0)evs4{}gsDJ0UA}UbC^6oq6u&Y-?NG3= zy=7W zyYPC;=H}qhE_}ST3~O7n)u`YBJMQ%4=*2%~;x|b5<|UnJSj>BP>#%*)66BY!?m1s= zD+TP(wCtAtMLdK2HbUCCG&Kk;G}ErH{lmo!^0vB-^{xL0?*G5TosWnbrY0GFsyo-7U=v}RJpr_L!p7aGDZxi9Tt*XjYFqa*7eV>Gp+#GzoxA_cs zNZ9fo-sWr{TM6>Jr(+xY_$viGU=*9F_Y>nyN~PqtlQ)96X}3cq)QRyvr|f!n`l1oO zZ;&z+x$~h|Q6`%lHHNn#2i^gb6-qF?%eSSC!^3;?(`Y*ybol?&iyG$ z1?Smux0d-lxlF;wTOsIK$T;r4MwmjWL{@{MY{zb#XlKd)WV*anzvDr-f};4QkS} zk-)1#!7fe-TVeknJpV=b4p@UU-)ar1!5S2)R3qfz?1TCT7O#0_&j8l3sDmo3L5GKh z+n?&eD|RbpT`er8gDvCh<_~n^*Pz7gK*b+1RIr&HSL|Z^7FmE_gZ7_wTu-y(y&ANO z?PCu?enZKgPYl*mfZnv=y~=9D4brwFznA7sSr0y?=ueSDxHy9(uRCpcPb&Y{AZ6}+ z^t)|1DRX^nh&AQFd-E~09K(BVii|iO-X!fKHE9s<&}N4g7T%fP0`_Y{ynUJWlbD`9 zsP1B`#(gW{6+5BF1!h9LYtD=PItcNe^!1O9;2}DA>s&E^*#msMbIK*Jr){EwPIg?z zMem<&8u)leUA*)=%bNG_KFRj6g&@BVW^X1mzMuf#&m+GtDih<~YqK@|>C-R}YA}#- zhl>}a#AxsDTs-%M@9~~Ifjb{pHAkkUq>bSXIPl)Y=*Y$JuJj%d#lzduz4OZ%i1&^i zn@n~>yf*|LCC`I+x7K-t)d%^Y=8IJF@x0FA{P2$kniy(X>;jAv`&)!ddor%yh9eR{e|H@ zx#^||9^Mnajn}V)cwcXOcASOx>iF9>W)SbXsDdI&ln**u7Pw=!2LlW{bq88PycgSk zHL1{P0RB_tJX-vsfY8s)(wDOE_y2d8osDerq=IqmxKEpNzB%s0$6Ko=sJO_1_wY_* z`_LfBuWNJF!Jl{G=ER{78-GqD#{2ea7!U8co;!X$hj{ngyC=fhoN(5Oe6k4Qou+$f zH;L|pMg<-z9Ph^f9*-w2XMLQQZt`ezE8KfqE#~075T5_1+^!J+vI-w>5#)8g+;S=q zWyf8eH@y8v5I){$Yw4atJh*yGVf(mAkl()T9zu5%X<)mMwbIuA!`_=TDYmeMLHv44 z=IpD7@?Y)bd%UO2;Lb-=FPSC~pYdP+&jal}VG6JYE#{~}+wRgdADb3<5z+O)sMEI;RshHcDSzr&UR1elWN>|qUZKj++pz#;ab zhW)vOSUPyv@91{s4*m?%D4ZOURYV2%*l{g23i89c_%#Sga6o4|@!k+?%Jwl5|L^&g zb)M3*Hm873{fzFdtXkH* ze>O-hIq=?k{6YYRx5BYWQh0cqp)L*5aELWs{k@Ha_qQ_!({v!-<=#4Z@1A<2zdTK* zB&=Y7yT>eL7C^jT6q1+v!v?8s;hvOmS2{R1DzB}bgOB&n?!=1p0xCGkj@!B3BOo;dIZ7Y|~6@|CAK3CGRwPAqR9U7@B5bpyw7QT27m$$<0e>ozabnx=a z)(+KU_;`1W4zC)`r-BxC+|?IUUo&}pyaRq(D|EW>9^Tz-AKnD{<=1shLY3+t5Dt^%jdb@ZMrV7r?4_ zKzcC+5AT@cpT;eLc;~Jo7qakH{184<9^&nG^Ppoo{6Kou?a!XQRt%t5Z%CJic(u>C#u{I}=An{yfh`0a2etBmb zAM}aRT(dGbIYGBI?NWw#&;Jw0oCNWHl>Y-9Fs1{;*>ClKhT`L`3l7fkOQ8Z?c3igC zpR)(Z_;}meoC$O1!MV3F+sAT({3Z`nDeojxfwR-MCdE0#c$Xff>>QsS0MuWY?O%1D zi^GZPwihni{o#AONwc~1p(ItJ_TTqYTBcYUxU0O1W#x4;1N4hwhyBG zl-5l8s-i#vkDt6k-9m|LkVZ~b?l_?+v`@;eZSV{iGswXk9qOSK{9l9WZ*k{iO@xTn zKmGr54!mPBKE1|<*aC)x3?AOvxo-ClL%fBXMmtz|f3H|Rdke&yQKT8t=Hi7KE!(>} z$cq8)ysbOc1&7%E@~>_8s5ihTWWKz4@QDuSZ!PYG7~wCm3+k7=D!)qwTi9{?a_#Qv zM&jdLm@(6T5fAPl3A25iBgk*}qmI;xyClJpwUSX`e#Cg6>b1XGf0~Xel!sc0$#AiQ zL@H5{p2`2uTab`4u6$f>k)I*ZG&X}=#({UV>tGLt_wLc=iFkO626~8HfOxN2?QEF@ z@zz_BZ0iB>Ui4ZiIrxbedam+Im8c86L3-V+@z)^UXK!i_tcCagAIw`Xp3LAU$XMm`{-3?cC`LW8jI|9@&z^ zpInLY7K|7B^y^pzx^Bh5N#!77ya!!&e-d`R#P|JwDLIuZ9|O&8gLB{x5}ceY<-j}2 z*jgIHo1R`MjfZ!U{}X`+5bvUlg9R+SuYG>?3qZUL7X($*d3&QvWM_mggohK?hz?a| zK)go{I*(n{YyflXOFtFAp##c3a-o?PKHd+1eIKa0PX!|ExH&K1oVEHFyk|aBBKPoM z|KG^=p+b<~P>lEFfIvx5;9B@GZZ$F939H=a(GEtSSF_&##h)yl+D{-2zX zCvxS3_Dr$-+&_;KFX6yDa>P;&!+ZQ-=mb2xB|iC#djs(fZ_J{yHYf5UXJgp_l7|3eB`zJ&1b#d^56M?p6KxZJqb9(+HusNq|249 zSPk+D)l|T%K@C%u^-91Rv`6vvk$6~x&WVJ^#rW%*K3yhRP`Ta>4L|nG=2Z;?Y>$hy z7n1Em3sY{CpPkqMCeC}5zPO7HsxQ494Vi~O#Li5$8_4)h1t>et#TZE;$KltY`axsM za2_0DXR&?M5#*=Uy|0|9MFqPu6$8W5h-=VYi&*#Wym<8G%4c)0?IJ#dN0cl&&=@4(S@7Wlb_AnyRn!7cFgbE_yjI*DNWg*Pl7KHD5+L5&z_e$ha0Zz@xcum?wH_$-*yZZR{qTbH?B0kxi1(4ZS%+NY8o*h`c*$|1 zba2!2@I%FaxgcF;bG)*47ZqG%$2A(xD!C(qk2m#LMac2hyodJ`whu{y{MMK++jrr$ zB(NONzLJ_kjCWnU_xZTv@#sEN%R@dlxY$9mxMIKHZam-PO)}@whmG3TY5%O=+Hl|< zuNXZ2FW!=eWbyD`K3;dcJ;YnyVPiQ9@4l#4=7%BP$*$p+b60qx?ibqUHE(7Bzcs6c zgCO3E9Vg9vsMr94FBy&AE1`oLL5(WOKls&qb^YCgn;_nm?6~#slSn-t_;{D=70y#| z=RLe#**-21 zVukD8=SMtI`$^3ztfRDFaNYl_79z2{F%=RHmlwVTKhoxnbz;<4#bpNYUW1~oG&j7B+@2jD1#HOCwhcA-{eRcjGR5poG_af3?hcbnLW|6sRF(9JcaRo#_#7+U z9?thONXJI*d{}*8e+k;Jqt%Z9lWt9T#c>(RRW{H&2mtgRDzH9 z_*%;Yy1_J1!H!!#@}%lR2R`1R)%Rc8Pvt$lF&~==@=Ge#{IZ|d<^d?%^R07HiLBJz7?yAbbPFWvfA4y;AD6-|F!@`(Y?X$ws&hj@Qp8nVY( ztN~arzoM2$j{?Q3q#jhG_;^43Q}gjd5DlDX$89Z<+WhD}KHg1gb0@d+Al{gdCj|NB zO_`G^7*#N={Xw&*r>7e}2*?r}0{$G@|ruc(Nf zPa@yrP2$!^xxazbKg(P89C$N&q+2k&-S4|8;^AGS7%}t>;=N-b-GsF{@uoNF{b^Xe zFV{cNv(0x!74o}ABw88Z@~OrabBK3~%i0~~QVqZ$+dFrsR1{GC=+;%~i(kFXKWBKv zBQ&7Qj(fQ$-)q%je7w~r9f>)yk@xUk#P*>=ke{<5@+-;wd zCZPcr8<6&5;<-1;Fl2_{b7{VxoRH>m=flq4w_+{4-txcw|Gx!}cYlEWzY9kVNr?&cW`$dWO|4Ebr2k)V1 z{;xs5&T!=;bo{Dx^Alq;$Tb{zr)`SM!SH@((4~%tcZ^fvyEzc=!=!3jEX4blqmkoE zi1*%$cQhYvaz@48z3cuYmJGTzg9_Ck-g=8{Tx)jAh&+@M$trkydSKL zce2u=furoW12pBAjivZ_FO@K5EIrSAc-OIgSPW{IU3-WQB2X5iti zr|+V%4B}mMj=7bE_w3wdSGPdCZ*_076CAe+{a{-nIfs@E7No>WeSoXCvt}&Yy5u_( z$nTV=YpPFJ$9Oh^ac<9)o5J0E)Y^#gY88mr!`IPgxD z@fXDKcHO&I4G-@{H&tT2A>NNgx4vTG-Q%OFb_U|@EOb$avSc;-XZN=CUJ&nqd!LQyKp*Pw;#?Zh|c3h&&fy+f#@vFD=YufHK zH6@phbZ<4~Ht2rlv z`M>`c;nGKkl``uCX*lzs}&%3#Jy){5Zs$q!#pSK{b=FZ3EZL*;Azw`gR+w*f~25XQ9M-4iZbut;NL9SOR z+ITf6_@v;rOuHge201e?3f7<{-$lhNU=1qpCoNJt?})mdcJa2n&H$tum3zMOeQ2lr z@A!^(CTQ+Hax&hF4qm)@q+<6k-~T@}ESPX%B@MK)c> zBeoAIg8Ww0iagzANC6wqJ#W?(5HjWbC;H!hUiI0iuzxTPHD4oBJ+hJbfVA@XrLTv} z9r%6*>88z{50x(TL+?Kqq`PzAeK1(+JchThNS78K-k)B1Hk3lVr%T-xiH3OlA4@th zAL8wH*7xxa87I_QMk3avfdPIl7{Ac~;$0J-7gW>11lN~6jCo{32Pf0at8#YX?;v&M zzgNs(K?C{hIQ?lW&olJ#hgknBG1kl9@*duA**?4p@@rrmc(UXK1(5uGe^rhW53!PZ zrO!gX#G%cHcb2<8=Hh^K_z~aNxh{N9n9KG3)>|JWfXbmoMs>6u*&;G!IVO9bMbPJQlm^9>XH z&{Da541T>8E79TpO%;Cz`Q-QuT8$MA#IWN|eEshHISC){LkmS+ojQ0A?FT{9<&Ttv7_z;ioSMt91L+mbLgA}(!Vt9oo|M&kSE`3}T-F+qF z=ve>n%7OO*;ShjT@3VKJXXD}h!{kE58;G~kP0JP*-oD=l)h0l^Uk_Eav}>+JS1rv> zvj4*Xj*7+CpTpJLNsg8K?{+i6!yhFZ%)Y?;{~Q~C{Q8%V6J?OQf1WO*flzkbl#iC0 z2UGF!Ry%+9cVs*7;XRq{Lxmu}J(Ts@9`JcfA>qeU>idZCZc^6MkI79!%eLRyEpI`5 zyrt6U#Gk#^9em&alNWO5LptTvwPe^J!MXQZ4!rj@?=r>kp7UtMEIhnpY-~OaL%dD> z22ELeZxVa2UQva3&%fqzTPtNHO7je|J3&qc&AaAkJQ)j!s-GNj&!^y&v6pcpV(byM4pFNgVtzhl4M~GQus7@Bofvjm8!~A{dKyg(Hg^E>-6l= zm@>IzWHSa(G4(s>q|k@Df%TR-4NUN6Zp#-hT{?JIuxVOF5Pl6>xVNkJf)WjMv*UjB zzg3R_`gAN;nGLl2MX&AQi!(?2i`|k1qx$BY>?L@Jv_W~Qclg%g?K+~ zutVq&@2@h?3&umdhb5xrKM@0o*j4KmBIPUejnUMpw4DV)91~+hqpT0$9;nQ0z8aGn&oKV zkNKUfvYwhTDe2;gnJ$F7*rW#AkKQuOj^ya`j zd&VachWEp!W4d^FhXp^MYYp+%aGtS&h4-Tb!+TwD2ANvc`abNNJ$hs50)0<-duxoq zqR=0(|G#Y>rg5N&34EJA6d!vX362<9h6yX;<9&5_`y77}8pvkHY0jS9cJ~cF-cH9Y z+>Y_!4N}+HJ{$=03qN0fJ_4>*EB~pwdPs&C?}(TaPD0P((dXAcTYf)Ui~HaH?c7K+v6zulFF{8jUr}c0OZ**pq7x_C1UQQ(_%F;;Hy} zJIN-ut{0$z$?UidxozQPFYxiUdh%sWCJ)};>df}Blpw#T;?n^J@OsNzX5=GJB#H4B zWoW*dt&xDX%^$wj-b%bddO_B=bU?+)_%H5!`a_ZocRpqrMU;vCbG@Y}2i}>FU!1`3 zKHg?I7Z2~*s<&igA>JR>x)`$d-j1%zk+6bz8@?!On`7gM20oPf^Ya`7d3| z+P~T-wvQZw{BlCpUow3n362l+$7qNV<9%}GtniQO3214g=%Qr_TvTs^d19?|-tm9` z@5!ByNOwHFnpYvXWRL}NNPmtfFQ}zjU z$0;CAK`SuNins=SJG5GA(sTwo_2{A<yNf`=VNHERQ>sq zu?8uC1MlNbE$!G4`{48gBRsrkt}?H_2=Tt((lf-uTh!-q(hG>UR+zC<=yY4utVB#Y zn8pB62iGej5O3>Y@ARp$NrQM#UCK~b_p(D5T*(T`P+|!yWu4wiI#7&D7IFHQ(^~@}5l>HP(|`gyE_C_X)0+SCyyf2Ov!2Ko z@*duUY#)0F@_Qn_@Q>C<3P|><4wBF##=AvuN^AbM?P&Me;E?iZ#QlHV{`Svzukio! zR^0gxu6!&kvr7ugADf)`ap0X(Dft=0d+oA$26%Yq{C@D71pEKQnpQp5-dkpSex4n~ zds*niBGGO;^lY@hXU<#(n5UpWkjUD5OHC@r0xC`Ov{|sb4uW8-MQIHU09e z0!&e{tNXblKzyG(91Mf2yI!YMcGt{RE;^E!VIkHg~;w_*%zL$l!ZsB43 zEQt5}-yO9ziq>fJ@xB^a1qO&L{B`In?ElwZ{8O>}A`^6y>@LVU!4ITWry05Z%M-h^ zEKMr5ET@4+cAQFb&9_yP@P}A)O?lUY?|Bbz4Ym)W{HFK4l&+|PGswg{5#zmx@vin% zY_uAPK^q!$^MlWGam7xjr2acUZT@eNmJ4y^BjQxW=z)`CGsqwgyie0wb1}S44}3=O z@V53lr)2~2)<5`jWdy`Ka=cYw1jO6bK`KNk*BZU^N7iQMBnD_(P^Ix0;{8?Euj2J3 zCUCwlYv*Z52cv^blK&d~8DvtALWdYUAU(p4%YURPFy~*Mw-9>a@{!cVdw4V0K8W&@ zyg97%Yz7Uyk&WALz!CaJKn>4KHG;RL4E~=d6TLxQ^0+Ldd)lk2fUN_?Of*IM7(-S>yjx| z*twhU@s@iqT*8fy*p?|(O8>0hZs5Q>|KftN<1MVYw_kJmI6S<|U)%|dgLqd>dacIV zoM=gED-wiw4@IxK-T%P`eRSP)QT8|n@S3kS8U*p)abC|R<^~g_$(MCMOpgTJg`zM$C(Fo-fzEzk9W4sfP8Zg@8K=R_K`)9-=aGKizLmdAj&VQ@th-Z z^-jq1u^um(i01D7^7_=dD&p1KuPKrnk8kGxx%V)aKHhljpYh-Me_rnT|0g%t|A%qZ zpyEv?bZm(AyS+jJuLk-3C^&X-MUiQNntxCjtU(gzrdz&b)u7qUjsgQ#=;mt@Z-&<} zfb*%72l`qx{XOJ)-MEPA|?%vb7n+jaL%Dw(%5Z9pPyEZ7dKirOncnuxg@ra8W^zoU< z8Ru^PuR*W5^--a(`Oo?PP!7C{=KpZU@E*vL5y!*3WwX9_Da3o+cdki=}-O#lyR9;&ItJ zi1$pYuVpyId)|7@n~x#hN7dsN`RuVmYkzLq?PJ0K=94}@$$)tOyd$~nYXK7&eYj7z z?4Sdg%nv(K-s0me+we0Y<|++LV#i7Kgm$@y;p5$&I%kH6FYn=v`FKf?-}je2J#ryb zAYI$$_B)vv?-}-<6}ojXXlikI=oC;(ID-tL95&30s^@#WUw+8q%12_STk@wJV|Z`k z!28_ekXabsf7D7v@bETX6f^J^;_XxCdVz)aZQI9Jsv+JB7bzayMrvpaVI52{rd$_;^qG?G+Poh4we@)y|&#Ju&!ruX;F1 z{=FCP;f?uNO_1Lax;N=-FBR0TOu4AAofvNq_nnq=>tj&T!DGT7B#8Te(!5RU_HL5m z|H;Y72JU=>%i6LhCm|eopFJJ&clFjNHc1!{Z_00>2Y(>m&dsl6S(_6W-U7J`oI_Vw zp>5^eYMl`8&6#ar2QG?3;Hzi?1ERZo9 zk5_}1imeM64{K1g9>rxdtU(bi&N|6(h$Z#kIppYKi)v0a9+-R__W#%1ceNIDe{-eVs~M{wYMLFn?|8RXFTmsC8w&n2$kvKZoR`E+zv zD8##K^QDmrh_^GjY;K0%og5CU&cTYc8K8mF@m_@V3s`nNSyh|I`HeuD< z&bpX_hxev~&ncb|Z@qGd11!8nh1C6DL%fHB)D`a-SfhhdsqZI;Fu<|TY2z#*-pd}7 z)IkmtByQC8`@Js;BzRcPe7+kW@1N@?I3+^7hSSyT^*`p9?N@pV?JIG zx&xZN_Wj6PCw@*BTtl{GB?Zt(O z;ZrZR^F7|QL)`gj8!qbhhj(xP*Z=cu*Z)6>!3HUYqXt#Dzx#;|u};RulksZML5cUx z={7~C(>8nCguohf;OX4iF|Yo}*CNe># zm(8ACg>*m*8oz06GJXvj=X)#n;z!!wIOdcA+x`{!HK23El{iiP z(AW?g&4Kr|*;~CZyxUL_89coA3btN42l1XiXX9lS-utF?uGk9k79u^p(_iI)UaVZ= z+w}$xu}vxo*%0rQLreYqlbHaVh<99K)YK}zyQ zK8DGM@IBrnPwssDj$SFW^wL;^6vct}RmAEZhIfK-<3v2X+uvVcR71R%Sy(G>f_RfM z`>KK=-WoZx+gBIbqkmp@AtetPK$9}hGZ^CiYxScf&s|KQ{7irGBnI3dO^ThZ;*XEF z&jhi1C40gzNa5s!&Vl!3X6z&k?^yNo z(s+0)9SfQB65?%cm%oFBw{?p$%^TwVL}5XdpPL<8=_x3<=L!SdlRmP?4C4KA#9eFs z9wxX|`+doZV{|ay?$C)ziTHRIFU<>~zlD<%c3fjQ#CV7Kt-aR^@qWLm?E1r6E)FM_n{|Gf;K%n366p$;K5{ea z*zf;Ea^QU_LpvG6TkrLz33zz-X6$etf_OjMJlxO1TTFcR#L+*UoJg<9@d*#3W|9_fn9{!23Hkr&(gDTfp{cVu$hv_Te)gWf^op+M3 z1{tl(oxc&*pbfWI_7A~3NIr?nh#1JPK~*ngbpLTq26JoYx`s~gLp#jh#i3i7z;CY! zC4D3kY`8srVpJ9WH%ND)-Q%5PrT)fs-`VwE_Y3|Rr0qJLv)8uqUJXLoK4J;-n{j%V ztXnD#^s7(kn=d15N<_@wX`cGei=t3bQ3b!^65=~ZNV0S8r@sm2`xzujfjb}J`*JKU z=CEdv$>TWiMin0WVMFYOx4-4^@NWM0+(aGX&6uBkl7)94iYgwBxEH#C!Pd((lhA;q#VC&-VFrM}onajkErg;NyL0;a>Gxn$+JoYnOr? zx%c>ZSIYEHUG$ju@XlcSAj&WCgx=jPwo(AGo_njCLX3BN{jHjW-WXIv+Qh_R5i#Dk ztV3qGHooC|yyvXo&PRc3V?gQ-*78;|i39JOKZ<-Xy!(dgr{dv#Cro;mImG*qdL%U% z;=TH+YBK8s>5O?`k@_`fRNUEl`l8v%VE=irVlKqHSIT*UZZs1tzBp<(?^PraxP1LW zY#~10mR;=+nb94&Tbn{eRl-B^zIN@IBsfT>3Cr^vm564T_N839y)Xu-m|;j4JJao4HcucuFqbHQjcBzR6t7x8lxW!s1R@Yr;=uS zVwvD_n*NkrG9AP(pe{N41Rw9yU(@>ogrz_nJI?Q!U~1zKe)azC);TV}n)mR|XZ!d? zklzc^Xn21W4KNU9U=u=&_fePp;xOY_^aEr3xQS|a2v=`Sdp8CrOnuDv4boCtFjqc| z>TImK_K)Em%Ypaxor8&3_0F8=Hw6!G{fUfc5fJZOi??rBc&iG3H;9LLfBtmh`SNHd zGZ3|X|d@7Vw@M@5B zbFTCbYk0-(?!ifcum<^e1d@DU4XR;w$17}fLkkv$-O1RQ3hCPtxoh8Giczzz5PZx$}{& zQ+l}epZ;Hn1Miv%U;x8Au5w@+9^O)lN6b$^yl>_s3>Mx=nOZR>5bw(!vM=PWxT3+s zq03SdlR<}Njp;Oq_r=9dQ~Lwq2hzVQNi|K8;MUcc-<7-Z@m^~v^m(;~6u8ZfYkgDe zeV`p5Z&bllYQF^U;k}COqmm%M+d^Np*Xc`vh?tH?GnW$MeLel9{O-p|s7cQX3+Hdd zco*trNgV8Z%l8dZ*BtJAv|dC^+Qu$OOBUq7yXtd@B!+kDw<={kyl;l=-E$M-9jJTw z3k&Z@&R=@OA>KE1D^I+5wH7^msBOuKm}F2f|Jkbn*dR$gx-p~?!UXh}Ulkp$M}o`E zXI>a?!N>dJfc8kau@tz*j?=cfx7PGAKHieGDI#`c-ov|u?Sn#)pMK-uaJV-O1X`NFw7oB54-?@&V$I&J+N$&)9z*g^WZEp+`9{$JiAed5lClK!cM^GnB8Zv{B;zEf5y zjp3bfDOCv%?-jLA-#&+UAG;ps9R%^dn-OsAF5H}`G@&${Zg)W~OD9atibw{_ZZ62V z4e`D^vgxUBC=-0VbY-LK-AG`&JME+*10V0w3D?Wj^rV0TJ1%c)gvh+-_;_bcnYL&0 zPu^>gir79f3G$0*UaWWL7!8O`D_D0^ix_X^Svy`$`WcUEY#X2i9IYYj|4*vi4)x7_ z!uJhQxDj_g+QU+^zU&^u8{xqF_MU_g3~%cX{)%{bi@Ke2`2z8NEcJ}Z!h1C$^PnB# zoxT6jkrGK4^wP4;ex~5mlR1@M&a@l@(@3H>}`u_kfeSFK_&w9N@47Rr&NF|9nNbRCFQ}0nLsD;#H z)O2bBHJs{CT}@q1T|m{MDpAK%1t{Ms?=nBpc2ew+*iJFJSdf^zn4Orpn4XxL*kmy=(P7cgq8*}*qSd08MGHi;MfZrt zif$717IhL`ENUpKAu1xyS+$EfFP= z@gf4k--X``w+hz_-x4krJ|UbToGiRec!RL3@Csp5VI5%=;Yq?GLcfH1gkB0g61pQ) zE_7NbOK7)Hv{0~+r;vk?h0r`9bs`TWkj1}>cZ)w4e;|HCyjVO>e7|^-c!YR>xQn>8 z_(E}Q@oD1H;zD9WVjsoY#2UmZDW=E;?fMpUEBM zMshXzGP!`9P2NL}C2t~olby(m$%bSNvK*Q6KWiN0F8t5W|NX@Ke*=<;5LxE_Mit|! zdRvh7n414S?GX}yDMPeX16hYDgT%s2#2-`htZL^Xewfl%ww#9eVoFbBj~3#CDV zW{5YY<{ns)fp}p`+im40#1m6XZjx55I#L1u!h&iUjH&oXlW|$JQ_+f#VVoFr_a3lgS zCH!pna%3TMvxKCo}foNdr zGt(U)GcnbBvhEV1j;WsYhJDBkOnoxS{Dr7t>Z3?sE24_2_w7_NqJpV+#Ri_pbWC-J z8#^P@F!k2@iVdQSsjf*HhY%%9b-tUChA3j{b=m3nhytcM5*Keq>^ zTMUq?m}={N@CcE`)QcM?r;sU_YTb4EC^8vSEskyKhzzElt3D$mlQ8v+vU3kI5mQg^ z29+bym})wGim8Si&0PouQ_KzH zS0Iv@syF=g4w1lA-PBJf5phi2Z%s%<#4vU5{C71(6jOIY6Cx22OtIG65n)WRmM0M* zOtDsT5J60_nqNc!Q>Q~DahY3#rm9| z{0&pAub;_ZF~z!vnEVA(tZQ4zgP3C7a!DS*6zftzazCb6cc_v3FvWV!i2NB-tjAx- zy_jOXl|k;o6zgdL@+VBOZek~YWGfZ#&2>Gsny@cB_j!#T2v1Fup<`;r+^z{oB&KZ0 zFWQl9n6i3sKN#7HspZG&>W~ObE%V#(0NH}6rMiYzNI0gJOcr~Egkj3EePbySiYbdc zttMnMrWS4f(}--sl)1$uIRySE_-7tsCRb&E1Y-)ciZYRnm|A%D;Tt3fQzrCh@kk)1 z7P!1Rglu4|>8uy7$saJqdJvfW9#gFMQ_1fz#d>a%+>I&L>wM(5m^zx0tw-*{)R9$z z!sIuY%AWCwMDE1YVUpz=@@q_GK7Mh6+<~b>StpapuP}8mSn53aC8jdwX_k`PF?B#V z1d!V>wXb=XDftDa(vR(XN^Zqe+NQW1ato&RnkAN!pJOUj#$S;93{xo`ncv9GnA&{> z874o))UMo-8{{TT?Of{UNq&N<9ZJ`BkQ*_@=#g$AKgLwj<;qs_BTOZx8l;dPVk*JQ zJd50bsd&ZU>0~CRw)g%VB-djqwt9yJxsI(=e2%ByMpCff#bkVXO@4r>XxG6W@_kH2 z8Cy$}?_nx(#8QrY7gO8r(pHgcF}3yhg#dC5rXqZb%gEK3+G0W%AXi~3TqNfq`3|N+ zpBA=}Z)0lnF|?dqiK$JDj$AT|sgT8Mf01utDp-vC8 zl9T6=D=@X*ey1M!8m0m!E0mD0V#@z*y&3rmru=U0_99=#ly5?uGx-vxe5^Isk;^gV zt#nbBd=XQg-;0IG7ck}V{B9_@3{&n$jxHpZV#>{jszxrsl zTn=}TQX>-ONUiSZPgP$Tu?xvS{>q+UJ5_js6fFI7YZVhXZPA?_Do6*WOq+E1eEc;? zx$YC^G{U5S89S~x?^4gVulQ?_KfkQVPqI|zx&40`wvQo#{4P$5HCS&!1GQ6aNBW`PTYoTF~s{pT3?P+jXPRpyz$$uf@ENFt#E@1#9P&? zq@&D*3Fc3@ZZy0lXe?|IW>s;dj# z(Wfol&zL#M!0%w{;X!!3rN+N=o`^dW7)lylI($D8+|xY}CK`f|w`-Tg`d7hl2ZZ;Ga=q8E1ZIE?{!Db>y~W3nVt;nPW?E16XNZvb^hT&FDCGPbJ_N593A}r z{6@}H1OI@uPXGRiQ$nS{2s_Tz_=bUjzAx@Z;31~2&d-Ishqor%M+QND8YjEL(F_`} z6Vbc+!-E)aOUaz2XZ&}dce=bi&ChUgy`{BK-@@Y`_Uv&vqb!)@bR|Y+8W!Z z!Fzc7uzjo`$nWWvh~=+rq=3x+>%D?b#CQjPj*U-*XKzz$dTkGFAimyG{hM&dDa4=e ztM}z`B3$`kRt=<0-k$N_`F}oW|5^RN6h{qW?TuhHsOOfjHeL-1i+X%7#;VA4OO*Ua ze^`S?uBX@!!W!hZCH9uaRCjb%?;q{U2i~mB zJ`C?+<=0wxc#}8zh-5*$E2r#pTnF*4e3kO+EyR0+va~L`#vR>5eHyUnZZdeF7QUGb z@fM_jk1ws5U{1!Q@u$B;f&$Wg&HeHCLu_Z=t?8n026>hpCx0N`Gw&mQ|L>LF*L~cI z_watn_Cb{27H1(>p=c^t`_yQ_Gnae3MXpSH^0BZ6cV>-M*gO+~y;Tq6`5teprQG?b z&AaV}{FxM!Sdf_OK1M;*R=!W|tt zs9YUToeY-u?1*^=m$xQmiN{u~V1nmyBR)!R;P?OMM2)_Mu9c0?J2v6O9f57|{D1r1!#1*1%>Rk!SjY0?=$U)F zbW{8_{^>1*OVY`Sok!??{*SMvu8y8vh_zPk-2Bf@!JG7a5t+AeuIX|t-dnHB823Zo zW4g+RNxTOIqW9f^yf69-)k_b$BX09W4zbpx0ER_jdv`+KK1LT-J#uIPXDcV!SAiJt zo^_ROeLHsdo_;U<Ki zXZw$Hvdt;L%cpfWr|dA2VUX+mL$d|6N{_9VREPn$4BMFxT*mG}raz?;?kd3-q|rG4 z_IbU0{}_R?dAANOp$Kgt>A1gtb?!Ek>eQDvr0`{u?HjqPp$JpR@&oz1+C*Z_rLSo<-59TKYYc` z{^F%iQ!V(s_p`U`*(8~ScrTy5sANvXfV9LhCRWxLH+JJY0{@yK-QR^;2U!Vpp|4K12flcniWB`(JYL2>tUmrLK;3 zm&LMPpPB34JQTc1FLjW46E?>xWAV1P(q^}SyywqLUrgGZa4i?@Xo0+I4h>C$#Hm7SBH>D+ziv)=PgpWDR`6KQX=!N<*`!2;@!CWtduw8 zeX&n2j>LPveUZ^m$os>MpHl}vK;E96DUTnefDA!%&kd0GRR)*43rykh7Ad#eBUNI- z$J8w+Hs8SJ{Uq>n{HYzpzj0f3)>Mn7WAiq8`0&Cz2ioi2&1fBX`Dt?QBrJ3xf>Rml z0^*nPc@Ni}*)+615efgw!h7N>K5qi=0l{8>Hu~@05>(b9mUaK+f9L;E(J*Kr1kV3U zDS8m;Jxx*%;(*^Et%>s?VD+G#2~DhFaQ;sXRjSJz;URa_vx-*<)cPy8O#hS(-vK9P=mU~UZH>ZM`@ zscmaw`2EPX>Z6o zk3oB$3FMtbxR}U3<%X!bcpb8Sm;yeIIx@Y7x3_+1Z;InoXaQMIWQ#KWV}beU&-{kX z*t`o02+RN>f;DKI;DT>U+Rk9}{+_!=(*Gju@jiprftO$RuhK+l6*K@vEPrd)^xqsH?**fZs*Rckb~P0SexvH|fc|(+jdS zv3M6|iQAlqyzlEQJ3!)n>`d}=Ysg#3Gp{JN#0^oiG1uaQD@du(T%i)k`+!=nQO(L0 zV8iWUy~HsVm{S&Jn4@ufY~o&DIfl)fFH_+A=K|W}eGIJwFTX1V z#_|>=TwvLdxwgm`eBKLJPkM`}rXW#O!4H_f-o?Lr8}0Sf@zDg`^Cs-4t`6pAow~jI z=ejpP1#i;P5Ma7Dl;E>Kb)YW3^`KJSKRHW#j*B!so+r8$={KJVKI)h@_vC(?O zzi|qL2dlnvV0Z6tg4wa;QTK}(St~*J&}44 zY5srj?ZkxDgT}jcO?oZL^uLsvC3?ah^hUVs_AY-F{n6|z!bPnfh(V9Z%2V@FLBZ8k z#?tce56FIQBmCQP0j8(B!iAnCJ`a9;CgprA0iN2p*tu)4PlfpK@XMphaq1 zt4G6WuLo(Ob>QWfqS)s6UWE$?Z*O?3xQs;~4@{+NN0`<8MC8Mn3j_8YRLuX|eNMGvec+TL?5Lh^Oi4~>bO*+1e%-dE%k`asd*BoVC0=&fDn>;X1;=R05_lr5? z-M)@3&ic3q65SJ9aAYC{OuSj9FavLIMfIrO@8@p;dkuZ-h;}hx+JAem?mxc&_vC`c z-Uj%9^lvmyswAuR=}+waf5&>HG9rlfc$4dJ!pZM-%Vbx|3>PrG(I!zXjn7*;By0b< zg-J-w;}@rkh4AP9o*u!;k%g0V&zrx4x;oAd{W#L{=lp*W3f`pi_{h9_vWDkl@iu-q z>?;g;3;(?2?*(~-vu|}7A@AqSZ7WYXdLT!G)~M8dP613Sdx_1EclDVn*5yJi;Bx5Y zi5Dwkz>Bs8FY6CtckhagF6sl2cLy4m`FWA&r++-Xbt59GbJted<4vvuFTcYNdW6rZ z!7pZkp`j3AeBK%2F%?(XlaMCfno7HN`~is&yw%>WXqN7I69TELWB0+Ce3d^hNDEW& zCLJ(I<~?%yHUk##>WP`vAg%w`P@U- z0%(u-cC?NkIQhjtIJ@}zZZ05jCFnf|5udkyW$;UoRM(^MbNEN%LJhIPh zp!@xQ{hid+q3C+L`Nh7u#fcCFZ_I8YSua>YO?Y%wSu4C2#eEHg`61YAZ?)FYD`y|l9&d6TsyO-Ob;s_Tnok60ZgYtOR(#%WBfpEJ zMpKcXop0su=TI^K`^8nW6@RDy`9FxtIxabV)BJD##~a~jZdd^_D+CCMy{3FrUb z_2(pW7q);)(m%&MOk;pyQ_5TabnHv)(`LsT=XMc+F&d|5#~hvVkMsW+;%`~~PNcma z)PmNr04KlujlBgNFFC<^>E52LuJ}DjHe#f%W_~cES)M)+d@3)k=B2~TX^nqgr>S@8B28ydIC z$G`w|VXq)h9yrJRZYS;WUX9jq8YjP^nS*y+u5bbEjpv{EIpFiwYIZ6!R!c-eXHu31 zQ!)R$tYo-k*ga17ygjL`V;AGIMXZ@~`~Q*@yh*3}lX-`x3@*gtz5P~+>ORPO0%Xg0 zK;9y62*&du@8X$@YjZAmAYyX$5u9qUds|Q6Is$o{i!fL3=V$?HQ4(cpqtSrH$;yNS zVDtW3)y4W5@?M0-`5Y0G$bN*)dq%b_LoAl|cn_j={KCmE?W(F2!xK*6*)#9vYD;|H zn!K4hmz5F`Bd%Um$Cp&h|7)F$Bt&QEo;QKYI)uB1-+e8a>)sL+yh)#_AoDIUt6;(6 zUDxfbR|0v9^&`0?-shOD#n@_5Sw?R=3U<-F|@~<53M5!C%^jC z*sBi|xj^=&en)0~eBM{IKaJ=n?LvNX)_xfrx`R9aM-|@N(6rKp?&tq@D(kplba8>MF7@cp?m{jJMR; zQb9*?)PyDEy`HE2X&_GvP!_*_$c!ll$kpEQ(%*>9o8_lZWXNtJP(8lQLf%o>+7sk;#0iQo1|k5DoHAND^w z#Px;#=l?V+>p1GJukhdePaE?+UKVivUq;b`NMD{J_aG5tb8f62Bo~@`waL6p-}3xQ zR#(`A>Y7uQt87)#FY2iUm8tH?xulO72}mkLNW$~ zBL+DFcGx{=(N_IJfdnE5MdN&KUwZJQ2fGJ-X_jz*aFF&cvCL>4!#Me+oK8i=TsXll zk8R-xQt*3_x3;bHH>Lzc84;R&_=<}8pCQy^{=xqb=Kq0hRMoM0pMT@fskuw6JOyvk zr_{*2f7oylv3Otml)a!E@^<>j8cX6GsedSd1M+SS4L|N)4nJ?Pz|&wsSt@wKmzo?8 zdCS$NpSJ$h49r@(w|#~KlJ*xq1pygs-jlca&sf3RTUuzGmPxG6oqwz#!)K4$j%Cmu z?@_dlNSyqRcSr8*+Xj!f5N24+7md$b>BFX|$^HbyZ{7VD(o6C8|F0erUF0D}{|`vp zBvMz0!J76*JO1qd%Te$qeH)O>yZl!lCl+tMBqilp$Xjru{~(Dsa8kDFg7d%Ow%3cq z-?$@Vo_@bWb5g;wJ3O8nAnzH@qyEE$7Lf7!+{oztXdt**qkEcw&0B@zx)LW`K`uq( z_`bFYAGnU)y)Rho{8^e#d%Rbob(G`ecYOSATizN@pxkif=fiM(-tR3>bPW$CAgyZ` z_b;Vp|KH?fsiemL2lKxXb#(xrz!NIvbKP5(f;Z`7mt@|VxuqOfyl3P?HVeQ3Nq5uG zMmNYiWT&+KDahM$`~;UVCww?@;3-1G~ops5Gy7)!KnXh+n=YQWFOWg)0oaui4zZ*ea9o}Y9zeWzt@s^?BP5OE( znYXdwZgwo*gZ)Qh)F5w8guj`@yYt0hy#eHXEJ6wSVC8{GZnAaQ=#dKc>T-H9LEaV} zs=oD1Er99U)rQ=*Xt0zwZBsc9cK05BUc}RuNCZM?oCBM%x>X%EZ%v2S%jIZraq2|MPz-m317i z6P5gL{>PiVY2)W`{$EMagGk@6Cift_Y`~AzgGNt{JFbQ+NZDJn?Jlqf%^NN`rW~lE ze&dWbQVUTv1{7TZ0RjKN?r@F30ad zUNy>0$s$q6H93OA4tD%YEJ0J`iN$~?{qG>Hpt6qHh$%(bgCOq}6ue0vWGC~U$HBvg z#oMyrioHGLjW}7EZ-Bhd%&=?D!1+Io)oXUkPd6lahv-9^q8zusAG_HMfl(knr zHt#sX%i`mVw8vW?tphK=ib-|e&|6%Ij1ZMRcj>~PzKL=kg2``I7i4oC-E zl)|;V=zoKBx|zB;dUgUN>m^P6WYd+`{k;+BLe^yw7}--{{Fgd%R1~Itp;|OSrw#u4{-B$QWogZ=r(s zCY1Nr+aFcihVd6CSvgJ5fagoPACO`)sH-F3hjG~X19S8LathufD^*piys)R%YXg`%Kzy z$hn}8zg@4T0S;cPyRYC1QZ(A;uE)n_P~4@esth+ss}?7|PWpk}gG~BlqH+!r!8J54 z`hLv&OaFL+^rfMYby5ZG^&kVZj#ixf_Qq_AhP>a3vGC?V-e2E#YzA2|Y-fn0eo;dk+|9H0Q%REkC z>2v$)vRC-LZ!dRL{*WAp9G9}IVF<%tLALGY`?8_(1Ksmhj-jp&<;9co!GFI0r%b_n z>PTG@xqFv&K3a;!JA!CA*$sI&YGfvpcz4fhIQA6sR_I`}yyoSG#NAo}hjw*1fCTO|tKKQ@UF$h_Bo$P>ikJ-leN>=)$S62mx2;=OOnqF6z=Il&U# zsK6WThS+ArOPq*G153M3JA^^rqfW2(`3^OMR$k`K$%Zk2J+V;C!QKb+UyDIf-%~*X!wO_2=V6t0;I+%6H6tdz*CjmeV0W0W98H zUDorK!uj7m)zgo(_qNwh;DjsWZJ9ik+;zzf@rmLaoM({+3>xqEJ3`(}gX_|Khnqn* zACqeneE(mx#l+?u1NPn9EmLc5ZJU7m|7e`}?0(s60odK%SF`41BscBd-r9uL;e(Uk zEZgztIg^~gwQS(2z;%4y+m~&h*DDl-1oZFbG%&zld+RN<>DqB?J>4%(Vt%Zns*VBi zvX-*U|Gxi6%VYoF+~EAL`9D2KYF@v5GWil45ici&)q~s>IS~PPi6#CL2wo3+5bI>t z1wpuiY<(2<>psC9QM{?}La`miGm@K`R<3G+^%+d*gm1B2V)_Z@YID{{d-{ZwkJZ*OTbJ2i+K^u8w)eYBxTm%+8?kI@=l#s z))e@@8GvPG^82-7LC~5*U+xNG^FH(K;jdHN+`u1=i%h8NUYLf>J9txRu_2&6-Y3yI z0&wz^(q{KHF6II=XWI8Cj^Xnj&AMl+dngd8NUZn$Ld_?3(lT|2+cW5%HzAd}I&|KR z5wgnWZf~vrAKsF`6Hlxm^WJG&CyvGYM`U}q9pqg<-D%?pd0)J*{96g~KKRnK#c-D! zLYPtv=&DZx1#XIC;*hr-o0y|RcQZJlW8G@HDi&PjRP)K@#pYeBVe6g9#tq8JaplAF z`S)P+&gxR!Go?m*ysOYU4&vmuOH|V?ub&I7iBi6}@hd)W=lQLz>%_JrM}LbsdKlsl zNUUagoLz>W=$`i{6YA>F`VsN$__jIT>J+?xna=u=dGB{l6~p4a<#>-n2;|LkpjcYz1dblG4n>SMhYn=NE+T-1V)-fL^KRui8H>%}{;G0eB1MyGz zyfa0WUs*|PN3@d-%+D0u#k`O5cM&Rs1oK&R)Bgsk6qR+%42qqGA4r31Z#4?uvm)+M zWZr{%uA*4Ht9m|2?}NN~`EMzc_TI?6vtPKXb1!#8ijtiKUPIp1Pn{|z;QYU}mieCU zhi1^QpfRamCkCX{mmWHcp9?S?F=apT7N7Tx;w=GD9nna?2pjm)iU01cWn+zc-i~c_-@QK~)YV~~ zb*5-MF6+PZ|Nr(k8vYCHL3;nwgQS>WW&B-13JVJ?!|Fj^E z9GhPY-$A+_Ix$9g;EtGSuZ|Y4Oao%;MKVbP(%n@u8%YCF=95e1wQxXku+!UjVm|gI zRh{TfgKvBcQb8WWG40{RGI3S7kF0mqL9kMw2`C4&U*sLc4=PWy;ZL$mX z@x;tB?dl3)cLO&WPxri*#-IP2H@f_^dz47`J*dKyx;h3AT?lj9GdKV1Qt)QFU=l*U z#D?ee$zk!X(tTrI1bL51%$z0helm7W^a=Nh39EC$&s(bL@4MfLeTm&{Fxj`jh#Qd4EE0E48tVrSlQ_GLt(vZOCy?NqD_saoSknSoODe)111sVUL%PqnojqZ8Jk5E^K zM$)CX9>?YeBpnLgj63JgegBWNgLF~ohAbBEd<|!%+mLsC-OVKqkhegg$@Wi>x6I3n zZ@#C)ueSg2-fz)5ZsO$E5cz!MStA$7Oz9g*5X9%5aB_ zS7f_fxd@+k{hOy3vgJO~J@2e9)YZXOJ=Ilza*nq)1@8q`PJcHiUZ(Gt!Q$Q6@=^Ld z@|lnhctCnx z-r$5DH$HDaul+U)7AhmpleaC>s&2xc{}T;ss+gncfBw&;vX1&ATS*6`!L_#*1@HNs zvoFYtla)ob(pbC&HP5imLf%i5ENAArch=RLM96!=3fA&(s_w|e%zy^F8)@KL&ATrq zkoVF0z9XL@?*OCzM?=}M;JwD~-3mdznEzUemiwgNljR1T2FR>g&>_;CYxIc|qcRGEQam6I?;+iJwf> z$#q9wiT8&;ge%CBn*kSxA#caTx05&E4$?by6K}!V7;v@v`~lTW?C$+RuJV~J3pcoo z#?^n=rSnJ~`~MD|-cK9HO=ypI7h1>5-1*$)l{(S#WpMp25@uV@CH(zG50v2xuk9x~> zkavt4tA!op9W3?2(hc(FIumNw(&UabIln2aG7k5D>pcW#zjST3dLOf2k+#U zGi!5bk9Rm)$61{GczQ*Ggy8)SNB(GMUUhulQmG@hL&AYz(kAA0@7=qYzen=goA6}^ ztN4Ro^nZKn8uuy|tDWKlW@OWI!A z4_A=YTlY`=hAYS`-alP+gk!+w31@kcx7a=9VO{*WRCjLRjmEuf``Xkojr|PL{8uWI zZ;NQJ2i-yIn1_>J#fW2JlLQfbWa`i`K7ikY^k;Rmcu@mfGuw zAn&9|apBMTZiqnYy_CrrxPqMW-9@^+<-hns8aKSXwX{p)+~{;Pc+;3C|L`9#NV|Ci z-+yAw4LZ;`WkF3N*M4l?UMbwEl}Blhw-Z{2J5GKFO4Os>yokX1wc+}G>G-_)L%X-V ziVH>72FMHA-@1)|iDil;ZU#H(o;TrF1a);>ulHT{X9vlYf;TZ~7aN&3Yt&^GEZ%xM zH52n7Z*QBDOcL*~_1*{1lkVP%Z)|pIc0+34^G2)~Oapq01^b^u-s4s!Vug^m)^sC# z>FyYyU^{Z?mLc|lG&NCb5n{{@mZ5Qdgh7#|QrO)-Z|m=UW9hWVdkn4P1WtaxgtS@f zgo&U;XHSMzEI#l2_*&%bv;*Q?sXFq3ipN_Bi!}W2hcnRqfE3S0T^+aHtshbP)4fe7 zcyleUB9eKh76&O~@!tRV@~@ka_v-7C^GTZ%^*&3_H$vVI7aT}P{^f@3R9jo9|1u5q z1;ae-b7*5w-Vv_ysZgQ$EFWhAiiC4-(Iua#qHi79>fM*YxSgi z-pTi=tHZaMN5(yFZgFBv!JA{2SAonM>C{ug;w}Gbt9J+FEy=t#io~0+!24Yv5(lVD1HXN*Ge3vC`7(dKJOX(;_omeF9*P08p>NovH(+<~Eb#Mcx(YX# zM&nK{X{jic$L4+5{?SI3NZR9l0IeevCqLGvjY6l2i9j`{xF9$XpZD{;l<3+J3nV#o zXlAg!370qF#FxhhqQ>Zd{x7Anj?-Hr)&D#HkJcvr|9d`gK(eCfK?2vk;z&J+6FxzD zVVxTRs|RWP;D~57F4IrTtn;vhJt)^=dejWwVwXiGlEnwz5DxuvFpXBo~D7_gR0q-9}%~4gFrN{dGtFclO}c#+VE^4gKs_U z^`J_$4kw)ah>0iLCu_LCqbGgmzg@=fK`))6z5%y&NL%Bb|1Vb810=@4P^6 z5Q@g#DYUqxC5g@3e6OXHdNu9wK91I5ij$w;iPh`d;1i_NUXB5mO7MAGnB|!7=kZ3y zj+EPMUO@%#PS)a+P4DQQchM8->QL$GZ|(T=dCRpFy!keq|NHdTxXDRPEZ*r`c061J zSCGFN%1x~x@9?aAiR+Me*Ujn5;xadcarQ=An_fE5o$?jqfxM3oc|ZODdH?26w-Q|& z1FF+TljRw(yLVB9O~rs8H>g14x?MYhr1-FTTkraz@x6lfc%MP*u)@i2X|ZRDh7A#n z=YBT5at@!j#QP96Y`MvxmP+hB;F@Izi}|a0ckAofy$~>H^jl->eL&>bTHVcyod?% zR``<4{Svn%l>iK}vN&>nALw2nfY{Ina2IqJuWpxw@7ox}fP?`@w(yoq2U{>O=A zkar34A`x`oy<2Ojt7GQ}_37}`|K9)qzYp9r_D|vbZ%5ICL>um;k>`K$c}`4NJ*Zil zH$o2%NY#N#OV+?129rpJ^3>3EAc9tHF3koV6++5B%5V!*Sdc^=s>u(@XT8t%Uc=l>QoF3v4eO>Z%F ze6M*L^Gh1My_JF1@eU`yv6X!(g7EQ{VjkN=Jx%z$*Z#cvWs{B#^6{{xg~c2EBX(+3 zo_-2$rT+ucI;gDUV!uqu>OaR@+EDNow%?#i=B@8PG9Qcgqa6L|XvlkrJ9pk%$Xox- zQ73-Ldt{AW#WJD?^22f zx{7pb*&zF@!COeceT>X|Mh0QP z;%)PB$JrdnTg-bRlEnMsSLGK=A#V%6==b^A?#NyCNaMz^bWkCF9-*3td^-$`X1cc;b<#vhvF zZB4;j@H=xWnYXw7@p)LhM@|lCRYKl@^}Jt5yic~DOA&><-`zeQLRjFA2#kobY}}j< zGP4fUNkQH*%}%z5A#cBT;kEJ-G2mvBre)JJY~CyjG8ot+xWNrH?#z1C-3)Bl@ug;M zPqsDD9&aYJj$)krB;Lu?*-vqSb>fn;95?WJue_F@wC|u5QXFkNu;u|34=1kk@--^# zrT_hZGb-!Iu3Rebr21#srCga)J7|^c% z(OoGXd;T9>o9niPhX=ew1}Ib&52t-EE5q+AT`-qvnVm_YLmVaYOXqgDR-3!`fvLx`X6M!CNZE zVlSC@inBNy7Vna7uiJMZ?_W0V8s?BUx6CFLG06K=6t}3yX-`D)?#PP;*|DK90ph-xw`B}c!QfLi9&iMWQ!`#HWjBJ&Te_WVaqDK< z;|ay^(79!CKu$1 z*L<<`3VhzT#uQ$PGSmOs@Q^VO|BvtFm|%38$cd9=czg#QRcL$M=zl2Hv{4 z`QM&`x7d45Uo!74g?pH>c&p1e6pKOLn(ChUl)QWD5~61z@6zRrCwD^LJG?dY)FJPU z_I=IxM{Fj#(fud56ZOk%i1bHdzaV%w2oAq{E+p2Ehe{#;3EH(&U|53 zeLORcYx;DOr%jN{heH-6?ZJNr={uumum?vM-S;2{cIxVQH=CEXGh^=j|BV#9m-+5B zAzxzWxpNS)c&i80@U4Wr=l|5}A@TMwmdUqT`^392~$9pSU zM=(x)MZ0Qc<9~30*EQ1i_x~5XJK`G4ro8Xqt{?-p?SJrjTN~Z;Zred!9WMP2?(*4l zE65ELyyXqF^vJyPzx8us@&2+{XTBBWEwxq5*%b0_bK}W0g}lFB5NWI3>4oSOvRW;L zyc2hnuCa%_!)$|6Io>vdC;5>A+7F|_AO~Aak_R@|wk5#}UR~k_{b-zegH|WcPwWlS z&{79)Usl@V{S>Vu5GTKp@89kU=o3N4J(0&V-1yzw)ZQqohr<+UIXCR&Ma}URZy!uP z{_&dbc@u`ItYd#)tNfqiEnFyg%W*zrA@j~bsyMKCKN;~E41m1*jDEI|c>AvZsGtpb zuVILuR&nt{N(DSOT)3VNg1`N&S_^q^+3-vF2;}`V_EP-^w;0eH%pOG%PK7S$Y@qUQbF^Q93=+gq;PmDzH;pv5k!@uwcqEiS9h-3S(~O?J9Gy)B ze%ibDC`{w?Zj066^oX!U+}1BP%woNZyErM>RjsKKOaHgGF4j|5hv#Mf>A=JP&Hs2a z98LTj&i`H%JxJ+@br!h?UCPno$Lc{+^A6a@8kXt5YI-4T1bfgcW8s)V*n{>@jYB<~v`od(eQB*%8LGwAX{qqjmJ*-cQgt@ijklI9_4%K9w&RTvxpgrX?_^$ai7Lo@o46#aG31@~)SV+2^453Wyeq%f3$d2tDoQ}$3UbKJ z#1iuMTNXOL3-VsUyMo(TF%~o$eaU1yfz3Na%|2YwhzB&Gan+KQ^?m<%;_DyuEr>y#9Jk5;WcN-+bf^# zpjERM!h1d_m*qw}cr2jZYzKMQx1UqyfxP>|8#inR@bi`%#Pd&;WAkpVFK+u~!UGi0 zxOt)GjpOau-CM@&;Le6~wAa1wqjiYm_0^f0yp}{|RTQtmE99ZBl=3Z@E$MR(PWAK<3Q|B6+ZQUsb#3HU@cz zip)+>@@6;g3}J!1&un~{!v=W^6^5O2g1oQ2&Gtv&=0sTi(L7gcI~j0WltuzS#J zu}o2^)wI`x7|=SNc+*-XJ(P25C+%v&?z z-cl^y3o8wp#UXD&XZ9Kr@3wE-t=B=`vmu^2K}lZ7^QHY|m-h~y$BMMaTN|yT z11CS?^MeXsQn*03SJCB&{{`>R*Qp=Yf4_svd*{nC+q0Kn(S7%pF)gR64xPOlgiGKK z5?q{kQ}9-0*|&nsyL@SxAQtbMftp(Y@^=0BVU;1|efGRbsV3yTbag0?VY(N>b89q& z5pGT}OMm|@3VHur{?R`Sz97BlIlG-M7d-zzDcI}Y0c@@&#Bt(SGyFIa8s`)s!x687 z9dFNm-+2WM@&;%f>u~bhUVG~Bf~QU~x?D$HbvugK>X|H?xqjg-t$*(lcZi7}A7qD0=d~MVepEseC zlmCsLH;^oM|K>P|e>f4r@X;Nw?;q*^_LdlRb!fahVLp!b`-keM9^Bks4S zgIYJ<{SI(IN*IWo5dPW>Ov6vuGHApAaVfv8e#O|AO!mnqjY_@TKmv_(4jWn2?1~*9 z`shx2uLu`ZP3LkQ=r{MRXlD1VIcYC9O*lOv?^f3Gt8Jxu0mZM!)8u7dWCZ<$N&o7Ivd_)lP|IIHZu}fyajS1UIjqjPXzjUNxUDV zI11W8-fOw5nfCd4A!{#5J70bVUyxoJ;}r>co7gx`b`Ca!$O$I?2sj||DSNd=rC@W7 zmKISs+Q|+0(YV~*ryo5s!;Uu-J=Q}6w8uLFt-}Z>zdq)BRP_Ps=pxA3Rnt-Vw=g3Nn5r%oJ;cUZf{ zi*(5Q#mgyo0C{VA)v0|NZ^BX5Gx(E;~3=4aNvXGvCqw*;B`jt zo#Qbe$Nhoa2{!B%p_FQ2c*q-Wa2$=BXRFMyCK;P|L2KKuCSBU&ErQl@3MW7F27wG6 zZ7y)Mxg+yb3_kCXKA&d3d(j}MW8dd=)_eE^(v=s6rd4n0pZ8Vj>ZolGj^{o%*S-BH zcx!$-@RZDZ-SPcmSiIerNjDWk-nAE=y(aN)-m+i82lB2GJ#ye#m=`ip6|YkUA8&c7 zzv^8L+)6Lg0}|Jv5d?+<@aV$EZ)Ak{+;(A?@wpft|#riEy%El3MVa2 zW?R-c#&{vqANEB3zLpN8>}KL#LEg&M=S{ZuHG}jOQVss+V!+DByK_zoV0Uj#wi$Da zx7iy4!xYb2FuaB-rF)}fD+U+BjOJDx{e;1)MS#hOrj-iO?}7Mu#) z4u&En2HM#1*WQH28#24I+v$J)7q6zSjw_7^^-GQgB{%(<3;yv965qG2KeM*-{Ea(aFIX0?fZelBl@en@p3>e5 z(i^QK7bm|*Pgitb(<1_#!gl7;v-mwogeA-~>-H}2-0p2dPbC#A$kp#fji+tse+7Aj zx;kdQ);%A)GMdTs_Ygrm>k7Ynx%j-p8yVv+-Q5Yw)K5L= zH^JxKwW?IT-?EDCc}tw5t`637g=M!g=XeKG@HP;-y_(Fsb^N+47Vn#y(Kg>8@2<7M zzev1YG**f1hrBCeq|R7C-k*f-&fNTz4)pfzHGKnlYbClWXihW(9&TBoN#9t&tJpZb z`vx}G6#Kr}cy}JK7>x_Ox)G`3!;T*Y<5AJKX^;0Fw2m)0`Mu{8>hx+N;rYk# zdDq1=tbTrfC#V|V+Pdo`{(wZ#Pp&z*mHv5CT}Qsy;;cVkZwaE{4LTOKka-^+-z|g1 z`^)aNdK_>-Vzx<+(1pCKp6=1nhrC_8sy!PaZ*|3P|7Tt4K=tc#Z2}ySF1OnryEE1d z7-a?OD}!PILw(MH1ONE`U!9Pao8cxNz=+0q^*m6l=f~##@Lkq>?|Zbzy9TY}E>3>> z-9JAcSOhDi=zc)@ol0FDvu@GM zdt>IF-U_7Ptyl7-m&`lb&Q2PO_oB$zX9|$_lzQe6CGY8S>Bjg?UdVaNuVtShZ=Pqw zd^yNFP+9&8`$#k3{C!%OCj@@IhvXjgJZ;e`tRBQG(=xUct{@*- zbzjzmm)Pf))|zkOC068eXLa`?FNFK_5|xGK8DPgwX|-ATVZ`l8pHu6C7I5BC^(nF& zK0(U;q~L5Xc2Ch1QA{cqN_QzLWNPkSbb-7*2j1?))|y*SNrD z=X05Z5Al0YZU95ZtB43-&@J$`=`$5Q=*Bm-9u;G{ACTg&ex<68mNm@bzE|f4r0o>E z%~dqkl6mtNyjg+8dyCZB3tEtO-ca{4Ey&xLhRN?eBM3{gRPDw5kULship+6eBR7!RghL|o;+L8}$2**Yw;4a{J2LNQ#+MYacsm$%X}dt)iRX<9NxVN>B?L@E-WP>} zN2^wOAt9T(JXbBx05#rMD%BwGB)gnx(RnQ(HzKz^O)mzNv=(U;{^M&b7OOtC9Atub zZ_&8GGF2JHe|$mu&Z&lDF@Chi+XStn5huSD3zU@CsuRIz^)A6rH}QFA>fDr>2YKs< z=PfXz=Ibr*Siu}^Gg_bz&bRp@e^P>-Gbe{`vy`Q-_qdMTfU=p^y1{lv;O@s0iNEv zI3Yvf`6YbbN{@t1QWr*m?{cRGo7C|SCn7jstn1uD(_u3mo<|>Yicq#eC|>!*{Wh{&t?faVgI)KJHtKeS7QK zIvwG8uW7G)yP|bG#>ww^M5?gHLT)f(ArPKjg3o)&qWaVmO}l_ehT00g>-fCuG`2ck zi!!16?rmR8T^%{f*Ng?>+1vlk|NpOtdn*3-VGoL-=t1i|PK1+tP{eH}b*vt=;oX7n zaiC29gI$~9YS@E%)Rjb^!WCrug%7Vgws|70GR+l}X&E3t;97+*od1_vJeI8FXaRc) z!aB~m!*7r*TB=)d3;UA!L+4p#lrcR24~+{eKi{lz7CZhppTgz_8azR21g+y3PJXgR zDV&r2M4)02p64=#--E9AY`lI*ZU@kx_7Cb4Z^G>5e+3+hkn{cVQuFVBr`NxTMp9SD zd#=Yye^!vu6uhmKKJbuvFR6T?ip6_$b+mOJswIe`m7j!-Xhi-B!9-|y&%uxX6KLX0F=DrFSv6L zmv{Wx-P<W1M&{(T$9!YdF!2a>mI(~iEK?mPM!kI%bon`Z5WlTl#OxHer1o40@F#jH!xJRlN{t6aGDHS>LJ-oLqBeQZ-` zkGD5k$1F~MS(1mghv{*HC0>lj1m5BEzRY=|R$ zttZsgv1gOY$v=;`L{jix1K$B8^RD4AQNrTQzVMOZEaYwF{zIL#_huU;9rO(H4nCxP z3;E@VyylXgS74t3G&JN>x=D+Zz*RraGPQt@^<_JWuzMSGa&s8`qk9X+T{xU0!vl=a zxNjB@33>OhdB?dv+}fNmFY(v8f{gDJ?Io7uQe}NMc>oWrpxxBJ7PMunCaP}4DdO8!`KbE zVT8?Sk%Eh03lJ>7S;{XN1HP{r-TWvKyQi?%bTEj7@qjTjZs|pR`G#EV`1N~(bJjej zy&lAb*5QDY9}A)G)#rmmV4xvuEh@#PkB4TowaU<^DiVCmt-ENR-h?|K5gg^~d8Izm z|NKvF9Sf`R6ucc|%h!-EvF44$ot@_T|>{{E%r}A zr*?D8c_4dwtPa11yxm6Kg*zedSEUP<&hoVY?{ZP2fT9?1>*%vyT}JE`WXG^gSc5MQ zK+w2~i#ZaXUSRXSk-O}E77aci-HO&xg_9p+&YG1>@ch4ICN`EZ4t(Ch-r&TSjszeV zW3_Ep1O5}F1dI1em{_;d{|a&qb#?FtTz_`w?A#90E(+du-y3zwyvu`gHL-Xv^cq_) z0eQdpxu%80Tj2eU?%=g6Hx-WFhab;~lf zeKFv@^%fVVe|(KaEAr^=XRbWp9U8aSLCN8F6E<%HBaaF58rtjLDrg=0IQh*SHHhS2 z$_<+D1nZ?Nz~}AB<(%30atAo(w65#xcYNNPmQ*qx_xeQlyqEA&S4UQek#O3duea=^ z;B8wk{P*R=7c0Fruy_wnZA>+Qyq_>vTc|_cZep7129S4g=od2+Hcv!*B&}@_^1j*q z!g4v}ec0pP-V59F%L*6r0=TEN#7u9W!0G2q3gnwYSEeBSb7UBy|` z^*rD?8Yg)CzVPA(Y~BWDU$!oPh z`$C@o^N!mwVfCOy-f&$LIRER9**Yr29wc@xcDEtC#A*jtIyHGx#YOA(#Lg?!^rWT_{sF(m-N?zwv+2X z%P;=hYFTMH9C&5xe}B6+`VR7d+pYdp_YZ^d2mK#b((sBMN7r%3n=iL9{3UjZ#yZ>` z)~wnZH+PARWTE11D`mBp!aKrp87mU+U-;lr7sy+|cC>Sj_h(lSbO7?+n$;vVu-Kl+ z?p?X!$cbnmQ>bL719?00tyb!kA%P|whr&sB_y+0sRtqQoam(CGH`x~)7Xl9CI2N`O zOf~;_f>iI(!JjR3_=uegxem1aHa75|(elE9z$9~JE-iH4;cn5p{HqRwUXA@PcX6X% zVlg#Qr=LjJF+6XY>);$Xp)&t?OC&QD?_FP+A}G8c631DPcz+lezJ3z&R$tv|sX52{ z%EA??kazTf<9AAr+7k)R5n>M_qQOM(V5c4A?f)_tdr67}Sk-G3RV9N#$chWCIf2Nx zw~}=16eW)dfnajn*V|>!>ZFk4g^0D6vb*T7dqna@J+phX1P6M4c zVdL{fr#A-xj!xl(omd*a-qKE3>biND@p-q=RtKAtVH989eD`Le;%$AyY8!=jf_eor z67Qha>VV6Tclo0B&N<%q#QMrRA@2Z(or2b%?1^bR;vYSXi3X`3Y_x(QZ~3HHr|`uj z5W#a$pJ`z*2s`yz>yRHZ*BcU;2+N~F;21e>=v_SaggA2iy@k6RpVJ}ltK>TFqU6VZ zzNA2xTM#tYMLug+Md$t2@#DFa;=@2S(=u))8~WE<7ALkf@~Casp^FXi{~!tWINIvy zG>$w~d}8kR|B)Cf-d5qk^Yj1Q+1p-=I3^_C(-*Xq>mcv+hw+wkXKy}ko*GNx*&DFq zj|>WQAU=s9q(6f5ztUyHsEd%d`u$EtH3<^X`m$}4t~DO$dzA>cl_Kw@nHQhDzb;$| z0CL=}pjYj#|G2&NZI$k#C;jx-y=Nr<)bSN1zcsFb_x8ZU3CGl34|-J4dHTz9;7f{nVz?*)-cFNHHOK7IH)9*ZonT6Jo_pvQQ2|A_4S%ut#hCW@swlH1@%m)66W4&pq&hiR5K5g`IyZtNr z>p?x_I?(cab$X{(t}zaXy@-6`V~XB`bf$E|F75IG;VV;*_IIP7AT9N%xIdNa%kVqM z30vCgNHW={@hN!z63aowdoQ2+B?@n~#bVq@yo1#2dmAC|;Z}n^YLGX_+4C!eAaC~< zT7pVDiqZ_U-x0XLLMAoAh19X!kN;G_fSTpWeW^?u=+LZ{P0 zAdDP0X4>>ht`<4o;6^BK86Do=Q6X=e;KJ(zBNPhd{dUwRP-1=sQT`MLPu!g}r2W-eOZbXsTmmW?9_c^YgsfsCe5K zsq;{H7e1-rK;pexw$_vl4oL0JzBcNR_buHpB`6q5^2;;ya`Hr7Y4AFTj?I#&q)Exq6ja{@Rp3w01mcj$-U9G(g&l_Vz zV;%0Edo=#sy=A51y*q;GCxv%!^%-^~-si>Jjc?BD zk8n4l&i`S@BflTNJIwI&KPH^EIu!M?RxG>v-~9i-HNyXo{ylL1=cDRD`_{f%OzA=I z+BOIx^`Q6boSfO<4syaX%31~Xpt0O5+{y4B99ChX_QXX$8p5H<8Qt@`fDzB&T4!+KhL*m_3e28fo75W>u z)#2mETmLv9O|KApcJ(X$@jgecBMl|LnW8<%(^d%r_hXv{XT8vQvv8cw`E|k_cy2ry zZ&iZMyS>tEtN*KUhTlO3KBKLUXYIx7)FS6^Z}Cv^c4_@#OW`ejy^kM>H!sJo*0m;aQ7+v{$IgKB~d@fyMu4%K&Kjfdy7QJy`nTc zSR7uJp!N-U;3)uCT`Y5ifFwE2l*P6>lM}gno0}gA+&n>lymQEPY(>e>XIIIBCx>t# zSu*bM#6EQ1{jauKrUbf!?6#$Z+FLa2AoH`lk1d^Kc;1+swAGQ8qVo35wfXMNO~uxKs_Shle93Je7Z?$~=37NN+?88U)8A8B{92c4MLn)I5nRm(?5-I2- z{qbHwuH!sPe&zSXcsU>7Ky6|wSBV2UZ-tBB&DxId1+OHx*gjp4&U@;6(~0QA+Zg`* z|IlyR>iF`bZK&bcJZ~;4-cG)c{yuvvS#^{biMQv_tTF-eUY#rKGI#c-&z{lD1$hrP z=zKe=??5DqKkE^I@Bf?L`TTes`WH| zo#ePnQmxiHT*$nu&#b$gH%5QFZ;|VGfRdkEfz!FS0)n6`y=mDmOLX2uyO#BSk$d59 zn8mIf%B10NqA(@z`h)k3KmVuGSjU>R&r;#*E&eTm zmLq@7LZlv4kw0d*U$;nqw4u0L3HG3gsEiA;a0j{kUg(O(C$_{Nzk>VK!wBH8#kFsN zOUH@beAzya4M;#)VvTmf5_mv5vulUPKi&v^!XhA5<*g71C&%f^Fxi&9N4_K{dx+bF zuaG1D@BBxj{oitoT*q0I{913V3v<0C2(D?Ht%$jR-h<9&M-ONwoB%%N2a@+2)u7&k z#LVnlWT3r|@pq7-`)R9V%~t;l^RL*66r|$q@$F~=h4+C>>;fd-6CN`Ik&ySgYB!tZ zkoTU>jwF4^`(FHA$N!WT3NPfRKi)>1@<}lt$9R(=H;*lO$ZY&D~Z?;yZD+Sx8MmN zXzb30OnLYW5{K~)3kwp+(~9#AunPkDCYcJiZaX8+t;+k(p3Ph$46c#m9-sLVRFsL_ zgM`B++1Ku+zaFGWt^_QslhEQ1SD8$C8bZ)BmQ^% z>q>p&D}yA)fBrvg6>W8JN=qv~`11tm0xI6VGjh);yqTZPN+9vhvP<-M4|(srCfhg1 z`-tnS3kr~T^v62kq@6ZI=Fe-&??T=$u6j1qK;94A*uuV;kwA#__klO-fRLnVfX>bB7wF#w(uOXar!eLiBj?Qscw#;@D7oA zvCIFiqvUTH-_l-7{ zhDlQr;Fn5r2+#@w+hsV2F-ge0H)k*0a+gc^Z=B;pVxrk8WZoI8O?NKZN`JgJlIuuE z$*;`vj(FfsL9oF;C&{b?op){5%|#_*CxHL$9Tr~aXt;Y@#7%t3Gsy6~G37MYF_SO* z=k2YLB2>J+6DoBnyuYcR7f0gVbX&zy5%M+*N_jEIdozbByEx>%B>rLD>aRA$eew5> zw?f{bLl?~@;O(t#j($A9OyJ9j-B%0Yii5xycKo$47cy7is^-_pCj2+ErOWb*g>r-e50my#|Ikge;)?)o`&1Fmix+?0E=}&{eH%)1wd&?3lE5Fv`X5@HZ0fEgQOzDreJh={Ul>9`PJ&nBs1c4@#OUs%|=)9-W ztHTH3*_(X$c>a(&diPdfkqPMeWXM&AB)_(*)PW<2e|9ASL-#@_lUy`Z^ z1qs%4QhJb>p_Cj_54zRWz_}a_NKE*;E_v94LT#!Y9>X3qu2vXJs<9zn>)X84DxU!A zIMT1;;0{txb^nTJ8xokjAz>xdf(KU*xR$=>MLrP{)J~SOz9$TF$#GV%f9 z1V$KtKyrITTO9?tr1+*|^9Q67RJ@P8x6h{V#+gpaAn`V+oKe^ec^5`E*)D~=W$O&z zq9^8?)@0tF`_x!NM zX@|M*2!nERT>Gh)2Ri=o#wmH5yOM-S`s2++u0s|jzhim(Tzdy_KtVnCl6*HhZ?o|O zMS74oX339={0Q{(e+-`#_sOFF3kDiN`7@KQ!aa! z3j$Ah?$~Wl(0RXz*S#&~?GGeQ{Rp?$M(^JF?v73q`W6g7Ak}!#R!4$r;;;<-f)w1G zh*R+nIQpEA!ka%oQVNOpi>hwV7|1(@>!ZUm$Xl7CL0B2`KH;A0cj@IW;v2cm1FwS! z0RJqiWrHzwXUOuA>$uzaJZC(^N5nz-N_8qwFJe-rCLlL#BTIKs4@@L9QSA%ZV`WZ*QAO z7-akd(lOfV@K^X9?0R{=dy7%=_P4(2LE-&5(s2nAZ^aGOE(MTxTDx68HE+dCW8T>Q zT||kiT3n-$ce?i=HU#p1UE5Nax19v4l^=?PUkC!e;*VWpCXw&nwoCSSswfKsA99@2 z5eea;$3OiD$rmpV~&qKSI7F6VErV#{1A;5Bf%~ zqY@>*^vA~^S(@TNZ`kAS#P8@mNaKYRQC8C*{P6YpjBl+)Js`ytdu^%r{L1*3*en|B zD06orpCCz7@eb{Yyhpjjeit87K;mtD(Yc`z^45|5{%nqS^sJg@(A*9(Vv5ta!IpSO zU)|$#7Xf&Nb+es^yw|rs}c0kOo@zqD(Ez{R6i%yJ}=xn47p)XLBm1{vfy8;1=o zq5pV-^x0<5!du?-$NMU|j;AR3Iaa^b_Y;6mkYc1O2EU;5-cj|XLA5>*1aWE?{Nh0W z1!-7qpr~J2IKy9JF?VUJLw)d)=S{&5R%}#ddVgZllBQ%}1_76eYhQr@ez^4mcoXChX4k z8J#zQ$tk;?#TPU-h#N7jLw`V8?yBia){XBNp7)7l+UgL+m-zIz^^muy`E>Fn5|i@rUTId*_nt zC`8FG@s$YMWHIF3SeXhi)pKI=L;=&oLxwE&x7{A=NkoOj`9pQyDHpD~2 zk2Z|KmlMVP{_GPJ+f}9))#df;g#X5gpONk6 zx{e%weDANO`@iUq_eOFZ$58T9eQ~blFbM~qt9GRGkD&9`aAslJ+7<-fuE@OTJ4M6c z1Q$_sJ)a}v^X8_l4w;K01MF~f^56Xbcgm*UKfw8a8C4HDh4Gi7^dQ$*9yO#Mv^lQ& z#OT^0{ej;fo26h6Y93?VyaM*1FPHr{yGQLNvJMzronnRW{|{|`_d#}?XrRY3bIFqg zY%fdP%ILv^+Ks_XlPi&X%1gO(u@CHp|HgS9T7SLZB657+msyM4Nc!tR1LQiMqvXe& zni*$1h66tF{&rX{9(^=0T5md}&PDkH-A@YTtm5eRATe)dYP$F%7{3R7qOA^2~Y)5k(cfya7XT^X~HEu;IbL2-SQiG{*P7~X)`nz{u|fmSMVt@ z6q)z!pEup|@bt%mCJ2c3W5tUCA)t!qw|hAagM!8cGBVPEfaDbrYQNvXfRKmKPm{iyKgUV#Gvy| z?W^IxCwv5a8tVy>j7R5P25)b< zUEH*4Hy#-B&fKysL*`xKeZ)Kr2!r+HxP=M|m1f(Kc{?j*I&vJOzwUjPT*qFN{1jrc z@(vSm;Nznh0j6K*1JYpy)4i2y{-9h}Q(-#+{qYv#0*jgfcW;J&yk+4KZFT5(_b810 z`Tn0Q74NY17*k63ZW}ROj>H>N8AS4eyjgmVKcC}mvBxXN81haW_x!@gZ%5pG1|KUp zL;#5eTW9w`-s|_Z)Gl--0a8Q%m-^Ho;I(qo)P^s}x3@k$sA8?%APf$Y<8Ztc^7{Yy zRyXgF^=?y#>5n(14lb1Z0>Akd9%sgZ0`mhFQ9sdnXOek~R!y|qd)1@f-V*pM^f+bf zJBB}dQyrqM4q)eT(ID}^`5$eDql>=}=YM6Y9uz$-dzI3IL>4fuM(RQO8PbG}aQ??F z`J}NJ_Mr7uD{ldB`2N4!!^~;d?1}dXnGI(@5x`XFTR{^z|Ch;~#-Bez0vXOvdHe6+ z!Tkld#NG=cUosVDj}p(t34o|;(--V)Oj=Pd@ zV9FcUAEJ%EgN*Y}@c425IA{v3dYoKO!~Eaz(S`ZTQO4gv(pX2jX=vxV==u47ITde0 zz4rixx9sBfl}Nnr<6@i+K;CzDd?=sey)D}5wlL(KAnjllE@ z{qep;u7ejPKYjt`({FbR0{az&yA>+vyfwCZW?eT81i?#=Uc1eTev3Uqe!ut@>@>sk z-aum=c#nIQ9~0&ukXEAN9Th**M&Zpja#0hB_oEu79np~Y4~*WrC6G7U?9aYlxPx4G zdf7AkP4>j@vgXedKL~(yB~tk;1U3@cgXwH z%F1b;o9O5Nn6R;1%5lFLo;R&^+$*b@aR2iIX+V$JA-B(Ul5%uaq6Jh0$Deev2qzP;T6z>7m(!hhpzl2_&&-G|IuyEm5U?K%46 z-A=AU6D2?QDT(fls)7I`tVtXfMd!^~`6gm#d?2{59cb-tRENqN)A8X+g75zY&)&YG zv5q2%<(mJ!|Bo)ld(cgW}&4yXSfk?zN)Z70=xmq#hKrc~NDqR+0YU8`@VE z!5%aydowo@4oDl{>RhW5hu{BuX~a5r4>ICQ)$Kf)aiY_*o>dD^kifGK1ji+M!N4s( z;SuLCLKqrOkSr`ee>uRz_&Z2*+UmID-Rvb%I)8~( zqv9P`aQ|c2uvY0rGw-y>^)d^*mp2UZX1*P9Hs8#iXr-1^WHLek zOPb5iG(q0HpLAZlKSl!Q7oK0~u`C$eIxzY~^dCQX{`CVqHIWqoCFD5s(-uwce8{|S z2xJXc0Q%!SO|BykCBH@Ciq1?o;4St^q1`=u(Ru5daGUKiIs&dN+P0}l5q&_)lgWN9 zOE|>vyoaP|tE1fAd*N98Jnt1$yw9ArkEigiQcGTo#9QI8+Pe|RyP>>%}TEsoG+{I|Da3}~$5>ct72KMzQ&Qt>{${qrdb?|1F?T1dQ;J-@$V zg9Fm?7xqe$kazuk?^BMD_pgqj@}drVqMQat>i7o&nCW+FoQ1rtR$m@84}mX8J8-<9 zd}T1$E`9Ex7 zRhtN&1g5{(2tG2#g90f*=b8-U+gp{2ZqI*Y2!niboG>YPV$nh5z4``WJmDCT{^tL3 zavcCAKmMfbn%)i^c-B~5d|@j(Z|13TF_y>>U@sw)ar6`o-Fxe)tp4gThUbl;wGQ1@ zOTPc+|NrGl^Z)Q)2j~CQR6QtpP#s5^|4jJPZpfP;mKA^Ol^wA>BtdPomH>hY<0^`f_XWw~Cw*bvopoLaxIBCBGSi zQ~0)C0f5_fgWt>>owr77)ShjNLO|mK(FkK2c90u(*jMg&*w661e{QF(4rW2Cdp!a3 zyjN23J{vB7hr*k6*(3`R?^HFuM<#Rg|A&(@;*hu5YmvT39}#uJ_Q(!D9V#bP0#eofNj{&X64kh998 zMy^8)&l~fb#yZklqO||a|C&_1ldPk}DZB;iYnhRF52{z5-UoRfxm9~F`mK1$ct)j+Pp1SP*Hd1Yo} z2|@5;LTPZ&1)aB&h8&o24+Ycio`)wi(H~BXz3<-Xk;BaJ-TU1g+Ugj4blv+7{5bJ{ zzyJR~oXP(;|1miK>rnNe^qw*WN)IyV+RTI0gO=U>EaSSSNZ&+NIZ_n%pbNL<1bAQ% znmWrh8Bk+K6yY5tfEWUJVD@DD3+Zv%x>lVBVAaC`%PF*u_{y%bI=c2JvJ7NZh^!>X@1mLxSyJ8UXK5XtyJO+8c7_d2M zlZyvcS9Eu6`^OGa(rQnmN4PK`lH(#4Yh83~L*{Kd>XM~%hW>ajBG+MrlHVPk+`(f3 z0^s-Yo#QJb(0TjxslBg1WCV<_4Sk6$M!&>jQWiV$CB!oPB^L9LwmMp#-mY={^9Jd) zRJ_xU7-mp-w?+?hBJmbC4I9jbygxTfC(ZHp>uf#w8uBh!7vb)ZYe#(hWyUh$A_3HN zURCXfymMs@lu97)wwqCnmIORdaXpp$d<40BuLA6)wUGA;a$G}X5uW!xGViGbqxxm> z^v7G1T*oJr`~-xSA5}8Kfz+v~(t%^>yf2uD*xU);4;noM&FX{Ee;{ob*zhc82@Asy zNGw^j)v;*uKH+Eh{LfposCcIuMa;jPXzt;}gZyP2NW6nH_mnn5-ZHIU7cPXn&m6tD zwifdKq59NkLy{da65|r9evJTNzzyQ{sJ7@jwVWq_tSMANF4UCo@od%K2;cZyKPO-lFPwdxc* z67Nl|s;AyU-WQV^GUj+IpU;^&3wh_Sa2nbiYDaXxRiGzSP5{YlxRgoA8~1k6M_I_b znMul6>I5DLxbNf6>_hI}hllN(7sK0Ig5)?u<@Pn;ANLDl`pk9uvgwbvAGwZjl>8d* zvHQNT!GZgFCZ7}i(0P}BewcP^SpYbH3Zz7fqi;^iKG$6}(b~`On-d2b>qt0RzUpwq zfAjzU<{1Bf{O^MEzdltD%4wY(rSzZ~p7rq79|q&)=!4;ce|2*7bKT>4;GhTmv-&Ki zp18V5pYId?jS%cXOret<<#7I2>0=vw?O;a)X}gw(CKG_hf&)A8um|~wcZh9CCV}GY z#+iG=LEzx>l{b0~k$aF|P;_HMs4zH0j${6q;H+~J`4U?g(j4&o7#;Q?avixS`KhI- z^<)iIG1h1$XmpC%BR!Mj(BeJS^h{O z0i^ETZIu9d3x4?(`RFVOWC?BmaDVfaSw2G>^idc>doP}*Li z$A!*~4Tl+?_jOm=>d@=me~u|@eg~;X#XHOYO$vqgclnq6NW8s!ig}pf4l)1}HaW-J z`u?o-amf2EUSNTBtR3;xIqQhKX9%EahuQOd$h-aY^UcypBycOPva|mheDm>$5dRN0 zWZs40>sg;e-jq1eAhs9j4#>PsD{drJ9j8Cu1>`!6QS$4%{c~pR9sy7_T-iHz6`l9> z-dg(wE{DP3r?2`?8fsB_V|3SR*A9d-Ja3FBjdeWQk|6Qt{C^!4?@V2nGz#xp;e0+M z-a&hIsLDd#nGe37m01BQL?-^f2=Y8Ya@0hGuFK{VkonFce`sO6;+akji+8BnP|HEF;R>zjWbz8=g z=DW8p74Hmwg+L1Lp(Dq5k$BgVJk}XO-fuU`GR>X6J#i@eun_VN3BO}q*J4L3TNrzD zAe;ccD%cdXLEcqzD}oB+NkHcE?nMb(;Oi}Xx2}@8hRj>gbI16*7-4XW9G6^q#3H%? znfD%R(9x1af4p(zI(DJtXWWz@lIbG=hG$sV{m!BDZq0mqFXO&5xLLirLb)82;=na2suP5Q>}M*=PUv{y)m*l&=2@=YM0W9+cN`(3sML_HnFTh}45F_9P03 z!2zkmnt44A_Mo?q-Sijxz(?$Ad5_+>V?*3y+E?0BLjau9*jI0);Q2q>3iC&qB(TRl z)JDWA82CPnyqj?Wxu=A6AGmOPfe1K6j(fbNqWi2r@-s+Fhxt~O2-4p(NR&FHQSuwv zP;jgAJr4XHd)g=7jNXHuetNNHQDPAA*U+#^El0lxnN{UkRKmgdJILZQwAIm7t24?M zIe&s=M8*4Ra#IO~H-{4U0wmtfdA{D-koT#xmCbX!JA1uea6{e|Q4Thr6>W)OD|$k$ z;4OAss6YWLyu@CYVH@wiNCE*T#`5sX;qU)*cw;X4AoDI(GxV*;iGWgaT!=g80xvsc z-dk15c5LLMKi-r&HlgGmSea zhg{q)_mM{g>?OyomwS6IeLFJm9dcn_%-rp*I-`@JK|;CN6TYU37|sz$F22{H_x?N>A_SI zs2eptV5l4nItt@t)c(=Ee;MuMo#qq)o#eQN9~NaiR>-`au|fUUIO&h~PjVd&DEURp z8!}tm!~yYwCnc)2=)A`oCl4Bs@Ze}2-b5m!0sZ#Y!e`|LZw@j1fP@jHu?}s^!c=z= z0QcSoRJvh&;lpeG;Vbx-!9%QrII4EFMk$zO` z+I&9PgC1=5_11?2(g5yv{}E$rV(jZnp+|ZN@I=J?aWRipsc0G~5ag&wT3B|t1mssDkcIx{y=j-%Hc-_Wpw%v>a*D14mZd1Gj- zW7gxu{>%CE^Z!OF-i3~<-6*_EZJHM$@jkxq@blY{_weFaeJJ` z-U?VC^IoyiALpz@f4nJmEJw-D*>k;cuM7^{^N`#sJ%rx9e^^Ni)U~^Tii&%yF0iBX z{u%T%t6gG%;du`Q(pCqzw(f}HnR(tORJ;qci}NVFZT&BaBk|6Y9(&gbd0RdhQ5S%` z+4(=8(}cWB6R-c+I=hQlU9P$P0Q~*`4t9-;&mr$!i8j)$StM{y#bN&_TQDfNVw(_X zip;zF*M(=w>LP#RF3Gx|Szw9GTVHprpQa-H@ut+FgOZ=5-H_~hcN{ny)x@GRh|W7P zXp7rE$opHtPzQT?9s2z5!MZj#*_ZL>|E)CEA;-Q%>d)gX8>o0+o4T}+!uw&-elaB8 z0zR8gPeI-eyGkqOcsuk}epQ0JNAFK2f8A+AY^!doX?{!q7U*Y_3PSt}-@1%!QdXV9FB{`%Xbo|mH$F`M4`oq1&>^!gsjh#NxVgP%PYa+Ov z8@rQu_Ov&@$UXQ4se3{E%CHA@$o1*2DkOo#w%Uqg9KqnQ9{2X4e_Ub};|p3ELPUTs zIj%b2{^_TG%>VBjOJ@f6(_ar-My_K7B|jz4gC<@5IB<(XDr;&>8s>dq*(CdCeaBe{PLkat;9CU0~e33LVQ-W{GA4D=>ySUvlYdB5;JQe5gO0(8i6rlr5PVs9h!UTJpz zL4zIr@$M$qp@x#*w>P)V%*Jp4E56n2`i>YSf~bK0p9!o0*b=A#d)VvJG9iBv81%t45$87~Bq*lw17~nfKPB@#hjA z@aZjbT=UgKPf7QXd2hNTLn@&|-e%-Fj8O9HJpjJ9>j(m=-!d2dC((HaUa_C??ezue z!x}r;1JECDx&B^VchLVW!_WU^92zv$!6TW__PKkW_hu^IH$FSvqwqdcyJra!@6F8b zBrGBC0k-C)b7yabUv~1$9Zn3q->RhBYelq;U3PqFKLK#PQmj4$d2@`)Hzr>p0grJ1 zJzo2R!OAV&%ftS0o?ky3BEH;Q1Za}uE(&tS)v(bI?Pb=`}RP(tcKdalcil;D8WC_l276ZW9TKHk}Zum>Hl z#~euBy^Y9!uJQNwAOfhLxzqN1$vAQR>>d9fH%Va7wRv^iGd!5)yk~?HMZUy(TB<*F z$`=8j$#JncAJ)})AorlPi#O?L$I)L8awpfZ5+%P7jpAXC7#w(T6dzZjfIc9J99%!q zujU2fBiFG07_CR`K|SRyA!l@VGyD!RzM8f=t`Ao`c>j6D&JHTxcTYLFP@37k$I;d6pAQ6MSr|Mkn1>)lAj>k z5rTgkd_mgAG5bgI=)4E)^g2aWcmW5dk6|WJG|c~*`&-2;ofw`srhvveuue_n*IRC< z;(ce6vjK&7f_v#QB;Ev0o)k~WJ4$o2Hy7l+cf04*F39_uj`RBN+U>-gkLTOBpC`lowuqvBn@VDtrrH|FK3rAWMkqw-TuL*8sgU0>&TAD=yKt_^vw zE$DIjT)2Zc^T9EoJRiQj<%8@_7C0cenmjg|xK08`MUBlo1A{^KnX`^qw715azozcV^+8IAaBc5>+`L`JBdHPIUL_{3x0dsQ8sP?|vsLFbH48yU-vGxd*vC8^G0< ziGWaY9A{PYV%2}#Vz<4M^R)gf{q-OxavfGE`NdmHv0akD0ZTc{MhOe_9<)?p#gD-A zhk!u*YTZ@b=(pH03FakjKV2Dr2f2l|IyP8Z-}m_Q3({RwyosK#{(jzaMxtL8i8oVT z=7!6VcT#coI(EqWq}P|ORLJ|=ni7qUdNZPl&C*{U+X&#@lHajjkoQDt*5ZYCNg(IV zkYB)>U=XY$y5rtqWZqn3SDd%p6#)U{xaRjR&rTH}Ut-mDA_lWk=#Mu$xegVS{J7UW zVE^uc1IJ>*`FoAgd2e!VKlotEAGA(7O{nXmUt$j~x__{w@iD{mR;a6@sg9^8E*}ie z&YvJzQ}MnJ6vZgr+v3S}6(rtP<@+!Vkhiz&<;FSQ-(9%-mO|d|p_*~_zpgm7fl?dn}$6dYg{in@U zWZsEUTc6oy&>!z#l3u;{WX_!p%kpI%<`n+5hD z$++Xm<$jv_y1yREzW!oDyt4AT{b(@(xKEcRH7_0~nzN@2`_+;Fv)1pdjn;Tz?iQ6h zdmZ^5Btnr5DR(7Bz$S8B$2nH)h&*x+Iwrc^?%7xRdk3i?xsDK&{J3T`0)1Wy0F~}7 zNsIl_FR`J|t@s>>Q^!ovM?`ds`!b0A@d5OzULf%q>7jlzNY$Tc-lQI9EMgX#-+pdg2-sRbe z6~)ygke#`|DP}1i#P$Sk6F7>@n`LlYg0F-Kh#<#RNQj;{;zZ_scj-}L2OaWeBG*xd zlAlk)>Xmwz1wiz*hng=Bpz{v7Yq<5?{zKsKYn7k<-_Zvo4$rJC<2PLl&)eODwmQsy ze6|+&vxD4C#k+2`#oryIS7eqZ67M2qEm=u8Aia3jFUSgcOF7mx0m%F1xP|y~rA@@O zmU?>*A18n{rrS5oLf%mat|JX4zvbr(4dcfJK#j)Drf+WOyl)qX+E#cR0z&Ps-$XCa z(7m5opAW;oWO&{fTI(=9pRDv}{|NSq>yt^--JeTmB{&+tk*YOM`Ka1^tb*1G3VA^%M#oh^> z_ui|X0{49a;m?OwvzK|GcWwhPzCZ%FAa-1SF)M7+3Ip&nGpf_MArS%g}h6S zjGAt*B!Q^l)&3eic(7XgNyy^`$Xr9sbj^g|{I5oitEp+_C7wXuoYWQH8Ea0Yzxh9y zT*m{H{7kMc6uW7O1A8Sim0Rr5d0)GFEV!0!Fu^Z#@``Tt1{&i~F-J?L@LI_tShtRVcvuJe+87^EH)NeFh*gaeX^z%nZ) z*nQV(O`zBp-va>AZuO{pD%a}pFz5LUo(9P9#}t8 z8{B&s`4T&}^kUOt`2PQ$fPnE|$6%he#7N`6b!>e`Ce3jo`8CDE#Abl#5zs`0ivj{v*bWv0Y2^e0F$v+qx}co5esMma&*?q=@zx{P(S?%Vo2V>5F994lEwPXFH6ES!wvu&Sg}5W&A*)P5 zC=G9r>Z*DF@@n5thUeX$Lt7mm@EsrYPtHFey_bsj!*6>dD7@FEI%y&C&i-Dmc^>j! z?7#lw9Pc}gV(aI+cgN0+KH9f75Sd(dbZwj_0DZfoa%Uj#t6hEf6dU1ybS2igCR7u+>NW5K~cvJh`?79J&cU_lrhw@MQ zR@*-|jINM_v>F_|Txd1R8jcz2f6P`!Nvkt+=eGr-IJ=cj?>W+11+_o_8ya zbxfBUI2=p-@A-cQnEo*sIREdb>Ot+--pxP%KR5pepW4NS)PtCf+_2H=Mf$vFc4z#a zozTBqFrxCi42dG#t*P&(qk*rEf4_@$#F~1gv6M9NA5vhZ&DvJ2hiU=NG)<5o+$bGHyBvSMBu=W zTN3$qE6{h4+BZc?9MbT>QT?>Sq$B$C|Jq;pmOss4{OAA0CuyrgPf*P5{htq{@1x@V zWSjfbzqhxFrCE`9=kz(s6++(Qm)9?!g}j0DG`3mAa5gomOFF2{hoYjX@I;-A9I<9 zm8~cK#(QlFz7-8lrZk=%hP+QGdJ!X^kO0;Nx5q~(7{tHPo;AQD^L}*iWP~H+eVQC6 z-N;t8q!*dD!kfJP=AQJ&yO~_aQk49z^p&k!%Z3Bh9^*qli_m%B6S}ob^!E{v+o@By zU;+9Yq>rBG&j;U!7@qfr6x!-YD8%r^gw4iY86PT9wA@d$8oT{ znZjFNFqR34cW|7Rsvw;IOBOq{Q1kwIlhb=~mJ#tm#<|5mA@5DXZ=WoKyvKC${`Mpi zaM#$NEVLaDa!lV!*5)D4{~toHFGyc30y4;PR;PoUveqE;mgSCc{Qi;t=KuHPI;2tZ zd&(;6eAiF_@aKIjsJ)ENdrAFEzlsiDz@zQ2`C+^s_4bxaDoe7>EaU&YB{`9{I#!+( zn#w$I5^%u*_$A8&4F6~TA^vCl5BV$j3;8qnAzTJFV`84?C_(b_QcxQM=dHZ?Wcx!k|d2@MFc%ykk zcn|XK<=xI}#JieTfmfWDhvzrXC!SY49Xt&@cX;x7(s|Bs-Qv2;mCO~zh3E3*a^SMy zGUQsxwUlci7Z>MG&X1fgIomnwILkQmIMX;|IgfJsa5{1BIIvi-7_zKnS<14Ig^T$o^GD{F%DJ%7%9TQkB%1Z54)=BId%4)^ox0kT1DJ#{C!8O=bl$DCm zaYyV*%4+%8dM~UdWu;WMMir|;St$~t)?w8tD+OE6msmB*YMJx`PV5TGO8!egA6AvJ zlB-$q6stm6$tEgPV3jE=8GC(6>~hLVdfD_MtP*9lWXh!;t4LWbZqh8mDo|FE7h-&{ z%P1>}{YI?VrIgho4KHV`JY^-$`luT#M_Dawn~}%LQdSEtrFCLuC@WE~(C1ib%1Q*B zQN>D8R>FM8nz2hLE5X;xH)9u5R=8`^M64ubC2-hjA6A00;x{q6i(N!n@hviG!HQE> zJnsm@STV|qyV41dT}WARMN1W97f@E5)~&5rQOb%#p;s6yLRqnm#iwC~DJ#}0M^~&6 zWraPrp$RKUS+UqGzlp_BR?Ldsd$0nO6%)H~BbJ}MlACRMFOKD-tbP|A2*UDGR=?c- zANKA%oT@c^9RAkcC}keDB2#3DObsL+GYM%hWJn|=BAH2|G8YX}BqX6!qNHi7Oo>fG zlnRA1ga%{7`)uuXzWaKwcb&C=?;pQw@9%ZaKXo6^b)Dy~&$-uguV<}i9W)>;LZY8* zH9ry-BGD|jd>?@WiKbr(z9%d|qNyC>3}HSJO&;(VAh09Rgps)jfend%2!2^lU`3*D zz4Fxr0up__e_;^;k3{1~j@c0AA<>wHNi2Z{iAE(2t`l%bG%`J(1OEq!hVNSG;(sI2 z(6P{T{4XRL+*&t-|A|DOReap=vq&^BvCtMjgGBvLe5LTyNYr<_Z54hBi9R~9JK`si z=!5cpL;M61_2R9Z@IR2KyW#m8{C6aJpHaIX{|$-WxyYTte?_9VYYhwW<4DxSG3AOM zL!#IHh3oL6NYr`Rs}BDKi8=!R#N$Vh=#}AFKm0HfwaW#h;fIi@wZBmvKZryxul=aO ze?}t8{dW8(B%<7}5ZaM#J3<3_sA< z*!-OYFC_Bb@a7R=4-)Ma*7GNLB9RwY(s6M$RobBkgywx+^xT965Nnz zw^DE(VHXm)Ei^bqa77|lQqUoS3lh1U2%9GCM53LZZ`%pZNaQSYahR|JiJZP$BoLgC z$gz=ijNphw4%zEJ5*(1oJ~L;AV2?!GHMj!^+mXnQ(>#q}heS3_KYtNyk;wYuWaE-4=BFYDW@z0Qm^8HkN z9THJKH;J!BBFfkK@HI$OP_xenUyVdp(w>##tB@$)Ro)5z6p1d&ksjlpAkn4YJ)-!> zNR-?3eHdSfL^-)ShwvmM$_^Mv$3H@%i|gIa;~yeX7Pnjo{s9tYzP=-ezmG&2mvEQx z_mJp(uznW40*THU9+SY|MWS^6tP*@V5~cO1^5X9x(V1(h{P^2QbUH@nF1`$jPT9sS z!IvV@Ns*aB{4FF(86dWPCaj?Vpiu$Dc(azsL27_%tN)O?|K)e+G&6d1%byPa~0!;x9q`DJ0rE z5t)iVi9}w{jW^>{k!a8Pq)dDY5_$T+yn#P~L>`*GV))}o;X^~}N@q$+FcdF$XiNF51gkJgw2(%`<% z$1)odLAi@%iyGWPI`}n6ub`_DJbF;IawR;2H1$l@n@_&zx7fcsi{)Hx6$B@!<03x= ze9am~zXxe8&uS=omho<}BYAAYm>)2R9hazqXOMD4e82Mw`yOQG+LvJC9anHl*=~Az z0{a2!pTDP1KjH~u`W>XgPWtk=QpnjL2+tsayuE37Q|8!SA@4!F9XtX}UH7h?*3U0Ox}>F?9Qg)%i9n|;cdIt!J$Vo>h=aTfeY)qxEer=Y zA7|rUZb0YlaBE=oOrs#UP91k<;HHFi2RiT6la(#qsf@?lk(x&e#{AsWo%i3EH_nB=JZknj_E#0nJwdvchBu|} zM0hvq^esT+ty#YR?lQ>ROMGOC!dw4|kk$_h?}KN#)iQNSXWm;pm|2?$c*BhsnnK>= zKSfSizi9;7?}|MN;n!O~EzlFlFh=K{yZdV%-!nnbM;$lBYg>~35}o%APwV{9WQj<^5#ya=PedO zUmhH5o)>f`&++!6;Z3=bg76L(c`zT1x3Kip=SGmXbw}}$UliW&&isyq`~PE>$HHSY z^+*?fWW;??Oa#^Jo7|ls?+d3#*35P`g3{yG)w{*v`TrqRyWcya^L|{k{grMF+#scn zlg)PztN544Thw|ge3g?KkM|R59x52~+g5+;=y*IYnEvc-qxl@0_hG$0d=linzT|yX z*wQM@4N_b)`}yH1FQ(uB$5qjp$1Q@t)ZdpA_t5aB+!;i8zq%03j>da!yz?Iq$XmC) zmzVPFZR0!rS0^CvhWISmL7X6S0RuHJbsjfhC<#-mn1K&?`Qu=yMwxILQPw#wowOkO?P{(DjTxw;{kAA#m-)Q6$i73Y7eTACGM~wLuXdJ&}XUGd~ z`VHI~CSmj5W|=SbaNYs%dei)5{z~j;Z*c)O-mhNGGCyxR^I-c}tBp(j@A-cw=>F%P z|M#bPjdwQ!4vqGUiF^maTRD%H_qU_hl=%Cu0XGH({~0GyBju(# zgFgOLsbeR5KI7G(IBFgzG3KYZ+x_z$_(`Gnt3U5sK7w6?O0CkKnvJ`GrMoAen({Sc zUShk}o)F?({)g#TkkXs!%j4mZmYF*bvnc)lej47C%|3*;YsMm8G~UZzkov75@11(N zS1G(7ts&m<@Kx7M>1lU8Pyi6z5id?n=@*W$9TMvJd`lzcgtd# zaKJYnFrGh_YWRP^o4fVGliQ!GF{?MunsaHkG4uETqM`KV;cFlvf{OQN8-ah(=dz|6o#3yhuM?wM}{lEVPV#kmF1^xd@I`e3@ z{zy3>4K7ah(eS1`Uxe@umJR1b$;Dt!3?DP1$=JKeMg=2jso;LvYy3L>*GV zD6kmblnC@rowisGd8;IEAM=0P2yUqVoZ;OO4g%Egn7z$J=UuZxt|PEV5cpHaZHe2H zsIm}!aUv;}61O{-@pvP7NMOuQVk5qO7RL)R=4Wp7>%!(;Av^ARN_aQ0Tronfc#OUG zhVy(%ab=S^EEAni@oT!V;-Lua2$~Myo-lSwBS*m5X)5 zYiHdjU=2D}U@o#0_Wuuj2i~#VG$Lua9xjTEjt8==v(aU+|5r*D^WN9r2u`lObGTa~ z9LU5ccdYrBTkPQ?VPV@&34!I*aR+y9YF+X#HR!CNvw)J(auTEcnIEF&aT;TO1nbwq zO1A~T5+#E?_eET~Sb5ZuWZzn?+6OAff@pYC9vMb>_jt`GqVYDKS0!@|^5)HnAEoeicq$Mz;{!i$A+?;(+1ik#aO-G` zTx~o!G1OI24SBCv82Co851#+`Hu|xNKsY$&ANi4Va%`m#ohw183C|S#XqKLJ~r>2H-f!)DDDGgn_fH$o_vDc zAi00QKaFMn1_`%^&OFABEL{C}1sO=goAL}i!n=EZyC53x5A1`+jga>PQbfok#IfT`cBE_}B=*=ezr&vctjk9K{!f@6mY& zm&PwWyio|;ppN^R+8AYJgw9*84?nz)h4FZYQuA1jF~7~B%QTlg6ab4F62CV6#$G{I zWvvr;{^11XU;HIMDq4-ryVgIQ=e<4CACQiFMqeHW?c@&`<;_*^02H97V zpz&U{p;r70vEh9rRQ*Y%4!A#c8xrF>c+ z8bOA2WF>ofILN-O4~!y;FJauVIPKyGZ>|;Hi&{*C6#$^C-la zpJ?l!o5k}5K@RzBNZm9x?|?@lyDyn~fw8`suM_sz2c(~0t5Gt1-+}2DCu92bbVog=Xf8W;Z1o<3E{oIz?UD5_iN{`r980z&kwnIoWeVcuQQz;uDvxnv;;;@>XPof zGn;oXJpm|Li!S&Cc{i}++ROAdf|LovfM+TZfXmh7p4S2N+f~AcxgOQ92mx;DIP(cS zzAFx$w;jjbzytRgk2jH;2iE-R+Mn*R-XsVnd#tj|C$M>MdGmQd+r$gx3$llAK99Zj z#%T;BJy!K*dfqrwI`i<~s=aOBf9L;W^>7UFb9fIjf~E#h-qS>Cki-@RF|-E*#+PFT}nipTWojNJ81v(Q z=lbE%7D4bK_rn{rW!Mc;`1z{xwi98%sk3DwIbganvP;l; zuh{;}(cza6sG*K4l(TKSZ-UNSKYY)Bl^8-voCj`Ms{yz_X31jna z(GxZDbqE7_m5%=5!8O>`yJ+%}(*7+>&l^W?9!K@T1+Tdc(oh=Sl%pXK-uE`9FG1t| zc|&ZTDTTMf=50S9@Ai>V8#Bn;JZb0okscG$mx~z}ZL`55ZKnMs^$1P9o&}rC+&Rb{uN0yJL8IQLEHIMZe^Bdc_ zZ(WG4Ab5A+_C-}*Y~IA(s|M`7g20CJ={p9`U~iBrM%T%oy21P(C+4_FUmj*BMSSlc zoqKvKgoZcetP_Oy-E(^vqw(Hw{7vs3$h)EW=35GHye#Y6HIVm_^MXP)UB;yN2Rmc} zP2z#2hM>lI$Xg`jkAwB6M&OX3s-I~X4jz8b8tRHf=S>s}K6wN_Z%Cq!o0l?}{#y#2 zw?lqzuZuV1@fM-xVTUol^wOLws}2YNF~P5QHMp^P6CRWlSGop)cEj`Ys>SH2-tza# zL)UmQ{n|Tf1$}vxvq!eo-S}_+pCS5ttVtYoh-0CtL6p;;kQ#L5gtRnT4Z0;`$GQgg z|Khv14~@YZ^xXbo`#SgzlJIQq@8SYGk^+aMUA<@=c*=RUWUt65DRQUDWYf<^ur%mM zxY??3aHBpl@Q)jM4N6%#S^h4K2#TrWyjpYHR~e$$px|qoGYzX{Nm%Lr-~Rb2Y94_Y z^D~RNewRC307Mr|OmJ&q*P!wHi)B6pfc z(k3#ugA|9O;Y~Td4B=gv_gxB&_vvX#`|XhTTi>pTamf3_3h$2r@CE6iZ_AI(dul^E z{N_{IjBp(2s9!@o3wd{TduPp`X#{0udF#vJ<1IF8dG-fvM(1s=_GF`0DiK&y$8q0O zsU2F4&f5#ux~ox@@px~d=HZDkKlAIi0t7z@fTIhK%{=AAijxA9Z8Bj74;-it0A zHg8KcyE_A{FPNTpr!swcq~0W@cEV5W!2bUb4R6YMdFX_LJw?xwLrW`Pd@cyHm zB!R|z!)WO4Y{>gg)aD!t@7@#LlbrDNmdKyEPgUM+CjH(NA-RY<4wSul@_GdFwiUH6 zkN6IG$B9SQjE4i^Pujcnmb;_gmKh96@63bMdogufo}kaq+Dvrb4m)mWTQT6`WQ3Z> zc8vM)ym5^_3H$#A;o+`AE3kRLBp0_w1x5iq$xUl731WZV0$1a(Vu!Ii^YbpCFOP-< zp^&p_bJhDG4R6YcsR(Zco*m+7y!YI9l70ethyVGpg0lDa!%H^z4cwgA(6?1+{k+Yj zuHj0}oK zjm>-QIbXukYrRa*doY5&JT|nDuX9hF0{@-=_kX+F{QvRagZ)1nO%0-)8I9DS!agAd zv>Nnw$V?|$saRJ-e53LgScA@QaX5S-1`#a z-Gh8V&BGgGey1*PmJU!91j5oOzi#Vb*C3@C$C6_ak>Ealt^0k`TGT&BM1<+ucB8EQ zhnc{J-oJ)l&%xLk)I_VShEuQ??c|=(n2z}>}2qem(V(q5DEsn8X|T#qw~IOw7+p3 z3lV&xj+^9CSTTR&zwk~i8~TvJc)Sa!dH7(=uZ%0?)r}YdpxRNT;s&sJ%ZbNk?>!s| z$kO7XAGgraAO%KB9TG}ldfriA=*uHGMok+YZU+1RI06lC%BlVcZ|?59vS_@oE{!KQ zLEa|a!3Lv{_j0A`m8y{U`qiq$oz>1HHMg0Y5>Mm6ftq^PkC69a-)kCQ31q-(w4O8R zSSVbP?{(+1xR(RurCemXdHhVgiRrRL#>F~14LXpW=9 z0w8yBtG%Z#Ht+s?t}w2Q!{FitvkNwAPcWN8`;A<3BqFd2>_=H&S>X^Lb;?8lbLQ&9C}0|FaY6kI{oS@?mjc zYWlhnKkWa{>^uP!=aIqkzWID>=ZAshn(42GR&J<&E$x1$S66%&0*TadlP9_eH;$t7 z4)(vc*779d@$RJN5ri>6zFW1r-|Yo~&>NeDMs!r~sVjpEb0P15iyvQk>tplAy%syG zb#a{Ot2fS5oW49#!urq8J>C*GkA^qpyDJFql$VY&XuJ=l4&LX3{lD3wneCLlxBKaz z>)YYpo45LaXQ!Dx$ww*Eevw2RxLUSQOBeEXYK~<;_ooqD7tlTO!!sPL)qEV=a}K@# z=baBOJj^13)zop%`-cXj-O&602c_=)xb=+J{|iv_xQ8*no)cepe3KRg%3{|=BiCbB z?+S?{EkpV-;NXaCz^-N3{lESTJ>HWwJDHyMWEFjRB%geAVj}MJfBiqwd@=H`a0R)L zrUp^IJcZPtGWJ45So(I4VzI7lyO{S7tU*86w8ll@3Uch?p`y3kyGTi*-@Y!6 zP5=Sp$@v;^1$kBVeP93=8LX=?uXEcL2BMZa;tximUt%wDu0C(uLV}6Q}p-vC43xL$7a-U*5>>AWM{ptGien;TCWBnlOB=#eA zr9z!`ftmZ6z6KS3@1QG>l$XU3CW(|s?BY0RcvC*5hVagQ)4LLlcmBnbx&*j_bg2xU zq41ts@jTHS@-{qu+$*5cm1Lz~rF=jQenHymj;KE59aiM?R08t;uBx0?w=xV|4YnE%A`IjljEoKV4l(*X8QYv-S_*S!`EA=<66>^yOLg`^EOO*uCavytG6gM z4;_s8Nv=5E#=ctsEN81a_0t@iw?T?k>bT2(aE#4DZ)H|BChww8(S#DSR;I7skyZ5N z@!f#;e}h)I9hw=6Atq+s_KJ0J!u#J}Jo*o44zy!?-lJ{h*^eE&jD| z6((<7hYNr1yS>bRK-xN2`topMU7#@ccuO2R4R6ZVTM^zkVbc|8ybb&gllMa2hW01& zXn9`&hKYXTE+idGNB?xlJM+U0{cy-T=jn#A;A?8ywUy|+B|oLh zm@grMUh25hVLTSW|8jdvAWG5KvV`$&Z^=;e;KrDr)#Vgbyr}?a9Vt*%qvP&vmxk7< z(BL4@%E}rUQ-;0whFdf3of%1B`s$54L|-0vVuwRMi+I5Yqz?e43QmJvq=cz+_6--|8KmJ= zm#!`zCEagrDm*Sk2A={;zn2<@fmBg0sahZO8pINFXWSe%NT;deTt;ImPO_ligB)&M z<92)t<6UCesCo2b%+Ci57dl(;g95?uenKSnC01os)Yj|pI|>|2>et5om?0aX19xUdA#1P;Xop|V9%x80C~6F(|DF4KnCw?^RiiG!ocsn<+5fL=)4b? z6fJ&ACW1fIaqxIGE4vZ&6{OKo$Bp}K7>{=>H4lI>zmEc!rsQw%13zc&&2pjGyd7KA zy%zBt1UxG|+J*b+SV0;;yRl}OEz|SH>Cu_T+P%(-e^-!P|HE7Q&$GcL2=DHDS?XxK zHTwePLm}@G{VNYCynEVIT%JMRSz`fsP5)h_b!F#Fzk@{Ztvqz%GvxjK_pQ}$`N&|y z_{*u!&%=PT_ZidKNp#-3H;9%dbP)d;xBktQVsm};>P==*9g1{eJled;D{@Bx$T3^`_lk%3E#XBa6;vZ*7=qqJfp8QywOGH zeXsnqwze2MrM3N0PKv(ReFewh<#i-fbdjZz;U{ zL@h5*K;BhaMcON^cae0yW#u2MNdN>svwKS+?@3LcCttbApijFw)-5^=3|vcy>$rx_ zdv$9@8BZq>e4vgiD_c<0|1aPFtG(&r_Q#F!c(0@8@dRUj7oJW!>>%@l2fLP-1-M}I zURULQx^5j}nevQLGzjdbpww)}Z(cJHI@K?;thm?77-Cu#=Qw zV(U3vkqCY-NEYCMD@e!7b!zDnWN>=S$0*S(447;@<|uaxy$0R(>PuP(??IYV$AMpU z71xK*8zfV;@XeN)jCT+6J~aYL zmHBSrwdjx7i5oh$of+`?e;H~Xi!kO_qB3*GCY}$} z#*Uc8W@7VJ+msSm*BA)mci!4~UITjtiL<{~tlh)>4@l#T>C40LJCHZOGS?vS)9_|} z=&~E(ZP0y26OH%DqM@8R$h-SsL=T1c*LUx00w8ZwCAqMYRu|HS0?pR*4T<3Eb{*kO zkoTH1yuLo7WKicgOFUZ@28=zll9uzL^L`!uyZR#JZAKmUHuSNOn>0G_^mFI3TN$u= zcT@8?g)zT1XD7<*J^6uJXxW-y$FX^<7r0#CWE23bxum;VoUlJ{*^tPm8m{Ti^ymM5 z*-u{{=IK@Z8;{I2NPINB31^I-A-qevyfn~wrwT^jAA-D}6t@HnK;G992lo#{-r4T* zEF61XNx5Z;68kz5!Nn-iHb2OFQN==CKtVZNwj}=0WHE_MT;j_+`dhoD5U*=)joYwE1bN@AvqC?akM2xpCOMPxEcA@7oXn zlpZ|V`%I3G>TPxN>4S`2OwSuHtYOwxpUQjO z27ma$$j#rgI{ycIZv{)UqOy#!t9SV0eV?zhJ2L&++w&oPdAL85=VCwh-}C=Si_Or# z!v22=O%37_F(FfG5T*ZL@X&@0tp;`CZ@hk`P^?=)-Z9Y&YY=;9$ahNrA8A88uz<~m z^z?pnmhpH3Xj{4n^a+oWvLo1~w57?Q?9eN@r|m!S28+wIzrz4krIYi)51UlnMa?a7rlDxZ8sfpUqA%S)NvkF+kYf4MdwXu z;1E6&%Xqv^sCoQ({_pb(ENwr*f13|%K2f^)_;qaF31?k08adp6Qe0`%j6U}MKZlgT zjvgK6@Bh_A>C59LD?j;q%v}FZq~XnxAaN7neKp|GJT%_&nymiXkau>aRtAN4bx1+) zRmi(o!QSCUsuO8$ z#gO+KP0=WC?po}{$$@B*+LQka`hOq#@)%!X&L%c@{$HFB4etfEO-%^zg0-hu(0JEL z+Yp=~?|5CC<&?d*vtynsk|A%Lc$kHI+)fhP`Q;pbw-UiE$;#rNkoN}ftomL_GVpE+ z+qf_(416D%-|F0k&inDUFPU=7h+v93?#=zNYJq>*|G$vbR#3%&XK&R|^EihwKkY3$ z+)ujmfw6iGmfOYH)w{m&fzZ6+U0}=dHR4Mwv7fzdxOFOR(TQzL-~T`POkW-!A931s zB>uPm&(M88GC8<{6sM^{0$hjcks2gzuyGMu4N`cOyix%+NPE_Om+po&h@0Fn`wQNK zG%d^Ns&`Q(E!pvMl`}B`=;*xGz5{DetFfK;GC4B1v1P4P@{dp;kyDzxbUk_vdhTS% zpV=b>mQlxjJiWC#@h$rPzZCC{S01*Ew}Nb><{^eLKfTw(Cr|9>1-Fk0POognu0c{~ z7HT&q?gDxPS(_H8R$*Ua?<($9)0$!aXOM2vna9Am&fgQHB@M#&rvS z>u#ZlH#c!izd{eDagCByRL)6 zyHUzlI3Mo+d-wW?I#^kfEY9wfC#EF;2W^{0?U1)hPVI+tGGt&Dqgdo&6$aFuIyc6j zL+3qD>BgOk2_dkSI?mkm@O)KP^yucOrdx$P&~7{>05yZxI^a+$M$<2yfQ% z7k$KHQd8A+;@l`yyqLweJ18b1PiuG*^RmfoQtmZDc$D!c#pX=R4 ztmrj}zxHKs{}Z8q#@$+zeC|^O7ps^ z1>Cw=VmMyEY10`A0j9$qujEcvVb&mA)oMe0#1!-Q{}<`Z!|Ty0>I>4#Xm|@Z&&VLW zg^zLZqVXOfi`>nCyr0{Yv{HCK2pzs$3tzDlsFzm}_+tbHZ`n14zKsW)Y!tpYLf-ds zL%g|HlEF3(A-sWJ7M^Gy^)$n3&#AK<%1V~OXLL)c;D4Y|H5vNxC(BWm*o0^lyn`huR_@U zzx&rfT{ne4OwYR|k-j`KT~yu;ADrv|C24pI`5b(O@Lu|%kPD6XR`R&Q2grNDq3T~0 z-kIfJ>|NpU7TJMLUl;6D0JGzupmZc29I4y(C=K$KJbO1{lL8qCayZFd5eNf8t}QEA z9nq_|ah>mtf_5PgLLC>|V{`Yf4PFt?3%)%F>;o4h*hPNO%z7pYm z`d%m}8t+w{9e>zh|9_#U^5lESTXOMK`#N~`R%M5Xq7{n>X=?KLxwTXApjP;G@m0us zq1xu$5xDpE%YWDS3px1itzD}33tx2JJj2gAz2WABDRo@1QG{djPjue?Znai}+Zm5H zA2pAC81ozFQDr;4oEMzGwe--b*Vw${BiNSO!M(Tnea}iaeZ%hm?;R}KpAq(j>DS&z z?CHy+{r2rUKeGSp|FL>FhWI(GLGm;;NPN<*8mU3tztn}%YS4+iS37IuigmZiSZsd{ zYf#|z+F8m0>F%%lRFAmYgW=*kTL_v7Ao9hp9(&>_>Cf`lCF(kG1xdD(PPGmLG8>*h z#a%?NL0&tJdI~NJf#uY3F#(3r-HPbuLkX<<}u6v@AETAILPA7&kJg- z{by~7*bP$LwY;Xi)8QaR!7a`-9QzeJHffL2wY$QZ{u29hK7D!Iy4mwUA$o2FDM!Ow z?3sEo!dpFH9ubZA)}Xb+r~FZHMhZ41S@(Pw52U#uZMC zfxPWxRl9C$kwN>G`lpwL!+>FB%R%3r=)B9vG8Q`(2>ml|)GMWNbUr$7mjlP{dk8Qd z@4M7I95Lp%*=zh+g#{0gdHl6wA051xzPP#BV_pPkCa&U;p{M_U8fUj*%TcE1jmxDk zkF>?bR)mXlD@a)y-b*tQ{Se-V?zIS_@vh!oXUqv3BuO))=r@qJXZE|70g$(MD}Lpe zl?}+r6Dt+KxkX-hh=)`y#Fkg-X>Kn1O%z$ z++QDZ`uzia1!+IMeAmt;jK`a0$=^I|Fy<$d)xGMi2rmc&obAbU@D8|j8lRPM3^W97 zxY)87yZ`s>sL{7N!2AsoR~~(NyfoFu(0DhU2>GT0 zdG|UO5xXF7`D6P{Vj%DHoOiFTCv63>V{6hjevJpQHkzs3koQTUuKMBCWZ>eviRAJz z6et^(%Jj>l^VWY;o3s0_&_Cl|KQ0#O9zf@<>g;m=(sIV*ZAi^S31faGPVf8HIP!ps zFZ181^J6bgxY!$8L{g6dx%-#iA8o3^-kk7vQ_6cV&GgkfN{hZcG(`?4geS~ZZy6fi zB5FRn5Z=dr`SPRjPCvXiU>oG^+q2~wg}2TLR-;77yF>Yn;KWrcP`zv0`4cbV0T-tP zw*>6}J3jaO%&5Y(_Z0`CJ$&}|*+8X&!#Z@{hq+06duoJ09d%r2uWamrQFPv+eO(jm zYZ#ArG&PSPjQQaorY;${#sk(6#hV{3!sfkg?*M=8a0sYeUEuz86ubXVc{^_WAz+y4 z`~RDj^yOg!)|||RXK!=D2A7rPGLBP{L!W&Y;RyWgfB!Jrp8&kXuB53!GT#E^Vx7EmDp*$cUIiSjU6?P3$vzTb#^C}F4Nd6qsZg`4)iA{Oa{5j?`)7Kze zCY^btXjf6s|5KvjE&W9KCBl2Z@^4Wz-j%$v^EDvvsFfR8J0R~aQ|}WuA@40;{fy3~ zIe^^c_qj=@5`b4p@0|w7`+N9Q6pINN9Lmqzx34A)WUKVbX#POw{oK~E;g&oRT%?YR z3)+m|cM+X;_tBL;?-Lo1HZB62SB;NL(&`dF1~9JS7ElD@a8e-pfwP-9vaQlWIiJcoPh_6*xfNyJogz zPA>KN`aWCKiuIILKr3 z#vNDQU|<&r^0#bRwoCz=xBbuV$+D;xrsq92Nnail4}a%Z9iQX9f`+%0lkQT4_tE>O zm!R=3nti|e5aiv;#;@85c~}01->-lTQcK-4r~7{#z@{$4S5amOASWkUo*VZ6XMZ@o znAIl(wqn!9Z_mPj@|cg)p$T-}7x!$8KCDChXPjr{!U*#V=)9+s!zNi7@CE4{Y98M( z=9fG#Oma2c|G%}>Q8!H%n|DF><^mq4K(J^vUt#fJ753s}%1F=ofgAHLPCnC_M}6d! z(%-|06li!$%1((Oym^kfEk@(5^Wa%|F6518AAL&8J8G@7vlQMD+&fFK^M|~HBR)l} zguMAr*fvk;k^x!o-nyzY@bnf{-SUWTblxE=6vd49&L z-l5byCNSnF{BVbVsTmKr*1GIdlQ=eSvs7CJr{j^pWHr99v<&<1E$;eD$?3g+n4fn# zeR*^Ue10E(`@jC5(OUig&-uXqU!A4~tr#)zL26JT-!f^m8kC|T(&r*utov}eSad7A z#AaEW6>f)**qwg44t{LZ4zwpcc>fT7L5fSmHB%6-ATNoiE30iGg9pNr&v}~Q8>H1L zRi^)PK-z~F95P*;M6ixJ?)h(gn(uA&8r0&iy;#+g@oEr~M-#^UJRb@tZ&u;~J8UIi z#wcUgps`Pr?#tE&f*a;i7nBsSSCF1-7er5-b7J}xWLF@4dAv^GQ`~TRZUw1E!&~9b z+J7FgQ#AN0g~q$o{QljekoO4Za^W_}dtpw|R0`xhs1V0*@!JlBY5MFjkWK_WI6)gV z$h+k+XNR8^8D!1#tZ6F^17^4`wj&?WFR?#klR9xcL|{rC=N5d!h%FDDw`9ka=M{Sy zk2jKs7{>fo^Y}yx?&krA*VG?gOb73pB=uWf>VaU0L*Sv=5FIPX^V$pG3DQi@8`nf< z9$ca(GJjW)sx-Xiiu^7i6k2DjeD{}3nA~dem%t$-nBe#-&-JWLUdO1$jo-I zD{f-w6Fw0{A1G4X2zlFDPIY{>Bm=%(aur{5!@z0o?sH8q(0OaEE)h>%Oav#X;|6+< z5A~;`^Y%-=a3d^;@pvP7_+ZTMsqk~xRcbsS@ps`~4?1pdMTQw|_@LkotoE_*Zl1#4 zLCRfIi3ZOcFES&|F2BLTUL^|0O5VV-d-Gy zH{M&fX$rFy)@l<65HI01Bw3dLmTi*AiGsY>2E~88y^#zI zrR+tw`-K6G9hSpkndrR5+T51Cf_raksN-IDhEDtlMz7w_!;k;;U_jpD)I4f2=J!nB zyjgAy54gWu+5g*WY~IFa`>u?1g#j%O$G$Ev?CO1e-_g6Tox7Qy_wQu-@`!Oi{fayF zzyAOKv)^X4e+m144VoIH`f=+xQiEJSh$^7fpzsWb#Ny?}y70{7Q!ii*S~O_nYYkVB z^QzlhH(j>{1HbjyHf1LQ@qLnuy#z-|aeJ~Kzj7pl$o)SqU4fU_Teh=jjr-ASP{4;6 z3!Xnh;5v0&p3If;9i`|s$m*)6f!7wsyTk@j^RU2}U-V*mXAfx}P!#9BhE)!`2Bpux z@#M;YQpfMJM*7Gq98V;L3qEC8XUS`0$lLMWRg2}mw!rV0kJHW6M4;HjtDgXQJDVPxXtyVW znAtO({25^&85e+CN=D~x^GUPB2J()hj(ZxtH7xO8`v3lO2VB&*F&=MQY91dj=9j&} z<~^@F4>;C#XVi#}4N?W+;m1!Q@8*)XmN|lStRRb8S4Z!+Xa4>_iOxK(N>BIi5TraH zy@rOja?qzs2=BL>%4E@aD?TTF`2l&C?>S1M@Gjr(I=ce${%xxrzgXH9_`6qM4vR_z ztiS3G6+zy=lB8u{*^$8|{^gvZ+TmbBdU^Tsz}=`Dd(ZA|>PmqpNEuPbg_qb56i%a8 z@5-$m{ZAYik9R#akB1oZ(+?#4OaVN=_!H^y7dmcl5fzs|%n&#PT04Gl6da)AcuUKd zA9>t6n4dSDdFRF5MwpjmYIT~*P6N_(_b-d4JLX z^M1n@q=N>gO&3420ScohZ;tFu1b>c;+^DATKE53&*^)u}_2=&8=fi=T6_2q38J+hI z`N{V`<%mFqI*#kW#Hu}No~ZvjSSb~D#2;cj-pGQu&Sc-cEOJpH^9BOAJlQr0?bp=UZ7X+^{rzacib6|w<|Rd zO^o?z)E7KV?&JnpfeW4`sAKbXx>|Xm#WMnQ%)TV3;A&C-xBsWrJAqGA-~Ns1c}Lx( zFOT;uems2F|Lgz%`TJ+&-@qEAO;dx`b}DfrH7HL?Pz9|99b6qQF(Xr~o6)&DpA2iz zIo?&>8{j2&%SN54C8kb5LNUT?rX~^8R=&-8DFC1U4|Roy1CT-7HQ(Ycqj0dZ5LeN1 z1ic0&9bYN>ZXOZrppI)vdF1h$8~qY{$GBKo+mi8WP%<@-5{&tg&oBIbZiEMv^E;&T zN?_NZ_R`pEP5J(yzN{-j^Z|Aait3r{X?f$v^ef0H?kT$R=v&XBzY(563VE-m;l1Y4 z2od3ZIOXk1G~SuR(+x{ugLI>0K&uJzzIoNP`!wX8{k8QYf2#v15~{oL=t&}&e)C|{ z5ahiHpZBHOjSQ?L)Rh0oL*5C)h40+ad9O09J@ECH5OAW7d$jiIIosdpm)MHfO;3m$ z8ISjBY93`6^E={D$Hu103oh$ucW^Aj=G}U;g0G1!9O$=9SiISa&3lcC-dImh8`JY1 z-a}s=`eVkY-sH^j)}rCPI`rH@g!e-CQYAFr1Hz3L^dN7K%Gnnb-Zm|d@<$+VE1)}c zQOq8!i5P9Ie3%G^uLoY?geypcyN8prT**M>v74WtWH^w@oOa#sh|W8*T)t#*MhJ*g z$Aui$eAzLH&O4PX?E7K^yPF{guhLAYa4tE@CO@B3}HR;jax1EF71 zsn$i}JJ6A`Cx%>}2*c^VnwU0Wk?zS}hjwy8B$)qPwk{IyrEjKlfc#QeE$*MnSy8~}; zg;w1kmBHp6V;=u={qhL#u%myP=Lh!ft+>)M<#l$y(4^t5 z&fBve;q6;%u>y@Z*NPtZc*tAK$?g}0_va4LJPPl2w^_G6s;TNRDJ9`v-q<4YSj|?&-&nE&k_f-FrutEC%ZOaEQFEW_DYmwt791iq&l{16w z(QA;(*7f^2xQRfQI?mCS-B1FL-v1kB-@mBFfHeroLl0wqkM?#9c@*$~wj%>QFMea6 zL7MNU<(rn`4$iONBX+A2`x1-O*+dE~@MiuMq#=EIWPf&x1i5n!k{%83_2=(CKzJ8$ zwXH(q?HF;o#24}|2{UwQpzt=&{eA)R=8WjNy?U)H2$h+zjw(n5p$ktwDuBG(V(c7d zJjvh!%YGl;pJ5S(-m8a?AvA#XOWq)`g*-IW$Q$|3Jw<*)lUi@5-C z!f^G$ibUWiT6>?uyF1s@;0NR_clt?|?&mOIcf?JWPZpi`3Ed-K_rcd&Y^mc|!iJPe z`_Oq8>rL`y+Atn(B#$DD`IRehl6Z=Ez`*v5colZ+6=c)_mA?2NN~AR*+w~7;W3M2i z&XxYsis)u~-ncaS^4N2FP(0x8?JYpVd!5$ebx8H@nSVeHjraR^!Rt#Q?_3F^gN=~) zyPlHdM#wvg>(S!%7o5Rq7v1USjfp^$=+0IMc^9nsX7w5Jw$v8f)-ekY)oJhzGSxum z-KxJxr&fpvf~n(zSLnoKeL?5_YL5Vi=MKi>jpXqXV}6JIs}|Y7j}yh;R=OR}iOm}~ ztgBdmzz-Ma+P&6Z#I{=oJ&rf-l&chQ$eN`H0r&A-Q6=+N-iWNYR^cq?`r zs-p4sOA9J%hrAazeBq_+ywHZaUSfCd zXes2^L$5*0cHy`9EGGgd>bR6f2E9=~;G~VM5PCu9D=hjICM>PVZEFtgw z2cBgU`^eya-Y))mY2o0A=G}1N9(3O81TMHHFC&6z>bP0g^c9V$AQu`eD}fS9pQ9W?ylB4>oW4iT$r`ddug`Y&9@6_W_8^N%?DLf-71pUxC}lfg;fuYSW9!oihH zE;a8yblzqqw{Cuf)%!Aaocn{KjC-5Wd9Py2JMX`X@pvP7s9?;G&p^EIxd9*89TO?y zI)=@g!I=NI2JpzOWUuwsX-em@Bh>PUq8N+4Xp;biS&+-FDur)*}7M{2G$_a zZJW0o*{80{-Lm$Y)O}A7tKLw3s(ZBp z$~V7?u8g_ITg+&9o7hV_A-vscCh=&zHT`-Xt%1B--BpchA@7l=XFIDQ@0FYP~WZ~Oem&RM#h4-NI4v}rUB&0$F+0=0!H3iXc_|bXGv)I*( zG2r4Pl$wVO#{3RQ*&cnL$qRzg)6(*rv3Ymxu@p4VhyXPm0f`nB)tHMDZTqS%lGZ<% zp7#?|`trDSlTZlK{(JwQDK5{j|KChggEn22_@_a7+PrZQS`A80xyEJ;`~PIIaI2@V z1}&@zW~cQ3zhpvp8_Iiv`QoatlT;GG(WaF@_2CLK)VkiUEs6}x-W3Sk)_@HXo0G)) zB=j0&csn5M%u0BIGdE9B-lW>2S!~^Ee7*9FgYSR{a7FzSWm2aZnX=&di&-YPY(bhu%eFB z{62h5cQHC|>&6>xGW!^>dhbW_z?fgx`)$h0*YSek{7AWnh1k6Lqs428T#?`yp`oHg z7Mr)_>)@j~noUg4JMt}kc|0#(CvZ7=j<+QZZ}Vke&LF%cPd%KE#@lwW&!20M_x>3c zd^O~)$7hmh2zgty)@O1}dV;c_gRc~P6Tm~xxYa3;ck#2v*M;F^a5_Qg;!DMFkga{{ z(O4)t?-RQ3S?8G(K_+!v?^!}CH<=gMeNb?e zx{1x3<$L#|s0EQAR?%*M=l~s?6De=yT?X5kzCpt6r!$XltQCrXA5OHO;ceENFOTq! zKN!P~#=HN^8Sf^@TSfiYDGKkLE>BxG$opCFie>(9Ji!LF(^7rW31Id7Uxvky_seb{ z&dN|S&~Xs1e>@xpqW>TE?mV2T^?w|`q0C{M=ed%Ij7hp_prm9-LdqDTP^OJiindvW zP%@KHDGgFPbD`ZphKL3gDGE)7Jonbx=eMut`L46}?|QE5dG`KY=krf>&iiw&_q$%b z*Zp4iTK8(iH#_Q~^Zub~p!&^76dXa~0>oyF0+`Tw8-FC?c^>|2teCY=s5883D@CT&_t;7QXv>x=$BI#hJLb*{)HusSSum_che+w&zJ!sL5 zgCj1tJivSAelu(NSl}^W7xGMCj3_f~e^Koe2~5rwvR{MG|F7Qt>}0A9dJpQHR5&8R zD+=_GxTR(*E}96S_n;#w15;bI>F*NTjnsk1$Zxlkam<7X4(!xUE8TDqy9bHIvM^5? z`-3CXq)u^Z?D@Z;ZEwoC7mPn3tsSJTj#BQp!|s1~kakeUGw|5YPV51R>4f{CBdWm+e~FE(p{ zL&e*Av-?vDZ!OmMd}zFPbZ@sGfV?{<>MxRc`&ymlJP&yr;QBnW_v{0vg!1%6@mRpr z=Be`=^5#+IlPf$)0?(yVj08LI;ODXpd3*om{r`mcvRnJ*MZq`{H)x&LMVLl^ddm^y zoxenf=l>-kb=YC#w=+-5wem4PxGC6ItR9TbyCFWlilf61T(4a{_~sk-3bO5sCZ7e4 z@sGEx)X}1;j#b~wGm?+Y&;Qm`ysd=K$xwJ_?5pHO15PGp7y604DeMjhnc`PhMU z6!PwN$#vmu+Xpr``hSlXiUqsOgp+yTfE34nbHMWi38b+GYONc=gJ$nfhg<*U^p-O& z2St0}=0qJ5H}0xIJj;Q;IB`8W6u@Ukf89G3sbeojehnvmSv93`z+~G-j?3ZLy!9%# z)}83|1H;!wpPQejVg6rmQ6nL25981O0yNg)P~EQkcmB7c;=R4!Y!`+1-O`9fXuLJf z5PB3L@1nQs9*}vfaYVu5gSQvL2uDwS$ZY3x|-ab_We>#qnz*d&I z+#fDs;N5lZgX{00FHXJ%>8jVOiGqG4u3G=0^=?yi-WE-o(oS^9djhFr3r2oiJCiG} zz2XP#PnFgLBx3V^(au*`lpY8Ou02!2!w)g%etGCprj+Uoe4_%wPc+?@Dt z{%4H&-+`(JIpnMvr1YTNG#xRt9<;waqWH6Xxlvi?kqh@=4=RhW?d|o|GCKM3Xg5j2 z4b0e^qzReDf*qN`rib7Pa^lclEu};fxYw1j%#0Tg_C1($O*`R+`gdnrpn*!qVRrgyjm2Ex9Yn^ z-#Fobl&C)=ejoDwb$aWr1@IC(vSRZy{xmmG9{kSHe0?m4h*LWs1$o!0y%dy6Ab~~4 z#((E8!Govr)05q3ZQil&lew!xT<)U2h->0e>*DPc8ko@D7-y0%Y@K)zb*#MJ0NexQf@mUhee!*34toG8vwf=jlwv{Oy>Hz2Aa4zc*zBhRun*4R2DozcBv%f1AcSR@~ythR0j{ zH~;^0{iffazyWD5RS$Ab!vCi9puPMnWzc$1q#*Z+^>F^bn=$^p8ulO=%eu9Te6)wsa z3<<2rG4o|=aC`U*0ndv|pn9e)3hQpX{T z{C-`L$mOcWfn&M7JDaqydFLJ7Lz2u02KUP4r*8WE4g*nty{@kA}SM#gx8~d2{+V3bVqyw+h>aU!}~rfDKsL|F! zUGx>?v+R_DLUa0CK~m~y#mJ9az)$pj7!EkU4CV4)hs|5r^@0jM^#FKq<>7(4Q#9-# z@jQ5MeBvYH^Ik|>9UNz$r);d4@7}wqc<-Lv8cX3F8I~e}#(Q9$Q)V&b9T}U7uYtT- zzm}f733=yfpS)_{2+7%u0`jKcN7<^v7kTRlsXP$-37GOA=zjjZ)88kK z#yh_yvF8!w{f1+llf3sv;XSD7W@Fdw3YI4bXZ^8&dv8rXvW}3qJ#Hu{D+wNN=@(#N zumKN@iwzI#yobIxF;*vT=gkxW0Ev^1T3ja^i@rF~&rq%us-eHTx0E`xG4i{fv_1Wf z0S>5mu)UPugw1<_-MOzjL=OP*vgzEl3N+0BsxK9sWd1NbZzeI?>R=%p)E2w`-~K=S z4*gV_!TH~vst4^ObX=nJphecpl+b#RcUa%hMLBpt`jam*w_y)zUuRERv0uxmOjTTK zi;n{+o;su0CJ+mL*Qt+M!1;e--)AfCToO>j@6;9Mg&#=Q)M7V^M8CwAUF;3PsN)-X4< zz!%L2zaPpCn6Z#b1TH)ggXuQA3 z<(NKzyyc#?6q9*Bf16ui1bM&oJQ1BKxEuWHyxMY0E*6-m+Z;atdH0pFvU6S}f#n>Y zVGn-efzBxjrhHFy-a$;ePx-?Yq!tpl<`e&Rf;2ks-%1I3EGG2Fn^MOlMt&-7uU~)M zivyol)_?oSf_;fqFF)?`_A(xPuj8(-TZzs4aHO5-LgfyI=e_ADZFN|&7+;e9d;Xs* z6>oR7;C~KCJ1|=(kH*__Nn6=#$XoWweT_Sick?r?w^oq%lBrtj#D#l+;&|l`>6Njd z+oQ=l9`arue)sXB3nY-2ba8I|6dvH$xZ(Z&<#>x&c3IJV@D0*XBu-!h_j4eF&YLwF z*EdXuUvDKKbM5{Tq|rns*&3{-tv{G@WT2kKqN zqfaYX_F9XA8%UhSi#3{G($RSrgf~Vdc+g+>rqq#*k>Bw*c7m+&I8d*z4xY+j^9H7s zYp?8#1a1wxPl~+5emRkeL+4(U!Dq%FkoMA6hk36~;%G$_`Qb!oD&8){praJt9yWVq z(RiC`vl+@m-iP}>7?bzj{PfN~tAxCVzeg)+Dma6Z^c6E(OkzQi-B#s3$os`FdqRIY z3CQgp-RoQw2GZD5nA zzSA`;0kGq9glF0R#@?HC^w*nQx~-^fg0gUzntZU|OxKIyySLefTAJ#xy%~GbfGPFA z{eKDodj1jiAaAN3@faV0N@VE>D*l;Sfo)z{WPInCx`yvu3iO-C9J%k6(h%tP^?&t%O!xx)Fg1_Jc z(n#EF5vO6W5PAH_wF#FTu^ktpNH@I8nrjmA3i19~(5eqzUqinq_^-uo2Z;#D7&(Rh1LibaXT z0V)0E%lBm70(l?C#2{}LP_A>ecL#hgox?+>iU1KQg~p~ns#6=JTyWq;7B?Y$2%FR?~k+3`5hR}9blH9u{2G;n>$(So1Yf!*7a ziuZmo;{Xb8?yl=g(RlOpy-{5Qd2eDPh1`U^dzcP<6o$Ol&dt@YQQrwF%+?g1dqDt~ z`9z|`A#dAdE2SS4kbogieuZEq9w_=8%(PsB&O1(kYs*S_dW#$qm%mo@$lp8_N4n-TsJmvu2c8VtXbv?c5b*VxcVp!-CL{nkML{{ z!}DfZPFo%3t51J)`ulmyeN?=?dE*l)yw5gAFG1sdzl8gz6Xdbcc#v3cw0Z*RX4 z=MRSG`bXQn8!@|g`t{-R`}yq*KmUhU(pHDSqcVf8v-6u19#p(NAAG$|;XU%!X)zk_ zDuP79QOJ9buy`7o_m}dcM$(XXe}GL;3X?q;w#>i(oGlixW<|5>LEdVDOtBStB*2oB zV(D-W56;vuzbs`#=Y8HT@JcHDdTR<2m(%)SQ}Ymd_wH(0mZ+pjf4nJmJj2K@ysee> z%w`-gUhphJau}O;#}mn&=aT(_9betWhL(Cv-c0tLfwRQd49}Zs7mamnZD=Kbd+WdF z|LJ+~M{SxCOyOf9`3z+rZcd6kV*C7isr+? z;KZk2+h5RwC0d(Fro%l5@@b*>)61R=mgYUCIUqK%IqokkuhyHk5BXxvg&#=Z~9p?!c=1g{LW6;TY3^e*;(G1 zLC9M(SS~oMganihNk_A94FfoVH(eR<^bxdX5uf>V5nxpfcviM}K zMTd892}m8282LGPgj`i|6abBSY5Epr*u1-fKN$>|xqw!MCbz7s*u0g(4{Y`oA7yyn zN*1)$Q8KnvK;Gy3 z<7BswSb^4&`%8c?0q{k<5*~%TMSXmn-W8KT)$dyc2^L|1-(`*Vhjw({+=n+Ajw}=f zi;%eXJ1O~>wxRRZb{biDhL`>ZBrc?m6&U%s>{uaNcM%8r(|rrgu4D5SKcn5W-`oW} zeBBdwxw09xO;FlLl4sbI>1eF{F+J zjQseRvfKRzaUhpPAU?JRoA*YASKq~2T|v#)?D%8m*t~PuD!Wq(EE&FgDMRV)m({McSW*#Y-RYvbY zUCO7`RNX~@2NL&W;oPRg3iSEEpj|jt+nfFdBuX7Q82Q}`UGLMOCIFV#sD7)B#_mC1 z*5p{fblnGvKRsZ+?t+nDXWZH^t3gVh>UA4$&L^=l%Zz z_6}_{-d}4TMn8hQ8x*_QMUn^ zABK+pbRqy9?~Z~9$XjyyfIb)G&9blLe7`c>AT{gHHGGWDJ6Gw#2Q6C>pn}BNT$))~ zc@&+u!bB01vlIRC&Oz#s!N^aG^fjfe0tfbQ-cK-;GJF!e?XcGw*gIcjNM=pwEg>di$4|bz*p+Rg(_2V&hc(f7zaO?-vIq`H z=e>i1u0h^0r#SU^A@99|MQvb0CJputiNevlZi15O$Ky==#y5IfD^Q1rC0!STN82S0D?hyYy$`4r9 zdZ~yfWAiQ?ebAMt7zBjAo1RE`Peb=+KIhlA&V%83N6w_vRL9b}s9Ax(UvKfF;(hr1 zv45VujeNOwB^vL-MNpZ||CH}`&+ zqd(r0NFAXV`PJ`RFi;qU0~YxUB+62;dDlEpyd)MD3^+FGUNPgu=52QNrO;O=#y{R- z?`7KRu*LhC_n9i@fLa0MAG zv0+g;>_OZg&2Wye2PMBvJ(Fi>2UG>*dTkO3;1Y9no+Io*F8l(Izrgvww7qG0Ay*hM zxSr-9Qi4AJKi!pS@`p_ntVH7Kaz@6^EJp7^LK@9Fd+D$TJwxi?$H>n!>FM3}Q~}Tw z6`jTDh~0y(rC$3suDc#wslU2x;m?Pt_i`zJ-uSNTzx^%-G5mm(mq%M2hL+W1jWP2( zNFh|bkE~FrpsXPMzcA9HO8diQ_N*eegXFop-fm z?V$u_`n$#c38~{IMt(JpAEI>Halq%|n3uCNHt#;EB$-P(>p_xUEVEPr_9d2yFG^@k zH-h1LGhIDSQysTmMogdl-Tx1!;vN3W#h$`DXEHk95CMF=`|*?u8z<6uNa@qR@Q&MfpZD!T`r|!`)DeS`-!q=4Lrro5AT`7N%W5xd-c$Fl zor(En3}z}_omKK0F}pX*^yl8%y)PM_cThBKb>tn=tBFjWzk3@*#XIbwr5Aw|?_fzzm6MQn zn#lXnoEbbgxXI`j^J#S6QO+XYrQreT-bh^Ail%Gsa_HS#?uD%HX&(CHeFCXN3L`(q z#-wHL0Rq4*ZN!fC05!*3{q8aQzCX9{;CJmYO@)6soG2crY4`Y$2$)3T%1-{W+4mIv_7?lgAAjb8 z=x_d~)WM38-@RVb!7rb1fa~(>vXF3W-jT=Oj`8m|17f@hUp4BRF}pX@_Em@Cy#g4% zdq?7Ft0T~=_+$b+oan#j|0&ZK9sdaD|07gA=;Zd2E94$Tp8qe%S+k+_Ah!2|zwD*U zjdFX}Sd_vZgx_S&Uf>NkNRQo}0LgYBC8Fw*#7hF$SeyNGFYG~8A?eHZ!5%cTLjRWE zV?3zPd%M>x1^p7+t6CYMZz=)`khtW0m1+G>^d7|1=~X_mj{bTOr49~^{3?ca95|+n z18WZ0Da7ew_aO7x-*FXoyu{0sZ_8a4wqW<5$fx%VGLAER4`Q;Ut&UUOk4+Q*zCjv6 z#ruTRcszyozUMLv(Rk}-wp)io-VXeGd&#`BF0b*s19?aD{Yr{1w*!s+Rotte5WsJ# zqYLdJ?|8PUgRdcPUfBn8r}FWDOZ9w5zAHNKH(`bG-sU2J8Hpq0UgJt6qVpE~6qC}h ziT-#~>fpu5Z#HXzXCRLN_+NZt`=P*&Nzqot4}F6)tvUOO z6nwnJ0*PD3^<;aNF*@(O>Hyq` z?exF!?sWH#5%qwJ6C_S{W5>Yg26WynvK_L?`-xt^&0YSWmY^^26;!R66}@9dvCez`pS3hz@?#GV$J6WAffJ8{x-<_GrPpH zCdeDl>8AfwHw-AhB{DtgLSLM)sGeARjYky7AaP4Sx=(xm%jYdBt7C;~>G16>N*z}) z@-sQ-s<>8Qys}R z6+fMB{x|>A@znpnQakBDV5RCoaT{Nsr1T*9?oB*sJ?NvVuW+?gxe*JozoZ!UpmhC9 zoaFgG{Qk-0VQD+yyf#ikku?@PS}1CE9QGi~D7~dB6(kUJF{QQcX(%XCRlj^T8GQw5 zRrJ(aQc(nCBXKQuF}rU6%O!Tl=INk(EkBU28_X&D#bflp z{(%1HpY3|Qdt>oOY9kb1$mRkIvU+SKFB{!-a#U;Q1Olx z8Jyq$Cl5&C{LTd;qOTxltTdOa z%hDh3ex#0H82P=abVzsNzyZ5Ob^ROXuz4>hxs1DT?IvE`{Jz-sDGf*LJUr?n@9)O& zyqRv%SjR%#@)h$dNCGnz?^6?b0+jB(zDl%_etQwxoTXS<& zg77*!z;!%#V(dEs$V(@!^o6{MdhQou;q(8Oghsn89D0K<8a4&{|feCISv3 zakagn>b~LVywy1;_AgSVKi*f6I#e+7JAH2JI|mX!aCkd;uSgJk1?kzg^wPeg^_J;)liTV^fn_CPH2lZ`8PENFjnKqU$Gpz_j^P3G_wyPaMg)?Ai& zP$MbAu|*F39^|2yzpS1t6aiI8+_4Df1D#RmJ*df2XC`!3iAYz!w=fxBq>cv|`SIh= zEq8UrfrxF>uD@Pl4@ho{T`k%sG>F~jOUGSr(6EA355L_PgeZHOermy zUqP}{@lNKE3#VLSPipYt(0F@Pl##R{Z?ojDfrXIwiU1BzPRM(~_a{3Xi*|uuNAwb& zbH##XQH!(UA@48CpPdMXylr?QyYrUdfx?~*kzwQLm)MC{QOhM+MSvs{m%U|;kC!hx zZ_n1XoPpEy$9oj1!v!NhP#DOqaTy1^CO>}Q`H0P1LnyGl$;W|M+0*>d%>F368?sWqg1SjdvEG(|%jXyXxUMYZ2r<>&kiX zJ6u7Ym6-i5ue}SLWzS1ig}k$(ZjX`g-riC*&=G;Rw=9_1c)s%DLHJXr-wj>pytgf# z7Q4tI0s@h^>Tf&kW}VS_$BnYz%A!Nwn~^%AG4dlg;2L-Sz=3OfHr&q{#^$|J-D~w5 z2M1zoojP7R7kfZr5{L=wE`H1KylJkZZ~W@t<1Gjasdy(8-zuW;&iYWwi^jWD)LkzG z^2VL7Jx%6q5|!224tY26I^`1J(_34&)iv+qj0J~e5A6ztyrrL&zP=85h#w0koWVR)=n8-JFrdGab+M!ED#?v z?m7Z_OCCISeK+Lov7tD0dLbS>{n(&y{|KFTo9x=zj|w8-5fW!oV0D(s1)X?|vr_qg`~UPdi~f)K!1;d>RS!znTM$I)L9a_ziJ|qN>(=E}0g~lLK1Ifc zd9Vk)^=tX92nVFtWC_EkDo&u$bei{FKLHf{XjvEtdrXTi$am-;=6&R>DRKL5d!$|XTbk3 z8@IQvmyKY>JlTCD^Tj&X&l(_yY`OcZEW63UEd;_)O5kRnA<$AG#s(>RAnfsj;)#Dc`I$B zt&XHIwU=kl%+LSaRJ_kVUkQKp_w6mSE1kk0Lqyz&4okWf3hSV;Nc3Ahx-^`N-Z92kYBaB?qA;j?}*sZ6rCml zjF7m?PG(+h|H6Cosv>>9X!_$#Lh4wDk>Ba?{PleOI52J;H)4Mun|BTij^&1#F0imE z;PAfHfVuzA^lg@VM7xRMc{6>du@24jJjK6{w{TJMK69aFn!;Nk=z9t@uT^>PqyPI&PhT73%g&U(5_@h-f33pN)grpJZ> z=3=Af^IJVo|5)BD+SeV;6#+9vf8)*$^sqPDp}+s{f4FE9Ukd&49zg2w#>lTIAUN@T z2@X8?%AVohhRxe{_v?CAduw2v@5Pd>i+#K$)7Delh423#@PRZX+Un5u)A5jpFG$0+ zHzyVE)84uw6y7N*;mV|6>l-TBYWLzBsW~sBqBd5&=^of8+LV*UfudioQ58-5=Sa z!c2d>&5=5cF!B?TV|$RdTmW2M=NmHg9Gkbcn|Hdz84co2J0H${H?eu&x)5M>HJR}r zPL$tITOE3=F)hZiXaC#({~rf#I{SyP2MJL1pbIMB^C>+@ounay)`QqwkBM|ilpCE| zVN`q(_MrER9(|dD_aIOFxmnd;<_wgagF5*#382?VYZbW%tqjnXbca3Yz?qHpAAf}c z&Z!F=8tv%!ApP%Z?F#=T3>G4BUDLBSQrDsPpkKF(?yvkze;cH}NFCoX^26WM@)A)L z0IjJnjE91;d(h}ixa;8rFOb5{{$p02h85&P!@{e3#u@(}WHya;C>zRY{ar!gsCZ{h zpPQiYHgKGlLgTHYA-U=YaC zsgQSu>{O~0B}w`i-w^kVwfeHHU7NPa5bnGNCM6yEnen8`l%v z+icyr&*vxh0>?l1lbkCEp!Hkr#$@seQrVoz8}iO^`r|9M2M-K!?pK)Bp!1H^D&43J zd9Oy|O!Ie3%O64K{rGKeT=Ovf@ji*v@dzWoMIEM-U$g}P@6to2FA}kNb6aj=ZhGNP z{Jk|WpvM`T_larGo$0EK|9Ok*WZLRb{wkYQHh=yffscxJ#<_5I3h%NfnG$HcaVr;R zXhYua?`t)4A@7o!KMTkYCz|kQJd2Ci3$&*;hMU|afE`BGVUdux<&ZYFE4;nMK7daS z+=T~Kp&9zj+UUGxBlg}q^+Om`B5_xyI^+&Spz}U3$G;9gLVvs^kvhCF@=I8F?%2bV z0-&>A^w^4X*t`wWXRnJqcPIKSa^m7|reSlUpd9z`_eaL>-a<6iaXOSGbN=fs1YRoM z=Uk8Or|>T5bQ4G8T~8v;SV7)gUy`fHy!HFudP+jxj*nJ4)(Gzbf=Qh{{2c^v?fWHh z^2>>eWz}2%K;EL__A1;$VZiBpzM^6`I`6)X_UaaJ@67>;lVp*OsO3Yyz16pEwL|U^ z`kVi|kUF|C^7|R}dgqj&09dN@J6f;=n|ITBHnUI1Y>Dr*mc%zN#h(9*9xwX3LBp2e zc@Iw0R!5`YpQP`E|K|UH7N_+56FC2iQuUyG(Gv?PJ?J~9tP)xe^8Gp;yBZEiOl_wH zF2EkNOXR?fn_gN*uNrF4U8r{f?S<=KG9M;@qKKoar(q9riRk`8UP0>C@a;=93{`A*_bdWko82QOb45-(~2>?*% z6D4DY-Gc%I7uMx}T}RZ=`ldhZjeY)~LGhMhA;Y~4--GyBX{$rD^Rwu~2=e*=1Q9CU zxx>%rKe0=Gy+w`tn*ti|50_@Mc0u0PBk!e>dD|S?casC&-ntoO@MKG@3y8=K(RU0d z01d;3#5l;CGf%;s1bKV3a$Rc^2?Le2b+yt%=$F{t5AQ8Hd`bjdLE`KMW%etxpz~e} z)_oN_Onc2>6P`#bH~IzD=LeHv;@8bs&aEW4gx6OngmtHVfYijDa9 z;Y2|y-r0N3&VPHGyg0cL;wFp6yF_7S&n?J%eZw+E^4=STcj(>Ut?7_=p;2Y+7sy+X z@Vzez@-7VdlVJ>bi=7Uft{`8nri4esc}f%P#f`-=Rqd8df&f1rH93rrHKeepDWy@j8Dlddk; zdxqz2HEK#z9rtIS$G(8aTm1L_KRplrNN(^FD@E0VE(wDG3#{9u)bBSdcAV zZsdjcJdp`|(87@M=T@FtM$gil*GfKe0dfhR4w2gk0O!A}_W|rdG6JldQ%gypP+)}? z2TLemlRCbCrr#BHVZXsN;KYLG!hjixJFjiu@wEv3egSUZ-P4~M=&uK@L+ZfFujHPn z&M9LY=5X!^T@BuT})_-C0PWd&LAWK0>2cQK32>^;c)Vo^4G7UW$k$%{J*d7panEV!u0 z1)Sk<(p+v$057gtJ*dt-7;UWF;&P3|K%5SJ6K65l42eyyl{FE19Ut$Lq?c3AFwt>jQTgBG< zo|g0fhR+8LZD4rbOd&MZ@hN8$a{iwL74M=eo0KTLd6Ta%MdNL4yk*@h$os?lW3go3 ztQ%gfxdwUXThHwq{OkhcJ2xn1*b#t>*o%P@$UADIA>fB!kY>3eF%V)G3Z%SK{NL%K zKfQHxg2lhLUl@oXaYDxInJq8Td23m91N<}k<6VW+ft6p#TDR;oJK+P;uC*iyS!~|? z`GG!#qSnOfZ2|h{4Y2qBnMgWwxrWaepLYjsb+`?(1dSHY-`*0Z;$0XO*FfQIx02X^B2;?m<_qfKK)fMcjAJ%8yLjXth$D7VV-akM4-nD>t zZ*$cS=&gsmZDQ2x6SdKK-@W%z&ft?UutehS>2a?<_zIo(wj9v_LLdF{u14zEijkkY z4nF(0x&YW^7+i5|DK_t{!b`8c11-S9OP)9G#x`LtPR<=!pfl%h#PIL`H=U%dj;YjD zgVulF{}-d;U0{BTmBL%R*K#o$Zxt3zYD`G*ng-v7=2l+qI0kZY0q%xvB4gc_#AA+nY(}`UswNOHz$B?s}#)oU=K>U9_BbuLIUNH zx6he=4goPY6VIQKN`IGFN*&D@`Hk3L zQvUUvAFThwF>xagd;VA6)m5O;X98+UMunO`VE3RJ)|+~Lv1=H91^MuL6-{;6jw>p# zCd{uO<*0a%)8d)w=J3X_fKvys`Vit`}Iu8jskSvm%Do1GYW-4IufT5e)#LoP;}mW zR=vinGwF{vr49j%{CJr>CEO%%;9kC&;mga|ydCcZvK($R0mP=t@{W@(S* zyel$a?9Ilz05V^GeU<)rMdOha+&vZXRCV1>V!}Dg!4yUaS_rl?&f4jFd z74K4`^xKr~J*jEB9F6zS(&?Q?A@8+1uFT}Ux7QzkR;xhX`i)Hm@2g$F%1id^{2=eN z%&BXSA@9`9FNGdK-aG>9J^<}dph}!LStf*jd+WmW(i3`5g~1XeuC1A4+NlSiw5AkR3NhR6FbUU9N}(3=Geh zx|hK3|5;D5+2o-2pp<9Ed=K{ugFGbe9&c>^?GNZZ=!xx%xF|dN>p`cHI-Xn5GJpNO4FENj+N`K`?>?cT>eE2GFI|9bP#Qx%?sgAU?rIQ7J zkJwpE#rt~8t}eo#5pOkT>5PJ9`@BU0tir6#;n<->?7l>$nTpfAuZ5}LE7{h^*@R;A_S5*;=bYt09Qq!7e1Q)3D|Y5G zL8jh8cNm^`QCA>MbvQ3iZIO?ke?VG^ig#sN=1L0hThFt#(0HE_;?yjIyxT>}2xQ&` zVJm-mL*AucR#zMjxPS?zHnor22|&5@&C9Ql_nza|v*U|N;GFxEj{MqC;52gLyp$R` z?=Rw|mP(<*z#fS!ar7qETtnwwbMsI`)j|5>J&M%v03*LX@3%iv5AlPKLw^!>AH(K7 zNqA)&kmNwTST|x7IfcD~jC}Osda+S0!}Dh9q^*wlb+3w)%I4>PMJnFcywAR-@XlxV z)kNc6l(}_HE95c*1}c`sMJ|9T7LEpd3dN5$3!WU6_(Jb@13e1N?1JA&j_ z!n?P=t;aQ5mxlu4r|z2LqUgN)6IRKY#R`LJB(9>MV9S!r=)9k~eR;wkNq@WtkUCyq zmSPQxCQmT@q|AKrshDmz`f$;K7b?fN(xcYpv`9BzD3gY&vH1fL-c2mM6WJXm0BhYQjj>6!-Ti}KIqRN9a=4Sr$v$edXP9$M<7Oi zx9u#{zBLE|oAI?t8LHSlsO#q0p&~^OqA$*WQHB8tvj;Uje9w*Ny~OY9 z!wb#)huP#eNL8qK-?>*fMY+VL@-(eR<1MH!>o);;ioG5Zyg8oSNfao6-~Y>b;MNoz3j8fqhq43FFR?lWG1t8o3j<#y zF6r`-SGM=jSCHebdh!}_^v7Elsbdl&ztM7wfn@l2%hMa{5`zCXcqcoq+&>_WJ^vrp z&tvf)&trJrdPj0;s$;{^x{kWPPmnI7;(a^O_Y#Ho3`eRy8t>t(GI0U8f{cyk|3l_& z_eUdh5c1yhV1kdp9H#`o-9Wg~sT- zV?Oc4G;0fk?MPh6=G$&E#pt|48aekqSV4chPa$>SG4dM>nq_TX#1GC#n7YcW!tUOS z4;hB3$$1d)5Ig<`_6KP=gp+rLQ@^dsUF`)3g!nSWh&mc-1$5xybGS} zTZP7(^e&`T1M;>gx*B;F@)jY6eNZFM|NS;zYJ9g*xP+^FCRV9w`XukGDHgM+`=O zIG6fGWp@04(`V_rt(&oVdkiK<9&B|X4tk~wxqicbyhYzb>d_iE9K+B58^UO-V|mc% zsvXDXc`v2neN%_nM&W&7gPtB5?@6x(mn|UggO)N2$a`;JHpXu!ka@SawMP}W0QJP1 z&5=6@;Bo%qErO8uL~F%HJIGsLt@Vo;5DI?SD*1P7q4VDKeO&wGE@3c%#N{OAi1Pl+ z?JaEs$)`D%^v8QMQim=^eioZ~3p|VYft{8??j=iX-it1t{3g)iLaf*(d8RM30dwum zU=l?`b+Uoea%t!-1-tyo6Kb_D1f^Y z{Id3jXTR*gfsy>V0+Tu}BP=;nQ!cqZDuKj9))yXD9Ks%u&R*IPxbAjxHP(NZ-v2$J z-I}I4o-|wS`4c_AL8?y0n^^6VNxsCAc{l!Cybz6dN~6?Hd&pb7o@t!S+qzG{{sQEE zQ#o3_G|m+Sze^TgaGC(d>mRotfxP*Z-DkIClR!nZ!m(*BJn&=Rlv%d{o%da#1%f<6 z!oUZKd&YnFU8pcR?{cptW?T5_k2evi;|fN8%f4L1_i^HYyu?P1`#0pXond(1Og^;L!R^4@XIeSGf?Pqx`+mIH0SfPt(lJ&v-nE=6 zB_WV^>6e26DUf$ccFo!Z$eSrwpu+KlE7-c}a;G_g0HU{UXx|5Uvoa@re|V7uRuGbU zHnG6tEqB-0$4R0OJnF^fYc7chgDXf}sZ8bB!~gPm3!{plsw@He|qwLa|ATbVqw!~IO>7@s%S1)Az8*&f&0l`_v; zjf(d@hn{o_?>FuZENHyP{EW@hA@2c=&68x_t9sks`$68OhLHzs!d-!Dde0J;qXba7 zUgGpl$Xl{axx6O_ZjgqZ*uVNW9*Ei9@_E9C&ig>X@o^VPVIYjenF?yEdlAsPH(z$h zwh0mX;~jw1fy2np%XZ3HOI83FdM{`VWW^qk+CL5n`1$!0J(zp$ElF(`6bKraMn8EfE%}@v5f#WZ=*_% zzEubOiQA3#^7p=L#pKN-uJY-$s2tLhpGoP zy^}RCR&N9(_QP54Uyjo)iKnk+`MG>s7KBqW2*G zZzBsDCKQSE_Is{?)DeJ@U!l#OnZ;B5zD#gzO_)8X zO?yq`+Q`3;`sR$q&5}r#%tF7ZfsnwAO%(is)VIAQp>H8?HSRO19qA;X9#DI3qcFV0)^oWP ztD*Bg8xmKO^g{^D)cuV!NxNASJdS=zjtmj5iug`{yi<`nj$`DfF)`eE-w+43ti7g? z=ZekStXjdyy?88+Ozh;t?A|uQtE0w40seyA9w&Bm-i?(D4ygVS0)a@J)2;0}67SG?3%cf>@SmYS-Vc#F zgfa5FRd8~f$t*u`%emDV9g5BS>-)Q@w|f1F%A5NPZv1J)?B3%p8>^%4ir=NTtK0u> zK5q5vXsW~JiQjPHnfdOmNyWQvyIx!2zj4(lam#@|GW!7&{Gl zrwAXY$SZaQdbiJcJSimr`7O`X?nB-sw=Y<%%!Dr|GW%x*kA{NyM~bV5nb3K^Iksl( zBD*j+g~VBMxF{>VN9U~zcte#J(%=059;rhgBfr)&x~ZI|IACqOsXr$goAMNYBRS;$T#ff}AO?4D3Sfh0lKE3td z{{R2(_3{6QcsT#Brs_d$-H~~e9yBt(RsgLB=}aBzSYw2$VS%cJpm7lFhLdKG8exMz-rb+xWrxBKfUH2Y0 zE1ioV9xJqILA-SuORiQc(-1g-9+K7=^%hZ z<9%|`KC4xb_qw%9mc&EeZwzd|uZ6r9yR^(TwYq_H_je-JaQ+{WvHa-_c{}Dkcyl$0 z1UlqaXASp;0vD@4xBg6_KVoOq80`iozxi(O zxDP*XSyi>u2=bPxya=S<8(7ShdimH>sGa=A`#H}#9p?O9G zeFga;VJaE4(;x3Jqzd=s1W6M+xU%yh=gm zeX-M5-DyAwgd%aFXO6LSiJ|lE8Vpa_|C;`IQ|iFV@AbBOVY5N->n#$dFGuvTc}qpy zy5xJ_k61exdc#^9dqC3rwN=(|Y9+(Z|6j*xtK*qSo$}ga^A9KLQt^JsAL>u(-f46A zMQFT%AiH50(Of?d}*A@6OgZit(w zl7N);I;)@%JeV*y88ZHt?%i{1JeD2qy^SJq8MaJOZxzsa8!Sl^sG-BXx0gsASo!s? zaebM0haV6HE;;&|VDk>k+GOdQ=SQr@=?PXYXvVyI%e14pe;`1U;k$PvzLBOnx&|Vj zy{-Ch{>Pf(=;GhQ`5#dApyv-~Z%}&B>kZmsXgw&URG>XcxZEiB>|SRA>_PS7Z{63! z9(2DxTT?;E1H9kwj{llW04=47t>0k}(#(r$+7nFzBZA9h^^W5~cl75>mMrv3?Au4$ zmnDA+fes{&uj|5#?tke)*281R+NS9568jFRV+Tflc9o;mS5EMQ$=IoP?@nP4NOP$_ zF7b5x5v{mimpmQAp8t7Af4%cBVf-G{sZ3iPrh)uwi~fH9Z!Hz?XSu!Q6yD*ne4=Q) zvp0FXy$pGOXsPHT^X^*aXhP<#mb2GTqT3x5j=YOj%_0D|CBIAFK;B_Of$h05Bw%T} zL$cT(50>;TS34Ag&RgoHt=?L=gQS4ODT;ZPam%7#V)M%f$1ZTv-z|1&q>ciN{6a3P z?i+c`4{oY@9lm=On>VwMW%h|4KO&Dm=-+UfhWY=RiI2F29>ZT^nIbmQR>y~L+mREb z4XJoP^{|bi@V?*rOc;&#Z=QQ4&5-xS-Y)Z4$h$R5=ZOL2%~N@Q_YpYwXgn%?w5pf@ zwBApAXob8_diX4!Jw*auUb&wnCBwk!Ua4XWUG%%LHAlC4aYze;1SD?Vjd1+QW9Ymu zUK04&DNTR8?;&;MVC3hU{xQrYjUUV%sm&F+fz8`S*h1BG{QWR?&b?`zBK&cB1a9YR{`$h>URFhBmv+H;0VnO`>B8fAL8fmIS=(5>&j@bG6-++oYiFKV2g?CTS zK|wU$Z_HCtnBe@MH~P(hy!S@oE$%XH#lOZKh%dOiu?+IIS6*bA4SBzi-Ep`#js)VB zA60n6mlK13^YW+eLSLK^4?U{RyCnqtk+`z2yYDG~ME~nR7`FLfQbT`hZ%Q3l`LXY? zZ#n454;)hBo9}jF^L}!iCAjmaA2CGd)e-x?Cd~Oi(x3g|=TprL&pT3iAx(9Zzqs^Z zA$&RUzy1IJ7ro^FtN$yU|2I(epl)I_52Xj?e_keo)`OJx=k8>Om)L`@lX5Yz2aT(p zFu%7?%gE%Jk+=}|KF})jKK{2p0VoU*{6YlBh!r(gOSc>$fxT5XmL53;AF(Ss!Rk_t zzCj8yP7Rt$2mt~Tcjeu?>MQpD7kg(OPG#5j{~gyhPaBy^QKp1aLM2OuXh5itka>>G zLs3#TMM;t-5g9V8DA`F=)GjF@iKryalp*z7yY|()kN5apUHi|y-{XG%(f7X3<2lZ+ zKKHrSxz@VY!mdGKQBfXN^I5M3p*|vU^1JKSqc!`1FcAB!(l<{DzXmXMM9vg3;ivAS`wOJ2uGTnziPJa6eeI7)s zih!CuB7@0V_;}CSlpQj+E0Pl1Gtznb7!&>fr-|XrP;<7&n=r_v4}-9sT7UNcS25t- zZtu1N#ar;j?HO2jJM^u)u>#_4-?@e>0pbl(O74zAysxAb1MU`gz}a84I%x|T@D}yE zE`xY)y&je^Z!Z<7TOE2*^ECpD%c-39QNo@<7VS2beXb)8M(J^jQ%sSaXa9ls@hGaL zG3()7NcZ87lb>PHoCKMt!eH9$p@W^9@$oLPdCe875>6SjPTKjalZpO+VNozCyo3Gm zR$-GA=?Tgia;6Fn|#6mO@1b23Tuz|F6oQ z-hKt%(|70o+iU}GGVuAFqbLROR`DJlHQh%A&rMWr-+C7T)a9qERL;Q0+g%Bf99}C9 zROxXNKdwBvm4%J>My`){-)vz$yip(4IQiB1=6zDSDgxY1Fyv301_x}SZ%=vis2!NG;UT-mAz`JcSe*neX%gS9E3-3isu09Qd zc;}S`zN6t?-F?@Qb~tfm(*w#4xNLPsE4y)S0vWt2oe{ph2|}kJ+R0Fv(J^dtn1hRp7rql>jNi0M>C1#Z}dfg zwTUlq2*by_s{NI(NTeTSpSkT4!OkYk-wWEp#S-Lo+HLN#fB&x_$CQr>K1I&UCI9vR z=-)p}|AhU&DMJnFse0{%)*v4_c?GN*BxyHc94%gKuxq#H(|xc8jV5g%&Vw_^ukjUU z-QiBpr`BHYa|ANT%~rV~DE^V6$7v<~IhYC(qLstz2O`1fqU4}9N$eq0D`wU82?ufT zg&ybfIX^~29=ithJ(L+R4`96-w1ndWiQ=^%}2_9v4lM>(FVB@{w*wT%u0q}Z@pg(a(pO}92{|DYn zWV~Dt#IPRT`g9+9@t0py5!4iXUWm2F3S(jeYD#AU{kqT%JlQB9{x zDG|Ui?``?HQS8kLoxt8FPlUyRJw5K>t0*0(VC=cNLrcx|DS6hz8}+drC%?I2n*(>4 z3j;-+hfy)2_;}YWw)0au8Ab_Mv3uI-HvH-x>y?&nWZTL1coWVu=VNcfORZ_}>n%Rm z#Po9BAP9dE9uRI9z9W29_@eL`;lsjvg@c9Ng>8h_3hN1L2+IkJ3L`?_ga(DWgzgE| z36%+D3#AF|7YY~h7P1#I6IvvsAS5BgBRC;AEZ8IXQ1GT;m0+G=hG3##w4lGBlc1%b zp`f;)ilB_3fWS|IPXaFm9t$)HR0|XeoDxXptKd7&m(G{K7s=<#=fG#dw~9}TPl->8 zkB|2U?+4yq-bcK*crWwj^JelM)-^^dj zU&5copUS_FKa}5--;RGhzdrv${yF^O{9Jrvd_#QQd{n+0LI#`_oaZ^yITJV|Iej@D zI4w9=acXfYaY}LWas1%;z|qU`h~pN=WsZD~Opb#byEy_loH?vHj5%~UR5@mH2>nkd zJFVh>{`}vcSpPR5$jQYadDlrEA}XS4-GW+4q5`Vc@&w-{&PA0;+lzeS98|5zl~yClqsllm z^(|2jRYoh6e-US+%8)x(oj40stDc*g5@k`f^8C^i;!IQ-1e#EZGf)NAdHE4#P^B;K zl1!9FmEOxbNum_0mN&<$5hYQzY;RU5Q36#^SBT+dM?a-&MwcgArd7pj!>+TIX}s8SSq zvw?`9YHo+M29Xn0bBe~^5IImKzejBaaT==RjNA2z1XRtIsB=Spp-T2ObuID}RWo~^ zUqq%*HDgcmY~%;3WUP3Tkx5iZ%TrGx6R48>xbGA)jw%VtsWD^>RnrqTOCjG;CBAKW z8S)KPV)IW|A)}}wP3)3KMo=a4xbiFV6;;A#<8zQNs1ov)sYX7dN^p@}9P$ZO0>n!d z$VXK1brts^A5g`6!F4+F9#uTvd&H1oRB^B3uSMRWic4gMBQk_4WVp!!d5bE}!rU5U z5LFyubN3@}P&Lg|9zkBCiXb8Q8hJ%mia%e(E=2}VHC6p~BhrtmAA8EKA}>)jX+3U+ z^r31(?$~;y7ggiaWUe7EQ1!hwJ6#H8hMDSSG`C-@&Hu>)#C_4MOFV^LpS6;s$QB%UO?`l zs!z9z4{1Twi$V2Hq#0GT^>*Ygs%XoT$Q@MCR&$WssG>E$NE51Py#msRD%z<%!_j~#7AmTMLV~Q zTtgM@1|j4ss%RIkAT_9>-A{p3ql)%9KXL_Cw6C9$%c!E=LyTNP746zqqzYBETP~4G zRM9R4L@H24yF(2rM-}ZgBcu#fw8vkNQdH62%0Nm`MSEHRDMl6TCU)c^T`5I&YaJ%8 zM^!}Ctv=#9RE6(498Fw{s<3rA(}QRP3{&`(^2D!*Hcz7bcV$~S!=j%a`?9|yh~B0!b*;?{Jc zKB_z?U+*TaK$XXxmL{Ses@!u%bcoAQ zbx`G$+qi(JjVj0Bvd_dNsB+LtT29nL)i!AvPU2!zZGC0Cg187(b`@8`iJGXgjamJR zxDZt~&OKqo1*qCG_ZBBn167-b7m$eRsItCM^NOfOSBh8R3)e^ys%Q@aBZa7R9oK<9%^|u{isq$i z5I3OzE*()^fE+|s+9ORaBneeVPuET&iKt5T)|NoXs5%1n9zYUMbyz?y8aaTfaSkyupiPc8k1 z#GoqPBEJ;bjjDY!zZ^t%p=$5&%W)(cReSC?97Li}6`OFr1BpacjP<7dNCc{OYs@J@ z!ci4H=4^+Ap(^UmMlU23RgvkxbdV5KMR;U3BEhH%*ZI(n1feSQ*TWUaPE>_FU%-U~ zqAK{*9w#IKRY8F~<;V_H?OdkUjQIa|{-5=GJlgwzW(;ePv{?-XZOM-_V$x5N#EV!18E^Gl{Zktz=0L;{VmIlH7f37o*o|pZp z;5%`ba1Rm*5>$;huCu^iV&6uHKEiof4D6@JCGE-8sP({JgFM%_``n7QITTj=jiWwt zaPr$f6?#@E7+#Pzd%-hffBYRJy)QQNWC=Sc?p2TWYc(-(f^_gp{|B-+`|luCG3R4s z%WT)RRloQDH!$E$o2H|92b12bVBuYp`pQlOF0t=>T_PMu+aUFu*YgA7t>&KFTnIcs znbwhC!VL*P#dgHd1>!BSWwfJw2Ng5~xUAUr7(S5x%OzBCCN|zeJ$WkcYQ%sgJ?_D+ z0~<^%vGFc5ql~JwvmV~4k4l{U7Vm8EG}j>k>O|CxOZ)Kgo@-iHI%F3}**hw>xNH<3 z?|u9SO?fs9uszU_~qq zZ?SI0wke3WO|6v>=Qa-@tlqlt7&QSH^d1$qfOw0YEbQqGpn}8Yv6=Bj5g@wvRc!u8 z>>VTxE98Y^gBXaU$Hm{vG&!&m8}CJ-ts>4ntcN%1V+l@vUU$qZw)ltuo<#Fez9aZ} z=l>EuknI>q*)6p)^h$OU=EgBPn#EFHmYLhXWqZ71Z!+iO!jm$SU4PF1uVcWQwvdA2 z-81`;5*FV3AJ5}6hImK0#eb&Zy<;dPYz*S9=ocBf!J#dzr4UvGINx`=m6EDhBS+UfHr}=buhW`?tcN%1 zV;fF>yK>2D4J9HVOul-Rehxm~t4hx}5(h&lhx#JhMB5udYtW81p@mpA z$b04<1%KH88;_rIjDxlrzJN?EY7GXC?s>R3Zs)EJ-#$9sp3%mJ`8>d7bTh|X{u-*_mpYB5l zC%+}GJb|U~25FP(9V&=8ehn&kva(U3#hc}Xe-?mNo_hQ(o%uoo3-8?O{i0-ucYV0wBO2aW6LO)h5bskh*S~M#bO$miE=@}* z3E+%~EJ%fTCr3&DYJhlG-KyNa4_>jGpdlu;sudgWrW%X2Q!!$H@$p{S)nggo?L{fupF6dS$ixHbqW07a zm-n%KgG4A}&WE^mW+m;49az0LGT=?yy+-jC=_ypl!dsEzwB|g-J1jE@y-Xt>9T%Q(A+M^_r@*~ye~g(Vp@icH_2sOy2_#>)x7GdL*z0K|K-$rtV*hNxoB?mz`63i=outDQT}VdH(rdZxW|r5JFa$AzEES^DfC zHs0roZ3ywLtcN%1BO52bm!G9cBE}?eFUczBh9f@SJ8s?FqW;sLqUn(6T@{2sIZ-P~ zO-?!C$o6q!@^K}+2C9e(RU1#y%N ztA?@&ARTKeJRpQ!gWmt_=Xpk%+t;AjGtBvD zkv85RfAaSbyM+O7+L2)tZ;S6ww6O3V{brfW35QsCrdPZ_mNO$E+cxpwPABES}< z4N`vhu<_KqJpO&9mR|@y;Oxxt8VoQw()Unr?!(@$n8T*B#H>!uI?Bgh1we ze2UZf;9dQ@dRsH#P5Vj-#k;?Ixh59gt!fu}tRUVZU2BGEc<0RM9Df8?Z(Him>=a6J z0~HT^WbZU4fCHBlre{ICKfHU^*9Yf4VCY<~Xr+XeVa}xnBX-o8{@#FXZ3TIP1&%wR7N^0xR z!z-FFe=q3NUB!teeWRA(Mf%54BBV z`bWy;v!j7mU8vx0+v7_vW|1JzyFT=29d->emhsE@iHQA;iyE@>M)a_2P+#=rSx=X+ zUJY7H_wfQJzoV*`(i|_6z|N_N`fYyrL#*+mw|P!-?iAJf=>9#G_)F{}A*%5Q3!>P5 z2B~euoR1wRi5c;GfA1jKGvH18@E9Fplfv#V!@_&wMv><(i1$H4i$gTTd(t|$aRlOR z7b|XXK*klkPaQt-JcJD9zVs0gg?P`krmU25rGn2_KT5ZVM}oDMEvcttvGKM^{V~YJ zEA}^TQTB|IXY$y14+=l>_@K*rcyFcqc!iUng7Lb1$rmDE(`7-`=i&Hx>qLy22rY4^ zaQ(0`u&rcb2AQk5sYo)O?eUI{V$MfE%B85?XMWEhw=&>O`;s2TTV=tqrC4~2)!DAg zfOww|L0V~eTh>r@1Ym=tC-Gpv?E+WOk?T~y*bzREo_~H!5aRvK@r{Td#C!J~lYw;; z5kPxXVRNlBHr^3i3k5TU#K01I+=Z#vpE#tk@#Z%U8Vp&%dU)@m`{2gOkD8srkuL{7 zZ$UiuWm9FI_CWb;p$bDk0u7F*b&~Al`kl%|!|jZx71(35zwZK;3BhoJ2!1XmwBy z{0SQ*AySh=tQ!@WtRAXyfzMlHWOQqd+x!D>ZA+uV>F{tOJ+5)p;}yCyu<;I(5R7(S z&4PH-eeA%=&&)RCm5dt+DDXW$qLz-2cYC+CtG`GHWljG`zu)O5+y;r@WV!kIarXbb zg&@VG5A(2Z$NyY!Y0H2&?XD9PZ<`7&9W1HU~{|&<| zxv*-G8PB%CSEOPCMAEpeVRSkIUGqJ1otGU4uk-XM!nN)~iA4 zbRQx(`8Dk24|)(r0uOt(&F_BCWq|(mVEue&-@5OWT{y+u%C6d85x@W6Et*rgyEL5b zYmmZ7Hd8)&7in@0|M@_AI|JUd>&sBQ4~owvV&OfK=jHbk;@xC5v^o;veXQlev4s%t z(ib+Tkc}?jO)-D1MLRs+vUFTU6XL!0lgQ)N?NktY^Xw#e83FFEA^)h_f<45h$rn7K z4vPXRJ#Kp3RFLRDHb@8Ceq!sbQ)lFhfI%bPQ=FXmLu|o=P`{t1 z;gp3_9K?^Wn($|kEm7We9eddx@7SBn`KaZ37kB#42hvUqc+>9VL-CF{{*e<4@68rT zJrZyRS@1lih=zAaTSTxO#CwU!mSLV47qCjML;F-C8Axg`QImmqPZRL;*$h{2!-dzF zJiZeF<_5;Py@DI5Sk-C%B8%0jUqpcdJuZZw%1!Raju-H(NsdxtJ-jvPKKOC+yZrdJ z_^~%4;E|pCm2GqI@ebx+?ryE%MA@qGsHBJ+AMYw#i9o&+gKUp?q!DvIj7N-add2_l z{~a0drd=?J;ytQ!ivtVqvw`W!3n1R-Bu&I=n-icfC^iY=opJ4EU&3V<0OD_qzbGez zlIlGfk`Qk_Ckavt#QWLC3(MsjBY>jF!VwQGY+SwPzJ5A6E((lf#GHL5@w6=@gCz+?rfXuMA2FyXS3}p6CX%F5bAE9>MS$#9M5k;#I|@NMKN)-<13d8}B1$=IJ0@ zVt?aE>s1~)*|=j?`+LE+$9^UD6A1yffDOho|ejXA5uaNBONgI5;`&a0=$U8ew z;vNQgyXxT2y$L(W)(gc5?2orIb3VA{Kc8NZ```XQ*6fI-{yFUbJ^rT#DbenXMr%;w z$Ql8x8pQF~_?kCtkOZrho`k^~w1_((?3deOgWU_Zx~N`v2D9=`_#1VR!R{r_;~!xS zBB^NWp4mhNikqjuh^dGKTf|$0GF7l^ioe;Fy~^vv{>J@S$jh%_j~#EJoct(@JAPgpA%XKE0Z6wZ~mqjif+A=vqW|yW^G3Qf2xl>k<(YQ zWcwO4Qp}u>c^wh1%}0OFAl(`8rd@)L;=M{?CO;P5VN1o7;~?I5iL3O&A>OSo$XBD_ zCw7-~j#rvKat7(z&OYaQ$zWNFuPqhgeZQbtm$C&uvCA2BQ~zuvFfKg#OjZ;d*LPpT zUR7I&{f#R!Ypy-K1v|d~WlgbIJnP~8iSDBhC%^jlMS3%qi-OgM52?&JgpYTg_2`TZ z)-e>4c<7|CEE6-x(`u!;zqYVF-h^BxeY{t56aO=VbYsAqcB?;%w`Au4FBaZg+y$&p zLcGZ&pKKc51&)@G)hBAD-weHo)5KDGZb~oJVsG{KS{}b*$TX>z^#r}A=GUub!Y&zc+-`~~S^?&gG z{Y(XlcaKyB4;J42TlZvFLcE7oF5;zaP9!xh^&NtEx9EO-rNrj~xFiy0BcI72{`ka_ z6o@xjdc&oftyB;{EatGlJmF&0f{p8(b&^@R9%4Y79!HunQ?lwdcKpJpHVFF`A|9t&Te7vo>+^U)y!96plIA;5L3%=(x`S&ZaJD~?_2VUW{~ukQcVy_DC~&36J&GyV zC^`=tZ&Qww$t&it9^QNDKGxvmch2#b5ZP1|D84i;j(miV_q>AW(rYVYD94SwW+>fh z!kv2)45iA8t-i27-bzgRST(WpBs|{o-~E4R_r=0LVgK*@KQ%~+_VN^3gIv4yM6qg6 zPDRwJ5s_j80nY615IDpRJv_E9ahA)qc~c zk3yXM@)LQZ)ICX{@A~7OP7(YXG;%Qh#!7udij8`P*w^z+tU*>E$uQ~hXa5;w6LUW9 zt$X`!>Dk{ytPca;w5QZiyi;$9kg)K+$D#6+9}cl4_Du$%5buC(wF@&K-jX-_)Me#e zK;HA+V`{s|K*s3hq&CDmVAI)M_8X~SY*Ie+<=RMabHBIT&@=2I);R0n+8dRkpn)ED zbnD)i$b0N~Vv>X@U=MQM zv_Yj17TybPX;>_Wc;6d5z(?Dh_}SOd`xD~r^TJ!m<$*KU7VU73TuKH{tpz0&A>K!} zC116Jc)!`Wa(abqB(Su2mu{1fjjQtI6Y_@|M1d7OE-*>wlT$Btym}T7$&bK#4U#I| zhXzi5Csk&@C2EQSud#3rr>*#Sf4y~B<5f!(#l?cK_L1A>_a_dnqe7s}w)ixwQh@uR-PQR0O zwh6cYk9AnC&_H>^{{4Rvb3Qir9=NEV_TThzF6up_eTQQ)Awqh4y-{7@BehD zgbh-~i095nDv{vYv5Jkdcd&;{qofY!1D>LP;|gT!-Zx#rjt?65JSSc%&vO00G2KTn zPJVV{H|&>;h=Ad1#XB#Ni3b1Qzbl4+=%oSHue@gjj+HBNmGa>)u@esJ5tgoTW&auE z=yIlfoK3yAs{YRb=>P`2X%Diac-y&fNMhk_Xz-XX9pb$}%GoR!;+?{+0JtIE-FnBa znn<_;Z9@;+H-cmkWc@97ImDZXEdRh6;;q;bE#p9l1gGzBPKY>(jcaK5^j~?QqJQK1 zO2{#_7qH{kJ`wVsyvBNXhtYkk!^ux_U3z4PJ_$IVn_SYJg^zd4m(%J+t%j7Mw$sl! z4Dg58k${ktw{j2I9&h&(!A$vRB}A*M9{#<&wSxg~0pg_!6z{!H+oxmUU0+{cTMY3Y z&bFzb;jPuz{_8B9L2fEfd>--A1##3}#yG_FM|_-qk*s8V>QEYuYwGFcbl{ zAF1iI-iwVZhYjB2Y-e0zcD8*zq%ZGqecLSr2d2 z$4s33YFc%i-`kM@VUA|>_ilW=2f7!y1_f-Td`$GKCL{Q(w}hpcDss2}58VH^k~tq= z1OtTY3x8K{KL)&cFSt%e@h6TWnk}eHJ+`TqX+U(c^yH z^GW~kkIRW3nzjfJequemtLQ#jaq<)AiP4>-EefU?if`XFg^%~d(e&XKHQ zg;j&XgEflOEeVVQ_MFD?oZ2D3nehoS{Lq>Go%3w-BZC=lLCe|Pc4;$W|OtWYE8btWO zq>r*WPiSY5Al@Mic#F+HU4`Nun>INU3vWBad0KNJ-a-@id}w%!X1i^g3-R9W{OpBc zu^X7Lm3WdekpR~0P2FY-@kYWFVj|3`;38+|(&hKz^OmhEY7d2A<64j{RogEs3exFu zL$Z4)!+zND4}LA(@WzYv@GhkLz{@Y+HKH$SGYQmPS-bn%Jbb)GxipoCQSOwZ9b+rj zJ;&cc(vwt|;sJeZk2hJ7IUk6G-)H2{^%lVlc#|e}$)k854!Ju63-9}%bw-y$yiY$+ zY@y-pKIhs41mfNMVsZUhOE*xPeY^1Kw*(O6-DyYRuG*J*gNfH$Vh@x$t?GEi_IMK#nDZfkob-)9_q#y~V!&JEaphMO zZzY$LGFW(@)NDFy0r7sJpsGsSoCrv$4{L|3x68-opCJsof|4BT2Wh4rE>2VW%0iIDF*ztDj+$An0vmV~4 z4_lo4E-lcZw)BbsyD0DMW#;&Ji>cVonI&&YIdH(LoX@WjbJB*+iIa=g%xEI5X8ZmB zx{J*Dc!I2XsgwL0@0|>I3!jb8LGiwku|paQZwjaRRu71`C7}sz3^n35^-jB2^5btv{=KRQQhyZJw&&_H4M>RfH*i%)%RTP-g z*1YF_kovR>#;`Uk|sQR+dee>%n2Xwvdgk_zmhB|3S5a? zR;^6D-V)wn;&i8t{rCSzpEBp;a$f`O^_Ktof3(1{@K4wvMKRPM87tmov<7MPC@Nsp zAk#-HH=YqLHnDvnu@Sw-(UAt-_X^I`M5uNm8-6GbjLHFrC zG;#9#&J)}paEk<BY}akWlDBM_;~lHf2?Tbh@@<^x!So&mx<3? zG}aGO@3Q~>e*`9d>^wGS((=y^QUn9uk{|b-Lh(MBUI*{GAQ1ev2N3w+Pv`AHZjQcQ z{yy-}G0A&c?n1n;b(N0L@Rl_g;4^`ER}}GF(0}d@Lf5xU4;Cc@YWU^@S0Ubr&2;Ka zQz|$+Fx1BfB0+gT<(lU2*wy%$pb9beGYM4E<085B7AL1-$5%^v#<#CzJ-pNDKCa^A zx9Z81+(L6vuv52Ml;b`=-XHseIb}S8DV?Vyh60&*z2(l4jwz$L<80smi>ET@4kV}N()*BLc9~cglU*UyhnY+C^^U6fmmtx z;V3>bcpkWukOT3iJeen7u$BrklH>{-=SPCp=)pIq{&AkaF65=had_PW8dqGn=4M$k zHr}}<8B>?dSPyRs-A5iyex=f4ANUWFz>7lvWrw@)@qQSv_0_0*FlFWu=MQ%)m^hpm zeqi$Xqi<}FcWfwgK8#;od}IqRNP~0lFb2G*Cv28N@y>f?HyaCY?kO?(ZxHYOa>P;^ z-Z^bqj;kTwms&cHS{b+l1zTe0CjuD+9$Rxi3F7T~dZ1TxJrxkzCvM%;iv;F7;>#L7 zVB;#;;nis%Ec!PNnA!2?oWYJy5?rn=zK!+pmZJMOh?Ad;HGfxa2ML(y*EuSD#K)U7 zZHw~;!(fUY*k!M7jE{Gc)O&K6p9S0F9XFRb9~(EHiy4Xk@BBYr562S!K7MN=fuRP; z8Mo`BHApH*LKUk9xrMoTErd0QpXwjv4{OlFT;+E!;2NY~#M<$Jw;o_%IPiF;HyK>& z^>?tB{7C6`7g*t}5APsNSvROA9R;}F?jxS>!fudcuPfh8kr4&F^tgPT2kwGn*fmJ? zqQO#0f7Yu(GwD9maPrd}-BNuVeh|LLXjPP(0DcWRl~Yv%n(ZmGnuZc(!trZRm#=7o z;F?CZuR+6^%=tLl@VRT?&jV>O40z9$sB=T{cC~t=f`#{sG)YZkh<6>250!?u`Heu| zG1?AN*X;Xi?s@@yyL7I8v zi6gyoq9B$Yr`L7jdU%`BeE^*N>bk~HZ=4hboj;yw?U{v-cbVdv zo32moDIbpqwpI2w;qD+2#6R^;$lqssya}RA`sk<%X#R7&Wj6!fvahLYQM`EvE0nSD zHhy3{uodF1xJqW;4v6>E){WOh;SBQY#KqD51symAdDXO(frMe1^;;7;-J^grzWwihqoHtM>0-+ zM|7qIR4x+*LlZ}`^YrlXHeN;uT~{AK(cSPxRbvzW@|H@FS!#cd5!-K&Chla;N8+zD z^0}{nUvIIC0q>c;&o82QrzqzuVc~so9nUU*h_?{mk5C%ki5id77eKs)ZkvUijqv~< z#<}ly&n1IGznzNs9=1q^jq<1k>JGLt#zL$ z*prP#P7cyu&q&}jJ#Mq*uCQ81?0CL)Wz&vpupZv14?&##)a@#H&%n)z?Y?crqn`M9 z_l%9U+_l?HS*ci)Cd`9BIZ-jc+dA*iYqrN*U?p=tYC|e=p6&au|Hm3WSn8j{{-4ND zgOv2z-k>#T{x5-rST*Q?h1|IYp<;s{vQ_!MaEN`@TKH}){KU>mq+?d@Voy+b*+u+r zH+(@_&Z|EH)}UYGWpkwTs9>l!PSfy3B;c$6Wk0I~d&n$Zdftxr6$uE?7^MwQg=yCkZHhT*fVGprwhx%p3*0LVnsE@}u`Ed)r9os)0Ua`C3M&8x4 z_;|OtsNC6h%7gOm`t&6gx%fjY!F|2nH`o6I*IT|`$CQuD7jy_#7ic?3iJT00&+V|* zK=D4hF<%`E?{d=^pN|ml9lE=mX?P#yjp&ep%Uklw7jHYw^#oEc9S>C%lEJFf&79s4 zZ(iN{`z9->VEKZTpRH>m0ddUuXml(#-fpUC@vjJ?fSVq7qjKHZ_2t-jU%30~W&9S_ z!`qeaBOfO}y-OPjXSa)jTJq~h$TfVtcT}#E6!@u2(bhz2ozFL7Hk#-tuvYBMr!N^T zY+t?QLQXT~!yr()dPm}Kyg3-~o>MgTcXHxWx=RfU??ZjRP7q;(6O^LfH<8cV){BTW*N=nfi)Zn_45mp@MVXt?--x`s@GS zKcgIUC!I;6AekQL;_i1Nr4bwNh6e_6h3>3}cO>0MBTjy)$i8#o@G@r7iAjf!W_-M> z^cN-kT(Oj*_^xrlR)LAvTduw@RF!RJ`v!@Cd|=MU(Xe{O-`86tPGi7ZevjG;w0d`r zn9s+;+beH#hYZBqG-RtZZFAz9L|O73h_`=v#n%*0Pk_AKx$ICB8N{^SH1LFYKl8HE zO@Vmd*`RlT%P0!WkFcm|9->>UBG_v5wiTZRO z<2d=PoqSS6^%n)A^Gqy0Dm*PpWh6nh2Z-j95EIC@+PWpAZ#8Y>&& zFu?P1U*yUjsnubW!s-+4_RE>5K_84?Da8e{e+_!ToR8W(FRF9S?-?X71Kz5?dTdd= zjV0Q&u<*W|^z@xS#M`zddX*2vd(DNHA2lG}Bl`!sOdolG*RqLZccDZ;d9>625yV^L zMcaD=Z7RrlC>boMyaOLfXVUO)zocdno7x61V#MHKI=dXbB;@D|LAjm>~~ zcSPoYqT#(PszY!DUXXSxKKhrJxF@)HxI(d-D-lF+&s8`B@!sSfGV9z@DtO|audZ=8BK^gaP->`n*6&!kk_s#0UTWzw-erP6)NSvHkIuy2Z@-h+V$eZQ8Ei)tid} zZ)M*Z$5Fh?9rQG@@ZQ<}d8ioT-Q!cRp0@XPjnfs-p0}tqj#g`2<_RoJ)MVm5kwKcZ znbskQw}8S;p1aGaAT&H<`%m5|@Ga|j`>KB&Z_$V^b)42s0%P>JfRmr|67OK+oxP2# zWpar;%gwz}A2~Sr-AOz5k}M<&c3ax_bOht$9jqKuRGSk>`Dyr}=SDsL-W%c0L{s9^ z_w2vCwTd|(PQ!J5DS zv4Q*8S$!{9gCcS$gHdn>8TV{U{9+Cd@GbSyvolhOV5&MZWUbUkikv}3X@Uk7kOO6A z^CpLbojqcc$D*-kgoiaGeAnI(0b%qwY6#DhA2QhSviIdv52&)<5R3Z2%g^1SbM&hi z3CQ0#JipeA!vK$&=EeKpE2lY8th=_h-CK`8gH(7}lo+WqNGIK;c3w9MX7-UEyXev+w{ zOa#s4j=NVvyu)mkHq2N+1(z$+zn}082dlf=8((b3#&yjt_q;Ny2r#9`9pB#^`&t+~ zUi1Cc19x>;4{y{5UVcB-+m>;_8>DC3u3aLq9Ut$M^A{?Rvrd#g(Qkv(GnlwyN20Q> zqh=G^<4sUy(uc|C?W%uvkOUdGg>Ks*XBr~ z4+-R+FdGxg!^hijxl%}oU?Ao2(IdgZQTUUSn>YH^2ut+YzW?9cz?_e&dk4LWkNn1) zp8;=mSAl#KZ!Sq~9W1<&dh>E4i1+NHBgbfX-#>TfpfSWdIBL&@;A{`jsW~o$h$n(a z71ww3LA*%@?}#~zsNlZ!qr)!m!@ne-9!_QSmY?*AjO#s6UcFV0Ydbmum3qWynwiVYW54O*P(v>+Mw|9*$BANGJX z$ZyfFD=%RUS{-#a>tdZd;9H@h*1($xRuh(u#laesXuk}m!# z@w`6G0FRxJ=<<<*{*4s9@D;9!-|=UV1p9Z>vNkxf{|u5zAE#=%pAn*e53ynlcxz8- zH==l}olqiT;a#-jyHPg8+imBLS2Vnx&QJ@ULcEtW@3`04LJ=_# z?`&dC!TkADP~LRvjo6QHu-_tw#Qy^uSCY8a;L`vRK&Hoir-e5hv zQ6G5u*&pq++dnD-UY6eITiAts{^%@xC_R;@$}Ho~#PafA_#0 zNHGq+g_#9LQlcPb6< z8|~%i^C8}?(N5v#;H5*E!fP7*VS^Mg|8c(u#QRGU$5g%=yx!tUHP7DqaB!?|BFzdgFGPA|R6U&-z3keR~ z$w?syv|D({kJ4PVuO#*re*a%ruhn|?=nA&)|7))^=i|2Msx~9?@9HhWfcN5U8A>SL zX~>~zSa`Qu6wc^{c=za;4$<(gy{BzL+k3l5&G_K)#vPa^pLTMQP6Rq0^Afi}yk}HA zFDzH5f>z43o&(L{0O^VKm{Es~>-T+I54Bf_06uzL{5j8*OIq0R4|DVutIT3OyuZQ=;NO5Om$d;f{S#<-Czw;x@#Sp z4zJjm*rM@u3+(^fN`=H_rpVw&-Iuc`U=2dvS*}Q&M+G-O^mp9Si2x3f`oo6i*!};V z3h8eLM}&bRJI_LAIx%pj#gCniH*&SJSC7WE;HlV7u@UH8LHBA~pg=`{B|{28QP z*vr+qMHUnl%j8*K+nH#P>?hMr<=OuYQi2t8K4z?S00MtbkV-M&t@pA{5*=b6O-$#< z!uv^~`zZs6x4MF>sXN3wVx8Xg%@FTSs}qMsue$@=kr)yFU+{_DO54J8i1*$p(ZCvr zx73O&ob!kgV2q!KvPTjd@4;tUH46kpzyv)mbKT{_GHL7~cIfl+bOd3&1_|}?1}DF` zJ@YosKLMBXn#TuM7~)EsS?;49I$4nvKW*3bVKJAJC)$ii1;tyh1 zZ__OQ2UAN#z*Tx&vYe=QfG0NIkt=wj6D(N|Z`4OPPJTMs4LUyOMSw$rO7@;ae7sG% zd8*oMwotsEb>|HBF>ydzztCUH$dc{*e*$36M`3SS*!-;D)q6Sv-b<~gR8hP|@9*cv z!u#v{KX4?-O|-l3 zaGQB&NiYdamv|Kay#OC?byX3WeGfKLQXSVQ6wSxKz4g36fibvl$@bMdT#z{*1%PzX z-8b#O_y1Uvlj+^^f=Wyy0b#QW7nX&e${URty!=CFQofu#L4g4jOEKV=8!-{4M}}r9>L(> ze`y55;p4Al@{N5dyfr14H@?FE#Ex)=*X)E_INR4C!dd2g%nYPeR0|p@8S<*2LG`wrZ7I=Swc-yr-am_OH06~#%vc7PLy_qDju>j(I z;2pnMxC#{*?>en4b2}1P)T>7P7ZC~rI^Kt+i@4{ob{)29; zhxZe@j|({Y&A7T>CeT|H?0su`DCj;u-aZZ!a$RJ5O61+Tb!&Is!~8v>|CuP}jTgJd zu>S|r8*`cS;aha?b>@NJUy#mZzf)t{z6cFgtwfhX5o5knF|r&UPxd5HI+4^ydkAl^Rik9p#TNODA;%!l8E+Ph3Z@0SZJt#_v z0P>AtbM60eT_tgm?V{3rVK9dtm;F%pgpe6F-bx!!n{GJCdU$iveaywlPwAeB{a8N< zaO^KGwSJ3__u#hRZ_Df&r60q)RO`f4|<6D8qm^ zSm))3;;nT%S`Z8G^DfqzG7#^doYDm}ylv&Rg>TdFe(G-&MR5mv7v86OO_IUNX7Zy` z5bvtNzJbjUZ?}+G-zNtmz|zZ|`bN3f)mz6zXu3d~Fjz*9Lv)H-_x$7Qt-ylGIH?BK z!yEPCkCPwYXp!ZZJPACJ7%R$VPo5r7^u!oWtX2JLWyuZETeis4mi^?Za z)v+6-MJu{@#hM%;L5k@s&cgq+#F1{J>^X39ssZ)|%>%I_KE90t5i z+Ftzr#Ey2nrDcFe5({s|Ej{_k5btC?VLKY$LYnKZ+d;hD_W4iE%kTjFm!hh7!_QlG zJm0@z7Q~xcc~$$392FF(4MphPf-^|q*rCmVjd$^f(wK@5LSQaE?$m;;lfM5r|L-`w zGULk!*26oW?!yizznonj!OdADaBWDb!;lAm2Kk1w_pxALH09HQ`1zZAnfS!c|H`UY z{Jw0DH$j(49}g_w(ho?>GvK`@SNiY%|9hp5=~#H{>BWPy5bsD(dX|RwGSz4fe~5RE z;MO zFAQwxaqlwr=!+#{SMO~Gr#!UzSZ@Ytiu%CGPuTLNN{Isr+z;4x{H_i@-jjCkQm3-R zDE3R=7Q8mV@BayAFC=rc{|`KnuE3m+9h1BGi$DCX-f|3h8;7R8MJFddz30WT@Ltb< zd3PDa+W{dB((qm+X5X?G;+=NXvWzp)12iq(y)TMC5o~YT?%4l95NM387f2OC^BtPLP|1I#>|qbjL9sdq>>_~hzu!1h&qap9F>ZQ zlA)wBlq8DZKA!uu&RW0s{oLoj?>V3KeE#vgTi05j>(Z-h?`z-FRc`S8kJW;{DK_uN zn-xyn*x-*JxyUB}D5wc@b8@TDc>IB|8O>k+-yTR=9d|wB1jqjQyoE3s@9mlr3nbqB z4-WI9@y{d3S@8Q?+U4)F7@&OeXNJ6Pzn=Q~~MZETjY;XW|NTE)3WasF zok=5ZPB`G;%Se}p;}B)jVRmMSh5z~A|54j-0M7rCWIf1untp`TgK}?5uR-fU*OT__ zlY%{ny&QMT5%wVQH{us#;5|rDE?i4LSGWOIo;enchD6}@lGC&t4oLK6l4&vg?O;WX zq0NQd5I~n@-u&w)`Wa;H@r$CH**O2kb+vjs=gc{yE+rL~I|5<_sBb{3M(QZR$giU; zY;V#m7f7gaS#H}sk6I^*&%JS-Mo)r0e){74)qqdfJ!p^A;WH*LjcI;B+AtqTQ5|<| zs%lPWFYX{E$awE==5i(R{@Fb*gvQ(GnUjm=KuVAe!lIytm1UJft%VLUw1m}yo=Z9rdEg^#>?(6^8Qpw!41-n_X;MRrTy#wxK_&QU}zaLRmxfH-s{PD8`*C& zCGlq8e10VwZ~08&a9hY*Xs=`pk+-GEy`DM9Tce=(tIG{H(DF6;ko>nq(4YM$ECTZW zbj;BC(aLs^&QQooFAxf3U9S4aI-~Qhsa*9VF@+PzA#rMa>!Nl3<@T0z^+*w&v((4C z5~(8h-jMhHjq*>3yvGY{_Nl=6U&jAi zS>-i15Ss0^@h7}FQKv_!!5;F~XW+khQ>YzyvZb8KTpJ4XHafIMdZF{?EPN=R*~kfY zAaSGpGycZ=(YyD4(2&2sh5C52B6V0{%HfHwX)ldh1t<&3pC;R~da`Qa1Cw|cW^Zy4at7Ce*pJV4AgipOir#~Q8@9>h(NSLy z`ij)ykCESs&GuCX2f2WU`{uKQPyb-{l<0~l1*s?0@uT0`{-}SzUSe@;SX+X+Y5yK1 z+-Az^5ZSVM`st;`9i$8yZ?pQEVG{2Gvmat;yd~ReJx3t#8jb86B5xZO10e>ugA5<) z+WBbG4P4Z_pf!Ij5%{YWwe>;X$>DeJ^+Mk882Rkb!0nWd1 z8rOC4o&R!yl%>pt;m`)^>L{GA&nb^z+(Al{@ix8a)I{Qa`{iR%G~P{t`?+Tz zZ)J}+14Q1=^F{~dA#b-X;XQ}D+`yZG@SGpTi9oG-A+rPW9*EG2JhdD?-V(Ut(9X(G zV7)?G!xNU9kZc6-lRJ6F!HM{-S(<^oD0+& zxiefdyURLae=&NcK0T&h94(BWi{kfRFw!^y;o>A zL*CaVU7K}Rz#F8$sAt`L918fGqK{jwLFawIsotUN80X(OfyjLq7_-rNUoPI)DSCqX zcsn6=WMJgSUC6m~PLmtlI>0Vm6M)TIZuD%dbf7&xR{-yMd_DGnBv2(NtauA2)N( zjqf|Tz|oM~Q%0%3F?-4{8O~bgZZG`ysJtKD-4x9KLOPA@F%C38AmLajt7G)C2Tx4V z;u5P!#@nW>DwxE(-R!d@8gI@Ibv~Jpw`6bfej;zqLDLUBkoPZHML)qVcMyBVOM*2# z5iI3&ujGfk!(RjsDs#63i+TP8mvZ=s-La8y11WUglT4!9*kalL#$9ONG8T+S=l#Ab z@5!Bf>f`+bsiO}gze>yLpjaMm(3LBg%G-*~n|^I){K67nywI%Gp#=f#`9C~Sw9+cE zo91~p`BGNLY<~8=a}kU4zXBO=>tniq?;zFTtdv0G-SMzrqzLlfn_Y65$h*GOsA~?M z-hLBq&i!=V9lV{`omw1~2;L2_q%cC>=QC}V+w-)82Kl+qr70mGPLd(6Y99Ue7QO-L z?e4eO|Hj!k6p4wHqx0^ITyFR1IrZ@tK~6Whu=1Z&D-db{JYq1 zhwu|x2A#1KyuB6YWnLtp`G4U1f8LbUk@;v#3G=zd?k!Ko+sf%}5UG0;^b*CRO99@y6LG#!DIVr5euKASHlgvfl za%8+M*EatB_SWoM%k^lygNrpLA4A?hd(MjyPjBC8<|Woc-uW9pr?akd2exCQ@;&Dg z!P}&}W}}ezG6{PRet2=B7vGjyVIB(Da<8%K9Jo!NIQ`uxvQ zJj;*op}zT_2dRS|Bfs zhdpR*;*{)5I3OK(wq*H5Zx7&=dHbMfY9jFJdy`fKcaWhcxrCFM+kuB?3GQM{C|KIG zy@iDp{fK=oe*0KbZr!Z?@oBNt0^xxs1pBluB#B6_uVhP13qm5_)l^|x5g-#|6iWlwl?nj z6Po9}qJXkG+S&$7PRA_H|C`8o+Xvp7B=H_@E09Iw9e@4+i#_DMcFNb0$a{-wcvcAH zU7X!{>g84s(7h_;_P&Tj@SybP+ar*-m-^3Jj7!_Ws`H+`V%tN3@b|?2Ef3InrxAp| z>78N+B1qg=p}T`UJvwhyU$I>IJJiSf98!l8Mt-|CYrM^a^FNOJ$h=htHgBz@Uk=-t>^ z1UMiKglawA*^bVe$C2fH#zS^6h{P3sZOAbHm(9sNukO*|57ftdIZ{UzMt)zjYEG{? z!vz*X{8Y!-v5&VLx=IEbltb}ZJarxA6WH_rSzG4j+@2bmACTBqQdUQ?i%)<}+T#4L zM87{fJpQS^y978+SEhCj?~Bd zE>g!MjQo0UTnUIvh1cFzN?q_##O8fQQYK-aTqwThG4JctGzzZ&_oPc*I`x$1dE=5O ztRt&sK>EMy|7d%E>iTmy|7(!-Ah(t$O{68Z@;z=dS`QNZCA4*xtwcLzuA*)qTw+1c zlhZkHiIwu5m(^GE00nbmS1vqG1cBFedl*-Z;|p)8b;Z!ZH%Nt+R0o|40e5u1wS_97 zFR{7oS1+qfuz_kME}N^*Y}Y>Y9`wTS>r!6nm3Zp<<>GMpNF7-Dc~pi}B){hZYGxDq z!^X3ygCnWF4Uq>WWZ7--4hrR58CNOTK{m+NHf%aT^8*r&!a5G!@)W6q&mckG>SVlK zuT80tcsrkZu8hX}%jYKxEO3df3>Taw@^&-YzONGUuDIxDFJtHd<_qv_3=a~)iKk{u z|G*_S!%Q?-h`t?6h4~*};}rtr8f-QuFrf1m4p-Fh;#dk4k+`usYqRiO=)Auk7aVuh zqdwlENF7-Dok`oQS-6H91m3vbP8W^M`}n22`C|A5X-;*qK$RTq9i)>->he4H+G(Em zs5@nKoK4H<2}oY#twzS%CG12iiT5+V5+yX=>-XGQ;D@|Fc%`ZmPj8>gnr?amdEd+G zytHYb2Pmw2{ge~lLAo!ae%~nMy;E}Zt@V<2U~iH+lwlSE#5RR8HUG;FvQJ&ZvtDK? zSc}B9o|r$f(*T{fy83&e250Ky-H+6vhLK`93oO}?^ zH#!mgV+{p6$gUyV8qJq9&l^W+9kDNZh+mL~-Fpie?*qC$;UwNqPK0elQASt1U3 z&s?cJOys@XronLt@-`X{TV3ww0hqRKyRfGy5lrNHj=YAvn|enSV;R~(k8$t5!tWs< zr10k^#YFV(&2*sWhlI&e5QfCmY|DVl?Dj9EQ zmg^}b-e-1cDx&fJ9bETV8S>V5KX#kQn;}<~V;u6n@>p$q`%$>}zIbN4@cBf*@1f?< z1bIK-dyt`pu^r_8!RNod6$<7DXFHVD(XYKdATWMvU&Rh^L;u9RW7~87#9H*z+o7|8 z{6+@UH~&9E>UfWlU(=IFc@_9_;<+nPSw)+$PjBmfpN!0g*WL=+&oSlLV)MS9BdPO5 zWh>2hZ{8b})xmkRD9P{Gf6xDuW;Lq*376QdWIgC$$E)P_!w_7WN>GMn%1Aum_!y$lrG$&mF8PG8a`6P68YIc=RRV{4cq1#GYw^0PdX< z6!{5Xv70MXh0FHgY4jy_#O5%8Ge(f==Kmz54y^nf zw}zsveA?EedM{#RD|?rtq$itp0kSN_fX1T#L+rLESP;Wf?oAYXUN>ZmVQ zrF#*(c!5-#jJJ3CPz-5_U0@}sq48!HNj826d20yVe@W!cv1CFt7xGR}O9AG1chIu? z3$q|s5)j9;H3>uBh98;DFGJpZ5^q+2U=9W0d@d)J!cXy{{nPgx{GbwO&juoqxa!)e zrj?=Sye*cg7N=gNKHdkBIe zXV7^w(8t9zN3nq&NSuJDgq*k^I`489oXF>g)W@3{siOiTKZA#E!wDtaU_xSzs&yMS z@4dCn9?x?%@#7s8Dfhgwzur2(yiMuC3oDu*kn{y9tAm$w$GM=m#qO;|#@kcrc{+)= zp__{;8t(_^PCV{|yt8H^^@zM9ZGLfOLEhUQubObD^8gcb+3%l!N(Ae+wwG~1-sXHx z5>=3Qd!FrZ+w&0cyJFbkU@$swvp}|rLxpSrSNTtzotfnGUT<{XOjDe;PM@fcw-r(c zR(_l%$Md8PmAVe@9#Rv>oZi6(xAsc!eu1_~ZdOd9)6XGi<^O%ZVK{onil(YF6o^yhH?*CXpe0T1UFzaT}N{{;=~n9zC< z|C2(TFYG~SI&u*z%xKQIf!AP6Aj3HcEL4XC1i~J~|Mdgi;4cEu z{7eW5vWD;fXZT?&uoAro1w2*X>3ob8Fd}h0N=qbMzd4}}RE{;AIWg@5cq;nME~es- z)Zv7YU$6Y_ispCl{ePnmj2*Vkpw>yM&uRH!iOgC%yqxdGK-uRFnDMxSYag)i{U7)S zNjQadM0n32A4uCy#@qi)Z6R@qCGxJHlw(BW-SP`(brkY`d$y;N$ouRZS1a-T|LX1i zdn1>-1CA>rCc{=qK)68TiU;J)!DDtadzJw7c7LKzd=dh-CFpnPB%||QVg8{vFP9Y< zAaPa8QvdARgucWw&bGhpnxsD7q&k=|@{`{9RU|iy3ls(^$a7r6=1uQZGRD980DkY_ zi^>O_*hlPtPb^+?|)C1FV6ql$awo%dP$LZE8ZJlg2ww;$)AnM zkhkW1{y34h%;Zk5e8~G%8+X}B6?c$PpS?Z6CZX2r`xc3>#X5-`|Ra|Z+PKZd`7zovwLT3G4@dn@1c3#+J`8s!{g=2H~Y^n^42Be z?JIeD@dfF`?p?syNRP%l>eS@63y^nq-Tn>4(_0;g+*%yh(Lz#K`acb=K`dV_ZO1Nyq5wR_x;~tK{iq z%VZb4;En3Xe;Bb(Z*jXn9B{a3OY_|ux0kXyMA{lsiwpj{{!g0KsQM@DK|9HMP)J4N zdr}W7mfXpX)`Nm?FK<LgkxE35_plK zT3QEtkWK76nKeHMpk=nSEV(xXR976I<0(U5V$}~GD*E)81=JyN^i!+ct$EOU&=&)N z`P*XDHy~|6>KMn!j}eG<`aR+Hg#yj|E>f#-w#2w_er-Dn-csJf(kkN#^>+c&B5_!L0 z)1AK@F0r-ch01$;+<^8}L$E+(5~wIslPo3je&SwCH%$Qjc0uQvZifKvJr|RBqS1Mm zGwiGL8Ds(5kvPE{9mlKa(Rn{Id9y!Vjrw?(A$7E1n#k(cn9sgMn~%2<@z63(RiyA zy*pt5c?U4`^bvWd{5qY!1@iXW!6#Lj;s%zj%qy!4O#+{t4fAs#?{9kx6^0@25u4F1 z=MqBz{gT;1B@1-k(+RhqA7W$$Oi0{NmTrmd5A@U93qPuwYHX;F_Yb6wER6iJ6;F>p z5QU$&I1>IzwHKSWOVE{w^k{FqTE&(!-d^l0NR8_F`)jK{(>!k-QOfFY-!8rS&OfiW z&?n=4MBtk*iT7FON)|NU`Da4uEFkaQla1WO<1PP|UGBv9|8o~z=B;;H@W%B(Z~U=xZd2A{6m;(xy*D$l zBQ(!D(ucA-e02w|P5$$7q8((s1IItX|Mkzs2~UUP%xJv(*9g@-2SyjQ5t z==IpKf?6alHB?XY8zcJW#OUPuo`zED<4vk#7e;>a&2_JfuW$hlThZ?`!q~@KV*Y*{ z-K*{J>kcrrJUobfyrnFmt55&Eo93VY=iEeD9i8gi_wP9M-~3P2b3Z9LIREb<>p{n^ z<9J9t=;=wogVuv;R?1dSv6g5zWIRAeX_#XZfF0mJk614VC5Q=G4ESecphwI^J3_sy@zL z?B2V`c!#sL%aM5VS>|)1@eYYq$>oQ(pCj<;qyV z1|-g{H}L1N4d}dwS6ph0Vy8adcab_qF!JMgE4}@bKR1vX;J5r>iOt*Imj8743O9Te zD`T;0Su^Hd9cRAW6R=IuJnzWel-032dE%`PJl^{6{(sVtO~pUq{BKUygW@g(ttIuK z1y^MOv>x<>K1HG$&i^-5_aC){ODy+~p}K2M@C(uk%f2x;xq=Qa)lFbo5)gRg!m=OE z|3`nmTPyaN0P4rSH6K?A1%iig6KfUGm)K61&ua1~n1K)y_tsf+_4`@$BX;|xgLtmA${*>?*gYuH>o)s( zo+GrsgLJ2?4&Je*uY|(I9i$l*_7?&W&z^4aTp9|ThM!nH#-a1Ra`y0j z#T(4v01`L5b#DK?QFPv(+^Wk4x%sJ%_a&qbFO2*IkG}219pV9&=g&5^@nO&Z$IrE0 z@#FWxhv0v2y6cS1`@U~!W#+o~G|&5~7iD#f2@0NRJio}>l#F-GrfxqH@2xt|m!t8H zQ6oHg26>wtdND-g?R>jj_ygp<(l|Z01@d0Tp!8PzD*;pn zUHdaN5d!i`y=|Qb(07pSoJS(pw=je2NF3V^&9vD;bl!AIqbt_PQy=d(qz-zF{6>NT z3~$u%fR&!Ff6*&o^B%DuE8YZoSEz6#j5cAP-r^Kwmyd1vNb|gLVieY)@}%#=KVNUz zOU65z)pj|Fw{-e-J~ZC>${wnHkoQ4dCPCuy7U$iz7#?_W!faro=l6muXjobh7H*jY zicgtHOF`b-O=LT?#t1;>=Id9YZ$p5>#owQ6pP=*Rd{lbBahw@!MB=LJaZ`5h(RrWV zO2^$|Mt!{5kvh^a@>9%rV>>y=4Sbb)O}Y1D^A5GB={E54#K#*S-m`Tb_WZx3IsN#} zS_hhcy~RuoWpyxwG7ca8=jB8uWV|DL4iu4i=d3!yi^lu<+QampAa5nf$2*C<3F8fn z5sC%o=_YofboZ%*0twCfjh_dT7^*b&51k@ zpUsLQ7T}G_tbgd8>BL zyRP-|#0Og}|1NCZ>4emn(z zT^Xjn`M(XRBM>7$`Y+kb^?7-~#Z4LeJaE|a|5rkkY`2jw{`k0JsrCcxJ4kV2AxA># z{|`KaBtlso?(PFFN&kF7%9@OKQb6+G*IUZ!EL)AnJCE_XMIz)~ptin_$h*mHiHHN_ zJrjNV*iQK3^V+g|x$S9*AeVP(X&L0rVsO-y=>q}0_dEak(slTOG&`rH%h%C)Z+_6@ zHlNN6#E>}eS5dDsB+!@G<4Y%U$&T)QSgeL51|udO<$hV{D9OFLRlS5cZ4Q(#4lb!vLfT1sG|FK2kD$cScS&> zvwZ!>vyk^a!+8S9yx-vplH^=O92*irluI^Tz$5td0Z`d_!^G;_;Rx z8SjKy13S{@WXbQ-E75pAIjRwS1@h*Z+`Wo;ycOLI!V)2GgYPzd?-m_acT_f}(IEnXF!H_q7K zu5lOj@zzG_pu@<|w4rYGR}UW0u~kz3*%55sv3>qY7RwIdkEq}ehf(nLmV=jy38!M7 z)BFX}%q+_4a0{=$d_8WFw*?vR_}Bi6-`*xZoVdExM-YuSv%?FwV#qt#Z;25(?~+Wx zJpO9fy`RdC20`BIQV-oY1bN>){>A9`CjziNd~H0a5uVau%9#d&{2G1WEdAUU#2fuWOo`|d- z$ERdIIq~Kl0XP{q(Eo}J1y}F#Fov8*Ut+xypRHMoX9CxdxL4wyB8*?qd(f+o;pGx4 z)YpUDkvcjt@)K*U$h#!U1BO-#xf-cYVP5~&h=^@|-(!z=+OmDtmk0Y9B-}dF%I<>q zwBLgSDXe38bHdhtZjiPkY1bOet zELPmG{s4%0U!o9Q0(mD`9_5C-^9SZeOZy2xz5Ge^#m!-0kS^BhfPp*eU*j7QUKNE8 zOyC0&m#(_uqqZ^n4$^|~@PXGp>f`+yslyT@zrMFDca1-BgCRqq7hOlNc}KimJtAS^ ziVsX+!Nssq@QNMIUwt)^2WfvmVxz1M{X@fB0&g$wAor8;KDBn+Iuh??y7xuVc;9>5 zw|XDseX!sG9dZ8unzC?*84gHImR|R6o;d(kvD6=$A36>qo}S(K2kszqrSo*2z9)d| zK7J~KieX@5V(*fR+UUGjt8q@7EMo?nkhrknnBI6(bl&0LJ+ca7sE_wbq>iH)`ROMq zzNUM^1D5MuJ{f-jn|FBit(hY`_u<(Uwo2%+V}HFx`wr6$qwzO1&wKV3Wp%6*DOo5= zSv=m_N5=ak+ls~a{}TtKvddRQ(0K0`m%8B!dF$UeBTMA1sAJHs40%@v=Czs$xB#Vf zOxN`!5&>VQu)qZ5O*cuW<2?XhPW(bU)Wj$Zw9w%{4_cw~cFhalbw`I8v>|afiunT_ zJkWVxr@uQnSV4Wfosl{UF!DRy@JG&tj|Z5UyGg6x!RGy%H;M0#-9G%9A@PH!)=|*C zo10gM)4inq&B+bQ>L@%~x{>L8Jn{X1wq(3dG?uuNy7yauJ7F~5S9U)=<_~$Nd2X>I z@@AIW`D!cV{b+hd`IearSjpY|o=Yzg^uF^p_y~F94ksE9K;C-`g~C7n3I(bK20?W6 z=)Bi|4}5&tk{PHYants(uO|QH;Y6R--MgJzsE@Z8QpX{T{P^?lGOE1c0etf|>0Sfa zyn`e!YSQiY#na>8U0rh!o45OXF}UDH`wu6|eWt9AbCbdJxc}b&PhE39S~jo;9U$vL z=fe`Nl6ugOpUXF(^&me^?Q%}ogO(_+eqaWB&;{#NLW-~l@$q-qrf@g`GXb`jGmjI1 z&nnT+VQ@e?|3q{6R1X2X-pU>LOdt$|+Ad6_ZbI)ts}(z19g>+qI1)#%uH&Jw4tG0yl-1!8A#Z4Oa&bU%CgYuMd|92udw_pL5{>sg*#}EkLf)n^#uG%| z_v61OeuwkFkX~WGbD9&-ob%pQ@+$!l6eJa0AaA#tM;Y(l5P;~aTBkq!@Cj1-A&*o= zbl!oNOEV2CnLsBJCv#Rxzx&@Fv1?Fo%2S{|-o8j3!x;G$bEj8YKjsFjBM0L-%CLE# z4Zc}g{@xWY|J}{h$`|{1%hJLqfrIA?%@0WQ=9JZOl0Tn8 z1RC%8^}&(riQQXzR+xCa^=M|4{u1PU$mqkXTt#Q_`i2nSjg7}alyOsv8RX3-*>tzQ zmjJx3?O%UGJ`9X+trLsTL+Ab3ck4@z_e@{{iF~diUPR{&+UbhWdDaKOJiho72X;MDVrjuH>bBwJXy#(~b|B-OR`Fqk#Jl_Lp7m(F_dny(R)@UzEwc+D@?Kjk zZ*UuSZrdv#!P1!RRkD!x@gJEtB;mEU9qsRCm%!Uwthd$Q^m>5K zJ6_lFJ4+VR-#7uM+%4lX=-1v@Ph9&@y`1{GcQjH58%BO!>NkT6y12pEn~ld^)?)KM z;EtD4d1;S7@pOOP5rDn-_H2v4f7Pv%=6QdqpsbFcO0?PD3cN9eJ*anLH+vhL|KmHRi#2)e!QFns+``*< zQ0mF7^$zwRj-EYRhhGwaL#dumcwZ<8>r2|!xeR>=*|@%nzR`^lgd%Zc4V&^dccS;8 z{j3f2LKA#cx5Pd`>afGe&+_q}vnPJ=fT@(F7PZRQJ4msOTzRD#9(c7k=4Y(RuphBg zu?iWgx$jK#1JaNgWp(6E`Fy31TD*efPR2XSxZnec_fw@ea%jBg*<%k5K;8iyPne1G z|Bs>e-UpDkS(X&wn{v`>Z{Z8VQcF6m8tkvl^uLz(h>Bm>IJMf6zm$gHD z7=4MIez|Z{HkJ`=LE?;R!fr&ipz|(F&}?41lnQr{NF7BO`CUGF&fh_f2Qbj}+po~Y z=KYS2<E@t}F$k*$=~Q7T-P8kD`bgLEU~oheof|JOfn zkZvuyFN?t_Wo!?{Utuhh>mA!6Hdva=!!UklbOAA)5e>8q-zXgS?gG zGiIN45&+N7#^RY_u56FUFT>n&W!cxT)a?;!CuGBcD$ zmX^!5gS=x7o?aNvasl% z`9J3Y_=n%F4XH97U;=lLxD_7tBg6363@!d_MCz0A0qW!Z6{!O&zo%+1o71=Q0Hx&? z;dCk3y!CYHcKR{<;j`^NYtFrGLH)gueqU#UyKXe}sndM-etn#>I&RJCXWxuF```Wl zBmmU>6VCrWWIgDbzg`Qe2i2Y9*o@YL60GBOuE8bNAR_}uod1P;p5}4GcaVq;g|oEr z+5(}i8%uKJwZ~dD!wg^_ z631q^-u3Kx^d01Jy;qDJhpBJ=KZewih>@SC#f?ufw|GGHj7;j&>Tj4mJ;{1P*jQ7>8@qb^CW@Ff`jK(|t z=Ev$1$lHl)oeYt8?)>#<43PH$`|{R=Zd;IFS>oWZCmtMSZmAN3ysgz&WdD3d0FCFY z4K9U-f_=;GtC`rrI&b5ejyYUe?tS?rt>C8y8Ah9e!)gGJfVS4oKc) zymMH8e_ix*KmPFq4QVBlahy#-8=*<0x`@k&G=E}aS0nZD-ig%Fgpprng|cm)KM&B@FRfwy1)F#KyStmOK6b}n z-EP{=OUc(;&I;%VzO|(N`TrJ$b#y9hllkZN7EdzX*;jS@NZngJR6`MsH)p^LF#_b> zhhr!u^1gh2@4F7jd!=QH@hvYqu+;B@@GL$aa6GOx`3iY|Sy6D84_f_CY)DeP_pZWpzZ+qdz37a}! zK?Q#7`Cl_f;78OSSA1-m*6UZ4e7(hv(fXR&C)(%jLRlRw;yW95UH|X;KQ)j2e{+NL ze*jqzx)CPhP3%D{;UjiyEbVY;J?OGD_ZMH-gE*M%6!yX%WG!GKLwtjDum82R+h;6+ z)}f$Z{yA~rg6yUEWVnNz7`rW3+DZTeYYZE@^}>MR+o0!pC(+L!pJc3!d-ILqZ=Bw$ z+d19c=sk#M>?q-V9QE~}$4DK^G4i`wu(|Sp3@>QoIlp0t8uk)g68H3$`R= zJE<68^B%q$8RQRnGgg0GT_Q%oD|UD`i3g}`qIuppZVKxdot{?yX9wv=#{2q|uqui7 zsiIR`(0C7hKc^H6d2ir!jU@7}uFT{Xg~wZ+k0gczyQ~3EScMk-TpVz#eUat?c^g;7 z;j`NaV9zG!k8&*GpmNt3@4zk()Kf~Hu92hSa*UuHiDQkD_?d2qeg&yxyXlM$@>NwdDOIRE>S@y=^*s3GyzsB~6E;~ius77D!xIaqJ1p zf4O_hqKom4p%wMnqNOlN=^;00poNm7o<*u2G*MUCzgJn^yqf96A-uz9z* z&@o>5@{Hzr|4yc?4m;Nar&Zwx(&66w5E<{>bJKrcZ{bO|Q3Z{6*EQLp49I(RVBjkv zZ=J9|r7L0g_H`>Azv^KFI2fHJkMhO?ZS~Ld`jEE)zxs#5b^?eCYR%7h6AH{Y2Xb`Q zp!2@^S?+#m2LsrP#Hq~EKU`UgzB!Rs8Isa)ras)b|SK1%A=IualTN!nvFCWw`|o_}5NeaUJKM zV#bdxe`_1x@RsHWq|wPfis~@Fj_(+GlTBP=gUEQ_6z9|=@!n^+juDMF^XI@NMv%9` z@~`Pc-aU^q4M!mFPOrX~=Y`F{bMMkywLEcPPc{3}2axyUsx8`Ao8cX#HfH7D`a{7X zPu-PcD(FjWK>x9xSIZgx#(6E-n8X%^zQjKKS$KZ*7WMJ=N9uTlk>97x9ODm`yx`O! zsn{E1l=BX~bKbes2m2K}MmK+^-MdBmFG&BCNm(63RuLs!iHo>0qzGyIKfS;~B5?@@H#f8vu@9eYfDytR=!a0&mO zAII#=&q-%^K>zLq?r=k`3HN8_zkSm(PR@;>i$?j4bLQS`UeddORw>#>{k6${`V zTV_k|7zbv@Okwku z;pt%Xf749!1CoF&Wp${Bd(0a}FLv)hGTw!!O#Df_g?&%aq45sUzZ>4>+@Ot}R6poA;(L zbx%+D{lAvgm+lMYQZWDf{TxbO)&i|apZ<=y{3@K$c=An%5xYW3l4m4ozAj4{R+UAq5#O`b!L; z7l|9cGc~$?1bvC+9?WUURii%M8b}>{82Rmg<6q!(MHI{%%muaCV)K?7bcicb(ZWv! z`rvMr)?@MxoKs_)I9)^YykGyKtd9D2$1%^8Mc!d#yvv4}7r)*@yn8F)`Y;()|%$t5WSd25;L)*h)e0e8C|MXc?J1&Ok}=G~C@VU-<40P=p#;lxz9 z`6y6Q_L;_A@kIS=k<^bC<*+{r5=ipV)G_loLE)OY`=ZzCF<{m#QT`K zuiFcONt!?2>XV|Z4#D(Rb=k`|h`d9{c;7l2&P?JRzV#S08t>ID2cx$@-oo4J4T-$R zS(uj*A5Pq>`NNPR-$0mUrQ4YZ?B=J>s-qdt}`K)Og?DGg8|1)OUKDiqzqck>4J%!GL{01k~n4u^<0T zIq%73QW;Zb9jLz-5^txx_}v1WBQ(!DIf=45rggg+cSq*_cm1CPfSP~C*(TGI^`Kgi z#7F8uXSy_a(0b56 zRp}|%gN|;#GoRZ?04`RiwN{)C14)g_}L#^{kn;G{XdzGjQ8DT`xaksNgR+IuX1vu@mBW9^7;;WTN~uB zC(i#F+^vDc`~M^4Ma7GyO~Am+tVrvXSRe<6CcZ-6HjlzH+29T`dUD0Lc=!bAhXi50 zU32J9kY+2Cuajk91pP>y@4=G|yu9eV72Tuc4D+aucP3JYGDdzA6OWIL>=y+lbVZ-1 zDc~(i{}1oFj46o*BkU_k!G+eD!G>>Wo_B8(Wp&((j128aCSE~G#*y)^9`<)4b#F!f zcgxUtYnO%J{|$MkJ0=(rd7I%fOF7^UQfO?`xc;9#U{+}DOdb6GdVKk>M;{??iyqB- zAIRI&>)7-#e7!|B&OpKXGdgdLZ#v0a-!gy;NSrg%``~^qbl$a5W`nDaQ6KLuNF8{L z{8%PF26!=xg05vYySBf_?%whlIwL;U&F~UR@AurQz(ZL~ zrahqV2;=qCqF9i2cD(34O?dzo~+H)op?0)$ANaVkKAZ^Qm(&gjT@a9A$ zj)DG6R+Sh!@35`+wgg#IAMedb9T6D$ZBrWm5w}GY=nYT2;rxTmyN%!buvx)gJijZU zJ7Y8U(_6i4At@ZyT6NUCPo^Zd9!ARQklgf3sWg0%cLW*lJI5}3BXw`9@hA>7-hB_x z-r$71?OM$@(o;AL_=Q{QAK8VzzjgcR_w{L>U zSy3=`bCPv4FZTQ|lltbJZq8o(VFfwc2Ye4P_ue?3bu#%8wEy;2oG^uTe0#fE0Y04g z-~IoTG>!kqF>nXTOxA-QY<(F?>OsY#+5%`jDDs>6y?by6dB`?l2XX#?x1n`MARLg6 z$fSX<)u!ORYPw!Jya%NAQm^A7;ciz%z?ec^1nYJ zbNG`V-pGZA{lYHnB^KwXyNavEkLJ%Had#-J;~c?Kdhr42WF|7+_3Xy%B;LQbF!7`D zzNb2%-voJ=zQTJFd56}&$UhEwe>i^j<)pqTd{yl7jxl(9L3TZhxh3SS@5!Dee4hZW z7#dsJ*M|bepgPrffWE};sfyd!@`eG>BXQ9c=MLJfKwn~?EV+PViKaf@yO25v82OE{ z>Mb2C5(NsJ=Pk!{v3VbLXz21^>5td7;bUdqh&}(~P90pYeV>l@2c$vD>hM>HUeO2# zblANa$#~y?eflr&jX3y#30zzbI{M<+;7=#V02h024<9f1-~0Ev@;-&U6Rqb?5_xkx zUAi>~@(y>rq%qdC7qsbGeCmY9Tbh>ZJhUM1H#aYUMmzyb%&G4_a4!@XTRE=eRYT|9 zB(J>8nu!q@B5@0+Z62$yMCUDqzhXpRM18y)kvgO?@~a9wdadt>7@*fQY}Inb<}I9C z8CA~bhu^s4-MAVjHt)bfFC2bP2+i}Z0NxbUVZ36&#|yqe8uDf!<9#ppKm)0JTU@)! zhsHbLkx*Y3cCjSK0M| z0N5v|R;<1l27-QyMuhRBU!3sCFAugf`N=)G>>Z zpUI!d6D2WXp#Guzo)z;?ueP@XNTJc9&A{f^=Mx^z4?Eku=X6$0kEj9WoiU z(fSpO-Fpcc?>gV6ViIq0dmmmj-k)x+a_fh@TQmGSiM&r)$|eyXPPF53Np=S&sjIJjwk3{@;%vbvR<=H#NI+n@NuZu*lFCeM`Z`i81wmE>4VX z_wir1?K$d9LP}^?m%5mq!5Gc+?pdI$j?3QVGSgB2UH>Qj{ZsW%xWuxP^`K^@+;CD4 zT9c%-2CWCVGYY>i+xGO`um?pSjjybLJ?NsU_EO8s=HPS73#&1B{oirs*|n!| zi8WHuy`y!90KmwLHHUda0n2;c$sgy@=l{YZWlTKR;DCh0y>XembTc1){@2dSFPPp< zeM{_hqzJ$`im<;Ege>@!H2-gLKDU)Irl z4|3-{Pf;B~rP;y97T+M9yp)XhqlHIVB;KAbe}vF@U-7ZolnHq&_O7cT^45s-pCJxN zhHX+SuPd2@m2WKcw!#7FSm!47M#%d?XJN;0$a~Gqi#zzFP#~3jm_3#geL$M)7E~j& zGJv&6T=Wr_GTTvf-cMIaHE2`e=PiCBbv(n!uW5hE>fKzTfcHv7?Zg*s-qGxdsXzPd z@x>+~9rUW$ym2COzbp4B&^&LP0EKmk1&m#Quh@azn~jWjV{^+N67PFz&8yIO^O-*n zx(0b)nn`{`K2w=Yfdy$(;7-+k)s^V)kI&YyHU$n*)7(p`PW}PZ|~)1*Zw&XFqU%Pw5|f1_xzy2?dWd-_^*A@PW$g+KOh~s z(NQHTYl8M4kdCFS4ukJ{Dv{-j^FIq2?}t8b-;uia6I~BMG~N;B5i=E#cNn+lTH^dq z;{C9~q9bUf8GO7YV*4QEeQw`39ivd-JT=l5+>XBY9?4K< z89l=Q?2x$7@b}Xa&(Jp~!dXt0^qSPidkCpR1S7v<-K7e?vm(Hz#VU7x0-Lvk0RL`V zc(-(5pwITJIlN#GdRKXLau@7DGgdEr1K<+d`8q1glGzH(O?cCtaEk@cs(v{2 z!yZ&;E*GR*3Ev>?AZ67X83L|;sA$gOL+?S`o^8%~$-V?!LgLIgmvQt#86SC= zY3renjbGqE`$NF$j>@CqW3H%w zEzQX5$Nkvul9AXOpyC9X9Xh zX;x={i0=jwNuH&mW!O8&mk#qz4dQJy&-V#0dSc`r|2(xu|K1dJnb`73x6UQ3|!UgI?NDu$2xo*?B#>R64D z-?Z2ED34BIaKlyf&-6GpZ@yMbd!JRiL2R{++rDz_9V9ONx+K${7c|csr%z!WK6~WzLSr zW5FJwXPrHe_u-El(o!JrRxK|XWy26~E`;+)NGCe)yCP+*zs@cJsYu+3XO-_fq|tdl zpC4#!(W5@zRY)DrF!IYueK>HeQWykTO4G(TMl#_BJqw4J0Oh4Tf{cjKMC^I*zOiU5=~n?LrC3x|TvhQW}&>*#xL z%}WpPo)HY-84}lH6MVR~0G;=g*%6%^($qKqt08q@D14VFTzIn>~Fnr#Goi;t?`=u$}mo{4&SmQr? z8!I&MHsWLr>sRm1jOB6p0n&e`;J^N#S$fcaod;Y&O3>Ay4lM;`v-3w(;8l_9b?&U$e{nIc%VeHty2zWZrxNb`83`c_PE`l`zxw|8cZD%5mn` zwQgFWX_YLPi)aQ(uN}f{9MONvt8!J@-A^`AT5L+sK757WAQ7ZUcP@Tl{r*3;dO1UR zC}h8Mrzb|)A3t>ZVzQxSPyMdO68P5DJR|SmjZjb}V zgd+SXC-Hed%d4rmUhPI%-w}9aqy&EjNqA^4yj`lD<#`iI7|dgx{U)`)Z*Pgx@oqcR zuova+mYuAM#rup@!gY7Z`*`G>Dk|?jvkziE z-WIexHsQ?gp^jhiCxO|(VXRJb-V1!*zu&($i2dS0DO)|eTp$j=dhh#syQ}JyG0XS= zk82sr<8wJzmQdQC>McUY`(cog9m;!Gyx&|b-eZ+6v3`*Eq0Kwnsk~*KuT}*>-j}op zCEM-b;l#N|gCf_uwfQh zLmOA-D9Qe~5u0~mrFp!JI`eIB>C^Hkz?q**^_eYNWNEPJRi?rPTYTOXy64wyF|(tj ztStF5HH^Q4l*!97=%{yK`3C6`iLpH7Yjj+`X8z$VO~;5PjOIJkS42?&rZPpzwBw>Lq7)>u<^C@=@4=P7`V@7s|I=7EPffE0eN3up=-=L z5CQfs`h9poDmL#B71wv8*|R_tZ5%S%e^!Em&0B4P|8lB5^YIR)<9YsNI{@cbw4D|muPX~AxxU)QOf+vG{%xcxw{@edc(eZv7 z{oyFe+oyu8g~fZk{C?3jPn-lFJMcYm$ zFdy%1S{{#Z=BLP>*F$!d0fM$0&m0}W=Y6Et$fw@V?!I%6m%Dr8NTbesZ#? zquSR6Z00OZUS^p9EL?!)PF7vkE`FZ1!Yx3W2t-fVrhiNc+1 zC$~x-|LrY>1WkD)ko6ZQBchDuaW(1E`6KY{t^dCNhjwdB{1f*7igY#T6<72ov<7iZ zAd9hTQ1-o5hQEmyj6H<|YDYrj2u~nHUJF!d^ixP+YUBej)Sq z|6gc%;LVTQ_uQNK5eZ;9BczbR`4P9DZ%SLQxLH;TC|Z3BIsO#C|Bsd0R_CtqmgW2Z z*m%bBNHXtypAWx*19>aZ@qW?qYY64Nx$TiY7Vk+F;$kAa#C}E=*-&{uJ-s6#6Y}nB zi%1BmafZ+LZ?E;`O9UF0>_Q5V_rSW<>Q^A|zIToD%|1qe@_;pp+Q+eZs}@|m^e&44 z&d|oi1hn#t7Gv|aj^5sV!kPJatJCtpo8QtDLqqr7l0ZVj=ANSwKJV)>yOYO97K4`; zA14cr;`jeaOV)idpIOWDD@gCxjO8J4`B~bl{6D3H{EIIs-mEfij|5R3Qd#~~Yj z$h%c_D3r>3*}Rsm@sPJv<+CmIubqL|$Ft^T!wF#ARi}d5Al-McPl|xN3ojp&dDj*J zTyEWQ(v899JaH7u9tWbM0B4H({E=JdEb_(C+`wrsMtmpyEFV zq!Fby>tXRe7dyC24DvSg7)qh?KD_h3%2vo*;Nm5V2_Y9yZ16jo{ZRrSJF~S>x3?-{ z72jGw-rI^TKO7DtgI_26_xQ}lZjfAr>RurO1TaP$r(V{0#`+sJ?_=xzcekHqKHhG$ zJn-h%-jV2hOHm4lKUmHF_%=Ro#Xb**bK0M7aa=Pw_@I-4{$IE(tkATJ^?7?UmdA}H zzOH@n0e!eQk)z}N%%tm|ueVNwtyqA?J9EOuT^90=+}m)5%G+p(LXIQky|K)xRomPJ z5S+iLPQ&;A`_rHMYC+!b6Sa#ZA@4J12Za~zBm+ZV&d_#cY~FiUM-{ymodxu0opFZjEFWz%YD;FQ#pBQb@~yFV%TK-Mcm%Ff*`2U=wD z`~O!mt1VMy`&obO{n(75JZ?rtTwcBJzy6OeP6XV!5UCtQ)QHd@fl`Zee> zV|f$|Po2Dc^3Nq!g^u@|7Rdu>gLKmC-cl^y2RA-C_y+P$Sz|__^1iXWp&}CURwO?) zPkZVFri~YQN$*bt7k79CP+xBWY@*lX;Oi~@r9H{7OUR%liSzm|A8g)g^UWUnt|5SW z+Bku`vlU~1VDsMU=kzdFocS)X8nisN;LK0f*}`&5ssyOe4&V|H9>nDxUw*l6CUhO8 zarBTncOicNU)|oecBdO)`4wd0BgXPDGr0W0@bBj>=g{$fefFXn%6s1QDMKvYxj}Qc zeT2L@bU1sdy!E~>v`B-zpX^?-TUyB(yxzXYYR!g3P;YTkR~Yi{Dy-{phrH9C9(y2B zKn52JX3vy6Ve?K;)?2Y^2LYU>jhk8HyI6e;oA-~GBJu@B%*T5_Ef2i;&3BTo(Bqc` zKF=4;3R{BDyRk}HDA#oz<-2L+{fjaT^#AFnrz36~u{>`=3WIs%Enbl0_2=`J%5=Q@ z;Vu!%+wEA?5-i>!8i~QfkoR$Cu^&|4zj;am^C!@Bc-57gVH{5E^_?k@dd z%*T5-Ef2i;nSahWG}}lLY;xc7dwU^1?>9MBPL@*^KxudH%Q6rA28ob}xNE$yW%v+PI@j z<()GBrT;HMBGwPcF(2=Bv^?vR}AIB@Y zs5OY%|LDIEwGXF6$e_a_)8oub>^n#me!5THmd=nK(8ih9wp%15W3M1V z%Z{pJo%~GK|6iizfj7S^nqe!pu}c6#k`U;vdXHOE3JZ0+E0UckQ)Tmyo|9!@1xfj0 zV;A<6^)Ino7|g?L;63dLQVlxZgEzT?P~J*)$_N&3x$#c3ddNFvwx%wX_j{pS!d=MQ ze%>L8t?74eE0?Vh9hX#Iw};iC<&;n&%a~@dFu}-@C-xV zlv|xewLxScNgf?lUx3XUk^H8){Ok-#kTz~O$th;RO>Ev?mK@S=Oqh>1k(LME{J1rD zUfHr<0^HQv(|BqHKJS$9czI5j5K6dCW_Yy?KJN#4?e0lbTqM#k(2OGTOM?l-&}9>)5=1 zY`yk2X%F-9Zl>jdH^1*)i}ydcD*=qV;zjjB@p*q&R2$QF458c#s2%k@$H2{rN?*ML zZp|#un^4GL9&a-eXrH%KrQtomhhA@9Y(OIJ6Rw}LVxI05L88xXY~E~+6^pj8 z6ToZQxX=?N=Ne_Ox3{cSCl_r!%6#|U*lBrK;>^#P^JYmyFTn->9YJtJ@U38{V3Xht z!SjOof|-JQ1-Afe8YUN z`JV7K@>TPd@g3*e&r`uu%#*{jk0+8Rl*g0DmdAugpGTEPiid}Ln)?fPA9p+V9quab zQtqSN>D?YYgkmvGPHmg5%SCUA{#z2)lUYT~-Vb)GAqE0b$4*LJQzE@v)F zE+ek_T#8>pXNZoF6!!aX#R@#d(Rdh!egZ!WqH2k<*=XEvGT39;XVY1Sc19k~l5klBFzHlA2^h0iuotuEu-VVh?A z!q&&u&US~bimjCGC|f#PG}{(7Up9L-Gqxpc^VsCr1pc@6F{|Q#zyJ3e^ZyO-vlH3i zo{*XsB?S=q(8%+M;58yI8hLnb^&#@0k-Pr0J|Z_7x&97MBXXgU%M&dQA}1O-m%9}Z ziD=}sv3iJzpphdu!b#*nBL|^yF(Nw}t?zwrMPx%GyW5EfaTXe_BWt`O641!jtaBgo z8;xv)7f_HHG+OhXFdO-WM%Gn7%8+R^vWoKmhD@Q6rQL;J$RrwBsOr@sKhbFQs810x zfktM{dB(^%8m&rM(Ta?r(aKE=HX}dK$W%iz4*8BoE5?nbkx?`rvjWpMLMj?G@G*3}{4e|<&)IYs0L|&qi+N~E}$O|-5%~d{t z^rF#Rzv&9(IU1>~`1KKahDOR$D(XlN8Ywl_@*~}7q?p5_g><2j!bZ+mq!W$gNk%ou zQ#6`Ai)Rpdf=03(m(`FCG?F$k7e;E)h!Ar4IdYR0ss3JQB!SeR(F{*F8M%Q*(;WxH zk?UwQmG_GqsYav8U0G(xH8lEZ&c}&Vq0xj$b`x?HjmBOSL?V@F^y8A^LF5V=ecye( z9jQR0(KQ~ckjrQ^B0koNTtcJa&s#c?ay0sSb<0xZA{u>3usw`iK%>uVzL+5A(P&6< z{X^s&8d3M#kuo%*Zcid-(TKX6gOs8XwfRNPpb@oKKuXYv`qUnB8jYwAIU&VpM13X% zIfX{lTj)p;8d2{!A}7&^`tBc6h(^>`rH}$NqP|&zHiAL13GLQpkL_Jyn*^frlFR>#Tv`8&kT3C~)jYf&@ zb_o!*&?upC`2p6WD8Y@{Ip1wdcrl5jz-i2fsr&cqMo0Mq@oe^ zxJe`hji{&dA^Xs%e#MhmBpHqB_-y!)Bs99!eUJ}HM5Eeb{{|!hjc#sfJdebqQ4L5H zL-wN44MF!FBo2+L--Y`kv1oMd#)%>%292s>@@MZ(djlsuU~C75{O1eE~&O70ce!FJGlt)N245@f@O#w8XZ=e4-j88I`s7`2jYW9 zS(O7H5N|X(cwp=d;)O<;UcKpvCmJ1?vr+}|K%@OU5;=%F8l~U45QMm)QCd#jQp6RF zQn#gzAuec?Vqkg>aYm!$NefTJ35}Av!+#@=Xq1?@YYyUoMhT%|$%s7~#V_jFimXSY zz1(i%h#eZmKJ!0^tV5%i5`qX~i$>AW+wu{c|K9&+{vMA2@Bi!2?LkskHRv9sXPpfn z)*fWE+NOKQ;U1)bcSN2g+=Coh`jCeW-a#sgIh>()-Vq$|jaT^6o&?OTCrV7<9^~>h zMO9+(4wAS5yWW-SWFXFo9J-T*y$6|nchxUd^F zl6jTu2tIer=JC6e1QO3kEHZ_>Kdz2%lYqSSn``|&BjG1@VvQdr*kbeUQf9a6bNxl~ zr;Qspux$IrbJ)Dw*^7g9r@-7VZNugf@yi+%}?aDvBcMIao}tG z=)qi5eBM0`voo4Alqg1Kn?J4lfzLZKoogt*uao6@KMQ0mk2%g+UI~Azw-z05>P8C6 zJNDfbE-c>O7pvtjLf(xTlKoWPR^L>5+#zp!KSH6Gzav;1kfNJjkOa=0uiHcA{n;#> zPag7KXZSd`8jyj$dx}B55H{~E{97^w@Bbp{(8lRsZF&0bFgEWai^=AF!OX{d6D^NC zocZ0`d9U&0LUAzs{Lt8-A3pDhVqZ!dNtvS6ptHZG5dZ#vY;nTFmAp?`o_FjH#`4g- zHm|A%;;1h zHt(&by=@aE%*Q*5mIvPaOp;afC*j&VJb80xcs4%ov&moR{hP|1Me{6*%)-D%*H$KuZh| zUacq}>VAjYAbpbZ%wKodfkG-7`B7+!e~F#@y597(@B)^<#BOY5EDx^`$yc&}KajSN zjyLsYAIjS!OGFrpcTVz3;S|VQXI7v&mA7i$(7qz-2~xhwcO_(fooP_*x8 zzboW@_PTh1&$(8xrKQ>bum>5`hGlslC1La4({*yrqvg}2YTCFqS34K+eb~IcH~Lxd zzhge$yJ>m&;LNWun{CaTbTKfeBcS&DC_e9azCqJDxek<4tC8j*9{l(J2||i1d-#{J zJa58E2J=V~7Nx!3qDRM@diNUTEw|)_AQtbvqa!ynAa9NQEH^6e&ca*$S0V4Q2US|B z*PTF7w`NZJP!iDmY`Vt|@{X9j_S`7s{YdldnV(#dz|Y=3^ynZqZ{Jgjl%cSxx3w#+6maAabvvLE2@-cBaVA#I#46z$-E z3@vv2-CM%sHBa43jjYd`!8`_D&N19u@@IPso}~KE%Zb#-F;LzCMP&k5ykCwxY{`PW zF9y5{qw+Rf7oz?U@^<9i)4IjX3D}8w9%vaz0*j{u!_6S?Lx)seG@Ne*2aUIN9r*=6 zPSi3}@Zvc(Z&yX6-T2xxDUCLc*Q#JX?`v${9~(Zz3cE8OZzozFLpbx(C?{Wh?j{a6 zo?eNlh{ET6ELpI^MOKGGDJU=az;PdUG4rbB_{j9-MJ#{*pXYtX@+d9Mn{tc(b8|wM zjyLuBB9wRYyhwg5-uEAz5zmFZ)nqw*fP<;C>{^5z&=wja6W2p+Gh*p~S!2{^1# z>80MB=+<_R8-u)^3H!F@Pm#f<8$}`cUD&*B9iC1eoth>E)5cW{9oh}vVe@`FVR1vK zfcbc@q2=)oXMUbbTym3ciGlbH;YvTw;qxAjT6buaSBKIvXyKT0wi%Z<;c;qlX&LLk z|4)cwERVJ8LIyeD*<1hh|E$sf8`9Mv>Jye|4cb<|L<*}0dCF992E!VpyyR4a1*}1* z?2jK@2y0MOb9+OSksH`>8>u`bnGD>{yGT308nkOMC^-sOkiKRm{^#aL0uTEp{rB=g znE!VgVp8}rMadY7cH;j z3O3tN+*a}?gB0~Iaz2o^xqXwmnq(b(+P$KhfZz8t9 zJ6pcK#`3&fO&QDM$<{}e#ea{tTujHC`cenV`}M60VpzN#j=DFJA@Apl)^k%EB=0)y zH$jlM)L_nOvji6qB|o+zl06x4nA&~{fV|sXcXH)G-u6}xEn{TJV71|4Gmlx=yo<9! zCi1hVNG7y#q={*+3oh8arI#%1S^=1kcM&ZQ8JziDcz1FoX+#t}-5u9`b`w5tll1ML zUFoX<->XlTceOEaK>FnQ=VBsNEYF*e%wQhDKTK5r9&fpbjyLr!C6xE)Z#zV>cwg8m zs}lox8=QWrK;`|~uJ>00C93GA~^-@5_w_I+SYN`$-}J0`xX zH6@HH7cev^>Od=I1NZ?`v~a1h~vyorP?Di(6AZ zpM14MPa>4^tnozX)cYpf@q|FPjXw=o{{!iS*)e}$a|u>CzQ&2ll_N$FUWh~@UCA;i#);FTXhQN=E=Y(F=_D%$opb$YgZNA zVqbf2ytw-o84Sor_f%G4^B!yad8$lelJu4~?&q?vvm>&wdF!7m)`@IlKHfiQc`U-2 zUrlb|>{kawfd?X?dmsy+_hL@9#I6}#P#W(LzE&T9drN)Q!9$7#)hxe)Y!75C4~Hkh zQOs%Qu-d0mb(mWyW{P{m}sk~nd z{!o7mc}KtNoH$qN4sKlO>Z;UE2Ek_8Mynz3(}Tv9p^*3eTuSrWY%*|9shGA+#^y~L zlnGg#3~x@*#<`B)duf?~&3jglwVJd6^X=ZEd9dTmPj`G&l*dpMH0ByFb+5kXh|*8n2GeyCgG^J1J^5%isThmdaQjYb~ZCFYNildnp}n>bFi%-a<1QrLlO= zd8AkB2YI(inO>ms24m9dYOw!z*3uM8FLeXw$teLza>-!l?3(7akazXs4vpV%?cLy% zpr(123_jdB9=_lxHt%_z-{d+B%kg1 zd4hD7Httx5Zmd!i_9fP{@`H0>F&ESI|Fe?+=HZ1iKal?&!S#pD^As#L_^+3#dik$L$)BY4v~d?c2OTo-!{*)gI!RJ*@p&Kq=5tAxe7YQkbafV`VC0wt-uBZZa2iXrdkQUi}eGrU1h z%f4L|Ta$s5Us-x07(uEyJ(lzD?ot)>Y3uU-;RFLOP_i?M^oX z)qAN++`yWfEYF*;kg+@z57ezG_}l**)A6Q$U=rp1J0M*Vi}xCy4>wmr-ZkwvwWz$W z$5fg;g}hgU4kiVudxPo5?@y~XB!iZeh^M{lmdE3iu7u zvAOdN>|buC7@j`4=Ef-g<1H)CFW`RBEY0%$Ki^r#@|a|69w+>LyamwlrhYLMQ7P$ZCsD>L(V7u*t|FV9^4ln%zV6?Xn6$V z%&(4j$|L_htlkA%1X>O7dD})^J>%EAnbPl(a_Q?42KxV&fp1NlFR*_9U&&w|sn7Z5 z{n!7qK=Ti$2v?BibTx?j&1kd+4T~tv!>U2VL+{*VU=6a7>58WI|CbCdNtSypG)^z& z^c^|x3rZ+Y52nHzbm+Te;ld;MEW()Aj#$v^?8~y_SlO7*u0NyI-rwjH$m#8jgwrISf9KUo44X)bqQg9=4+6S((=HYpKHhQD|g34 zfb_>DjYiM#d8>Cn@-V%#k@EY@&TC?)@mG){qANCx2%l#82C3`1F++JES^LL};3Iah zdYjSlrhe5Q<;|U1t%k*0J8pr&T*&*>4sedjo0vFa{Q>gM{BcWiubMBAU%KESS6DK5 z#9z^RAMzgB{L3luR4Ygd((7rOt!AZ**|iQ+YR~tTq>d{r}7T zyPv#m_W=dQ=9YEjWS~;E%J(MZJwIo?k6&>sP~*=$-usaZ{0;XQhmB(ME}BziyRKk@ zNy!jmsTvzp2P!ya$Sh-@w9emzdAxF*^T@Ipj z72T~Gue*nPGlP)SDHpm=m*xBa*l5P`SYu!rl6?42^-CQi*f|6Rd zbs+D@AA>uoyjQua9bE-^U)yqX&zDU;Ag|DG*AS@cRDQ(y!nm$1n*Dv z69uJTm4^G9@Odwuyp(xw{YJ{N)o(su^Tp?Ff970H$U+sCuiiUPGL{GTq@~)a6aPK` z&k`E|a0R)Bt_D$0o4lU&P&|X8szxw>&xSw3yl|>UZ9x& z@C8?Pm8C1f52Ptk7U>8peWhHmxze(rpcQEMACwIrj0E?BtXENHuxn7;BmJBjkqJ^g zZJgJ;SqtNSVAr6Y{L~9`9&s{V|NoelM;FfgzH)or?%faHAl3I>x3UO-5AxSy_8`r4 zUy6l-#dBe9{7>xUG-!Q~`clO5HHhyHV|mzzsA@g`dxO-PjyLrvHI#R6>a+P+yk+-k zXS2gg?1e9BN>twR!Ga0TA@9^XoqBA;zJRAV=4vfpGU)G)S%yH~*6U^^zJt7P^!!rZ zLx}{#Vt!AawPW)Ry>M6Kz1{@rBW+wqPq*^9fB8UKThnsa%&*MHJB*gcL!9|($*UW3 zJ`w@@Ghd#yiN)t#AlSL~>^@)0@%-t&r>F7n{}Wyr>gcJSWqIC&9>(%;?!u#kT<7;r6HBK&V+!y7VQ6T|9-l=dC(X17}b9@fe%P8 z6AF=Najb}U>Ai+8}Gw9f*NcY8~SEtU7`9-YWM z$U7)JF5>oUUr?dTxmdIzJzux0LDm zI-65Y6l2qrM^g1o`2BynYnzvD8SCF5m0~Q9NGsm)jAMVQw*?(<>gla0Z{&!%CKm5n zm7l$0koWj3uONEf5?j9McthT~VO%;2khjj;{AUA@cXxKi%kz+TXNlp1hGsHwyxGek z*@L~k^(y%36FJcd(mL9>{r<%R{UO-A{UenegxZ*IaneuA!w+YER>>;Sis7OlZjnyI z5CNZe{$>HMOC&pr*~kRYAIImt&-pg#=NBE8Uz}`gs%I#V#m1S(ysOMLsHApjwe=$}KI@~B{-3R;s>ym`b)$kI_m6zk72QRVVK^`sZ3Vgwwblx+& z{F1=1mqxf3Y>;{{uCm;7v=w};{PM}}2N`Vp`19=zLF`NHjrLuKZ|@r?ZK93K-=Y=k z5QJTW*8HqN8Z4Nv23@D+VTCh4@tp1-4XGkPvTf+=s#g4OkPsVp>%>tuP$oo;tlu&6 ziJe_qM(^t?SpO0m#9$uJZ>OmJy@RxljyLr{c9i#b zrsnJ`LlwwrQ3{GX+k{%oA)B;k&oBv#z`M(<9Pb+-z)zY-fPq<3qdUN@kaBo z#+jevESCpE#UeoFexG2oJ3jC9vny0j+4@mpZRBDPn&3aZ)y{iO!niDt<$2qGXDpAT zZ~9`({x(Q9bi5@+PG+OLHF|gHVeytHvDJQqyj6{UcTst7*>-i_3dlQejd_~hj4!Y^ z5ZrVVp59t}#r}decZn#!%(e~N%-%DZ+c7~u1EIqEy)W#>m346E0B&dBL4 zTY^t&>g2Hg;zWeOJVYya)&DL|*3$77A3D1b<$Yu}Sb)X5;fnFQamc%+%=H_U_cNsx zg&QI7-i>qj2~GNf>^iwqatNWI`MF^^nf`HQYX!<9#)JOroopkM|%g4{x0L73V}fHoYYRrlyY-G<4$k z|1vA9-;hoPQa*#A4x z)gZ+j9xZAOl6#{OI9%sJz^Xyq#BTX|Sc9%V>Jy^YpooAyNyG3Nq}PD+fWul}Q0M%} zT5VPmP_VX)Zh|%FNJQ9|{zI+c{oFM1?Wf4#bzOhhx4YPTkY9$kTGW+{k@{%kHVFhY z`)OcbVs|-{v`>c;neP7o5G{`#IP-Iww5@G?A`E_gm&l8|I)GVgQBl1g?Z1WW-%eS# zBqeD|2Y&?_lu=Kf>C&WSRPhyc;34n|I;8j((zW<$Qg@XV#7MxmSXW9OsFil z2YKgj(9)#x4mm!fbq(@1@2Yv}=->+$T&b#Q;7tOGOE2-2L*CC1O6n&ah95|Ob63)2 zHyO14YB=t89GmyYW0JK+m&Zu=Y2z{sP19yeVe=lVx%=(?PUhqNftJT8&ir!UXgie4 zih!E$T{~nl@p&%}dgmvUv7NHF?1A{y=R3In9SALb<(Jj}5A^@W4CWzUK-T%Yf^?wc zEl)D4L3w8>oHE4X-L(F=)kDZz)Jx5b$~#>03UL#a_nuECw>*5o?AIN?B&CwTTSpDv zT*$jOkf%c^w-v1Xyy;N$oJf#ST69Ku6?TJUn8DT>)i6d%rH$)%;QKJR1)F#4$;$;2 z`=&2*|T^CQQq$x0+wL$9!npnegb))DN*yL@}93Kvz`a? zCN6K&s@dQRuI606cT6=21WqjPih{gn94t=UI?@WB-QT|Vt!yM%thQYHUwE(oxrF@r81wOdNy}p$&is@tvs1FJhybBGA7U?k#P9zlemvSJ zd}9OUPQT6WxBKuLqzByBp6!!o{qz5P+p8GLqj2&3y|?53e7$8o9dFr=%W5d^$BXm~ zuy}{6#d2bqtE-oN?Cq;OOE|JLwT%NrgBX6 zz<>Qe+N&}3PuTyv)72o=T;&7Q8bs~?A8ha@V%4Cv6lbA)Sc6KeUc{Nf8dM87ZjQij zkjT`Yir2g13tXg6&RZ&x1l|QENed`{r8wTLDKk6(?;u4h=#_+!LCfsKQe7}o3{^NpMVyB(vvHS}1W>qaid2pQAchC&hAjsQ|j`v)@ z=?av0rL!`E#XCVB zuB=Rc#h%#;)FVjOgWwC&V*@3=-$Jl?o6nz`yLIOn2^|;py5ZfD=h(bEX0GiK1s#O+^CVwD zwoS-7z?}p*k6Aw$gDXg1wy=a&$oq*Nah{`? z2H(Nv{qq7S=QL+N-WzCnjN{DjhRnq^?_z|3=OS6>KyQ5B>21AoveEvO1t(n-_ix0n z-oqO@T%w1{Sf2L-CC2htb^VB$?%&;87dqa`Q!45x?@#`>*|2zn59W?nAn!Kgj&3UN zWgmvNg+bmoZ{I4P3HAkXDz-xV;LVB6x9^#Kg1jS!$18IV!tJe@Ni7a-GWg_FKj*kD zHgA{TyuY@kjgioC4s*7@7-_}kEknHc{+b>0@ph!;A%!zPy|&4cUroZ`K=%t#A0vF; zzC71*7bf^qMy2n$i8eLhE=~yV#SVTUl(IZ;!fOWec#*tc;cxYJrsJ*DSj&&{CLYR| zg~fYnW=HZ3$lD^wXpG8RUs_^jHsn369Tqd!+!xI6J!~;No(Nv-{u$E?d7CWr6*`jD z3a;G_wzchr$6InVzc(RZ_y2db!;H&MjFHfBLgf#S%{9gD|97Sbm+1O4AMe|=JhtP^ zkNc6^_>)XwaKAP0a^_q7-P=s>?t4DcTPQaD+ZFtN&VsI6#LEEI~ z%x-}-s3a)ruw~NrV;XFbW=5MU8@V`+=;U!b*(%8pl?%l&3Pgp1>n=Ed``j^-aQHJt3TV!`U?#7?~-5SzavOSrZw{Vj*u)hwEI_OYF{brH7wG-sS3j`s`|cK=szL&O?StKtO8lmram& ze38tXmVK?jsLC*`JwFoYC10CvzlY6xm*T*P-itBPLfW``m8b464r24>P_&bHb%yzP zZ=>bGjx#?ele;62DIy?z<0Z+|0DRtethv9n#q6NS9bfoa&l8`w{LMG_2LxIF^A-o9 z8Ovj4|G_M=v_HJP=y=al6#sL2D|PpFj`(|SEZ+BH_Wn+WysPcjs8f0Sp8ME240$g~ zsQV^2~k}|=hS2K=C2>D^ntw5 zar30Pcc}l%2~x$nelP5qkT*9ik0PA;ebQRHZX1s%Fq*qkfol~$?+Cu1EkB}nP{{cM zJSGhctRT79dXoYQS-*M{8O&qXx|g)mTRiD_tABc3h*odCf{R>OyqiYqpB#X^`R{0$ zQ+ZGKw|wJ;2c#X??D*zwqc1pN>8P|+HVMr4X?wC1^1k_GO2;%E9&afpAiVQLB*+3@ zip%d}^EMN!BF%a~MncCWtsA@$`!63zt9;ntq;-k;s<#O(j|!am?Wmka*e3=7zODK^2>3I*WBY*9@>kHOZo!VgzdDkrxUabOow`5-TqGYs! zrJ9rH5%}zF_LV5^z8385t-9#$hMil+NQY?SvK4N0usf-@dfgZN?Jd4_9luA|w^0aPAC_J3VW4{J8%O%&P*}hJ&jbwRG3#wm zye&Mv<-h))iTi$ZYOwzgq^m)C+k{V}HHhp;62YoLaU})4cCZHZ={>Qb_W$48W-J!L z6{O&!;=ycrf8chvaYL;ae8n!cSjlD1SIU;|8&-4%8l(U^-U}>hG*RAP zoP~w4c(<=wrt1oMTWdCKqVnENQCn;edCxf!yPo}rADF*iKKYnO5@4@%EvJhI!@bvZMv2Z zHg5s5%9R1t%*We;mIvPaeuys+N}VSH1Q*yXmm%WwwtAt>6ESNqWn4(NTeg^i734`v zb&5a*%U5s0DaP{P{Pp%y<=^xF{OEY=aO56Ec|YJR7r^3u;Kr-oAjmuW+?}&j-Zmrg zf)^q0{W;U;ucZ0`3FjI~#5oDf4Qs1>4jUxr)h$-r;#xtKoo)1@bO4(rBjgmW~-;R0DapE3_P3|_)Teg%|({yO;BMlk6)ID zHR0mqzy2R>vYGfN?EgdPYS5DK01vbVO&Tnf!m2@!GfS^(!5Rd#2d}JzHApUE{e@rf z9i)zT!C&_k2Y}%>66{0p0qHzb;k&Xb@CGSCGjvmEE9lZ`pY3*l41RPwgbCDOH%R$} zx2c_RW26z3IR}N;Gaqk7S{|l2 z^V=WhWUP2w7_`@fI~rfX=RM}GYP0@e4CUF}hui|Z_-~LB)T={p9PnfP2FZi5Jd6#O zREO37SwRNV@m?$t^XL2j)cgOr+)u@^cykj2)*3 z3&V-{r?))H%lsJ3^^E0tyMAXZ4>>lnrQF{aq=V>q>%Y`^fmUx1?J_Ye-gDg}Cru%5 zZ_gYNYJ(Kf-SfEw@_uwC4t#I)2UX%_Q6d&e0Gza~E`z+6rN4-7+|~;Ec=_k{Oq0P; z$B}AV4Q$?q&XWT_VfD_TjXU;xmT#>RHt%a@idK>9n2$G_M>Wp;YFk_D0-p*4ne!5J z=11Z44iiycCMz9Bv3KZbemnh+=MjfRKw9r-kHY_tdv9`|LnZSz<1bFM7QZ(QIIxK2d5`)r zmWRolrk?V&|GxkKPkCeJUtkT|LRW)G9yd+V8sz4#E{|1%qGa~SvBMg)(P)I1x`K?g zt^HsP`+tkyE!WTO+yLy>U0CH3mk18cYYmx!{lC#UyAX;;D-fTno%BUD67;p6>aMcI zu0dUILrm`FjFEb2ow8kVm?o|cT|u|&uD_5Hsq$jx-Tm+J?< zM0u;OoR-7leXS`!m>2TCMDf$6@>YGt_9y`I-kw!3yhwEe=7^gCKCOUjPgJP!+-ip!fI=+7EWtQhXWx-e;qFU9@ zOw#|XAj9Z*8?pDDLwQpQT4k|#C+OyNi9+5k9UeAR-g(!IF2+ONd%p6=NH+(9hFkHv zJ=YRJ_qJzJxsbO=^&y7{|5k93xa_WjA{or7<8U6f#OD1*`IoOl>KI9ZHqI+C=#d=> zoA;^BNoj$8%*T6xmPawp{8s8E=nbA01~x_gaXVb_c^{8jaeQ`OBIWk4GVe-8PH(Xn z{r1(Oisg9|92m^whB89Eg9H~Ro9K8iZJu&Ld2<{&EQ7`S+{xOFa*+3nec!fHd5@i5 zQCA9iv)7jnE_M$D-bZX+E_s#+BEFrbY=FGkujU_1+RzG$L)N||T_b}Ceh0#~*Vw%8 zI-G9$lrl!zK^ym~&q30=7n}Eul8tK~`Y<2wCR!eN^Rr2{-8nZz7-X+jDJN**^A@ko zNgO*7M-d3KiHqaBhr5`Gy`~}Q0}NRHcuPj};5JAzA3OS|dWX{SHY_Abp}dbE8>F## zA5@e5p#phZ<^^U`c~32TJJAh!+blb$GV&|{EK1k-rp2BFkb{MvjUeyAJ&W^AH@1TF z#3(I=dt{&&ow2ED1e^EL>h(E4VD;9ajVqmC8(cAp&07UAL5i7>_i|bub8+VPIV*~D zL$xr7?5rs76vXF!$h=pBy#n5Q6E92d1o%&H-Lyvb>^*Uhn&9Yjgj?)g zmOoFt>InkU&iBXJ*b;$8;rRh+Rd|9ldHUfJt5#4jSZZ7xvm30OE4TL3$zaS&!y}?n zmG{+g(hAzR$KA3n>h;+D|3_7)Q1%?=`vz${Essw)^UHKzzGzVpe8f&aM@UZL6XxFw z`tKHZU`$dw1SPZoN5PycLT@bXF}UEuzA;~iJ7=lwfWDt-9SK1!y+oy2uB_?KA1s}oyR?)pFQ z{r>{S@)#Nw zX^b{*W?I!f^&U3w(zP=pG3m_5+ntujS)BP@YI}Xbbx;`0OZ@6}kN0&uG#2Il;T=xL+qlPz1LbY?EmIMTchk4w zh7riS>0n3;J?}*=pOI|J2JrvbyVG#0-Zp;tn<$cDo1#=mhzwCO)V_$MRE9D|8c1d# zLguNc&?K3aq#~5DVj=T9G@yYJrDP{$=2^SezK{LlzkX}~pBK-w_i=Q;(S3Iv$9;b5 z)48s5jkkv?f)!xi5qch>4lwWYWzVXkjp4Vq{#Z7lAL9eQ?h)B&RfK+V0%}xY>)9|# z_>8QxwNrR&riae^Xz4TXfsyujS0Xu%Vbo_ZV>Dep2)`ih7+0))CpK?ph*x11%v*rT z;0_lxUvIhiU8d0QF5UCSy1C{o!+WJa(H3X7u0s<$H8NG&}y$UmVN`9 zw^EY!mE~>WP{X34n%^_*y*F;(5|zN+>U6*N#@SMrBblLZwf3Wb^FMi3qv@aU{O?22 zgZ3I`&yx?aP5i5+(0b6&sh6X9a1WZy=Bn8V?;z9p8F8cV{D1I6*O1n{9ncZZy1(>w z2pG#yba9X%LhDr(SA}eaU$NWwtf|`B2P8fcb78%N-h)I94(qSBo+Kn8>k94{xQhv+ z_aKgb<1@|&Xzvia0m*??pKpZTam{yl&@2kE{C>6lZO!%*Lvi}}Kz`QMv@_a1SDQZjGLS3{C$yuaKyyZ0%~+k7zU3yJqi z?{_u~@GW-RS#PPv&)9(#!_#IPR)hj??)IM>Vcxe^UA^~Ar5S`~Oy+Uu_y7Wf{I!** z(0M!gwr!L&pCs%+*3EW5jQ+)i&YSCcw`{T|?eTU&a^NxQ6TiuN!v>EB{+g%v5ME>R zKEOT~^yWb%D_`@}tg80hxaWBrgiyyT^{-Ci8ae zdnSR#+o&@)qY~yV`%;9Jw1bRnKeU1m=3Oe!*U&p@2eQox-krLkz`0EE#~1kQZMwlu z`-vURKun1kVyfi>ULG365v|dA?}{>eedORIp#xcW6>^FZ;z8%leCtNglnU+f)<$wH z!>G^0&>z=gga-$1)a$SM}?jt%isCmlY;lI2#sbk?+!l04QRX%Fc(U9!o0_Gigii6 z2MP~L0$TzMM zblxZPl8(%EnVx;dH3BW>`_jkJ>E7*j!zi%sl-Q%7bfAso-J4%K;!eh*UOmE@_}9=Hb~>w?gOn2n z;>|$qdiS}E1aBa8VcJls0G;=zCmc4+_a+I#$huu864Z46gSU3ys#_U1X^;0Hk^`&0 zL%$gEr6l0jTV6TlG(J6y*}bcU4xXvky#m?fMX4Xuqhdgk=o;R8w36<52Z~dd4@-r4H%zMsl6Xr_Kc9I8^IlQAQc8abyg6}R zHT=mx1TZ{~JI?^~mh#rrdMe!vTqAe%cRcq7=Y#6MOLw93E}UPfIecxB5P_`YReo6I z7lhuuiyxh0+!0KByq_XDukd5uf+W4 z&^9_EH)!yb?gu0#Dsza}q_1Owg+j*rVMgfC9~+F86SS-u%ut6`{m$>IZ=xFECKxjB1qk!Y&o3k8Fv zV;-H_(nKi1+4uX3@g~5gZJ1Z_-3xf7oAf#Twn05K)DC|7xi+Trm0PDt?vs;9Ss5!~`4l?}aYCW0&sU^xQnB1dc z2g!3*_wCt3biaed2~wG3Ro!igKd0C)Eur9T#O20I=I!zJjm07#JV6kuOX=Tc)*e27Eeb*Y~C;DiiyTB3>3T#E5n${ykl~G6wr8=+@Ak(2Iid;^{$=7d&{%WJ=HL8#~SUL#as5E z>~sI&oS|S)q_tMK9lkj6<85Iq7d!m@KbDi%iZ^?M{b`b>-J0mU+xudBGvLQt4k7EV zo6PN7Uy05;dUV=Fg9fkvzeaLk)#qh=@_xnwH(23ufceKNY~Im?431Xko6tG_cM(~J zwV2&La3u5SDNZB0=Zzy$mm@dWxBSPQKiwNg!P~%lV=tMvx1GjjG~Pz(qy2s`?_0sF zze&8gB-+1jgD+0Zh-F@qI1YF3z`&;KoFU-O4W?@+VBYtfWkaoan?ZgDK~wdoH^?0o zzLLp^KL0CSi(ECwG({*t)=5V$gDzb~pa1tisVrDGPkY^44atF3pONQ$U0VPTU~(O- z<*38HI3ZK_{dYU-b?EnnDMDy2_RWc*FO0WFm(l;Xw~H&N%TXQl%c?i}-}Qg;tVYv6 z;X^DdMGvyr($h!kL2KY=keJwy;m~@}+$kMbDYysi$XWGJ9qvJ{T7D||@ch5#(RzaZ z5eM+NVaQp)DH!N)Z_yu;AwtVS?kp>)X#%}E1g^XvUhs?3eO~_@M4$iPAFz$_FPkC| zkabf6$)a{!&=0Y7A0(QY-q7Cs{~5`FRUgwS!!G}K++el7^|Au+6Z4SS{BDhrCsQ)? zHtf!7V*Lxu^*H6+c|R3H`X7*_sm$RkGqwKj{Lezc`|zUMMe-r`u5P_58t>b}$}(GE z-e1a0+ey4L>Nl1b!MwGs>V*y;Z~#@Gm{&=h3kLJ0TP|3_yszaFwef9DU}-!5^stFH zaDIB=%!ncS4w6$#i^2Ey6u|>ocRn$dqaYofcfb-H=qaQ<-uy@otoq_3KU9s~;RdNp zT%{IEuz4??wA=S4D+y}In3o=($3Dd3gx$J_gZt>7cOVaSIlil2_qucI&kk}K1#h#L z@HJ7mdy}3Zb&^U@LF4_HV0?WC%==xP>2DHm_0G5*PhsBbPtGX5+u;Btzw7tgTnq*} z0mn>UZX!Y-nO8lv>}~=RM+rN2DtUwQuAOKL)NYPu&vfD3Y|C0 zjBnrMP1@r@cntc<)x(*yiIe=Q^>rBwQQBqcw3wg_@E8**0PvbMH-Oa_^;P~ z2J^NgFtNKzI{?$Uy;~fUg8{*(OF|dsUH5+b_>E6ZzccI@ahK3}pUYaQ^xd2Gcn2Xlu9i;1Qi!2w)Qm{3htzP-Z*M=oY*J(_v1vDm??Oh*cT6zdA9{9Y(wK6H}Y$P zKFnKQ;szk`UVh1+k<`8Qqvho8@;d;rq9vJ(1;M~Y>f1~;eC;hHRk$$tdlO(REbKNH z_Xas$Utbx@pz}_ZiE27(Hbp2z*7--5R+n5u=PmNFHss53+T(o>$$?ehDXBsm4PG9w zvC(?TC0%UZyPSvu_3*Vf)uMJ*>qYE)Z=JtvyQZzKL-(7LjA`m}5c@tgwBGnP|I_r` zPc9Cg|2Zgn&^P*X@$2SX4Qhgip)L7kRw^nVYM50yD&!;M7#&j0KbypOL=6(jSGj}vA_PGv zpP{DSU}fp-2f-cahuG?|0F&@_(}cCix~L2Wb^#~!LoAo7oh64Z?eT6#a&TbOH{A7P z_wp-c-Fv1|pqCMWYb(o7KcGfq8#bUSm9x?*Q_aCkI7J z1_K2PzRW~9BJ^bi+bR9~Fz?#ho%gqTgL6u^x);`=^R5$08N@G}CIlht1_Mv0*O;L5 zwh+9SdtHY1c()=s4rA1(k-Cn5U+Z2`9^*RH|Pj&vCHws=53>* ztYoa00!6y(2X_WzpWebb>@T12{7(10aYj_;@cK=RFZ$EHms9XQV(EIE%==*FWd=0f zOS?-x2*bQBKvWosccRCE_8gdZc|OLSO=uPp`F(0Q0ACYw*@|Ij2KaS3O@#QX^$OYP)|8F2Uu*D>4T ztN-SITA4xrvkrI%$wSeDY(;OZBln<;lzl7EdQgf}OJ5~C|N9Oy2$1Ig$?k!5*6?}zqD-v z+tiHpp6~GnGKa!47r4<6vDt<49n5#937e61KYUqmGwaX~v9hh1d4fM^ZwL7V$$?d0 zceHJo)+0Pn>-&2Dz7sa@=5u12sjau6H9y#Y2##a#AOqdU>z-V7r~5-}pc8dDqSM+t zBxC;UAn_EuPgXTLk$HCtjC7x<~lXIpC__{i5l7}ylLXLTC$EVS|x1x%&JZI!Ip&D5?{*rS= z1P40r(-s{`j7_x1TNTNHRUebOR#V>;9{BOeJz~|x=DqaoVSAh1X^`W$%ul;EVDr8% zbpK{vSQp*%p5vu1hvDplF}=U1x40;HTVHA)BlA98Rm_6M``XoGOrK%i-j1qqB;I=K zx+M3*ybYVwBj)xxg5jOY(!;gz=7gJX$r6}%=F(@Ti2+SOz8qSzV~sb6_{1plWDK2m zweanrvo6zwE6BP|otws&xzKsXTKaKWKBPU~O-K%``sAi@rd`_HAU1#3k2pna-rY6) zLNnTF&^Cv{BA$LKE>7HYzR$S-72Wg3Wm1{r+_w!fe>W$b6uhmD#`KVRU-OPwhQ?b) zK>f!E%=?UITqTLOcfVAl3e4O3hjgbWvm>a9SF92y1_Ae@rO?UEL`W!je6LPq69`q& zA3hE99@{>Y^Wi_b_pN=ct~<=93A4z$vAWkUOxL3GcD1OFvb;ijyi<`JSoNv!37-$f zbA#+Gh8^2DuzCNEe?1rjUwbqCtR?V%0DJxyj(GlXZ)q>x@4bC;smqbWIQ~s0_TT(Z zp4DjjCp`ZPQ1l?@ReC<;9_0RYFE?5b%H_NpauM!9`;T~P5#SyqLTGs^2KS)rEIW&( z9Gt;TapL5;p+IoSJxAi> z1X)+q=5O?H7JdFdZKG)sSx0;G{|6+;8I1a*yYJ)|EXRZL=5m==yMAHL|K(LG0kSpe z(00RI#%YgQ?Dak((#+)obbp8qbXiMPj*HDsH=Aqz3`i>}csqWa`E&n2>Gqb|UM@Tu zZ~oP%AI8GGgI~UL{=-{X#zq0=9a-ZQr7P|X_I8}*S&It-1sY3xhm_zCq*rBo-`Lm$ zrtJ=`x^3VMp6-qD*7=V^tXf=RTdL9wp%ht1h`Q@9`4OG>-kuNNpQq6tZ-C_3k5Qk; zr6DVxS9ma0kfWr!8Jl-v;3KJ!>U7ALyCgtngo+(x&&j<9m%7nCZ(KcB43$UVkN?%pD5?>W(UFFt55PlI`vTJqi^@xHchg{lV3ySPHADe{dISY48JM{89O zc<{^hl`PD=Ft;<$SE&iCSI!GihOZzU8oi)({|)+pRC=NQi@o3s!30_NBy_YpyAGYV z8PUve-k0`xzd&+WVAN-xeT{ke1|C4FJcqyuM=P>WGo+44gwB-j(a?|5}|^N$tD__O~7N$`~0M!H(1~BeuA+Bo%a@@ zjjMjmP7^jD>(2B%y1%gzowtVihy}YT?eSJYa%f`Im#C3tz|w~Ydw;R1Zy3iOkODs} zp6`Zv`xG*-84x6W;7-yhAU9 zcND?Ahiq(qka(wAYn?j@^InzQ;yTCa1T>9i+>DL{fgi8R&OL{(y{#+#BK%XY3B>1k z?`D8+Zy^LY4@mT&^BxpQ8jl*7CTJk*_<0I>z*}_QXL?-qZ>iEA@9#(s4~+VZ^4)ig zW#GZHU!LOoTd;Zi+l^k?&yWsv>Gn#t+G2Na-!Q&q`@6d7e*X9MqAo{V!m-oeqyEkR zG(Go|i-YI?H55JQ3=j02+=DpeR0Pm^P;;?%|jV=x$r$m7Y>%0 zjc#`Vq942Oaoz|7or6J6Z`Fvegjxa~K!5Ha6{6tn)`|P`1Sx6$pQ&eB ziN>4X)8(TD%)4#L{c9xNk>3=onqc0Lu-$zLUKg;aFA~grFAxZ`8K_UI5+Rog%RbYO zji6#7nW)9#1EBPkcH$A}ybHPxcplv|OCYZ^9nIp~eGr}Z>zfLze0$kwj`vd}M-N7Q zpE{O%>O)*$S3;wHd3p;sAG>ttr*(AC8`nr(j^|6J z;$;2~NUJG$yWSm4BX@7-(;a+hyiM$inCxKQ_X+70B;M+5FCPDZc^|rbeoOp-GazWC z*v~!-1U64TnhLbux>2I5+Z2O4j;oi`}Q<}E7ODgMa#9`ugG+y=Uhy@QnW zQmDY;&(S^a)PvOJkkd>0$#Uh-+1phVyiYriSCDzz2d46(@z!A(6!L(1yF9&0B=Kh3 zaF;;<9*_*)*mp4HI)hcs?(1q^27<%9>+H2uh|uZ@zjbwsjezs!Amep*AHYx?x5X(Q zowuEBaytK-SppNXE>BGKPPYd-@3?WB^}1=a$J+_Xk%&>>`t_Z+ru6VYWqI?7>U3=0 z&)q`!RAJs%JUq5rt)pW8-zjobje(c$2P7Q#TIzDR^nT|1JO2w(@OIhN`hm>*Y>68W z8t?F>CPslUZ(Bx=Riyc!%scu~PKsWpGf41y^(Nz0AaE4%;5n;Igt*o+@$hmq0i|8b zcLi5?19^wwc}Zh*-oKu=tXO|$hMh zN2Yo%VA*|~Z@>ndx1#WkV?t*$An~pv3^Mh#*qf7KLX zWrt@>W`?^sc9G>fmsv4|!oU3YA6okpfaiZviXP;>2)U7akZ`@sTC^U->;BV+2kt@j z^K60J;U1LfcJuTBcn8_K>q%K%kqgKr94-8@F%Sgr`W;oPPK5LywqAeg)d)JWPn-(y z@dk5Y4K29x|2PM^$6F`mHUf44#T`-b(NRI-FE>U*Sgx>RRX~w zWgYt}K!jpG*e@5n*a#lur(SFC_6B=;m~Xzhh0gnStWT}omRZ7HWZk}4dx6-^=)5Q5 zc_lSxXm1CZf#krdZol%Y>l>>w{#JbltB zLifCJp;YF`V}2w1cLymZ(Rf#v1P@BXye+q{e@o&$l@rc)3g&IP z5X)5(?*cB(7iaI&4FrBl<*%yAZaD`-2BiN>5th(zHd82HQ0}`;<{j5-D~QIssjL6K7Rbyy%! zvTd4a-A;tAeqE_&S>6b;E#p7z^6&xuUXG6n|KszP4|tP!Tm5DUpOJOkAywH5m(k~c zfx@bN#WcA0&Ovgl!l;j<_-)9qDlWjb^ZCxpYq5E6x%puE*W?FKZ^o(2)*|e;x8VBB zTvW4D>3{xzL0t~RCl~B?Z2mX@)7q&2f2;?d|0O7TP{4$nD7gpe*>4a->p@jEyaI0+ zv(+6Qy-QVtdr+rht78n@gL(#B3>V5=fY0HH?W}$Q;H-9_h?+JLI`*K85yuB#AXPgk zxjPg-2f0@?@zNFa0V!DJjVb>3EI|QTCo3}UTl3Qb^-yBWqgV2H89VfU%=rJ~{}_hk zz^adJxBEi385bBT2$p8F9!Jedj&jFTWrIjcE);yBlSjZA`wEiO6A$T<346NVL7Em* zm*eVFo!M1?uONw2@b<6I?;`Wwy>UhqjrXIU>ty<2-a0|sn@PMs#Y*d)hj|BvYkL=# zx&Zm%$orFN0YJ6&W%SBjM93zrWcAd>Mqm^Ddf~GXe2ZPm@qM$d=)AN2GT+O#%@WA# zxGraEtay*k+k|b%rnQsyPH*KPIk4(Wf7`3%e2oii`r5*R?g-O-SfuXr!vRO+shUH&i@-Ic>BeiJVEAtgtbBhjrZwQzwL-H@7u{H zGbG;EbZtevNjpeqhsot|_f}E5!|&D<01m}WI8130Au;|`#Y==np!v}*LafspuS^2PS)OgveU6yn0MFe8{(wXTWar1a;#w9kBm4)UXi@CTDghlzRiymf2VR-_d#Bzs_9t`06ad3|Tk4a)p7|33T39xm)D-`qCcn zEF{MjjQY3@SDw0jo(mLzU$X7(JobRZde66ZA?6X(PS}vfu5M_7051Y5sJBDRDVBR&v z2-AbhvG?A%;NFxwTN3Dh{*R(E$AORMH^G~ef7k!X(;5x`gy;WF6g?W+4!3Dfa-+Zf)e45XK-h+y*S0#CTrM>xI z5Xn)3QQw@g&rcCqF0l2*Sbx~c3Cu&LdtL1sNbw1z=N>lI-t=Ta}=Iv%QB8kTPxscGMJ23CkT|Xd4JKa}uik>$Bg|;Sb(MfO6GFrH@yat{3`tnoZj&^f| z4rJZ2G4}RrR5qJz4 z0eOR8o3M9~GdFK<@SUXpH%R|XqAmyFVxhDA)jzzYD0qj!uURDXwl9Vx(0EsA>)+3X zdAGK;@{;ENJMW92OEB+o;O$U3Q8{Sgbl(0N;Yon#5PKzqDjAvum<)K|S~w4(n$ z7qHoAeC~V?Ht*_CDW%4hk0GHtoh>JRP;q<9sxAEizenl5d*i6hA=LIj`tRwjjTF3t ztxaUeyj4dc#nE`**=WvP2J=3DCSVtdcZ-v{&{ddsLcwq)KFbAcDcjcZSu+5vQx{(q zqeFx^CEvY#Gt>a2(y9yhUiAT5_nLnHa6!L8S}<8d$WvjCup3#oIM-IU>mK^%q){>} z`QCBb<1K{bXu_y(;_Yj(y{EXq0rncpV^^?wZxp#XC$cLKI_JrZe^yeDxtYOf7KLwf zaHsqEAGedb9F{h(!$Z^mbZ(*Mheb8M;0A>UOSJP>;Q-~3O*WB>n3gXjOv6g}u-ud5lk2l3os zlSk`8#_z-0jo==XWcsO11@1v*J0$au!ab<&a6e2mW>Z?lJl+dBU1-yK6m+EF<&;Kl(#ktC@1(0gc!sFsD>;Vav)*l2CedvD& znMz#_$&k)2xA8$GI{?ql)P;B0k#>~n;=kuYqc7|iy zsQAS0HCLNpi!Xh2&wD+UIY#812?K?Hc93!uyd#3Ies!$-z<_zFxcH1em=|K^`FsF=z2#x~ zXc_kg;4*K(u2td#tX)~W^^DMYJG-3^&ptX&utnD0yzE&u>xkaHBVzTtDh4@dZgWD; z5s6XXg0zHfoevlMaiX%~E0);28_pFRyj}YQde^>#casD51=7Is--komKhXUJQjR9- za_k;ym|cJCPxqFg;C)^YFHPoc8n#y&jkiDNlcfwFE#)x+*9+UdT(H*c_&UY1pVyo5dToT?fp4|4YF=zZi!Rj z9rUxe9CsMhodju*H#r9#$0&&EV)M=#$f`DidCPAUo4-xXx3~QF zj!$O)qI=%BFe-D@3r2|lyZ%oj6DUR*@cget(SxpZKd2@5AfL9SN@zXkQ2Gi-UbqLX zS{gH=3?E`AHLZ44TPmvC={IRKt#bxa7p92yQ~sd9!7=K}VIm|sB7RHdYCSlZ{Ml$` zy$={~tv?$|K<`0$8Tprz%jXH?b!smB{$Q&fcQH=UD+mCEE zam9l>d4%tJCcja0lK(d6Yn~^tsTM-7ud%AOiEg1M-AO^S{9bA*T;8Z*Kl~4T)OLVD?pg5A(P` zP)~S#hS`h=$t#IC1?JWRk@sti#?yR&_k_>RU!~~0-$Z>%PKcW)cp>XD&#bXs?~Hzk z{S~hfs+U81yk8+Xeq+?P!>Y=|X#*Y*N-wjkufgUWIM%Q|!=wmec7Jf&^LZ`iKZn4W z@5j$@XVCqC6nKHU99l8MdX|5`|F?yLceG2T1(|oMTe2b=@44-1v$8PnpSt;bNW42D z%Eo75-UXcF@iuPGK)O3PqT`1@(EX-X5okh$#tQCj<8G-3Ru-T0kNW$7BZ{mIqq*q3 zWmQhDba9&}SRm{6DQl)Sokr*Va7J=(>}lHLy$Q*YgHd06MO){+<9JZYwS)cg4E7E( z&RU^mBBl^JzV>!vtpzskLFVI}@2ytQ{RPtJ)5oaFF=g#{Z2a%jTZ$CCqxOWu{|$#D zy}h-;#Z3W?cgxz%gK9AEZO=_SNxYBVo#7OQ=l^o{{J4aN&R`I_*3>xQ52kxf)t4F* zA@!!6TF<`K1B>gnJ^ju;fFKh0rMLi{_vtK+)m!(?6Ugf(N~}!%LeP1u=e0{MY^FWl zE=Ue7jQVCZ;vY(;;(>3I1E*s@HgA)(#WRm#-WTpz52lsXV0Leu<6|KIik0qp(%oF z^17On;j-%vpr774=l^T>)&$z){SnFGhfyE6DnC)mg$EV_(uc)Mv3Wa3e6HncD}a*g z;zmRGuy1dvJ$XF4y5E)VHz!(D<|wH=pHk}l@A^M^R-@^ka1T?@1YuoDs^!NN&-s^*Yhz(m5BI4l{WZ3#Z}DKCR`Qu;ZP){nwfOQm)AFq>A@9OXPIY z=)MOX`$%05uSot^T^IhmVn>yNcWi>y1M&{CNxNPZjkoEOAhq`}@2;mdiX`4;?zj9& zZ;BZ>a|c zT$*nOTzvpAS+4qC8=ZIlc4_5KsRe=tvhK6V#B^g5I`8ZoYWkx_w8#4~k|P(RzHirX zH#gPcflIj@p)eVncVCHH0C!(86g>j<43A;+-g)5D<6Afpx*w3dsm#$m8YI;U-$4p* zPLwHlUsql6zo)lk3QsDd@pfj>SDS`;8(f^aLgKCZGvEdb%$sYZB=XriCs4ZoQj@Ph z0Jwu2&n`YfgzQ&;{>*l$9yE_>t}in30nQ5Fe#U5`^DeVC);3?UKyX3U?Tp+J2X&+K zt`M(2_*I$qct1ySyuhgM=Xj9q&S@@S`kQObKqNNr_7_4PHoe8r+59Cj@hLUf-8*%j zyZzW2y625cp)LoXTDZ^t#6Q>nw^8uEw$w46+`V51DQrXI{bn|O%QDjZKX#>p#Jlwr z=b9Y&?CqvL!&zQNXP|D`BJ_Ljcx(^Z;UE9ic6a-fsC96ipTdR_$ld;cG;&7%Ludf-E> zIzt7aW zy#b)qv|TCJfe6{&ZBe|ZTnE&-h>&Nf6YwvNstR#aL*M_c8G{1g$Y zx0Y3V8de9Ea0@4LS^0pMCbkEdTG4qw@)_gHtXv?xLe|xt+j{@G06OoFT$RI@f6(3z z@&S?qt3J!1>PAjpJUHnXTl+*AoA=DeB8E2JQpoqN7`QEi-Mu|(hs-@zGSdBkB-ub+ zjy-FpWG?|8Yk0y6JFjw(hp-rwx|KRanG3?zm__{=lAf%7s+#=2W^~E`#^ZB+04|+>9%1*UoA7ZcFuSo730?>9CW{f%!;8dM|h0i+J zCuH60f#s!JMA3PlHY(=r-bH)7g^(OB81*UDXa2a^#RbCR+kf2l#O5vP`i8h;dpR^> zoAg?P9sB7mTwb`;i3mQr@7}m4)aBUx;OnpZ_y5iRG(Go|i-YI?y%as@{^R|*O+N9=37aJSWc}?0q{LYU*iKxMwZ!w4xMEd3YP+b+VT+*u0SH> zey%PEJxPu%s72QUhFXHb@5-s&Q~0f zG&uhwIfxkbJs-^#U4(m(>#a9{M`a2%C;6|f>!kbToBfrLvY~!So;~&s@{nJy-f*HX z-S;5RbJXR?**G9`{O>JxdnkBkUT#q&^R`S9#-s7}{nBf-6h6ed_l$>;c<+1^_~|Xo z`>oNpuG$iN5ItX1XXzUVOb%SN{^Cc3!VXACW#-iYyNTKj3=Zc&kmS#SN3rOk!6h$1O|Ib_CRH)3MIq_`u-yNh51@C*iax=)hd%5|n?E-;zO+!!ZIU@8y*SzUwUkw;-)R668 z>I;(c*tr{I(RYxA@7>NM!MxLub>Z2EI!c<*c}pC8oU33#d%T|@Im9vQ8@;OMV)TIv zB=EdC6|fSUw*b$FiK_7msC%MT?#omSX15RgB=~fX!VM%PLGJIea#O=VAe)(K z^~9S9Me%3FZsw>39C(w7bKJh5@i$|jq$xV@2mBi{%s6qN1zAUU*pOMuggzh@Yza9b zphJ7SGm#uv^(p5{Dw|8-!8_0Ud&`$$^X>wzdGihx(DLb}dT|QayhoB5Y=(LNdX&sUn*TR?eeE8DdHYy3 zv#S<50zRg9%f9al1f2$TF%QlXA?9;APQI$O;O?`BDg2G_>8+fSGdon#d0&_J-Ul(_ zfB~{@iLLlaxkdEuoxj9yz)+m_cwa$sVAa<>$|L&J3J;u2bO-j&V$c7v4JTU~Vcv}= zKvn8bDsFFiEf#sngN5$*-nf@k=5SfmP=Yrn|Gxi6p4MpiCp`b_QS_jkbbBXq4=P)& zB7oL|&UU$RWyACT;p=mOTi_m)<(1)`W&wYLWMTLTG28|yTZ*65xeCw!uMT-TTqHuL z!k%t2_p1gmQg<^a4Sc~v(N5Q{0Q3Rr%d+<`*jRBO7g?wFjZrEy-3)c7w8}D0dDj^2 z^`HSH$4ZR)d?$ZrUC6+Lqu?0NS4Zqa>?z*ojc2W^Av4>Q4d&cboP!+EG)xRuq5mHA zmC77B+Y;jbzGCM91@A}hjhSTLQDEsxG~O?^KEC)I=B<%+I-A7%WZZA*-!Sh3>r87) z)=DEyRC@8lH%ETs8g;LB;jNtk!1)o049KS_N-oT zC=p^!%xY#|Qv=_8Cv*4nB7FAtM0dc6N9epS%l3)|R;izBtj8 z;Pi5-^jgyg9oXo%i6Hu6q0(+T-nmPc31y=5ibl<&kj#TD&(-bQIZ~mv@p`W5Oc>X^`(Sr&SZOq9%Xuv{x zEm{w{UhVe567E5EJ(l+r;U2WccuC`+Is63a(8b4R1Fb;6N7))z)j+VFm(}NeED>tF z_sjXKT@`S({*czX-xuu4DbLzpZH+q58|OcI`D_^u>_OIjJKA?|WvVIa`Zt$Hv^o5E zAc|x(@ykO9dFewm|0Q-DF^z_a%EzlV#jq{F;T40 zrT-q(L|u*p%Z@&SRzLet`zoypSTrsMwTt_L)U3_<#jWVP`*da4 z%$DOoIXqdt>>C z8e;k>Ts4+kjrz}?{BQhANwTr$jXb*Ny|j?J930|v4sCb;@HV92{Y2wt4ViZUTkC2x z-c?prM*cAGw_C5xlX%DEITy3Rr?);#M=5W~w+7-7UkuIc1Hsb1XKe?s5}}*ntxr0; zs(=BHfqxLcFF19a)g$j4I&YbCyvfg3;D7_NuA@^pR*#6z`~1*sO1=*5@s>t%gkscJ z$c8($&jEhCa?|~7+Zl4`o;OaC${eHGM1! z{q)u~6HcB11={01jO2*HsL$Pg;|D!yJg|Pb)$NBjHgBjt#&b(XHT148caRT$u7cd9 zQGc>54b(sRg8t|KrPSpJYW*zVk^QH8>r?Q~eRWTb%-g)mMi7nnlQ)4WNigsIXN8SO zytmx z9h)~Jfo-S=zV?>W`OMK8e&`dGHS!y&Q5}3Nd*tc9dzW9LE=SO)PvRE%<3#_i|6|FZ zf!~Mce=~|6^ejH3liY*m=QfF<^`NBT+9*8SgSG^+yjOsGPF=zxO;9`p-MjTCO|I1o5L`+LkS0Q`9N@o;Yn5wbgR*Go721yBnb`XPh& z1BEMQ@9fG%=Y8t!OHRX~MM4R(?pSz*rr26jRNj(@YHk_!(;n}WNRIUw^=-<@PfnQS z0(12~a*T14B95TN@Tq;aOy1yozld{CAM1Rp05T zC7~bBfdP}vBNayIy!~90S;E(` z+*45kJpWr#^q`6hJ6@4{&{?Lkzj-)sd()=H!HSl3M+=J>Ke`RvJ zavbdYmJ?A@=LcS%GO2RShF`JkKJoLeU?teRM&W>yzc0{uYO`neZY$J*$BVs}Khb@W zpoOfFDjpDyu4a+G7#_n@Zqyxs~tsMT!sUh@dM2e}_# zlo1@LgG4=TRQ=kh=s^XHXLHxBr~moCh{_y?=K_%{NJl7mmm9QfBJ-{!3`wH#7PY$t zUc$WjzpT|J@g5n7Xr4c;s4n~4{PTlz$3eb1XS6h%KUj#|mM{Ad{=^QqxVO7$B{(zH z5h=^+2kd2fv)CHYc~58xGG2~`U$KL%Ta1j0tDQ&ZJu%FE;i5V1@g75RjAGQ6Efq5s zQpW|%zaG94b`P6(Cx0blpiUh$#n^PDgAMx>J8q{=<;q9d^v_$1x*VR{Sc6$J|Lh+kcR|cT+;JI2vy?g7UXtFmJW7^D!jeI>#oh zT43H~ntA4IhmM22Tq?WN^8G>JQ$7EC8Swr8nVYiXJ1fEa57h%l;nQ1!CGUslh0q5i z7V&K2Si>Sg2wAt$BCY#~D?0DI-@iY7+Dd!8mm)c`FzOpl8w)*XhzF^sHnOiz!RF00 z|C8bKKrJMg7t`27&DUFEmr6#jUPk}j`x=!wToh_ZH%P;K@52^WHr9o5{X&kr0clQ{nlrQaJ#fxA8(}?uY>G@s>k!7-G~H z;25^tni&tq2gmk1CSdbk$uyO*#<&(b_3QJoLmRQXxAM{cSE(OE=$`ji3+i&nT>gHS zIriW6|Nl=1&HuOmXK)X)qUb@j-b%;GJ!r*sHhHujG{MPS?*$)Xm#Fi5Y=(Q#U5$B0 zJ9z$oz3P^Qh{XxeWwiNLc$zQ37xwN8FD626b$)~HUFAS2`W8p}Za=V%?Lw&ULMMkLWH_1;*pL|VwJ%|g*A%#)jF&Fn|jPU#a)b>`zHCRe9_l^!Q_M+F+CcPEhc!*>lmA%sc%3 zds#Hz4^9ja&%?ZpyAH;ZcuS?Y2b;jWv)4ZUvT4%^VEBN0&9T?MK<>J;?U6zv)bO^i zd0e0ZC`OvITv+P|x+d*@eJ7&x-hHg>tikjGp&MCu5ih1-*^kcqwZ*cCOXal3dl!@7w=RhHV~>If;})l$l89HWUq#RAda95;9Mj8^{n94MZgwN}-}i zwp2)_42dSGl%kU|l%an6)Y+fstlxU}cb{ji-?P>^zxDZxx31N?-p9+e@9VzrecvNz zonmE~zW*oC>BCVyQ%a%qPyg>kgZKSGr70BeQNti*EW8ET7N{2>csuwQ_EYe#O4cLK zNAPYiTcDN!JA<6_58D^oM}aqSq55CS$uMyuebyuE9tcP|bHmg{*U*jNJX5-h{VyZx!< z121H8f-g()cxWpA_7>@;#$d-OS*EYvTFvzN5PkZ>cR}Kx?Jc`#@UAZ}S%>0n{AHaI z7T#Sil%gvTyrL9<6R_hWHj+GLVW~ zKWF16x4c$Cz*j9KH(5$Q-ir>Fh;awwZ*Li|*|%eMPJ-$2{s`0QV`0_}(`*0s|Njh5 z8TlKe|M#S+L9KhrtXG2_)BMXHYsoczq5UfsRRTM(QIk1N!@jbDQ_9E4@coFBmo zMh7GAkK@-M^@r+_(I(kUUxRoX=<_kW$!n?Z-}nDLXz*?^IAnq1owK1w6ASN`3zJ^z zBY4mIe&PoOZ(Vb;_hAI@I*sYaa<#ibP?+ZKC8_&CKwEeM>pe1jtH8Ot`~nQDsy3e6 zPl^PpZrwvYcG!52N$>3~K0ZfMp~lUs7Twa<#l}0DGtu-#1>@n3`iR8IZ(Do*ncszi zK==^9!HQ~pyzAec=zNagZMidk@iaY0?AQ)`xHp^6^mr5O==AaU!9%sb{l7a6-jBu3 zh@*IK8!FJi!h7Jym$pp^-q2j77-a;xL`>XwAqq65Qd7SR@&MjrUTMg+GtpnIoZbkE^*$6?bFfU9=)f`Rhf- z!+QzU$0eNn!oxfL-#H3`q~Va*&3EzfeqHL)l2h>rj@p|2>7plo^{y*+xITAr0n_*Y z@t5iIQF^q0Q04CiX*U|YAH9ijLGk{r5~hxY_X+LTT3ZC~?rJM73f^6p`8X(plY?Fd zBC?>};IU2i4hgnMkZyV|?~`lacEPjj&G7K}4Vy8nKT zgvKcpwh20BVdHId`qI_y#~BZAKB^CZli$Ig{iZ9<34&X1jy#vWgO7IvTejQ@1n+Pq z?W@O{?qd$x{uvj~-ZzU%`TyYUEqZ-CS5T4tTfJRr@NOz7`-$?(&fb&GmV)`2JbDyG_p zqk#O)?j3%u*ozbFGUpEZRsABNajfj4>xxfcFHUrPxb|e@2;K1~R|Ly<( zDQ}GY4buPn(A1zVry65Q4U$1FNQcwy30O7g&coD^H@`{@R78u{QyQcYVxdbeQiBH9 zK-K*G?m$YoydXv=0&soY%~{q$hUK(wdmc%x0j4Jc4EH!kfn^qC(yDqV%tyoKy6?AJ z5@tzq)VPMvEB(qew_(Qn7aN6HD~ZC4_EB%5`tZfcPv5zHo6%Y#xa?AXEVvoJ23-}6 z+vxf95&Tx?wS(dVI%?4GgB{Hs%zuJ3;TL^AE=p#Z+uZuIg5*tucc+@QJo<;D&GjEG@f*m(P;sv_4=&60AdaT>~{PpoaR@s{VFwpt>@czExl`dEsS z-@43ZF8_EUAnYYw-PVYYx5<3g1%e&O2-0Ur#?1yF?~NxN#5Y*lkUK+fgaQwQ7;%$HMj4l@5tx$J30U1F$$gYm3;C=3O_}0@1-fpgT3A@bPz_Xj? zbNP7@V8rUB({K|RZaSM8kd=8C`L~ zHwoByFTS(1<=Ich8$pIseaPVC=YR0s2jYDq(9yf8$x)Aww}PYlf6h{uBh=ZM%PO zs=~)xQeouut)xeAQc(SZeo6f8E&VDsJ2~0UGdR!C1@AU>)#!KxZ^^?RD=REr!OSgHO$+t?p!^a4BKC)5 z`1s)`Li%TGf&RP?iCzyQ0pF2A6HQZWyvun$K6tQcj>Joio7);2Xgi6Gw=dW8ao$13 z!yEPCjgz0$?DhT2H3Y%7T=?f=I`GcinkANs;4N7qr9AbFj_N(N`AETD=I{RrKj`zZ z&tlZV|H8lhKcn@c|7|`<{~th8gZi9z9;VbFO8;MEZVO@6pqP#k&yz@lbTRXMg9=iE z*67_7+=0}f+x?GrNlJNw`_0!sj`N2D#SretH9cf_u4lYGYPbqmdx1BzXCpz-@fnAl zJC2zByy$0*=JRPYq(Ew%icO8M#*eL-@#66gr$3)$yaq{_>O&MKzhSq^tZG3bcv-bN zH1{L^BUahsS8hvZGh95it+B(*eHcs_DEwVP@}t4~>9ou}w0b{X{hbvH?~&O}#WxYWzoriSpy2IyQEO2Ug17CB zuYy*#9zeCV^XKg?O7$KqzsG`w z_oBw+g8K;GG4b(2lm@B&a_Gtg1n<_LXEnoy+`-bS43$lH!-4dN(fy7cWLUw@#W5uQ z4tUJtGwWEVU{#Rjng|6lb>FIjkjm_mix!884vFkst-4u z{3OD9m#x@91dC=ux-_5S;~lI{IQeW@GaSEzbAif5{Ov9M-@VVl%QKlC@6j>(d~9QR zbovZ(Ksqw^_NBqQ`{W}%w0d(*r_aN}+pPCnN+*K%IiWCR3f{k2ciB+Z-nO~*-5zj4 z?%rle^_Jj?0GqZXyBujF!}q#31>|tnfO~5l5>!4!f&rcf`lqe1@wT$u+sNTOOL|3( zGqrZDuY8A%ck;N*i}baOhxc}>j|80j;&hKU+N2VJz0aa+o4fGwmLrM7*ATo*Ha0*P z7t!%@qKX7)Fk8m_n-l5vVY3C&Mg}MUp8x;fcHE5hL!<_U($t{WX3oda8q@@v@?zB> zcDD=;6Ql;6{RWv(Mv&jQ!pFmq8gzYMs*H527uabton(9?6sT;y{#xP{86NEks$Q*m z3uw&cMpgz#ftVccHQtsEm?OvquYcT4vYaMGQ{$3{J3_qXZ^ex7Ef(9xI>>l6NRsLU zFFz}d;zRE?5kX8Asm+r2C#Fvn9`kKEZ?+6I!^RrtquF9jhMd%?V{61 z%)L6TzYS6d4c@O7ur5UL-rO$6gN1h_r^{9=1n;?;rMoD2@98mLO=*yN4WSGDmR^8x z^mkelITUyh^S8vkAj6g0XRZ8dZvh31(2%I*Q9yEBxo2YxHs0zN7wi^0HcgVC#@W2w zvwaN-8}GFrNh;o*jEA=x)dyaFn$OkDH93i(@2ut%b2fauBOH7=p3i#>PgS(XImzQU zNS;6MuGuMjm+A2qo1)K$di4JM;$weCkij%~znI(}g5tf8?GqOk-tq1aPP!v_51#J{ zqu^~B75Zc^f_LXaC7+E=d%*COF8+I(VLPX$7yp4cG399pwoxPb{)CD)jNm=@8?yIH=uay zl;7aQ!uyb${8$KrxAcCa6BNAn9SZy5fZ$!?p_$5}xCbQUJ7)wP3V&i>l#c1x@D#pY6 zDb+^>PJYjuma$wGCIW>+PNd^w_;}xU_m<7peGGpLwiv0ugunhzuoTsEDqP3({XbzV zeLkXfN5ZR)|Eb=AGE9K%l{DWcO#_QnfuwF7;dd323-cWTv7@nq``FYMV{u@}!vG@WNi zqtrONqhB_$v0?ZBGbZs>PfHmOZxO1GpE&uoALy%GGKAorQFLADf3WuUq?G-|<^cTT zE#h_0mgHS#{=$D=}!C6zp7y)FAZ<-YaX6J4kmzlSxT8eZYO~gaM8FA>hMWBO%ZCWO$Hx?9iU1 zo1pwjan+hFG2nCP9?roId(1wUl;g;;HRC4F6dRsu<9#b8GJr~%an zUVh#4_Ph*jC4%qbEGdUf@EfGH?+3j#qnqKR#I2pvN%%Er)#p+R{$o;1|A^i9i9R3U z9)_{vf4A7}r@{N3(1KbNZ}KT#A{O4`^-b^CkVovBBkCV1c)x&-NfQygXD7KHKpZ|` zO>tfR!^sd}RQh_1?Hw6zS9ry8NT>pMnH@Y#Tp10LQVLH#3B<;GMtYZ|$IG9jWNKW2 zky1^|Wo*2I_K6cur7<4fvs52}IQd;sAJH>sA%YqUJpt+e0p6oV@7;sF@u#;~NG96- z>HJKO_p3GZ`FJ6jskAHg&j>Pt2JgY)&OaBVQ5HzMw+#tk;hiv?W+95;eO6fLHwEv9 zCENFPAtOkZ-eX!RByV6~f2sAZS}4dZ-B)*dkPN?6ExLa?s{+iWMRPSSiUv~Rrr&bk zVB>AwVfSLU!Zc|CHEz>`&n5vcvGLx%`IVvn0mj37C)LL`ocvz!7iH$ICxZ8mIo2oj z@T+$d7b}l3QoYYd+$&R}=k}IGKzE-F57XmKSWKsnic2?@|MvgkG`@ZPjKv}GxRccew07^OkVlP2)&NAUJNx7!kI+Y46rop@yu5(+}t1qYVAA;V=! zvh}fxE5Y8fWkS3kqCsYGE!V^p_Vm_;;m9`*;nSoHYTV&_!8iCdu>1d@m;+}%Mlv4W zc~l>PIQc!^^)jP^j|f-|1q9d1;N!iy;K;+YtY&!mIe5%S82{}p!fJ{6t7q>q{{?Bf z^!f1eQd-;f=uh^KzqBEd=k1yC+xB;$2Z?zhb4{UeF!t z({nT`6j&^-T5;($8Mb(IN}}L$C73oYV4e3c3Tz4r&T~=1##=FS)v*eRY0^e&oTA?T z$}Lma)qB-S1IvL4#_Ru4A38YsX+`F7c5)Mejdw-UHX=UW-?-Ec86slyrc2Z{2C%T+rWngTNURP4OD0 zuR$B>^pXBqQu19q#Dcd_9kq+f9+Pf zlhZpz>ZHag0x{pAbJ%#VO!;}qeHY{5{hR7T87IGIXKwKgL?PE(aMk;@X5r&4lAS)1 zj^I62TK&Vg2EYH0U6AtN-j@eVk2ir%AFaG~)%}#l@t$cDF>kV9JiLpjK7Qilw~M6X z48ei`a{uM_BpDxXoAu8Pq55X{r8DqWSckvDRdWAwrtkkhiPGmIJ)$do{om~^ z(KL8}fccYAynmg$A%cas(>96ZE(GtLk5mdNco*-Jua8FXp6ub@-B!F0#Od8X)My?8 zwh$*yiGC!*S3P3q4TaqRz*_F9d2%GM-88?N`y4jj*`xMLr}zFK*-_)-^lw)8z>#=|>@>ca~szl+N+J>p>{0^!3MOTNV6rS{dmX4p;dYu`TEdd$xS z9h?yK8c3(3<(VFDx_xxjny&aey%j}+_fW`bNfd93?E%7Ac)t$xAA5`7z4i@v4F&JQ zjI>Ng1aG#ESH{(5zCh|nIca}p2uP2UD7ZI-oZfn-aVV7KCg@Y@lP=DU1_@FD`g3pW zFn=vsW#bR|Eq{^{sd4MBsGokk6TAQ49HAS|eU0((&Zhb>!^!W&*s;lX5E01iw8<27 z!^b;j`SAtXA8BU%2$VJvD1!eb3FMhid33fkIoY;RB8*k2K zCUpdtNfH`onC{7?_8S{-K0Z?KwL-?j8}-41lb@)~l-o5^L2xj&crNEFKHhrP`72xz zydy^LuJ)+IpJFGpG;A-s_mJryv9Waekf=k3c7OW+R5lvCzqEC&M)B^=Xjp)Sx1a9I zVSfZ~|IFp9D0nYiqw~!k!8=3b>ek^>f57=-Vj|Tp7~I~>u|JqhhNnWe{Cv5*3|QpC z9Li~tfVblNrtAr9yfrU`MwVZlB=J$>iVtLdDprkQ%1x^AR`P^4jCi z2I*8*8oWpIxe(SMHmZl z%-W~O^mr4#)9E9t*;46G|DVc2gZGH<=P?v-?jFziSa?G#ec4YSc*}~dx2NC@F9_@n zL-5vkowGz&&L8BJ+>rm)7Yru(1~*HMlHuIEb^2u+%7KsZSd7oADB%CRrjCho%Nitte_o zYtXTtrE*v`s3Jgic6PSJ;60~h>k6a>hHCAmJ-2@uFo?D*3+0iQCqX$@9|!H)B;y4=dl^)FC~Q*PmtlDwDrNqql$s?yk%vnT+tvM@~`H0 z#>V@n&ET%Ypb1hMHSUXy?n?JX*!_R_fp}h)6vo4Qis}O|ze4+*GM`ao2k9=)BNH3& z@lLx@P<0H!d*|Ye;A$BHULi{j13UoVS= zcW!|w0DM1it$30Y1X>1fwci>i!;@xBJeTq> z12fZw{wK<#!4gBxHh&fD{@>S~ytL`T1ZgofZf@slVe5Eoytn9EY5IjS9^T$mA9(pG zM10=mSVRQ7vh()~DB2Bu?!^ro++o$HzZ{QuaE^!a$MHg9GZ zGJ-^^Hzy6=-;erlMDf-uII;)}?>4hM3l#+K!{x$L6ufnAe`VJ}8l=_Z21SwE0>JUv zDAR=vLEw?cogFpb$uPUock!s^E1>TD)k`7gqk$Z0Yo5+!Y`pi&Uz_}lEKV$@#$8$@ zQ+2Ex8}9_q?)E#o84vGpst>&Uj`**R~cyoFbuE;YD04gcGS}7etfM4fTN!2$p{N<#=f_I}OptZekb$WOd$WrN9`eYe4 z-f^p;8kNKv@>4+A4~NSi<93kQ$uO(k3=AG{CDy#0erms z-?~_^BY1BcnBKm=ijKvJlVRWCtIWUupKzK^A0h29<@OeCq*)nYts@A06L=@^RG>+q zTA)NAS0G&=ULZ)oU0|ocMge_+l>&#*YcO~=kaIoALb9^_u{wb zH|JO9m*W@X=j5B_8{vD!*TGlMcayJx?=)W$UnHL|pA(-Y-&#IxJ_SBWK3?8mykB_- zdAoTVcyIGw<~_@Ml>0h&KKDuPMD7S~Z*E6!3vMHBP3~pf65QNevs_=e2Dm!89&lB1 z6>(*8rEo=a`Ej{$ZRaxKTE(@TONxu1i@^Df^Bw0?&L+-k&JxaC&UDUr&LB>A&Yhea zIrTYLaxUT&;$-8PU}M*dW#) zte;q4u(q+*@y7B7@VfF^@vi69<5lLB<`v{+;Th){;(5l?%u~a2jpsbiah`)bAv~Tu zwmfD$Bpy|s#XKTB5cd!6PuwrK+qmoa4Op+U=Cht;O=OK=^=5TswO}=3)nr}9D#6Ol zGRyLXWq_rVw26~4oCy^aV&|6eFz61TxAgUZnLUurJP-P$e zA`u!um7QrqEc6;xwhF5%+SoP%o-1GHoTGr>NTEu|)#vL6y1krrS_Asy55k8bMvC+SJv@ z26dupd8%DCpWj)u>v@lI;#vp-TCQ&jsi4T=hLwt;i>MMh+O`|YLlx1r*BH8hDnZqt zV(2`o_@}iVLFZ7#*Y+U+%0(6L**n{y98~dm-;##TqKaFWMH9+K6&DBlYbXm<9R2H8 zL1$0}oi{-17uFg(|jn4eHQIRIw5j%b`qE&3iXl31y&)P-%D&Izd(PzvFI; zLB~<`%W6#*bPQE<3opKa(or?@p@RoXL)CP3!e!_vs(zl`$PT5V>W6JTKa_$h%6vPN zj4I0XB$R|I%4`mF1XYyg7fM7GrB{FwP(|6b2OUNgWs?(h2vw9lA<#ioQI^o51E`{` zI70ELqP+VD#i5GwsuUE9D$1KBPzaf~y5CcYV;-vF&u@WUa$2G=r-B@jdm>G^!%jmo0#PqAFZO$QAm5s?g7^DbN(ELaIB? zLX)TpK6qj~G=ZuhYb|kT994mfbXcM9sPZSrlAv#>^6Pu>1R6utzN3#cp|7a&-T7n! zBBRP@W!Y=!3suQeZn%bgP(`^A81hCH<^EJ?FRCclO+sF%qTJ30?Lk%Ro^mV56ICq+ zhb$luR6Q0uBM!Nv>d~7R7sw4&O$B9NAy-s2hHE=RyHVA!A=w{tLDfT132w+4Rrd## zrXVL&)t8s7gLa|nUgDY_$Pra_TicW&2UNj}jn6>#sJcsjG78zDs;0hu9I{2#oveZ` z$Ocu_wtUvmPE=JbK2;4_qw2P}-5baXRh3VQ;-DR~yO)udk&^A=vFg(=& zS)%Ityf2y1R#cVs6t0FWP*s}m4BCXM;_I8sppB?1N^R4CHlV6-U0DIN9#sVreZ7z=s`9^@e}YU%2fROLKrKLZ({>g;jn0}wz}wnKtC zL_$@TN=F5>234o0POC%us5;d$)D5jh)yeGLmmxh=WxBg>gLF}qp~w3JT7{|;karfO zgQ{bFmm48%RHa`?ISOf^Ds5lAJ*0`MqZP)} zkA5dTrN)^mC-Iu)Z^Vr6)y)&GSt!A9>;LajA2|8dTud)@Od^8gUB_Pxp2VMn93J1e ziUn?kAJnJbt1rgi|4&%M`sHhG1=CNl)9d5uhP>b>*Z!;^3DDq88K$Fn@8cLyz{2~z z+s2_v1aJAxhG!^vpOn^6kwNf2eBttEh429I?(z2uUt@nzUzB*D^CuZTnQltTK7SE( zZxBw~y(R{Ha%n#u7LSd0j`Pnso5Am-VQSnK%_`e(1K4=GH6IXDWMe$Mv#CB@aq>IB z@=f`dnGjIQd3M?K5I)`^4%)AerMAK%{BLylz44E?{C4z;BF{Eurr$w2NvDq^t;F)w zgg>vh@YCQ;={r%p8>Mf^W8uBz$${A>1n)I{+1bWrx#kQ@N|0tgy! zzxxAwVKG@Eg162Gcai$`d{B2V;`turcuRPHc{2AIY`hmmx;Z}58z-T0L1KI*3yIjf zx6Gn@TF;RgZ-G>X>SGg5eja?XGBc4xz<=*kNb&*t@m6-zbt0ML@7~(AUHIhPOcAEX zdpDgvDhdN@Z=U>9z4>VHrc9)ucz-WCx(o~NdY5|!&k?*$7rES|;B7x}uh$&Gn>3dh zLd**QP7D0h>K+7uHznmCjDL{f&PgFTwcnROR=AjZp9*rk<*MqgYN_p*gAJC(iY=;{ z=DxWdjR`4zU^36R zJD2q)!Rb65x3?Y~sEJX&#Qf*~9ir0*(WYqO-`!ihGAaKcFBEN5n3`+&=H9D+R2yTDBqb8RW z4UV&D2P$93##>eS&alhNandnr+^;)#q}wiF<1JqOxxKWG@$gom`oPOC?CXc7?m z{$KRJYLEhDZ3L}Bror5*ST*RL(KF&^qz3K!X5mPwK{_=9OWcqeWalQ4%rZX!+|lk$ zeQoUZN-VtRdv~iiB6$1l%XFjQ zy?^OK{f!9TuUY*Z9TfwB&4hq{)%0F)!DNJgW)?Z#vT(UpwMI5b)=Cq;wJiqZSbJ>xhg1|av7pfmHo|4-1P&&Rv-HX~YpE=W%mroo%CdX3_3 z0++17!rRmA{ib~g-qkx|d?Gn4GOy$_})4cfoKjF;LPE8LXrtkj=S#NGA3@=XntN^+PkeRtz9NEtmBXv&0;1Kn_|7abLfYzEI;D zO;$b%R>q#ay)$@a7gQigVdezG{^R?B-0O0I_UJ_l=g_%;>@4H36TbG%Kjo0Z+=~KB`mzxB#DI{NAP~} zcrKQLx6ALSni&M|q33rRm+V6N|LHeNbQS!-Dw&aCEd=jMjmEk?`WJxMRPR#x=h2|N zK56>`FKoOcL%gmhlD?Blsd3+Ytdt}ivGGnW%-+|a!+3Z{P<k>V;w`Pf69=N@X>G3Ae>mwaFDk9bU-}Qecm;pfgf64!< zK?;-|mS_!ndYGV%RfFOlw#k2=DKYSH{Gd;%L6LW>?W&OxPu){N%;E^kdV9n>@&1y|C;278Sd%-@~bBd1|^|d3jzmSelKh|PA6 zHlpDD{y_WY3IuO&ZKBSeCV#;9YvKDNi(J8AVn#DJf_IdQR#<*kDwrKSW*!+A1Dd{$ z8gg#Neq}D}%9WlD8#1Ym8s~9=w^7|38}GPbpQ6y;j5o!8n(8AKC%+Tbi(*vAiNKO= z+_P*IKHjA#gfFc?@HSl%eLk`rA8*3O(I)wiub3Whx_!uN{mMdKu|ul21P$JlJ@6>r zTA5iISa=s654tRl;Jx0jZ#@NXcnh0p34-^aw@=ck9)Ixhz*mbq4sO8vjb~T&FEVVy ze!1Rg?JSvEGPgNu@5jdb;I(a&Mc)_? z@B36A2XOM+B)?eScLfoA8!`RZBZ7~&+#PSDuglxvgbmmH?Hcj7x9s6{DYE^&i|PA+ zSvq~3em#JDRw1=x7UuZp$V&VbunJgGk7aPkX$Vc%ZoE(nU3DCwsQ(~q~*wo#QMMflTO zldmE_?73jd^mt#V(??>Bx#Ya`KmETL4c?Tulu*3SHX5j5;T@E;uWB`dH|y$Ilc4O=&9*DQqro=U4H}BS zv9GH*bguHKn9RaHb9aP8{&O-YClo~Wsv^!k{IYBB^QO*9Ctv@Ka@I>vw zd`Gb4!S0j8NP{FMV5i|eq72L$#*~km#R5%kl_TP-OfmahM_Jj&tYM!?E2(km3G#A= z_psv|rdR6^vd)JY?ZdXC`nZRapHJcg?@S{haKy(-#O@w`4XPd$k7@mZY>2Jellj+`;sC6Ex`a!SR0jcF)y6Bglm` zcvIe_NAaE;%FxBa+xOHxkGlxor7HwAD0n*v$Gv}#j3Ce1tc!Sa!XI!emS6w<(g|cu zaZR)#cz2#nJEXZV2w1DlRvuG`1?{GWhrD-Sj|fNdNyOU=M@bFTIQ`zQjo&%3{~VT% zt$%U1pYiY>rutZflb>RLt^2+TB2Zk`D*XH`KHhRxiZ|yrwZS7ZuLpQ)@f)O+Q{|Ik zPnrMq7R{6N`4HC9$xr%w{=XCr-jt&uP`pEluB)){HX}SBw;_0kaOh}J@Q$-iKU;&~ zeV%k>p>>r%5Lz>`-;mt}Y@E?4D@E|$-;%nns4EJT^DgmhQi%m~C#;sML}M>_ny`t8 zMa+znCa7^g6E%(2YhdG@tGz@gt&#EYHm3T>!pYA^P?>kxPa@Dv*4%p}1s`weWoz!r zo3+6az15qJnbOf9@pq_m%xh=<21$@kAKA@vlm-bIdoQ5Dn{w6(iuZ=|YC2eW2l5+z z7(noLI>Nh(7H^gxOV9V-K;GJl`+lTT(gpBz9rr(k;QeYs>~})b0r2Z1khc|#1z{V% zec5{k8}Hw%I%B%ujFSAQaRv}^@eczDlJeJJAOr}U89@1j2ue0sun z@zZX6yfy6OU%orr2J`m7LoG|1aL3-U-8_OEL^MvVjc z643Hd6U=zK1>HO{{EXNC4^n+>$I0);o-+0yJ4At4rI}l$<}9X9lqIXVR2PnvHn_Lq zL`L>{{8#J*@AgA1)4EJQ#qLX|kG-+Erv#99kPy6=(BMruz6`~C>uyG$PX@dzpL4L$_lWag|+ zEO@ecm0H)7A?B~~P5)b?0QC=~7HZt>=Py3j60rM!Rf)Gtmh~~-BlZ>5haygX^=Yp} zeRD*C{N$$HHnRA5r`11k?n`ci6IOrz%I{6b2y)zEbzeX8uOJcV^&$O|e~0g%5#(YT zyea4Lp?JF`kFa9leQVbPT{i@8(LOhI3f^CA%eNjt@a{L%sEcX!gVlBN8noxE;WYwX z^>+}wi)RvSUbXKBXZQMW%RGz)+xD<`9+oi1#QU1eFS|y8kEG4ixQW!q?xqshc=x`4 z%_&vIcz9o-`sl#PZ$nf7OZP`npf?fQsY}KmL0UKmD?u+>;i7Xoz0+y!n4cqB?Vl~( z(fnrdQ>L%p59#zF#-E=vP@hYw-m)}!Qx2F!@wWASz=DPM%@6T#2!eOSeXc*Vx4YQ< z1$H5LH(5dVKm726e`r0e)X%bk)tqySo+5bLed_5mTTDzL3Xwc)y|g(89@YZm8QY;x`e9R8QU@eZ|Ln z3l;Ck^8>r*`QvYIDLWH9Gn7%s^myme=_Bfu%wfWTKZ_HKXz-?-n2O@fqJC^17T(F? zjarEa-Us%E|5~31n+0ODqEDzoq_g1 zZ@8dOEU@GX)%&iCJ(ezJY3#MX_K9RhjT^nM8L;dkHs0y32Djs-8E@=;iRvQ>C%-Nu zzeitVi9q@Dp2)CQ_;|a>PAnHis&~d@tlscr{QjRn+`N4t#)9ele|mig-R#_HedXW& zAANc=^jG8&t4LFWC}&2aHE3S+241WhG~ec+$GhnggG6^FGs*~Z#Nb1VB~pXNAG`S3 zuJeOgYSp#(%5H&^J}&=}IY$QHQli8-;!cB5Vz$$hRk2{1^jn3_mQ|RK*zrqcnQ!+F zl9o{8nx$GYc1&W|EVjMZa=fx6VMhC`$EZGjd;RD9#D7aAoZTV{IIe7BDLakdAX)hG z##ga)z+5pam&M=0UqSLa%ocRNcM;P+Vz(vI=VPAL{4Tb?`~MYa@TMGsj^b_hQGy2x zZx7bAWm5>=L(#8HD0r_;yz$c)!COkOCaq+vA8ZsjeK+x?1swON&7Suc8Fci{jaq!q z1eM%u7fV*gf^|-<$){LXW8!TfF439j_?Bcyjl18IU*9%|jrZz_qBTCd84vF@R3BP6 z`Q-+0xU}TBD7ZCvUO4tBKHl$-ot?@<@Ls5@y!i7PI{N>f7xZjegNgSZ-`OsU9q&ke)VO;dH4YCs zu}6^Lj;pY)I^*H(LG_`Fli!0+SN5N=5Cu*HU&x1|@$uGkk=^q3T02~v#k+VxCqCX0 z)`w3#OwM5X>b=v3J|Akwg&o1)4bsbK@TOc-f#Q9(^#&&v-odX2YNQant3pqbDAhYR zs63$t!Q0f=^G=b!AFL4YnP*sbJN!X+v0Dd%H|rq(Ou}F~IPPs;_8G(i76(7x)#m^v z-cm&bwjs;+q-p!VajsCXK&&`6-nEd}MR69!!&{Q-;}%YSp~J$jE}a$y@3{?zzxd$e zUD;%Rz7WAX>4A{M=Fxi0&+(tZTF&a%HWAv)-yof%(+7KbvE1M4y_5!T%DpQn-frCo zIk50P(s@fu1;Km%jwn4^yvw)WQi<~QgD-6JI;pT}J8Uc5|5O_3|K(>xGWOM_fMY)w zJkx+;LI0SI`Qce?yr)9@9JWQiCq1FYZ8+v<(ES2?aI*fJ?z|_)jMx89P<&}AMX{@9yv`vWngxSjd&uA=&R4HLT8jQly)Q?{5 zCw-*GT@+|eIPnd;2A#=1^jKPa0nBJ0HK6)9g_ED_qwDj05=B7yy~hH$j6=AGL;u zs5?lNY4E1p4T$1B6#rTP3-8W{8;Y+WcwZiobf(~KyI1Y-V+8LJV;|vIEkAfwj>>4c zj0wy>+*0)x!F$1%YjuiZ=fSvYRrpP>SWw%t|H|yB8YbSuDFbSQ?_QCrsc~xuvX7kp zijB8M<(IQeZm-W6s&C;}qj(xCOTG- zKw!nv*G5d={}T-9^Ktu4LAK4`<1LkF@TOdLiQ+wbt%M&7@6R_sMO9q5O)=f6KIbajecT0?j1xgPR4u#ok zV&bhV$JT0dVt}MTjpNgLISc;7;KXiTLyZ^%;=P>e!wM(AWx({x=qpi>Z)Mr5T91#n zOqfk&2WJNyb?o@rvfuc4`)QkXTjyM6`s&@ViasBeRV$B-{CzobISt;F+gnk*`Aj1C zu<*8;kU8)K!P`Q5gCzy;&)MzQ^$@&=c6*W=kg+#mhv4V_J~Ozf_v?BgWbLiobDl$? z0CG6-j12eemRJy()VAVYmNq8dWzkps`l8;D!l`l2Z|6PT`5*9RtNT);)X8|$Ti2*Q ze#8Gcza2|77rqq`1=81Ntv$=}@zz`%_ zuj%tK0B?Vn_3!@we}4T8{SDIpYtYmn%Kg=74dP5Uk-(}!Ifp!_mmxLCV5x5zr3QWE zd-Nm>IfHaGsdcyK3c#}VuzsN@LhL)|YS-T8rkjk?Jtk~uOet!SAvQuQx zo=g_!zf%aT9&B!^&yE3uJ9wlkknJ2;fBFx_O8oWWJ4r97aW@q^hCBbm25He`|0#u~ zjEDCFst+Pgek^w)Rpti@gGFWbZ<`O|<1Hq$W%DWo@4B8x?5AYu=>J#7_C>JoV0yd> zDs=i_n@FPe|7tXN%LO`hpm>|Fcp{30x3y6WY=+={&O|knf_G5y`r-xz?|B|$-^U^@Y!D!w0N@U=^HFes=1e5zCKR7GBpe($6*I=y27Cf=e7DLRV}c9ULH ztl+Wp^c3A3X ztw?EOBj)FbmXFw+riJg;^fEo(v1jS?Ve#u$__MQrs<$c)-b>6p?x1+za=9deh4+!{ z+&#MxylbmE6DfFC6+F5%hu|&p(x=X0jUOyLWNMiup$_+5f8zHU!F&CL@)cW^OCZd{ z^2;aPSirq3RP$-TV$5HQ1J_Y^k({R_4r<&MX}%d3Hf+3a?gP7gl^G9jTdI$8ocv-> z2aZ>SHNRehj-}C>_hc{z?Mf(3$G&M;1iO&VJ1|`m_NMqF?UG061 zO+S$aX~8;{l}HV0vbne92=a)XcwBr!Y{fp9wOy!h+}0dCuQ(j({gn*jh?7P+(WPKk zwGsYg9|I~r3kB&-E{3r_9Jf^Y5l-kfsgfG^);*2meHiv5cGb(M43!MVn}c+w`q0A3 z@6smgy3Id`U{=iH>Q1R&n6(-Gygn1+BA}2CSo>82OC$>&k63frK;yhYJv*H?9=xQizH$?RTaPnKWHr(dWW+C7X`$pTa;p6?3UF($Ah7MTCUnS{{ zI{p-UV$vsN?#Uje$2-%OJ|BAD))0;y_%njkronspp5`$W?{yuI7hvJ-94~$O3xapO z@x0d*yvcI_czR`)_2BsBr3f$3O{)x_+-om^%iz ze5_mbvQ7vSZ&7>qpF>ygliaCslX`=Cj{?x`CTJ59sA(uli@rzs|qHX;b#OI0A4g7Y)OlAPw))jNFs68$AB8L$68O!X0jlV3BbMtX0(Ft}fRlu!GA zu=ci-&(+Zg#y{Son?)(2czP$(SMSxV^!fNjBB-p5&iMEKzyJFWixD-_|F5B`LF)G- ztI!%Ww@_9Ns|L9*>gV)CMvw}PqkAa*|FzcCPlHGe+P+_))G5#x-mN{N&+fAWJpW}m zxN4XTI5$Py{mgpvY-6U-@8r|^ARi9ss1>6xS%$N8rPlpAfdTtJ;3@1 zqbBWnrGGMB4HBjLh``BjWxsEB5>W`eKQv+#a0b6Y61m{&5t!Bi4|JW~vEefQ`ahvw zHQy`6nCWW}A(u`c-~3dy|BfK_Y4BD%_01Z^d#3EiVl2ERSQQ-iBY4l6T-rv#`?3vh zd>w-Kk+1L)%`#tjz=SRTbm%s)^7IkSho8vc%({>_yspvk z??;MqU1zkDYCloqwDped?M=kSTm9!uwhaT~{f_EG1t-7D`4fu6&xxS$P1tRd7<{}X z)2oYjBzM4H7OhYS(!rnJidC|$Tc~iI>G7`PqR+>&>w@<0Oa6=?SJU9F>bUtGig!q5 zwJa9i+V0;Zb|~KLI};XR;hn(arJjf2-Mes|A}!wK_dl!!8nF0mZ!ta?3r5P5s+{DylU{p%Dl@y<$7wQ=GtAmvfxdd?gbbsocR zkfy&xI+Sfrza-ouo#F zUtBIDk*RS4{?*YHsn~dD<$WAoo+F9*|6z^U|F?f`PxWyMCqLh;%Y_>cpu&}X&KgnfA%)PYKZ6Tp%+Y#H$j3?YHgLA}wg5=j+i^e$`a7L^>f_>xE z4W7c)9lIFs5z9^WQHqma|C%h~fXA6DaUdHXJMK*o%$#7o)9;H=P*|?^vpjPdNFV6bu(1PZtDo*BoQC$@q`h zqSr(z&GZgfwkDakViv#uC)f#O$%`yw`u;z5h&~@~Gj9n8OaJu$1~hnU+vldBc#r7a zmdC=|z-r;b6$sw`yanYHyt{v=SVtguN0a>9_67RDS3tTxSBxz<7WV#({yQ>w94sQ< z$XNmGYV-L?t7Ac^Eo88JZZ#&}0;9Zv0;%=2Xk7Sbsj7S>Y`lrDLJ!_|WjwrzR3E%J z`8k&EHh%U}5X9~57fS5M$Ggz}s6xWo4%l1fR$y}lKHdg_XT4X*9AtXD2|wub@rCu} zn@@Rv@CGz^YsvrD@fJHm4ll#Po8`q8MMDJd?@}wzQ1B+$es1MK@Lsi-!`O+>7oNCs zOVJ=>C*XRn6f*vv47mBY`^|RU1k*Of3%*y!f{*t;%cs=W9C7mN^2r-F`$Yt923;|QP55{(SA^kk1aDAj z%JtM5zyBxjZjsWetY`kg$wzbgd|0K%QQzJo(crByWoVC9?|`!wOR?}aypWf(9l=}6 zRyK};w;<{6`)OqM*0Hm6CS#2+ym7ker*7ct@5uG_NbVQ5#Q^R}G(QDRV6+7qgR)S$;=E0x5NGe{zH zVmVxUyx{i#!`_{TQ?XcJ7;3_w(HAS!?ZG z3O03EYY-!s-hF9k7If-mq*2|h2SNspWAm;tKvYG*WN}mju?M}73|mk$e1^rxIpqfa zS?Ndq%+i5pZdp77T!`QAfAnYeAAGY{xH@`K^7E|Tum~QqfX%z7lxXtN=l_mPtqYYe zdZDIz8LrL2==UIrN(~*bri&x{9>n5CTpc%65(Cbsu6@LgCIN4y2(eZ??@Y`~Q6%0< zil%yZVBXHWw3e&9r##D4w!yq_*5u}jaCt)qCf(=h$E?8?)qpR}&u4+E@zsqkl=XnG zUSu0EiUyiDb`?a+t0QvUGE<|dZ8V6*$5m_zPyC{S%$rLtWyfMC>G9^q)v*~RKb{7j zO-_@{Kv=lu$I3o#)=vfv4hkdSN-w~pR+c&5o@{W9}b@7hDQ!G9XT1fX3`-VIq9ZEQ9w5gT! zcpt;np@ov4Y@^-WaTykXHJiY)B%t%|6AO$#4|nfC@3-&sN{Bc?T4pT$dFvS2^Ty~h z5m!e-p04meS8opx@KzA?dWPp+kthk{6A|VBW`^E>llE z@P?B2xW;tp+JKVXi{?Yavq0=c>2g$gEl868d292JXfXZQqqDzL6_K|~lnm`%%RcNB zF0Sm!8#|E!WZv|A(iu&On^5@-6Tpd%qOdFcu7o@{`Z*>CRa?^}|A5I*I)!Ku^TSRfpVh-l5 z?UYQh%6q=_{i`i7?`O8JTi$v4K+hk0w-0LB0B@$d)Q?Bt*IR_krSMVJg56dcQXl7H zz|n+;2A8)gh`b~1eKpoQc4NbEai5oWx>58X^UmD-=8`7~UcHUR)sc>p->?1NYP%Cz zK-I&c$$2q!-Yc)Wa#rB8H`%?X$qUD!5pmh3NYC78V>s*bPj;^pdb|IYva z!I=2J7Yg?vU4kBT;QEoj15%U;jSNx`T8_}(BMbMS;;f1t;&2Z#+e-cQDSV0Dq3%=^ z?N1MgZZ2Zpsl)>83_GK$(lHAr+Ki_Le%%M-{cm>d_!$ifM>uuEHtQhvpw`cu?reE6 zip9r;_hl9O1?U2#9~Auyzsu?vZp810^#A+6{qNgwb%heNl;)^ z(DIsg5f$_*>xIgjInAV{o*@2Q@ZV?eQK2WIJDSOUi8Udz4mOjS$-5`k=6@Xm-s(Y5 ztnfQXdY?WiB;Ge_U$^PPyy^V0zgL%7w^}voQJ6Q!;*%T-Jx|Ey%B{}jeU>1toBn)Z z7yN>B6XCr9ruV@a)v4W2u+gBQqf3fE^B^Ke+Hv_%isCm|d|c9$M?@wCGVgs1^DAE8 zNN)#8hpR&ZCBGw!BBjh3%z(MPRr%5)`Vw2=`#{16=Ivwi`S<8D5j)7>{q!NPo{&9n z43Tx@?Ei2E{PPB>Lj=6l4hZYwdEXGaybp=@b8EREN0@h@dg-fG-pR9h?w?`a-l^wQ zOiMkXP-Cv!7OySA@(n4I?>)1iB;8+jdszceS2qnCycP}GjL$r#JgAMx+rSJP!Fu{N z_6aU-t7U`f!X+KVE|v5p#O>Ng(&KG}t0Ms=zf{G}iBHrlpj>8!Z}T)d?`{f6+qt3_ zl6b_}>rTMA+nB~GZUEgIco#bK?2^Y9Fl)O-a_SSpd=FSxgf`# zp)l`PN5kvacz04h_zCk?`yE$gy4ee&`j!9V*$pf3e4I5?v40j6k4tr>Q#1hQgHjtT zOQS&@d%To8w-zGryR;0P9`3KO^|(0t&2INtHIaFTx4b@6Ge&y6YjJgiqU2|jbST$P zodsm@7Wd_ip!2o~%Q@x?^WIY{bNKBz5jQ7#h`rk9C`$IcF~ruHY5Fg)__)!S%Rc;)$h?nz+{x5A zN_xD-adkwX>c!t!`aFLdVZ?fSt|^u0Gm6|*w(j+*>8 zCy~U};dJ&{ju-rT3r2YOSVwUc!?>MJjmDWe0sivezew#T0MGwM1U=|bPA+D(2W@{R z>_)9*gF)&+HDaGncK#?=2@lhlSe^fO3343xWU)`>X^(ztx|KV$zt#TWuTvI4nMrr} z1QxyriI?WS(#|Hp?Yd1+@>~q~QKGeRE1ePI5__L9EnY!y0{a~oXTx*L?bri-#2utS zQWtf-6gT4c```MpH{$9*%P;tvd3@_PW>9faLe|#`eg1#wQ0R6U+Y9a5x3Zyf1N!+t zX2)X|;lM8P??HUT)iHVMdL1?V86+@oLjv9hU7!CwAU)IAB9FxT8Eu#R7|c6EoxgFF zx3Y(Jv;usKT{=_G>!3^SP>E61{r5o@V15L%PP};*>}Sl$*SG=!hT@!(8J8Fk+jwj= zPS+5T1jp`1&BiFlfc|RN zY4MB5yw4S`8)bO^7K@KF+O9#p{0^D7JO&zJVlZz2289oQWXSE02Hv-Pv^QQhMqFaEOpP@nsXk$SaB(rz zOMcH43=#jV%^fP5{p3%2JqTY1T7L1rmWx>+W}q`|$G^7@y$7{lj-%jI>xJxxPVGAw zh`xigVPoRU>b*twJ?H|Fb$ro{p~qfX+d-NU@HTKa_{;mb-kxB=YOr7 zTjjm|?3PhAn0MnF+c%HjxNzn~@+^1hYyw?TC_mQw`_7~C@6M= zuzdnw@1CIRo_D zTZROrYU!3QlRfVNBI_sMsEUUbA zFaPc>g?UFGuUU7E#~n&&+M%OSYyl({Uk&v)%!0vvdvuP3H-Q69PnR0sz6y{@-WabznMuH#lYh_uNqX}CCpmcjwOSN8BL*%|n0t|F#x@tQ zG}XT!du0|t8-Ba)wtfJ&uLCVVrObO0&)+kF@=c+0wTtLIX#Vbd&H44c5QC0s!Z9Nvc98aM z?#&6=2iCM=ZHcua;B96UIF09By<;;y67PFQp@WR@68px7Ic}AA;}93C z9?bjqa6esKwhPp!3-Jtobpi~Pi&uJzXTeYBBOxYq4?xY`P1kcRW5ARjtCVQH86s~B zzPZQ~k#pEjxVTqtHMW1wBJ<9OZ;N8$B|YBwI?(c~!5VQfIx>T)0L=vFDRkb|RKD!Y z8+)PCgH;Nk6nzKz@cf<-mZfg8=lzq&I$Z0&UTQhN#@mvBw<({*+NZay-o2HS^nL>p zZ|d63n|8pw)vdb?S9u#A*LbrZ=6%M*>)Ysi7bv$U&vZ1~5#0FjC~4^0EO;-JzFoS$ z1+;Dd{h-V_20Vmltt56J^X{bPP>Xyri*3clnHj!6N^=OAxA{s~gB1_y@y6GImfxWB z;PdCP); zxABUY0KR(*tlXkS;;qd1a##lDT{n}&x5_(5z+`SS%)9#wg-yJQD^&Z|w)fa)dk~jX z(Aify3-0v4JT>j!0y4{0Sa(Oo09pe<<+2P@#O`fPQ<%bVWd=)!i_0yL)zhLz=8Z8* zwSLP_dc5&r=sIXZ~n*EftFue$CXkp6J{WIiCc#HF*GXic|Fz@&(jVmAq zeRG284s6I|`!D$HEh6jq)Yrrqo&N9r|70-zV=(ai??BLlY@&yg@jd83ggP5i54s@G zbn6T}|8JymZ{7#@Acogz9OCdDq}|a~brSJT&|}djJ_X&Lpx*N1gT}M7;C4+DCi~Mv zKx@St_~CgpuoEl$qS$PK*n^I-=iPB$_=0u8#R*@{(taUj0+4>DNy(?bJ{2UrB{mvY z2U>mx5*<+-7ns2Mgw}4XCWQ)8o%nyh-`@I}d20_eZ~I`wi`VEqD0Yr&zL)mDVE&&W zu8zkKUca=swl*Ny6Y#dyN{Yqv7Gq~(MdJPL%8*bh^0+k(v7S)AwPYuhi_ zPFx(NV*I@S8)HP?$($0d!n;V1w+pTgwETYgdO8fTF$1R*&&^%?(Rru#?W{B(?SZTc zVq7_v(FY`t;ec-HZ1R7+W#&0?b;#Pq#kz&9@wOx2Z6zd|h36f%^)oXP@1BddF4V!i zx3@8vtnyyhNSFHn9*|zNYWMM(IYaCGVuNjC+(Aat%Se^;@caL*_=LIj9s-UZm!`MA zjs`U&Uo3u}I*i!8%kBrw?0>v~y@!j_=zREPFaw$QI+aNQNfP9ZuLCW=A-|5#pVOJa z(VLqpsl?EEhv%K23xs(mcrY-~lo4@*bk&d;3u6cQ&;K`xtYclHw(LLizbyf8i?4~Z zc;4sO%b1XOXVo%Vb;G>$Ed%wKZck+?s0+t3B7k{el(}!$i-b@aIOglwL zuY2R`U_{AJHbhYRI2|*%Z|q{K#evTIV*=eLBl=#b_oSA77&8$MNbAfTS3EjK{`0>s zadljD@PGKLa;H->?(U+moupFgZ#-rCVwwBQ2sZr9zg zc`J(x7FhFpjNzmpO>E%qaK@4j8sFRcsa zv6RXG#D%@~+&L?c%-dDSpNEeGFK^-Na6!p$PMsxc9Dcn;2qS;QA4+uI?bQO;-@#{Z z*=}`;H;~^fMAorHaYp4+eCEIB|M+2zl>ZLT|E>f*$SG)n2j7E4 zljS&(dXTE*gQGj(9<*?+aZ(EIL2;Zbp`-AC6tqCilGft@6|F?3txWoYmXWvC^|7-+ z{pZOilt&+f&I|6NShHyGG|zQi>M+Vi??Hi|mxI$)d!QZdKdaAvBw`2ogCmY1QHAV# z5av6Pb!1i0;ck$2A>i$(%6K2oTUVTRGZOCrH%(4in0GtdhtgHvKfP6gAH%#O*dlLU z;B|z?vc&}Dz8?X-d!9_%Wc6zWLmLdkhGGSQ9WA$hY97wz=JZ^dE!Mxv^ zzVuz?y?4v_+!dI2=k)KMKcS8g4|m*!_7^_j*noIcandaKmZT%o@bVETsZ0wP6^;Q0 zTgD?2m#h%G_cul>d;6MiSQA{_)VTZJE#}C)j|@06s_Y{@-rsR`_@d<3eo<;!Ns~D~s>maTUr%lJ`Fa7iORwn}9 zcH`hBo_FNE;*ChWPp94pa)NoAf<&oR-rrLx_a1?HyPNnHR=skB7(Oni*d}=c^SAmR znNQ7veQEPobx%D4cPaKep9+cwv4Mg;=605dyleN^pOEJIhE2f5br==oz9~UIoZxeN zRV*q^dc5&+wxE|Ja2i4Aa*3)KV2EVhrzs$bu=!oUfznUd{=1<^Zu;xK~jB> z6XeD)f_YKz1=3`HrTV1Kg6`%Q2PhODfi0PNa(X(^AZCQ)R7C;u<*jVSxwn;ZU$Kd} zxJ60B!V?FPdGi<~{Cc&U^myazK+CVdU*qz!C^I;FYp!mW1A6xs7F?{HhP$`iAsUy% z_lbBoQJYQ;v-F(od1Ew)tb>Y8Y4zhR|God8lm~xYZt(o?MbLvhLSoiFVrTUZ(vtlB zyhuH$;pA-5-EZY8hCzjUWZ)i@aoDCt816xG`yFeZY;u5v1|Ds?XdeK&jr*Q{^qmD( zNiMsqmRdn+oBK`Qj$R`B}dzxfSij3}kdgL^{5q_aKUom$B~!x}m327cK`9^NO9Bi@BDJ{{{2^ zERl758YsfOV#kw!xBI^9#`q;R<;l`kB;K>B)vr5X-mLKglhQEnhr=~d4lwT=2f_~^@7E-s9|K%+i;_Bf0_1$ROKexAd5b$=Rnkc~YHfU_)M&kYZ=YjsWFmHMg zTC&PJU&j9QRhaj2KfwrkSqEsQb6jn_%pV+v_=VX+XThkUdrY@uE651z$Uk!`8fcvH zh)fhj<~_3ixH@=^&2kIj6C`+Z;!eQZ zXK(l(a&&$w$kKwYEkcNpdTfoWyf z#MSUwpy<=|$bVxiaQ}IJL;aO#U?3Vc#CypGadT4r!TM&q=pxn(7YBT;9`1=k=B-%G zUKVOidc5!8>QF|>&vdEfL0mZ#2pHkHl~je!`*NcM(_xr5gGTi0>_6x?Ct|upw8S-@ zko|xZ+fG~^3H&M+*jsD!zZ(H>=aL=nc-|xOUR#iO$L&dBVT9*@|KDGCt@7@_oDaUh z-8&*swD3!k1N0}>mb2@gAGpuDG%9&)77V9$^+i5@46aTKA1(`s2D{~KmF{*UA5Q4p zJmxH!_5&-1ixcS$A6#KV<{g{gbYEVV^mre_)e(o1U$(b}ga6rZ@eo&sUlGJPa{Ax<|H)wbU%UU`kDv$nTJ(Lx z_n;$w+XRq$P{-&(?m>8oJvDwVVL#l1;=j9|Xoc@VTI`2nUVGU=>>VS|zC8~FpT5jJ zRI`}{{<)vj?*~5tqk-5v&Wp#ujxDb%Llqnlmsqy^^c~jPzp#S1xU8nhWfd(8#2uu| z%hz*HGfA%pG2!ZPMahp+g6oYK{D5>_&V0aWaY_|5JLQb0D!E>DL(ljwK5v&t??E@| zD5@B%Z#xSw#51p@IE41`3BEhisIW2MBXp30`@TP<=jlARo)%m z?XF!gZ;DV^y3S!csMIR6^fnCnE=al?~q!D;Oc(nkn*d;jdahv&VK z5!#N#`|-|*-e8z_ilpF=)vLFsC+s8pVczS{4NXm1*h5NNMXs8R2C;RyylTBP5 zm5$*D`S!1MZyy5QUeETu$MgR4E0Yh2cR{}N=aVq+D{KLGR(anV{}VU_^Db_{exG`4 z51lR^mn)tK0B^d%y?pmsApiNB$5eV7kk~;PAwe4h*z_vGe(@pmKDr<|tZTl4-Gqyi zrd(EtzlO{^`va4bM?C5A4#CxtgOVRVbj35*fd%A_oWCSZiOyT^HN#Rdd^pi`!`kzW z2>PeD1WcHIWC&6s`|iD$$U3HzRHWqV*Dh~)6Y%!DDg@zqGX^_sL*gw-BmL+S%-d-l zo8Kz$Waj4lpD^!PiNW_F)DDoV)bsUm*8+gKC{LY%_bkvnXqPj7pbb2ocAlsnKL%VN zzB`^v$X9Q>E2C}PZ!TkfaB*)o>^L8H8ToJ`x;~>sGm!Lnci`%XLCNpCk@Cc?KTKes zS;h~M|A2RAEjQL<3P{5$`n&2S{~zr&ZcL4-yHcuO9wduEHiDyC@6ypaa7(HC1pAV&fHLel=|kQKz+Wno0$M zBzD#Jv0AgBGOIySgQ5exxb|dgRD2Y`8e4UBHy|&u+8J-&Y zQ@ud`Z;&#cB(9F?13tz~$!kk&5CQKXzWr2q-q-xcg^+mvxjBAj0p|U{%)e}vw|;v< zSq;ovd52odUK1Or+px3LS0)Gy0y>U19hkRkpjFK6cF^r`+Bn-b3ecT=R48bU%==3p z)k44PA1o6t?%2G7q8T$XZ^|2f2JxJv$9o=E2U>m(jZ&SA%1of^h8iV<9XjvC8$3Rx zFmLHI{ueOE(JybsmMh2}9ULV4B{sHQMRIoR#!=2jS{K%TLo@ zJS)452~5tsxTR@~&O7I+aPBcoFXZt(MWo9IeFtgrL))i`SCQ=J|IqKm)v=Vt-MRIj z8>9mWc>BM2*oWuMT77O867Q!6w2gUT-Ya!4Hm>r1X;&rK0Q1%_@!gT7Y6}I-IcfJP z1%V$`aoa^rXTh#ZZUZZOda(Ki+~NwvLUZysI}z!+URk0^WY9Po(g?Pnt3y4;w72EtJ zrAy3$+84jrI8Jwh^Il(CwX7q-jb*pQIQT(oq#sfC{o;=`9TZS0F785W7MtOFE5scn zKh+PN5>L|WK{>cO(DHLx65QGA#sZ=m83dkJq4%JT&qNa`qI;m{7QLEWHAM8Fk`yOa zs>fvCgD^za@jLg;p(hP%1JY3f-r*bBT=2a4AG{Dn;%za1%IE~lTk>v$^eXS#uua8T zFz>A+@3}084@2XL&qr%jf`Ev)xFn6tEXb9$lQ^%`3CdCr>(gsRf?Xy{X=bg+OKb*^ zTAzM|0uscV# zuf;u(w|Cm{Y*lpLolG>U)@a+B;Iku zlht`J@8d^Q-^;!YRbx;nGT>? z=e)_E{^deU5d{v^5w0#kO&w0L!`%h4p+xCz4 zUE8|fgat&akNsjOK<8bom*C8EwFgQ$n0&`k`yt}0_IGupYi@e6O@r)tV~DKddI(Ma z)Qz?79ZJAE^j_~pJnxrQ;d_yIzvK(sdK>2b<#j{WD({c3r@1*`-n3uyrC7FGLHUtc zpVr9+0l9uz@0ZH6fa^wbV)dmC0InKeVDpFskF6!IvYR6Fekyw0C8G`lwc+B1Wn>kc zbCG#FO<7Ry0;I=#09S`2N`7I{DzVz>ETEv#p}{>9owt(->%32A52R4_vuQw}1(kQp zA^M#c4;GR=?}tRzaU-hR-1E#D?+^msAqnS9@w}bY4(>tX?X7em^)bx5d>^OQD(@zX zTIQSZ{I4^kXQr8A4f!gTmwuBB0zZE%O30|sf;TQAM-LlzfCRcCt`l5Qz-3c0m2D9+ zZ%L0YN%A%r$Q>8Ap}#~(v<#W|r(3qsizN7Z3w#|PQSyt)p1ar8!vZAN`$k?pfzCUk zQ%)!j=3SH$6YxP8oi}Fp(K;$0Rr23^6I;jL{VaK2|33f!cl9RaFW~tE%kMYspqwpztD!AqGaoEbl4y+CExwC zRzN%HEwT7IzMLOr$(99l_f}w$h?mWm+>3uftud3a*9u)ACO|4+Ac4A zdPx2~$eFl0EDtlBn*Qej>0<=EV>WI7gkNHhUm21@;(gy(RbdOvTZRAOD+QRh>5=Tl zR+#tg`cGRrT1}w)c?(_NHwS?{+6a4%ZL=WuTd4cThh4xsSR%0RUIf6_8=o+^hJ1O8 z_dexGMXiEOAw!wOE%ZBsK=(fJ-WmQ`VAvEC857zC z{FBBKs%s*^^-8OIO18+n8>jrL>nA9oGF+Sk2Y2R~CTqm*eYI*!%z-@8H-Ju>jgw&BS7=qn<^b{WZn~EQsM8DD4`Zy+*fIzbMuFgd21hz z{L*rY^myazK+CWDwcwtu;Vj_kXNuT_m*~88GbuQphxb5XGoRvaQ~;mD(nI9{F&>=a6<#=P}abt&6JzEk6ndMVG60SbztI{jtJsblwV~ zjnXe+-n*C&1i5b}qI<6kzpr3H{?GqosEDj%N9ydJf8YOy?{1|1_eASdDuNz#LSia- zwFm8h-~T5fY=c4SK|7_!vopWI0}{R7iW1y|bTUq*CBQu>V@y~skJAVeulstbJt+WS zZRC}AQO*Jl)6dP_7khw+=`H^>B)wBr7&;K z#D)A--bKFwM;gpKGsV4jlaCS9q2Fuws5bye(wq2iqnQQ$A#8{A^?Shf_8?S`3j46`8L z;k^HgKi$B@kk@G2*GM2itrnaA8<}@|Ox}wdUDS{iE{=m!+`~Q;nfJ=jxwIn-q_=~_ z*Rh0>-@Ra7(H^*ar=79Ydbk~(cm1nanD-WtT5Tv| z4AEa~8tzXC1ogXO73W!I!HMDo%fZTSz}a`^hToq^Fn-<0Kd2Fz_i`X@>p}=M^Z^&= zuB7OF`MVwB=ERu7`quAR(&N2^tHTf_zdur&=ok1o089OFbOAj&Z?Ro9_s_$J6LX!v zvredWBmP|Qo3e1t$GY^E()aQIOs;?5Mr0i?M$;u!n+sO&|BoTyecUG`2){YmJtnaq ziT4??H0{qY@Awnur&oEeo0UCY5A)7C+#T3^$ryS-b@oRSRS>vYmY>zcF$>CS8CU|G zx0@;S^4XhVR%UWKGd1Lbi<7_oB|an67V+2U@Ju`I#yisEZGfx8 z4kbV4s?P@%_p<_~9X@u+MDXUr@#f#ep<%ug{p~I1FO()o3e=PR*;{`eadq_M=jz-^ z`1kYw$fAwG^FJ*?4>~QvAdjE_$2XdQB4PAGilnA8DSP0XKPKuD7N40<|MvoIZCVK;il92K#C;iBT17Z(K%r98VJwkc|(g$1}@hJJ#`dD9k9Lox#e)`vDB%&{|clS|d zovG-7Zf+Aa5$i4?%CbEt{-Y2hzXRcmiPo*K?ow8iEc7n8ec`J=! z=Qrak*F`20U&>+nnM+xyS_ zzn*~i$tT~#@ZFnl!#oud@12Lr=!{|B=9}+ut@3W@TTcEB^A6o|F<`T-A>_v!d$8+* zKZs}%=wSac1NJE1Ir~Me7i1nkIT)=R2{uX4%5Et|=52dkxskbRJ;aHNyP9S{%XkZ! zcYlkUdDB7CsG4u~x)Y?e7jE z$B35yff?D)|FJ~YQCt%A>Bv7H+f>oS>;!hI#Mi zx%qA%JRn8e+-TN~HiW3}*sOF+`GXPjJ>>$6Gk|?+sBzEMULfSX6eN5IemL=Q9F?vQ zGVf~*e)r$HuZPNTar#sSqp3%bd0$+A+2Di{>G8(baRDX2cXlpsQyN*p7+b5Vm^nIc znKs&_iqsyc&ghekc{uvv#ETugRhP`}kUei|e&XtwnPA#2mb$h%p(fy+2ZaQ=KeSq8$Jf8iurY|C#|p z>MPu3(>-99@BP2AXz)pnc9VN6Tx~Nhu(wUnI0@WuH6m2IO}RqX^~%~3%Rs<8 zeHp8S=dCWjogRs|Q7LCh7tC7>vom6qw@O)PhzZR5`P7GHOUn5Zm}ELYTpxx9IX!k4Un=m;q8FAwPCg_kpEM$m-qMNWd$0jJA1~8)CQ3tMc5%y?+D5 zhl?v#@p`jq7jpMbd?v8m0=&v?aK0n+1*uVX7pev!G6`~jwHpgv)t zU-Ak%ZL^v9!3qpaHBQoHqx0?(01u`7d!UQK2O^x4(Jyad%y^sLW6j8(cPx>0SRbzx zPbmEN{eS;kGv|Nw--UY+8$k~`&v|hK--9;x05+r^bdF0#?I66ww(NROc>rEwQ!*1= zQx5M_+4M1%O~&ppbkJ+h%^n61(0K5A7tP%nAjkZ4qMD)~yztDmGf)o)weNNm8aE*K zpjUTvHe6t%hp@P~=3d2jHRH%T$mu=PirqG(*MnZ*>X<^w&p)SsD58c1*j6j~^6#Wp zLHiv(xpYFLAiWbhSFRky>xDl5w=teIFT7hx_C4q)J#lrc*O-zwxwy82WF_F8J-(QS z=goJVg%yeSq_=dWJ0CqD0;leBz4#WEb7k>2;7?i zJ!OqHWg~sSK&cjUN;w>y|9yPYE)bcwqF(G6dmSB=kBi$8&l298h0L3Zt+&g?iu8CZ z;Od}6$#4DnB17h%EWpm|dRgrjbl&W9F)e*C??cWpG4!oOod0tVIq6N4|1EYHP9p2* ztZBr}|11Q&v+7>2eZ1xB2~zX1VP+)WIZ+<-Au#Vf)z|n}c?bNtbFmrbou9weYE!5g zq-!v3`>DqhY%Txkqy)_X(eUEQ;D$cHmSMkltT!ASVEDQeGmOl8`la>OSFUuBHZD#j zL2cZl3Yj;?m}*qef%JG!;p+Hf^#7mV0%WB<0I>k~&1LB`E9g7O3+dYR_02(uv=!Kj-OEDb| zcC-11G~Pnytr7Xlzmk;>62-+)T(Yjb5s1t?i-XyZ)r0hSAHda-iIQJV<1~#3Ju6_0 zw)B5Ah0fc$M$rFJb{E9?z;IlC2RiRkj{>EO9_0W2KQi8#I+!#{JR}CKT^8w-gx5C1n zz-Mnl%^P0@^#Nzf`_yNKBfyd=!sua`Bh@S#SRy;f~;$w<0VGXd2?frcWuwvcs$|GAo?YCOvdYZYTo~X0g1>u1mn6>Jm=2o}0L z10-_4b#|TU2U;ngZM~Mlf#cq9RwhBnyfbxq%Fg^`fZTC$(*;LTbWS1j=Dj;Qjrl`* zywBn4K+BKY^L=1M7%RB4gF3=q51scT!}PS@Z#toy(PP8eJJ27o`_8JF%y&+l><6UV zMApG$+p;p4v37#QLBKn&-0TdV_x8KJ97w!BPOVVTz&ps}CSzu+ys1ZzGMdA@A5Kw^ z_Z3+}IS%qKeEHmfspq;(|EuuTTe(TMR^{N1V>zh{PLAxmfVPyw%UK zjjtX~lz;s#6AbefDwz?Ep|*h7AE)GJJGcX{({J>ym(BoPdC!OATKypKsLkL}$q4X@ zx-86U8!~U>-6d~^tr(y&T-=*Pp0UH!$h^1G>$+ayBt71SxH{1C%hw(<-ujCLT+M!b zn_C8*x7ea-Pe(~7#Mt3vEAkEfa6(E~F+@0c8`%#?8Hb3gL+@$ZHJkJ`-s}Xtb2atN z@w{pC{n(LsuRHWXa39RuyqhtIkhk*8_z#V37SMcPCEsmJcOW2ll7IBp4B&F7a=0(h z53;empI$nKgKhlrf10)<&;M=T>K;h>&_jZ_IJ3CPNA()chP;|j0m-G!louW%{#^bJc>VmxnWgrTJ#S1Ok#%&p zi0=D${{Q>yC+RQX`F|@x4=Sd7_XppDluLH=BK4rJqnT}<@PHKmCNW(bUSco29S+up zm)Lv4#kWqdIzoGOLbo>`um^NclP{{r&Vc3h8679Bp8^vlQvG zhk1{A(%OU_1(#lLR8<#7<{kGidfgO;2`a|LeW?%@w&X|Vy@gSaQg#pN@ji~LgBvBk zG1C;mhZ8JdaGT>L?{swD!E&)`t*1JnOh)1E4V>un|GitB-}Gsf$$mikSxH2gDb?XW$x;FT&B-RcOqU6(n<(`SJ2w-ko;-}^yj$wa}Y#G}A3`m2I; zB{J{AISuSxM@A?F7xzIY$Y?SinfI@}Wxp*X`20V<4z&Ert8>e*II)1!Lfk6Fk?6dm z&6VDqpY4QdXpI}$KcUb68QyhrNnBURo_DSfadkiif8+-e);1@c1iUY))2@B~-|F34 z^Dn%%Ao2d~#m)N==6#ImYP!9~*R z-uODu^7HpK%-b`=0;FVF^h^WLdB2{oKa&UZrmwfBDLhNW{2yE_Pw&5*{P*6(*6})` zYumr`KS_`Mf0Kjf|Lp`l=*IW6eE21H`~sH%QV+837?=4uSFYmPzl%}_?m=Zse15uc z4_cQn|0Pz-5i0pprjwX#2XYMVo(OcE0SgIrucIgiz?Uh%$>XAt;1_M{r+j^H=x-kX z=NCf;yOu0iA?gkP#0fs{^;IABK%D}d zc6iNzOU}#vZ$_Vj_y^;*7VZ(?fnfBAC-6e#xTHYocxHeFdV-7ldiU*!$BH{5@AYTJ zWLyF1@y6Fdi;~~ak1Hql?}Fd|7ylMvlr@x;e zd)~g~#MO~g+U9Ub?d<9kq}vF1U%Mb{gy(%wzHvJeZ^7Vob%HSOG^Yk?Lf$?H#ZA8+ zc7%cl{f=*QwgWapry)`Q8L(G$lD`#t3etGy6IpV@!M*09KQ=<1h`eKkORn;nvOrC^ zxLfgAs#WaByia|nmbFYJy#rEw9cNJTUE{(j#^EO~^=0oCLdM%||4(6Tn zLL&blLHAaVmaT5FbA)*H7%!%p*ny|#Hp}J)&wv=0>K{jop8_k+Hy3J{!a=`<^R12k z9*Df#xSb+)4lzT|adElV^H>W)-4MI?2ZJxb`6uZONccLYQ1WYA*dTGiiv?gm98MBy zLgzin;c~*dq64BZ;5aw=0sZxs7ecm1KHASq_5;%BQR3=2m9xi`*YETyZyo~PS5;Eo z@Vujr*>6MQef^!=0TY<_g7A5ILf)tDZRWY;;RyLgHnC4C+JVd%DVfEH8PNT9$oWas zQy?w&&MAWNC>ZO0wW72IdH(nBKc?`roC%u5#jR{RmtW|Fd^o|U*Af4N1P>?hb?iXN zZPa$^sDa@Iyg}BOO`lV_s)LeFZ-afs(hV^0JN}OGx-jon z+S7&~SG%{n{rA(B&Jb_U;Klp@Y{=nTpr z^ZxyH>_o&#HYg4kx2^4H&D#!S-YJg`vGU}R9&dadX!*r{&RNph$p(6#Ia+?AMCUzf z8pBSL-ws{Y61?d+jm}%Q@%Gh?D`&}`w+)eX__Q@vCC9Bj-oj77yWIL#2cEYgx zyra(tUhIW=fBsNRy~-PZIFZycS|q&R5eiVWkhQL`1N&7BE32$#z^x%yR~xkfFvrzY z@N{PsxEm+0W|HfJ*u7IdGk9IR*r0p3xU>q4(aaWP-dFb?6}(zSdc5&XhKQ@9=XR@d#L2b8i5&#I z%l7#H!1FG-WxNxKw}ZiL%?X(Ir_BZNglBJRmOEb=07rl%Z3r*1 zcbx8>{{`*2TD3DX|$adeMAl84Q94cB-*QM8ZLM;yL|q zn~-~ujt}o$=O}h44i|UdAS1i59(jqa=W$_95Fx!Dgs-CxCBM?GsbWKySU?Q3SXf&; z`V#9a_;!x^ayvA7vHzr50ud)j=FA&|s_u~e{2yyUTpgDyR%B&vuPw2=33yl62Ykcx zzOeg^C=ze`;(JE2Fz@QV4TT0U?~H99EnmXCYi(jvg800kliwdd09#Fg$oJH@9a1x3 zy=*}lFW(?gO*g!B34X-xN|X}oH#TJ6!`}`KGh4Ak*Ku(>Pw22V9!KV_R&%hfL4ovm zzrxj_ijv<6T( zPsG&`cja1ieC`@=VFKQFPB5n6d7CO#h#>KfY=5^~ALeag`EAQ8?+=&mSQW#(FH9wK zQg85ta+ZC68lN)*$M(cjSjx|U+HtXFb<7~JYgH*OzZDL8>wOQs7DwhS%6-YPZ$CTq z3>SCU=wx-SBQkFZ`-=Q4I;6)NUk6%#jVIn;e=E)k+8_qIJ+`86e_3z*0Rr03h}b-E|oe;6ulp z<~u>;`Tw0%+wM^=c4!6{7m^}<_tqFP@A4nPbmtsMkM}sPjtZ3g=DY@&%9dC_s+IL_ zWkYn{XOasQhvnKKi;!;1`Ss}M|Co(}v_nVskp1Qa!$w>kuAL*kq!A^S)Ze)v|HU4Z2WfvD_$Y0jw@%2gqv7 zfQg!BWu4{$P*HyFy&nA8+dLKyF^TJtd3P#E4@!Myg9LDKU*`twj%OkBesOl+5jk(t z|&{KjlQHWP6aNVn@x z{>(()K|bQ91$o*VAyr&lftKc^(@r16of6NZrWyWa(z`(#U&j`d{2t5gZngDf1MHF2 zClspCdl2W5310*I)f1%fk78Bm4@gHnGNYDa=qCFf@k$U^^hrZCR<7^?k^RcOx{5i>p;vm?-J-M&uo-BXHu# zI?`KW@pXiwc2#6KU9E=s_=KI-N=Jnz!ah5L|r=l;>#_ZH@@tMAxh1oK|!(8|6A=B>7H zeUr$oBamoh=5B>B10YjS=d8gy15VU@-zsxy5cquE7E;i56g2$iy8rPAGH<3o4I%tr z*`dd{IF*akR*x?r^QH^)iK{_Xi@UJAl0Y+WRex|QG>ptvzuFF| zvZnRh>Z0>@!>VpmJwyJV|HsluTpj8M>kmCCTD!a@LcqIDuktFM_i&@XBogmvvkixS zz`V1Tw3JtQOX|13KF=eZ;s z7@ohqvt#p1rA!at~~Tc^8R_WA0$Rp%k5>3>8Xa;5i#_ zb6$7`d_T0GuhAYpoKSpPL(3Ts*3I9HKA?%r+cIFu^l$+?#Egr3OU2z=#OXF|@1V;I9`C$w)cIg~W9%9}e!dtZ?HlYNNdcrW*72T6?r@9O-xzwZB6 z2yW2A!kc%MFZWIaZ~gmsqeg7JqmrJRl+n}P z@)qhN3@5)S(TV3@1PFk;KYp1Hgpaq6?>(Qdb&YV(y-e6(2!93{)S zAKyYgtm;Od*hQ+hDh1wf&}Rd52D$u5##$`AQzSo^2OxM~x}=h6h2YI7qETdo;C;a$ z(4W}s2Mg<-tGUWz0JhUh?mIz025x>$d@8f19aL^T0v)Ug1_^1p)wkxct9QOn4CLp? z2d9wZ>_Eqh+`nm%)Y)`3rMYMiZ`8+Xoct^j=RC*SB>zl z$;a}YEckdQt7|{+?lW5O`~Tmm^l|celyM_1?@O8xb!;dw8QhHsIvP+oX0~{2T$S zzUo=MqaPpdk>2`^w(X7Z`hc;<>*aNrtJ;4}a!Lo&@5n9u=Pl`|^|3TjP~p$yM41Bb z2b_kPDBh|OYHP6Y7OD%_mW$wB-_#yriQxU^Y%2RWviBys?w)bd8edrTbkmzdhc<#! zg33}poMS+$x+$3d2eNwGb}=E(;{ez*w?jCs0lWXd)oGSE62b@jkmEil@MKyZ#@>7D z(Q|ynH9>oLqdq!t^0PT{u8N4f|9AfIdeg79_;`bGy5ZEJCfMzCN{5C9{@xp1P{X){ zvE{;_oCH$mBjsHkQMvHn{r|tp8!i8U%pkQWYEVP{?C%DN)c+G_t(dWD&`{%^RXt-R zdaG9yl-eRSD581On=xbtxzXm9FH9c<+gdE2{T?h2%x-Th_wODB$4<8N|6+O#%8GyH z<%I?Vk?8On7yjmewDmXT3ckrDunalwrNf&cjR#(sL&>oG+2D1%X|D!Zl6?%|JnCb*lI?NSi?i*7?Ru3%&*gf1u8X*0f9J zY}xM_rbC?LzlN6%`9WW!h5OW_USJO-d`Eg1W9;%Z#X*!A99SDSb z8u{FVuPTGrdZo+Oz8eLis?E&bKeU4tUQ_9tjt2uV7p2w4TR`gw0XBSHw>>~nL)-M=s&a_ z!CNoT{e&cf_xSeGosZfAV9)9!DU*V0z*KTv-oVf(*rM_b*gkFtLakv5Y}z59OXM)~ zu~zIEgVEQR(B3(;d@we?D(nLxFdltnFG9 zZ*TY(Jr>?=^T#tq5xgr)TR+$!cwac*;HHD%ZJ?^Kse>l~mMAViy}4l>SR%7ZA)Gi0 zTz5mUlO@RJL~q(_AHNXrOXz5U%zJFS9|rH;Ksd4lhJ^pb6;*fH#WZ8%ZL6XlzUC(F z;SH00SmETCRx99Tq`DaFU##kzEQ61?cKZXOGO{@lzSF0FP26M5NgF!JiQ0B7bYi#B zg0J3URQh5TjdNM0P_{Vq;Z$B^f$rb$R>;!V zje;n8r*QT|uffDCrwRA_L0~qF^V6;u*!_Pqo9U9;7=HLCIZm@TL$JdP8}BWhTMY9c z+M7W>Bm3Bhli#mpbRr`<1duym{3G`qKHh!l9cGUZyl3bXfmj9={eNbtcf^P53m$Je zYJD6|KeOUb|G$m`?&`g(>kfW1R%H5&f6^pA8);|)awCdP4G@h zfd-c${O2v`jO17*CKvwse` zymha>{a}aS4GFH(s6sX;I5^I{>3kam=ar0FX?+p`@yQqYZoe1>ii7I)5&EyeryrcP z-f_Xe{Oal{wu{(!f3h={eyz_BTan{r+lGGJDZs{i(teaEtWSG*50ib2;^eo#o@d*q zW&*g&I~%dd4L_)16YqL2gnuu}lGCC7zqm+PCA^~LP}zjdE@dpe%>`u}jUk6E1js<`P# z&!6W3jse2^28Qr!(3n>1_RkL*U^CA>hkLm3zaXVM&pS4)Ub*mVPyuy5Htz_Nsw(|G zgEXMP`(^y}CKT^2MFavC-j;_$4hSN6Ux~;tAmJT(qApYk!8<$I&N81E3Y*>Gw2LXw zgV(BYZSS~%9B<*fPH0|anKeNOic0*0IDZrC5e#+#{xFY&I90KADD_r`5mGXI

%c;{O2cJDaS2oD>7Fw57+A7a1F z?b<{9A+g{$NVibwV}skas|Sw%##^5P?-s|3-xs8lPH$xiedNZ%I||<4u7KdZZ(~w{ zBZ7C3y71@@1n*V7BRly`LSed(TgP}BwcvY;Ig-zpi~@+TXqtKQH83l0Zyr4n1QgOt zm68r&&SG$CzfdJM-bxcMlH4n35AS7U9|}16F}=TB{6&obuK9lZ zTK)nbZ*R?3?K}kU@q4f|I)TL75KraOR*uPqrlQ7 zCP1|PHCX1X9V=%N4DQFDA6aq&`+_tcqO~hGod8@-juT*Cy0KChdvc<-^^W7#UfRQ( zi|j)gC%+uAVKdHOJYbnia|8cfe7wu@iz8ofHNi>yHPS>m@%R7flA@-N7fBZWPz+ID_(;J;o`)%I>BIqZ}rWO+SqtsPRGDl1Fm>MD__aHTB@x?WqqzzJy`Il)Txe>6gyRfzEFAJD6*ieZrZWKt$vpw}F z>j3R{GGDjz2Z9l%8(tL^?l9Kx=Eu~fM-L+f;Lqf^MwtrsR88z57HDxL%3IUk6T3gj zK6G*N+gxavo}NnpE3y>&*_0qXtltaz&%5+)p1!rL0S;^Gxc>YseuG4}HS69BkN<)G z--=2fniKEISL~Qj;N1~uaRMD;-BlO`u<(wQKKtw{g10KWZRlRE*!jYVOzuE%H2`Sy`D5elZosee#zp`x zBgeH3>L1tqhCRf(KCaI=vzzwtMt!*8=ByO)aXn;#o z9-O=I7Jq~Em9ndu8mr!dZ;-yKQ0K$$!j&4KKPN~xP~iP~{m=I(-U4MUOR(@hp!0bQ(6^ht~RwSBB9Z-ezPU5jgod4=P+{ z=HdY}Vmq|o5b*JCl{M$Pj^KSg&?`nJ62E#!sd|U^9{nHqKw6zT9~Kqa+XeD|H%P`5 zc(==+os5y3-1w@hYB4C-t(_y6i9fVwi+CnM>a?Uk6kkJ=Lv_m{<4s>3pRrp zT|x+xr$@n6y2?1AJsp5sM3K)xB@nn4*_&?B!p8f{xo-nZ&glXf9^!!Ebk zhY-AL_N6;}eL?o#m^AceQ;guHi|mq<&y0eNT)!T_GwuKv_2+he`Wgu8Jox*8xCiFk zd-6)I(X%K4xQQIMTefz$%Xe(N-{qC8+3ZJq{r?xTkGDAam6%$%-tOlCi|Z9mwfUbW!+e>z(#eJt_qA{|cr_xwNFtf`_09GUZlhq;HoDSdTAiS-;AKm#djJ^!Qjn1!i#^1O+kHys-7N@DlH+({f?Nx7 zvHSmeD=!XK8QL3SCCEM=;pAsiHeX?~lK^C&Es36q#vfwGUQftz&ey|=lYEY{6;vFM z?q};dr13v+|KEEmeaP;cTKQ)OX)^`heeP)&P`tBG&5B^*-D_|%&H%yt!Rx6P&IsO1 zb++Y5BSS3z8@R-pBML52H(c&eU4_ z>>+ks$vY)mMG&qg$5mMUvTb~ejdx6F@qr9E+Qa(`*+(=^e*8oH7I{Jh@KpUMSmKV4 z_p{lzs$WeTV0+e{!s#{mCrIf=fn)OVcME@rB~s@@h4(>h)WzR3NHYq&d$rCDqj(Q( zYgmef_tB^8n{5%iQydMYNO;5M_a^)iy#2RN_C1P@ge|VsAKxu)3m@`X*Z3s>x!%%M z$ZjVif_Ld`=i=c2FdtT8v5$a_H+SZ`?qEhinBm}`xYX6Jr~S&X@n&`_ml0E;J-ksL zOgQpNN{(x~|UzrD1eyT*U}f^U$jsq|s9 zs^@8B%Mi>k4^PiV-dLwwVX;}vEMezP))KTAp;GJl`^zri6 zL$JQ=D$ODb8~9a?uHWU*QQ#7CR@~!b2Y8qeD>W_-N8l1AF%5WK}B^o|$Y zqT+C(h_U0&P1Xw@Z#pV{tSs?O6#esg%O(oEySgPkQM}u^U4^jlex0>ycMO6zzwz{A z(%zfmN42Xa$m;Dtw^X$j{UKPSg?N`y$O>lvMCaoWISTG&Pah0<-T^{tId$Bm0>K`x zo`~+{r?@+XAo~IWBgavFPJqY`jwsEN}Z@Lwk6mK2GA~cQ@@@+#4qXU}5}T zyF(WrZ+6o`?Dmwx8I=l^NA>;F$` zNdIq1QG*6kO6AcSbakDW3|0-2txX&PX6smEuyhvf)u0x#k1aU)wa)uIIP;DG=<1&}yWhjFL7R=agv5gC;WwR% z>A}(XN9-<7TbqPlU-(~;#!%@aYbD!uy@cO0NDB(Q2i)v3P`ocnPDx?mz0-A$z6-%y zYE;dTgg1{UbmI_$cY(}Jz2)qO;eq_cUXxBc;kT=}z8Gv91(%-PH0Lbp1Z}Cq?UMTg zz>ADN!Z9A~Ay)CJ1tIXP5RAsnwcC4$ZNbJH*8N~yR6=`rE0KLv;pDe!D{pf!a{s^S z{tmn3e}MO(Z*m_~8vYIv-EG2>uj0}Reg;{8i#i`h#SGGrRUGL9>1`Bv_pgQ2QM_jo zY9z7n&Rou{@fpFpvWg{TAAS7YNHn_4$7eV_L5hRHr+ zaPkv=wRUwavU*#xOsC|)4gBh@Y$CCJ3sSw~3q(>39#XM`7Tzcz-uekif!wY=x@|BhnxZut9HJ5xn^{I0W($y#1bZ?c0zL1xFvL znPV%php%`Q9)0RC3T9Rlm#y&a1jHbhOT$ng(D9!Q6?=n?w|4f^_|q0b@H%o_tdzd^ zrzmW^bJtk#IQx&LEot4@{r~B$DFYtMX%FxFWFKib`I&6sledv10Oh-HCRQKC z$2*Mq)#SjhdU(0->Qf_Z_;_=9{4%JLUHI2qI=EBk!%8ggn^)Su{r`d}V#o~AmZAoI zIx3Ze)*ustfILQYF9WKu$Z`6>1gyTMgg!aYhDZXw6tJm|I1-}NFJw%-kw`VgOI*~U>5xlok;61YA#xoS}B|ksNV&T18_0btW1n)tv zBhNe#yeCedw^)xnv2&gObh7o#VR-J0NXJe;z!u91HKU_+jE11n+%3uJ-N--lqG)lr@q5 zzq}-Yd3Wkzc)yj(worE`*m!{b9wV@}^${?Fk=D+;`a>O*uT|8$&bzB zRQ8S~1TeqnW+VLze7qmM_PAkfP!Ge?+h26u!k>H7ZHRt0;d5u<<4vWH=0kj}UH`uS zhu6Z<#@{0|NJokq^d;ty4O)XX25~51)u4PwlaG_1O7!Rwi#2?a8l=*+Y*qp3|67}v z{jjW#hI_ggI~{(y!69otUZ-C&3belMev^8$3q;r*mb0Gq2W9D7bI0SbYtZ>}!yByX zOW`}@I2ma>0Xg#k%>F-JMb(>aNCfknrvKJ2`vTcV22Os*pVZz6s^kH?Z{IR{W{Te+ zU2)E|%llRfvnv^MNwDMZ|I?+aMrBsiE&Lipr4M(xWf}6tzh{sR6nKwsbpC6Ib+3D+ zh=q6S&oz%(kRet%OyYnKg7>>_!=(VhTW0gOo|lEu@V3)Q_Re+t;AoZu*Y$-*!FA3e zgX`H{;0yEF(5>_V;91UYk3bh}yl;mPqgA<=!Y{~izMI#c(ig|ZTU-BlkLXw0!@Hd9 zLkB0nTOmA*jWNjke@gwMFV^AX{k~h~)G^&UI442&+=Eu{ig(u(u<-uG=6h5W!P{JG_MSI_cNuSo%4P)bIWFFE zfw*Yc{@b3%h32lXPPBt%ruZm$xq0unbxap{zI+n{cfLP3-+a=#WgB*bq--t8QTsBL#>5r*B!aqsVr-|zdI%?Y*p3R~l8@awG{vJZ8f{DjJG!dXlN@Q|pm zYP&jq_2z8b6<&i>?{6VS!e&`i^#30QBCMa^S@8S+bkzD-EyY7V-eO0AH}RgOB8qpa zqsdAvyl49N9^ZiAZS9hyPr`fdyNG8tf;aKN-QB0xMI9Hg$MVps3ZwEd0dYP46q zEyzB)aPqsmlwIAbh6nKaXqdT)q#Uc5tBaN6n$zMH3uZ_|?yUD_z zdsFG7tupD_2y(sUzu*7=MF8#ofb{=+C~DBmfror(4LTXbpn+9`9OjHtk0JfPvMvN{tx!#N>=gYn2bYIpIvxtvMo4Q2%kbPpTWlnwk~;n)Cx~ zSL&qp{mlo`$+s`vy*RuS<{-y8o~q?65yEbep80FikEhUHgLIPY124b9%}`8I2oHGN zu9%URgkOW~<1)f;CDp)8(%3UdvziC?;k8TQ1LU}eTV7>rOkxkQXI>3= zAIzgYyf>45;N{1rA-v^hIS&{$J6hitg^zdZ3HD!45WHvdrH=Z%pyGgZ-QiUM9#TdBY8ois5j;UESa=US-DLL| z!TX2q?c06`-cMCye3_62>4{;_MgFm9_~nIsW7iMvFul9zDlfKCuqg1nO~9KjuzmfD z=Zq))!O*IwJ<7kZ@ebdzPNDY5Qh1mg*I_dd`9cF5?@LSv^Jg186WTHFJHM=^wh#1xgco{Dqe57fAm5Y$0gYXU%hRp^ikvp2{0e~y}Y%P z0`H0Yj-4ppij1bpSa=_PH$(ph!TW$?!B^7WTh(so5Mc!Gya(;3NgdHJU)TCOH-C^+gJh5wq}IN0ro*a1DNjx~?}&ic@^UR@(bx{PCBgb(B6baYOVGprBH=~>+Hqc%TxQYkUxQvsoIm+?>>)gETf8^1k%}2)@Wx0Rb$G!Kv2-ES`EV0-u&(;@dx&+V z!25^B$-j=b>@u&{!ooZIUMGVVf_LrNwQMB3WjcA}!VtWj&aV9uVjcsZ+_$|13iOA+ zSBTwr7$O4mJXUGC&~9*Y^rhOC=YGJsrhD*GF*e?eJ(&SNF#Pk$%Xb&B@hg*8ciX;=Md3O&-h)hX9$AjGhxawI54`*|1PM#OJtly;^}?FOGJL!{r0;zH zf#5x!EO+lSHLtgDMM$s+Ed1*&=&1G4zeI-odW$m!-ru?+{ZYIlPq=Dg;VrARFLy73 z_mB33gFy)1xuPGJj#{ef&DfiIDDQ}YhrfOx=6~{qlfLy!dXE!V} z;5~b(>aWvV1Ut<&Sa`3KGUPsh;JusqLwO*AH{X??PJ&4Fwv|d;vS(uq{PywPcZ+;| zVVS&y>!+rPVD^-Z-Yv~;U}7F~VgvG-$`RAya|U~`@qT^SO6&xe2%JQYtB5!IzU*(# z-YN}m%Bzc^J-oZfKJfBmV5>5l*W>|@z|S<_41Byprb<^!@YTXPavH20(fD6)(OHSB zuJO=b@OabNQ0L>k;;baozvurcyKLJ18R`E$|5JnH7+l`uqW%9qb!%p<8pK^wXaJ9t z=s5_~RvkoY5K#I#e#=5t?`(@7?`5?Z`0m~h4+ED3!z=Ejx*m8;1i+|AjdipeJn-*j zW3BWByjD+pq=T{VAenvHs*&3+0;6#cv@&X!S7Hyb`I9xyKV6s7-1+|>WFG}M`R!R8 znEM?$LHbo5KBuviRSyps+sCd(HEXM3XzD^}G8I?s(4EU``w>g?fE z^t(awpun46RcJSg_gjhOOjvmHFWMB;ir_sp$TuBEnn9-Kh%QEEkg^<$98!?uEyU(b zX@Q$TuyW8E&#C7`0B^WIl+e`;_E>1=GE^W}<+%5Ie%^?Ucdozqmr!JR3yn)kN{Rd& zi;Z_lPlPtF2kqfqK=y%`AFuKAyYL(j*m$DFw1yoYZ%Nps;YL_B9JcDx&U>u*L+ru0 zrj$)Tloovdzc`*c9}KCZv66odNV`+uy@*@%35vJatse|ncuRW8XM8~LW{($EAmLq? zbiywh!F&8UU6B9U7}$4tYiOcY5X|Kd`VO@c!Rx1N;`bZ6ffPe$MSYDgfW#OGaq8H3 zn<_dV0?6_fGdWI@d0AeyBR1ZwWy0y1ezb@87P1e#{NfT#Z~5sEfTOGBO;rYbylwcE z`X&*)+v&bQr>J?oC3|wm{0WT(k2f8)KJF}%QvCCQ^#1?gEj#~i%n!x;GwV}&EWB;~ zi#~lv@ZM2r>KuyT{Y4b2=Rz7JqZsbQ%yluaVqezw{*pjgVbesZKnD@Izl-2qK2)^-h)E0_*(%0s znh*dVj6b80+Cv0)PB=Ew7j%OU8|zFIp7;Tgbm^B2i?GlC2dz8y=?!vRMU))ZA#77* zp%sXE&YeqH{e-G6?e+g5WFL6>9m`yIU4vsW7(XtnJl=zkx1jd55G`cy&EitTxppeP z|5uY=&zj+RYr)UG)2Q^ZtXyQz@z^xLhBPs68LH{HC%6Z=+qoOLE4fR!&vB=4M{@^q zyK>udZ{pVBR^*o8Ud+wN^_6RwtBdO?R~6R{t^%$!u6V8kT<%;BT;^OVTrynzTr8Y( zoJ7t(&SuUU&Rd)pI5RnuIKw%;Ih{ByI1M>9IAuA7IXO6fag1}k=V;@o=P2j6%#p)! zf~}OTkS(1pku8kPlWiy4RyKV$HMZq!f^2N8KUl|D-?F}Btz*5zdXY7o^%(0RR$taV ztX8bXteULytRk#jtaL0BECVdrO^c1RsZa@W48Way5fZQPm$Q;sxR3I6MA7WviVmDOYVT-Pe$lD zszR7=e21Q)D(I=C0Q3}9f#+UHLQhZ?;ICc;Jw}zk@s2L22~~c=^S)3cs(juJ5ugTC zd0#3jgz8b{6{STFJwlbI*?kqL4pklkLTjN~RP7&IA`R7`%B}V+5qgNKeR+;GP&KMt zx9(DbU{twi*bPEesM`BQEDm~rsy&rAo1pus+MW7761s;fr=4CbP$jB%DMj)@6{vEY zPh)|~QRVPtEhlsrRrcA+E1)~5+TrnF2)d0bJNf%I&@EKiE)nX2%1~v~+nfiLqRRSg z8#8nhRaSmNkE!zq zLOH0?4t}r?I)f@LjX8ZN8&zvLy4ayCRIO>LtAR36rEw{DJCuPc^%(Z|P&%sA*0YyD zr%|Q4#M%H#LzQyx*(~T3s+214`#`CvTAkFq3p$A^MN{EZPztIP#G}7J$*5ZSN!JWI zfhzeYyu;9ORLPwVz6Bjam8|*xPUtAAR!HT`K}o1uHn&;_I)W;hM=!deL{v!^yz++< zP$jjyK?aIPm81sq1}F|y;=h*ZL$Rn5d;HcDib0iV!7e!{8dV~$$xhH=R4uhn*M_1{ zCCrq?14W`r@GX=N9YU2r#pC5r1giM`2cJRVs9Lg-aWQldReVzSjzM9lT09cA4hlsT z;o;?U=m4sC5^|nGA*kZs@?|p=j4CeKja*O=syIdm*Fk}(Vt=$k4+=mPTaw%r$RAa# z_R98#QZUIB7L73tI-v=3FJLr#z@sz_%-AQx1Tw$LGGRFQTZp}nXgeftOPK^5s! zDQGvUNMDvfPN*Us#D{jFiga!n+KDRC4MLD3sz?{EKn|!P-A@78ql)x7KePi?q_3YL zJ5-VGA%<*GMY^^X+KwvHEtilDsz{dtLe{7v-Ju3qp^EgH5oC!f(&I0X1*%AIWkB0d zMS5BQ+KMXDP3+JXvXaY9+{X!hM%6hd4+m%rRcF;W1EEn=o%!Cb0})Y`-P|(|eL_`M z-pxnQ2&yujrDUOxsLEJfr~(b6Dqa6I1bskNTAOteG=!>CxwY@0K~$w4UYQCFpz5TK zVgb~TsuT{n3g|tmP7v>}gWjR)_{GuB&|6d;3)&s7may z{{{7+D&cOPH`I-)_?W$^P#3D=%(@Riov4Zx6Rv?eP!&CK-WYm~s>7At$DwvqMWswO zK(A00xubg()P|}wmt7HlV6q z{`4GVjH7c4{M(Z@BjjD$F**HiGRrROOxIt@C^~g=w z9MVKpoviIzXbq}r8QQxb4OBgBo6?5VQB|EE7YC`K3J&^g0I8y?YF9-tq=KpkoQ9c@ zGOF&i7jK1>$Vx76THPEPNB^$!^3oU3YE)H(Ut@w4QB}VAMiHcds=ItE1))`_y4_!Y z4qAz-TNQrOkUXl&;yIHbIaHOpJnM&KQFT+?Ko(kos_WC2CZOf0x>mb33tEP%t4Z&C zAQ@DZ*k6AFNu%n@O5Yhs3RRcBo|J$jQFXDgSq_pwRdKfFHb@**7jpZ0Au&`H>78(e zL{U{p-#-tDpsJu{T_Lm-RrzPX--Luwl^0Zg5fVaGt^tb`B#5eW(8e8*0IG6&pT|M` zs5(<(eH>bXs_fvq8W10#Ii zmxpAp94;dQje%p$8#nfVBX=FQ<{%rSyG|r@iOpf}AVGz02l`iu!8^%u%(0ynqpYM3SMsphW{Dz4b+ zxYH)YW4PegAnCfO^fB^dCHaaSUkbcQ({vPXbq@h{EWF>GjIZ-X@OCU_BpyQW-a5C; z_aK6Ip_}Wka+w&|XZeq_oNGehvn%Dd9x5k-4NZwT#Tq?8jCoa%hnOGOYhunW^Bj8z z>D)9&V<@*6yoVgOdGg$>$4_j$Yv)vUpY5bQybH)a9^vFSZLqbrV44SrGxHq&ZiJ6_ z*0XOGlEP3k*Qyi@D@S+Vfu zEgu<B?u_Zb+OOJ z$0Zkh^>zT%`8aB7V%q-a^p+O|-lUa56z|kCMH+U{!42X)sqe)ry%Dqq1t}OV#;QT1 z;>Y^Fenh@O60Uq2gVdmNPw&4KM21+awAhMmyfJXZ{d4DBat^?{^6H0;bBI9ND)yq& z#U8-leuK`d+81~PUCpqI$8M0EJ?6f9M2W-hf*)e(GO6@o zBp|8w=LBgG1>U61J{0d}W)T7w-alUFPqHFItj~IuMI^k-I z?fe&Pylr1jzuu-tdw9o^ecjV3-GNvsX@AoQRM2(mQN?-UZe0%9Gc*ZB3~- zK}sl$zHV}J;p5FqoexdMA4(1@<4N!T1ybNm+Py~cu3P(t8w>AKYo9oaA$SMoa>zy_ zcpnZk+3bbjJ@jenSc7m3{1`42E}jX2pLAw_d|E^VhXWIabfbH~m#0atZE?+w~^x>{m{*R+>VX6W~*sAne zFkF7-RU|&%&Cu}iw2o?c4RFf4rjC#IjXg~=T;3H6{(^KiSL%Fl`Lu+8i~HUG2T~>>g{{!RxINIn15w)bmnCu_!-^o zGw$63WThsxnvl<1!Unia=5}FEPG;F8J(q-u!J*_h4o;bMZ?1aH$mnX9DL+ikX=ga}CW zKCb?F^zf4qnA_Rk%Je!BaNC8M%-Z*WgwK+pdC1<|MYi79Q&QM?n|PJK_+lXjqjC4j z-X4eQv6r_DGQL+b-lILd&B#6saq>GKGPqxi$ODqxe>i2k;N#tPWl+fn*?YUZsrqZ* zN_@O|X7*O!KDu_nPfq&2QRjoH_Z4g5sekYP|L@IP{=vT)nL!?;s6nI?mVebC&2@rU zHE87Uv`re)|F0e#nn*xukP%ONirhBjiXG>xAAN;lVE&K|Zu|Q~VW59^kxDFb|6i!$ z&+AYxkk%`C`6J60uQ4cP&lx8JyUri5$Jpi5FDQF0nE|c@9(-cbBH%LcJ9e%YjO2FU9 zae`5f^c7mzc)$J83yOwl4{y}R8=U;!4Ie+kB1-_AS5%ds+{4HF!sVa#h6vtGy*U-H z?D6rY6S@6z_ScyOk2jq#l|HJcb+nw9knj$rz?*ai9>rU9sCx+(-g4}x-rhs--ZCP) zF&@EtULd^pE`s;tSjYRPd17F->P4?ksfWVbExk&v9Y=PM>WY6^zwZI*e7irKm-PcP zqBGle61*_`^#tg{`hrn$7>(o5Qm~e3!p3`z%gu7x!5 z@Agwgd{}rJ?`gd90>PV@6Y3v_;5~LuWBe6@_rSGn5oZy+Pt={i3A2a7<#7}7mr{vf zV!Wd9-18prqVCiRT@gQU_hyn^&tvTBJ(D4qN_;2|my_eFh6XO_L}KF|RJ^*MKu>$i zTeD;z0XX^X`k7d2Kx4e3HwZz<+?ZnGeg+fN%Jd z6GqrOcG-*N3m)$|Dt&Z*eC{2a^KbwE54!OGUTB0(bEYrQc5p!Jx^(`2~I+>NS@bCX$ z98H~%BW`jEf$_hG*hmVzNgp2ng?HVY2o~N9u9AgD2;OiU&*q~D-X-B8K7I(^9V7Af z-;o2-tTO5S(K`;pgY7n7`h1Dt>`njotd_li&uGOmIVT^$^AUOP#Sa_rU0fDp8()gU zi^*|mt1~9{UBkv(&O=Mzp`G^dMt#WRoAf0;iZ@4F^HMCl&xlW|*dchY z-*z)73Bh}PMR;yJg16TjnegrvF>ul}ozM-sgRuCCumcT2M6hT~$L%NR1)H>gmf?6viqAE;1>U5)PEfq*`}YZ9;aywHeJ%>Y`@5}hQzC-*+|<2oQwZJ{kBAg} z6^()KC`SiBkq(2GXNu|iL=piL=azT2!o6T=Ocl^i^#yw-^m*?wVJ~m3+fx;JO;iGQ zCdYjadDKH{yoL?h3#<+(hdXt{`}b`w6{-Fxr!-%PKDo$Ofi zgL|o%oOIIND)3+U`~Okx)cLrrWvSP2?%)0&?Y(IFPo)26qNqWn+n&%Gr0*{$gH?m* z_^jnxhD-DwA7AB}g47`2?MC@wNDZ2#e|X9)AqEzL?`8DUN5CrO@F81EBH%G&5wxl6 z1wWLH_n%|-1xXnnfY9IU|9k70J>kD60UssD@gHCF{k2mFW}lmCIPKKBp7v^x57|c= zPJSa37VIW|1h8>HYb;xoO%IQm9Yuo?9x2uEfuZhKGFtd2Na-ZLzZP!1vEUmds(o@EcFLxUnhW3Dmq zp`V8$@>0X$d(JP|WNnFnFL+`*ducDYNw{*pOu!es=ev0u zAMflOc4!Gfe8D$Jg;e^uC%(6!=?H0gE17`;Z_<5yDBit=_aw3KK5m#jKZD?X>Tz<} z2?Xya9k0Vx5WG!1&%~;(kAYKt`NLG%!eRc0ObG&xL{PHq1fy1NFG$@^aDAZY3)(#d zL-(;_&mbROV+oEtD*<W z^@3tEd3E=LK48%e^|e}z*wwpL$>P4!atWA`99JGXHQ>J&yFoHr9>_8HkoK0hUXp#7 z*{3Ax_l zUd^V%7dS<48(qr=GS&`!CJm`UI(xP~nc1SMH#e)xD8DNfc2ii=(Qq^p9`lITjMXLr=e_T{ zxWxK^C_Gbq;f5E8%(moJzJPrP$+w+*j~L&VfTPH90U|!{E^frGK?Unla~65hUJd$A z_EChB-(jilan>mwP_k&H*SGEXLoEBFR=rhH)$r4nYMszM_&Z2ahh#)g$rUa5AvTgq zA9;?}scOHk*hyxkz?*alI*NDTwsBc3yiE<#8)6W=-z10)oI>yxIC{KA8X01LbYvcQ zt{w}Imoc3b5RZh#1edVnS}yx(yjg|-hNjrS76~i9#Au%j^Lf( z6v#xvn_pPj(FVcWR_WF73g%ciDQLgLv7AHj(~-yW zrC%exdp$nh+3k?-m8Hn?7T?J)%Z90#L9W$nuQ{l=;Fq`PsPxg`mKD9Wim)ASa`d6opq^OmXl5au?R6nXSj}|Jjva6sh-1z$?jd5AWRRwiLl$-WpxM zArVrdz2z+qvX3#G{Avnb%6j?|zySLU=+wZ+TfxsgxoLAXtaK;qM+^%--aB742KH?d zUhvg>{3UfhX13~V^-B7UH!}s^q<2?Pyf+KlF2llGRjaPz0fKkQ`K(PR5xhHJ3PMQ; z-g-xZTyoDNtGB0(ELJ*2z;YTN#N*6~KwFaIenERLaO!!IoV&{hcm?@}R7qmv&Ad*+ z{NYmx*qau{lFPzC49Vne^hD^ z5xighQnTMc&FigaDmLewkXi6}(`8fXZ##dV+n|YaFg*xM7~xHy1@ATKb`EA_tv@p0}av& z>U=CpmWa4e_IrrsqQINV@)bmimdc?sBn z9M{@HZ~1c+`~1Im&bBJ6wX}!#O|lPPoctvDpRqTM^ML1-`JU^d@$s%2ajZHZQ4L%C zFnph3h=0B1buM4m@Iu0ZZ;&oi=_A0KRrX2RZ@f7v@Fu+th~jW*~T%rY+id8NoX@7&0q(6$=}~%rP=fQLt02bcwhE5xif2Xw~xEqulQU(#aeY zc#|HxMDZ@Ve|QxZ-pkeak~blEd!M`=osQsrzsB^}6$J11#OKbV=VRdy4;?i33rE4s zdf(*7l#%cMuQ4BfzP=AQik^<;Y48HFVlCbxOxVj?F+{<6-Om!RJUK2=xK%s6?r$b1 zUd`XQd}t5vII<5rocxSUx$hoiC4lU+>6sRu_;|-(-XZQPjBHN)vMhNyL&fCe#FD2> zGOHJUgG8l|wx-)_{qO&--s}{3lU{E{@y@@mzY+^?7N5;kjtJi0k7wkaM)1C%yvC#% z!TUr0n^#9;V&M@*^LuMQM8ZN@AMYZaD!A4)$^LnDALum5RJ7gZ4NR=;pR<=@t-``Jrc<(0rNX5x7-1eyUiv|LaoSc>#{s((+;!AH! zeWv2|7Wor~K9a{4{@GhKDt*X~swmt=uDAGi|NpP?n|6Od`hPx(8bo@(8m&S1oftK+ zYEZSSXI|-t61~KHwX(BF4VtU6iMfufK|bF9`pa-@9Nhe1qCtE2Vfc_-t@RQPBB*7* z*74?PAJ`&P_tbj7CwSU5eD0Mf_6DiNjM1j6`jRjj7pttl=g|-BA@);_tz%EM5axQq zf9pShCE3RqPJX(UeSrl#3E)N`(dXSg{2|uiz~R@1o2%eAm4dgkM)7Zu8k0I>@seL+ z!OtM$C8_gaZF}j}%B0^1q)ODaCeLGXTY{o05- zf;aKN$=QUmI5;oZ(|M=aVK{zFHuDY-a{pg;;X0=KeISd~@3VEE2bd%(Pp~b=ZjeT6 zWHsv7NWxR(xW%5?Kh8*DHOa_$i)eNy?OYXjnx_(kN01nd?YYsEBW+eV*(5v!8vw zzrJ(6>-p>Ly}GaKx$pP+z4u=CUTd$jW6>~jtAN*iWqv2(b70w;z$s6J=h5#U$Jb!< z9)tT+7Zt<+CGLG(jae%fHt#o+m9fL0=#Td|w2t>U`S~o1tTO84MR?CP+jdppckde? zJv$R%_nvXw{{FE&{_8Em2#I*6s0ij~r@sMdCtAmTocx3q zZZNLT&ln1)ul*)%VYY^xgqKrXDKj+TveMM9BU+aWh(q@#lXU>j+vXaZN6D zu6y%R@m^yhoJip<_;S567H`qgJ;pPT_u7Sa0)KeReIdL!33<-AQHrFOXuD< zN(2EPG9H~?0WT-wGU45OvJ<&{@ukc_j2B`kEC2mS9X4;f++BzA7mI-{Xxw}=U!6jI zY~B$Tnv!J#^v8P-S_cUyzZIc%Zw?&fLx8a5^}G~(-aMzQTUFuS+wvS;{g;;byu-h| z;23wh#PGZoXsm;OVc4`w?0@tB|JBU-zxwCG`F|-@57Od#%lW4VN%gLBamjHeVD+F} z`7N8QVGrU{I&XLh_MqmwEt%qQ1*z`&!t|6Y{jDG=bv(t% zFRAn1xg9aQh;@Fk*2-D@9yH{qTqAJ13hduK=y>%h4F{xu*4EYgt1^5KB23X($GqF> zf6gF5-b<)>YreQ&M|s5B={;PB#XD!KbB`5HXHIz0;7D6koWjUiCs)DkZr zMm*TB*t0%35@(OmA8$$>c=;VN8cUEcf;UK!xmzR#@p%icl-^@DSqS42+_2w%20ho_)mb-k;d}42RFqA8$$>c=-tzy+3an&x-_HiYjI4!sor9 zY46pF%35Hb(wx3U8~=cGgPl}wr>zLXzr77~q^%BafsdaHPtWldqT;O{!P!IM{lVbS zS}fkBwfQWkA@9ZB%cCzLsM=`XZxtL52AK3=z+68n!weup6j^OeX z+gY)C(E90^V?PJr5j#$nfn3;wZVB5yh=lJTPf3ps$+?q&`zb%=ZiO)5XRDvx(oaSn zM^~Opu<1f_U)6t8m+?dnsyh7O0@#mOjwMFbVQyl;3ymA?isy2;i`|1t1DD@Fn6!lM z_W#+?I!bWz8#A@F5D(#d4EFd7{kf$t-F#;)Gj{cvaUW@DT&WJi$F{k z4XXnBG2t#D@A2pVbtP_Xw}mtqe?Tgxtq!$_>u=5m%<*1E#e04B!5m8WjyL$ujKzCD z_iDll$os+3HynR>>oRvSUxmEACTa{nxsbrG%IjmN&BDO!{?Go?!(^m7o@FP~hAyPJ zrEXFg@(#9o=OJRgcI|IkV&E7WS3Q69+(|QR-W#nt1BTDjU-!O+)`6GbHtCz{ zMJas9$@)9pKp3C*?USF^szKiOjf)rSB;fNVXk0$#c4Gs>^Cqa#SjRMrS0=nc3NB7W zsCa81x$R2fU8MYo35&N@oaIg>$Xk)6V0jMYeQ09U^D@Z$e1%KrKFGT^e^7+gDGa#T z?Yf;iN=9}hr~T|!>_XzZ*L~Ai?um5mJinT>1Dkie#+2&y)ncFnjSKtX^nI}?Ht$E` zgQJpH=#O_CS_fW!x}(Np*PintHL+^_BOLg=M}O`L^SM<8rjq5CZjHe|oaoI|;-4p5 z!SK9m2(;BPpH;s`aPG&6;)SVruhaN7cRBH&#ff5T+&nDaZRRRPx{$YkJ%`$5$U7k_ zvvwHrb`pEebitMcgaSL>xgH4vpO}~}Ouv(n#Bs92L-8(T)xZs5VS7)+`ln0o^7Yuf zqc2ND=$#S++t9c}#jKrKU$9?q6&3}Zdu>a9^FO5yy!@_j3S=#Wn-j@Td%g&9;`9E3 z@;*8LWwxCU{_8E`_SsJl)~sUqwf72Z+UhX7tz{UT_22xDH^b4z-@`|&1XT~x8((*w z@`(M?y@d;_2iYD`P)djM|K{!L3Hh)G<=kVEjWB~3q;=bC?R6l5<>Dd&tjuA6**;2~ zyOoU0ypI~>Oz1**^gG9)awSDDU z$M8LfaGka~rcbjeeyW%oki@BYZ?5|sMBzOawuBRlx7+RE%f*m4nVIj>b;!GVLS=I) zSx@Bezb4oU9>rA-kpayK+5jCdt@hv&Aa)O zVsvYb7$`>L%t>tpy+zo(U3Y!n6GMl*DRu0}$?sQulfJVAAJRJCq}$U9pSQS`Xz4AR zO3-J-oh2rK&wJF5FnD-@Jj1Ubw;Z9Zj^2brX21U4ASFh{TQ`IA8-@4&o8#U5K~; zhX~2j9!Q`(?_2Jr*u2lM-sE(-EC&40IEPC>>wFY8Z*NXPh3`cA>)w<)ym0ahv|qDE z$e9mOjGaDmcPl>c(Iwtme|VpFY6#x?h=%k38(v9!g{m+-Zvw4#tPPV?_Y zjsry$-V>%ZY*@Uz?tQ9!1$oPQSJvf0-mxi{n55x=RM7Y4q6VD*hb^aDezV6|z00~1@T3}9Y1`AVL8`g+@XD5Q z#^+6A9kmzzQ&iy(q`|efC>3uV4PH?SZ#CiA1z5aI4|Zw|Lf+wH_pp9W{9KooED%|bnZglJa`y(*9dM-EU2?9;lbYj|K(q^ z%r#65q@Z!5(p|sKEXC&iP9lu|2_3$@rPT2TC%+>b6a+4i`H(~DOgHki@p+r4-^|+R zUI}!ovMUuP@Of`AA}qWobC2QI-nE9b)$y!E>D&3p|IYu@#e9#K1nfbwR6WRe=;VG% z56U#&%#YQBJY|BG>B1f~&cUR6BqkhVHL-%Wf`T|4)Pm7(HoRQfKK!h3!J4<8n95uG9fE66)mw8f$r@?Ohr+azSF zsw3xo^zp+TBtST%lim(_Pbx|oylNyP_07XO3AekDpP_6i{$JdY8ybNeKdxi*j^E5; z>qZa<*U`9~{4UvV#l8_L4W+VOaK8@B>1NGR zDP>^kkKlJA zAX??&0(nQ}_Bs|p-q!<@PIyAzKEl(?t9OyWdes@T-H>;vot{DSV=}Td!7@F$vB2~&^YB!1_z=pV|VZ9rMtp1&FGK!Hna{BPJY{` zBd>J{@gW&ZPdCgD$LBrf^mXC_l26ORvaJZ5;_1X}Cxa$#Qccm9{6 z;%&G~U5mo|#r_KdJ-iuQr4i!S)X_gn)wm{x0tjKdSxItR$9Ba2?mI%r# zdCFftB_nK}G8sRwb|Kf_EzsP{d@s0SK9QqdrMOBHjv@SrSQHqMdZff{V8dxCI<2*KMjZ|fV_>*DF^L@ zZ*Suw2&)h6A%U;Y1Uv_(iQvHj!QTTf$cT-_R{^Q?E~HXM&-=Bu2cq3#@IbyDyL+pL zWY#%<6a#C~xW&xL3MQ%8yj9G2`s?ZN?JcDaC7k@ezlh?#sKkdTnK1wU>4DGtra)Lm z4&?3G;5WAEem&-Ezkf!rMU`S>0xFE(y%*D1M{V=EKW}gUJOBTW0Q&s{oc|T5dXUBY z?-wXNh}%(P304n^+>z%y*k7Piv*-nD1?)jFhkqZ|hmY7MqjR#u@+44kAg!Bwj0h6b zxc!T&;RflH!{qkyF2wlci*BN`J7T|B=T*Nxb`O$^*xY(xtvIkj#o+u_Q?e@?MjBe#D3DVY*dlkc72zwo?8p+Nbk>?9s zR4a|mTS>IBa#mg(NTYEtO=UK%ZouZf`FvdYg#r5Gt$@~{i<94t`??Bmy?Bu|8JEr; zuEFQswJAfPI^hPWYTxD1I)uN1R6F+ll_Bd*hUYC8LR%fHzg$!B`}=|PYAW7lA>Yj? zylY79i?Dca2-{J_30IIO@@7TKAny~uTwgBy!~4a9(3}kBJkrT(mNOAex5xe-npC8<{?=Bf(E=`&}_O=UIx}o?idB`2HYt~i^>&NE3r?f=&!E$k6 zg~l~X?O(e<3wwj~)dS&tPA>YJ|LxE^UgG4p_@mor_aOLzbohjtcMd-99l@57wX&sP zUBK4VGtD%7oX9#jwDPnb!_WVO1+>+1gHNdNn)2M@WEBLuR{igE8 zdqv3G=-_Jg639D8qIJs|$h+ZtLEIU*_vTWRUStX1-VUax+bpXmBR#CUPR=~whngMyhCC7yxnq zyIN^nJo8E5NSo@>BaevSx`2`{Qb#tsoW9I`Hz_-F`Foi~}z+yd|iDX&Ao;1?a5r z9*QmkYFf$@Izu$9AYb(jDHUyG_#Q-fPGcRX+XBV@?jR{s@wQHX1^?UM>n&Cr{#=I1 zds6Ct2IL)jBK1QxYB8P8t4=!R8(OYy0?M0{!tWM(e=KZ;xS9 zbl`GcL@iWz>R>lM@4@WI*Ox_$z-VRl{`f-tM=XJqlzimL6UOI#g0?ye-Y9DI{GI=m zsCZi)S{h2>ZEo;L1dI1mHJ#oYkTS!TX^0r;Uj^O>h6nqZ-_wE z=!VhD5;C&bKz(%_Yd2#3t6F(EZE6;(!H>GrwpN6t)kWx2EJu zRbn>%@g7C%z{_uyllFSfAzp-4w%-5QTYTP?Hr!D!-W39~S1be>8h$~luU%);Hd)3W zkRH)khjF0D>8kj-UvE*Q;%%vI^OVASaqW3wEZ%~J!>j8dZz09Wua%HDd6)7DZ^+vy z`)%2*Fua`j!H79WFA>bEIxNmtPDYk|_Aa~5)Qx1BB3+jp+>x_}?Sd8V*u2jl78GqX z5C^enT+fz|Um7=I^Ilu1S$4IO{&=57>%hy8+je?4QJfc%x@XIj`x2k`%UYJ!&mD!J zEA_3B#48%+|6eR257TuSfBvVj4o8b)`_0nk=KnQRytnguMNxQLHM%dw;w_-}-Mba? z{(SZK)Stb#`!T(P+aT{orSh|d(j>6w3AypaXCi30%`2u}Nk%4$yS#>ecOlFN+QyfJ zxFZR%H@-bSfzA8yOQvciJ;)o4>sYfwtNmYi-(yM5*!GP6cppORz{_t|@AK4&Z@h?o z(8II^4fwn#Kk0=W{#^_-crs563E?kJHkRg0%74;h_{E7v1#NY_U(T+=46nENZ~y;) zHHrV<1jG4Xld1>VJ=Wr;^dR;kF-fc*^m}V|kuvN-H(eGyxC48TM&aqP6cbe)w^I*Q z-Yg>l$tLEGyCp=>cqsLe$|W+AqSoYaNUR&NkbT^LW3@Zt-*IWCU=wx^a(F|KEgTmI zhtW72&fRgT&Df9F9sJF?QmypYgY3{cY;f{Bt8=EkyLch;Ff&##S&B;s4}%e@Zowk9 ze89vXKP??Z!~Xw~^MM=lbs4?~5f0N<$NS1V^@$hf9DAY>yc_8r zZ&YSefCEy3#)Z!+*u0NBS!-|kA`aNmxN^grdmrRu^Cl)VulUwSf4l?HIzn;s>*LW0 zG8N`UB1S#L1BCH;zaz41@8T)|k2@|^sCwY<{|m2Mp!Y)~kKuU}*V0x;`#Fik*9mjH z)v0*z_Pjkn;k{kzp%@l#V@(}R8_4^>3YVr^koU{h)CHxGx4{vvJw2QxFp+b4_pVwZ zFf3ep;y^ALnKd0ol!d#I!VQ)@Z#K9iB2nv7->k>x&7HxzW8|YaSc=A3EidqYnu*Pu zcgp+Cno0WO&4Jc|mtVr^p^{$s_IAFcoS7USKJVDn7{z+XySK@#_Hk1^{t41GQziBK zxeU*nAWvf*mopxq=l|8Hc<++CWkcbuaDcQDi}&8JU02*7?^9i$AK!$$y)S6-{CT~# zWdr;1pm`*a8&+{y91y|9E&67ud1U0WcF93Mp>9N_W|?<$jXR?8-Tb`C3^wlvzB>g( zK8XW$G;ZSO{+$<8j$;069Ic(rB=geW2I)Pt4!rzWvg~6OBzO@;m4>pkDf|IRW@cT+ z@iztF%=Y$6?7wJOoQNFm{d)O!4c?-M?*D!01hKztaaq zv3QT0MIAW?d0RDpeo;%sTY!fpm47x8q1#tFFq{%&N{PA zUSvQtfdem+239b`GSM$WVU-Tz1T z?dng0aQojTwWs)IJ?ufvJ+`ymMyfh(;T9Dg z@Q9tEi$=cvGa~TMu8OrwCL^LAdXriz-H7^vjJKz9-H^OM^{O0J>>d=jLHvVfojACP z#+{9fTl;nn%)%{<^* zY7n=(6#pHhiO`iFW>OCrz6Y&XN?RSNsP(+El#vCiMKXL7MG0D2v5gtMPrq z5ad0$GV*pE_`Bm@=Ksq@W{Ne!^v9c0M;1OKYwwB^wkWQ3UpQo<%oZ)#BR?}8TXqj2?!@sY$ z)=}|x+;f19(!EP>R?1-Ue)uuw)i21qckD8_2YDaz;;%Grt^EgqXm*xg&K zW5XM%74*m30j)z6C%>yT{k_Tkyoi1|-?y9V@Od|-xmu?XI3EreL1BQq-uD)<-@*D>KSCjn1#%(E8C6i7S|Wn|EiN)*&DAPi~uNWS=Y_!c^FFw@@9Qcg^KR znrcngz>c8P{X0_e2PDFtFS5=WY7Ebt;7DT~UT+Vd|NHY6YpHnK&nErTy~ED!l)~aI zDf`k#6!IQq7N`f1_cL(qqbl5cv*#PA{2>AN|F66qeppBZG8&G0%d*G__r0by^Q9o~ zH!lOCb=;9l_wTG7@W)A*kU(x-SXv?O^g!!J(utf8%r6LM2_ z-~PM*k0HkYKlA@4svhK4pFT`^#KyKRQNrp$rUFl{2Ei4iZFWgPE`9dD;Hl=7vmZY|;%c#D2sMtga<{ z@<@PRXq?8qg#jv)*pFC^)gs#0Iq9zl4Wf0ZZ)cHOg45S zTe>qAw5)YQ1Y@E<@&;h@9*uN#SD6t90%)A=VtI?a3T)mj(mX6&T=d6#46Wk@PJUXJ zQA#$4c#+RX6bRDJ_`HAGlGEiNZ;?*XZOmjER*(}S-;^$C3&Z9;)AwVMwgCO{rqnToliz(0t3AKRc#)RKfdlco@Oh_l z)ZX@el?y)DA8<&hrs3m6a-w#}Rb|GX|3A@K$JulH4 zRcAg|-G{vQiAB}khrF2+n##)|@9zCiMdq24z}q9qaVD>bfZ5YI=D>M){{M^b!V~J< zi0%v`>{{oBw5MH`>;IRtw@b(LCGy(EK^q#kp||wpVs-5KUtl=N`h+O`@ut+li<6(= zJHM%kQeNa2m$~l`6MWt^Uy^uptMUMg<8}$+I{dXa!O$t=?C~uOzxE~=(^kiX*yEr5 zaB=eA`F{p@1ppth22?%B``VR%enI+%Ad?1G4_cDyaat1gpeF9$xldpZIy_Ppv~Y{6 z&V{oYcO=Lp@M8GORf88{07Tn=cuyiDCn`RT-#70@2HnOpG+Eq`mnA>-#dl&qVq@G% z66^L$fLCbTQ|YVU-u}XV#Fo^2$?oQ+zaDf7t)mzxzjUYbW!cC0kaY6QK3*bz4>~!t zq<}cpo6HW1>7_jdp|WYb+H~xUz31fU3_0-c^J^~e)Q>FG#LpIx?KHX zEByZdgpQfw4_72%vMaxMEjI6q6?v_l77`!{jcYG8{yg;*n|I^um*2VA>5q2`T1Nv; zenTE{`!C++Lkc$+-#&L7pLc4BP@gU29eFP5_p+5VtRP#2I}4g`Fg$Mpt#yeQ zrborwYwN9l=6}m$S*lpPZwxLfG=#jb7GBJI40#{;LXagw-r~nN8&}*Vfso{9Z?zM{ zK$>1npJ@yk*);EX;EYi>@@|}m+i9m8ve@s3^_mWB-n;JzTK?E10hXX~O&xx#A8*HA zL2`Xh(Rs%~f4uF`Iyi9hODkGl;ugY($T1lim>An&}b z$f1XjHjZDi+Cf;H5 z-g&b_R#Qy^AZVO{MTyWVU2NW=zboC=FQh--yU{v=aPnh6vp{nFLq24mRax5^FMQs2 zmb6T`Z_NeBdarxZd+~XX220fF+)8G6-W(yc)iJqPGh$Qh9B*AJ-tHrdBq)oMk9YNy zv3P&r?*Sf=_k8kf!6V4K*r|BQN;v=TQJ=ip97zIl!}ojTwZp)Uk$9c<(`01V>D95E zdfiC<0z#_!VK-!+a>uu=-?4dj-P-)CNk#%t;!2U^#o~t8yq7G}ys=S;{&;^t>kz`p zZPNZwYNAA=UNk8GmuoPGcPl?;J^m z$6NlJ{~2TcH=*i5{u!-ee|nH~?<$uk3-%DOdQeF#zk73Ufll|gjP#eV2U*rLeUpVf zX#TTJ$CJgPfUDWmlJ14!VCBpHk;G7V|G(;{XePUEB&owH@6+ZP7phYwKp`5ZCE4_a=|1-SU!K@DX2(o_yyMY2 z%5d@viTdqU?aPO}VTti@Ifc)ArTW0@r3RNk%Jh%)qLVbt|4jR=J{lA;JZ}OUjdif< zA4KPWBP!m$2D|_Hg0yJKMJ+7edWHfeUm$P8pTw*NH6Be zTz&?5>rPFF?t{F+0!yJ~Y*9c+?eiEi5e5t!BQXOL_;dx2R{t( zQFs%q)itqrYc|c}5`et>;>2>FLf$Kl1FgFaRdq&psEXd1CV>X|&Y|XyVL+-oDMm9A zUT>+mT_R>X{QiGtSc-Rr8*=aYuf4r7*t~h$m$20ylK^#S+!pOKfkJDsc{9})cGL;d zU-#xm>zId=pFjW0<+bbhkfTLg7s-U<^X7}}urid$0dIuAe|wvQKmQZYT;h3_ti|w) z6XGe_>PVX)HV_H+9ejHS(`QuwfjGk)>Rvy1^c^^yZ7|xMc;Epf(#StZB}FR<_|16v+%wI2t(sm9ZM?rv&QC4 z<`VGpdQX46h0r<%aq?T(^GWSDCm#}4l~Sch!hghujBKw78OQ>ke#c$-xB>qWYxnW? znyL*#48MYG`b=9L*+>;tnAUTMN?sbc=;iSK2Am=4aSuoJ9Q)EzyOoD+pfqZ@t%)PBG|lp z!`D771QH+*jZa`4^!1Fezxye(eM ze$R!x^%iUv(BZ&;drRopUd21KoZ)#BI%%wQn%oqksW7^87Knw1VBqu9LPjbuDf{zZShi_tn>?WLTOYS}=Llq1(gXu`Y~@t;N6(N^tmuGx&wo5nhZIxF+i zW9GW|Rw~|yo5dDWcq^}nnTN%@qwK+>TF5(3${?);^0rZFer^bP8$K5(F_w)2pOF2hNstbYw;Vw0*o%|j7u~FyNoIZoBri(c|G(IK(+g`@c!c{gE^le~FBkWi z=QI4;yU~xfI@;nzF8zx8@BaUP+8aIp0S-vkR6U4z=G#L`4~m;L<-+Pg^NuylUk-cF zQ%j9Y9k2(e5W zNu&Z*&0q9-k*AOHQY+VKyu_)u2)CM$Q`fX{9=!8gmi?@ z)jiM^5gpa4lf8+}J1HsS#EE7Juo8`%|4{ECn;EM_XV^L5>9?BS3TL? z3we>n5-P$<=I#+N^rqy>8t|r#`7n`K&9l&V9hy^*uK4m_qla)aMdlJsKCPlm6n{O8wO{yYCq&x1dj8=U`lQ}rNHgmVI=2MOtK=Ev$mGJ5{)_j?L- zm?qdtKfoTeN^yzDS=fVY+>PEo_lg2T_8r|$(qZ7vr^BQ?A2Oo2HZ+svF#L(#d&U;P z#ued|8ei6Q1G@(`-&#M!F<%laK;vRcpN>ZC$L>MZ`VTK(IZ1y#=qXx98BTt_JR6Rm zjpIX*+|8U~>G(Zp(oSJ4@IoY5yV6RZ`6dkqq^A#!)>vvVeh-?Wv5v`y^OXPYAnl^! z9l7;gAcgl^Wgb2(-iOoIMYKWQ{&wWTZpi!S{MeBXFyN%T z$6xpm8BsZxc*W4a8#!2)Sn(|16*;i!ip%n?*sr%#HraOx{Ez@1Xk5eTdz{l`Y~DTt zp5Ftb>5sP>r4F3@I5(#69X91dMna3EyJ?vJGnf`_Q0$BY!JQKQlNvN!vBQ+LKfRdo zf8K&HlSxw@A(J1TvS!V#Aa_#nKCwc0?t05VUvKp=yZGTYGBtizvTtWNc{1=+Grsr1D+$$W?W0 z-kcwk&CYz50Oe@hSVs`MLNhk++Qq~hkLj>`b5rWT$#0t~@uPw;KcX8OEVm#Tzk4r^ zIGOY#ArV+CzIfWR0-yIp_zwMvjT;z#K(Y&_t&YtvMrA^x<_<{jpyD0=^|Aq_d)KQK z@?i1Kl+J4S33=-)r(NxYy!8mCyvdOFz_m7q_I*)cr`qxbkCno}l@^mbckm&mg{QNPY2Y2^-}_J^IT5tWTW|9%r{Qp-G_j|s_y5857Gkv3F>dcu zWso!1y=|y?htb_S5-_eKHF z{@4{s>S4f2>5|9_p|z;Zp8J;@)f})u1LW}_2A}>*u2@xI7NQ-Nq~GbZpZx! z<>A}dyiK(guUn?kA8$^yjx9L(Ih(XvYhK|)E{<)O&Y^*K=)S7QE6yZ?;Om};RE_X? z2i1N2@Z?@1!>_%G_i3wRyg7f=ApXDe{|qqw&z=8wpz1-V4jcb-1_`NBTY}Yt*6=9a z^oEaE(&G540oa2Uk>Vx|;U{*}wwi32;suOQ`3X{#gLT6Z(+ z-y5X&Q1Om6kq)9fVr^#G7Gv?Q&YgZ43V9cv%B<>#ysZmBLOkR>WByU`vtksm;flTx z|CtD!9^V*z4|zYU<~ZyKdAsMNJSbb@hNML~l5+tE<=PmsdS#q#> zFX(;nE}579KC#=1)-fL^zt(fQ7p^z+BU?B7c6eXJACSU@HLSuX?LdrZjh=P`4I89Z z7eY$(`52xzVLOd=OuyQD;qUPldn(>Bg6a+w-bXTCF2dsdHsMz98OS^3sAP2?1(K?)Q@++RnC5UkIBU<7C^S5Q-^EQ?7 zKt8h{0>Zl=m)lF?&;R14iBVewPBJ|2>sx87!-;>#waeji^S>Px@8}NO84B;o3#o!w zybnwMn#qQ|XH=I~_d?!A8G{qs;M-e^fGVpY?L(XR_Y8Ya{{BKFl&{ju< zCRe9s+T8qaOT{~?D(j#9|F;?k1+aK8Of6I|gS@A>Mk;!!cnAIX*i-{~_lm>?^+Dc4 zen&D*A@4|a`PJ!=_rkBG!F}-b*2*lcryRZ5dvDr0V)4Ky-}i%~i}%9KiFs?^%H?L`^A?rWV9H5|1SV_Lx94%-^FH(G-l7Lh zs~CR%Py0w)9gms4_WQ>DH~;@zr=Xj^gZuycsCrOB*y?}w|4SM-tib9)F9jnkm%ttr ze?Fv=413VsGRq5>;0p4j(&LKuog`2iIIy&HFA-GSRxQ2Ck>~}M;AF=K}PphRx=-q+7Z>Xl@1R zOvU@``Zbp*D@aqp-^;LgubUJoUj=#V-(OSp3GzP562W~0@)o=++B6$Z0vCh_dP|NH zfx>nt5nagp9(i5UGsxTB^s)M*E?30aP9%Jt7dG#G8t)oO-IBl#jT3$|+ME=C&3k9G zt99mb`s3|_)?tH_-_9%P`B!`RkelUkMFBKiZ!y{%xTPj`J<<^R$Z=aP{v(#y8!GdR zw}jz&6Z>eZWA|ET{wIIG|97I|eTHjQ4TX2R-y;z$-o}^TuxLZx``*5){s?&oESqdm zgS-hG=KL4RNkFA?Lhar;BG|3ZRw)8`JJ>93V2AU+y2poQ{C%#7VzbJgk%QR0E4cTo z$ahGBRcIXB`2f9Je%QPn9OEs1iqjwOYP1eJocw;@-R1XGksp~-{-LiDkH3OE*0;oN zcbqFy-k0?``3C+0=_C6j3y$P0Wcc}?!-cjwbaIDciyP(!q`g$U@EndG8B( z&)@17dTrblncc9~Q8X5t_wooP*DdXm;0GGlW-wo7Pb4;PW)+sQ8>{G#_e!)50#1Gl zjw@Ps5&4n)p|4TK3HZDhZYK1}M7SckTV9ok((>yqXV$l@c3H^q-J1|YV;yd~E70Hn zbEM*ZI`8ur3h!~mWhoZ#x*t2v*+br&U3OIuLf!+CoCX}QdnccNywRE|3aHe5Exz7B z1O^MoV;(`?Tw&55q9N}CwEs%f5YaT z^rTesARYex-)ppvvpD(f4w1C~u#q3}?U6eMXxMwp(^0!t&838xR6p8GXvE+DC)n#g zw>8aTc;3WawAG;;;_SJrS}d7ro}r3W>niAiGhpz4N$s&yX< zbR5rv+)>zrmN(D3U4}hKFU>-2L4PC&GkaD1ivVGrskyrA<4_8<-G-6{kP zH>C01$`)f0>>iZmQ{SiySCDmRoYRwMdx$#6G57z!U%42)x1avbAYDT1z{~H@<#reC zMSRGDkw@nWX!r%Gwe#m`7DWdEvu`UpQ*Y96#m>Z*%nHxl4BvwYHw%mtq8F@Fvnj^xOofVt6($3kU)4h_w9E}V4ZTrAa z2AemB;DWaz+5As%0 z?=KpGyk)-jasBy$w0Ne|d`Fl_;O_jkCugLI;8fcRw)t@W|4>`5ZwPre^ZfW+ROE_m z@BcMsDTF;BP3%=Zd~s9~Y(?X$T34s}Zo*zcdhUq^cRA^AK$=AB@W9DWC3;oQAx%C+ zG+g+=;r|8iC939322wPvAgB5se6zj9@Vp6EdT6TSM|!@e^xxnAbD`p$^vXJh!u#u% zgq2v``#L*c={V$lE-$C-GvqB4`KZ1X^43?94?ekw1e8p(mJO^Ug28L)N2LC|-rD!N zj0^G>avyZObKey?{rtqoLM?3GUYkAi4$n%0C^T+e+HXYJ9-Fr$ue;wTN&4e`0IdTr zzmPKFwN*>`k$K$5{7Z1d27#l-F~M=0{hyk z6=t^*!D^mbVFdCHTG^%E2{$Kzdj73_tZs|Lk9rdU2n8z{50BP~a{6y*Gl1 zQcC_6CC2aGTWPCfZR6|9{!#zU|CGfkUH>PX|GlYtP==$Y9i<2LJ1>{R>Or!8#jiZ! zBX*}W+nI6LgEVeUZ}_u8DnBg#d+%%{$oAf@98nMo8ltB^Zh`|+koM#5_<(LC?CG=T z&PlFFw~6tcQ~&b&f8x@M2fJ@df(|rJ*wXgPtR8j`l9H=?KATB@1Cj(<2VQ>L7Sw%i zy1qDm>xNK+oq$m)72dVy`tcv9i#_vIHhiR)rcj>vvpBguGkab>7v)x*`(WY|;+*V;`~OVrTZ0zAFiqqj5%OmR)C2!se~) zv2OhHb^7DYjn<)plV3xU-2v?$UPS&t(5H^w_`GktJu+3*=LfpBU8rF0py7(0wH&kg zeg6-xw^&DG9kDI9#Q&}!y{LGnPPMJ4@V5I|BZI|z{N|ptILO<%J0$rVH~ zNfIQWalS$ihbJFk^Oke0d~yF4{qZ(L>sXDG-c_Q-;lHxY~CgN1l{(&pg-Op(K?oVy*15hFNMY1$N9QY3FIyJX~CtjKZ}!+WiS7HoLEb85gbL{*c z3NlFU4yPdRyK?iJ1R?L?#+AN$ui*KA&ZfJp`>}Z^p8iEBgS>^&I78_NCyP_Cd2ba_ zNLt-af4tA5b>QWf&zv7>Y{ZAyb5HT?b;0L-;)?Uyb&&TD`46RQEb-Ug1mpPok4`o* zJa59fINIuvVM~(v@BTl!9{c}E4$l96R6Quim{d%8#C}QQRKn^(#2LL*LD+-#5dy=1 z!5(Dof66Bz9uhpY9QXq)ta}g{xvV6 zxiYhDk0pK&@~=*aAr+c{r)$3+ZK`8Ve!>=F-nzYrCY~t89bZKt>_od=} zS*+-v52OPfKCHpwZNnBkDFu1^i;YG6guKUo&Oh=7@(xTr9pCRr0#26wLCiIwz=5ew zE(-Ey&0aGo03Wf^ihH^SWnGb1Qr63^C1dkGdg^4XsjMVuLE~&e`m&Wh*q_*iugSMa z9H2km$Iv>$aPnL2^j7Gc2p=->s=Tkz3ZM6)Ons{|O%E_^Z`GDzj?bHIK%-svBOAjX zkQVHst&SpoUq|6{bG#2x@y`BKoI>f|ca5(pVDVlpcGp@H@}4O4i~Iq3zsnb3A;1+R zL3!FH*#v&QHMCDTq&O7FB#qvRfxN8<7dUw#@5uaprQ^KPq~$^9%L z2|Um^Y3u15J`b^ZYkrN0<)p*z{Ti)911G-|Zs!&TIPoEQ@Wbsb(Fn(p8NND3m+=pS>x(v6yB~&(&VvtOXN6O8$#Xz z%ZgGbA#dNWwdQh=x3JDe6_N@G6e&sbtjh@nkMstnPeR_J;_L4I>E3sXx>_RTU6HIS zCKbmLv3Z}|HmY$|MG~Z=aWeOd`h(wK^A2j2aM?Odf89FZXOez|8tx|PP^=EO>2 z!=?84ysfj|t}}Y+0+zke(37ghzuscav9tG!su=%zi=?Bp)iHYViQhHl^M8Jv_#hSU z%xG6`3UAgk2CK1nZyh-9y&LkL@i9I%0eK%Y58dbid2=WV%r5h5NQc9fET1a>vDdVM*_PmPi!_eCIYoAmc7?u4|;LX*|8bU|J98;w`PT1 zkySs&rOy(vAF-=8+ud2FB?(reaj(;5&is6f{fJeUKNO)68MF>focv6s0_r$p zc@ewOyj7=k@E@^+Bf?WsN#0;|gN~}zM;dyN)-98j8RWe_%1D!#O#+pRul-2ZAcF5- z#llPeJYtbkJL(|sk1U&)NzQjg+$<{dKG|UN9|4 zL4Ul5(K`BY^1HTLMMSBY7kR`*a@=8n&$~xHk$gREKe$;J`TR2%KJO$`)|dHlObkE& zmu#c0j=ioLkMC#9&HqQJcwhbYO_0KSD^KwFq$3N~*gBu!g^4tZZg>rlqYFT6GVaTqTj(vkS(_^2U1@5ejL3~V#^gH@ec z9O2b89FV@;;>2&s__wzbuFzPA@y~0Le~-5ursADjB{h%2d!oZ%1&g=;`vcdim)J0AF`JX_N_CNpQG{bjqLNsl4_#A(G-1@>?_x7jaeI;VU zKfm5mS+qeJi+3Xbj21JT|4oj2giS%-epX9#6CrQMXQ?XR;N?WpCa*mj8$$u%gL7{o zsd@#`u;K>;wGr7NZgLkTTA|pjD@`k5D?|(V!MgY`_ataD+$pF48Qi~|3Ow2a|<5W$$nI;=J@EBswS z22t@Y=7_sVSwU84H>|_ry~}yLDgg3s)Ezv^40)froydkj-nX{BHsp>a0S`0B?CnuR z;C=S!8BNH$U6$k%19^WG@wroz>4NNNCs}Z(WAip@F5))XBnft*apo-Z?gVmS4@eV9 zec`d~^!JE0K8fj=M-lT){; zj9g=Q-ozBz>Uh1nB7r!$Xh{b(epwT=#Xx1e=2;pA7a z|1{HtAU~4D!|yh$h|hbMNatk1ufsszt=!&eGd^#E)!0i*8-9l8O|YS{j#YzP$$yWx z9Hru&?=QN8!uzA0nkE)+ZUd)+e8_wBC^?h>c^iD2Q2WE1=+PFSTTBAFz8&lL*b)J! zkgR<+#d_@T`i49C5Kwf;AY(l~?^S0qKKZ75gRe45ANEM#&;MQ0Ri| z3wzL==jHp@VGkNELiz^uRdwn`kwl3w61eg+@U=GF|GzpZKQkZppxUR>J9^hbK;cx}`P|1X(^rgx_KQ^iq7@7Ufm-xjfid}*%ZFS^?+zv6y{WBn)AyDxyYiYbf;r-PAJ2Mt6S?yb4lZRMe&u#*C#SyhA$nhb?)V?}-aMSD z_U->STgHtdA(=wv5G7e;9x53^L`gQ8q9S8bnTlwjGK5MQk_u(WQi{w|N|F?jid2$l z_+DFkeV+Ztv+lK@<9i(6-`>yf{;S@%^FBJ?9k0&oI#;_YW&&xD0{eYWM4A;6o( zHUr#_`Jx}>xzu$jz}qp}&Ych$i%jVrZxcTpjoh4xpKJkmPpF)?fdSqYZ`}fk!Jcrq zcYm3QTXb&U!~R%LII;6pwWtp^-h52Q-qe7}$#HVrn+)N^&ezy@Cq~*j$kE{C zL~hgvPJT;DWfU1A_~GI9_6j*kDyp}r*w<+5NaWs=8kYPt{JFP!ze)Z2O!}XD*9=hS zBPd3-DG_{o```2bwA}cUa|1I-c8VHQqioTP)}TZkD{ibBR3YMewfa@De&eeZro5mA zsW8u;?F2PwxB$`NNQ*@pM#QX-Y8*l$^Q?E(gZ^J#A&KDzSc6Qz-&KBKHTX1)bI=!q ze>fm*)Su-v@=OLPB**oP96c=i4;Q36Ebr-txYFJoBt5bZy!_S}%eP2cfHz1K7M0I& z;@6@8AnD!Ii}p{zW+}Pq|S$r!pXw73ol5euuh+CuH?(pP8$j_kf*U|yr z!U;o{z5%?=JANN-lOn>JPu||oRL5RoKYePew@JSYvW6TNe#Ini0>R!vGO4oJ&$)~C z@J=H8z{^kmMsBu58b2(&Z`tp5ZhX9JHt4e@S9-vg15Fiq*{GO7CjaPq&c284@n#67 z(nrLKEq}itmBLDacjeO~2EGJ%a|9c1w1@N9O*thj%&I2VQTj?)5ua63@>v&bkiO-QTMO{k_S~C#0^n^Udi64U91-S$ zV4mOau<<@pXW%^hQ3l~7$907edtLTm;~lossquO^?cp6o_JNn*tfiEgo{j*lrQ&te ze-S?3de53REk0roPhOlq@^T9Q<3v7Zi>~g0ndu&Hg;Uh|IH)#}W)?+S-b!Jn!21sI z*?;EVn~xu1$HM!|Yt?ms0N!DT^mcGk;5|Ir5YG+H-X5OVZZin*7C8CYMG@eAS?P?z zWq|jn+>y=GzMk+Vwm;{Tb+G&Y^OAjB10FJnH91bblJi4cHFp0W^+l}z)_dAp-a13} zftTODdcX3>mHhu>ykFlmT_fCsKRNmT8{W0oIRAtn`?vq6gYKV!0n{LFiW>Al=%q0_ z#QJ-$7r?4PU(<>&6G06kwmezB2-KiurMs6qfFX8==1J{V?l?pwwH&V3jzq#7bM}$$ zAnmVbc=8N1NQ!@q1oszv!W%E_Xq2zSu0aMS4u*HY2~sO^+(cDsu)-Sb1_?4O`#e)Z zdo^ec*#};J8Uj+uv6+0ZtmB0Tb3eHB@!0v&p~qfr?2P=VHu_RCgI|LlKr>&J6@%!0 zh#g!?oeyKRI(TZ~id_m91>SXEbO|WlJ`9WbvGBf7(;RRR;Jq4wWd#7NPHlTL5V*1aHL;hof~ zp_TyfW(jsv<_CE5j6^~Z=>He1>z)}Jj74U>ANaF&L?ZdQOZRmGyq)_t8fO8#m&ZA9 zi4JO+_D6 zqL3RKTD+$K-rYG}%|w9r8Qraie7Zg1uBLM(9lx=w_xJr(%jLl3#2#|o`0?Y}(g(5e zUY5610N%uk zaj|az?*bQNkT?0^ohz{dQ*vv5~$w)?*HR;aWwFA(EsyO z)S$-#*EP`^WO7Mc7^?>TN{GC$2-F~zQ;uxHpa#9}E9T|{4U$@K>Cg4Hafr()ljYO= z5y*F!?_1bG4cb}X=QRn|AoFHgTaIQD;l<$@$!rqXZ;Np)^n$aOhK6en zVB@{BF8gh5u?&L71uxZNW3vm#e8$0Y>4C4zQnZJ+6WNCqPJWLsN3JjE;DcRPq={{w z#>bnbCv;+Vr9YzVBcWcVg1>{rFk+$pwQP+3@qSC456J5e>wMY51}T98??*R(t@uy% zKHVvZg*VHh-SBFFcLR$BpAf)XTi(}YDZqPF1hFg8h(k)%kCg^pj6g2uMXe@%Ank#q z>_%6B_o?MxQIF?{@CMy0B`vMkc$XXOE<08(gXojvjQ#ZvT{XtWJGWN1rC13FIuH94h!flHO0`-)3#hbQZ{k3$OEg{E@mB9N*)zMByMZ)5Im>6HNQkz#Le^I|vOfU)sLbX}4I^k@(7P_mCYocuDZC%=k}@xhjx52_`9!^hiqJz@3OMi0bD zeH&{Q7Zufe;}fpD*lD_NkQkh)^Kl_^^!?71h3d^ifp@)m;9(T+_ow_8Vc~s2Q>=9> zX>!7DDzcaY@BQlcE#?-2Z<}j=OK#{LbGRd+r^WvQsU&l=hal`pG`<@{3)1;8p7$ept;palZ3^ zu=i$D#HHgYieJ5D(uD`IQ$p!}a>9O%Iv*QuZOIQi`|tgKbo8d_UqSybL{Wp&*vC-}M~JAHg4DB@7SpSF5c>3bmn&7qh6?AXR5F;2^rv zeGOvpqSA*uA@=Y4e<^|#c(?YJDx!FoPtA&9;l1SGD$!1W_la!2aZ!Nxj+^$9Y(^UT zURHBH-w($j*CzLmGkb+295pN@;sEb6w;DSe0p7&iSVuQmJjC7vGIPnSTXTF zn+$T39Cz7CA5JpE9%2L3TW$<{(;nV^WFLVz`EgeIJ~}7Q2Y+jeFH`)0kM|TI^Jh}I z5M1^?d?@4-6&s{cKQG?nn52KaQ>gRt@#+KOh4TwD$i)m6v^Qm@0Pkew(Dy#!afr&|%J-YY!V!Ie9jhRKxA|{g_X&Xa!`3cq zIW;2eyjCL0p8b68RBn{2CwuZ{<`l$_x=C4CUri1dL_HEV9E=a3+nx_xQ5aGH%F*mx%lPnrq{$shr6b zAU$IsCwU-(_VA7&`@qZZ#BDwK0yRE3x##*`KPswsYfMvBri4DySLe1#hmVR4QqINk zQ1dRj$D4slA9}~?)`w>F8qw;#&Chcw7T%ndifv4w|Nnknjgf@+Zv9Jb zOkjDd^a;~Yp<5iH$Fw^^y+0fwzEew|1bDM-*gn4m;N9q$dY|PE5jN%zUU72^_VSjB zos5gaWf{bX9Cwdl_3-O%?CQO^Kkr7c5bZ5*$&q~s;^ddc>#*9Vo(~>`P4ByW#IN3i z0v#6IsoRmK?pK#gSmEEjeLz^&@%G>rx}TiLucyw3P4d~N_rc`k-~E4@?)?8I2l{_e ziW>BUX`3EegChN9WUy+G*4jtMe83Q!J2P=d64W5|>87u_p#SeX)#y2u6Ne-#)^01` z5{?8Y@K{HI8Kl?kI~KBF25GxA|5Q__C#-(DeA7=}>>>7cO|op}s5GKRjx%jgJ!X9z zyZ=XY?A`n}(B2SxgY2UoCqK<6`*z=#;DZSqyi5I?@N3XaYJkK~?;Y^`-r$wT&r;F< z-|1C%SpAv)m)NVR^fB#_s`>YTv-EAFNDBi2fCZ(|O-nfBFD+1tst1q)of`s?= zf}TQvw_VijUo2U1h|yRdvzB!@BC4YnKm>UI8Qj@s1@LZS%z3s3eBSbiB=hixbJ%z{ zC+3Tcj7uZYTtIITihXz&f{>`DnTyVj1>R=ffz@e2xF5g&E{h3cS1W&i|)D>f3T( z5)1Di$)Cqh0K5beow39^4d;^laSy&I;hYL$G6C zD8O59=w!uHZX(>yk$8816gJ-Mdu|d3CZ&-Ua@_1$d-&Q{?CSl4>(7TuE84@GiR|Mi zPJZ{=9(~Eb!Uw-Nv*uS&KR(_uzg2&Ri)q8+$M&&Z7RB%XAEuUT%oD%UJ>Daysq;~J z`ch&`>_Y!9Oo4Z2(B?3-dgm~mkif!wAm`52EP!|CsTEz~qz0+PenkPmyJK&65X)(> zIkB?lYoS#*!u(?Nt|7pC(si{(0>JyE&wJh-tVG!I)0|4LA2!}!o*W%G{X-ftBgcJ= zvK@9F!Nyx#H6Vq}iT3cGB>Py4li!J+mOI)A0XCYKsA?F%$Gi9(VbtKg7TmGUWJ2~i zeuEVKiYLW$^$gwP9otxG8I?pSBJ@a=8V;ly4Z=jB*<2fmSaF9CSV z9Pxd=4B-9te7jvbz+1;CdT-2$IK*t8>0GQuI5L*^>?!Gai*G`S9v1-Kaw$;$;WQbm3(m8 z_0UMeA$+{89>3c@tiKlFeo)#ZF^zxrcJ|QoS}$Yz@BhW)sPo}@`k+-)%)k9V9d!Q- z_x~j*YEVD(dJA-jEoqccz^XyPb{eWnKn*%zR&iVw)Sx84*7+X>8u}Nt*p5sM$02Da z1s}{D3`ZW0u39_;YLIxF&1DC021zcyZGWmT5r*HfjOk=y*Pv6%0gvVzr4cl4(xPZz z7y-LM`Z(br-!4vjH7JSf;}cGP86V&9+4%6mAI}QBI^Td_gO(M=76|XMM%up)F5Pel z|A<}Y^^@X-ZF}i{h~?^`&WCzkS=I;e4N|bYwVVR)zDEg8DBcnK-^pX)ZRaH`BMkVdMSP`L<4Yi!?Gvj$^-nJE*A_dx(9tvcQc+n)dLXB>Q-SlV5QB{iIK8 z3Glr>+q1vw@$t4}jC#M-&KlAFeMaFHHT{23p4#4%VRVl-Lj!d_PH_Y($CNDe|Kb#Q zKRcNT)ZeeS_Ilou!@|2VqhRS;fOjA=kRb!`)*;5%l# zJidFc0p2fkShq(2y!RB}9De@J6TW&xWZ#Mn*mx)K>oR0@N+Vauajh#l4{WKz##^ki z{u1j-+Qa)8*@py9eglIlqtUzg;IkY`((?#D-cAAU&u;5Cg$-7%ak;ewzyF__4vAh) z_(J!1=dU?Pm5)zL2KkQvy&%1e0`I4u+3dGtUA_;X93=mCi(-mm*Wu4KYii+w&95Nl~Qlg`!?lo`?<-oK9h^)Zc; z-$^Im2DL{7SYlU8{+37hct4QX_ua&I2W-F+f4gb|zyBA};mJ65YMAc#-tIY5=VR^f zH_k}Zzx_YG^#3a;YS61s^7?2Enmo^^hE;nhvipcKe5xn@HMyf zx-^2u39j%OVOxt`gAO0R(Q}7^_G(Zw*+(o+ezsi~DonN$;JPerzsQUDHOOqa5v$;( zb;#3~QQAve>v3<8GT1FL?rKpBQR7fL?>$8lyYHw3SK#CAneCOc zuEYqjUHkIT?r|y(C$8;JKhf1k_jofDQ0YUh{+-<4!-Q7Sc#p3P zl>DVbghLPR-C8n$jrWTs(&uKIq>(Uk+`HXQ<2IJqdv6K~r+K0zXb~ll7-Fjzv+1dU8uY>6}xQ%I;2 z3wR)%9Jl<>`p)J1uxn7oe8>fTXWFYlNn{_DIQg9sN`LlcJ1@-g)=kjtD1Hsff4;Kd zT!tSa{eW#ZUn>3#vU7I5SOyFI*Pug2)cIKEx@PN}+=UtBN(#J3ZqyW@cyIOX(!|2s zbk~!j!vOEb^Z*l8fcL8q!r^-W@0sn!M&BCa5GZMt(F^l%Bw;Mz=4*g=edN$PIe_=e z2fz1+xPs#?!e10ey0P)zcsw)xIk+H=#`UduJE-G;jknN^8xkeEXb*2QvJVlQ{A!2o zKCkHKg+IiWn7>NE$Ghjo^wxk2en@{#p?P~0{t`PwLWskLf;svhVpjxH=VP+kmwl%o z>3EAg1>VCE#o;L4_a0|!VBvjxub9{=fcMi5m(3~w@BXuz=}W=tt=QUELYB|t5ZU7! z)5nd&kuOk5-V!i_6n6Z^akfgVztzHGV zu@^+>6j;+QVCe>|+s5ezQlEhAm|IV3vk$e;Cv7 z@vfVRR@@okgVgfhC@WQ`qI!#6xCGBw(|`3|O{I@LrfDm7FH~XGzqfH$-7IyWT>yd`d_=1%~;g9$$E5dd%PE3Ev10Pj^pM|)QTyk(ypb+NeX z3G188?&7vVW)Y2+O_ zPMDSNB||E94N?!-Htcm}F+yv9mIVdzJ^bELl>a8Hitltf8HMlz*>4 zqP&gI-<`v+L2nZL0}QIi=)MNM`AD4)o5R`T_fIVJ|0)!Czb{zRg$}Wvye&FdcxSv^ zZ>tLM&J6Tkq6zTcvUA^~g8*-p6-8RQ5^;#ZrZqAB+~LT6x$ODP0B@TI{)-g>-W}-) zcMZVjEwgimGGjht53$$B#@K9kNF!+6#}zKziC)-vH?2^X2`HpJyswdcG~?u#%2U%4 z!pRE@85ONfrULJ(4w0lLHd*ASx|MR*B`S81w5+RkMbQ897Q@_T>U_9$3n>2GK~ko` zdpuOu1;zWP=J~Z)c%PSaeGUV>Pc~eW&;WRs>ssi#0lWwLh5NRE&s#_-Z80{J2uJQg zlBV_m?_K-C(!>GYU7ixiCk7(y+Fp|rl!RTq&&JH`UcW~g*+GsAGBPoDpU1}gW!ei3 zuX5VMJC*EX5GOz0Hbvp!a2_~}(Kz|nKK$zKH5bH8Ow&LPnRN8pGf}aF6n9|Hi>dzw z&s(ge&PPMen*qVUtG7xNc)#1c&KAX6I>ToT7T!nlj9je&-u#Sg3hDrFuk}KYR|C9{ z^{qC0=^uy8&4f2HX#>11Ipa41yo<75NXh}ce-ny|*8cQ_RUW8C=tN`V{YG%LdiMco zM3o%(zGKJ!qEFa(YY`X?Rz09Sya&lXv~lwL)>>RS!c2fm7j-eSgy7>nI6HE0`nxC6 z7uC}r=!TE?a)zsn#_FHxetBykC7&uEogL{;$%hs$Cn{3lJ+{ce8^znVX0oHouzq!3aU7B#oFMRFb2zf7ZjK`o;9V#@+usE?Cu&dn zm@kbb!i3>E4-rZ1_y0B~22RNQmPYui_wFIj~{XAlLi@N7@F8^-Gp%HLe9Uh%fur zIvCWT6+7CCHpIpvQvshp?&=Cdx-#_I+(8Yh+Hvlj2pD49gF@SU`H1j^-T+atI_x1f z)~@o%X)|dglN={nJsc}4k6nYdFt5EhnoN5`Yz*0l9Zr6>hfYUH1QXy|_-i_^IerbQ z`B?1vHEj*N_)#&3%0v7b#J~&fso%Mo?uS?gK~}1KT#kOda#6uT|F1!T_teFJg#*$g zyakR(v0~w!_W5}2OMv%;!Oz|`0B?zv-{k4m^zwt{De7NC9qkK!wnyAHH&#jFyt=X<6XP= z2UR`_F)Ar<@oz83q~3hL+{Z-!_peFQ5+X6#wmAYDa)_oPMl!q;0#)q8p4eI_it87g0| z_zm!`%}Jfs0(g7N_bEmKyeq>M3q~7bk&uUm>rah@A*x?Z!;Jvm8iS_OCID|2Nt<_E zuRP(~aT&dKPS|+AS`pk93MMDz7Y`h!qS@#(_Nh8waxGRx7gIim$@s4Aj zeY7Hv_V9i{_7RVhpQ-qziYi$im^UCqZJifB-eqcR^_!Trk!07Oa{{lasNSua{G8(9 z^xyxV&7#VOPdm>cyIcSE|Nm{jO>6%V^#5xqYS8xw@9(2E$luMJ8>p|qGP60IYE206 z`TA#P?N;E|pj3+?i>rzr2%FQ>+IRP$yrpva)tp|8FmGInS05?cof3-aD+Zl`8E%^=Itqnse z?0#hI1$fI{T&&Fw@IK$65%2`u|DUf=5+Cxw#@mW5{JOb`H1dla_wXI-YmrWDydOnH z25KFry&=|^?4uDUzk{ukI~sQI!3MV_w5t^H@osj4yRK`R!C4MlB)X>Y@y=%u;N-d4 zMfZ5K{Nbm{N3SQ(hRnYYq-#^){f)@xkK&yuILU#9_d7EVvn+sjCck>RF2Ebw^s9R_ zz+1_9AaNBj7SU7XC*(c|Lw@XzNh9GcXyRGG2JjA$e>>ap&=d9zE}6F0#m0M?@|7o7tc8vD9;Ju%PtB!~d*nEFr?|kESFrIOYS%TpK!cML53-M8ocv6ejCSuk zOMq=6<*j`*@$nvfEa#;-x&@YdQ+a&JMf}5wF}W>wHc6|~egA)pN*`ip>Xu#(U%-1c z1>Rp7XMdu2Uwx9uj)nKk|bJr2J9hu2#x z!eym%&d^@<)+GC=#K}*>ZI!<=Cm(F<5`M;g9X{U4nc25Ehql0Zl`X%Wq^LNYIJL53 z4RpVpfF|0W;M|LalIpkGx!=g=C|n!G^(s|IDK-@d2_ zYEaGVZ>tPJ4Z0@3Z`r6mXpkg!CT!Xpi>QRph+Xv!Lu$l)Qy=?%fZY#Uw=EAFf`8Sq zh}_#jggxuJWco$0&mcWbHfXd0caVtWxQMlED;!d=_y4cC{?yp|gZ64r2iXT+elJt} z)yu&rcDo)WYF2RJ*C2_?U+I>xH?py==w1jH{t(O1#&7&n`zig`pb0+ed~DzLRr&7$ z>Gc$N|BOF4isIe&f}0-;@0BOi=hgwdMSnci-vIEwBg*Hr2rO?svOZ#*?;VTy_msOQ z9u7l{*i~j;0lYuhCyvg7A+}_-^&*LfM0j19SjcD>Hr|^gM1<&wh5Ut8sTLHYk8ar(^ z0C=4IqQ1nE7p4+ot5>KY1$4_5QRF+Iz3 zo5b+(j&XdkT3FW=(UaWu^*Cz_=0AIMygv2x?AF-gPP)f?-_A2s`Irg5d*f=v!UpL& z3cTkOxN}gvSAMz9i-mX0XQgBpfOp)RxgGid@Ao_Fg%1O~!`;8uMmfeJ#ot~hIot_D zc*Gzp4uH2P;kil~!26lV?58hDvel><9zx{ub4(+Pfmn7 zE>)B)r9He?l6?r{d2fTW4u+?mge~*GCafexDlKvQ^#^;E1lo=8NL^)jRVdlJ8~UispO*|nSTo#ALIB=RmA>t{0`Rt}$}@kc3h?%YyWQHchuCiWeWMT01H8#` zAxEvMx{a}CkOzpvKlxtM9^S2FA9(q(Wrv4+_awkx4$^jk{{y^tN1whP)r#-wg$v#SO@+-XYy!G4%0=yx7uZP)3{OZj+ z^|^3+&`yMfyKroIClz0BxyR-=n|GD&@n(2Tr4NUurR3)=^eOOWSh3R$#XCdc>S8Rs z!!|pNa)Jiwe$uPO#sKeBw*1<&U~?j0WmDc;6=bz{_vh zgs6+NF9BA2eVBdp4?f;XM=NJ!lPnQo1Ac`FF8teD3?kcGM8EBz{|3p|g(@GLo|Q;W z<}Xxl_`mR8`TIlZf0nn_CI&3R!n;N!MMo6it;6tK+6dsiY`8h62H<^Vyt9lA?EnAX z+5NR_TNvWoUbd?o;B9a%vJ?h*Pv?%083z;LUpv;PjT&R)?aCifdA>v%`9qFtPmp#D zzl)9cwy>C!1~iDb1K9^&ewUWqIlw(afLCd#wU$Bn{l72!kl)gE-blV-bepL@{_@sb zMom#^R4d)%-RfOUm5`J)MDkb3fac1?jhNJ34)p|iQ6$d48ct2?q5D^F;f^!bktQPbp!cub;oX<94fk)Fax%`zhIn4^Dpd4N?c)xC!tM^&*FxkMZ%YU*8E2->`?H`U9`Lqvrd6 zH?qaQ`P|4%_-cY0?HSno4z}qmBZA=;9ZGZoqU@O2|OkKYErUf?M zBOb!V@d?rh8YkE!b?D$f%pf!KMyj^A(;nWh$Ud@h^2==7S-_A4W{^(XS9tW|<1Mhn z=38{WI`UcThxZ9({2Anv!)wmUm*1j$yz8%MQ{_W<>|CfV_<|IeoETH!&9><0cNFiu zw--dP@Xk08%~}oc4zm?~WDfA|9B9R^-gT!J8&&kt9^TK%J|5uZ zr!c_xm4gpHcG96d`2{}SMrvaI$XKMU9IRM`MD_*^K28R=Wi>{UJ{)mk?mrb3?UVt|m_h9>`bFwzr zdvA$JzbWw2^c$kBPb zb)W`GyIxqmg;axj0+L78Yv}7gpLX%Fj6+;)zZwQLgd)k4neVkh4Vq}pEoKBYD9pye ze6uYPULh^y^HC4G25EKAIyJgWBP+>q3b*F>Exm?4#0ve6B23cY8zib^AHq2KMaFtv z6jSAcuP^GaJb4Mf2C-~_W6lq#A~pUm-YgTvuR&=Vy=h04>A(N)^QO+nQfJE;iSdHt36QM^~l%}Qb6&5^__YYFgXKDc`~JR?4weH#7A?|F5Jr?Y9IQ?+o5ONjBcnhzvRIkb5>)?GbFe zbNDP}9 z?=EKkU(o+sQ|F^6ZVBOb;X;FCNr5-d>R&M^-Y=4BC9&`xk-I#%4dC7CcEe>ez+1up zhD9U5yVqjM01=5pRENh~xzC3plEQfmrT}k_b7j*L0PjU#9t*BEAi^F8UM*ExgpGHh zqKuzbAlUyW$Bi#PQQ91hjrYscu7`uSXsvDDdXy{+)*6J^cN& z1Qy=z)=e+=0KDHg1_o>bcpLRP%9BoS<#d^vZ<&upGzqSvr@})Kx4Ft5(&j{p&2Elw z0B=c2)p2cWB0Tp>oU>9M8*d-6gwFObX=I)p*Z-4P=9h+zx8Vw_P|tg`hqnjWhY?PG zot^oaF?9r3d~?Hb?lOG5xzgSn*cutbVNdnazMQ9`|34E`YB{ul{`-GbDt)L9A0QuZ zF{i+r^Vzch;H_!CV>uSy_ulus3Ilj=;H-|`2=JbM{H@;>;4Qo|IpD?TSVWQe!4vz)Rgk#tDqrU*&8kULMMb8l7y=EH^*5za4-TQG((;k2~8V9v-MK0pO?*9u! z69-Lb5bqAMk3yXM4mmt27E&O!E+Vi({$sanK;|1siyKixYI7L(FvygfD~%b3BPW5j_4pJ9un(jCizoUWf z!#I68T{*2eH*jil%5n;Ga&r9SnB*AZ=;nCHQNeMI;{wMCjwp`39PS);93~uVI21U< zICwc2pfAt}^b~pwRYAp2Hk1OzK>Hz2$Pu!DbRiW;0uq2&*k{<^vG=pLve&Ygvgfg% zVUJ}$$i9c&g?$sdKD#=*47(6J#5TwFk!_HzlkEXp8CyQvIkrT$2sVGV9c(siMr>Ma z@@yh(+^oM@r&!;xK4EQOy~|q2n#r2X8qFHS>cP5|)r?h#Rf$!cm5-H)WtwG_rH`eV zrG}-1C5Pn{%TbnK7B7}GgGuLrPa|dyIaBt-{pzOi@gG zncSJ|m`s?~FexyJG4cM_@&n_o|N8yEzoY%X0Ul;HrX@{&3P<-nje>5V>WID&1eKsF zh9~b9bRAXE&(F?4#i%+|-f|o&LRHkkxF)C&Rgul1!KXHd0k(OCpKjjEmRDiWYmsM>M0 zhz&|bm0QS)b5IJZTrHq>=p?GPFO3a>l2PS6_O=H~Le;ir7aQmVs+`if1fk=oa@@?T z0VSf!K~5?YNfnDib=4Dk~z#F(?{UmO5X)Lx)gh0R;p>QK&L|rt=AkM3rgY!%I*E zs!W0+S)p)L8N;!aP#CI=c)U%aP*iPrAvFLUM3uoc-Z&@(Rr(PVuc2U6!6qfG&;eBG zDZJVT?MIdFh+Gr24^```vM)hFsM3kIsDuJhwbqW|7qk~uYvfavpa4{9eTG#ae^jk* zV9SO4P^FpV76|#GN@MFFKjecdb>;0D&>mE&O^}NP^FS?QUMWBrR;^Y zL7u2m+Vti#v>R2596FmI4^*vu9UlnoLY4g0iPexhs^s=net~wPN_O|hIA{l|R`3nX zLT;#%?%%`?xuQy{G{*zljw;DWOFhU1RT5`sw?NLQS}sz&5!!~TW#8_dhMZ6(RwBX( zIigDRcyI&cfGUxFPkN!Ps9Gw`Vh`D)YRQkQRgfL3gxb6rAX`)krtRGW*`R9i-XlHG z7E~=#{r(cNMwI}oB0sblReX<)MxjlpBCWSW8&O4Co`kGWMOw{)EKvm}H))Ussz|*8 zWR5D*sXfRHRir~skSVH2XF?zoRFSsOA!AgLb{ruiRFUrfL58RzU6q11po(;}1TsJs z=^#F&PgV=(mLV8bq!)xBJyek%T!Gf3iu67Oq>C!jb$)0asz|q=Astka-XVt8qKfov zE3^hxq*pE>ZB&sS1%$LvMS4RGT8%2w*Nh-dRFOXZ0%@R%^sNj?9aW@H3qY$-MS6)H zQX?ycqWea>p-xm4rnWgj9jGdZKKCAKN7Xg$#)nWFs`7ultAJWjb)}QR25LdoDnoyOuu5usr7*)B8j6|SDR9zgn{u*jPRd#XMDD((bS>eP?=pm{yjrMCo z^{C2_jn;)8pz8eOMjhxrs?Oa!J_FUEDn0ImI)tDq&4!x;szudV<>24YJye~3H=hdC zpz72e;e4nXRjEmqE1@b>rEE8Dgep;WQe7txx{Io$X&)iz4ysNxmM()TP<1?KNjp@I zszl33{6*pxda5XUvI#ZlNl+tEU3GiK=5oKVLwlWVMp?g=iJ+=0?>qroimJ|_&0&x* zsyfzLhCoYD)y{Li4iZ9DYj3F{B#5e(;tQ3~VpKK9%n+bOsA@7&YlH+)^;qD#Cd5xx z3dP^e9z$K|&l)}{J%ad9_2}lW6%YYc4-Z|lgm_U^ZytCU;z88|p_j%GH>&Es=n^0< zR3TLciy=-_)uw&;4RN6Ao>MoN@S>_l*`gU@M^)7?f-=O0s>;V@IuI+W?k3ED7fMle zhxn`+Vn$WPIxs6?LRC5Irw)h_RkwQ{Ux646x$i>d+vM@RPWsJi;~>tgm9 zROR1U!N~p%RacIzf51MCs>>F!H`u?T>XKxM8~c}k_y1|X$72Bd|27nBkfd1+y2QT4 zMoa-~4U(IvLf^Ij$nYygXxr9sjU{#Ke7Wf8;*!1_?Q?`u#vVOoc!FJX9L>K@WEq`IQ~>y;jckXl;&@V>NSO@Gmj8^uHf$=)p#@O?J`_P z_d7_BiPZTxtvT)X^6v@KEfjc@rs*i&+$|sFvG6t+(PjDx@P3eO4B*Y!#kl_^z?>15n=KOf z;N>P&+3}(Hc(?9!xBl(D1(|KUlQ;MP|AKV%pUW4|e|tdpct^8bp~}a%{D-_vf1kJ9 zOo2CPAqB;|>~y>=7T)RJGtWc;-jB^qxk-437)nNL0C>;ohEHh(#36MIE8lK?7mD=0 z(D*}|oNQD2Xw(hxW;$d0Q#q9g-x2f(gzjSFt@A)S>M}UqQbmq?u}(48b1637y5g)G zHE8g7iw4=pdYt@tl!W=(n)u+?3i8}q$MEqsDLGkVvcVaS+2GBuLB-cwZ{@e$kJ@sN z?l(xQ2B`D#T&dLOL(0POmQ56RlU4>%yqDQnufW24&mQG-iU9A2M|&h}0N#oBX6KRs z-UT~sp;NALh^BPT=~I27NGWUX57O}#9{$H|;{fk@RWFXEfkaq8K#}o#C^p_}wgnz9 z*)5G2k>f-bpA=Spg*`c`Oo`RJcZK$<_bRfFYMlH+iwU22%@>Vjfd=X9#G*ahKn=1%od3TW|B<7Yn+VtHbXpA$V>d{$e%m?34}nkYkmEXid zTt}$#k!+Z|>u1cu5WAHEZ_;KTiudG~Q57t_`HtNtUI%!qE*6M(0(dtMUmkA=_X6N*tvj=!951v;ZU?#$@XDr<={KNZys|&WjY6Z_* zpmB96KbCyb!p2+RPq+K}YT6rORmeW@^4od#klCx-d~m7xtgR1(Kg3qu<&GF|@I@?y zRq~Xnd1CkY?{pp3{{{VjH>KZ8Hxl|wIz}+NMB!jfPE3b+ug`i-Nu~=OWrkF z{w@rA2ANUuh&wV;8j&E!`DYIYuIICEwn&HMN^2&ny5HIx@u_2Yx{b-uigwBsq@kQHF2NE!-eW?M}ar#I0lM$ z$>DG%EW9T^jeEBOyr<{6iyZ*oFE?}58v(qRoGE08Y>z_%Go5y)3WE=%y|{Zv58&O# zVw3w0G)UvgBD>6eiSUoE0~d*L*m!HkpI^N+S{gy)46Iff5XZ3bo>qx{XI)2o)mxeD zV+JQbyDIpi;wpZ4^tJJ_oVECP{|PzG`lx3!(h!>Q>i`vBZ(UqZUQPDlkCUI!w`bCG&V2B0!#j@K4XD6-Y^V^vuo;QJbNr9o zCH($B`ny@%O73pD$2fM7HgA48Fv4Fqie5#!;};fO^&m*)KQ3Gz^*~2-*uXXWoWMk6_S0J z;N+Luv5I4Ck^oP=_TK;gDt`Z8Jo=|b{jdv?B55NxK+O}oxjYgkt(NpZgS^U1l@GHfVbB04|^x|ctq{J ztmwQzh7@QI?^d!8E1dkUUpXeKrNal0FPjgssKUqlZB5{)znnLsJ8)u~zajn* zE6dtqySuEM?(v>&rp`y|&Zou4@)q#kMu9i!3_OZ=)VVwjEWDq_T|@!^-e*R4NNfjq zkMeuWegMl`>5)BgF{<&%-44V#s{J4$E_ydX04#4Expr9jMFhD2-&i^&kmd>V8Kx1= z`eEa3ZPY?w{3(SH$ZoEe~F)?2SA)>7ORTfxmjopgt)a6m^g8@n-l)rH`JOCSB@4@#g3a zQOCl2tD^B#6u|qNT&%7Oz=<8u?6) zYYsL2Q)YyHyyYCynRBe3_V6Ai`$)&h@0zg$->J>~@Wx+nt_b`O_TE}yf@lVW|Mk|5 zVb7L)m^P&Q>dlx%osS{SMHiEbau#OBF0=wRV}Ava7#2;j}F$nNJ3@V+I!xV!`4 zZS`Gb&De@~#Ev~>e!?IGF|zxiWdQJgPA*=>LFpbpUlf9x$Am-JGzngXBhmH|Zuliud#6^tD)cZ@;>K zKnCF52<4pE3Gn6^Fe8)$yl+p>9=@ayk8~-<2=6`=f*f*v9k~PGeQ>{{3m3q%R>s&dY`m=(Eo&KIqP-cU9NEVvocuKZSOsiz zBET=Lj%^+e!pEDhh25Y1#Y)&=u-SWYG!@mG>C~@HwU6n)dM~HW$MUH^S3Z<3EN{6| z;7xiO0>#^--hB-g-piKoBxnG<{TCS&?*MoU+;Kh;5AYWIso1qvEgqQ}yZ;Gk3_*^K z^XMN2c>h@(S>Fv-ZzTim&))U+g!PVa&wNqG#(V$xxzxUwQV1Hy^*G|A^HFTP-O933 zqxfhK@4aLn+i~(6cS^GN2OmghnZ=IlcyWP~%#=`sbp&ZE#0Pko1>}_rU@21YDD*6EL zwo<#P0j+qXRrV2am-sp!A=zjm7!8(aLAAAjQ3Sjm2-}C>}c8UKV#(@UOlcENZUV9?d zAX5L&|7$B7Rt=JsXbr#jyjWlRcVQtB)F8e6OuJdY3(^hiq<)VL#vyOKj6ZX34Mxf{ zcQcRg`2c@O*lY6&%pkiDY!ZCwmADc7v#;!q)RX^V>t&>7b$Z-`jea@;S*fl6` zrfqBR1no6Q^<*EJIQi9`N)k6==ZD*Q{8BDK_%+Dnb>Sc1JS({8NMvzg4HXxpl?)jR z5?|1N4Pv3z$1BOTe|L~}Q{YW{z6`~?a$bTJ3-8~lS^BL2@7vmYT0H^Y=T4n*;Q)C1 zJDcaP{t$;eh|+wxb8j&6#GGa96~H@|@muppfcL)nT$`*)PuQ|&#%g>X8}FQ6?v;;f zrI3x}INpu(hi%qk?;r^*f3rXMBkkdxN%p~wlb?>F>Bn<*;QqgxpO2{|KHk0&{1sm3 z-C$+AGtR==RO}$BNK3vn+e7~ik`;A6S{uKu`#t6eNkK_Bk zy}#pr|9YRp`9AM?KKJiA*LAMz+ShXZ`vqwmGTw{#@sW5>*o`ru@g97{!22HX_O{?0 zB>>(ExFj44;N8B8OYh3B5crAA!H6pp=-~B6Qr}#D|g)?LekZW zN5Vd!^JaaYb@C(Ny%~wq5uGurUyshab>#3LHY)7i%t#$g82Rni9mLfH<00WhdZN5M zHt*$QW&?*=wBh3S`}X3Bv3cv-)JVUB;Mvd z)%0k*jlW#_H4J#CL1}>_X+t2nMBC`_cv?lXXw0b)qWk81Dg|$NE{(<)oUI$blx#vSp!6WQeXGBM(VhP zk>8Z-y+3M?IU$bFjq`MB*t|byGier!YQqOb(^T?`v9GtlsT+BUZR@6a-Z(4D>Uc4s zZuTjCY5qS!#(VL`R1)unsVj77ym>6rJ7)mz-zj=BHh}k;(qD9o-`>)FZCURi5DG`c ze<;cB_JChiM+Gk~PA1nn*$jfkNlmif>dGP_6s{zlZvO_Iw+x%h$k#>@I0A|Ly`DdT zmmi(C;9Z^@wX@X6TN0^bEk=HU&lwM~GT|Ykm+#_@jIentykGH>NB#)x9Z)AIq=n5} z?yl#YgW^`2=Pi;%SsnE;2RRNz{dfNV|KU_m`TuJ$|2vTNpv60*Nj>O^oaS=09u(=g zYSaz%pnDfY#vMQpYPm7~VV4s4{$Hx|K8cJFI6R20B%#m)c3I!eTnu{9?cC?K%HR=e zYt{SsbQTdB4|ZqUK!<(?>AcjrRcz%V@E8*3C==)S=U;vx-7sX4F!PD}dXO(tM=eHv zC(ay@l5fRBTuuX@w!dUi!}V_2_kFdq%+q zsd~nN)!ol&{t=5?M`0cJxH+%?J>FtR#(VKre-dx`m;qKa-h~Gx-^2jk8MRN9?E!B$ z9-nM&aDp_rT;j@>2jCZ^YSv|^FL=OG`l`D>1Ky9N^jkiG738Be*Pc515h3Q8Nw(Z9 zbl#B-2{OxzL|{_fK<{qexsT{?Z%c&2R_K19KHecn9d|MEbGE$iYovvTer_BUmmkFD z9g`BK_QLldB*e&kbW#L+{(qe7k?)hZpXN768-pmT!+El+>t^86{C|>+_u^+NNW7cR zl(3-j9%y;0o(6c^n{iv)0p1xZ6So<`fV7?NhT2qZ2+aJeJzl}u1K!Ux6S=rK@m3D@ z>jk_A5`;%jc@UwG0v|SPj6vre5s^Ezr9uS$gv5EPd3o$acZZ zfII%ay|pFdz4+Y~5^piB;ALpM4|rGR6ae0)IyGS@0dGRL%F5q>w^SMZMaA|ISRwdg zKR@IFkJ^M7dPW}PZ+88Hp2c%c$g1fbJA}iY{|U?a6%354z7(HMpyf`W~?sNF9Y3`Nd{; zc3QG>K|Qago65bgAF-{^yf}mtT;Pijc2C}##6BSX_Uy6YF>c!5Al1K0SshiyEh*cA zmR69b$#^e*N{z%j$$JGJjdxnqrVUDfcYnT};c39zf&}U*lV*Q79Mtt&c zrTO{apGAS9Iz}FKYO>`oz20&n9%jOoHQarI(+YI)P2!;8@i{N zq&yUXNpY{sflAoXR&W-p11d!0E+7P>YTwS60yYFk&O4^$1X{{JI0GvqVYbU znj&-<@UDg(Z#n|r%Tn`8gaPl>28Po6PKCfT_l%}N=Y`|zk2*O6-eyw0Ed_x0yV%qx zu7`U z{*?@C(0EU6`+DvN;GIw-ec2W87GyhXn+SMEWva%6#0A4obsJ8NdU?XL#fdeAfOl&R zUCSKct$%&jKwkJz(a?aWQkRquz4TpaF##X=m4MNV5k;ciG9UR>{+(R!%~AZ&s%jfWp(H? z$gVniW$E>nD;aO)PvQ+E-g&vLtI&9>*H0u=_KB{giIbZ-rpkF8#n;(13ou8&j8-z(8$dv zfH!k};I@|y!LXI;N9AqDJ>f7PhQQB&ccZ@Y;0?eVI>NwwL7WJ^uY(2q_M!8Z=~ln_ zHctd5#U)hNGgSMc^R7@`w!Wy9`gn^Yb==3uPt!M&?X@!=dUk=Sky8b`dl$Sb-Y@>t z0ai}ZNo)_LVE!Mn<~ykHhUU9B?$HU#>d?>_Ui^VHSbLu#(i-uJ~~ zJ~D#aTYdBU3tHIG7bnwALE*KPBCrn<$K_oDmH*3+6Jd|@n(9>edTSi1qZ}i@`uzMI zr}yHa@#9jvc?j6NSFyQ0U8t~zYgP)s`A~zs_lEmsq>@_sjpq0Nag4?k)!`KI-RVu< zfAc@)Ohyd>pa*%A^`L!F@IO6>l)go8S zd2SX6hL3$*GxFBj6F&Dv`#cPK5PWWQ=o{!kS$6i%zjG0xmvEr@ZzB35b{M}0|I%Cp zZbITbq}{~xFQGqTuQI&!Iqpq;kJw(Mj!PK%xsBUYrRH)%Rcrd2^|F?!VbO4;+hEk^ zEC=U#=q-zM#$G|*5bsqN8rn|50LNSGYJPoDL+1@ui8p*YCIY`k;y%1_uC;PN=l$Tzc#60`_3_?;)Nv0ZKaTYs zcalaqA@}$PE47NSdG~IeN`0j#2cPrxGv%P99c$6b##QZ&*0#<_RAi zsOWwPcpE$s4Qv6txewO3dl?WR<82Z%2KDH?C8R!xC)ta@2a!1DiuLPwM$vgk!!lMK z;nc@l0I4GkBfqET_=?5vazc+?6aCyy3b{D_!Fp)cN9{G21b7Dsz>`*{NjY}C*=h*_G9xlU)SoxL1ze^ zvFgcmP{uyJmH2$L%R_A^&7c1ttfj0Dy?Y6s6&IEkCmv+H)qF?$NZmX1lpP-$?~VIb z_Pz$ZFRu8h;0}0iety63CE#re_XgED1;aWn(y&B?C;T~#&vWtZt<9dKqE^8BHuG|W zilanGYpU@3=YRQeqMh?ctI~_$?kyxv&`nl7a2B2Smi5Z}wKA!X_i>~SDUAFQ+98h& z4Lo!~Uiab8QEc7{F{WpWe;kD7vx*NSv16~jalTtd0)KYW{`{{+VI6N5u8D!g$$#hn zv8FgG_&b>Y&y)3_{fa-PNj)fUjf5y#4{G0#^vo3WpvnQx6kpJTVtWE6et{nJeded4 zmQpa>D$1Qzx)$`HV;L<6z!{`Gh8O8`;0zKz`cL_Tb|SPT#a`>ER`d;07v3(mjnApC2gMhv)tu_b4LXrnlIb}WJM{YX!&44#=fxp3a@Q7_5TCL~O z2+se1c&Ps2DmrhuUo4Zg1tKsD64#^4-!NZ>&O5+sdlx4a?jT7Zb@*cBC%om9z0wdK z;*@Rv^6(5c?~60q!FjC5q2qxkZRmBdc^{r)7u^zGLGuGr!B5KSkUJv%dm?#>w;vgA ztq#TSB;J-&PlVBU9~Z6p;|h2W+?t#92E2XGi57PP-btmypNxcqVejn+-OKiP!V>M# z57+>2`@NL}7r2P9lKufFkthcwTd z;yNS+YUBQ1Z{bVETk}@!Kl}eH`a*@!cv~D#T6+=juFJ5HT;#pG!YQx_@W#=+{Y2aA*KJ(1skMx*l#zt?+%;%mrif_knz@V@na%&Z`~Eg1<`mHh|UQ{1KuH) zAtqD?x4Q0?~BrHiK}IZ(8%$8{hO)iueWyQ zUM_oNDgqB9afPFe8_S-c&;LD}O6-cOrn8Yo*Y7(6DbK12^bFx9-N@@&`R=jHAxg5*&~|wO7mKMtU%OPq~!%uE+!a z4IS4H1uMwtPx>9#!2GXr`5_(;K9Ig~&Rajk5B(7NPAkWa3xKyuCTBzz;Jwh$&=CNR*mZ6SW!P~7owwef zj5@(su>X(5CC^?K%JxO){rm-st8)?cJ!1DFbv(n!&vKS^!$Kq;a>EDOac;oo%|*Z3 zH%7}GQr!((POxF~)_*KkzrFVX&GR0DDXSxel@N0#c8NDV8E^fjKn@b`jI$5K(RdHC zz1S-YcpFWwXIjC5Nv#;F%@6d-oQY!)PAH;3Y zj%!57l69}`Hw$#$n+$hvf|5kw!$_Qx%E_KR-srqTBwE^(%BhdH2vSD?Mt*V=Dt)G} z@ldQIPl|ywHt(YH!RD@A=8%iwh)L^13Jyr;F%jeNWi-zlcbCFC_)b@CSvuYlLr2D2 zFZ*0FiMRJ?gcus{o4ql&l>l!k<|^nM;Qfw8&utdW|6XkC{e1L;VH{_~3A%X?m_Lcf z@(kepk&QjR4)BKG9IOlFw1wDTKdjS`vqk-wFt|fdLONRnW zms~yd@g7C$c#V;t#Ls9i=2ScsJ!PU?se#Q~jbm4+z3p;X&vox!F@5aoEpejS6AC+N z|AI6eJ!N&wY<#in08`N7;si&=Ti2E~h{QYV%7Kk&yem1XtF-~|yPK_?`~Yvol#-uw zi@af@n1Fr3@b%gES7+Hh;ay!-NsGMCRyd_E@;1CJ>eBq32z{y$W2hTN@7`Cg#8fM1 zioo4SoTK01aOyI2-V#wgtS6pQAMY@v4iSv}mUA^{MH9K8&gTuWtIe=^`#$L9WlA{; znLLwiin@o*`{|E#qu{pvG~d0so>5ju&V6&(-tX#v`~TR}_y79{(1TdXdXTBO$Ul$R zJ@lMg(0b5w4@tF`9bo={7MB2s>ezbo+5BC66fl=VNTB-eFeE7qD=E2RNBx5x=h|+X ze+P*(d`DRwb%GAke^-z!WV}s&CbN(pu?+3+Wzl#S3rpVa0=&7k^;-e}Z{tisQBClO zHUFIQlzRxAAk7{a5)bo$CsUp8&;j0E(QDT~2fTN?N6t^ZB0_2sQSH_A=qpJ7UD8#B zej+d_PM;@{M}P(W5sRxn)9@^b`gnUGbztSE`ZD`&l`0oxlf-YL)Q`K#}??tS%vZ6#PiHlAS+ zh1!Ua`?2!Xzh}_9_pVQE6ITO8U>79rNZU}*9XfR0_thfDlx|TU?=46jSotN}OkESa z#042_{~hK&j?G&(wd67LkyB6{$G5961z&IRjnS*xTlbXac`K%CQ&h*wY{E$Sr6u0X zWW0@{haE}0A8`3eqwx+3(rB9oyf--sDP07-uOwWSA%fRiR^u8*cfs%fWxtE``^9*` z=M{FD-37eIUn&z10p2sGh}Lp_L}-Rbc6rG%^zL1;uHl0f*qoR|;sVU+;xoC>d8=x7 zf2ho-KHf!09V!_4+2x+i-qgbd?TFwsbo!0Wn@jcJ6=qapYZE5|rrQt z-UF`utjrI8uZZ#4)W@3-se=_Gzp_gwpEZGx6Fpvke7QF}_WW;ttkbX( zZwT$XT=DSf2JHDi6;t~j<@`G{vT_Kqk_MK`F|x@53=M7 z_9XQn$rP3yXg#Qjv$!`BJYp}7dbx*!9#k9h$m-1wd9_DUN;BmX!SJiv`lrmT9xxk= z>0mt=kQ|R1tNZ!&LMfKjCg-aNP+Wh2tn3B!Gf0jaHk_Nj3d0FV9KYzk>`_njGe{>_ zcx1}rsILbRkUFsPvy!^=Y@h`X4V`XYF7J;0h=sTPq^9h!7I{?7j^$atH79%v)+PCMMP4UMoP zp!2I@g_&Sj>XUM_+Y=A??Ck5;cK~mzTW9y@0p9E7uGdAg5ur2dvTAIY&>yiI_J93k z`b`*iMdI?;TjdN+q4Pe?&t2k9Pkp@CA$4HoCzI^G>O?di>c2RAsP`&1Z`FOr_uIa- zh2}U9`#pL>!4*6DtxDIEi8TL+#R*VW$0?mFQOZkSkd9eS#`{R4g&~PIziFyG8t->c zBbBlN@7AI2kzl~P@55G@4ZOWg$-BHye=Zm{_R)2K?s~wY5d%3vfcJfyc;QjN`+`H< zOxOYeTJ;F-T=f+7+#IUy^AT2t^9z_n@v^D&XAefUmc< z5=Vrb0dIq#eKVZk?d`aDIqQ*G0`yhy&83WXblzHKGkPYo!tf{(C#RZXrQM9qo4)qy zh#Uv?@!pNpftBB@Yj?ZfB;g^mf^C}hh1k3|6z|jU$hUx!?~1=2y+y(NPnQ$k%})Eg zal~wj>UdPv-}~a$((5fYGTw&`R?3rje-u#OipJY7WwiJS;GMei*@+;)`)i!b=}5r) zn&_NG_n%;x?a!pEOMnL~?xk_}5a3;7#KNKsc!%#Ec#(LC2)W8WJd_!OzBu7EklQ)w zAp*N0aWe<|;ggBz^M8iJ!h(A&_3`FJ>d3^%FA$tZR@lM?o&SA%i%1PN?-7?tMP+6u zD0p3wV%{z6-~Ycg>!TOn*hcef@4DU|it2d2BJouVczgTb{7(h*Jyr@}{^us^LDt-H z@L~^=0$1#G2@`N=J*fS8@Gf1@gW?okD@1}GR9K@qL=OfeV@>F-?4@A1`_7SyJ@Ov# zUNPba?NcL=$A_)l#lF2zH-GspRc!)9n27k<*=&P)#4c~Y(=^9pVb~stORH`gzW&4u z^`85dRSUAWUvi=T`(gdZ@PF#>w~#uTG4lH%kg-|kC?1ke4e8S1#O^`UJCBC?`dUL) zF|S+fjj`wd0~c9ft`Aaxx6zz{#wWl#lsRL# zQH=l<9-eoTC`IRec3HXD_gZ1N1c@66JQTh14mxk;O4E$aH`K@58L2}NBflxf+1_2b zcxZ0>u1_b|WAkPo8XFHhYYn;3E#wYwtw#N?{XhS;EkBaZTe^kjdE=tYD67Ld3= zueb1IypLt)gMWp?EnbjzIVElv8t-LJCOrheJITGPJRI;|RsUed5b%yP|5B_`77Pns zJ6ZG0+XG%#_kf!N@a}0Ze#imlf5qP~zP@WDKo4gISAQ);ACP$NLXkULgyBjg?n!@N zf=M#^fb@BTO2&hJ>f^l}sbc^mKe23sr}{2<$gbzyV~gF`yagQPYU1L}A?c*IF4|%g z3`k!mdt_XyXrDLh6h(F9-7}f_nX%NpImvh*_1u_9;;pNCTmg;up#EHn3*bE;Zu_O1!D9&8PU4dZl;k@|Rk+>TB{vHP#^a1JT<-`0r->HvxI8w(CjQn=M#;<*~xS-S>QY8#T zY~IJTGS+*)Fo)PpU$q17*ja@AD?APryfB#>x3}tl)4_D-C_$>bZKZb*hx0Mb{ zGl}=e!nU1gypMN=6rKmXzp}e4F7h_APhL|Ac(dpHdR#Id4BvX3W**q>0l)dgz5D~< z9e#?^Mep90aS{HqRJb{z ziqv6&k>Bp%aN`pXDj_{x6^h@sjl*J0`P&#U8Xc|EKLg#EjO1>i90su!9~XuF*Lb1$vOJ z>di+Upa*epc);ZOE(rFo5HX(CaECK`&zs!6Ho+py9Zfqjp8; z15#MxS=U2>!tfXp*Wb}|$~XaiKw_GXW0#1fzDH~jQU@bOe!I4&*V)c+LTNc=6))15 z)Udz^oxdU$7+?$qgvYG7)`s1KM4Ip)wT>_-V*UG4``^R8xhbmSy@#h;)!$d_Ysh%p zw#BR`@eU0VV?yIC>{rvv3wUn}sNTBByLV#dD*^B}E|d0Y{1pVhBV^Z1JGsLZ-;ap| z0^SpBl36DJZ`a3@y{MSC8lDSTO zyycNP_%QN2c<#r+Kvg`H@};un!EJ2b!aXcUAD%OYtk0Jj@*Ky0y@hL*f97dCyNlZS zV&=C_k+M2mTs|N_kX}v3o0zp~X+T=+-dh?c8PIrVDk#-%1iVAN=v^-Z-cW8c&imJ|i>(`TsE_vmQpXHNew@seje|Hmw7(~2gAqCs zbgMe()Ms|=?tS|g1JUD-6V1>6mz^gFl+fn%)tD%%M|b)=w!H@4tRfZ zmauVSCqTxvN4RGl(RqhgKW^a55{Au@xIZ7y45}YP=RGLZwauQEYsKb$PHSefO1K8(>gxEhO0@?2?d^$d58nGxG|wA%HHES|Rt?+{`TO>k zhm5z4O4uI~?_$QwbZES2N>(h&SZ*e|6(>>ee)tb`h987(K;k+S%&b_NW zV4F2@u3CV%-<4LcGQj(g+}VNcR^ap&v#Pi4JUZ`jLwYHx2g2|=B<|jswx7Kt=)A2C znhHiVP#^DMqz(&={32LFzn1gjA=#(aPw~I8d0R+~a4Yhu!`sG^Kd9AUcW<1$wU33{bIr-b|K@+p#U3>TfcbwtSr2mhx%DTh2X(L2T8`F(%vHInn%>-2 ztJ<(RJ{I&Kq6+8OcJPROFyVb8Pbmm4+2ocb+297}S4&NlIgUV1c}>Rd-o4PO>*~FH zKM0Uc_}m98N%U9jC;Vpj<=hp94i<2 zq}P%0c5H5NCh^YB?J@0o0!iP&7r?y7d;f4yAvF5`GUlWnCdZ!y+-F9 zVO8jD+)91Cg^)VJF!HMs+~6XSkB8FyXJT3pWAl!b)VCTQJ_B*Ni))%lWBD%vR51^L+8zPBegSSfckh>A$8y}^0U43*1Y#CC-gnd5Wm?Ln>Tm$ z$1APWu=$4EyYIk&q_abSsT1(- zE8Tcv+j|0(di2coU+>U)JM{6^Ul|mJGm$vv!$n8V*yeRYA;piLhC`dif-~nfgaQ}wQqd_ z=s`Keg7L@T9i)|&PJU@cAS}=X*J)Y0!K-+`^0zsSKyNg+NauNh4bpE}d=*0kNRQEd z%-;Zg{`U+U|GmdX7&b)W&ZUevxhzLNVt1&0OmxDP`g)KvQpZ7z{PJvmweIHRf_8ns zWYtv5sD|-R4QC_W^vN&J8fsxKWKwy8{fNam-#84j$eA#k; z>f`+#sUrv@zwrtB%6@G;ByKmwN%s+(x0{2n=IaS-sBKCxD02<={Qpzm#8Arh9?kQf zSx#9U!zOg0m%Nwee<3p7E)k>utRN+tx;W5yn^qRx&IY`K~4b)&2jVr$tXP~Jv=}d zK7_=zf4?U1wgR2ET80Syk*n0lTMwy286&^D!;_<8p_~w3HEzTB7&hsKiSJXz zfVc8}bGk*|wIerIvVr-(RcuFA4lW1|zaDCplm_13a@?uY1ia(F^EpKT-Y@5G&#nYN zZwdBXr`7l`ysvcZk}CqoTOyG-hFUM@>?(BLu~MJxPvub`??|MMXpH>Eif6uXz2<~u zY%9bQnXm_>Bd5&vyt8+OrZ<%|l}uxAkd~QWnPS)&PxAxPJKtD}>R`C3Xmj}Qj}ryR zcstABCrG>rq32eh@mBs)?N$YN8?~wHTwPpyCs;)b0^TcaH~i*X7XlJe-c7sP$ z_xa!eZ@IN$Q44@~#_DZW>+=bac=#HvKX=f(w^{OsZmwIxunZD6wnH~}Z6G@DpQ3LD z*-EI7w=q)3I7WWzgMD8iK0IVNo?O+o3Y+)cS$^}kfVY=u_zJ~D3g-XIX}=E)-K2Tm zI5!IG=)QSN_P_ZbYlNeYzk~T-oU8|V_nY~XdeG&k+j-G?(D>Kr$A+K>ZG5#WCJFSQ z7IQj_MzDg^6v%U`iwlHDH_CsqD|3ab#qw&eo*sdM>!t2FdiFw$30#DdeME@AtTN!? zcJwQDS7o{nozxJ9*CKKIV_ZBqThZr#nWXWGq(ju#gO($8NMhtyMYrz7fmSX^T0HJ@ zt`YVMvfcPy<)wZb$mKM5!?Wwy7o;=${Mu%iMf(GiN(5zf*zLYrWC_k70p4O{yw8@n zf`9e*=PfLs8P=fjuG@63!V2(aWxU;Y4e+ktEU>#8@GhKIc>W|I5Vm-!lOz4X6`pg5 z^|A%LhkpOu{{ZlQTh@K+$2KCgY<1V<9(HuzKE@?)j|1MUNF3kP^%kK!=)A)o-SOe1 zLf)=O9YGlR^{t%?eZj*GWg70EY9wOwu4kwBSl?{}jpli=%&y1gjT;(iN|-LC{Q>DK zg>^Uu=_Jt=Y z5Wc1J@lYA78{Bh2XNt#%AFG+$;Y@ul$h!8)@8`kTyyg6o9yIJb05yMc zDSq<^`}LMYV|(@S0a+#LSTg+2vuLWPtd14_?h8%Qi>3^H#mG z*U|Sh_3ez*mpRemxv8pCK#OyqEJGKa$x4huCpVnaSEn)gF{Y^`3-oXjPw4Zt6 zG`~0r|3XfW`?|=T7{J;5s2?iu-vL58$88=1hK?ye`1<-nsWcXbC8qk9d z^Bx_)0eaA(v!!AMpa;zj4dxbv1;YLO-0zaVxxf-v?f-~6k3e&~jOQ+R^g@B`xati_ z;1{HIPaNMkqW2(K7exuV1|fI>iK~2g|IqJm=j|`V&xRZ&wNPZ|w8`-_HNo&2!*2&G(@BQp)ORGqUyM z2wqx2ZX)A-{{HiS9$(_e2+*=0||oAPKKCvgo`IpURMFZ4!c)BXJ889Neq_ z<$!dQqu5AE2leqbK| zkk!1ayK9{fLcOK+e~NBnZ;*PGCUqW^+e7p7zhNb1bquu4Npbu=|1U|#+wZ`eF%oYF zhFkn-yk$JYM3n$<-iLIbuLIr-7ABSrfVbw(x1v2!fv}roNB)SOD@=T$ZCeL;s~H*L z1;N|fUY2cw;%)>emrY0OAu~Gf(x>}$H+2ZXc}U#jO@70<*U)*lH+E&E^-&-1+ejTP z82MG@vkuOMa6#ASwbnZFVe@8@Znn1~9)zSXoY{O*nt~0|eY2dZS9a+3R z$nXCp$awqmiwu)^?=C0uq4DOKSocZ;@P4(m7h2@aGd$|n1bFYV_U0A58VKVI)f>y= zU19MOkHmDq`|`TS4^05?>!u4$Ek}var_G;NymLn1oKRlb)^J@@7$(IXu4DH6%!vMZ z%XJC#JT`}^Z~m7<>fpu5&*HGj$HZtZNJFUOA{@BBa36h{Sr2lM|{vK|!N+Ez;HLE<-rMA3SXOG$K1 z*K4qXl(61=6ZD{Kf;#*6ZXu;h=S)fcMikPUdZv;PsYq zUKVee3tVaS@&F$2uFDRwn*+S}ZoY2mrAL6=uWe=@Wk=_|Y{61y{IU@2fy8laeN}q* zB0BH>Tl9rb5~+{({QTcKdNA@^VOAhzI**4=T$Ri|cmbPt&g!1#{AN3-{Nx7tbDt?# zL9Wc+Zu^ix^Sp746xLxnR8(0%70h%Opo(7kG74C{r_dy%o!~Cep#Z7h36m?&?4R0a|yF1MPz<{)K_hGF?-mBE21UG>JiC!hhJKQr67T2$|+TG{^7jCO}b_Kj2uT0gZ z1FyGMH-#kg-y=Ym>qMF+3eb7G?3b3$EE0mFk+=#UzXmZ;bly383c^AwsgJikQbz_x zery5P&z`x%1-+>$m=~_V=B=lh%(Hdc3Tij8iH02;G4KCNI@;B?U+5^!&;L>)l+__R zSC$!cacOfxhK%>c6}O5=yeDfc1<`m{6+h}^2fR}ZzTQXyynV**cBKK{AK7j_5(^E4 zOF8d;+}Ys*@BYEZvK#Q$C7f+A0=(6~KlbD=CqS(hPfTAFq4PeL+fY;o_TJi%xLZZL zM=Ye#c{9My#lf$skGC08$HL=(&+kX8ui7E7IFT(k*(}+F&709aaplcfD`;i-!1>As z?7cT!bd<)7s~PQg?~jz#QL9g%zU=;g^FI|#_t+_b`F{sl4~l$N_|FCD&-hnMq4glq zKU0$FULaeb z&=%$$na?D^6+7#sCuWzU_aMmf?2|PLLU0NaCzBc-&To%CAPo+uaEPfB zF*LouWEUPX6-mkp`bMvY^$#xWCcI7KfEnaEZkTj;5_<{FDN~+vLQTzI4F*i@^y;7rS)n#l$Os_qVE}h4j4Oc#EITa5m1?hjTNF0s#ovMY^<$(7g_SH&@ zybX?MJ0AnQXB<5rToen0_q48@xbwyZ4i(ZNHUZvMwXCb_0q=g6^z{zQ2@u1CyGwT! zI`4~C#hX(P3c;kfxmO!>R5qdWe${2jwekq{@%BRMz{+p>=In0neRv4oX{u=K%riTtFHVD@5vO{F#5O<9D>AYtQ3E6b~8HfZTPouEbOU|_Xtu4R(@VL zlUFmx;vsi?cE6Qdv3ave(0zHMYY2H=+Ug%yPr?2FM;5#z9yHQCZ`=V2>oDIHCGq#| ztsEKeP`b2>B;Ft40~^tJ7ZZY3wF2I^TR(hV+hE6c(>rJw*1inueSmPk2B`F zz)TZ;KQ92@NtK!!>R@vshEDmRuonR;Q+RI@dy|4L*%=t>!H7O4kSTw~vY)`NcOu5xhz zJ;)>eT}?LVL3}}kuyJ{LHPeVv@m2i+umZ1F_&pm}*gvgq`ZSpT;|VP9OTg-v1>Et%b+iuRCoU07^#C7BfkX0 z%Q==!oKUdc`t%fUdNnK?wxe^79qM|}`)Oa5_8-_Q$mSY_$I*XifByH{Oj#W}l*cr5 z|9(MAk&JiDrTvm5-gPH>Wzl%EK2mD_$ zHZ^pGS!bQCT>ossl@2CiCE-L)_nHRzza+E-d@1Eoh?$X|}z&xBMyv^S{^( z>jMQ-+FwCVO;c7!?9tGze^-#Z$aqIv?t4b!-8Xhe290<2Y>(Xqz+0_}$2SY`)=%E- zwHffPRX%ch%l7~{+F~eUNZA!Wy^`(uDZm@w!PWT~@a}cKRg$9wz93b(X<*J6eFeET za&_iTMj@CRiK|jC-N%`R&Rar+!@Zl0`c{xUNF5t7@)K$iH@o(p6FN5RbK2=XHt+an z>{eg&Z6V(f)|eli6zm{<6nM&*(NFuldnv19wu9+$a{ki%uRz8-N>1?>i8rsak2D%@ ztw_h1NWeQT_U7wMz&jJ?rey+n=j?g6^}=)jT+m@El(E4T{yD5sa}4mlJylZm3h-vL zmR}eJyty5}E__8;iy!G~SB)Pu3>@-jiSU$S(3eV|nh$MZi0AMxoA~E)cGE;jb}g za)mk8T^rN@ycZOH7X1OdV{Q!(+}%Tf%EQ@8=ylL}i{LzsG-QR~2S{98xk8e0DthgF|FLVBcA)hjqi^bGwu2s& zB}4d-2YOIfSfoHZ=s~AX?BH8D9{|URj5Gtnz;c5SL`rqbsK&VZ=-qM zitQgLs^gnmfl2!1CEluJyyFd*vyyoCf4M1-#@o?J;Fk{IE!iu4D;MzAwR$`04|v-r z4jami1;AeEQZK#)xWe~;J`BDDc*hT$b_4_7%xn)%2I2`&@n~`2slDjD?GFr>r5+Q6 z?;>#}>dts~Z*<=3x6_V?mQWvWE2NIy82NSGK6%<{85fivuy=xeCpPb)Z_tAu(W;Qn zaUa#wRTQis54~k{Jk?3_ym9&z)=^~>n)vs6OBFKSaWWqBB;H4FosmQ1Eo-J%YXW%d z&~IW~4 zx3{VA-CHo=eRz;T)q|4&)mnRsg^HthZ`DI9tlk$0!c|DzuQ#eQFHfTL{+dF+{8tzC z@!pEmF^rMlyimeO?<`_2b>&p`_>o4qwx~;BE?V(`)_xHJy!~Ny|gZZDE zvO28PbC2B4{%`)r(Zc_L`F|f-4@$Z1J-FC|Hhq*N+RItv(0Wi6CEo}hvGL{`2#&i0;Q|Hg7qZ|6sVaTVtyf(~pmcxBuIJ9ZPzztdrNLzc$fhpZ zwIdY02VF1~`KkLt06vDqg-sSZ*d?R)poBKAE2{R?*Mq!}I^r?%ON<#@^;Q-S$)yz+ z`$y5KVbN)vUt5~F`v`P2b28_0Ed@JBPIcEVH`vqu3i2Ffbv)MM`V?EZG$8FI<9)-& zHktH@&3IR@h{oISUim3@z#rGad;@rgn!2+)YzOE61^itVR9xY#-MPu3 zfcM$WX^(mUZ*@ln3!8Bp=ts%Lf+<6E-Yj8awzk~@@HZsxwf@_ntxo8?@9Dh^t9GG2 z-V33B>nOy?@3(Jpa_}S`dK&YUn>inwx51?k?#UPIq4f&2CBYNeyd!C zft1zp>Gjygw|_54-$TYbd9T|x67L^PS9hWDme{!c%__jV8s2^THsIY}9^%ytc$s^rD*Zu^*YHZ%J=grJaV(cLf zfzf`?TiElze`KdktJW8q=Zy=Ytd51%KWpJzOWj+YjQ4dhe`OMH%gY1>G~PFc1k{88 z?*Qp)?nU0B32QD50p0~_H{PsU69`KYBZ`;1xWYZ<5h_Z6x03g(s~F9jU_;BR{y}-46~J4{cZdcp~s8HgBA{)wOkPZqRed6KA{xDL9bGHsd`d(h(izYuK6jMjr#PJMXrq8)sL zgwe325cD9~KF9s1!8=Ii+vR1eoC4v4(u&M$)m&ijFG2TDgGa1XZLSL|=t27R0aq3} zY@n~oSGsIY|4R>wxFnyjO#uFa#Hm!2H9q^70cpSX7pao9)YpSNkveoR^0PJ)F$p|? zhpukWirlgsy9dSI6O%12wub5DFQp2wVLxJVceXQI+m6$I4;rVij*uYt4Sx?vYm@O# zcNNzq@m}pD#DvD1L7B0n1Mm(dY*$(2&9s~2Z64rVGH~~qhixDnY=9fHv2%e>rsXC^ z0^Xtq59vF>{6FzzwqVaT0wmO4xkaA?{fga{uR{u79T0#8kT_zY)JZR7G zNl_o~Wk?-cG4e~9wEfo4jfcK@)8%BUVDpwromd~oOMqV}EktS2W8WZ!v#>psHS16N z15y@cb$sC)mNJf6T0v@&@xG<>(3QmdUgj7B8gCV~>Zv}!+c@D@=3T(MEpzJU;;**^ z<{nBF9}R@{Z?-8vy5<7!Oc`{Ld)*3iA51TTUw!sgL({q>dzv{FaUBRV49hgl^Zt6yh@v{e4etMTzqGVLs!7KCCih-`5^rPmT6#3z zH?oWkzXINqI)_#)^4@tUd%X@AkTi1EcOZ9ic~kytR-zK4IjioWm45 zAc}{kzm9KyX^qX>K1)&e>uqDmRi@?4coz2gf83Pl5Bg)1G|wA%b0bA{@K<#j#Q%N0 zr9s9!wd+nFiT5VK7&QKVSPkK%BBh@)PwENTW{ain6-g!UV>2Av(f!J@nwJN0Gddu5o`leag zM`@n71&aYib;yOgxo`zv{qOugm5liRng*Ev4aj;>Ud#(KQV+T;puHTe2jR0nze@%^ zNN3%%^kUG1CN8wu^@A0p)!sPUW#9`^*-D?@rZS&_uX&#R&IWo=LsEHg37G#+sI>|8 zrQ1OBuP;G*2hn?woV=8lPV9Pk4vCvSHFVZT1-%EA(!VX~i{hZV-~Vqy>L|v@&vVz@ zD&lEQD8K7z*waK$cb zSvRYT@)Ck7iP$y~94y3St671@B!doavr`{Ba%@H-?9ic+&X zyc(UiWwWaEngZ(M-GkI|1S3C5j!7}WVoqq<`pHOQ4mR&K3PsulPfg)Nsn1?+aKe7Q zrEuccwWGQ9G|zjR31xM>+9uGm_wV%f@EUl>pX zc$aAAmlpuuC*E$B_qrGe=cxV^X7@P*_s!pYwGr^{?;u)|zgX6Ivr0GCNs@ z&Aa8O#Pg0uQ}`m0J^EKO1s9|pzcJ#qyM^X?qcjjCW=W&XCl-k0k{xL*vc+^yG~i!2502QNki`!B{IrWxzX{d+2eSYancH zpgE|!&IN`$G#(fM-iE^oW(t6JZ0=z6o}V_*_jAngS^x5Ri(_-%DwYBQ@F)`Z$@Obr z-@kl&i=oi8&V-Zt=6^G!4myndmc80jInIuUc4fiG3MR36ONMuU|6XJb_Zb^+(on-* zd)J?v z4?4TBmYd0j0Nwiilz!?d`Ua_DO(*Ns`t@)M5?8vFc#}U4eSm3TDX)4SGHcmUpo4yQZrFAhk|;~VF|EB4Y$UO_jy z1L66)>a)kxonaqkmvb_JH($xKKu^GXf7PE81%}{)w1Hy0;-2?}E*5|9N}sdjA~<8t?UV2AuwY zca*f3{vz+6{mtJm0p6}W+3j`}fw02q6()+o&amzlZ900u`+kL5#}mN2?&g{dbz=h5 z^*%aE_!2sAL?2N*=!NA#QPu_@7vQ_ z^`!1Ste(9RjkoEebDm*<_mGi)Z3*B#oOk2RcQ7DDaGlz(5d-G`yYyC1JDlP33Bt*X zyq`|{y{!hk&z&&Zc+i>v?d6P?-I0XO+gem0(}ovpkRov-UsxJsywG_wh_s3SFZSL% zoT@ea|KAz+GS5>gWQsy4rL-t1L)WGu-%rBWzUQKnEdn3^O?l!V6|nrM(BZ9^0h zCDG*f?Aq&m{P9_5?LU6s>$`ogbN)HKb6@AW-jK9}g zn9sobTD86_hIih9{oHtXr@ED>CqulOSAA2TiTC5~&)?TWyz^I!4BUr!7f7sM$qe!S z=&|%EwR#&qXGjjz&m)QPE@%}vQ--VrdXdt%A9fPIoH%ftcV4NJ<*cvX zQ{nXa$e1s*X)}B|@xS~37-GWz_atBkxot)bx*htJ8>>NH+L~f`HAqvd!b2CfS2^P`fg4w$GPNw14pd&8p7F*}=Fx>t><|B+CztauIujaw~ z|Mv3989FSRCLDOwU-T{R3ET`mHdTag(jb1szMrgNQaxuo>ub=cTPK3CKAq(Fc3I z0GHD;%58}EOXkl_VG!?QOSI1RCcB`|gfC0iU&qJ$c&E-*-%3f)LW^4;uwt9FH$L9K z4v82h++sYuV`x5p5ac)dkk#k=U3k5vwtZLJ7Gk^?flEKOIcx?-T0PamlXSddS2beQ zpz1p7@g{ZA=|k(IvE1L+Tei-?yI5?<0mHjBs8tvbZzHA0h87U-vj(;A??Ak#_bZl7 zF4xfgbY6k7B`*@Vc)r~&%;F6W9%(l$fOwZUY7ZtsyvHhy-aVakK}D`K+6+GjEA=?%?B4je$35_eXaKKqi?reiybH=#(VC( z!%M$(Zbf}>s+~1^LA-iPa#fWXd^tAz@lK%6hkd_7R@mR;En8;beT&pL2g7^!!D~Wz zc-ysBtltjt_LSVUi;8#T)!rYz5N|)ZO<7#Nk>KF23v2c$d4oNtw_9dGy#0lnCi5ZQ zd#hMFoTgmRyUNL|3g-BDuh{A-tT-eI?$F}W!Y}SL=EcWbYqJL5lWxYtdpXU=GJ^be zKDIGfq$hyh+_vYA*GFQ!eVz)j`VPCJF|s?BUa4#*Y-ZqWX&t=Dan`^8f3t`_A2K@c z9@QQDvpHcs1Miz<4!bbCTlRYk;^BSLZIyxx#5Ln#XGz5V=L|749w zB)Fu}`_-+$8;~_t%j|=Ai#2&ROhLR$)`-b(gWvyqb%yn!;dgwzZz=9<;=D5tyr9L! z^4=BTug1swtsCXGa~b2!|2Jtq-Vo&X6n$ZuRnCvD_Fwf%kBfNz|6x|$Q84O`GFe^9 z`?{Qt>TT6B<~}$)`KwEeFL#!15rS;^^R=OS1+(K!XVQb-a&Hc(sij! zcn9h2rxC|@dbyy>5?NSG%J2syuGqDQa^_0{bz0mGGp~EUobU&vhDE)Od$}0z5z9&Q zL6o1yBPG4-@D)4mbdA)#X1@s^nJXLTDp*(?1%k>2X3lgRkPdhWR6^C(&H4^^7JNTn z69u+d2Xl|S_X3njE59cY@3W>}2R^|icH7~}ZWl)v^c;(dgZ?Reye+FH*DhEo3DRkC zo=Gp4ty_nWx24l6lBpu&;cY?lVL_0emXNqk;~sw0;0mYOD{o@Fdy5VoIbe1a1f6&O z6#cZ8@UH`@rm`bH!*tf;O^Tw^hxH|n#ee62yBT|Ct)t1yP5N{p||0YV23+nxv zVwN%=zk|Hy+gA9Dt;9R$2*LADhq@%}&Q?f3763ugcQ|6v{U`RGunKK3;E&;I}R8F=3% zsdiy_haWpFfroeX@boqni1);^uJOAN@3zXSoLoQDSJxaQf4wtuzT$Uf0(?yK8eyvf*9K+q<$DT%BWFztBMDecn9|22O%=-CX z$eBJLhR@bIU(Wc0x9tqP@7!wA$MC+lb(c6E-p1#qeY7CnB0^WZsCaWPjuY#Ec-tNq zP&8f?1;n-^&9((z;JKO6GwSlz)MM@Y=OEtG58fC(zwd%>BR$AFsfdqv_KO9j6`7L2 znieV&%0@2ypAPHH_tx@Q0UA2UUt54ngyRoI;TxBt&5L;kK>`{EYEx3*zNK$1yyftV(tO)XZJXzED_7y+cAOCv&{d{7)pZeNN@okL& z`<8lL>sr@L_}8Iy@mJAHomI0QZyRO$e6;+VP}`JsKojOZztZ z%L~Nc5^afqc%Qd2|IP>T9uCSpaZ1(|brd;rxAYr6-p=A|w~n5c1UqPPJ>DY&E0XZ> zKJmj`YT_j0;q6585l@icoc6%yy6}QD*+>IL6IS8@$tZYkv!H7P;Mo{b-LY-W9plr!l;9pKf1(hxfG=I=LJWZ}Z&+EHm+T zl6bx@72>UZ|3RfS$s6Q_EYkf9@lMP;y4Tj9g0?9H-kBHWf<6Zu^aRK8Hzzhf722Y} z1`j9F;#PcH`+M)de4N;k@8oFwXKvhH9BgJ;-~0dnr}_T><-ZRf zv2HVJP@_wLBUXbJc+FG7t3f9g>$q3I4)O$Ba9|aD#0EYtcK3p>*pX36FTxoOo->Ix zFeE_#Unh%FUMf4XUPU4lRz$Y&gq)89v^QC!RI5`Y|5fTr?jp1o=sNO{lm|^P#$( zk%u)Ki1AMElS->{b^;RXL-yP05Iz{9(~O{4x1#QTdDPdF9tjp@ra?1At9p9*l^dqpN1EJq8uE6Cp91^Sz6(fcsJdwLEq@c90U)d5yScKi;I1 zbovNZtf3umah-v8UCZx(4ksobijv2}d#|Wu-3y3!Vd{B=inr@$7uAJu^|pUaaYX;p zXkaChYa*%W4X)pix`V*g+j*;%kw}QQd6~oc9fq!`r!%uc*fIRg3GI`i)5TqLfjceE zjhQ3+H~Ap$LwoVm(>KQ(84vFjG#{!2`AOf@k{#paN5k8NH}NbbUf$XsSNem+BN()= zcURx=vkCXl<(~%jFI(`dcj5=z>C^8R4{uAFk5dHsEvUQ7 z!~-`cmV6wHyX{Df_wTV4i<~PDgLHS6BR=1VHz(3}E_Tl&>CXD*M0*E)J|g{fbYmj^ zd;kBR^2W%&fb+lSj2iUVdet+m2DPr?Qp2l3H*1;VPr(}W=IqudHLwOHIrv77FV)a3 zFJlSUuZ#lcqwYP3HirWee^mkSf}hxFvOab@n1UKDOY}-U?Se{;dUOch!|xz#MeZhR zR7(IETHNx`UlKej_%)~^gYw2Bg^S_VAS-A-stEEM`CJ%X&n$p`P(GMOPq2sye0L!RPgY= z!uPJ>EX4c4QM;{FydAif>Md5+(0%L^+STwl3iM5tZI}1-0>&{NuSsw~dSYK;yAk3o zF5f+m@0bf3Aj=}3e-a<>WvX0UDqRvFh!%J2!QF+P?D%*uWLie4D`q^rRcSsH2=Ysg z3Qek7!H*vBnfp47lXyU?_1_@dcgh?13gx&=cMxxoO7A|_b6_fG*5h58MV}8gcAer4 z;eU3J_Rhfj!Ia$IfABt(w*(LGxl^%x7a`u67d^VFA>JY1GS~P(ynkCaJuvQx0;eCG za2`J41y1g_3zUI)Z@ag~p9kVCpWpq2749Hew(Yl--j9#BSBkI080%bs#kEH>$JkHc zpCE1I<{e0R%XoP2q4{_~kY7o+ft9--AIhnd>^i!D7;krq0I%8+Z?M|>$m5();^nQd ztBsYH)vnHZyh-`=`OqDDVKb2aXFzhFfp>GQbqI#{o=qW(@$io76|%k#@h;ilK-1uT2qjnDb>OD~GI*-K7cmq-b&Bq6V{6g51Vz}<{q59S>ia&IS z@lG|d+yu4+fv3bYV=a**v25DRneLlWw?uR?hfAHQj1MjA^#vBaq zwMFL2cz9M5`>!*5rJc`OXtAjE%m!XPt|*Yb6Pg0&Jgb_ zdqg%|fOzlwp!ZJZs0$i)OuneZ3Lo!~*WG<4#&ba^Elz^jy)NNj&i{vKlW%WOVm!Qq zX+91US?fgI z2UGBC(2G~i4GWAVKrSsVW7t}E&M*89GQe(=pP3Njb&!u}KK2phm*CO~w@~@fwqIe7 zrO3qd|FdU1-)AZu1BzTfNh){gxF9X<3G2#Rb$4e0k^i2e8l67&BpGY`eL>oH2Hwx4 z8~*t~n&IOXO+364wyqEhfOv22i@Q_@@$PI2u6+*izLYhwc~fi@n3I$cH>bc8+&O>x znxf|rnqpp;<9LvQ7JP8}e)66RO454%>g`JWCH9NCT9JcJ5`dW&H-z-2Up|B1K?>gS zH`}MeczBaytjRt9N1!c9LRJsdvdAMv4fPG$lp?B zT=wtm%z~eKB+%tU*SL@^3m&n9)!SzV-mM?jF2<@iNj6gh5AU-lCZt0k-d9gtP^aQu z9k9+7K)l-)9DL}T3J0Xc=@&@7o}gviV*EP9d!v%<;UfnqXnN?rIVUPy&>f%hT7E6T z$6GtZaQ&$e3E)7BGqDM}xF!)FZ>D%)8gImScx%vnuoC3g>RZVhX()hhIP_6$-63MU z4>#P`KE@UWHZ~X=#atuC+iw zitSg&!+WZF!|Di#w?+Qjidu+w%e_GHvk-5a$+T;4a-u*^4KlzX?FCxbb;$9-&50q8 z*FJCd!_Qk>O{vVUcR?>Gj-kxDM$^pPkA0cz5bdyXbf_9^Ps+ zA8!fr^Xn;YZi?hb>qX?m@17>cTR7Hr5&Q2*P=DD>xx9e*a3bm4GE0Ovebx_1VFl`R z`7lsD_I-K4pX%*31MertcK-8ui!=4;QarpLC#)jy-@fIAN{Bri13tIX@C^%;rzxU4kpg!bRAOY^t z;*Q6y{+4QskN0*!W*ZG-JiO1)eApA@_bWMSVSFt=%6{b6)4Nr~cz^Nycxx)+An@-~ zi5}lfjJJ{WCEsXAu35i&tLvLfmya+(AAA0y|IYu$+UN0>6V~MMma+d@T;1)8agoMRt1}$FD)VE(KCz z(>NJ!|Nl4nuaDgX`F$}D8LmnZKwW+bCB6*#PPnFc!b2c}r}PNOWfhgua3`)oVmTZ5 z?Bt7QeFteQQKD9i=@{3E|mQw$$( z@3rc-4uj(08!hf##EbB;fBF7jMahz9T2~nl@7**XRRsCHS*QQ#Qo8`!MLO`|P6{#J zg<>WL7L*+UW*6tDA8jJuASJbvzB?J-o%MK=dg%1gLXtT5_jpU-47^{y=Z(ei{=DPD zN<6&l<_~VSf_R_X+~-Hddq=!khAhPU{LgRG3-&~TC+oI-ly~(6oH;iqHtvNtNSCh~ zIC7YRilt?nHy?CCzt;BkFPX;gASHR7hr*d9z!WX+#?NTEOdI^_%`b3JQ?8!z@D`%^ z5F*HLMEoiXKc4`)1bJdI2N2_J!=I6=eSMO75BoF!2h6~`?bh?B7~b1Id#=F4J20njp&i8A->{8D#hZQ8E3ZK~Ajwvn z1eg0ofh-F9!$2)hAiRa`LLJ0AUG!{A@gWLYeLXF+JlX|4JaM}BHw%9Cu826sTB;}k zj?&`D!RKC|b->5_1z_ds8fHAai)lXE3GzGFC}I7@gda_P{v_*l3o+h)KOeW=hjb5&v8}7YX$ekPg1oz$+`WFr- z?{z`1c<*`nxEjBDKN`M@>aUOh`LsB9IjQ0lrZJP1$uBZ9XB*>4oZKOXY zh9AAqzOB}BkQncL6$e*lxc5d`TIPL-gSa{2$u`rzQCl(V@m6_ApO5P`TR94o{+s{* z$ysHHbR@b02YG!>d7wJv?9L!x|L0mMf+S)*z0@$nrh#4ASb5 zVu=O=ctJWxDof4*FL0Ffe1Ewcod0uLYrzo;`ZY)5%~vxQw8l(}uUHiS5qooD+Wh!F zaZpc-bKIdkb;c3D27OQIuH#l|l5t$*)IBejF%VICZW^Z$-Jhq*r*M*$8` zGZF52Uf_y~h2BYs_m8mVeCKcq+Bcla)Tir$>Ro+&>DRy9|L4^jT;r1~4%XA+9xk%x zZCZklw|~n?%lvJOhqoKehc7{Xwe1oy0p z1Ja*fT#epvyn5E-ZSO&!583VmGAe&BNZ&sL@6Joc$r#>k`L#@Vcsn#c+PnAI`=`mr$e)1H4f7SiHgM%?UJq>qnxYu%n}>cNbM_ez?N7J~f7)E|ZfWC)-Qg%7Hw z6p8UBsedg3D-Q#cfz{3>5_B9+l+wPRw)5VsACO3zbowZ5%HaEZI5Btz-W@@8|Lnb8 zEQ_Cmi}wc2vDFaok2X)6se5k*d%a@LsUiVbd7QK0_&okQvOJ%MV(`le-Yb0Yts z{Dw^sZrtBoZs>1 z#NmK6exf6MN;L{ZqD<@L^5Hi~&DjrIyAGi@%TP9#78=|s^52O8e_GsIsgu*&Bk<4vU&^+M0Y^C)ZvX!j%||9deovLvr+4-7qhqad+jaDb z2c&g#rmD`{CW6&WmB(JH(NTkTIPSZB*?HD?kR%WKe3U0#jCDIj-TzM_&A|H|>*YBZ z-ix@zIq~qmptk(r9QcS8NHJVT#e2*CyS=&)Z>E!^mNmjRg6vR84AqaaRDH*gLu@*q#{g$c83sX0CY9Dmm1$iH<9FZ?F#ts+?+{^?1J) zr_aZmwA~-<;T1b@c`I}V-n~uf5*XgM1^N*@yp^MV{~|-YWrDV}HbcBMqs->}K)fkC zG8Ix*MFFktWclmx>n*#!XWgVgyw_J7e19HEK@pK%cdLInqa3Q=cz)*L(=w_m@R zA0NcKzuUrriucjSe3WYt@ACKLW$NpqKwa*&IE@M~P&07n{I%Uf==Omj_lO7z>M>+0 zdg_1+YWitR@IVy)fKLW?zS55Z|JEP%eu+3z{0mKg6K6@&AhMbSWrd53Lnb|c|l z9qIFXzWX2hW}HrB!2yYFMh*I?RMCOeAc;@90(dp3 ze|L803poF;+-%eN2-cw3s%vA7@C?$HVSl;%98sWogKW{O3qIgdf8j|D$00Pg?uGKI zcnTV3`T6475N9;Vpq2H!9DWD6d`>`1;Z`vaLW>i0m>ZYtjo(2c`tot%J@B?)2Kz^Y z=7W_WzxJzYf-#5qQMWs_>lE)#64sQdg!jb*dP(5X&xc!HmeNs!D%2Z(yV=bC4zh|q zA3swjEbR;b%>S%2@E-iscoD;!?J5sH9^QKHXFhd8yoEQj`cUzH=aeMf5d%%M zxaTUGQ?X|Fc)yFhc7T1F@$mMd`JfQwr|>@AW_+Uns=21yHJw6?_vFZY#ocX*VC>lZ zd)z(5cyqPw57@f#$*jj)vx7b#RvxB@xBt2SFNtLa-XE$m!ZEz}J$=oKhj+`uryP9{ z@2Hzb%v8M7!meH11@Sg*ju%}k83lyi4cRPO?*o)MhIHE?-X4@U$D`sXsG|&y3Btb98n4mQtvyh%3n`G{Rm6f^c`|38U& z2Hx+J4)I`k2lQU&!NYrHs)5W9#QVejuGEJR?~4aQ-@k%*|86dGD^iF8N33pL>qUHk zhsC^)xz0oA1Ty5N7E3`rKaVz};m&A9*X7>1zwz-_stndGEEEGZw76yW)%%=G@bQ-N z`yq15fbsB_qxqOikl#atJC`3k+*?6(gqPrjJ-c$3oT^ughFY0-c8|1sDkijxkU z|2b#Wpw9|CFR(}Kr{OhXcs1zu94@IMSc9D3%>DfY)*$84Ja& zr!0e?e890U#xaL>453kH?Moa}D5y;jOWL~4&S>5{TOL6n#Aztp5_o(iUiu@xjtJzLc9kg6j#{~p$q0Hu2(okK`UERwEEUNqY7Ns zSC0Qn2kD>iuv30m6sXeTG79$=uo&Xwz2%soUe#{K!`qMM!;&Ds%iogo>)rU#>FIWd zTVBL?hoL0idges%=xc`ZNhM;uZy8+wELJ-E4@ieu(dR?#@LLm;tUq`oGw}XY5%TB$ zKWYbAe)g3x9^U(|BqvotysZy@lBVLVXehsQC&c^K?<>2Ddm}-%SYJ=ufDg!-w^!#U z#Jep|s;obWfb4f*?X}s#>)F4|{{@0fi_18~KmaZ7&~NdDmMie_7MoXGa_bo5 z;hj(OAxw~8LwB&kx?+BGmxEKi)CXY_B=QWrN8;+#vFd$g@S+eN-cJSl+U`TV*Opt|dQ8RJYsL5uh__hAWm7JA zFWqLQ4NUAkKH$fbduDfb4xveBta1tyDJZbrIbvt*jHX^!wF@4=ACL_F%KH|nh=H@T zxDhFP(?AV;yk#_N8eiUIJiHBPJ{Az<_r&eI`1TNfH2v*OPQG|zyf3%2z7?#B2c8R5 z18=`0p8u`tP6annDrfzG)L2ZP5B3$C>MCOYRB!efcn{mR>0x-wKMWGY!~2d!eXW(YA z--h!)-;5eGInR4LR)h3iwCCg1p!nYj3GuK7Ii0WPdkSmNz`~zpI@BE`HNL}Q`jNmc zvEvZ4pN>@ADtbxO?=1xJYsog;63qH=Fb&7)B$N~;+G^I z-VJxZZc2rCFV(z%r4`~Wom?)-3h`Fz9Mt=07YUa4#{XC(>}S4xt%4FOc@6 zQ_znKgKJ)9I-~6See+v>;xBJ4RzEVWks=DXX>q6K2%Fzpjeo>0mF-5(Xw-U`q z5mumGL@A0h*5>g8c4{Ui7Q>5<=fLmbhfA65}22YagpOkpMQ? zcNUUO9^n4DVAY=V5DC8{U^46P|D)H(m1P1#lodWyyt!xKJwCM96vO-eZZa<3cSh%t zvLN1}Cn}h!cyHbOeAh;Z_miO`YBA>`!GMRV6*}$%7F)!30f@J3(9H$wPE$~`V$W=| zEEn|G%O64<6?<@-3GL|nlbzk7fTjI!TztUeRZ>Ivcpur-XESWUczCa%`8Z6FUnR*$ zvL!+cRU9(@#bQE?_xRD&$D=g~V1ZXj=0g8gLcGI#dt3VTw$J+NT@XT_4`HDkiEZOK zRJ^%n;QeL85@QVS(w(m2c-6c1z5jR~#C!RP$h|EPZ^fr<{F@=(4s*jb)vrZ@fWqb0 zWuJWjPuMxFD!U+mp%B+iO|jE@0Q*X1MO_-< zT^6$*?+gw4d^~$_D<&l5)PLvy|9N~f@GoEu5}r|mev96;#A;CTp=GjoHHh;uU#$nM zLDeN`3!lRpv`fIGv<41HiX3wyUe!f_N*TNGb56cMV?8gArS%Z1eTsbPT{Z~lvMGXPuJfWT{RZA@9h`-M=V$CoF~^KM1dYH?%uK| z$a5`xy!V;zTPF63@$lxP`S2si&-c3)BBdyV8hXkmrezc3O|Dh{ItSvt{kBdO0NGp&DsCyxR^f5I6|&Uh`nWh>Ca3 zxxCN05bu7@XtwdG2(aHrS8k($FNn9R%@^1@gudgLR$|JephGnwCy&2$MiWNJbBlBF ztM_WjZJmC{ML`-ZPG^(1RTc#w@A3DSvqpOu4{vRnk52^oF%NxI^?5Idnn$LHyu440 zciorihaaYrfln$YBwQ99#UuHkv()9V@I52K_H~Y`(t-uVtzlW4tV0iO$ zo|eMH`^$kBoJSzu7unBuQ#U6YzS|ck%1o z{7dI4Xo-$(>85w^^%gDHMPUW_cwZenX#FWs6xh<@*4a{wE8pYet=#)jvS@_y@V-p* zp+Jyd(X)mZrX@mX?;1xQ<{o0a)s`(gS#~EG$iL7#Grfd(K&p{E7-3nxb=KqEDMX)- z(9tHA4}U&yk;Fd(?K?yWF>`g~0Lf2du5{=fVG7jnAz)My5AT!3m2=EI2~Kl4K}ixdk5Q8UNHubQUBcpo{JH~gde6c|X0 z$uHeV$NaDVL2pC3<*dh>M6Zvns(y`*fA;^yX5c+1BR&PI-ooEX6!7rwH#>UJ2I6hQ zSF(kQckR$b*gDuj_PsYBYf6d$2GM(-m8SUufkz`zB^EE z-ae1e2~YeEGKN3n!c8Yp;6saJHo3m1x(FX{gNSd>YcDb$-qAE4x&--+sFWgNsedpkVIMl?e{1sblj_fBKi-z~`B-y(MTgvmBh=Mf(HVG? z&bt3|IWd=Xi98zuw)Hzy+Z)*O5Y@#Ya)=<@Dd1SsA9^%zsXW~C5fyytT)dQ)6<3UsABDxJHVc>ebSU!|>= zj?el7(r@zV^Wh)PBwTcudV6b<$p7H2G_6_j7OUQ?c9_fI;cfFpb^R`gcl+8mkyN~m z$G-(OLA*7;t>gP#7y(v$3Q8t=`hsWUFJDGm4WUv$U-xU~Qqbd9cBM(gIHUfr;u^1O zA zyaV}C^xi?dQ_4nvm|r5E|HG0Jn4T4qW_|Sz3!%?PdQe|ZhUk(1_W%E9%4XbO!5XyS ze`=62GPe0ER)bcA@v7m~pfhe(5sP3AQdjGhZih8!^{t+3!Eiu&ts^zB(mDbZnb|vy zc=&;Rx?=tFOomWytL_DJir^WfiPmC2iW6EZai!Vp82*5?zUY|o_G}SQO^aI=v-o^V zH~tx<6R)#_vMbqfkL>;5`X8{C<|Bq6zpES%6Ly>xK+pJPB(G|iAUra6fAs9}{|A?Ja6Ma4&3V%Gf^U9z3fBp=-$&FwBdByIO$vYK1yzgy# zA)yBG7BTB8e+ltUbiQuq1o5tL+;TD8J_7W|{J6nt$k8bT)*eL7)zgM!BF z{rYWfw-ef7Jz2Bw06yMEou#$`_e8)eT3mMcjb(1F_;~M;99gCIhVk&;K=a{Dkl*Nu z?h&Rh0_bCzC&6iNi1FTHld|{{#Jf1BCMlw>mhi6w>E|BtF;S;k|A-}hr_)EkMDgOk z`~UN1;LU!LtcX=_Nv6XbV(JXXlNQ2^cisGwh!hq!~h@8jlCUY`ae$>rOohw11b z)7F1raV)1+M#&w($6NcBw(>1`#=|?A=0lSpzsGBmc7BophG^QY+ZA#30E;84V$=49>+yjc}9e`0uF zSY)7#hqnv=uz)_qyET9%j*7Rg-CYwyh_`HSe3$yc2(YEx?`gpsU*O(U)F=S=-j+-E zzm2*E=l^1_gcYlu(J#4LpPi=go0GHJi?l9si-NDTxKvx;hEW52yd~~NE)&*eJiOCs zK70$O(OybX)5sieH2HPc;P$pA`mJ+*TpgoRlp50jZ9C?F;QxHin!3xoAEBL4NL2 zcg9YX@uO-5ewW3phzF!5^IwJS;^#oBlK#ug4mx&_oE)um>_TRL2T7+78QtXNqXmB+ zu?uJ5%~N64h~d3;bBiV(-u5@A!+9azevNDIyn=WeJ@ND14Dnu_S09qTIRdE1rdaGY z^#^gMc@0i)7(y%WOn%#Wmx3A=D3;oKIiWw7#)jAl;NxxDbn(Nh8^QpKGrm%KBkNzj z|EHi@a?rMr@$fdJ`B+Gh-~D&?6UHY5&^4EeuI=_B#(S51uS3?IbRcoF{J6a;}Cj+pC`=!4h20VqPHU3*$F+O{N3Qk zzuf;fkl3Dkw@DaaahHS^GG8>tuin0MNe3@JVm!QiX+As%^3#;p4%^VmkEVeakC?)V z@fPtvySl6-9kiIO{E^pAJRp&5I0ECVf6RKkN!IlFu-N~*;Mlc4)mwT7-duLdff(L; zC;Zj%@K(4uxLXq9eaVh8MBSWtx9QXcG8~Z3yQdYeFpdD@^4k6@Klp)17fSgj42RI+ z3cj$&68QeVn!m-EyA!(Vo&5WxLHrBSs<%J&rSu8|ZCadY|LN_o4Dj*ZaokVEX_)cw zuAup_A;|CL3r-y?IRTU$F7Fd`mKbm8mTwnXdrpHj`d`A{j}mWA_ywE$T+*|d_19a> z52DY9Q%o*%Ma&<(rDovGDgSF6!+XEw+NF4Sldd;T%0RrOcREH<@orn5BpL(p9#v)% z*#xWiLdT7tl8*ZUZGVIBLdNj?zsB|DMYkxZsnfD8bt6vbdb@Myx0m2ICk0Dv8aE#o z0s6GK--fzP7kKdJ|CO$SE+$#*4A*<-(R^qS@N)IIy>|7<#a98PFh^56W=Xp{c`o)4V=7tN?a!kt{^)Ecw| zUXYdpc98ID(DX({-oe&<-QRuw%$=|Xy;WFoeKB>3ovmhahh7B8zw!N@s$~FRGuT^q z2pvLg)|l~~XrQ2qF~|0#taL&>W9Kee&x>D!?jL_|@m5I~c+leRUT`#w3deuMPTkz2 z>`rF9M{G6C$0R|1Qd-X(s@C(Poe3>E$g8h}8=h>jT@TYAW`f8#QPkoU9rOPw_T4s_ zp|ih(OsCIB+qsk@A(#I=VijlLEmX*#gFRx8Uc0Z2hj&+i@3K*d_kQwtb_c}!xg+<| zDL5c?tTfeMzaAd36Gl3cRRh4;=N3_4bm0fmGrFZz>L_UM&FWwJN=|4g_Yb>J3VsLK z`n+im(;8uLn-;f1s%vz;IX>Rqe9V+@QjCXpGtI|ag8cN)1qwY86hMcc_a(m?BgVVF z&hli!;!N;u<(!dfapL)Zd5`mheBa4gk9XNS`h0ZkF4P|XJO3-pz*}(th!ckQe*RM{ z@$f#ne`xmv#Jhe^mmU>wd+7syB@plL>#UNPj3U7FiYy*K)&Nl06{Tgpb_lhvy6N$$ znu2Ee-QM_Wz7txVrR6Vn7awn?KB?nxtc5`(EpBX27Vj2$e7w`S`KR62Fdp7NdjI-J zCCD%R-GW0D3x1R*DC~4EiMWF_b^o9=|Sg}OPRa(3I)Hi-A_Px8xwSp+c8 z<^R6vnLoI$>(Oz0-4Lqj`ZVAMprC4oE);t?C$x8J(MV}AKHihPd8-$A3xjT2+{XBq z9Pj7jd>Zexo-2TGoHU${L& zJpX@ul>4DXYx}I9|E=isv8~bzE&F>pvD^&2`4_g|#PGg~pjvo%*Yh;BF;SPdgc3uk zcrW?V@aUDQhVD0Un-6VUBETsn!3VLa{vf9GfbDmE_?j7zjyKmKl&g) z>*NwYV!Z7PpIB6nWq~af`yUU^C!YV0$2bnwNqnF6c(IStN9Cz_pYOQ6WDUfdOV0STo^k|8oyXjI;cfuXisN3< zsy&1rek433{g{Hza}Emo-Q|c@%)M{(AORomC8HvBrTs#nk``AyTCo2;FFxL5CY~{^ zMU02HJk7^vg8XhiPruJL#D~^@^DrF>BgT6pC+JIrc%OCKTDXXw`9IG&s4t2%>j$K; zEA;tbb_M-ze^+mnXW%WSBgll|ec~8k!o%A%Xzc47i1+oxm^$j_#O3CNg46@j7HPcC zfkp&qG!cGQWjwrh(R>i)S0B_6TfU4REwJ@GpO;FExBQ~>tW0%TAjWa* zU^*T1fBQse=OK#StjD|Z3w=JU?;lJ|`uqJqr5SjO@+dH4cz@lOI0p~!g3N5B58{2$ zP~3@%_nZ9(GOQrpnKhZ_bJs)wl9=f7YrX-%tZLeqWz7((HQ2pltdW8`pEB6V`OOg> znyj9)=`23pDm^=oJrxrMgS5CZ^X3!l1o821i|`VX7-KxV6=^<*^1G{EE&cu|Kf1(b zYtGy}V!Y$R$!o%EVfA)wZfQ-TWB!k$Z1vkPGW+NMlXUt}PZXiPoX7!Z-EpQXB;L=w zeY|bFjl5;N`Ml?O6L^pC2Jr6Uwc$15UCpb)E5$3o%fd6k^PcB5&qJO{o*O*bJg0b~ zc!GJ{dF*&hdDMAic|>@~+~2uBa(8jJaMy4bb6?^<&3&9ZgxibTf!l&xpL;pCBDVxL z7uRpDQLY}Y=Ufe3rCfPjXSq&t6mjHoq;kY?9N_Tau;(!6Sj(ZwA^Io6*-x=Yu?Mrev)i$ovg@*|v&*uJu#?%ovwdXi zVryZmVJl|4#CDqPI9mvt7n=i{1)DzGayCUa2{ta)->jpoJ*>}J8(2$O^H|Tao@5PU z^<#Bm-NL$&RhxA&>wH!|RwkBlmVTCYmS&c6mI9VcmL!%4mLL{47F!k*mNhJDEHW%Y zENsk^%!ACG%#WF?xWc&nxLmllaBbw$=32}(pNo%+iF2H@pR=8_nX{a;fHRXbi8F#T zh|`VJmeYiD4W}BX45tt$8^>y7Kq`7?Tx~0n-W|Qzj)QNgiD$9&EvbM|VyU_G`xaH#ajI zlW3Etax0(50MdY|Cy#&MKYJ#WKrZereaJ3A0o#v z6)oMo9f`qI-5igN_nDWg$_7(}kl+V6RCP*Nryw_IABLSH5 zlG;0h_+!eWr~WPChpD}Hk~bp0m~ua|Yb)Y|sXc~yuMlrcxk;;3BVL%=HJW0Kcw)-6 zy4n))z?4f=SR1kzQ_i--I}mqFIcZv^A$u_8@a2^{;)bc6_ht4WyD?=SzbOLQg{d8T zzTZb&F=eMwIf}So%J%2cJ%}@=wmm(27jeRr&FOu$h$E)927bGSIACgvUi>7o6I0eA z>n9Lqd59$|7686S2e8=6$v(vK>?A`nmOpEvC%oJ&r-PVQSN0SS4bEDU%y# z`H-!cGLCqjhHSxdeblL>*HLd`>S#mSSqY=G!Pl4O8>xh^Zs0n4+$?BPy7pE>9v$FhyO> zK^9|*I{YHan4-=Kh!Uo#r}mIVn4%tXLKHDYJrjZ`V2Zkhj>uz*y5oq*VT$_hA0mq> z>Z?-7LQGNLEJ0*2MLmd*NMnk6ZW)on6!iunWC5nA7p@@lF-5(f0-1*?>g)W7B&Miu zKO=K7MZJd@k-!x7+EzpyQ`B275iv|rF9k$IY3k1%YKRD?s9!TegfT_^_zNP0DeAW} z5J5~)KP`X=V2XMZJHk&>%6ERMzeR3h>UN7h4{`%jC0P|BNFk<*y%i>q0!-an$F&Z* zj;SK9`NK#)rf$5<=SQw#sxVKw3CY7$fnTf`aurk8H-8*Nu3##kYhE*Q8B=)!MF6>k zsjIgg9g&Nex)LfsqDy*bmRi2 zvMjX3k@J|!lz(v&Iftq9KlbJ$XEAlI&UQYMfvK};hW1E0rZOD)N{};{N?#Ip9661t zGfZXQku*%DJ)~G7shCQ=plX4nU@FDWH3d0^sZ*>AvLB+`@; z^$XVsAEu}u1V(rP+zQ%A^{8n$oKL)bC(QK_N>VZ+qmr^bs2E2chFWrQOvn0lXdhzDWD)WFViR)h&t z{c5U($Q(?)W4$~FAz`YwDP4j*jj5gsPi)D*G1cvwbb|Z~Qxv0768R^l-g5MNl7C?8 zO}lds`8%dMFBvD3r!dtKRM$g9XhSn^j)wcUFDlst~9 z7YDtH$X_t^JW92X{F$bd?`lpsBSqNHo=G>Tdg!KVj<0v7L?N z5llU{UiFMTjHyRUoN~z@G4)_dZZCNVQ_Z#3A>=_!HKjG?kUwCm(Ivo<{2o*Hm+SeF z2QbyZa@c{~kEyzr-)G40FjbooG)?ZqRE_^l3b_|k)hn-zl6x>!#Tt-A?#5K*z}Ocu z1ydEd)~CsDF;(vGeumtIse6_cU&(JURmLA}L+-@XU6N`SxdT&oZZ+wXUt{Wa=vQv? zD@>JGwl-7It1MSg*)8%Ym!$j>oVxMS}+^0WWm|7WZ@ z_kYa>?*D7dSc9Z?HP{;D@TZMjcx#Z=y;++J;2LCNuTSk;xCXf*=!?M$cn9g{;{hUr z14qG^%L}XJoC85_PkF*>)gd(6C9#XtYQb6kJAc3cRY zp~V$HxxG(D7XKZjb#otvW@a$n8ss*b52F0M19v9Jz2ip>CnwJHbdM9B|9`mWuy>?X zF1XUt{vwTz@Bfif^-eF@a%k3Xkdl(<^KrY^Y*oO?KPO1lXW&h3(=oi)3(x1o!@E^n zb7?WeJEeWdm5TSGrG+XJaEV=J~j`nz9`CH)6c^T(4fT%{mvX*16y4eVOt3WII5xD2uK>ykh5caU7T z9w;xo&vk!b%e!Z@IhU_=R=~`lek>9beI<6SMQ=5tU}y9jEA>9&BrZ*{0uMIs>W#vpl{op?j|S`<9#DW z|JEoe2h?3O-p5~kpRk!Bt!_?*JhA|FL)H;Z$|)}A$aD@8MH*yQ zAt_m!Q7ZEk86s0M&t%M0rYIswkwk`MDwc`{N}7qvkZ?#8B^iGEXrK2wf4uwM=fB@M z->dhZp38Gz?{(k$JojGrUVE>-(`L!AB69xUV)0zIx1Heprcd1RORa#m;klg_3fSE{ z;pWfO&PraWi^d%s?uiVp#qQpXrYGa--RX~a6k5kqocwsL@4hKgAb>-h=~JozpEprB zyd(~J_EznDsWhh*KJQJ5@Ojy&9m99;)D+t4IQlN7#xDKe_y7LuyiIREL@u$Lsd^B3 zZ-ml=_Ab~>!0JJb>)S*Vksh>5$m(1da*1t`9qa5xF0m$Jq|JYF!(f*C6OF^mz2Jk| zUmj9ogJ5>&@CC%1~3s8r1B&abUBV1LpJkmoF3_dVQQ1QsN#~^5^HS3B@sV`TzI->(_n}ts@R6zcq`O-B@!@1aO}T^<0~WKOpUqQR5BUp95nvjO&8T zUSj@UD0Tb4B^`GRJHrTx{Cf2_IR1%)ds@zVu+LX8Pm31FgdgCqGV>>wIdi z{9w1rv%`8c@ZOE`uHlXdS^MBQ=I@2VTlVh$pHt~)7@qg{JG9jyCR4kINAVJw_a-Xd zclV(!hHc%G>FRN!TujMqJ)Ic;iIAI-X>B-kdbn zku$mC!;#Rr*IN{+c#|K;pzs#cF5$%DUG-sSRyM*rQkob@=B@ibZmAor$)PK+)??AMU%{cji{<6x)={$fX+Fa{>CH~@s<@)TQFZ*)f{cH9d z>*{DYoG9w~1GV%149}a1#yW0R*Cv(c%+3D_RJ_U07g2a8Zu95B;=L-1(=89-UA0C+ zl+0VfX6U>F!rOe3d-1xCFvxO4V9zRlPiXJ`$0kx{5JgI{`AnT(-`aMVwsvNf(e~HZh$uPtH8#Jyp{P?$O zGwdEzvUj^WX)FEppiHz5y!>2Qj=Jf8=K}-TzFB)Gf8eeNWoIIXv}f~SB-0zA&%O_E ztz7`_KFh0s_>sWH3a-yI|sD&FKrhAF(4SFkL_;+^v*;)@@``^*Kq>28Gg z^tBQBR|xNpv6LOXAqekE=Yw8OUNCOK9^3UR2EpFa`7KYTJAu*m^P%UstN`ID>0rtv zHt!xTsr%OLypR`-YtO9ikbQ^E+r2T;o>z_jcz2_9;N@pY(t}ICzN{i?_#_n|!Ab-sxisnq=OGyqa^H5Z?J5;w&q(!=UH=Y^9r0 zUNBGPWKEjrAZW9y&A$7y6R1Rlrfl0_1z6AKtP9GiJam|8nxZV0mi&B@pL;+|sj&QvW~mt?>T zpQCZ7gaq7=r(kbRu-qM9E%coJZf~Wdbu7Ti@1T!jVonnu7=3f+&VVmI?^i70E$VuC zu<_Gus9BR%M{#3EuZ(u1zYHQpPMmsfKN@!HprCE0SZ{~#@Xq@<9cApG8_9Zsvx&ABP zqx9EP80n0B_vRn$R@-`9HjffBxv*Lb#Gdtp1^b{|u6Ff8=^KVK#>E zLF>QLRtHDOx1!mExfSGgD&FK5k14!sbbc?#;@$Ci)c6R(+tF~g>NCRooZpmkI>P(L zq;d{PI1F}-n{po@&0pog^>foyWaNPLNf1(ExUy;ARDADT*uuO?G1y*hx40vjd{VJSHA>{ z@FTakDgz>yEban1=^r}v)RE1J3zGBg>#=!53E>l4j_|^xXq;bX!Oy5t?Cz~|Zso9h zF8%SQ)S-=&-wI~df!05~AbiSn{g+mJ-aEwaIsQ6Y2+I~_4fpHQ(7o4uz4}u*iQ#z% zOVUuGa~6ICkS)^ZeB5R0^w~K^QVx!_a>APqeZ@Z%h9sO z`-Wo}3@`2KVoLRb>z6fe&lVU2GImRqI2LpP^>WR=PfeDf;AibZiB#;nw~BR-q}Y)C z{}MDV?1J1*mQd`q_u;XiZ@cJl?@b=9124aF{meYpLO!r@WS>)1KR$2EJvTjrkiEC- zL)RxIH{jpBHIHl2+>J~r(TE57fp}!U6N3@R9IQb3T>yd75`37-&E@J%i|C#)0t7B8^RKCvN2c&mV@g^TI zN#Pyg7PAtIw_@Rn?FSLw3eH#R$(s|bUoU1UD9Ed=`}Ltmi6snH`d2I|zUmEKPH|q? zx)^!?KWw9-|B5bfL`7WSMzbZ@XtE;jqbN4-Gx<_>W`(>^0gb!iY1m_{fz7+D(l<=H zk^Xp7>L|v^Z;jcl>_=JrK%Hd2yV4tTn8NPcT zWfrBWjJr1}Zg1_R;!Qp=mBRadr@06gZ_)jPNIiu2TSe$d&3on{mx~>97;Kht z=MT+Ccx#>;X=5J*`^zFO7%uAqr8x)Hdvz>9{5F5Z-*VWC6Pe1z_7(EH5P1h-F3xF8 zOmXub?8Ql+yVX>w0sZl&)X{^JU!0Z8h2%s&5LsNHq!fYAd!@L_8K+A(;kO(8W{EfP z_uiP^y)%5!lgaSBnc8WqWB z0`a-nI;00#9;iRjk6dCOuM7==mJ#vTSIekk5vZ{!R2l2Ub;zmq_`b^hqU z_AYQGaR@GaZ2^KKo%LM)VBcbYWjZPQ?i3M*qj81%h7RuV#_mCGp;p#sbmv2Q`;EUr z>u|xzPwR0CkLdzlaBlCY%lg^xxX<%PSwB=>7E}U-uZW2~WT&AA^*$9-Gr7e0J&49S zyyXk4B+t#w|NE$TlMg|s@P6=(B#y;e#$zx^El@uJp&-3aw)rC%^mlm3NFBc)`B;4TqT)<6mO$3UlP@YnMP*v4=ti zd+~2?iI;ON`_i_E;dhXh&{#*>`LKw|zdJ~pRJ_Tj`crss)V;M1i}z2-H@DX#yq9-a zH})aCLt;%>3lQE<-fdym`x6RPADd;=3;MztBcDxT6C}WS@RNnk<}SecALlPnG@CPD%lceIha=&%$v?~5$sTo)4Pk9R3rM>2pf?LXdnLWJtyt5n&p6v84hILcvlE>xnyLZy)rxNq<0EXwSPGcQ8w$~p1 z@}66qs8jJKe|Lq#J9xMLS}fkRZ{O_Qg79vPh!P|7HrN+f4v@_Wp?>RifkUD2seQPk z-dP`*^isHT=?n?zS_x0hm+Jz7&z9#NH9@}KDsE(UISzaNSNoQ=$J3S+;oCY<~PUkjB>#PflXsBrBIqWHX<^-PYv_bP^J_IbOS|In~G z(f`dkN8=CUfB$co#yST0)#Z`y{crxKw`ugh1vo8r!fu1qJwJ!srmH7Bc)F!n9>HouO66h->G#9l<}XvN7d zJmvd7wkRSvoOkV@!U+ESA8QLdSay}cYhI5v?ib-dLCW+;t8}y7DaN1wr)jHW;pR8o z_x_&$e~5}V`BQ2X-s1~C%VP0XbI=GQBD`PL71R$PywgIhqwXQRODo;w_Ad*AyE+HQ zty6sAN3VO=>OPY|XI%H!D1$DLQ2AwBL%Rj=nm=^0avwHt(=Y3rD~pKG4~_FXNXy*VVdE2pZZ2y9R-_Hrw8Kac90HI@g{#8kiwgH$4wb5-m2r5jtd~Xe=hSmLFOIc z@e@3y|c(c@@7{0Itbmi>G_A zc^C4lok@I5ghVuszv|K1X%hAd(l0H#Xv&-Zc;7_p@WIJ%!M7^Sf(Jx!HQdP^2aVIytmf4 zOJni2eEd#-1;X2gcwdmr`(5Wda1`NfrBI@q%o_&x@v;i@*!e=qOZsC8gCuZ9YK(tu zUl&MAlABUvwgem#JAd0A!{$9v@xm>*hX}dRxO9nn3C|g9-d0VKxfd_eAMf929Y=8T zJHg$?>LSexVxEKsKOMv8JxdBZo${m(OSpt+k!Dk zfpfgIsCbjV-b&%EZKx@Q#ru6kt;H&YHydcY|95lZFK=P@Z9E$ZVNmP~_`LaqFXVY* z`lET61cnUycJ%E*p1ox|#(Vy}1z5nb=7&}y_TAgOUEf3eJcy7LjSC#&EYah^=55OQ z%cfb0{&-(U>oCH}uRyi`ZJPuy5I>PKu>U7M@1{j(9`-*jg?T4u`Kw<%z}>53l5K~? zkDQF(y=kq(-hP^V_x9iX|6k^9dixPF{~J*CAoBOCDLtrZ_rgtBJ!sj{14n+gAOq6A zM@@ssC01C(H149Dyjtugj*6 zK$8#>6EuR|gK}-Z7!?2_)Ij6ZTOIX-XR&+GsL^?gomZIYZvX!pTE{R>ejbMA3y$g% zK}h02@m&`DdyuikzwW80 z{vbPrxA>zL1uWi{lY15aAiT}ua@@(h?ehD@8W7$iuP%_B#zLXT=CP{=_P$U+P(eZO zB?(lCg^SO+bpd`w0iN6UEdYoA^YVvT*el5Sg&A7Whlp?q8h6oZuP9py_WZw@Y1uP1 zNPoOp&^k8Ze7B(P81i9UV>S+`Bm)NcMl8uOyWpL!y#r&38{3l46IDbx(EYlgE z_Y&IbC~HvmP5b+Liyjqk4Uyyjd3r1O*j0Hf-d3;LS(uO&-r z*%rpLhQSQ`B^e*$e4*inA49xvNnr4u&C5;4yMPO8_{GMT79ii0ug51BoA>9|%$~K@ zL`aE~n1H+?SFw5DC)E{ce4szxy=WcxaPs5Hhir|DctOk8*&{D$nEz$=$#x!_D1*0h z`7?hrHQ}xxz4-Lye#$Lo_zlto0&R8p*C%gP`TPFAE*0;+-=3VNbnl$!ZX2<97geji zU_p3GoKI~aZ%#av5MQp0+`Sz?1Gq&*!=Sj$5xA+^7xG>NK5yDc;QBY)WXEG&z&AHV z)1%JIECcigi($Kvvb40_K=P`cwwxX?$#;~5#k*Ra@zYZ1e zJvCp)DZIt6ZrgyxTW3(YVll#7&N<}-nfJZEQ~KrzZ|QMsPe^Wd$hGVOg)Hs&m_J$ow-MzN$4_DNPR=S2&x#^KFElP!B6VQU9Gf>+bD=?z z0R7GXDQF#>IQg-3Hs*wG<^{nHSDk&n;V(|&1s=P2AbW3l>vt8Atnk0yl0ENBThU&| z|MqqgGi`Nri8_Yph5S4JpWa6O|C$dn|C>_vAZ>3GK<+`ZJrcHNG3HEIJ&3SGq3i=P zAoVNGKl2soLGhtOk8jD!tNHJI7j0u03M;%$sMQ?sfqnZNY}4@AceHUnFA&(HBTrs92YMROE|x9x%p%2>R^hx!Wp5Z({Q8s7~e zyoc|9vs;SH|99o=n!_?ep}4&D<;Vu)2~xQxsY?$?Ag$FwGd{WtY-}{)EakBP`YK75 zmQmQei_U$v&)_3MT{P~l)ssSvd)T~ZiI3}a4Cs${30lV=ocwO}&%Y4&o&c^mjfK6E z#^)`*#I^Gm!kaX;x%FK01KjS-6dEgY^fZa#dDC3S8PeU=fA8KJQSsIy1=mt|TOW7W zjK!NzPp*6j;q5l_CxFcRMR6WSh^Vbb>45S&*a15(|kp$#?hAu!IWFR5bC3$|_9Z>4*K1g6)p zaYWwi0v@CGL*o@kz_%q2zP5bAUP0bDKD=3@g8;vxak($Tqx37VdytN{OWgMR^B}$b zdaKbo4&me%tSxkV{~IEhS^Kst}mY6C2^S$r~!X3ub+J6S>6ph&ZTR?*bZ96_=)~kAU%$%Qv*c6&uzYep7H?;^ z^1)_=_c=}9bTaQ|lUpSR5Z(fj_<|ieP2SjJhEmU!|(r>%Ftu zGb-M?9|XE6ye-eyGh^|NFa7-B6~a4QZ1qkuZz+9~GFODRprY|AzqO&TTd8W@`ybx$ zVfUt^rMF4IzTVr{@A>4 z-?~yQ_=o;@Uqb6B#mTS6S<0=cj0k@2c>6+L51+S>hqCokgm;$F;oKXS9^%gbOnQxb z+TQ>`AO8RvKgw0qFbl$|~4S&Ac zy6hVP2BUE)UX>Zk#j$xubgJ7Gu+!iCe-EuA6equV(OahTzY~C;h_~;io%p=ZSnv60 ziR`^~eqH#Oo2J;=;{ z@)4y6IhbiI!RkR4MnMIINDm?kSuY+%dXVD$FNv`-@@f;Gudc7E4Tdq9M^0R_@Pzwo z$CZ6kk#~?r!#W2VyTJEDheOI=ngh-|p}8xauzOJ3@9-z)tpvCPjSE?L^t@3vb`Scz zX=&MvC;eSwThThYaq`oY`5k`jI1v#1zr>%*!S6w~(MJwu#omUWGe7Q8UxPpYr{6AK zKI4$Z@I7c#8Eth0g&CTtoSK{ek5chIEMGf9;eDn+kR6LRU;T>Rr3i27%jzW~2=Bw6 zg;(YwyhS{XcH4akh9fI-%pwXsVeZ3@I_(S+_&O^kxVE7SY*Bn|FVtoZl!fgceb&R~ zt=Yluv$2f;mC(4lLs17+Phj(&G>D9Fi=aQ=8fYC8IQfnIex5 z{Ekld0+Z%IG`{D{t!&7Oi<8-HSasS`b zTdb&f8^6q`qVT?)eU}xBcf3H2!ySb81jm~BWZv!a2Vy4?-rpQzeAgZbffmt+;!<6_ z;QqV?rZZPapiT97(fO(_AmH7z^sL+wki>SmCfpC3cgwlm^(h|-FcFPA)~HqR+5wxl zQwqzK4|(**yBV#+0Vlsc!D|)Yb`Zgu*ZEV^iTJz^KAER;J>oW$&ghglRYt=BX;+wA zcFLb+{P{nJ#yXCD`N;A2@fJ%e-bSh34=B8k-40!Z#rxR>pM!Pe?#;0`kG%KBmV33H z4VnKFc;0RGa|(fr);33*=6k_)e+oQGuaUs~_?wQ*WnEy>_pl>t`4J%IlgSPK$JyJ* zz0EsAkiECHXxwTSkMQClY~I%g%4*`u=#RG(T1OsEevK*c}Lqa#SAwxBt%&f8EIZ??BaqtWCa} zQF>6W?RElI4-!c^%5@IuL5BqPy!?*zAeZe?ldF+StmLaVtD-o9;rZ#A{BK{~q3L(` z*1&M&h#k?Zon`&V`TsuhI&r_uz=@v`(}7Ibm)Q8(CuX092=F)>*Z5Aj_+&bE56bB9 zzP&`5{(4X%T1OgAe#{!)8()MFfoQ@?Ao&`<2gxQr%zAUQ91aC^FHFsDz`eyTqdQyW zxif;{d(gBFZFR^EN3l$vnj4Vpsd!r{=*}H)L4LeNR)dEJi?_e-)z=pg-e#B0JjuMn zvn~-75Z>mlBnx4gV7T#kNr8yG2iy%t_JlRYai5>I z!F(J=b}%C+cz^)4(YT#CFKx$yuz7#$lUt>}hyHlWp>+)5y$J7FL7}2tonUCm)@|z&<^iWi7xtbyO#*H{6}fp$oMP>5n(1jyE{@ zwLCq^;g~@L{5Ae{@9OZo_j*EMk;m?GXcE|RhOYsC|DS2?!UFCe91K7I(^|)d&GA{^ z|32PwjEeV>N2|Okyq(t-b7JxC`*`2^D#F|4(&Ibi&53zw(J4m|-WM(#2X>wehF6Dc zE(vvez%lQG*TWM?z$0lutNCpg__@}@+VG1x_+&DcYE_HPyX~9XflOp^LWvWspDcL2 z0h{+(GeP5R4)n*n6|Ex?C%+gH|KrF}B3PpJJkP!wpSO|y0%E61Ib6;W`5+)xI29yr11)&v_l;U9PHUMdr=a z=kmcF;ax;5G#SeXhRk7_OOLMbgi`PJzdo5v0uOBXoI6^&0LS5n?|!{E2hA%=zW1KR z=KY*UW$$C;_SRE04)V&#m-S;WPCjXjz8`R+Kin`&XnTw zzH>CsJR9MCMfj_I>LdKSw@lgl1k1&ob`N^U)O6_j z7!&5e_5bT{;s9F5eVqKFXCLn9<0XQqc{R^dSjI3{%9J|xn>k)Pc&;2?TvQ4A`x|iM znOc6iy4+7;{2ug_wmRYr*&dl+ox8+3Q}MPFmAyydy)I($QY_xAKR(V6LwFyWvfNAN zz3^9cKbbePo&F_$wUe+#nN)Ap>jv*GxYwKLfxO3D&Dpu zDf=kA2ee=EVeyWPx&J5<;VsMjW8eqE`|ZuPEu0AN5c804gPteh`4b`*Rg&(I?^{k_ ztPcqoI9EkkOm>0G%JJdSPs~8Ww+$Uv#ISiksP%5j|4D!k(72J~JzO#Z*u2FSW(2(F zra#_~&^lJ(7XvJz_}r zmO$eyDiUw8i(>O$y>!~))++kry#=j91Sh{Y^W7%I{t%J>?0Z(0bl~&O-(KhZT&5hl z#H!y>{)x|4I{5p&(!k&5@xQ^9X3yj_o3eUPq| zi0~fbwvi+A)(TVL<41VAG#p#0(t8rxJ!%w4FL8&4!x0~YgGpeOcx~;);Vw|S44O24 zGXvfB0wTVA*u4FJ_@B2LCBRNJF4adwAm$nN+WXfo$BQyD^v630t>XtyeigE_!;d!+ zL32RT*R5^%ydMozN3zP6!>}ze-JIDp%>P6D&KtHaXL#OBgS6FgYQ>8OFEjq_|5Ii) zy8aWH|2?RB(1{&&Vw4{AQBO)3s|Vfu9cg8Y^q_5WP5wWT9`u#7q<<@N28qy`291xO z1L38#y5xb6Rr@b$@g5ZMkh?ZyFuCR5D$?11TNI=Fl{6Ly;H@J8`HgQze z6zooMBprN<%{!7yFpqGW0QaJCGZS@FzXp6UZ{xU}JNn8^gZ_9&qjfmp#M{W?^A@_oF}=8~0)9TWWNI?70rU4lX|1obR_!`I$@niwr(L40j!vPmgd3OU z1|&Bs-cH>OpD4WlWHt$5@n*TQy5j`GJ3OSTb{ygTsl7MG4dLxV+;+}wM-U7O*l$oY z&kYV%yF>{cC4oh(Y`zu(-QYk%b$GdkDX@p1Lf^Jx^RASh+&X-Q03FddUBggz{+HOi z`H!retT&}U-gnSCh&cIuyxViTqJscFJX|d-D2C6wu%bqL`g!ev?Obaq^GxZCi z9ms&BKL2w5hoB&+%0J)a-WoSJu))Po=7TSE$Ov2FIt zuy~7nNU`@tcsKk}TtMdS2k)Dc@7@O8_+rsG6a-% zS!orrg7izh8|~^62uE|?SLx@v!iVWS+eLRHUy#<;Ub1s{H&_wuvh!}RDQG^kpuP7c z_9fOnP(JC?2m!XBar=Y)&-FaT?m-elvFfa9^w)zN(K^=QV;-+YsW%)7h4vVRcaeOUV@uV`c->{uV|eE*s&bY8x@vs8lw zO6RlxxvAO>%sX#gvW+qYcS;T4ysyUQz0GUs!VljG@Gcs6*{-yF>I^pThXG8lKkCpQ zZ-CZOkCUIew)24jZ339F+NXcY5TEz?OrpYNgtxTuF{z^W_&Z2U0eyA6_5TM3B!AlK zIKAnkX71kyq`j$lyL}9QN8x>Z@SZ3Z?>w*9Ta6Ijf+5SYej&VL|%@V`5xf@7woQQ7BF$Gf3dYv}bV)L$)PHhrE_Wz~P zIL-h+2kZZF{-3q3bk>Gr^vAmzt-}H*zdk0OcwY%3D9jj5*rb8a`$%>}%3AkI*krWo zMBWPgH%Ph09mh8w_hk41>EIY`b*Q+n?~Mtc>)u{eyj`=R|8sk5Mmc&V7H^jQ+d0e- z-XDLrZYA^9Ju<``ityGspg&++9|(E#e=}`Iy7z9?$uEy|NFZB_(i*`Z zrof}2!LPdsn|Gd0wNlnJ0eYcvw~|lIZm`Dg-bp9-2RodkKi>Ih9q~B%eHdAu!QxH; z4k>TD=WWO5eJw9Y^@dv|6np2X65D}4ATd3?<-~2hkl_a;rf0O(!EyU_6U?5Q|2?UA zyLfBur*!YT29_dNybG;@i!Bk}Z&z=APu`rM@E(-m9>3VD(evy=@< zK>bis!Ahxapip095sK`+J^xv5_=X*ucS;hIo?ILOzC_~=bCsIDvckT-)semGN1Y`7 z@jj2%(T0=X*a6Q-F&6^Z_vzH@5=DI8<2tXFyCQpU9(%oQa)0A*P6!^bxt&+w$MC#| zXskmkrGrx==->W7UC;fLP>F?50gOP)_Pw`c2ss^qc%n zVp@rP4{|o0D>+zz2#3(PYTv&2m2a^hu{(an`EEB0{q-P99S%78y;~tzxf6MU^qMwX znagSX9yIh^vOGGu0$OcoOqKPc;TF3}q{WD44#W2#rcJcfan7Ka$D(BJ5*tXx+jllW zn!-EyR-ZT)Z+-TNwJHd2FLS-I-w5xA@AF=(A-r3A=Gm=V5eRogr9Iex-xbEx2%mYm zkp$vyRyq40=>{i8_tk$#Hb|?8!mYH~+2$ynTWQcme}&^M~T|z9aPYh+au0EFb0kG1G^?f~*f;5H?`Q&hP`0 zZ2)a`*nNm1ehr`F9YDp~r~P6Lg|~v-gLPQEJ^Dm$s3E+C8-&i1c?a>yN$MlKH}94- z?%x;)Nvn%awcK)r2GhnH&6JR@w>C`2%^G!s)iZ;pCdZK5TP{s6X85srx4b>3L_|Js zS&PQCYBmW*oxSs75znuPfzeMXW#K~`mi<)Xe4H1y?b*#SntPIbaX^6%;NG@j-|L*_$Q}OmLEt~s5I(c(qSxJ-_7Vp<*=c(={ z4@g2sHjsI*wfM5?1j0K(#aXIBD-a3;(Fldht}y7axaYU6B;Z`quIZ`M4eV`|QtWKl4@mPK4*Fn(Y>+ymak5h3#4Wjjm`^D=2{p~iNz)&1ezXodocvyvz1?XM zO9V0TY>L&6_`I91eSC9gsuDivwr1aX{VC?}g|Y@^vaKFFV(|{`l^NGSc$+9SKP7KYyls_dNkn)Tr1Y1?n*~DSgb54b ztFF*y@DFpG8VU4%>u7(ouNxR&tva2ddKiH0?F(0Z!|vWHhvwOiBk$gBN8=VGWNPYL zWAh&Cl&c?5qCeiMXdR2)eO=oA6y&O0)jeFvX6yI<8KOP>mOn;qV@Rm0~U zY?{sN%T&wwytQeoyB4!BEnEK?$4p!XD?)9^Iq)v+|IR;{&+7z>zId=-$hfFv_pnO@OiR%>i8{u z-q)4xZ>U3fJ104A%P6kLT|qLjb15lQFJ|}^Boil%b%b1OlAoLZ&oWW*4osNGO6lGg z>V2fKcvt_rmn4hu7Vaw&BJ);x9c0gk@K%?|FI+Yf0PmhzAW;3m74p|x>XfcU9&a&O zd2Fp)Hz+CH{hg)J1e9s23FJP;=KX0yQQ@i$L|Bc+JzcNNp__@#+n2YEHE)3acz;Ce zaL36noJ%ZDZUqs<8DCvfa221oS%|Ms?CT2XqHLh7dm4X(^mXouyB`(V8NPd0UZSlI z@m{?(5ohM^-kzl59bk3LnZlb%Z=VzvZ{=OS1bKva--JRHdGD?LFkinY!h4sZ_AB$L z04Q<8_VK&7u2AF0k9v1JF##e=r*>@2!{*Jbd?+Ax6%npM z<3wcMemJ9x&AajUk}-v!^v8Q1T1P!jehOdBzsp)7PjAV|cm2AE&->g@mJoY{x91n> ztl1eF-rn+ie|8@0QikWvTf0DPQxpy%)*H~7m*(&NlL5@@P; zUo&yF8_0_?9jj43y;{hvbM5>fJ@O#kEOVtps=t^i@)!e$SpN1VIZbyDMyFteP z#LiLL>R>YxTBbVpfwZ%WsCY*V^r}*LKWlDLz~U{@*vY|#@Rk$0(>0Coma`ojGDLXq zwQQPyJ2n7nRV8N^?R0~iE`0wjxsU|zEjTS5nb{52Z5mm-a=-|vZy}t0}yDeQwHQ@g6o7 zupuJ6$9ug3$-E1X9yBN4y=CXutpRZX&_dd_t4-bw-YPnIp@j{(z4bWt%feLT4N~XR zHm?^L13sRe^Q8}C^S&auT~Y5n0aD`RgdTJECSvpcc3UKS#Gd|mQ|cJR$!~#g_WI`p z0?pZEP{|7Jmix6=DR?o>yq!7GCXgl@EF?a_yS}l{?7jksCb9P zhW@8}*D<+o#NsVka^}HOg!fR2%rY|XYkCQv?GfJlxB5R@ofH7SrzigWB;p3Q80YS_ z=OTe5zwbv=61#yT%R_COBx6wiI`dD=3^s4`3d3b9Ith>xcXEGF$pRhh0V!lOSbaAeGvrzF4)jM5H>E55qRX1Sq_UbGF%MspLOrB-ry|?J2_9{*Y?+GcT zgpS+*m{K>i@!6Csd@n1*xrmnpLgfV|mc@1hiLGUl$4pE>yxG+7#9i$9U+RF7a_@d3 zOhDrf4F>Z45XRpB@0*R2R|ufL`JYlp7fybo{m1x!FCqe`ZEX2m_wacSbT=$dLH6Ea zi+3_tl;HC&dsVv3I^_Vv^LC)I4&K2MpoV;V```SJHQmzD&yo3`gQ^Fe;YklB_aHgs z5xcO&!%SE`D5`(!sqyCpYBEyk+nDBkS39`0|78Yp28l+!%!<*304UwWY~GgZ21$Wo z!7E7vfGfg<*|z~XK`N?DX;HipurR$QAMA>KiDlRS{q@0aBBaEzwy)0My@-8@Eo%+? zy^N3kF0l*II!bWz(}|npxU0hh%!5L;UXA1TpoceSKfQ0RgdGP$f1GQ>ACQ=iiOPTb zs>tv?h{=YwI>Zkz`K3Phg7n!XRJ>!6qbVtu*s{-$w_x$kTF_el8{w@sz}hy8Tw*_` zXfJw<@Q!2EPceuOfVnrnpD0LhgU9?<1hotgfVhPVxMpj+K}aloqnmF8cy8Hj*zJkU zd&c5k?rr4p7A`bSdzIL81%GVblgvh&UMkZc?@6?dUpV;{7xw9lUEl%tHl8@aGK$aJ zyS2E*oTmyJOx70(jN|VhY4WT*+GUZ!@Vsj|X{&?ipB5{WHMfFfr{Wz`vd)ddJJT*z z8H;!8ft!QV2=AKcN)IycX%TIeS%i0>2}|uBWd2_zIM3YD(+z$xF=#mRV*os`N;WuA z*$tkpS6p}Mr4h*8r|~i*2Aj8K%D$#O2=6OsT($4#!?mv1ye0PAs@}1nKi=kO9cys% z14`E)JAdH;x0al3aTvzu?GU*C^-hHMvm)cyn#nZG|D2T~UZgaJ=gqW)#yUzm*NXj} z|JkT`M|-aU6yDkKM>b>e{%P}Z9Wyc@@hezzlX>ss)hB2m1Coc1*vk0`?_l$5Y|A3DKzVj;r&Ku%pgdGC$F zTR?Tz$T>Oy2EUq>^fYmUNm@E^cxnJhO`prKyU`66m`|;~+GYgOd~eirgkpDZLC5*E zmyykhR5Z@Sv8H!)BX;+;)XTZ=F)>Yddv5}09fxu9YmiXRcabN6(RW>{r#|8HUfQ;~ zWGAxs);8=D#k3B8{&$v{UGTxFli_)H7}8cpeb4aPZBhT`e>$4-u~R|je*#qxI=jf- zf!u@0^S_Ol&O)pnBw-nC(uu4fr{41IU`FQu;gvgB4UrY(gvt|f?Z^PQUCm44_KX|s zKXC8rla~WPKx;+Nsorj28I>nmC1nVv10Db5s9Ry~|A$Vx$hGzm;3OJ%`hG2|{eA2m zB=7kTG(MC~(OnM;K??I$$-Kqi31pfgykk6NUzQ;&NcC422Zx8;;I)FChnIB>fE^;5 znGajL!GraJBO!W*Kyjt=TJVls;GzNTcI zP2PK3tr+px7vWucHJFR#Yyi9-=Czho=?2y9j&3^9I{;#@owFTnLf*Y)xo_eeVFXqm zPu6^W3VZ&y*z-ImZ!ZywqH*uv*QojRVDt8qmX|L5PJg^j(K@_v@{2UnH9NhG0LF!+ z4+;Fn=e@cp<4X#%_qHc4^VbF;{Q3X%RHyMHW*LU>-sO|D)$y`O_=pK|_V&O1f9$cF zZvG82|1YKLL21m@lawAL#HO(Xs|V@w=X*XydQeUMRcRKa2bmhIm#aZ~kWTUbc6PA< z=n!=$x_unkAgy6B-hXERgt3Zs_$=rFt82Fn=^Zlwqrd%LUv0F+od4~1s~J}g6W|CM zH?VAJacUFx3R2ZVrD$Ry{jDIa&^lCb^5Zkw5hvl!4N8^{M8Dz3UqN>ChI`l?uYy+$ z)jv(su>T)C$jx4{dJDt%Af|rW>hKiR=g=>myTtNS@jm~wbM6b$qLQLb^AXiT&afD5Nqw))m$^WJ!U{Vrz`0j8mG@zS2@HxjUU%M_;SepyR@yrt1Pq;T>Ze@lEy zxWx_Z7RS|n<-_M~WoqN=v#|==J>UIm@EiX8|2ApN|4%#P&;M=-wAE4mC&TE&+!v(I z@=@_VcS&yU1SvA_#4r7ev3M6&Djj%@@ct6wJ@m&r7Of)_C%@!*06ZM$2E=>2*9i*X^Db+0I0+EmBd$>m2DHropZT3~ z`SKaRdw0`VNBZdFRe$GyUMk)xZZ;{D#mN@#YE~@XyaWf8R)qKW8WA=!@4Jiat_2{x z?>d<)C>{%dDrr(OW%JzOk<};0eV+_~1xZ%~wtVjfA}J;Hdu9y)S{!SG4|U%W?YS&4t!Mz{zi!qwBj($mYbx)BGp2XyC1zAihks zp%QL4S237+L&N+Zv-v>xe3}0P^FM8Mw1j&-9Qu2D3z3R8Z<07J z*@5sTEe*&g@4Y3p{$$ldcsq0@-PS?&-hx9bZn(0zLw(l3ZlUG@5OuXNZeXw*M4$Ff zTq|t|E_d1ftaHHTJ!b#YC%vBlFQIW;=bc<&w;X%^U(jFoVDLQs@g7F&V8+QW-d}se z)o>o5xj&};8x4z-&GN=-0%?_SP4a`!+{^Lj|D(#s*k&hW8NPcz-AY>>UlL)busf++z5L?)Lv9(K`0vRyU2Sb_|fBvVnj_8v+{1`yuwR#n-YJm3$%#%=jv_|px>f4d&^{n`Mid==vxFVX|v z960lerCJ~SxSnWyWDhp)JA*o_ea4a7TWFk;Ma%5dY;4{dMX%?Vc+ns4O0*tK;C<UDyVk|Je#6n{@3z%dsS?BmEkY3PyA@BBWID2#l62P zNI@#z8Rs?3DZKMWKXGC4{*WzSS%>iE>uEJ1^M02X7toFH9@$)|RTkk77p;9_+=p~; zSNAp1&kF{?$zuU)7cT1o?e0}xB`@>=&#DpAH|p5DJ^90YZ;uinCmQ#9QT?ZF0oc5Q zj9v@>IZuDQUC}!Haq?3>BD#2KB{yh)9I)#v4ZKIw*&?D4-WTV4W(m?V|L;GdbgJn8 z!2C~Z9aE`hqJQWAWmLS=ExB(~co$Y&=fvX8xASmTJ;M9S+mmDD%?UI9#geTE@4X|> z&CWmahfWCxUhEx19!~U;FS$`N09a)r_W2QdK;0cv!z>j8kbH&^5b_+GcXeM=g(ULz z*0X5beU3xR>%_4Kq$LxIXH_8m@xG1L!G@Ec$B;v`D$>3AJ-eT33gItKINK9f$R4VK zr?xXU9HeFbuN(I3x%huz{;#F2j+xv?A4`+w7AFE!yf4U{j-l{w*yhWD#XElQhSQG` z-tuw5ab(_~e$Ky7emU`ocmY9cX#jLFI~pN0>IQY^e+vvN9{_wI!>2~rdqBopn~H}iL}-6Ai;IRqS$})|Nk1h z>E_=d^S>xn54!q&@g+(Rx@WE`fYpNtGS@?LkRGIX{j4f0(u3}3m~lNqdXS)VFaLsC zU-?|8GU>h{MT`?RA47XF3lER?jt*6UXmC8R{K*=7Voo`BPQ1o z-me$Td$kDRz2n)2@n(egdZ_v~=eIBX9CwGuqsk2m&N#(9j~@VP;+v(PgB~E-IguZ) zs}F8uZM{FNi+zc8SaG_$ijN5M&^Vin*!#Sx*t|D~KdYJdf&O^gp>-(YR|roR|D z-h$ZPIO<0O?=5Y|ofXO}Vdr|WRMQ8K@NaKT@bw&6Q^)wcX{>|WnB&UszpuB5Q1Q-= z2)IDueX6B}4~uuX#!Zz%gm(^?&M`9Ybyr@lCl5%kpQf+45By+rGwDosqZ_>QDO2up z@&I_WCF!({at}CsShFO`P9HG!Df(FckGr=ep4W?~*obiY%ilPj&cLJ7$FO;8wKjfj z`$>Pii_khWaPm9A(Weoczyo;u;?~Ma;&*RozV{BKG=C5V= z4bo~F>u~$fD#`ly_LeXe@5?$$%P739Sh9GrcsI>%lqo@YXBB^(ByUcva>%mmL3nq5 z6m4C7)(>)-cg5I$M2@$xQ0R0?8vyBPXIm#X_JE|$rN5q?(gz~iZPDfC*xma?wUO^P zCL&yp#vQk)+Lxn+&0F?U)od$){str`v<^v}{B+tj6a~EC0czeFR}$9Z^UgeS=i4@f zH-GGw>Q@kdbAl;rZ>g5sYKG^{luctDi+){6b>Jg^oM;6V?<}!5aTMNCZZ1SD-pgJX zti6r!j#PDuBlGqQio7_A@b>V&7+UXlQ=6M4A40v!iuz;pBJD^3OsQ zb{-&njQIN@4R>!}CWW|iA$xC5zQ5!nSK#meKmPOo*t_$1s=D@Z{71$zoMQ?hgp?^6 zN+k=)oFNp7D09ddN`|5$LrN+`At^;k88R(J1EnYxDk+B$MWtx++eiC6pY!{?zWdqd z{_mX6>wf;}x!uXC3T+q(2uY|2zLP%#8ov53#X^3(_bzNQFa}FU0CWC1-A*IEM6~8D2|=c}NecbE`Oe66rxNmzMj8AB}*k z@AO4)M!ti@QpYU>1`mVD3bhg~&wkLdXx*}Mc6*>4C6T{55W5F;C-92()(XOIHH1VvFGJ) zBFp3VAnC-NhdmcuX8IoFn?PS3(*ql)H|@`$JYwZ(co$c?xltdn>kt2uz~cQvTFfyM z;ca$*`omm=_qy~f>jH!~*G@yj{O1vHPJsRJcAjA9!sX6U96k&p&dbkl+|~~sM*6H? zC29`}_2(}*;)~6Dd!&MjLAf9-K;v$_PM0b@jLmy*?(UkV3C82?iq;Wv8AR}tQ)HCuSR6(iw|)aCUe=E2ae z{!nmQ)G(0DJonVhu^(*jno~ZcZ4dmvy{RAAi_QCrM7ZqnVnOJG#*tfFT}MN(dEa~Z z>iq_O##=#_pmj9kB9XyaervNXIe7%lRl@)qhnx&VuJ^0&ReauMF$YF7j(ynnI%SlEd0 z&J2G#$1^Pww%ri29>@rWx$+T$E^)))ZqQ5CiH-fBb=QjD-0sNjt;XBeopZ5ybGmL( z4$l{apU}AJr}VZqIQePzP05B1^Mi+@i{`hh;q(5oZcI`I z;a$OY(=WJ|j>8F?6Tm1ekLh2KMzE%{j=qyd3V*M+ETZ9EB+|8)%6q|54>2s>MRT>w z@)6!spT#aw&fciJkA7%a{x~TTerZvt(8xv>Cju@mB;?b$8jx4)J|~Ok zDt+G#gKmbibe06dh38b<3!H|**~LX)Y7+W^ldqSGxv?G4_PzIf_bcoklq}j}d#hIv zYN2s_S6+Ho)nY$llZX4?ELLH>9+ZgIk%W_9k^;NDN*F(|HwMHx()c}Sx83@wVU}um z?X-^$RKQFMqeE>Ik)@a+1UX}k%srxOEN7~-Y-oi7h&;!pAst? zkMOR4#lb=09kk=uw_t>Kvi;j5`%J^3JF8aPo%ew-u-8}Hd)qMBpCY6mAJY$(?seuJ zceMj+R^GU8OUC9cS#~|{P`4n|M&nYuS%)1nv3b|*J2q@+!+5+GpmkK^^yFdlC%v<@kp{LcIR-kuwc+}^qz$~CkWpSRwNPN%DDtKnhkW80)I;P2iNsw-Ho zmI*NZ{7-KkifnmV@yfH^dkGEiQk&5cD(@`i3~4Oh4^_t%jv%~QT$N z|NiZqH+-cdV1$QO{?>g#Ffr}AL$~)Z*s-l3Nj0P&)AQ91WXAUe6SJ{-_s+0- z2qWD)1C1L#$ad{kAU5ykZ?#TH7Be32S7;rbIQg-5f4JdmEdbo}l^<5?;PZ}lUwqFN zdA-Hj!ldUr&a`6w+EdrS-o0k-?ZwPLAceoAuMWsIMjo!8J)BUW;a$Qb*-GVIamPst zi+ARmgT1K;?{{-#n<-~+gkQQTsR-}s6RPptb`ek@QY2UALJ+k0@!`r7|6x$XHd=kz zuOB?-mpt6`%?{*{pAYox!R9^V{Y3eEiy+KG)^x5 z@Ak%~PO)%)aNwat$Tm8)^ ze-?zx(YW;oXC9tEh~0y_$KLIl37TfO`~N{`9WQY5+p?B_?8S0^khERUDCGwJJ4nA> zBH57ntKiRirCs@=_%}!i%eQ=V;$r?UNTauodr?PyKHQpJK`x`=U6EfupUPWbcz6jG z@5n!d;1Gm&`>#O`3hzbt>(-JG-Zil+R>d`h!6lLQiRW{6!RmRPk2y?+K__3$s^_`= z;QC}|F+157vy`b#_oJ-~~{eYxJXB{g(ZnhFU zIm=s>hWCwK3g4)_O;Rfruz26RSeUyT;eF}o`$ArXx1`MEmIVm!6cvf|Y0_>u-F1jd zkt-0I`+XWXV}bDYJo$d`WIy0`k132|w*x84Dw|YaVDonPDz=MnOb{MHptFm+Z_cMLNDgYWRcpJ~8_$_*L?JT(1cJ2@=60 z?$*W&1g7UrcO6RUN6_#8Q=#E~eI3s_D(@1lLyNI^*B2PwjzoC-iF+7QcrQqibX7oj z&$CWBBNw_G_K67`i?RrW_P;MFuCf^hIU2#f6Y2fH_=b9bd4wJKIJJFwQylhyRBas+ zNJe;%qH#fHZhJIrVle02Kek8Dog8C4-Z#)Xe&gi#R(B>UE{Y%UJkYux#D_oskKSA- zxjmx_7H%ol&sd5-{}VKaH#APqXa3#W<@D8YSLdR|*^9H?TbYJ;InTl|DsPgtojexr zNbel^eF*Om4)vFm!wH^C)5VU5*4ID0FquggER?g8enJ$3H0ofA5_fRMrTyqgI0)v@=w_0dQF zzWhu{N5C==ev9u5Ng%Kdu#f^;Eb>? zN4_nnYCrhI<_cJS3?I ze&Ffynp+Rx^UhdpMp7)QgmosJuPVOb4@iN37UW#z9ASFi?sV4iq))~m=TznB~V`{d5- z?9v(r4TWvI8WqULTPle$dmkaYw;#_-ijQOS=5cVyIpZq?m!ok9&vC3B_%Gf2;XT`D zAvui4dmdUxD^7k-!c_aBZu0}p;4;?$M||Gao;qCq2yavQGO^KYI=XkPbb0uzDCWN) z9ZzQ+3J0#p{q5fBG`w$We%nFiUDFw*jKw>-+mYmp@D@|xSE1#7;ugR2mU&@Nf#u^R zv&;ZE$3xo4Y4tFOZOSb5zuFHJ?2i{1T(bp^E%MiSpJDSp^Of|v`IjKvjK-~DW64pH z!S3G4n?JU(sWKk#9JG!koc!F@Mvnem!w&|!>uwFE;q!iEy<RslTD}W{WdY!s6ZW{ELD=!uwsG`vc11 zL`ppWBmvppdbGdD`|#Q@cts|A?d5j?ut{BM|CsJDART`6F{QX4z|O_rIqGeJ(`Uuc ztL|d+KIu9o_*QbYSn^PSu^QbK1aoyfe@`zTxEOx+kE>eg?U{b-`Hp zPZ2(Et)a4WXOOcu&CIZ$*Vg0T-ilj%guQD2F{bBzp3XX~p6~iunDp=G{~3GmN3%ob z|J5`-=yq*=4Ydb(&gEQz)q~!O?8x7U^q@4BBl8829;CBFM_wE0L6c?E>GSS|K%Nhe zH*awEg+;fczj%ub1GC-IH$J`W2X+I`XYw32f>h0|!8^aWK&-!`GUL!i+|LAIG8#A5 z3Ixn`uzQe^d~f60ith|}{!gs~FTZo^T!<6O{D5U&{2_glFSzqO_wvwRY)dNO&*a+& zCvxdnL7o-cv3jvA)At}kKAm;^{!**+cLlkMhWD-1?K)K68oceASiH~0KS{7hc%O)N zyUCC6&Tu}yPaNSrCpY!W>klDNFZfRGaJMfcp6lw#6(0slg1<_0o+B&Bz+RWwpp8KD znYGp)_HCHFqaQ9Ib-omYYG~ZUql0zq^Ramw^1_RSWX9u7tz#Wde$IoJTI}AFzy^I$ zTkj}*-lQAu?SfA#pk5tU6o)VV{6Doo>6B;dY3AoGL0=u)GAl|&kI$|kwP|=addEvq zdBg+z|}xt_x3y)(%2u`$BCM8&{8qO}RP+Y_E>%jI4=$^5+O zt>gH@M8&_|dnFBTxJV$A%3F*zKpl&>D_^+d7KHZ=%^4O7?+%MQmiG|e!cQ;8E$|J6 z$GXz92mSouE_b;F(sIK<+jQ=mM-TdeK-Y7zBuiWH{8{g=MFrRc5}W(RcRmh6uoI0F z+OBbar~-TbujQPsD|pFxyjjsY@bWXW&Av)NE+<|%RMdO32cNg&Rzkhsib^P75OX5$ z5B}{f!W;9v@i{!q&zsIVBz`2578cER?-ew>>%aJ)qVhJ-&{>YfJ4Z8Wg$u&Fr{>9d z%Gq1w_5B&`2yYgd)|u6bq3~n9%~Z<^KiK`U-)!HKVK9=^bXor{^64$V+g(?7*n-ub zuk#k4!{*&?^>$O2lMvKK;}jzM1H@vnd6y;o3vh5U-u(X~DTzcZ2!CI;oHK zAAjNV_Me4OlOONHI_vf?Brqo{GSSWIGwzCz-25VGT8#_zp;YC+D@a`$-uHGp)Ked^rTuqSWAT1Xc=6R3 z;r)T@Lj;94`}4A?0|@WY?XT~c3WdP&O%8TfLcC$*!WceI&S3yp^Yk;v`vK=&-|&u) zHejXD`U`W?u(!8PC%h|?t`LMP(6}d4E3h#dT%6Pmp(K_bho$G(9l0NhU2dmo9TE30IykbW8U>!E^-T7`=Hc$|nqH#P&`aEq)v3bjHf~Sc~ z7;k$k6suoam5@tUjtwY26j-bqc-v7t9a)&k+Z@#Mf9~KC2w#oyKD2Ee2!UqGl zA-lIG-MtEV$susw;x$S8kNH5j*QiX1I1F0OS!!+?><7fB$Ooe}HUge#-JgCxv3Wmq zt8-h}CJ5)DacY$wZRuCBdDq>NGpTfCJl+q`I_h!qn|X24L#d1e`t-{)vS#pkgZTdY z#t3hn+0c)zP7?FIxQf+gsMq@NW7bWJm4ZC6AV`#NzE2 zA#>jf;VoeHC78lHF(y*c65(y*A)S5hLI|`}ex_+Q;R7e{ZwW9F90oles_~28_Jg#< zo4cnCHUfFo7q|9(z~&wMPQ2@JyC9TB<4i|(R_*o0=B-s}lKCx>@p#9eb>QVkJ}13L zXN&~&_4_$g6!7PN7S;g&5`_wQ=0nfI@p1gaiLI5!u^$hLGX3Jju$sO)a&LE^SsM25 z{LfHxK2|cw{BKCpgB~^BIZmDbcdrcL!0JJU>mqNhLVD2JXY;lRBR#0_((jTe#gOaOZzB zgRehy<*&o98CL#JPvd{Y?!ere7cQ zw1^#xHz|LWunxl8-N%xT!aH-IWu6McyW5@1;H`TQ)ZW?|x>>;k>WzrX)P5NP$-FM< zja+2FrIT3UGH4A>ZWB&zvBTy~oGZ}Q$d9~13XLoOa5>WQEH-Z&@_5?UaK_`!gVwPL zC%=s?#Xs}7N#Jv&P@sAuK5yR*NjaVf@1h+873^&I0}>(di$bI9O{V8f2&S)&`x)9N zdV*$8kPK*eKeWmbr1BQl{>6&L+ehT2moCCPz`?pf2;sf?PW!%12=A27`z{k|gP^AT zn{TR39x(Nu|F>P=hd_B-xP&wt8K^j~AVvPR1`p;po2~Z1<}Lj&Sa`1#@_Gw2E-p5< zqUgW8Af0viWa!*WjK^CNt%D0EKbbpTb7Ya-+pSL~`!et0^ZxNxPvm3Bb=aED?K?LN zpZA42|G29L%b9-u2MzSq@k}K8!}m2ODBs?qPs96xT@5>xclHfdOy0vE$F}Mry!~G_ z?WOR3bo+s2GQxZAQ?7(R(!o$OIr30ngeSbd{~+&)A48yK(H!D(0vYuE+P9Zg*#;11 zzV`V&!sadR@m@1jR}lXB^EWPDV_C4?b?ok~HoE&<+!*8W7DemO#L4fuy4l*VS|m^} zaW>`HI6m*!CGDlBL$5=U)D+Kn8y&m16*2EL2UVG#H{m9Ibu^L>pKgy$rtsFI;ob5o zPmRjk#VeHst9yriez$lX!rNhv=t2r_Dbc7-R%G|qwN!%bdP6X*F1qvSMZOnQAKP(o z?#vKKI%&|A{R8=WOM4Fc(qlHjPxSfg)~ncOZx8Y#)MfZ*h&T0;!S&?wg8rrm5g>Zynzs8h;%*dpqy(nqV=3KmQ*a`P^K) zM}+AYC(@(z)v=PN{ku-azwr?m{Nx53{v^g4^$r1VgEN($vScu`=cA0D zmo-SA*K2j|#1_o?Kj-H*RXssLn1aTcFYDd9ZwUJlySF_h(7NF(!_EI$XdN*)`57!f zl{jw?3G|u=1&p2jgggJQyr%WlwyO+AT%FlFRY%7S(vGYzvZ2yU--8JB)^Yblq3YlB ze-j$sPrbB1QF%Mx5aY(;{rK~w^>T!_OSMZXg?Db!i-(~I@1DvqH&Ojvuv|c??taR4 zNYI^9x%hSn++Ox(YK0UTY`yf>Xn(#nm>D=(`gT3`3eqjQaE`TtApC*GeR=fqd2%H7 zBX)56^ku`ZjK|vrtz!fyzg53P_9iYTfm`KLyygbuxV$CA2gb!WT!VcP1SyGbI!=)0 zBxEGF6*E6?R{H7?8Ay9`5BZ86q~;Kq#^2#P(grJK$;dLLPyEA&_UjU-RbzGT6|xCQPcq8uamYjK125 z&HM1EEIDh9Abg3&JxFd7srSL=ePo>YvQe4w2BZYEjx?P7SY(Gz~{E&INTP!~B z74z8Vg=>_<+mh}}7Ej@?AnU(^W1UItOg|tEP10A#3$;svArc2Dyp3phcaZ$vQ+aRW zY2w1-&Hd-2lNQ4JnAO=|v%9yiUa?Ogyki1AdnR55!jWsna*cBCuyj*_%;BLS(Azt* z>dJgFP)(@Fi5Rd3?Q46t>epfO-r}G#;bbcaAEI$*`!4Tn`7bXgelPR9(%qNwcsrnV zjNs&F)WzR$s+$0Tkml;ZRL?jg130>azneN)DmB0g_I)5UD-wv)_%{@+Yz9k0gh zzx`dDtf%4q_|cy-D(~8p2RN~KCni5VuoB_j>!4do%R6r*%ANgXAT&Jure&FuJJjIb zXW=}GEKU@U-yG#9gO=W;nLiJ#fkOV4{CoScd0%c>p7w280Lr0pkm>2Fw_5u>Ohq%wVRb6kBHaf3-CKh2hO=G@JOj=hZ1Kqd{r7*2_BVh$Vl8QUP*1Y)U1|@C zWdj0OJ*YUyS8_4ZgNkj&R78;#q~zgBXI^BBU9CZ}yg$bqHfNdXymj6Ry$TYaWjz`K z9~OrGu3bR}!4FTRSdLl&SI>wfeIxAoe{S5!C})WP+=|9^1uA8e&SLkVrKufahp&BM zxcQ$8twRYXKf9EB_Pe){z}<+!wZf~$a0etGcl$O0+bgibQE3miJpO%#;4MFVreg>Q>3wwJ&>(}!wyVD{@K}Sq1H4~5?Xh{+m?+&l zb4vi`pm9a#3ZhASv3XCHKY7OYp7D5BqjgN-i8D-S)dw`}0%yfyiM;Pe0V*5P4%7k#~j1r6^mb;Tko@7M`45sUYU$L$$Q5#B8i zRW4I_KbX;TjzxG&cRE$xTC@|IbcMEmt=a}NG<$cJbPj<)?Y?Y-Wn{2&bR|Nh3)j;4@jHS z@P08zu$IbuYfCX77VleC9DYg&Z)FcNPYUl?uEN~{2=5>2>jXlY{b1P+CAIU&>nl?X z-|%O>7y>UZ{;4TcB7?;ZzIUz#TLaEV!zygMv3Y-0?c(44Q2@?C8m3)+3`fm-r38EW;DE?weIVq@-~)<=EdTjA^jv=1>t@B4|xHFx1!Yf zy~+r0%ajbSOMCp`Nc^Z_n3o$oRMOlz(K7@*RjUf)7094I`aSz2TWc`)Tn~r#G3>>O z*qToZPY?tl8yXj__d3Z?4100Hx@Y6$ha|@1ErQm;fs^0+Q0~gLfCMVuzE5lT2fVBH zzS+EZ3;y<29f$(qR?Po;OJO?e=sUw&b7t?q^FO1F`v1>-kon)1rU&(9gwCP%pj%vq zqF6mBea)FRNu&qWc4h{MAw6g?k|n_lxr4OpYwu0lSKFbP_Q;Hhnmr6XY;Sz1aR>}q zPQ?8&CIj25+@nnoErHAN@mnoUPVoPk6Y@hA39SQ`%aHjWjf=Uy`km}i>>ji~I?+-o z_cO!I|I|7T;p7)!TNoc|LIUn033*XxMsQbe)g z{Hu)k%q%)yZ?Pn1-3jAWJzUg=un|FHSd)j$fZax?SMrT;EjaHMvH2G#8N2?WRdf2|Z-vWF7Pde&eJ(Vc{ zAsXlOQqhOpgU$QVF712Eq8X2OB3ef~PJRhX4{c3TAb|%yLP|3AqqyC>C0M=Hnp^^> zy=!X1rt#0-2wpCpU875xzIzkA>8nHNbrjzXgF~Vb)2NbL{Tgt^F1k;mrBg7@ekjxbXzL zMLNBq%>NxE1Y7#*Aelc*TmSbfb~n@T9@wJxo65WK+Oz}~Z?9ZsUQvYi&TUyX6yEus zTq>s!-iDWFUJ2da2G!f9&ON(j0|iK%e%MzI0oGS**!=9sprLr=CSQvs;7yq-s$Y%G z`~5pbo-r8#$cM(+Ujc7y-->f?4CHdiO*a4 zb%4F$vSJutM=XEujL&=f4L%m#=i|)(h`ml<9XAE0yl0Ni4oI75c$0~SGF0BDGn>S* zc=sLiHxNU3t1et9OX2;i_y@R!@b+DuH7X_L21|CI^HwF}os7pj0Zqg}wDTgfM+@1)IYF#L zcC|y`idW+y+Z~0Vi_gT(V zfa$w8@j88VZ1Pzlyn6TS`M(_v@3-ZxzEs|Bzud*Jc;~-9s3(E&jv-}Urtn^&KBjUS z>E5e#ST6^Sxj_YD&i7QJ9qd?o?*7MmWO34Hrm1L72A-WQ>EV|wf$(75g6rF`c^6iT zBsK{PKtVLFg8jv1(tYgtf5K9oThyEJcvI_`#K~{b^EF}5NhBa0Yb4LP5dUz(_Taso z%L^~TgoLdN#OV2O;*+a=GZD;xy@l|UzBDJZW`!0LdOd7 zo&}lz=ozMe#1ih)SBJAq{I~8)vjfsr8r~l)a<@}?6ZwBH!s0D{#nDj!;eDp&v3Fe;F2dXI=eeo=t9G#9){Evy7ZbSbo9)u2my!4Xy_$RYj~f{XE%(}x=d%Gk4DoO& zk;Hz)a;;wBxI~E`wxV(TY~i{nA{5;MRCv1zLyN=-FT|M|KNJ3%{vDsFX`7cN((O1WO>(Ww=zr455@E+kl^q&J# zY1;-FEZ#9qEC&S<-Z$Qs{GrVMAV~IUC$fU9^C^4YT)GL0N6$RA(ldi|`}nFIONT&O zp^n_{V+yo^O{g zwFKH1hYqOzm&=KIK*v32fFG_z<0d?oeA6$*=G~klw?pVA$r!LpEK(xG0$3l zu*;yuel_=d-0t18Vz&*bFM>AidIzke=(wEd&gqw?z{&h;@9lKfap{ea3Ua;W-}8U! zw8p@HB0Xq3O%M9)_r-(yh#i-cQpD;(kHq~ec#s}s_KrtV0_j1MV+w*!Y8rZrwx!+; zykZ1ZhDa)ATn6y2f1hT{*&$FiZ$hhn7a5$$TIb;W-5mUR^gPV`fCI$(n;9BEY`$s( z3I0Umx?)W){@};%K_49V3x7%f$Z+%j7+S|9PJTr?!>mCr{J?9kjmWk8Z*hCjkEE(P zXQg~7YUVQk^#?k7&{Un8VXPeU_aJ)fI6PfV=|Ko@HyYj(t5fe%c^`f|ump?u&)fFC zya?~`Yx{pu=6}btQPJxV-WTTjN{ob=Lb-?|LTp6_kR>22_h|kQnBf}aJ>^dZqT7xP zn7CPhAQ8imnzh*5TLUgPAMf8yf&pk;`?mI$L*3ZCO+4k1x2Sw#INl>@9UF1-i_VKF zjFsdETT;D8MsB~u<$W}ue!GNB0hCm&Y29+2j``nmYxeEm%>VTk1Ul!#;#~&W*@FBc4Rxf)&;qA~9E3+8k{Y(2^p?r-6G`5b|kh*Oh zoJ&p!ay&N#N*sA=19y^v;F^<3VQCg%Fy`xYg9A42=Nnc}^W>4>J2bA=xlN9>4V$-c zG)GI$A;#m~gVrI1lV5(W~R zKE_N5jTgY)@q}%+`sjH7e`TT7r5()wf^1uz7>*sL1RQ5-ddHY;z~R`|ZQ#t?n!yP_l~gcpIQ~XyN21 zB2ZSy+0PG_DRH(f^}s)Si;cNe!1AgP9-gy1*J3gL;>7G!%4b#445nXux6@h2yY{y) za**!*@BEK7-7?V6kpanzrUy-J?mkNGLC&Q-YFIt!=pxyF!uaU zR`!qAALoOg(KyYT1rnT(v3t;@jSb6Z-BE@ckUpVx{KUymR)RZs2T6(eE68VpR~GHc&SUx>BrHr{9l~{_Z0*F^6{IH(@9)~vI#k|U z)n2M%@jk-(^CpG&g23Jj6yBG40VR8;%(g_?lTYJ-B@gVh{Br~bE#GY;VrCR?C}1X4)lvZ zbZgTOJ(!&S)uSV82%O`JDya@514+|uw^P#00YPT;vu6x8?~=!QY!`Bg@DK8pL6o?s z_A74X9l_>3c0n^3DvvQ-_pU_i_==O?ZUrl^==1!bRgAwq?i@bvqKmhsD*5xEpOYka zo(BF3vhu8z$Ivw)rl0?V^XaQY>B^zrvj=9ow>u5*uWdhusk{$H#VKR)?mSg2&5iK> z{ocld!u#&QyNP>{?X8HXSqcf725{#Rd-!0UKHTU(*Et|(2sGQWU%wYZ2G{-KKfY}= z2fsD?bp#8sdE4%pUv2S&2!Ek*t=T7vUZi02R?}h?F}lKdyq(cHR^sI6u*WOd>#`W2sd+4`4J-2!>=mDEZH9ya_>ZxP-;)%EMV!u03=gm?7SacHCW%59CaySF=N zcz-z~MyB%KEM%pG#anQL`5=Y2toSE=3U3p6;`C00xAW<5J8Df0p+nryuKZYiC>Tjx z!gpo}#2>oG`!t9Q!mF*lWV_5kK~v`@pCoMF_6zqEmCKRfSv0P2(e5AhhSKb}NCI|YK6^H|_w?CGb1n9&4EL$5L(uV+XL1M5-92u-%yZk5n zVl$u~;$H48z8PXAc18GngOd&~)Ij4L$AdI~Hei1SsV0OovV?Pl;Z~5fXdMtIKih*g z_ZEzjz`=|kp%$CFaR(&Bp71ZjGnw$Iw)^d}Rytm>6S=!tQS<-67JCGpbr2WNDE~eG z-$}#!xAd1RD({6G+cmLxE9~EKg~Gcwuy8qrcd_wlk8FfDna$)%7CSqbI#fb7Gth^` z%u|o{9z#};PcL7ri6Mh{ww=$H?=b^x%SKLKEXL-|+O#)&X(lhE#?{D*T!34!AF*b& zD^tIOGahduT8A}Gehpl1mlTUgK!Uwv--Ay*xV*bpK0NSf`)T-U_bJ)9-}sMMf^YRr zLU;kwKVoBj=&PeW-kG%J@9QmmX?XwqaOpqWTOA2!G_ZJU#?%>bBD~YzEnYz3{c>f% z-u(#g!!e2%j$5!ot|OOn9r*O&g^zElOOFqM1z)D$nnxom$V=pBq;qD#WzEr3uOK#W zi(eJ%2gZ3JHBRD++2^K>*u3=;FI0aSWjx*vXdOm4`Q=I<-|F!m+1?uPA_vTQh0DAC zO9{@+Sx9aj5SUo%OX9guuzc>k!s!ba`hdWS>Q zv3RGc9vGnT&YfOIpztnP(UaqD4LqJbMzpf?< zc{!2%TA}G@W*|&F!fVw>Y~G%q?}@Z*;Dfu-xPAO&<76*v-kV8X-JxC|7;bSAjMm|d zliwe0cEboIeoz}G`snI)eBN_(_4@81ynj#ZoA+~+j?0NlQoz%Qc1w~`iUDVu{V&kSe~hduwNpD7fqKf?#9aZ*1wG@oR{ z{&3>d(5?#A4#wl1i`MZ6CqFKUobw6&Bw+5>(_*y07q@$xeEq7-eK`jnF;y}jsKnpB zB?LroPwDwTaQ8NlzB-az`}Tgy{&)Vznr#{C=g9mY^glgFnQi^9*+=a1{-vIx5zYjx z9`p!Yj%7u9kX=-2J>?PmAz9jNk%oreyW6Y!wI)`9h=)a9UN;S3=G(+Y5y?ZKysEZ! z>>wG4gpO|XI&2Dn%EG2x0qjTYDzA{+@58vEE*kge);`N$|7AdeKh{0A8=9{lKd5Y-=q$_mR zVUeyEuK4!`X&?=6R*A;*)JN>v(1)urc|YC3%7*YZa9Vht!uxIY*9$xd@4O9;&AU=o z0GT-Bj^BX>uzXxvcyr1S_;#gPy+45roT|obKj)i*bl)HH{p{GhkNnw@9^SzXsc{99 z+f;QFu~(46gu;0y8-^H;cNSVlBu;+txTRivBnf!xzqYqie2&Ze_N&r)PiNBM8IH*O zO?13sC-!{(L?9>gUvG&mqOXoMpN0#+MOB$uQkj#Md3Z@oZw91eQ)Y_ay`QPfPYJS zmWn(G3V!sK?}R>lVdw z|EF^H99TW*+rrn6SdbnR7Ns|LA<~1^E_rfe7cwASvk95cQfLBt$26Y3yt*D9QG}wa z5{E$kW_#sFNo0_1Vm)}(-2`+A`m8SPw1-$}ZQqp?z_(&9e1^u2pHVvtHemOl6I%MK z3S9>n?h)&c){%{q-}|kLY%d1#gBZfYxUkZ8+#aO5?M*AU(?Mu$xlh)Fj#un#Kej{5 z`fU=^_n_$G^wp81dsC$(adrh6M#FpV0?P_2@6e&e>{z^Q<4-J^gYecC-~EH~h-qgRi5Ra-wn_xV(j1 zLio9z4?-(3=p!UU#|ctwptp|KPK#FjT|tJ@@aF8yw7SNvE$MHIWRKHmiP8 zZZ!dI$HV8x*loh>-d&#t6FT0_g%8j;$2*?JD_XI6yH>w5&|5UfaNTd#lcE0SuE$$%;a`xB{XR0KCn&@8=l=vc>(J>qYO&

`XsJ)rl@M`6u8coK~>|CaE+q#m31 zq$=sphr^7=`wLpfZ=C!tJB557Il~X0y-R$%(ex=U@8u4rPo*9H_JPihBteteF2qsZCVNo7Vo^$eZrKpx2YT7Iw-vNG(JJr zCdkKI=9C$Tywm}FnWVaB-wogiey#5XM~1*2nP1tXhsa*SJ-7U1A@=sxfz37WQWWEzy-A~W9Kp%&cg*&7g17)!$D`65q|u4X z+jy;*@e73aT{ff5Le2QMw+QdD7wsYlG5_L(-a1O{3v!TeZ~6E0|5(#41N|JC|M$}L zAd*`2Vrmb1qi)QD)q{)_JBtWN50W~)K#em0=Z#-hOhfh{rOq23*8FS<)^fSZ7YG@{ zYbktXZG*=KXpeF+y7L*u$C^Hzqo?8EF*rn&6eZL7!(*S*i9by(u$*T)jG z*+`!sjP0B66c>!omD;^)O+FqKwW8w$>GWyevO8Q%&wEi8eRXI&&AnfAYIZ=1pyADP zDXp8zn`BtSg~fZhAWI;H_nwh&!W7;zbyo5+$bdAqP|8N-k~y%*5pCS(YXt3n_caF~ zyd&8k?}taoKsw8135j3=^ir>Uud~JGJq6{**ClX49W?G3xA>Q|2iUyJ9%$CiKf`#u z=QRGUqXH*Cwqa8fr)Yk#KF%t&u;c;euQ7F5`-C;Up>*^BJpR$(%Rn9-A5N@pUEn9e z$@IJlm2}oIx>`~8@9u3l4R7w9PD)hXk!KHZV)6b^H*ti*yYQQ!5QVpDN@jl;!kZ;3 zd>@oE1CdhUi7XOEaO-m2xW@?Zo39?pS|Ge@PT#BTur~pr14S4Z zaY_}L|J4mybHp5t!Qmxa9ocSS_n;6t{=TB)>~KFC_dd-{^&1!V9;9ftU0e5ww+y#} z+=td7jgwzo>C{4JePP^3>;JaoR}qyvZAeECf*0@Kt|T)5BlZ@3b##wCI2QT$f^-ZG zZ=or-*^k&!uD67y^YUZy=4$SrL*ae+*Xj8b-uvZ^6_y~p4dgDKT5!$=*!rlmMJE`+ z_wIANq!He=WcRTR2yaRFh-;y*F$nM`WQ1PE=AAHlls)VRJM=;03d;|cFYCd6#C~sn z?|*-a@pvCa>zKjGFExBapLfDP=Ur5LHtL!n{(v+j?Y*HXID+YU%gNAJ$FH=>xw*(k z?2zrPXd2#vcUPoPyZ6iUuZUQ@ou2I-q-<|(vAiis;XU;_dUrjtf}B1%tiMg(2K37J z7i-)!g2Kd+HS7rQp46Ve0EG9Zr&l&=>^BCdMk9Z(zlhB{He#o#r5gu4j>fgdrL@O4 zVe_`>Gwthle#da#I|;4B5huT@MMAv(4~2oe>Dc?O3$^%N{Jh1PDY0)2Pd2GtJ7Pk| zfRs1Fqp&fS>3I|At;4Zp3jOw$eKfoUvU|g*yjLe)~N7xhATi`=PCuR3E4a*IcGoy)L!yKGFn z+j^G+o<`$r9oNb|tik5ZC)zO*)XaFiz0f-5=VvIF~ii@Igj$0%jwZ~~26_Beii{8{X^_x)!6?no8JJDku#>v)WlpI}uhr!lQz0-=~xnCNuy1A3HMsTVEz{D_+t|Y& z;<(EWnDOr_y*OYD#SCoZyOACgJfwCx5II3gKk+o&h|?JOnWdQBT#DU;NIsX<=lQcj zZ#1r1ILRzx0J{gto?PquPVNoEtsq6vI+o+)=X=lP%jtt+xR2KVZRn`3rMS8q9X%*Q zIp)Oay-fdzB}CC#M{>+-JER98yxC}YFPOYvMCE<@8>a{s?=*)(D+=$G(|c#{|8G|j zE0jcd`(%H({g&Gfd}kLFI-G6{hZ@cA-b8pWTlZQg6XAVu4(Xz|n=yFjHAnWudu-m$ z343%xp0mPUG|ohlLtQ2q`+7_JuWe-k1B}PpgIWhpekxBJZTG$T=e&zL_Z&6Zi@znm z-`qxVx|Xl*fB$+g+dqfUS%;&Yopbyf%Jr5ERvO-775?+7ymy2@62{^^*ynCf;eC3j z{}-iuzs=m(!GZ9$SU07;?367Cx#4>yZ<#S%<8LH;8sV)sBV}KY@GgtZvM!#F%>Vmr zYOXxR9*}~1+C20P*bOUd-4mNL3!p+1@Rc!DK8b@L`(HsoGp8sVQJB4n#!+5-Rp>-_5$?wC0_>=S1 z{yFc~`ZMH0Rs7xCROesK~?XC3{-!~HXdDD!^?3k`1(=iL8%_SR@JL=cO2 zqwf=Q3U8m>J?xbEe|3&VA4GU>xRTK#=D!gfZ&aP*sBQ%1TFmd-BD{H@T;5GW=Kq?8 z-->0@#$bxnwZOp>oA;{+53v)NipG6jE zAjbc5-iQ6yfA0*(-`*ma)#e=#j$!`!--6CM3SSm3Law*`d;gyamY+xunn%-v7Kv0y zP#>{#TU8cf^`O=g;T%d28hp{vLwUrqWJAs}qzC3ScH`fz zuU<0T3X&VGgN&13DY)?X1=l|xkQTlhJGobvj`=^{_o{!?0p{;Padg(<)w5J%_KID` zTpHfe@AQ#>`ulndQ}(eu6ZLpqKUp;k_|YN^QE(9`pz%WU5b@ zz$|s~Dt(0a^Wd~yUl873SWFWKi;RHyTAq8C{>$qvh#P$-cks@Ef@s`Y9K{9=Kf@Q-hp4}t3yMu zZs6(3*%c%g4R5LPXBJf6)20u^v3MI4kP|4pZ@#h`q;&5IgUR6@)mdq&_wLvM zBd1fX)v6|N`@Qjv-;n`HUr9UB0^xmYeydk2zcFx?es^mo9((t8@Zba*NiIZQ(r3J>-y8oPaF7HDJzjgTYze&V{Q=x;tOuxOgF^axAL>~$4|CRgi z{eLEy{s{zR{wLD(pe4(awoxCk)_>&WuzHYAqBS?=6+7%NIw~oT*vMm5V?oFYlDDm5 zn~|9VIQRTZUhvip@KvMx%HPNea^(a^fB-TeebdO^-D_Y3;t0NktvuL|*wqQzMKzcH zG(@0r(HE|%R&ZiJV$TT4-FQCng5e&q>(M%jaq@HTYT{e`^q&t%A$lv5&)L!OiXFDL zkZwcff5i5&(pN`+L*UJd*x5%c9}VxtFCV#6c?-XsScJv<^5fqhDUaBUz}f~1?+E31 z(J+K}*8B=5?uVO!+T0WyuPqkPPx7VlTZFgny+jU8gtx}P^^ZOqjeykEtmSi9v3ZLu zb_jfuGSeW8#*GSobUFJI`w_e5&x?dl6cPF;0GlEeagfHvjw)tEqp@Ouw3r zkGG6(i7U{ZVg3~)y>*<69V$d#v4eDPUK-x=#S-VJym#Mdkip`uoRT{G_SO~F+wW0$ zD}D^rjYN3MJe08YUbz`)wzSV&P&S8RpGOCp5Zfd;uv6;}w@ zyx*0l0S;XPyn)6MQ;y8LGmg#MpsQ7aw7;9-cn_gc}K?){dsmp8xaE@RmEW|2LJly#E<#EZ(m9n~N#kTl9B- zJB4>h&Hj;SgtzyiO-}6zn?R8Pi+5O2^*IXf zD=}xEQFwFo`M%6Rct4r*M$BvdCa{Dk_4DarQ`n~4;+-p=6eQ1k>~WkwRY`o7b-VB9@C;q~YB;&tQQ!u$WRci&M>tlh%ElaM+|Kmi+w0-~TG(geXWbQB9BiWDJ$ zf>=RBQIXzzFQTF%V($%Gf}$WcR6qqQii&~?*bv*d2Q%;D-nHf=yz74V4R`4u`<#8& zqt0gi&Yu0uOeXWVcHC)P3+`mD5m%S1$sNfZ&K<&)<8rwSE}8S4^O^I3^M><+^O$p= zbBA-CbA=<|oZ%ej9OUfg?BHzXQ=}fLL2e?I$VKEFauPX=>_v7WTai2@14%++kT7IDvKm=|EJi#LS7aVyhfG5( zkjaPd#`cXw2Wt zZ_JO(cg)w!M&?6i9kZHQ#VluDV4h|kW$tJ0Vs2w@VrDT@m~qSqW-xON(~r4?xsd6` zoX@mpPG?#%QKm6dpE;JP&QxJ4G6yham@K9g<0s=Qqn**hc*%ImsAtqLZZawv7a8Xm zCmDwsdl@?!TN!zb3`PY!L&6rKiU%7LYfPnqQwWCg>T2Lobji|a*P3lPMaOx1MobYNGt*cL57W;dU ze}4jhe*%Ah0)Kx3|6@M^@{~jbM#0I6*jzX%5&m5A#DrjoCJAdH8YirRI3Zyw7R1kS>JUH0sY3i1rv$MhZZO35IP5gu7AFnyLmUg@`#5Zu`YtvMVr%RM zh%K>eAij$ZA?0kq#v2!54h@A=XdF)h(jjv5(L3|WD2I9lmkq{eVl_A#0Dnfh^I}qai*!~dj#d09l#xfw*#8M#M zjR}ExCuSYQ+cB#lR>!P_cq?WJ#G5gTAl``KLA)O00`XeRJcv~>vmsuMnGUfs#u{Qp zj2Xl$F_R!(jxmB*9-{~GQp{M07h^Oamc@*KD2N#bksmVz;)NJ_i05NuAfAgsAfAn( zK|B)!fm9j|{z<2!!9VF#H25c-j0XRt6VZzy9*+k9q+`+GpL8@D{F9DEgMZTDXz))u z6b=4K2cyA1=|D92C+&|0|D=7<;GeWN8vK*?L~BCa9S#0TCDGuYv@06?lZvCkKWS$) z_$L)bgMZTYXz)+k77hMMg;C(2v^5I+leR>Gf70eC@J}j;0{^5qqdXwyMS*`( zZWQ<@WgL}LB}BQgK0Bh?`W zL}LC|MPmN_BQgJek(mFLk(mEwk(mFbk(mD_5tx792+aTD2+Y4v1m@p60`tEp0`tEx z0`u<`u>hiH1m@o(0`t#{!2G*MVE)}AF#ii8F#oO*n17cD%)fI4=HDp-^FKdgBt*vu zWr*`4F#mHSF#iq_nEyEun1A~S%>V2N%)cGRe-@^HCWe0oW`8|2I*Sq zThdphFG-)5J|%rbdY^Q$bfI*6OyH(q7UFq#dPaOWR6YN>7oV zAgw2@B|S=7Sz19_URqk3DNW)2;C|t@ao=*AxKFqbxOcfXxE0(o?pf{$?ji0TZV`72 zH(WAFc=2g*%r!i#wHT&Yi?H`rzEyOsTl{fynfu4Uh1Uu9onpJ$(9 zA7Srf7qbi5`Rq(~GCP(X&fdTdWUplVvc1>~*pBSkY+JS^dkT93TaT^99>rE>E3oC+ z(rhN1g8V?fAZ^H7qzQR~JV5RuH;@XX3^|LOKn@{$kRoIYl8dAxiAXdOimXEdkmZOE z;(@pzbCFrdRKy&agcu?^$QVQo8HNl-WDyQRM@XzL)+g3`Rx|54>k;c7>o)5e>oSYa zDrFsG9blEPwzCRY*{oDnJS&p5k+qiP&sxe_#BygjvF5O5u&i08EEARiOPi&^Qe_Qg z4P^CWAuKBM7qgSu!E9x|Vm@OwFl(8&m{*yXnCF?Nm`9lVn8nOOW=EF-I|#nF>sKrgS$}@cQ@H-=DzWpTOUrz~7(1 z|IAN-vLz1&Kg#Aj82l&&c`*1KM{&=A!H?pW4U->bK{kwj6xVE+{U|QkF#J)Rvtjz9IAz25N12}u^B=`A8wNni zylj{NDRZ-71f)1*!wg87lMO>4#XcLRK+5cF7y~JG*)RuEW@W=5NST=plOSbAHjILl z>De#~Qf#wf7^FmL7b4~0MRIG7DU6WX%NR}Swb|(LLusBnLyOb8V^x7 zO9!G(mL|k;S)(9oXQ@COn>7@oR@NYhnpv_C$7FFKj?RJsm74*to{(!oFZX}U7RC+Xmy{5T!_lOLt`hxjlZ{F58f z!9Te^9sH9Yq=A3({WS1TzL&NdVqF^eC)cKde{xM4_$S{@1OMbZY2crHI}QAktJAk$$L`4KY4d5_$Qa7f`9U^RPawOP67Yqohjg-T$BR-$vaZ~AZ||q z|Kx2c;GbNW0{+QcQ@}rYOA7cWZ%(m?Sdaq#$(vHZKRG`I{FC!iz&|-R1^kn9QuHBa zr)WdWN&)}m%oOlX&PW0Ov z?`^B4}(s+eFO&v_#DR)I`j`O(N#s zIuY}4m5BMbOvL!;ZX2IvaN4>!g>$4t$oh zDeSz}qz6hfxn0~=*lFM9UV@!l%dB^V+>?4>0R_z`V;zX`X%}adI>$Bo=D$FUrG0%&!Jn= z4e1(m1v-cJi`GVaPOGI=&`N3hXj^Ehv~XGgZ4u3pHkD>V)1nQd^`lX!pQx{>52)9u z=c$LN+o_q4csABjgrRCetC)1Xp6N z!t)mgWC~@{Wg?}HNfk@wO2tcUkXkO~E)yu@1J_?{WhTLO7iAe)xZd(bx>>qGYPOWQ zl!4SJslieRc1AnYUPT|?R52JLElX%uDi1b8G;8{yjWe##2&)zx> zC`OLq*&Bn0>Bvz$d)<|^137|cuPTZcBZu+q{tVe?ND-dhQc}cQ+kA|_3Gv6Xf?&fI#1GFl z*~_dzR^nN{g4H}^1)k-;P5Xo_$FrQ99q*83c$OXJ(T*&|vn=}WscEWhxp=I z`iD*)vKY_O&b*00eDEwaqm+tx<5>#t#7|@qo+Xd}CWkDpp81zsTta5x znO~a5BxE|Ct>k^NLTvGD#e{)n$TU1#u0F68nTlsiuWrAO*x=cciw~O+YdrH^GMkN9 z;n`x7;R=W)p81SAdKj_5vqg`}>Jf81TX?{JKVpVwUct?Yh$)_V+Q@!EP(1UHt(%Ta z!87;9j1FWnp1B>@4nZd2*@8&5H^@XhbG2n>ASQU`qV_WyF~&2eRu_F_0-nu3^Y}Gl zglCR%N|A^mp3QUE{t+3EXLBb|MMGmD_0RAdyMnVV|sAS3b2On&PzL=Df-Z_RIz5qLJ`Sp6$R z70)JzF3Lqz@NANO^b|xH&n6C;9f=IbGvnszWMmkgO%QlnB1(8>l-&OzG8E4YBM0*l zMLZin3LStb;FXS$ipmB=7G)5%s%MF!&8I9;9*G62uU{w~;n z$m5w-&Abvs4$m~VOlJ88TNTQLE;)vOeJ%{n)L3tdDqxeG@yY1J5q&be%ym@vNMpbs5RPvx|2v7a{3*R#td%G?IpA zg7x)FkyJe6Padd_q~O_wxz>Cn8PCprm=lR4;n~?kgOia&JUbJ)=oXTIXQeaazasH? zcG_jJ9ukLVC!5E2A+dON;>2BjBnHop?@w$-qVeq5{2(PH3eS$JkGXN!TNFbhVo3u$6 zS&e6fvimn80eD8W@}sia@l0xH*)CQao{?XCYG!@FGtx;yiO!Iey+8ow9Jp1K3 zG?mqgXFruc7O-0I?0d_;NvyYc)^*_!mGuVCz9s*@%4){5&iVD}tk-zeLQQDu~cE*!?Wj&wPvh3JZn65Z7Hi3&z@xmQdl*3_SB{JI_oZ;JsCdl z73&V3J?aX*%({(d56_$5VpZc=L$XZ;>lU8X`&5^+ZsOSky)h-M8+dk~B6p5;9nb2n zg*;gb%E%!c6OB?tVMu5S}$HT{spwh-WV>%G!_vc-Hv+_;+MK zo;`cee*&@(&z>Gcb&$Py_9T$cL-yd=W7GEokllFph^69>l;Byz>#`7J7oOFhfirV4 zo;}$3RDkTnvs>>KxX5NayIJAGMGElj#>v6wkWF}Yeer95Bp=VNjU7G;$-}cM#B(c> zi)WSfyNr+=JgeAZbP37Evny-Y%OTk1RT7Q7i^Nqy%oz)*(eST-e@WU;06v2x-{Uh# z*i?gm25BWvVGLa4BCYWBCt=reygXNX^Oi4J3757=QVDzu?DPNkvlR=l&mhe{`JpWU zzG8=h?t1)Ysw+A^iBb7|oP)qN>DS@>gl6=CL)Jsb#3r=j{_<%qH>}V`7r!)KDe-5J zF8ZcD)85|2e#Nx3{EfD`E3wf&F$SU ze@=dAOy^aRzc1^B`MTGY;b(jIr%T>yj+k}CL}tg_*R6W1LBxBn zW{!C`?>qU081H^RlAav~-t)8$hwk3*g7Qm`+`X$lM_~Vk(-H){4MzC*hXU_Q6`xbQ zYpl>md4aX5TZnmYP5Hdyj^}s&J>j~;D-YkA7f;OlGTT0B)#y5j^z zhu&Ni<4t`Px)bC5IL76{Z{U5)W#sh04rg?h_MCntZLR!AzmHtuAiS8n$XR=e-GZ+g%q5(V{!5* zBHrWbb{k{73-&$QgYlmJ&}YdC_<;1MqJTN71DsJdtt-ak+bqHI2wgQ@;EgQ2Os@sr z>F3*+$H~^{ioJ^C3eOSqK5+kfsJGNlzPE5)=M~RYrhAFI_v=E%H`|l$NnH0nC9I=E z#PKPPBY$|mtoI*~Hk@;QtEaif<42k?INdbaNz6KmADBd3O}LHv4){p(|;M%?|$pDkQ>-6nc8V;J%4E$qjt#auI% zymxP%64tRm#PQv)wYAT8={@fq=USz$%EWlRg~FYWimd+w-~TsQygIIH<{mwK{O|k! zdf7bwGs|KBKcq(w!tRaWJt!wzMu(^e8MU4D$9mB9Ez;3g50aOS`7i?}$SvVPKU*%j zq1vn7O?(|PUywF@+r1Hq@D)3q(nW_7n$Qx*H*qctt$UDm9Pj(WI*dddUt^uD&BXNH^Imi2wyA#{8{rWs_(s?oK$Y?((oFE7F;EmnA#(BTB-!qno_x3nj2aNZCeUuc8_xkr* ziP#sUCn=V7%zd~39qgz$d-?Nu0<-c%*g64$+l2F)t)!X-;tW&4~d$cw^5O;k+j`PSqsh%`ukmzV~J_ z=z9*v+puHUS99RKcETKQrQ5Ek&!@rqOu4y&y2=kvPXq7K+FFLXz`O2O$OOt&E7bO! z>&_z$#KXzJ(zkEoG{w}rfD&G=yDSYu;ZVfT-9Pi-Ry@sFo3xw-5=e-?#fnYXm}yoY?P+_OVNjQziIo3qOlxjxUEWFuxBcFUx6 z{@g(t+JiUt3_Q;JYh95(5$_E1-9Z@d_g4$oV!S8%cD+ji-nSQ5E&jCA9n~BY^YB=! zv*5Gq6^97meP-F3$CH7#=io_aRXZ(F-)olnG4F_Z+nf0B$`gFzFA=W$S@z`X<3q%} zSuXpXojt21j<&l3%!)z9cX?*rTXA5k8NaR+GuWB8cC+xtH6jpEf2a`tp> z*WT{#t=NM%_Mr}(_neENdPKaps67h9cpoTTx*p@L);@mCI^aEBZ|%CtN$%*DaMz)l zuFisrop*JY0`H}>Zk0L%@81*O2HR7u&^!DDN2%Auyl)4brc2p<=Hu%=EA9GaSxn5E ze0SD|n31<7j`v+*9UKwIrxRPRXL6?Zyt5xk=gbHdgZCn?>=|C)|Mr&fV)5#jkaEp` zLRvR(g&w@IPbuNNH>yw8CE~qyPT@w3caXkfIL4bJmu=<~TckeA+SVy*q=`>VI}ZdVnJmKHsGldMPFpSi20&tKjmO%=0_ ze&pMRFr55-{{O#i)+8~7{r`v_JqY`pCf0-W;5$g4F7zZ3^`QG!7hSL(bXd1~5!QoN z&PyCpt*39AW_y7XSmlnEq_}U>zqml4cRu_2prmG$yG)st5Z{FUh<-l$c%dcgZ$Lfx z@fYza_E}TfZ_T;w{8hqrT{p^WmR~16#p*ptI=uE}mBgK5n}l_sB93p`=p9$WmF0T9 z|DR`PGK)_W;}pBXVOH7V{{tJOE#lQ-I%CB!`F-7|Sk)f9u@4^Or&tF2x(N~QcE&eX zjCZN8#$t^3_3M*OKLYRfBYo_z+;B$&%?4GuuU;USxHv383V4ryW3grj@P2Rp{!9Vz zE*l`XV^{+*?{Kpwjcb?N`S`l3abBB0=MnQBKkArWXWli5;~g!m!$QRI`P@#L^(M6U zymwDMMshV2{dmidaJgpAwa`AlLArKbygCqvNn`6Xx_PVg;EjEf9_PK%ev>f~@1X-U z7ht?U6rNmy@!p$Vt)T)FWJ*$n&92+-C}n!(;X8vD2oj~Nwco=8sYF%!bryK5t7J^R zRBVZEzwGx^uY#EO&yCvpF(w^+eBBJ?A*PMN#Jtykx}THia9!eflSBU0ks#vuc6V+m zf7jT1-ihcZ*~8z(xV%MUcVsM#>GQlvMq<`sAHGZYc#Com-q@=laNaBC`A#6>9kL;y zyL;3Iec-+AbidPez=A$bRrayuVog98qQXkw0Fzj(vX00oFQV-kGIRw@RBOkM}oW9XmxF zA1lmYTEywzU*38l_~6)7Df;o2(t%&5YXtY}^WEENqIh-OiIN|~jm`eM|L;}r_zx|H z{l7+!9)!K^3F|@F{{KPq96C`Cigf!Pi}fI1wGVb!589_XMd7fnzA1ME`A#~Ghwj+U z`&fIxO`xkkzRe9bNSUwHDh!|pU0nIH?Mj{{dT~eY2B-DJJ!s*~XZ!Z8_`oj{uB%QM z^-+BdaSysVlfzl%R4H+%*j2(h>O>shhVAY4tE*&tz5frdowaICgXj$sY4yFm;nDVe zz6X)kh*w9f`2tybN%tvMy$5gX^<_A3hg~CRM7(7iR&T&~R}3$jhwfGNUZh|^5w<|M&_sv0*bf*Gu?WD+^jaw|y&YYVT*A@};){;pW>NB{F zkFSduwnVGZiJ13i%g5aMcFE(dC#>VQh~x8g&QahE>-_}TdfZuG=d}oXk6DHNC z`#kS(hIn-hpHbnJ@#pcDQ9XEL@8iRHzpeNrMa28`(;>?+-cxlNTru7)qa%t<;qul7 zLG`4WPu)?A%c~Ttt=$9*<7U2^1ia%?_XaHh-i_aaeyH!YL|+|@bGWjQn78GIu4_u6 zZG3#)%z0fm56>s&-GAbs!`m{iN?iB071l9K#PRL9)naTN)O+5ua~|ed7l^U{zx{L9 z5#PSgn{-FaI{F>tjQR6;%g7$Qu@_9@yf@!CMU*fPoqzP4v2G4HUJc@YN9 zZG3#4UECVGcRs|tUCD~f851S%=0uFJjwK?FFF?NBIeBL9d25s{vpls-boVw)RPp)j zv$D_MAPuM$ua1Fojf**{-NT7m58l`tQ*qu8%rnVEyf0r`-_84K=KlY}TjkLo-aE4X z@LtIK!+ZM9KfK@GUPq4#ute`yEuo*rMr|M*r3-Ep*T(?%!??awF@zvYe{o89& zB#`%bVI6KFj?cyY3hk3^?|GMm%4WviDi=Moe@FTHDuqhcJa(2|CW3erYh9h<8DAV+qE4%p&>}jQ65@N1xaNZ?o`mSB`kY z<*j~!RFB#2f{;(okL3aH_SSn&AAq-ATQuouvL$*wh-^Y_pNh>ZTxaAQGTmwX5K?$-Wtts+JD%* zK@m@CWp%uovHBl;i9`L4J z>9^>P3JfRr(|^-C-2^i)Pn@$6c-MQk&FlyJf2qQ(%GBMKX!NdGNeA8#^ZsN-D$Drw zj*qXq%d9;!jY-_ScLy-St{YcKT=%9}|Ec4kh~pb-B5T`j-uoM*8rQrFQ_97-IdQrD z%R~9HzCWCli&;mVpm_7r0VvGgqkHhizIO%ZJwGOzLBu=Gik*S+PPad5i}7wQ8<7

*uGpR#psg2CSAt5yK-$9I)Rs{-$;W2=t5gPRkn?M3Sc>?7taFgiME z>9P0xWZ}BzqkbE+N{PF7^?cfqmMfCS`=+ptdm@hS=@Iu(hv?pS?=u}r-%lxue!OK} zuD_b!6ze|Uy`}TTtE19Gck%q_zxV%%hJT6r@6dzvdh{Udo2T#|6q#u!OVoo*)?AIm zdeG|Q{U=~Oh5(rup;GpmDZ&-jCe{Nte5xK7}46zsRgEA0|j`MYB19 zzbsHoi|5nI4TyVC;cw58dp(-@X2Nw#E2*^k9O537KW3rQm**EH?i9OUSjQF-$Cqtm z-#Kne?|YE`_jvCut3^M9R5bVK>|2Z6`+N_YvOv5#R*&w(36+5~;cw=9shV#BR zi`$=wcg4NoDHv~m`ME|I@0g&)I_rV=eA4C8b-_IJ5?^BH`;S7-w>I;`gzKj1*W4^@3n9Fe%&T3H_<80fiQ|1; zSjR#U$5-*9qALVzExr8Z_q*)TP&?6gkZ#MBeO5M@+vj-)4-&7AFi(f)*Ee-r<-kBND|uAh1^`GVx} zjuzI@BI5XRJ54I>{*A|5%p9bC+&A((0hvCHKamTAc_lS8fS)uBrHSjIpS-37XGWp2uB;p&SHwRx@HC(S; z;=1=*VI6lw9N(}vU%q<1?tS;JrtNz1Vyo!=fB4hpebmX%`aExO>v%t9tb%S#clXxr z!5jPbR-AX#v2ZRCZ#U!H2Ql8&p5fiYNk`}0)0V*7^u;Fggj^mP_QRImnC32Ey}!_U z1bDYjZl>J<-tT4SvsS>px0Az?+T)^#XYc3R7c0uzweazEk4|8xAJwK?Cm<`(iz4-sdYi*eQ0)Ws`lYpa=0ErL`|! z&O@!`S}4~|c>=H7{R^1M&8W$>%fA*w50Xks8h>=N1^Q^$poDV;#HZMaZmAiKMz8qw z!gUV6rL%tN5T9a0RI&qCqh%6zinS8f5ia8Rw3j#tf*X5(iZ!l_@aqZ|-Gjasd4v}A zQ|t4m*ww}2)zNt+ye&Gr`xI-~gE#ht>^SdKGIbCU@54Hy{4n01G7a@H-q}C4Dy#$E z z{94UE&zmG}9Z|_->=8TY-s5}lp69UrBhI_v!kqy`ycb+c4a9i+mOts_aA(B7y9E&GdLN_t`2)xV89Ck+l@9kqNt>h0_pacCzq%Te;=557M*j+mH zHD6x1?y&Xh>9PO7djfU$f`QVKclCC*unrRu$0wM@`{nw(_uc!qN75xXQ_)Xv#kZ=#=XoD<60eS$i-tM_bGo~?K@Z+@Cs0S?yrmV2<%xK6oldO7c<=prrTgZ@wk>YT z$-vv7a*Ior4-Z}0Uw5hUD|Z3?>ZzL7z}xEWPKPw$EjY2FVfiHsbXTmM^MnJ$ygQ4R zdEcmi%`XrWk{MI4{qm>U`29DCorod%8M8xFZ7 z`l|1W>M1m)S)bn^kyeRWhvxioihsJdeh=PrzE)=7yw6z#$Pw|r9(BH(cS^?P|H6Cn z#Xr2m2mRqKbNLT%sSkg6|BRh9UbV^sy^{0v;%7cF?{9Hywmk&i<-&F06d$=Ui-~!M z@NLaPB#<{P{!blYB93o`l-`h{+r97Jp2NP-l3$9Ry-8zAI)XPp?EAcR#H%C!rrUsb z@qhRK|CtSaFaK7UASdI-WYg?$EaG31>UtjJ02o)EYPx!`(K9e zh! zp0rm3<86NLo$F2DojB9@%f6jFwAwYR&^Cl8h-2#O=m78Y=+cc7fcM1Vfg0gMEYMGJ zH|mXdIS_ulWux+d+7_!Oe!Fnpgxc8$CfwUdxDi;#m4CV+??_=CVIq!ih6^jL zzh>`w`#d*rSY{)7f?VE_Kd$uH(LT@n!e{a7sGNoj2>Y}DH}1jPMeS!aKAhM|?^Gb- zJ*J<@42<`F{opYe??dXkH;aIG(6);Fqe(n8>wSomNgz+KSmWpFQNVlV5bLp)!24>z zvLxmR3smFomtXBg#Jtz6l~vx%Z{m*>uDdtzvATCHG4D3lGF84cU*dRg6xQ)Y#PMY$ zbXc^m?>%oy+_Q1Txnf+sZErnu%dzkCCUuBeN6k$?986MFD=YIV`ac|S2(I)sR~ z!|QRL81HnaSZ$2AeXLFXa^OwQTsG^@3LdH*c83@3$P*+VJ5?eJydUTB+g-8YWE(&J z`xXl{`M8dM(>dbdXL9@)LyX7PQE&c;rSrdxsdDZm_!`kT~9-g>^)UI6k-V zel0%Pz2|*`XR_ZZQH;l10ywJItM+Q6;W_O5yZ`UyPW(T!9QOZaJ$lf> z1NQsz9#rI}p+?k$nw7e~lA#C1y4@az^`Pd>@AjO89z?0Dj(P?A|LrfF^A2b71TAMB zA1sC*w7%%(z0a{tXz&E144R<@+F-5BS-OR|2mL?{f;S#(d2VgIS4Ld5a?_VgQjX>_*e{V6uuIpCn?RWT+=YO1Q=5`{j$K_dM~ z5wDJGF7(lVCP=ggZ%-T9FF5c1jTcpjco%iGBN*=h6D3uQxBmS*`X7LI{WDkNw|9AH zLt4bzM;SapK|f7}dBD4D>%qw!;5~Kt*s-&hSfImC>zt>3BIX@8EdAwQbc&uJNha^A=AJ6-`@D_C zt7EquN!|5N_ny*&w}))qbe#9Z+wsaoyv=lG$zi;g75*B5@jia`=|@GlIk7zEkjupf zJT!%~@z8AG?GnURoesS7hHX+G47^L`PPMUFZGjr=FHU^=H0)aznaw7=lpizx&udQU)RJF-<&v|^rh^+1o9pv ztfNfS@y%O1e4~5sc`w!3bA0G)(NAxY^o+{4a*y_T-XsGt>zFcqtv(DVf4~2aXxAn| z{~h-K);)UAl8XU%HX1gq>m=);rXUfKzPvTa&8$FhR<` zlH09Z$P;`GOKwPoQ|wWBd5ucg{||JQv0Vn&Addzf?%z4Zk?;;unbGnF(>+i5__}bT z8HIE`;#cgXk{maAe?BE~r`TJcQK0$?Si>Qeev?Uy{>GK<;iYemNQPnnd-{@2aeO8x(&uj*+5+{EnzQxH zEE6g*@0{q(KF8lb<7W%kg$LBu(~lGL4vH}}O3ITw-kXJWM2R@QiBV%8xBK*-w;6xM zzJ&2&@Se7pm2+-lpWh&rS??38j=dktL%NQ3-<&Y-!F$o8vU;5NyA4hwiFm7{d){HZ zgPZ1e&)$niT6LQ@53RCabDjje#~ozs^9SC)xAvRS0=y@#jCo%<#R7ep z=y$2Bnt1akf z{~w2ORlGNevHyRi;&5nDUZ3Yp;)_|w$4xWF{oVgd&?f&M4h1$y(|hzFzch_Wcn^{( zXX_C4pb>Fe=dm8N!ZN@66x+^_z9$JdmoYg!!O#o^i#^bTUOx`t z?|~llHDQrK|4|lb?d+=uNI}G>*pvqYv^WbN@oR+Z)HgoPtFR`12T6K*(}Hju*v3o}eTkhkGxfyAC02cYgA{HoUL9T!68zWxxr1ce zgZE0_7b~2%>5c|%BHkz8HD1JcU!82wy+QiOtvaFxybI(7H_Bh}(BWImuTVGf1T&wX za4ZJix`(v=4+8ITOUxeGjkG}L$I))DbtUFKYNu5!IPHd4 z>_GRP)`Rzo2?NV;-rjA8#uD+irYxw$cyB}>ck><*Wjo#nii;vx1V109Ae(LB5qNimptYx3)kr$r6!OE5%bp4 zeBwDKSn_y364qfP;`lhRYj!*g>OJpzx0@V4Lopt2c^}<6d)9$I&zp2a%sK+Ao(NxW zF|`Np<>~`lao!x`P%R?f{?~JEV7v`=vb#4(PhPwF(Y(J$Ns@y8S-RJBnqlNyIy`{OoOv_cHRVZr+`)6G~Cwy>NQJ8#(uQD7nHYu5>$3 zAh4d5nghI#-Q1=k0NxR^+tj~nTB1${>5Y2L^9k?0P5E(aTEDI*{Q1Il0?ik%s+=MS z?=cm)Rn#;EO5VM<8Nxbti8#KgKI5D{-wz|Kk7)O#!>-shx8sh;->19O{cz<5UZ3yY zaVx~Dql(s8R~%gY_x?W-97+1`FhS1l(Sz2+6>h_O&=fw^kf;ZJm4EMu^`Ng?%DbOI z+BQG)lnwNt7gE_?KNLMsgPRS@9Hl%2tT69)eCRm|BgO8^sFnwOL*cq_N0teaZHTWyrY?_&uA&^1xD8UPu#P+t$5*XimE}>>`~Cmi zeIL)9e~;{D5L{xXdB z%kSkX*c~Ky?wZFFfj7yt(|FMU543LCC$-oQJi*ca$@b@f_vQz~N;80WdPA#L#!GW_ z$%XJS3r&ePNTt?(i!Q9G=i}=<9ab+o`;nOUFwZwkhOgxDzAUUmUBvM*Pf;d&WcQx8 z++_O&6&YeokjGQL#D0=LCrO?4-#V64;?=RJK;xQqM)w3cs|WAZ>O-n<-o>Vc`b4}J z7=I7PczcaaACB=3s`HfaeR*t_(#il z^?rjiZTtnFd$UEq-lFlwvbep6Q~Esbt<~byL2J{>N=xg0yk%w&-m88&t-^WBI<3(o z;{7eQH4o!Wp^og{AT5!8H*g5>UcOf<>L}F%eKy?e$j zlltRZ4x6LT{nRZ;8;FOKO&4p)!!|eY8-?qF4!ye9^_=(t=~P`i2f>u%5;vTb2v();c`(S6df;&Gy{-iAgwu9h9JuFvx>i59PpOq;ofM*O*YJEI40|8k2< zIPZ2%RF{bNK7%QzFx~}Encer^G^Rf`U;^(T86PFtHXdqUmRea4A8$FISHU^}ytPc4 zjEjM{T$9g%>|f^Sp1_FcBvs<>O|#xSn|tjcf46X5was|y&wuFNp{8{z)k7uk-kZFz zj(8ErmuxFL$5X5K-Fx^BdoFLa7*}t1-MxNn@u|Llc`H@SIwt#uEC0R!|8LEI|LeaA z_W$#G^q}Clu#;F1(tk19r@qUBMAU;)^qhRK9@H{ce-Ji78eeUix*K}XmnO{_A9Os> z<=Y<3x?aZ`HYaePYN7raS1y+6fX+%R&~*eRknNE*j2%_pLR z`~3dj_n3Hf*m^17cZ%wsAm{ery}`P1E`EyLd;W?E5${o>26$k+k2km|V7xECXRX}? zyk$45O!_(21Kkr87_Ih#C#c=SW(ZVd`U&cE#a8>GFrZThIp6#WD# zY56mAv+NOlo_F{%@#^sM6|52bc|h8s2k-St?ZXbJAYpXPv9goeBv$OZL)m{BN%ueBRLk|2i{}!a-=*ui8n|M zp%e0{+V}Yy!gUjJ?#c8|B<9_s|8m+yzU1+464uc!;`n54E52^A?tS-e@Bd^z$z1f) zTdhXlihiz7>hrvd#H_=1Q`*$uh2598=Jenl)NytY&U@siMH7g4d%4!m!gwDli|xL8 zTj~G#p+E56!;W1ZKgt7D_h3(6Pw@~u@CsgY6?n6|?!Aow-WPt{I{|`zhU%l8t z%sXl#`pT=~J|AD#Z$iHH{wQMJ@7p!Yjm938xbB@QtmBJ_AIyJBSd%a z`0$3*=y5@Po_E_q@#+X}rsb#R{eA!6|N373-}wt+|L@YH2Sr2`DPuhd+yCFNcA^vY zpvT&G-;tmP(Ok^bunp2tZ}Ng=(1Y&QOgZcd`~P|8wxHEJd4lUHkE4HJr`Vv}atr7| zZ?Y~!g5bPBD)wQzw{eLQ*Yi_Is-fcxT!@mG;UX$6hDf@YXl>GBvpMm$x zki4lgfcHd=F+;poo1wr+%sAs*w=gBrbV_I$U89}Z|T42cXAoM&!1vRvSQXTZRjSgKNF-=58h#% zGqyPIOXPMbBHs0_<1{edvG*w5`+o(d-kccV{pHz`h5K|pP)ko^^!ag~;BDf#j(5Pj zj9NQp9`HUB*Idtmr?;*djCy@Cg1CFrWpiWKMAY)DgzIDjJjpN3h@b!eF8I0ZbN)ez z>)!o^bvde2*Lx~yB~Y0+12Nx#&5wUx5_K5sGWsLlECFdp6@4a3R& z9=tcgP`EDZ;W`_I3B6Enl*78T|YCXshmr6N8LwUr;l99o{jYavWWG7Nw~}qo*+9%& zDg4Z)F^P5jJ@~p(^G{q8V%}Sy`<*>HMDp&vX$b4sE8_S*1uWvqpYDD44p9F-J+$?z z$mjn_uavZATrcSJv$wc)4D%g5M5*BK{{P?Ej{mR!9yrDFdi0>Ur4`rk9@JJggG1DV z+}_um#rFSa5{7kugH-4+t(}$d4w9V*ubaLa;ekGG-K1&l#S@G?d_J0$(u@vZ-gP#B z9`qwulwZGsA(n2VE+)J+t-XUWq%!lJx)7 zaZSYWUD8p~H*^dv$wnH}=o|->nDl7%2l9 z&RakHC5wpn=Z3e}Fy8(Tk96}6@l{D11{0)_m&24%njWanV80@bSf0SgMLLoOycIOp z$r=Oi(w(FQx00ZHH{6jPwvM=akBvot{@j0;kFWb!)pUzFj<|bEeR|+`^n>K_9xtqe zE#ml$$C*bN>Gq!YIzuU{sTkkh@_h2;LsR|d_4)mOnyGkogjFt)lH1nZy%+T09raW@ z73V$i>S-ns?~_+1)nL2};{3aLyQ!a7@&ev3H^2W{H_ih+s(C5Y30`lJA#3j@1-ut- zG|im|yshR3Hh66|N6#+*9q=HTm^WYcotxG08a}=*=f$eY<7X1{4wJi;@g{e_#C7iq zVI6TIjxRXbGy6kg?|Fw^>}*e|65|2s6VvCuAN#rVe|`A;`SW1^zoe}Q7`x5t{t2a-M{UBS-$Jeza{Y-u=O?-+yclOA-Q{E*K zcZ#hM)^SC|@vY9j`7>ow?|abm{8pF#mqb4x9bU9A+0VJX@Asfe@#^r3eJ7<-(mg>g z?7=&E{5LtAx8gjR{zSa*EmTRycvo&(-pzZY=YIbv;5~lyga?CcVS{uiE+!iG|Nbo} zT?b&i{jab`0dMv>{oEi^b2Nstamf%fV&0Amua8o=TFuATHLzdwUsF$firs4ZS@vYJ zU@IV%_Ay-j;WH*Zsh?}@3vdo(?NX2)a?)P+ltDe!^k{|m1P zWP$fF=l2sv18>=Ji*~<2&C!+_Uv57hP0ZUUx{~E)ew&Z4+frNS9CDVJcX(0#PSsVr zC9Zo<64sF*;`od<)VzQCsQ0{MQ#Idzyd=g1X@2`^$|>(Y&zoc@W*wJx?rvT>0K5P1 z*@O50WADwwsqEhV|D8-JWy~z3!H`5rr7lw%WU3HlZw(R(l}e!yAh8`&?anKgZ|!efRzy-T&!0Z}<7`c-`-Hp6guKS^?Eb zA1Qdx4NISohPNmwD;~z%r>cfLocO%1IPoXgy)DRdiN6c_e_{65f}wi|q$sO3oIC(; zyT{1^iU9BG18Vihw6vjL2?~pCgwgRHFyXDdbGMpEi4$vgau58&`+vi;!f))EVLZIQ zB0459@{2VpswtGEAMd4B4{Gm;U>|Q;%T>%l%4uhMya!on({Z)PwCSi9dH!!rg|~mS zTOS4Qz7h{^G`tn<*)w3gKkPOj;~hGuljA(!5nb@U#)Nbu;^|A$-()P&0K)@ z(AqE3Dgf`qalgVhm$jkc57&d&64%_2EAi_hdhIPX_cZIMG~>PzV`OKPMeM^^Nzkq0B3LizW?{X z(y{+%e<@gE?WjB`+{D+3;z0r*R|}(gP}Nxf2H1nHMcS-{`+pH*&qouWg3LZyd&1Mi z8p7RszViMt0?B`u-OgpegH~_3dzlA#(B2=i3U!OLq3157&;nz058C$WWpT01D`Ghk zC!uxjXLm1p1-W0zDoMxrNa1{vIn}1mpebL;eaF?_54E?_q%V z^gG$yk6?SNvp!K}p9_J+@q~NnVt{w6!jX%D0B^Isv-noZfcyWPS)#URqvNd-d!%~( zoGPL%5?8~ut%j!_9q;7OvX74k7!Pj^M8_kH{B}m1=xVm0AMc~(cb{BIpkaa(wb9Ms z&P%4p8)r?Uj*Z18%YILgY^m@L8JZwa@P0o~D~N{oPW|NvVZ7(H^ee!4r*CyH>jHT5 zXvm8+@3DqngnZ!L1a@yblM<^W0p9l-KBtQUyaUHA6}il{Awt96(RLC#-pA5EO&`ms zBI1#_9;IgEL|^m@Qq@$q?VfES!@0LBqGJ8Y)P&_knMI znJ|5Wgj-IV4lx0XH9^03Zx2)99h}?eMZtS=X{-Pm-U``ATw%OfQ~~0(ghbGc`PQNE^ak7s&2S!wcl~8E?FO1auXeI2gRM{Gd+xl_fbU08I1fEZ;IG_*_D3011?^8X?h2{I2jh1 zWb?ndjp^N6yn!|yoBZN#Nc}#XXhVhf)zBPP3f`kvT=>!OKDN!Cj5pNT_iuPRA$Y$> z@ZN~v-GSh}WZH1tPfQ!ynj<53h7BF>VA6fh7l&RGw;*xX-e+G>_CYUB%v~x>-!UNG zHxL~MF!I}Q^Q^IydlCd|7TnE z|CQec`hQ0%4~jNfaE#(XP8KUA(L9Ld{H>Om*WmuYowL`IE6BFU#r|LqQuO;z{xjf; z-SuA*uE(AtkY;}z9#H~IY-kSt4hL9b-FIhJ^GbpFzYu4|tv~ERKKObYH?r>qaU&9E z(zY{+`y~1j`#FDYNB8CghN~d65FH~J`RyBX=E}cB{~jc9|Lj<jmkj_MHUuB{t>N(uSaK zFNkGGTnF^6G{+PjZ|yUzDGiSq5AO^_#}17A2BRlN>l^9EyG`Qcv#90Rc<(!)sPK-g`u2r__r@)8qG)(0gv=6#@h(gI&4U!P z124l3Ql-#BE!cxLh$*(@g9eGi%>H2WbpllHHpe)=0#DNR<7?UmJgA~9>{E~LC#X$q ze@@P4EhxBj+rpGs^a?Vx_FU}X%5vgWB+hKLgu%hh=oMsp2WNod_$`L3Afpi-gBbZ; z&g%%ds7-%^RH0LS>)>;25Bj{tsOsLrnsxtSdj3EEb$NOQH0jv7%KeCL0QrdB2`aqf z_#U`Z@D|-NEQ5x(f|ArV7;mw$qna?@c9p?aaRBc-_azbxZxbMy`AI1~pYbHIyrt)L z0Nx)DjUO8Vc+YK6(@ROvf(E`lu^1^tzyI$M$GJOA56g-DNZc>qot;U7=v(Y{GczKI zrtu7icMhWCJw|@RC9m=OJb1CM%J~OS_vhT^C*H%JAg$*R39gAEF+JXQO$BJu(Ys@$ za?9@t(s3%hV>>FAQSd(2RU(as_q5i`Z5Z!?_8bVtd)uehURQv(&n1UCgNFpjHIeXr zh@U{}zCZ9$1K=&&U#l|?@ZRw>%TVBs7W6n>om)2z9q*s_4Jvb#Du|DexaUJxk2X)C zKajR7(TuP)gYocYeeheyK8*Y(&c|C^tfU`r9ejeM`Z5~&f1j`M=d!by9&en&AZ4I9H)@ry6>3Qd&b;o0e5U97E!&af#cn z<)gcIP0S>Fw7_kKbMGodM>9r#if&c;{gL$J9sfnFVtxbm*IT%`Px1R7i!uN4mZof) zbnN6iqPHDfkPd2ZCn~&exT*D1@QyOyw+IdI8ZCpDFy0fA%QRrTN6KF5LjZ57noQSg z-2|v>(tLr)IRYvCior*C_7*XHu^issN^z;*5wcVp66{#0I@*Sgw-smlKGUk_M1CaB z_rS%*g~{l(_wjK(WBoS9!`l|o;f9glHb*kXx_b+IM{+5nVNAmC_O`=$#9`K-^*^h4YgC({}tM0^e4=rfaN^08j4SEH+ z!S{vD(Vi0GHze+1N|N$-8T2Lgc5a+Q`oma;TVk~l9SydvmmA0GyCH6+i+#@2d zX*eLAp4Q{>enOowA*3U#>#4NqSaDuR>30Qrh6?Yy0)p)nym2pjm!sjG5LHU<|NX;d z$aufLTX$$5z?&uXth(q;0%Ug4y3;iqPr6||w|^_ZJAG;|TOYvt`2m(QH}7dd_q4RL zW>nCZ*bV*W4nw<3iAhM@4U6g9o72$oUilh9&mP>f7N?zRceswW-piU{f zvjnDT!|vU;z*2ex!28v@JU+{40>t);^V`u3JSnedj-o!myYMBqSvSCYUB#To2a>g* zyu@I~?c(To*UuJ8NGmTT<|1(_@o9;z!RUC4b-QaEA7nhd+YlYgG4gw$XFBSJryp-i zy)`R6*I*xSVLdQg^Qn9v)8j2Qn}sGF-Z|@((nH92pQ6J1c1nyd1#ePo;8HZaSxkie zV7&Q)T+*<|F5r&apY~?Qu8)1z$@F;Rf@stsp;Es5cX8rEg?Ie%pd}Q%MF7+{!;?*cyGx+bmt?$TMM7x>piXo z$;HQ;mDQoUw=ui;#JlV=;&LR;JzxEOUI=>spD)DqlWjZW&EEDPI-X8bOzSW?WhT|>Vt5^!u_b@-+FO+D~q1U3a%MiTY`uF@l9evIJt5DGYdr*1MgH?tQ z#eB7sP~lr!=X@IiWMgJD`t&)TWUTnO8D3(0 z)^1dQm)Na?H_v=5(}H@!6J1wzqI*!z{;5kp4T_1qNZelh%(s(&_{2^LCw;0Ee}mzc zSR$fB9V5RLc@Ls%Tj=+oqs~8G4@+ZvkeTb59rKQrGrb3;ETm0Gf&#A!{t9{i?@opH z{aNAU7o_3mEgyaFP(s7o!8D%S|ML~3>%w?T{}{dA0q_=5h^cQnO@I=K3%})*;Yl1n zyL+|+yno#pPlX$#Py#cNL=J?YClYGju zAL(a2yssiUOfm91v9qYmpND?DWvh-a(Q3wSkZ_XbQu-|~nI3Q4BHDB~?bx;{;r9jU zZd7>RtG}B`ac_35v=wN0i>!Q1-o4G^HYMXdoY^=k2O1>S$6uUT0}0SMJ?jN3#dwmW zZd=0^fcN#<^Cq7G-X`PO8VSI?J>C^e))k=R%^6X5vsa*m=!V2CCyr(s*`wpVaeVBv zrAG|Ix%UD@$5xE|*o&*z;Qj}@w{y%w4zHiYKHl=V|IE~dugli|zbX>`Q~zCY8g+b^ z`1xw=_v@|asPImHp!AM{_Z$@$MKrv7Sy__d2C2Acn7n%%Sj9#R1bEk*`Mg|ohX9qD zUsd?=3{TSA^(#de;GMD7S!fX8O=O+A^{!S6Tz7fe_RMQ^yiZSiCrO?!AwELl#3Sk? zn*MM>8t$VG=a2y74JSMh9dj}AYwxXzvA#jSdv|1Qzk2cp4gG)Q*SMa!cFaGV;2x$; zhvq98`QQEjSt`7f4rS$2@b-MZSpg02c1u<=-rSb|j`!Pt;Jq2aI}^cs$6iaj(o0%U zi%@%(%}?~%TjO#c!)A{X;(H`c<=Vvg*#z|Mt%G9S%~u!@?+=I$M~wWoaaeha^3snt z-!e$X%^usmU)_Ovw+{_6J>CU{8)?#U_xd)-`|{uZ|39^A{;&QX-@TD6R37wrnS2?= zgG8g))zCa>{nm?C@Dh7+?!ql_gM|Nb&CVJ$NG__cEAdVQ=*g+5Gei~w>DIUJ*1N$H zdp0~zw;3$4k;gr9^TM?tAypm6fK2oyHsfKP@!3m-L;)mjX@_=nvN?JMx#=mJQp)S= z3|B$sB04r> zrG6B{;k_Kuu^uBoHz7es{r&XgEh&5Vu~a_|6{JD=o#x${OpiD2Y#D7j>a3ork}Jqa z92MSah4VI3@YX7dQ$@o&vu^MtjQ5gIDKg&2dpBJo0KD7x>?p0?Lx4VOy1caOz>|K4 zd6(@1c)uL?=5GOb7nRwb-dU#wJ(>tzyHykY3(`Rm>$u}7A?pe1!I^O2{icbHEC?fJBaqA#cWAlaRcwhGC zp0B$*n&I5r3egdck>86D|MCyr^yAIG-hd?Giv4k-;wyv9J(XHa@7{VxchICGS}kn* zeHZd@;ye}J53NITDR^tF)?S5%_t4N{^6{4QH9N?7zfE3a=LPV#N?X{$YEFPe9aO(= zeTgS6{*{wy4Dh~HL9F-y@Lu>;&{L;M3u<653OvY#j(2cvY;EIE5wQ`8<2bdI__`Lo zIH@&yN?O{$cz8!5I$ALDJJMRYqD+{6yxGcFJ66^|$Ns2s`>Iptt{5;q-nggAH0ju# zQz#gA>2Lr4zuLF|r+ztTkT|G3DBIFj1@@rTU_knuJr0NFLB|v4Il>iWme^-&AA%d&N4ge4+K5nZAM?122)&qC>2af4j)O+i?HSPK9??@0uT!C3gG9lJ#hK zrwxqmhw+|nuOTn7BX=A_t^vI3-A$Lr9Vb9~V%c3=g$bmIEJ1Dffb_M@Nm+RQuPr#% z&ILY@cC2dZGhBwg#M%UWu-@uMBsw5*na{3p&Kf~qVw*Z99L2sf9^S_h9qkzTY06gX z$QRJR#HK!2`#m-QyMk;{?iuoVvzF=c?iQgiW@Wd9vUn1prTddaqeKa$@1b4a;N9EW z6VEQa2Y442Db|IY(t-*;8^2xYi;j1(`mmQv35l48#64E{k-;H=?%ogmr>gh2GalZr z5gi#A`I){Z6ltxb-@SKerrvUTLBq$19+hgVUuQD?fE4Hdf;Js5Vg`QC|08Ep;r+z? zj06R5?)24b(eNhaKe}E;fMO2* zw44R{e?f}|HxuAN6+xC6ZNP(YH`^840<@q_&HUR8|FFeg`t|AKsqs7_C2l&0cS-dE z^ey%_U-jF!j)gN^1zCmY=)uVEz3Pv(UU33+SCH1LtaOM1H0(k0S*fD;|B{MVvI_k2iIg~{ z{ma*HpFv+@7kE3yOTJ?~yq6(5gfa3<(=PR3JtRms-d5rn3ae?jL8|bQQ>^fn45r6> zYdUQ@Qev`h2Am@I|6Ejf=cNe;QSfeAIyM^(?^|2qJz%{3)$Wt=KD}z?_iTXot}mw* zpd$pxBYafwAi!HCjgSE!kiI?OHw!)>omF_B#U8kKP+8L(sXuIQ#VK<=Dibdt1|o55 zma{f04WZ+mpX6#`uNlE`?tKr@QG$`5TKS@0-B|kFyT08xAWagx|Mz^UH^<<>W2VO& z_kuPZ1F^&1PT&S9P@K%6!aLXd&}$0bUvR}NXn60PdgKG+EwILteEwf2N!G9s;LWG^ z>blTD0>n4D(D{cTf#iP1>Dxwt_ZPuQp)r8>`W(6IEZ4Q5b)`1zG&i8Tccb51{k_=* zL^UKX`#9T;DK_-t#CqZI_KbAK!@CpFaRehjIbpGu{&xED=KT`hu+R#-|1bA#t#~ef zhv^%nr$V&p_^>)|mD&?B-kel;=NR~pQ}EU-x;hID?+0FCXJNc$aiZkeTmPqZmRSJr z$=d3tTDAnp_u!kZ1mNCz2h2BU1H6r@`@RnYykB063oZg5C$g-T?cIM99q)DQ-Yeg1 zeMbDH`a4ektLM`5+tKl!vT*8h5@x*Ngf60Ew&kDmyKHz#+ggnN;$)y?yS!Ks4Tlq- zr?CW`%3ylDagS)!asTsjFUP;{|1o60|Iehr63a{FK_x7Tr4$d!uh5@|=0R$H-?zXX z^dtKPx&L1;ald#T_{1(}>Se{5^91O|=0P3@aR0v+&xg+kfCp(BM-RUM9<;X1V%xB( z7Q{i=D*m1a-Gg>7TjrUjokL_t;)s_ecZgS_SCDxJYDG_<3uU+p(h|{8gpprtL7I?c z9sNt}#ECw=)EOE)=$f^|WC` zgckJmKZiIg1*ES%OBK=X=XgUgAg4rF!GzVab7jg zb^7rxYN+s*>Zajt{@js;awP4BuByf2V46bG`u%^ z3!1}t-|+uTe%``}@8x#*2C2pUN=J^IB|xc-Y8D(5c+x($Km!86`z^1Y>T7^E*U8BT z_0d{TG*lX<^8g+1osy}G8%=YGF-V+ib}P%=Kj6K0q<2A>W*FnSH=^SpMt-)Ffi1>ld1@E_u z^ElD)4yfZMz<6K3ZcoO$e{4Zq62Mzv!I$jC;P#frsY{zrfZ>G5FRcSs0Pp&zHZIiw z?=sg0TZ_Y5P$(PZSOQggp#FX>#l%W?VxzZEEp(%`q_gh3q5k`KF z-FK%Plj(PFey+y-`p>Ypx7t0fKU6hMVEP8h)bkomIyT%@>=6J1Qc#?5Q{heAxRCsM z3p{%}z1)uj4Q~U#vBNOl=RW*)?^PM;p(z0G;4D`ALnjFk>zjVPWtg)&*|E21kq4?Pb5hbjxztZx3~i|>iD{>K>^g>fA9Zeg7q1A z&_XH?dcn2-CS{48mNDQ%^Pte93yfh8!gEV)gg=mOC}W=wzyDWiRF|dz8l+XvY-ELA z<4Jut-jFT=51MW{nVbMT$nJ1&iD$DWbULj%04I&^K}y^KV$Vggh$oOZ2Wv6EWv=Ka zNb5CA1b*0FWw;7b1<~;VBfl-BA*I3F=zoJ$GVuJ}SAN)MkZ{QZtAu*LmW&Tm@3UXk7Q2z7HOPGE@ z+A}MVCLLX^%5g8l$ao7-;awiPwwQwV&5i8~(C~inbF&_dch~g@^80_kPUn<&0le?# zOADui-P_`~3s{T_@TBCp(}|}5-XXzZK^XvVX`RhRwhfxl$saPod86nzNOe>a-VVw< zB|0N3x~=(eQ58I<5)hecEV}-2Wf(+_97m3@5IX zU3j|{od4f3Evq-@F`mSkV=-Z>2ybT?^tyaKbc2Q ziPw?1wG|}}n}49=J!|1eQS6=&hI8*bhz@p){2p5vX$)~pt8g=ZJ z0(b{&N1i_e@P5n_8L>VSPkQ6*cIyzpJ7R6>Kn1{CFI?ij?p`hEc`V<73(Dx*TLm4T zq#qS#6DyFoy*ljIWxk{L|DEF&Jgwr4H=HOzbo625cWT+y|HY_0==Go|H)V-+F0_3hcdb1-4Pcn>tsRsA|w}v)&-GM7e%@MnSRay}L zGPziS3AzW>H(3-vQOO|AN8}PxTNluoRmngDC2RGE-oy-IHWC*%=;7x36@7`#J8)6%pm7kx;XRD#D8a~YbJMJ1 zx&OiTRwG8%5(58cPa@g<~uP;175~0HTRhBUM25Gp0Y>|2= zh=%uV!A=9%z1g>flV6Y?V~@=(0C*ejx>&ryiU7?q;G0vMgD1tk4(ap*c+bqz9%i^wco*$$U9<_YRa<@3~ttllTaUOa68{?Cd9Wy!k)eoT!;*JiMa#Y zTk=!XHbtKP3erifC=i%|Z|?o~`*LB6!2O~>r|lKF{2WcL=P!uzFdk29q> z30rYj01fZ$HL|;5yki2n$asfk%x!)E@E)4+D3f<1K=FGmAFq3dC;2Hn!CwY=Crw)A z-T-*FT|TiZTuloS9$^#cT!D_a=BZO3_Qhrr`H;Brb8H&o1L%0`Np+;`%DBRC?yZC9 zFv7^stgMDx&7J<@+e}wp*7_GUx*6t$`y;2 zQt-BFI>C>I_qDT&$#~DN_;>J=|^51Njet$bYeF>yT-XG!W7SUiUAK_6Tjquet68E%QiMgP|E2_wIZ(=H{C zKJsDq@&81M)%+mmSTzk3q~rJ>>-$xie~CR$qYe?bYpZ^r|6fFfcU}2$cM9G@Bh%t& zcwb%QAq(UEy+4{fAmu(N#|=Mk*&p1gYEp}b-u9+0O+Esi*j*G;b^+jR8$a*{#=9zF z`{3?LO^BmZuj%UuI^I_NzoZZOJtodZ;=JnA@llcJ6=Y)j<^wpL0EWZc8qx6pBfqjH zmHgQc>Brkca6puA4h<8epm6;ZdlK{GeU&yHJiJwMS-&Spl2mxtdR}@;!CTI;LJSS> znA2}oz<68PPLPkch%b+BEdqGU@Ql_E4d5ZQ0=+RCdpzk&tD`xL_kvga+wK9pkL1+% zm``a!)_Mvq{sZWE^Dhfv4;y?;+>6A0A0OK!AB2u~h{eyy8x4$y_d-O+b&UM16`Osk zXXwX!uKJVN@*3C^BwaiC$E(D|nZEx&Y)P9AH#;#oDK~P1BteCDjpdOH3f}zM38H9t z7sUImh4G#|t4GFr%%HsN1HfBs#!8`N9s$Bv3eI;wiYFDXT>9xe!29`;wdFA0p`X_^ zuH(>xa=pYH+kc?rjbE$wZja>?Vg?d-l)Wo#ARZm>t*0-h)||M^aPGYy(P4y<_O>0(kS* z@K`TeuLX&RYx{}0qHk|$`%FUHN}mvgkhnI^v6if5=pQFqq>10PpUZf&H$6nhevJGM z+|0asM23F64fU2D@|uOcdyDhX2uy6yWd7o$hBh7NrZiH={@(xh&sL2we+K>k5-JaR z-&5#8@u1;wC0R5NTC?wL<1gSr-0!-!!RP;D z*_Ti^;6YVB>G=fyeZ zu8}K9St`7na@oZxc(Z+dae((yH+SD4ZUVGhY2`i0 z2v2gplcVne@Xji=&V|qaI|vX-Z)-K7)%e=v?t1hJQbRA~rRI@z;wmKWSnJnv4LkG- z@=d?@7uE#E!&@8C@eU(DOa1_FjV$`{-oBfQnEHi=PwZGeZq*Wh#PoRM#Awu^#crTuOgOp{%E3+0*L8=d$3X>Y}(ER7ZHx^jn zNh`w_2*Le7VW-<&xIsGGTvKy_UkiG}b2PB&9C`)$4Vv4XGVc-b6%uDF$u0PJDS8EY zqbJJYlC&Sgx%YQOM?6M;=87{fo?W0HZ`hkTLxp$44!(~Ryzlm0mO{f@)zF;_ZjctdP$J*n;{E;8tBU~d0rSolr|Wp=Sn;Gs z$d${Ez2GeMUXhbQsWPc zWzdV0hliE(d=waO_I3`@@fah&?i_Izt#JC?+wy36$~783PK+~s|7XmG{~uX_{$HNTgFZI$s{hM_Iz;8sJm^JDToYVDri*ElJ;?H|k7pfd zkX)j~GZq~pK%Ck;#ah2vk>ZNt^+U_fk5g^&!agE{Zc+!@TkY{lJ-;DQI2KWE>4dX1XrD#HGg{*}0kI?ZB z4(=p+K@W+lNZjc0q~vAF=y><5ew@6$*N5TojzDybVB~k9_LU5)A^muFXY^E=+@PWV z@A&qsVkPt6AdNdaLYofWk^tr36Qt!-c(=I_2^74=m**}+!+ZMnsTVNbj}rEhcW+gq zE{~=Iyw!`{e>9vSKr>5yZ@rYjllJ;$3c$O!+wkYMr2@Q{3O)*x?$U(%PdA7~>Y+DC zD`gjEjJG}{_EO>$zRmdH&>N(qd{w)MRg8!C8bpT+Mt*ETJNLK<(2sY;`C6H{&)6qO zaXu*vR1}sn{rn$iPn!;@kyq<~rIOuy85Q2GnuCHAy!UWiT8f5ulK;JDFy2Oo!wuo# z#7?%O#t{H-`AekvQ9cAnsdF=L;5u-$NRu5i{67;z6|HyTM!-g82Q~#$xv#Rvm4}kms?>+1+hVZ1%>oa=K0=%!R5qg*g@IF#^I$F9_6Pi45 z`Z6ycI^MISlH`wwr4h%FIJKg{q`X}8;sj^=_37>>jE6S|qJtA7ziPGhjSW)t<9#LB zOwn!%d-mq(uOG2gpZVwio=vpr7>qge0U!Oh|Nlp)&6q!e{(mKv2X&XO`NNH7FNRxU`w<;4 zF!G!KCc~s6iI?v4|9kiBtJzVG-T!-L@p$$5-DUdz-}449O*#(W_R$M@K&~K_sPOK( z_TXPz?9%g^mC*1ukX!NtUSjJ*LsVhB9cN0`xdOapzg~SRqYtjw^=&JB{nd)3cyik+ zc!_0Q%$AxC@XoV2+Tm%g32ikn+cZZA9q%0q->;B%r4Y9uaUG7&>ypgT@!sk0wnkXX zo8j;_LUdSQHV4z-xYs(&c*0>&t0EY($$qhzH30F64@Y%Jg#q(O0_ zNQHN&PT?>GZ%bDXMKrt{JHslmM;27EV&Gvmz;J zk4nI|x1?Boce)Mm_HT%_7AV$)Lh5E(mP(^HNSekQUTB=ZPrQo6P5uZOTk?m;i8S3D zck>7{-f%(((Xj<1zkYtG%$tLLycdq?)V)-|Zjf+S!;C&T%QAg&f|CiQNyoe;23xXz zKX0i(g?IbUjGq*|s|~dk(C`-HXl;Y>&J$cmzTP6Mdiur(fcFOW_;mAq1ZZ8Qi_hnF zE7Cs2YlYqb?-K9r8g~KS0dcBDxCu?@kz&=W)?{?N!@c?Dlq`5ae2By)6k8-UX`^p% zJ=L7K*6zu8cwa|!Jj2K@;w3r5+Kc*ZQJMlv?Bew&!%P#Jm@Ni!pd4Dp~)&sRt;#hy)s@C=b!!<~c5gmLO`Ne;n3Y48ge}i-(xG^qv3t)@MiM$7F}vn zWV{1K4puY+ydP(Le$!b39!M{JWwc?&id4(dzZrhsQgQx{u1bKn!^KO40}T)~9$cw2 zp^c8W{|-lqQ&1A|7ZPVFEF|c+0v&JPR&y@>Ii3uMcMzf@5F@|S*FA1}*3ggl$NLv< z*`;CQ%_VVl-jANeOy3|yBwnFOhse(dg8RW0JHWkFsPO*0NANBMZ?>;-s%Ut}cNdDl z?p=P%MGgt5dcsoB((`tpC*|?LvSK9|#A>OKmN{TT#gPR*Vh-3g%nE)4+iz@wM74ho85&v)ZE>e%_+aGGvAG z8ZiHF*QtK-4jpe+Wj)r_&^_W0Brc+@=}7rcboX9i9@f}%mhon99Egt982R-je_P_w zML*ti*^*U*v}w3|tNuq+CC@^p@BeWdf6}I7A%`b?_txM3|KB=o#{2rAC-pj)@r^h3*#-hQ&U0!;GH>nVJ4~{Ja3W8 ztt-)DMKWKtG0qa;t)a7Y?puI&#gGSo_%2Q8a)$eg{up$;ZOhb1x18=0Ly>;~%=<%XuFy2{jJe~^yyag|H z)EkWwpn8XaZ$Z6Qq}^wa9oz@-9`WJnssVW4d|r{(YOD#dN`1*QxP*@P!nfMB{Oxy% z^N=|8w}(XK2GHGmEL+N~OyoSn;Vq8nz~%foKS6D`ZIzt#yZ0KO;A2`#un$OkhIKCf ze)bvj<6YTClMdIP9I^|3!gzHwyu~@wBw+W}_`Hm~d&?>4_gWm_ zy|`S~F83D!GVY%<&wkvB^vDF=^v18PctP{I?-@@t9ta< zR4zC3OGM89psxJiO%)9qJhQ^$m2UUw=!# zdq)_R=5IH`zTQH^2s-rX7W035D{yHeO**_@?zm&~_x^vhnwGKt9Q6O2s61%mp@JOj zL2&=Cy3?E;&4bkTo+O_^>V0*d+#oGiOIf4@_8@nBQ8?K=a{7bfi(78?X4%(USsYX>@_a)z8Iy?^b;gDSK4$G zJXz~7|5+S7|JR_xdrXt~hJv^Lz|d?oyloTnf5Ldn4}Fz_@jkQnUgQOUx3}q~Z%Kg! zs4GQh;aIU1DRq#&)(YS)xGVlpHNe|t6H(K&7lL#jr8m52M6V#nZiu{)u}dIsrNkxO z2pStluOP3@(TG+KWIVioB0AzR@_YBIcVG`Y{q8O7%Of))gx&wo&EOFuvS~6s-aiUy z(~)Q;=C}C*`FP6)D!jih9{onaoA|DZ1r6_$9))w^{+}ynND{`|NxAD#KEPW}??F*$ z8UZ@!kB{gmvLZFyTUcWO@O~Oilzs>B=CuqAYi)+0sFv)3tXy=wTX*EC?|GF#yotnZ zOTVk>ScQ)FkGG~{OGVun&b>Pj9kbv4IlrIh`nNsVNdNAwtj$A1+j{KdEja#*tQ;v2 z)8ma(rcFnD=$!R-G34T8Jr&*~pGqbuc(?cl&qBl7YTR`ZjQ2WU#YHgQiSm~u7J%)o zUpr00-n9~-bnS`H=bl@UBrdjVnFGA_-uH+%0=(bL2lPcLYC^*`iHEE7(TkHW&h_@Q zqV5pKkhoVY(pxu0qwn7S47(_H3u3(4+X$kAHT=){&FedAcA}JiyxG~#>=GNrKHf5_ zLTH%HR>AbMx0c9#H0h`qs}wc^cW?il|1(yr|KDZk58w*&Dm&+L*n@0ei>Scw|1~U`aoNTPuGl%XMEZ^>o}^uIe8L`h(0%A)b|LT} z`HXONHWy8ZtCj2G(;)Qz-{8UdTjmGiiSv-SA5R;Uy_TbYgG7uoF!8>1hT)c2V?;+8 zMt=9W_Tm;ip}&GOH}FiwzsIg1aTU&+PVxpYfB!#qk|rH#i$i_X)5uG#HWl8}_TH~3 zOYFv{LUYmZKD3IE4dZ>M!jU{6l{6CW$p(0@?=$&&O_BiZdp_@60}Gy%UAD{=#v9ty zf4&IdeO_lb*W+WFP_$q`fB7+Vyie&ptBQXTPmDq0Zi#oOTk@mhy|~hedp*A^!{P0U z=#ay|Ht-Mi0=Bcv7J?KWN`F0g_C*_a-8uIaWS#Vd%U z+5x;9Lo;_21H3yb?9P5W0`Ts9@2I#79q;$&Z0f(W-6qB$aW{ln?N`r2$9wDd1J8E{ zG9KP-hz=u+{JMr4Hcutc@7`A(Q`$DD(cs>}6Gx+b*q9z~+!NY#EcbFUb_O>{gW^P! z3h$r%N#zv0vwmf8qTwxRDOm&K{q5X5GTw>DmoDZ7{r^$U^!tZ45ujHqb|2qeW<}bo zxElxKt*0|BRRZu{XEP*R>!b`yYHBl7EJcx7y%jiswRQrY}x7j*Qc!WBAGF+QVna z?hR4lJ=wg!o`N^&wI2r>-ig~6k@4PP^6z*%Ab3~(1Me*e-p_R3-@dp=6S{G#Nqpig zdjCJWSvUBbC2(&fZq~%=jG}kw{r>~ghKJQ`jE6S|qT>lhe%YM*5iREQyZ7m9^Br=Z zVIObt{B=Q2WU~&_d3a| zL-U}1^O0nDiH%Y?MLz$p;R1ygfC_To}gEWok z(8tJcam|_Ay3X`_&`3Vv>P2DfB^GzKvtVncGt+wzF29>59V|!t+E(uLg)7J{RCv#J zp7y5TotMndi-z~gJevd&9wl8ElFp>LPI?HXZMeccah$>jz|hCR8yV z-VKP3HjMn@;{~EU{s$MNmGkIS32(s0drW!#u|U}&rpH?`dJ|1La-u^D-(DtHka|>j zvnby#q~P5x*s=f(Z^@e}F)-e9&Ki&#r2ER%m0p$Y5ZTCCeo^azy2ew%> z9Rqlu+~RNb4B&m^z2Sm#9Z*45%a$c7q2nF*^1g$M8_NY z@}F@sqteUt15zm&XPR`_ww-fJ z4JPBQ`(Jn~&QweIQtm#&Y-BP9;~idX(UH0dTuwYxsmjBSj`!}mEh*^&@kD(jE?HjwS7IbO z-WU7JJHuBp-t5f`(Qz3gKduLg$}Lm$<9$SSD%W{}hHr0&3Ys-J$C(~)TuKpbI*RYl zTlV++e@5%{|NDGEgJkeu9<+k%?(AHO2i>}~Lm1727DmMQz#jDT-g@^V+3D9~D)Erxj-}%BUs{p27`v=I2k=g>y^{|=v11$T{Y_j#6MFyQ>h5j4=y)sG z`h^WC#Soj3xYGT4Blvi9ywlpECnus94{s$zM;1nYmG6#n2>cJO*sg@D@5@Z)lN@hZM8YGIQ@+kv7-)a-RWs$MydRc>?f`)LOoMmbfO=_d0IR!CB~d z`!qFwQ!a@i_9Jm~`AU<9E~Dc;eRkE$`q?fF=idH^4z_cD&QFu~zT%BV^t<%qvO5#<>$p$tYe9;NZb*Ju{6#^biCgYcb(Qf#dvscLv*xa>1IC28u&9|{#E(hR!N<@9? zzNjX2(DK9k`c6~SySKzb7u0u8#u9CiIM33Wa`}Vkcy~=jo_*cPcz7>DbPQtT_j8-c zlIi>O<1M5b$Hqg;(USed5`KJB78^ppf@~nvd@L0h!>E!w6ite`cD19gQ^m?q~eb= zTm?zd(T$N`?yTS~*^TsngS02hLR*)H2@-DO{x$i%``MUeg+c}A;{o1=(T~Ge!RG*9e5*r;`YS*guE#Xnbek6|5Znsj689Lr9++#M9 zIgE$5Dx!lGBR|9ZCB>?u^e?g6Y%{Kr^4Ja1;jo2AZE@vHkGGu8a+-APP;hCE{XIc4 zrowx^m^?oP@6wJ6F*LmUAGz4Tc1T{?+-2LoEC^C?nmMpTs|DY?Lxz9V;>NbIZ4S=!K^rZ{aBkv&zpjOpx4s%e_Xx)uqh-&lexsbm-P6to(g@ zs}U96^Lj)KDR|qSxF(8*ci^urM`674Hdv7H_V;mCI0x`ftVmE?-gnZP$ainuh&@;Y&;P9mCxVl{;~|Hy-6w^9 zS&_2s6{I}@-q&Vtb590%-&flsL+FB_>r3C;@@JvDcd?$?@ldfF#A`_0fGyW@twrc~ zD`aLaKUd3mc$XqNR$}BQQ7>dI^gnR#z3*);LD z|7Vh=8hDU7l?N?6d;eb(q))y}WzjrHT-jR?_Mq&~bClsNc7AK`SuvnN;<8;XeL@Ia zv3sUH@;$g9-Li1DBwRthm)QCgt{~^0^Gfzk0u`k4!y`#m=pHmMobD&u6iM8V#Jyc} zMl^2&x(8WQX6|eBbYi#)lA^;3Bfp;bac*ZP`ul$__YfI}A?yYTC*F00o6Vm2E69DH zY0^=CsO9z1RPqvQMuoSa{&YNLi5-&rA%lkZi&*8QFy1QRt}9@?9Sf?tG6CKK%K zd&w* zmL))@+#5J&U9lpSXuRU_2YBB)Q!N1R-ab_iZ2Eo|f;czYr_Rej$GgW=)G#OW8j&4| zOaAPziBA|E?{~IJZFzXc!<(X`0VBWhIfJK3!}Q~Q{XuEg^m7_2$OtDkj>Jl)#~bJG zNSltyW%aLr_y4=8@a7k*wWHv@rLSBH4exIiE&4Ft(`nbq!wF{#T-z*gL7F+o)cZFu%a#zxXHg9n;{G5nB|JQYXndYi^ov4k( z#jNb}E?ABJapL875i|3$7!PlXjw=}XMGNoqO6sB??^m2`eNHXdx3}PAU*WQ1TA05< z`qWO7j&u1rc2^Gt!TtX(D!h3gZB?b<9XrQr5gOj2igS0ucw3)7NXGkul5G|2-s^1V z?|8e60IgWtGk<}L6-jl?ueY#!6DQkO-Gtp+X5fY!nitb0 zr-27m$}U+8SCFv-Vh>G#2d(svVTT66`Tvk=^X@`$LHehxlW_mvBJOGj_y3=gh;9*q z5TrQZA06=ty@HfAciCdt6;51%#BGhVk&oDe?m;IHxO5voI?8Yj(o#f+D@J}l1HO%^ z%+SBY&iyjQ_9Gj6iyfDD_GCS2lKGd|^RBe%Sg0pbY(suxXD=1rV%yvnQ1IT<*Sj1I z?~mX7dtkg169{TB-t5s14VD0JJIey%uQ5C{=S|>i=_V^uf6gAoivaHx@^iZG0KDhA z+&Gik2tkc=cw_=}(3e>V!MK9)@E$>QWMbrJ zzxnP)(XI4XkUa)|M%BL94bpgB_@M*FBTSEXUMg)m%v~Kn+Jg!b6eku`cni0(JfYw{ zIu@`L4e##7W#cg3s?|ZOVZ7_|-|syG@ZP)6c3vDe0lE=>YDt9pA+}dyNtQ;ZsMji<8`uAG77GYnZ+`iK+NWla8r(_iGRrR;1bLUo_$4 zExC`vdf?+N&F2jG7g|8jcE^PdCmhjhZ|Rv2d5$L{iTX&~4ZXN|lG*5Zx6g!%)eSHn z-V_~O82KH{AM+4+Npb1j|YOFycETPKmR_FyuSB z2W^tK*x}A=&u~ku8=^xSBfo|?-Qa_*^m`Cww1&gQkA?|SNLsr?HXGAdkhn}5bv)#= zQ2jkYvZlgYdcBDxWr?le>rq0(d(Dz>EpP?N;ZsOnVmVYZ#=8LCI#sVCaF6hiYQXtr z^5Isbw8-t;0RV5Cx951^Ep|64`*GWF2zr-xz&}qCy+O)0Z_@ec4Dd$c963fdb|s-V zNDn6XDnhR_9^N^Kjz<{zJ(1?R@GG2typ5MB_o?O6aJ>bqQrmIyQ0B*5f;Jsf8uR_c zACoIc0u|m;xIrfh-h@{VR-oan$?ww$UQE<4< zH7k;DzW7i0>#dKmD~#az|FP_&nnwWM^SQ3R`N@Zl_pvLhKaac)BU0j&RX_EuypE1{ z->(gUa~3%;oO?SVI)*Uv+b>si?6?{I{r~cP!Ai%wu<>5*6Ce^-JI(ZXPXyAYW1DwI-2!+=x-1HHih-cg>|oBFf52O8CTO9RVmOf!m!ICYsp%Rz z-qRvi>K-LB9^Mj&j@hDr&TrkZkU)mFu$yz7T} zY0`0Z<4RrCxC?*h|NnQl&3JzT`v1dJ9<%l`lmVr;;Cw5Zpr_Tff50V@-(1-*cw3n5|y6*iZD8X>`_#G$o z{$I*u;*7<-5aJyqZvCq8GTBGy{r_^a+W}UxwhUK6QgkR{zW>ACn}^l3hyDLsb9*&wq>(g|1{F;!B1sdaQoG$C2}w$tG-yyFjVd82C5cEf zWpAPkkxFPFrBDf>LPfu|wzZyXU+4F%v-W=e+WUK*^Upc&uDk2H-_FbZ`P`prIhe^p zc%S1vS1I@mYLIlU9k9LOL2Z9GUUnG5d$aiG<+%{vpRZPXh2J*=N1n?F`>nyo`=rBM zS4EEu3L1ClgPq!iC~UmNGOrNZ@>vh>BE*LzPJVswcYd6EmwCL^wT)tr1NcKM;nD`z zfQbJGK5yB@pbxIZ*E)Zfw|wdFUhsAE1{CkrZH0PRc!^Znu_qtgA z>I@1RckA4ya)Y3D<@u z<$NUA|NDQPjQL3MJN4bYoVL8Ri4Je&XXZyxyf5Dg(Z#}Bz-0UlJUQ98wwQ+ZMhQ3l zb_j37byKUC7m>ki(Y8)fp$FB@Q0(g=2yfkjZ`<-AyhVRJZSw{}(B!z)ud5x{cx&v= z1}2G_6g19JG@Y7if!!bhxjCV`vsn-Cg@_MfocsbcElM{ViQ;c`{$qLzef?Q^BS#bN z?=4df5}pW8WP7|vS2E_~jlI^$$!OZ~79Tpi=NC8p&)j?K!gV@Wc-!6)c?;wHX~Pih za^iL4@Qf-5Z{L)nB9}BW=+HDYxbmW9zT^sOvcy>}x%igEJenXm9{$7$xPcSFgd zSpy&NCnvRivHnUv(`?`WJ4?qgxsF;?&CZOrQpdH!WSN9oqljbjil?9JE0idIzx2f@;v) z4=*^gpc-_4yrxlD9t0OH{~`P57j_LASnRwyp)!rK7>P^pkg!FWGPDxF;<1cE0XJ<9Ov#K!yO$X0>?v=Dz1iOb#KAT6>S8}HbZ zBlEvDvmV~h5g+k5`R$wXD3QIy{197dS=HP28Gne4OTB2G5X=7ke_Z}0hJ0Lje|)LK zNm_%nl@4#s&)-K-yoZ0~EyKe5MxoqO7;pEL3N*au+V^N$KzN^DeaYoxI~k+~eRn-` z)q@%<-S;yC!W%qO5S0z%EitY+z8`9k9xo`G*p0pa&uQ&bqSbMjVv59_UE#L3QULpc zbj0!V8yrpjSgv}{LVWDS$#4GH^-kgc!~Or_2Ntc3;rP{?kY-jNAISda{|WVs`ItV& ztpd*73!ne@r^8$0PDnf&^X?AQg^LZ zW8?k8)h*rU66@g|h5EqB&oQK~d~Xx;lapr&j{_6+@caLZizQF1-I-zg25Itu6hl7h zZ`YHS1mwebZ=u6meSb(eTD|Z8(J{oryIS3_%%YMpzU_H84B3f1<~r9?6{HM*(R6I&n+TmbaRXTu<(U@b)u&H#>R<86=qA{U!9)gX;4DTnO*~Z)S#a0Ej>5+=-z$$yu(0_pJ9 z>G`w{#e3P@QBEwpJDi4^;Qs&jimx=hCFD=1G(&hBD2Sxb1d%~;0m`=J)gIKd5lfrl z2FW43|2f?Mo4Q-aN3I0H5Q7hqg$~$wpRE9@oOlmW!jL$r&nZ8(2C(stHoCsAR^ON9 zs&^UUBNivW(E{V=8@idV-cq@*;$x39FoTpHh}FF|&h~f{%oy|W;(Q{}`|tA>JLvG% zK6lv>#e2h*TO3$;_sPxNqb+YO@7ID?Z@Z5B4jDrIf6qnZChbr%xK^(&Tp_}PdSl+< zgV_+?PDX8~G9bKf+;}k<;sSzxpD!%y_Qb~fgyOG7EAtOgwjyy$#N;er|H8(bv?j7c ztC02ZK8E-p`0w%8@|W`$@E_uj;Sb{X;dkP< zXc)s0yetfQc)_f*>T6~IpVtib@6TE}G zUA&KZDZCeXi+OW+_w$DHZsR5K+VPt6>hdb{O7imYO!AEI^zgLs)brHvl=0;Ar1I?L z3FPtOSPAVxGT7ib06l8;|}Kb<#y(_;x^)5$Suz; z!p*@o#`T`7gXA<;ya|x#kr!*&#W18bLM=wVk$32c(j&hCyjzb(V96=mD98MgT z97{PgIAl45gue+72)_`1Abdl(Qn*k!LpWY|x3HhEtFX1OiLjQiqOh1Sm(YaJpir04 zVPlNJ4f(=0dtc%0iMte1emLBZ57GErRueHG*Y=`GTo}dj$gp zy#&__t`sy7R1=&dC?N1hU{v6(K)XPrz%_vif#U*)1>yvP1$+gZ1*`;&1QrU&H#L83 zMW^(FoID&-4|gnTmfofU>_XM!F4^Zm5USvKU?-{`?KXM=1fuGp-Oeyz2dW+{Iw%bU zpsH~=cN*A^s)mcEQNT7--HYS<4s1o$-3>P~0Dn}~t82^$wxH_v=p|dg4^`ABBIkh3 zsG=M?-wXJn>Xz4T5nvOl>NE$J0Y0d@F}d>~;Ek&5ZM8vw7pku1wDSX=sJgo4=^22G zs#+ah55NOeHGl3J10+;k{&2Dsa7R`3asT>%kFWJv=XQFU>h_+`KqRaL_K#Q_&o zo$q_v1306q^4!8UU<0boMcsTCs*}eaI|A0IDs=0P2G*eJ zg#HmvzzS8z1>Y+Jt5H?(K&BP2MAgxghPA*dRON3zr3I`+Ri4SI{eT6ka)~_?zzS65 zJUy=oEJsy#34cCdj;gHC$u0myRi+iF2biHMLpVYQFh$kju7DkY398a=?w?hs)M$~a$p&%Qsq?)fTgHP8ED!E7@{h<#y$lwK-K=NCpmyVs*+q&I)EjpN|g6j z2lP-C|9R;LKo?c}8Y52tI;e_E6O{+FQ5EY+lm-@~D#m!k2hc**-k&o&fkmi_>Wo(d z7NRQh#J*dACaNN~G_(U6s0v@}b_P&KRT$@j*MJ(TLfht80;;ImUG~rfP(fA5?v-l5 z0#pTC8O{L8sM;kYVh7Ae)z04SIlw$r1=cK=1e8#&oD55H06X6=5fU51%pUwgD zsMM4g5a>;;16?0QZ5}s3NtPE(gR=<$fY|KOl-Kx9Dw00TEPf zTHv-^5l~sD6 zCol_Dt2cb20t8f9Dw_8aXHd0jmXA8|52`F$X2}wNqiRLg_cO$4R4w-zP9sjC%3QC= znK+3mkXN;p_zP904~qneKT%~;*jPaPfhyxIGqZ^ks4~(oH6o6qY8jC9hB$^Q!}ixz z#P6swxS7aJ{Dvz12=x@=S5(34?Zi=3!ON4xFQ|f7bBLc&1vkIMPpE=>1>y**;8T0V zkEntVIT43Z1)m8a4xtL(LMINQ3f^%fen1s`_mB7_HWL`}qY8fI zlGueR_)$P&C#v8#)QBCZg1=@&e2FUf<1fS)sDi(hL41xX_|pQ!c2vPHu@j%63jQWC zu?vViT%( zCYFm4AE65VDm?Kas<O=~vegr*qB;G>R zggNCYu@0L1$)fYWfBqYZ)S7qMOC7j|Dy6-X1mG&F6m2z=fm&24EWWi3xPmIV!Ck&U z4XR|X&)E!IM%CO@*&jePs^&Oy9|SI;O2));H*gVEQr~q`fhtr<-U$ML3#gJf(i{Vv zN0s>IH)TL2s%Ebe)dtR?O7u5W=POVp(ljp*IEyObVmE7`992SoTY7;rs1h{0=L3|X zN`Q-050s*c*tx9|IE^a)%F$w=1XX+?wZT9!s(9T#O#r7*#UsLN1Qel)t54}Ra1vFV z*A}b=3Q@(8SojAxfvQ=qVky9JR1p-W9s$P?wdl{scqyO&RljQwy#tP-YWhHRAdru$ zDYsRfKpv_lAN1XVv;I4yx3R83?B>H*oP8sB_1@1DUA$ zHlv&dWT5Kn`<|CTI;uts{ulsa(G!FK`G|pSa4ifP<*|*frn+q@rrL zGS&<@fU2Q_%&kBQss_!SPXfuP`k**h57>{YcVF~vfh1H7T;@CnB%-Q6)#@OSfU37^ z{7Qg$RQ1g@9Rc>C>diNg79b8)JvSrmfLK($&PvY#Vo>$UyRHC;MpgF$&RSqEsye6M zH~>+o>Znh+3`C;pW!`FWAOck{HW}Xo!cp~He~u0ihN^a8$tPeBs@h(Neg#5N)mrjp z0@#hJmJt2pKnSXyF70^%1Pelc<+*2-5(JfqD|k0?B|`uC-#@JOCjjmLhtjPocSv>8K1au!E$({#QmF7u(}aFlErk;h^uWe@|}( z)8P#-q@Z|vq*M5?@D5n9XaKI>wxauKcs~VPyH`MXmqnOY{Pre;Jy)96CCHJf)8(G? zVZ7JGyRL%qw$f`hU+iNB#=q9AK4FWEw*{Ai##8SDltd(Mv0U4n;7Dw|b+}~juCw)F zxyi|L#D^YEevY%L>t(B$$9vTtYO6mO;zf?*V61Qu}urcFb?%syzyt=K) z&w7UwPa;0{;N&Nj5Es>~$^7J`VAh%APp&fX_IB=^S9xLVf4qf|Eyb7*LtZca|K9&+ zwNC$k&j;%NBk5`oyf=c@phsRS#jt9S&?D1}a1FZL*GqdKoe*_5Q55>bZiV?sn(A>f zDEaVcJ80%X@oe4UIa7T&kI#p+yV|B0PLJpC#& zI_y7#v>NVX$cIRN&FziZG`z#<@P>D^6?f~g4icW3mM@(780CR-C$ybt>X>EgNd{CY-SELXizA6hv1DQxLE%Kejhyz~7(CCm58QS}W-~U_HSyupGPF$tEUq;Fc1iLSG=K1ww<831= zv1Q=veo7A#Cve*Ji2Vla%ZYDDr-~0BWIeq9#|KV+y${A*2FxXyo}73L7rxamc#8Xb zAB)$j?3wz;_IT%|Fy`Z~&;1S58-?)w|2=eg!{>`oypJ_S2x8&w>smOLenRPQ|Y`JSi`maQGPG> za{EC&>)mwoe?vyahdU%r%A9(q3$aDGexG~@Vx5(H_TgKzR z-s&eyaa#Q@jP2*%)gg5Z`S4mp9C`$8PW-q3|G&4~EcH{U2F23VAozqOT7!uriAT4Y37Bt`dgtkwKS}WX?eg=mzP=>(AjkNK;+sgWx+z z7sj}ENh^ckrMd6ZqC2sN*oy;u4ucC5DYZ!4_Cz1oG8^n6wnF)a4?)_4#(WH@I8;Q@Hb`UW@P>~Jqj>*p zvZ)7EJ@|vp5eV-mza>fz zLwJ{aRwjQcFaxX4mYn$^f{k}hdD?H$BZ-u&NF3;-yX!#$_7Hpj@#?PmRjh}1HsYfm zCqKQ!%r4n7<{P9@s^>)V75wEb4X4o`F9Yn@9&c;eFAVvxJ2IGB5J&6(qv`O5&%mR2 zhtBSlz`|SD&an!{JJcdf53b&4ES%?cKzK*q`4}R1nGAL~#wKkx@SwhoaV^b*@Xq1M zyKxZ0`(@W`Y4=hy@N)6T7NP_;-iFzc1wMZgDc6y>ZsSY0M-O1*EjTxPV#<=ta@8C4 z!H<)l(PN9I9iN!T`+BmzwefNW`u{%;4~}`UKi-6T27TBJnHv24yv1HRyx~h7DBg7^ z3dOPTZri%C6vq2D*t!J9d$P?@Ybmrjp?v;ZIp0NPT*Jn@H`(Ru;HD%>1`;QJ#*H zc6l5;8w>BwK?h9r=cNskI9DeBTr4iWtXldT{Oe4 zL1EFv^QW)wqnIFZkz+R&ydz<6kgD{loIR4Zk>zHPp@E#9hqo!>gAXUatFw8Y8=qhv z@7^md%QX4%hgib;j*DFrscb*Q5?tFE^3ir#E%!+^-2dlt(BTc=q(||V=e|D|3-1Pp zedl1jdm|$aV7yOPlU6oDc!!Ew$hSNtgEz)xRs?EzQ15IKu!VP!!p(^y@D7sH?EHud zc{9)oxUzznkB#@9=(9W4gv3*9k+^T)W3OK9#KzlSVErYv)Rt+h~S-gr;Q4I~}3nJ&O)+_-P0fZ>3#DbFlE1 z3|GAcb>=wf#ofujKB+J?2k9${b9y@#149@|DBu==B6H;WN@B__HENO9@OT@sC4-C)_H>U%JAnc>?hVr zwi|-rh{PuY^%?Btt@@qb-p}tPP`)8?Wp}iQNq*SNTN*C@zuv}^SPpO0hbm5fQ5Q{= z9Lkx;Tm0v>6-DpxFDDYT4x3a-_p*KUCS<2EjBm zYfoqmitbWU#;QR|-UnjfA=cFD6|MibtDPMRKs6{TgVcFb)e}s0kDYP@J*eQ%4~6g- zq<5YdNQJ*39kzVFMo)+tXmdSaeW^8e4VvRJ?|P|A9K`{N+v4FKak&|L4N`iYrZ0Dv z3(M6Y3B-pOPJR-D5j7&V%-5jnTkYONti^ATDx1plUut->eGS^~UdE6Q5C~kHd5kuL zyjF>F|c%<3sUw@1ZDR;jI`*jDzux@bWQ(@!lo9Sm_>wxBoR={okWxkpH#G`6+05 zYkh2fMF6x&CULE<8&3Ar6b*my7e z;5)1PBBC|%R59n->^O2e<~RB@namk zw=xSpy_L&Dhd2DdB#QT-QnDfz-hRnTXn0$6n1e9h$8t8t9fI(tW_oI+KOuu;^J2dn zJRa1r3JHxk2=C&albvTEycfGIbao0e1AWZe+c)W8$xAab2 zdSL3gkJ63AnRTmvew~TEymfoBuWPOl>*1}9__&Fa-}9C6zP2Rh@vb^KHR7@b|8Qc^ zzBwY)Jzv-!@5Ab|8S+8eT{GFg_rLz1CHwtrOq=&YHBy{_6YJs+%xzQ7`Z%LVCaOJP#(*D~#sN>H3XL6t+_PM3snsjK0O;WGj z$Ds~Av6DGGPe>elh%HkwH};T?rtC-JMh0!Os^hSS*qx%wzdHVLVz~yX2=TEMC%=ZJ z@`~y?%-5jsvQI%>!uUgMApgw9`qTDoKZ87EJIRobMUHD%Y13Yi$`z!;8-4^G#XDtu zPz?)jCyBjLFy2iB+okXfG6&38nt|}1R(=q5sS&zj=U^PFnsNz=>-Bi#JkJjs??m^rwGsO^upHi@h>sYY z{F-n1cpmx4Jl>75{kL9SV_*j<$4Sai&6(}-CKRn_%tt_)iN@a@Bmp|S;aB}pyj#9i zt774OHbZnTjQ5$TF52;y#-49u@lbDD6nx36&hJI?fLnfSq|?!#77%W zejnFg&c9I4Jl>nWwqCezz`zbtv)QT+qi*)cTLfgthwhB+r1U9Tg9Omw4S%Kr#XCLX zfC?7gk<><7_14^*X$)8Ik;lqr@b~}LuPyl|;@}CoRixLPb@iZHDP~u}c&~aK(3A$@ z{iXhwA$&o)p`dhm=Xq?r6;Es|9A6nrd4$B}Zwl!JTLpYerFjDjadf32OAHn;KsbVObG9evl}zA zAiT$Sc18fn(A;}#P>}jgY`mqYnsa)7#8UPnaf{Eciwh!P+QV>AwFbq z@_Q@dyM5*>^VK_`(|mZz75u%oxX5Zfz;=S|@s5kVz>trgo$X4u3;*l?|JiD@q=x$c z*>p7s{_+%BgA8-TwXteYC1(O{h!v5tq#dzaO{5$)ff}Tn#Neq8elqxHaR0&r=mn`a z+7c(>`~TlFj|{{2|8=~tMUHxzfyC5jxm}sqHE5yYz^daF5fniruE{{nX}ctL4dT~( zDYP$sJe@YF-Tky~eEiAmBZ21!b53w>H?`e1|yKtszLwEx+JmUN?p0r5eu&-l?YNhF9RBkb#i2UQZp&KP9`7|zv>EcD_Nr#) z-G15(Qj`vF_}hRe-YfOaEyBXv>z7nGjCcLFJlg$#i(KUfMF?-Dbn{&s)yUw)?^&Jm z13jn@6uDDjyi3)7-i4pHwEJp*Rql-`IG@;ksNxa!4wB1kSIR2>D2gf)S2%d(YnBZ5 z@)ob}vz_EvN0zJJj);$0IQeO}Jq+3mFpu{}iCy=#{P1^>Zq$0X%YVDg_IPtnkQnkY z_OUknNeQibi_qZ>f9w*)dt`pxLM*)fO8P=!ybEu+&@M<9XWY{SAiUM5UzG@(K+jvW z94Yn)_MqB~%JRaiw-v4j7QlG(9^Ng#Z^9IeBfR{%s}CFRjm1BOmG4AR5|Ow#-WKb3)j!@u1~=T3 z)2@K3x7W7=8(_SB54qof_ufJ^UM;aSHUk}&dEc62h&?&s|L$-pfBRmF6B5_klT`ow zA~xO|3bysXj$u8#xeyUSQi8G2Ap%rZBE@m@41wFt)B<4l8S|6Wt@R3iT#?j-CP zWQNkSt5=KmP);LpqF%!8@2_CvecE7j&*60rEQfa{;-d&Bzx&&+9bSCo|FFE}5o=?) z1b+v~MpUo#gYrYR$NSLM#SHm4Bdc8gJc-u-OVZ)(eKbi5#ryuH5@+8p7K<_}-HtVKS(<#_02U==IiXMQ66ac!wSOycNbf$h!Ix&vsMLzU|ej zZXayCU)qJg0*%8c>ybGAZj;;}`?2wUfAfIUpWCd5H|papPJT+KvKljbnXlf1`HLMg zrtnX15v(PmtHqzPJ>G;y#(X4SYB;^4m{z?d=8bF04l-z!zDVW_^z|0)S^IKfyx)W->%e&5k<9)sxziLBw?8E% z{vT1iS8=S?!NPk)p_+Dj z%l>x_?d|Qa-3PcWA-tQYzH6I*dw>9M{XuT%aN_X%tJ?71TS3-%2)zG)>bbqohe=Z~ zaz~pY8H(NiCv|=bECyI_b7BMHBMv9OrnTW(Ykx40 zcjVMNqu(DHIGk9+`@U&jJ^T0n6{3v!xGR5N3tHa#@BP1jHrp(yq5fZvt_E!#+7SuY zAj5ujKM_uE0#*&W_TFj*yu>aLAVfR=Uo$Cu%nmw1`di%SRJ0)(ET8%|wfQ}Xsv%K6 zc>=0I`3J{>5}_ItYh4nitpwGeuVcsEmS7LDt0e~}haeNPN(R01?#Z?4Dw(iV?GWa*tF>H z61yxN-u^eQ#-T&({LuSGSa=7$5ORX?=99fd+yB2Rw5CBH!n>w0V_wt}GH717&LZ*$ ziTZi$LDNwPZ>tgO9S0!1Gxx;pb-!y0nkf~(o&>O$*q;#JF$mY zx$*PQd6R5e4)1ovha^sZ&31F#VqyRSN;ENLPB43c1O9kE@B!v1(`tYyfDS@G9O zp>o;`axNX-TaqIF=YVuyUdA#kyp?}8Y=QBXbNfx}|3kMZYD++Pzo?mx7}X|&9^3nF z|QuwDl1XR?)gHVGsFDkm{ z%0e=j@Jwb;;d~Ej6!54YejtrX-O2|)kQUPk$_lref*0m4EIINoUvCkfmcM#uTPUR( ziM#bHFFkb+cJ&VXTGSvizSoxiX6Ef<Ukfdb@@U>W8h&oIXyXYN_cTD}#nu z)q$NlkD&h`N8u*7;n*0Utbt+iYMQ zF46jbMLN89B)$Vsyge?Babn?p@(q_fjCb7GG8*3H+c$?Cfbc%YZ`f4ew3Y<5FWGy!qZ8zH-u>48B@t^ToH0 zMEz-ZSQy5;(BfwcjJKeyqH(}+6Yw%&K&Lhj8*lRZ^R{F{2&Ec{%MvX)v1uzd-opwV zb5{7TWx2_T7vkd`PJYi_ohPmfG2bBN-c79ka}U4&Cm1I193M4d`{gad55|1(1f{<) zf-Xoyb8mS%ythk#I)~z2P@Fak3vcI%aUB@%8g)(D>n-L+>FPcZ-mBGgP}mQl+awp>1<4(HcZpYbAhHgVrn-pO}VfP>za(IlRPf zyQpB&6RJT2q2e`hj%2W1GpH%npF|Z^KVu7jVs}Dm*H8EpyQka=*NhjKfc3LAj8?qH z9%B0s%{McM45FZM85Wy~OB=C=*o)b!Mt=8Jv)m9nfcU`6Z{A6>3wK+YpF!?(on=Q> z#6KXt&_+1r)hrISuR$lr_!;tHIsM3c-rob#Ds*`7E_-N#;(atp2Ef95sq?4bFy3N= zF|;Rk4Y+LcwnBIp#`<(itS5s33k1Vdcaf+M(tJVqc*~plszFH*-qlujzQ{(HfR3Hx z4l$+Jc&mtPo3o-Jh=Rub88OV<5P^;N{8gtWPH9`Q9Nwyk58V7XE+6|zWFBvocE5MW zdl_humYdIV8VA@OZ^Er*4EfmgWAa098Epo+fDZ4F-7D2lybZ3r=f}cZT5S#wJcHC3 z=%T&2jM;BF&tvC-2`kp zr)v>#02}Y?RXgwf5!*#U<6c>(z35txjdz;Etr|)Z>*0L^@qw3L*_@#?XGiAorYv;j zJ@f~^LFx|>Pgbc2W_!GyR7Du_G5T_#WeB=K3QbOw>F^G=GMqv2UYA_UhlTfcpHd+h z?_HoO4R5Kl{ZEr1yyGVA`J?T~VBF`=KP8e$RGX!bB1#~I=77YGo3*l`a zP_g<*95&vk^N7SFzPl)PNL;1GkpW;eHr}mPS2F!2*RWjmE<=3a<>%3KsB)-~dAx5M zwc15g;5SHw0R9Z?AG_EdZ^CIl#(exz*3tdDIWeCO?_EM7b|~J5BolbC@cxu}ObW)E zui2Zn_f~yHmkNJ-+vex-Pii(~aFxHdO8}G8XtF;B$tcSN1;sY!OgREL$ zFNRfv)NX%y4mU`8sw1=piJ0O(cLh{~o}OxMD9a&(^KNKDYsM|6j;TS8CvLAcYHw>s8oblTeGj2I=zb-Hr-nOO_jA zMG+r(`6U`}Jg{zz`5F{GTla|lApZS-tAwN_%ImDzeu!0e+s}{>8{hek9Lcm3q?&Yi zN1oVs3mszHWoL_G;cXkB+XLerxM@CZc`G(IWAADR?{S?qjcxH{@EK(%`E&w_TKBnG z2gcj(-Gw7C-sGqx{i1g!V3^a}dX;~sCpQDYwOv2FKcj5F~2|G2&xZ>bda|GY(@)G;&@q&o%pM_grzaHX4BW%zIqcz81qrwZ2oHG*gm-bSEs`} ze68CV6z?NDsX|zID>o*7hVfQ)IZ4C2)~nRO6~en)_wRx6 zzAL8a1>>E1*ExMU%oNPg^x{pBcE+5Xv?yO~xor|e$wuNpPVH51BC+unoYHxCcRTBC zPP8FD@bb$G2~AL6$@~WC_UdmE9FF+cTRc3^D$38=#r6%-Q{~eP`B>+b{h&}Y7sgwS z4(~9|1+P)O^Z6nKvG7)1zn_M8v>0=ECv&C^f2W#&AP zB2ze}B!fLU*)K#0TR~zyyp0hbc=oxw|oAA+X{9{2P+v80* z;>3^-E286h`?CM~f2@|9rG5_8ARW3Iw68Jp1X_bCmzzmr)u4tge4X$RTlHbci1t95 z^~zRvJw5ZPFEye=lAhpwr+0Usj=EF1&PBAtFGxQiFUW(R*xk3gta|2?33w7*7_;;Y zb`5HN^u;)YdpqSc634S-Y?pZ#b`7%HUwKq0+Jfc!|7VDgH8}a{DTdiyOlN+GwZ4*5 zB|*ktgCyvbmfaFu$Nn?OK?Z&7d-{3t-z9c!I=ti3MCDPuHKRGCu<%~0I^7QAU79;Y z`+}6(ZR0BV;TjTQc8t-OP(8rW8 zQEh=egRE4!d%OMoc8VVo=k%lWVfJP08Kn1)lE+aKtcUj{#K$I_{1z;^8zp4LJl_55 zhoV0|$AABy&|AMg>p(C2EZr@Q(E)N~3tsThuCng?EessRhP+ zw;CsH2Wj$pe_amr1*z{-LYp^_kiq3A?)bbmf$)B^%m%*yKd<{l6MX-F`KlA!2+pRU z{MzP9D-~?K*RQxS&)YSCqJ+fV-ywc$(LrpySII^th3{I)a@E@f@nMOR-%+r2(pZrB z`~S{AO*5+fALHKo5;(B_q{GYxwm%?!qmD5jfc`=0lZmv|TP-@gV~j_9P`o2O&xm8; zU6ZZW1moS4X+Ycm|Mn#87zc#6*P|t6;jLuQ%X~VIcL#}@ec*v`E`+zQ)PipK`+x5a zh)CaFV+vB&w;sMIfQ@%z?W;9ArUNKQQN`Vv#68GX-a7&UR_UkSC#4<)TZmwdv>fMU?z{~H! zJ-MXULlU@E_@8~74(C|9Iaf38@10q}7he#+f$b+J$#?k~@*#iR<&zw>@W1!}{s{~# zYN-D=psPX2HTEfJ4XP8-l*g(;CcNs?a1FZI*+_eX^fdnmNjqqWt>g=v5EJnP1$=4+ zd4fq)|1b{2V^9s6a1G2$hH8+&bxrAz8zx|#hAn|F6}$g$J@%_;!MQDz+eq9j`@U!W zRoMOiOEIkn5@O3)t_HOuKDu%86E(lu>eJ2q8sx%`qnuJH3~Z2kbli+lVE-CKFzsQ; zN6MdFx+SHw21%a|@BLX%{^xlM0&!QR84atMiA ze3&3J6NQbp<*T&ftSr{UdpY968Ye$Jm&&yfQq0dFQ_pmVHih9YZ?$PP6d5$K{|C|( zpFUv7$9c2ejb7O_yqD17o#dL*fmUzOC+e)P>S6w(tgNcg2E@@C@?oH^qzP&;@CqC<&!udu+THcM4^Bi)^KA zLE;P(3GZkB%MH@%xP^VSvsbWO^vC(3)Pqj*1<&YgpWx3Gym?RZPV*3*XY=7f&Qv&sd~ z>h01Z-MFoap5Q)@v4k!z67`a3G6*kk1yfwQ;N`7?NYV9<+@>H;!WxgP4s5*nRvgIT zzrU3NAaTMnJB3H&u>1d2_3l1Fd8~)GAmYOcCqL=3^4!;=%;RmBx>1QklY!S;;;tOD zS!Bch{r?%pd<@#w9QXuXkcRNqrNcY^^U@C}-Y;)%mchc?zV+%WcyjXc$RzFlzaaVO zxnc5UGCKThnYX){Yf%oM!#am(DcfBC%S zX_-sHWdCgx3KEyN($PX*6C3ZmZ7*uXsAV~-NVZ-?T~ zy`8G$P7aS*uzmHGKE;?1i%+uV`Tu?Yj}^Q9|9?(U4Kk*yL20*l6rwfgx0sePRt@sH zX?OvyL7w5Uv?X?44d?PN&>H04;&zFe7i6$xrQ^bjRU~R6Ir9;GgLJYs_hTGXgWL!N zGm}UY@XK^)eYhL;5G$4VIN`C+X37{6w@}humLmYWLF#h|$R&50vD^$&2Jtb7li&P3 zQD?qzFkgeDivmOPJ}_{_Zb`u!x0Mgs{|r+0DaL$Uu|ID5cLr%hhxehVJ=`eXw-{0Zv&f6wEh3V?_c+iPrw(X zS45ShrN1@-ua@nz``V3-x0&i{*`Jx4DYuX~8;>WC2NbY}Sgo4|`aW_X%i(Q~_|V76 zPkxSAL}P;}?o#r+a#@yE;(1`bHqHVUR~bYuG=mSFafAs?e0=N61!r_CUj(cyj2 zmROGBy=df?5*FU?f^=!eTW&u6L2Hm=yn=qsg8F~mxS3j>Ph?P>=kO2tQzUBcjOHvD z@A9M+AOXU=sy(hF`k4th7M=a#S_3xT4V4vd2A^-HOd@es`)x}jXJO;5Cph}eJ(l(G zet`He!pZL3{brJT{0E1@LrbibqKEBziO8)f%|_yA?kKv2=Bp=d7bK0WH54Uk;1z?5>;y3 zTH!(n@3;F~G~kaDb=g1MarvnUc(jA?WZ^Yzyo>op97k9AQBERpass#NB)?!!P99uY z^fXMwoaL%_DdM9EC%*?zl2z?Hn6KV%vJ+E`YZy2ntx&P%#;SI<$D81HmLVS_vWL3H za%t7ukPh#Zfu?;Z-mfCu6|nFQ7HXLV-~VsgEvF6RP2tmisRZHOE?GP-B;W~t>uQbY zIYgpP2Xc$Uj}w_04LZS(6FHX42Z{8XfC@J_!m1x(<6SCeXV(44k1`*LGZayX*(Ln>XbpG{+j)#unX$k7el zA0FgO*@DE8<()Pph-25Fbi)Ir4^gHpH^ibovT*Vv{ZQba{h9e8*66~E)<3xn^#9Z6 z3^!I+v48)6@hoFL3LPC({`UVM9o|`?leAClz@N9MT0EqNg?G&v@-Y~1xz;(f<*f}~ zg1&|j-c9^%7d(5(;7#i|+wV|=w8%GHg`Hjw0 ztiSO!eJ93s+I=Zskhr~fUOhPZ7#r`>Q&XN4fc2KQP#@(u`B~qw7FNE*Jl>C+f0T?d zFvJpysm`ZoOxS*iCGb3E$cIKM^%MUo+6>Z+4)07WP!Fx%qdv8&Sa@%I`|vo7_d4}T z+6mJAex@Fh5Z-@I{2uRnNe0z}J!E<-NYsE~xsSyV-XA|%d&fX{|JoIPJr4SMtFyf8 z=j-dS@irBf$UUmDnc{}THQimn<8v1q?;%SiACDB)!`lq;F@lrdt?Zoh@^Q@1AXfkj zU4(V;m$ycMc!!gRtJogzw=J0r`Di+OG1wxG*8iK*;hiBIp@ZW6M=M4J3-83Az9(S3 zTbFKH4mU`v+qZf3OCJt2b&EtZcQxI&_)NlX;O52TM?APmC~q}yD%m$^v; z+W(J^xZmrHjd#xNvNrA=n<+#jZpF9uD=81L@xGRs`C4_5_3+L`eB8pxZ=|Hxw(&Oe z)qADwg|KJ8@i#~bp#1e3rPb^|Ia$h>k6w%RHJ2)B)!T#)@55aIJ5aoD`>tDnh4)^r zZ8W?mU459sd)s+iIpPr$@MX|U{MO;cnL1P&Atlk<*gXW(%zYL z*2CKy@sWs=U&Jh<_V>4#$6LxVXlz^!AMc5?vhyr!Zn8bzWv3YPQ6HNt!jt*m{eP^< zKTG`_>i<{K)u5v%4QtUFG&(R_8>N5yGvhbVc|`V`5Fe}J-&B7twAc(9**pU@NR5!605iI z1TUxTZ@t$9y&!cnUKW00_r7SF3yk;5(bTW2H$tDc2-{(s5Q>fW+G26bhxtB~MkFpT zuZ&|N4SR?s&ErWp{EYSRwnluAaq=tVN*<1vVIJ?V;W1mMU*IpX6U^*nHjS-e`v!@S z;LMN@%kSEEKSEFJLe<-X4(~jZQ~Oc8zkjS)goU@}CXF~4Z@-`uwEO@1B80cMA-s8Q zqB$G%Ji$J{kqvn_pbw<&uFHn;P8ka9h=B0cJvBo7X=4J0FMh!hMZ(5g`@!9tWj#KW zC?w9Lw=unJJ2u|FD+A5fFEwVl>b)58u>~i;G{5So-EW!4n>)Cmy;2Up|DW2UAtG79 z{?}Wk$F&*qp|^OpK4%K8|6f6ecP_DK0>yice9S^Dytgh`asbA=ZO(Vv=`Hi`ZO4ls zyjw)wTwI{XiE7vHI8Q1gQRhpCiJXD(J}9ws1B~|#HL-02t4zQnPL^^Ptg-RF!+k8` zi~c6cQ6%o%`}_v7BR1YAbng-jYgrF()JG9cemh;v7HP{ekN3pHt%F=0_ze;v+$=$O z<|g}B?^D(c`AFa|ys271tKQ4$@XmR9UK7RJEv<*m=9E#%&Q6PByq35btxIQh9M-uHiWmU+B?ediAs|ABuw@%T&6 zE}iINw(tMv%GfjHBcfCHjYZLa{Xa|f`B=$7Ge~Q?8g%m5V@I?GiKr6|uxijX<3sLn z4I25dpVlCG%hz`XL3fbykBW15kvzdezK)riS4q?*Zg(20p&E4eWs>f8s0K|hzbfHp zWdh2{S^Tk0!>&Ou?Z=Pa9QLBfBXJt{<0=X&v4_}vIZx1P%TkuBLC+B%xj6ax3-X3g z%b2f0`R%8r!}j5yARRvFoK%`+$@W8R0Lg(NAKI3`_IIVzW{_*>@Gf-gjz;n3o7cJo z3vY#?08bci-*H~r@|MVkp9{zk-oEh%99UDBhMa zC3;wR6Z|AM!FbmcX4CLqb|lZ&62d#;t+C>epC{PR8QJ0tEpJ_o*}1$D!rS=9t?$7Q z-r~B+FIuEb!0B&#OEwx|<4q*ml}(;R)swf<phOi09cj??ZAysU=`Fo`k<2$`6L?o^@;cfdsXe36?~RMx|r5AlJQ zpZX!redk{=U%g2wN1Gv>td&&{{M!|$903dJ;CKwmrKbXNYsYmDie6`EnMH$ z8a{g~UShuCro0JwSyLiVZwWTuorNMP@v=UYS|o1CepTKxy4ZN%9?g_or^tGn6CH?; zJ2?5(T|Ad%B*%R9ww5xzdG8Z`|Nms&M8>i;7uml5f0Xf+AsCLyhm)QUN ze>ZGiGvwnBKjm=r-xs9q=6%mo<21=2;p77 zX(d%o*%J&*ZQBVXk*KjpW}d@%^A#NK^M~-Zt&2HN9y114cf8$PWr&UUSG~D&#^-uc z&^Z3rHFma3u<>3OaNg87$bjYW{*3r=z{w9d@%e`5DduO8dp&PFe>#OfgCsa5YK`|g zvi}V7{XT|#Bq~|D8~uIW(v}YIl6j|GP`pp4FkSARIWTR`CmNf83< z|NXyv91RTl2#-6P;E_dZkZkDiJ~eUm8H#uA4gaNBcu%{|IKgXdU}JdC$of%cy*5Z;GE7H*S<@CJ`6`VLB9FJ$dsUcq=*K2uGC@lH>X*C%W@0R_r7tl|Ba*IUwMti-tT zy(q#+Ts2@!3jT$S_p!&VV?VyI9^Pq)kE1yGm0fnca-g62>V0}pd0Wo~{JA$la#wq% z-y^o~{|Rwh81mtjQS;3t{lEU7rTToVWT5`viLM5ni@rY(u0e4BFFm+{2df6@d_3`c z3aUXdjZIeY6}vVtf7Uvv23;7Byzjy935MP|I5*jeM17?5d;UeJ2E|)kEC_^ZP`BnU zr-}gRi5=?wxxWDHD|Uz0w69-QM4}u);&@(i8ymY~pF#5P+a%Onx`gG1*kr`V7M%RP zFRC=Cy~BJB$_krjR?d&V|4%Th>zX~=f&GWrXV)3>(P*;NJ^c`E2I)wLcg5R=Sa>Uh!3PEHudsRrHsmlvdq94LE|kFy@$Vu%mC z{5)^O9Lz~zeg@fED0`4&4*nOUyfll?wz@oId%O)lpJ2#Gt3+M;+#|H(E$ivt z>8-e5TTKJt2I;YA@sm1Z@TryEDg}P*21(SfZzR5sM0t$FHC#{Luk$arw>(|6uPWbQ zJ-mewA9(rg{qP}F>=N_UyPS_=So|G-2kBzerNZU1?0-OdK;S$>K1wBJd-gyxNN94h zjt=iL{cqo))%*PYI~-Ve3%rQXgYkZxI!tSjimx_0ghO~&yuLXT4|swXhcu42_>-tX zz@XA)2=8I#kU!fXyhW}DjD5Lf44%7oQ%If@8}BdNr=BQ^dr-=exT}=bg)4@!FDLSD zmcH!pi}mmxL45Gw=J6JJZ8(;i&%oux|F69_4X3jE|GzgfR4RmoG8D;J z<|zx6p`;QSGS5?*go>hM%8+PQL?y~BskF~T$&?{;hSbJZ$rK53pIhht-TVF@zq51q ze{%1A9M|_r-^=xR@Oislz1MoLwa&Eym5Zh&#)zN?c7jB?RM}B9Iu6OQ#`5!HE)6~!5 zA=Z+@gYr&aT6jU4G=n_%)tnv8gHHCPtt5HSMo+nIq#5M7eU*bF@EN2d%cNFIE5SQR z!4f4}x;D_dDNDYGum@eguvXg__8?nUWyh*#8emkbSHI*hCrAs`%{r{t9l(zubphjy zbF;y#GRI)N9m=hC5Ysh)!H3r&>sO=CAZxQ~BU+0N z;PsF?wF6#hvVYk@dKCNgQo?WA!}~3w;~_?WqfHX^TuuLu_d$!_+`e^GJdh?hP#J5g zP4{@?B31m{~se1#ifbU1dCVnoD_{l$NO>)OO}|L zHJ%lz15W2ZeZPl3gZx%|^mz0E+6zeWh>ouq{nee`QM)Vp-|@B-?fD_OoQen1ni523 zTHn$?-c{7;=yj<~N`0}A|Myeioz+{{O~!k@!ecfxygllbe~~sP_NW0v65j1+r;;UL zyu(u~gnQxd|2HMIe|Ci*NdKl$E|3l5ou*#ntI@h-@_!jNq9f;_7h|wR%uWtjxRsW9nF#@+B(8NC8!nme$ zwrgTN-M{~LUYt4|5jFf;ivkz$Hlx7%(L?D*GTz%&BUsV!#tlY%C*j@hrMr`acWYYQ zhyjdu#GUzLEo^qcqxjIasNL33kAt%k>EpzrtGv%hA1AI1Q)=Z}t_ddB-1=yH5gqT* z2k~1bv#s&tNZpMcTT&wb^6l-5!oe8-T-w9?8=|8Gqd)$Pl&f0ood5iBV&Muy^{8do zb8npeuWxlb@${enzmHR=!<^N99XvT%1_xbchI_bWB1?2xofd_{|M$QD(b{hS&i}R) z9`wYmE}iT_cl&g?&^#zy>+E*Y4ASOxw<^hlh81wDa^Zkix8FZz z|Kxug3cQOpv)YjHu3xr{6AkZ{=5$RG-hP)^7p~a3mFV!O7{=Sg%we-Wyu9`9bwXf9 zkS!!2kx)&#LAo)wafoz5x=3u_2kTx9kPte!G~+MVTj161Yp60>;4dR}Rp*s5Xa5qA zCK{W6I`7>~b9g^Rbc|v27c#xl)jR*+@m@cDOMBP=8}CnS-lvN<)Bgc!0}f}Zbc{() zZ`yx-VFqbUfp_6tnFbl}^Zp$x(C{{?DUv7QouurraQ;8T&@iD4#`|UZF5*5F`1TfG z6HU&|wvYz%Kmh4^i{J)_X3`g=qpUo+9nBhG*NNT7?EKK(JLl5tRm2$!Jh@K)d)FDZ zFm(4GyJ=++$ShBDcxNIyhB5lP)=Vs2GWPFy%dUPsl#zrTkZ_Zki-xD^|NcL!b;!5q zUiRc6?f)O3z`I}|`5qZ>MaM_W(eNIHA~ull7TYtnu>XH}U0H7fjCXjrr|Andc!SjK z{Ok4>8|eDYHeJ&Ff3jR#k^^A8H+!xxiK){77b}Cu3|!Ii=HU&r@a(a~$0BvVpOx<9 zJdBR_rjYj^6EbKIZw^F9(dF z;GVeuiP_5rIwmzEl?mfLMp)tBAa#!q z=4hq*qvKs7KJq(z9qnySd`5IU!|2bvdXw;ehksw*a?kwwtK$q6?wu*Rfgno%=l_F$ ziBP5Ed`|5W%Y^^-|7k7i|F8YPL#z{p2feWOcN~%LkfOO6H0a4E}wHwG#J> zQ6*w~P;kxNl&Q1&biacX{4t3t9R+DZYvVE(0+J&I-X&5*H8S2Uk<6>m@V=<62S|8V zjXqph-dc6!$b(6Eh~2oVp>(&fJrLI%P{?qwhZK(#cN~ZDmSJm9&4=+;es;I9=)MNH zfM0U?XQ!*S9yhqnTv!xE!E=~%)*&;P~w z|M#bQb4uB;@y>Hr8sI;gPxpA6T5qCC$IP8a%&*}mc3}5*puqdt^q~u6ywk^5F z!U4+*O^EzC-eOOI_tVCr!(_Y_t?zN8 z;mv)7*(M27-K zf1$nymsgzrcf18{OrryosrW#;d~42SUoE=N|F}TvbZjETT$lN?dTU34cX49VVlv(( z6Fw`^@Wze1?jpIjC}*!S3GW!6r4ku1-U)`uxS7rH=Pled_K&A*A*ZRM_#_zbpcisA zp)lU|r^hl2L^MId&y*9#C(!Y}_`A18glj)O5vhAyoo1z_^cTD%&x=d8%F!I&QHTx& zjQ%#auJ7U2|M%BhrJfG?c@|^iJu$8^dE&rUx}Th6HY-x4gU3akpFKM9zy1IJHE`3| z58)Z4JB0_8nLWEm_8`GUo7SRvP~^c>W|9ZB^J*{LL241|`!W*tApJ#?s}7{tgZ1jE z`KN{)AgeIjybDqA6}z_T&!i*a`~P-uZ%96`0R(YRp9=gXARUzF%h6FV!LLT@Cf9se z-}IM&^l{2yTdKAs&3TXqqN4|+zw)U_8+_=$53y3kW6dmIshB~A?h0{uUrzsLkfije z)1kxVg?wV?MuGRMjgsrgcqd<-5k$lLu6+~-32z^t8w)!~gE!wMB*SN1<;4s_)b~o8XCm=4x-~CMt`$iY)itn{yW|-y~`Ol6krdrxU$BNnU~Gzeu%|2 zy{AgY#Xe@Kg0zMF?@EF9%aOcYWW2l1RSBTseIdY0kc4+@ZRNuL|Bx8F(Q_E@(lZ&a zwujn-c^&29%A*d@P~A!HW*Be0S@)T=Z~}N82`}JwX@EBm-gBl`q2nFmAW=T3Wr8n9 z>Wbr%!>6av^MA}tzf`;l?YValqT>Qaf8P7wU%a^d-)E5Q?ltj;g0XLJ2{nw0Tlct* z?(sgkggPB--roB0{M^C@sS5?(P%XzpGTy2iZ}6kx&0M)-BMEPJ^V)^eThB(8Kk9+; z7V(+TF*<4w0%gKJX^J^O>?=k?jz<&0q($7X&tU{G&?~LJzC{CE$$qVl7Oo2B(I_o1D?@w@xcsz8sH1Ru=vBj-2YdZ zt)HURV}k#N)CGNQJM?B09q*<+8QbU7Xm9VW4AIeu(O-Q{ez3B@zq|L6>s|(%#IYwQ ziWeU2dT~pG?(tS$d7CO7FBA!l`@;Xr|1_5L|Mzy_{C|+bgDQ;=`I9~9UW4R%G!If? zZ!aKygJiko$qv#QB(&Da#vJybmzB!L>qH%Zh1u=W@l?FKP%=d(|9es%Pa>(AbGQw)NK!ssvC zUzzRZk$)dzm*fyxbZ=9U{|g>qn~E3p-xATyqD^q9VBlGyx+=P_@C=7 zB;yyaL&IBrMyiU0_tO&7h3hT5e|9bxf$=uze=Km6!2v|~xo*o%afEyx9pP++@m_lP z^Gdg90$`|(Sgo$12`rkjdn5w>a=qoGgqDu03Em8;^Yu^=l>dQ_x1rQat`%Xlhj%2R zLl2|BU`TL}lH>UvOGPQuKw1-2ZSLO9WQC45KmIiMZft^ogVaeSU(McIfsQxtM0A;~ zEA8RE3emxh(Vx?+P3<}C|2~8C4g9cbS`8cTfDuo|(Y7mekGJE|qg3f|%oXIZzPOP8 zJt^>hox9}}8SkDik-}(rSExJ8knon`tz0-Dolk688vx_oM(novo@o!HT#iM!2suLg zS5LBOM-su!!TR#zC<2fzPaIvYqzQ^=Ojaq{pySQVi z=O`-;=6^;+2NOnr+^X}Q{QCdy-tYl+d8;|>(_6SLwd@gMTj_suBKr+hI<9q0ndWCK zse}-*P|*4exMO=LNj4M8Ez2;63r;R=EE|dk|#CU^}qZ5xOB69P$Ci zTSBsE={&sm7C)kYsOpXeP<-*U&@T>s?mf_TTk4&d34SwDXR!AE?!gT7{2#q#zsGrL z+H>#Eh>j?X{z9#pZ8Wz1JKhJFefE8m#Kt={ZQ}*^p(47+TlK97RXW17k5`qzx3~WH z{XZS#DtHEYl){7RRJ&Wq9%Q7-D~aYoro8b6q#;)CZJZe?|Nrvt^$v#v(r)=S6Q5=W zpghuWkL9ZqMD%MKk2yyK{X&oHL*fZwM)cRO+n?bJ(&iYMOx4hbSQFf-URTb2cwMCK z>jpy}!vgdnR%7$2FXP^{w+6Wf(V>db-=6%A$U5bJ_n;Zv-rvzW*d8=p`QVw7#J;C= zK;&Orl>0`Vj)baD2W+AihS(z%c)#QG6er^i?fEW&hIfR;ZW|Kbw-n;`k?^j*!5A3} zsrA9D5NSVr47KLc2ALrR(Md=Raw02Du;6F@(`y(Taw2#s3TUX5N!Fb8jj3 z{y%QRQ>MuBX8Oll@)=b+wFw*XAijk?<}~ zm^LQieMNES{kt&UUfmKbLKY4nJABy7f1MN5|D~s52*&#`@0?0@ECCoZwgzeVX#%kd z#g%6V(D4>+>(Q!BHo*%cb)C-&EC!6w@t&72UOd=Hdw2^YI(}pHxB2ZY_b&`wsDFLY zM(m3pR1%tauwQR^lzEY5mv%heZ%(wh#!#grpkl-N<$oS0_MyPL%2)k==H5K^d&SW3 zZf3l6n}oOT^>0Qbyr*~Zu00Fm9sKoCrvrc|C(rR3gTEc2>#jrZ;=_o*mr(fP3%vLC z;w7ihRHFuXEfUhQ#UYjsy|An|bi(E&t_zG-ITppTqgz zpTdKhmH7YX1u47iWt-4ENblD93)8R%Rkp46C3%pT6yJkUc!^!fE||gB+!6Ff%Jdw3 z=nQ2uR~P1-CIYp?C!&n55NE?m=t032V)VP4NRron)ni6Y&JP z2URs>yBW^V-WQ~Th>o`y{e3^Xc6(dYzkARUfvoziJ=jO=>Q3PmR20MLeg^r*k~$qm z`uLiIkqbLWeiV2&Ema&M2PFNF9$7TJk43L}O2V77`I8q3Z}uyGH&?<#EbC0#Ooy%` z&`{n*ER1!Aw63e_ygWk$cMg9&#CC-M%JRho_2JK3j`bgT&i0r0|J<7sdEHl=;twHp z*Dnc#S?xl{`|#1*{>krY@B4pOM8`pl{v^L}NvD_m`xQG%%8zFQg0Yvkg11>nvsFjZ zJ>EE8>U3;-dRor;&-wr36nHnbaE_AkHaL(igNCeWkecnB;RhUOZ+VLu(b0&}A5W&FzZmY{-8(#O>$AG=*zS#sXdSwv z`IG+fwxCYOMcWh|`MV4G-bGvJCrj z;$W?nGS6Orp?kb>R@CWGXWgbU3LkIzFaOg}&PQtn&i{cF9`r$ssfg@BjB6Q{(LAUc zJhlD>dyq!lOa{q=igW!Vm0=J1ZnUR#ZqyO@^UOH*&pShJxzgiSogji&9f_w$Z^2jW zzV4pwg3ln``yqOe$pYPj3LL)I-jh3kzl+pmFLo|H#Em}0UaAUse87PA?jX%YbX>&f zkMGXxvfxfm@bS6C9-g4-}1xLFYmZ=MvZQWD;QimR@X@cx)P!om;Z&3sPYR<7O=j7)KE zTsPqiajP*`Xr3g3$6WGZmy_W9pPleTB1HpOTIzm^(MQMoEFWIh(bf{bAE^Tuek8qN zLdUyFyMOcb#k6;W^ch4)BSwFXYO`|qR4&jqb|p4>z!Dp8t6H2vbs}UXbH9CEKK2aq zN0O0y!e_Q;Xf8)DKi5s8PKWsVz`2go3(H$4De!K4b?$$jw>08RRzSlW=!MUa@Q#yf ziy`67Hc@u#2fTW_7K%A6_P`Nn>+Pt>AUZ<|qW8WzoFanOf{L?hHwj>jxp9qOng(d$ zcV1$wg^st-HNMOEL34Z~Qn%S@^lRn_`V3Md*S?Eu3GF>^A&BTu!{{$%o8HCa9h@Lt z(PlQ1VLv9`Mx{)Ip~^%EL~ksAP=q~$#ARxGWE^Iqd%STEsnb!&dA3L9!9xB&L4kMc zRsH{Y-cokkA$c^st*lOJke0VxQm&pQ;hkx?)TR{1`$7Ex`-%WZpgWLRJ=N|Eakb2= zMg$VUrf**vJFgRf_sDh4U(ez9|AJcZ0sGMLzE`~pZ@btWZ-msHIQ)F?b4GOcW?aI3 zpzJX1Jx-L0=wQI;Z^wjzOPnwlCf5I_%gP7xozC5XjW>sa!Hz?gKj}UoIf_%KZWupDWD@gAMAwwZBv1UVn) zg|?MDLr*t!yto-e1d2`jt|wk204S27F!!zoP-A%Dvq&5r?+-d*2VE?@agVfvq|~j*OGtDA!h617BZ|5}Ur!hBW;#X$+X=bf#O@KmF*DxcE5_H5V=r6fGL&V5LxCuuGEH%M+XMTJuq$7t^UKe7&2jQ%DH%6Piq z1Jd$$XOdA)4c~hE2mCJ-PwKZ8Rtkt z>{T2E-aTVB_2eP8^hC8f8s6h2hrCI6<5wS@BMq^eytxl-hw;94t18em*a?^z39RN4 za)HdZPKW6F62ZNa)WL^o1mG|;D^q5u4o)%R2KQ#8<1KGn#~^(*5l^nm;;Zw%_9F=O zKl_oyhc}{kd(#}=WF3bw`g^YQ-MJx`6C8KmZMkc%2vsN94w@G&3fTeU-IVt=L$$07 zvmPg#HpFh4O!s)>RH@YAC)c3#=luT}3cS0YpEM@pJ$~Sd8XDfE^N)K-c&jcK`%1!l zV{v5aP8e^U)HkAX?oMFj@H?IN{4P+D{@D{j$BBUdvKyqFN&q)Y@4gR8RR`a8X#H3r zjDC7cg~h1-+o@tifI_9I?){7%7~6CjQ;Fh1#baYPQaQw|Jm27 z029|hS>y2($t%!Hw-FXFfIWi@Ub@V2x#|Y`&;RVy=}_3vhyVWP^_J5Vcz0cjOC;kh zpz5iLhPPo{?9M3|Z=Dr7?IgUDi$#S^VZ1joRh&Gt(+ON@+cdU<*9BVR`qHMr55B#n zJpM>U3IT|1)a~`nRtLisOZ-oWqT|g{$f&fzAOugY`>J~~qVq4$Tk0N}(_Q_=oaXRm zMs(<4^p`!*ZX=e)3F=O643~PGi-~vtlR3TDrk5f9uO4~ftk`%@?M%JE(RP;Z@n$!o zP6ys)(|pCBj}wC^@a}Xdxk1L;?6{^18s4{;?*D9J}J%lIM z4fph`ZVEup|8cPgz6GXlr#ZYc5FN1?{oN>6e^@QT1^N^kTkC`#VdCuv45!b)c+XxX zHry?y;_j`@9iJWn7W$u@Xj7@ig=ySM+#|K#Z`4gU!TBo+z}8W0vxAbAie|7(A- zVL|ht%;fXie!w2&XXSl?l>fWSu5|OmYmk;XMZ11&b_Q;08{%Jkxj=IXCd{*5M9{80 z%y2x50J0Ll%7koD2ke*LM(&wG4@ip_hac7}&&MxC>WWt@$t32Y&mi@;pZWYYAd==h zXepv&J4SyS1_s?{B{{+Ch-XLOPvTvqjiT?7E45a zov71s#xQcGDtjUSGgIK*H>|X9K{^TV5TY0}8s3TmhJ7TwWriR7knon7RO>Z>@y;3X zAo#Cx25J{g77y9DK*dCLp|FEQP}IEkV%kFj&|ran&nc?|vx!k3mtJ(d1&goX?pWvG zO_92jxx31L1ft{3`N_5>#q2!I;Vp#dSb@>s=G|UD_Z{K{^Gx1biz>16Jfm^L(&0rn zpt)?9x7PC5e;urd#!IZzR?__p(sGzO9RsD!4}|j;@LoiLH=%%O;evD$-rprBn9%T! zxH1?v0pne7Jh7LAxA7sjnsYGT?%P8rz!bcC8?u6Fld%irr^ntl?n4A@d4t~L83eGX zX3NJ3b$EHp8}z(yLC3q=rqtQLGXsATshbMB!!c`zj`t29>1gZJ5Sqig7SUmV(VwQA zR_2`|P9VKgX3}_DDdr6F?o*v+6BuvR82iwkK`LgD?|+H!isz$yym1Xw>R3K_YvaQ5 z)>S47ygx@7EIe;X!rP}2&xnS%b%E)oNf__4r9=f1-eoLG^$jrI`^0%1rQbV&8z*BY zM>Slaod$P3Ee{jHNRq-+qXz_VQEIXIfg*L_dn|P$emRLL@H+kDO{I>JLx$xKQWxBtkpk~ehOTMkxp!?#1Opo0v2ToXNq83rM6My> zZD<-XtqJGD>Bv_J)H$v)Me)xtCn4;soW%uTZ*LeXnhqpVTLj$9~_DZH@+`G8|_iWC` zS4PzDy#>X7dj_4szP$y%oKLZB8U1fg^sS*z#}r%9fhzcL;(z&{hI2o;H8}q-rSPDk zMGr2KJt(h7pB>GEg!<}Fj=~;Pwcm?F2=*X8>GK&Z@DOVtFl+e!o--&k7<@PvOjIpoG)Yw-GkyFn|JC4W%!LqUFHg>s4NxqBX;6v z8mn8ouG5?cT|{(X_17=?Hh^EA3*;Yp!g;Qx26KqLa{P(Ov#DE9s(ZF$u3cSB|5X{MV@0$=@iiUTr@)z6~j5l89=Ok%} zwVJM%WrXo=u&|hXbHN#WP*@xC=DZ6e(HdLZ<3a>P4ZF^aLIU8mmFtbzst#(}-yg?o zpyRzF{?w@-BBgk8-I;Oy<5FAEhuF@Sy$%73uhJae9Ec9A{&rO0ZaTVf0!FhTj)%3> zfk{bYi6~Pp}&iXrEng4&@Vo zi}lmv5&P9a^R^S;UALp-ZO-@f@DWBlz6q(jZdt%(rHzjFo?9K4Rn!t`4sT0D2UdT- z?Ru9vKH>yxR`;)K9>aFyjXARR)<17S(MC)2^R82o|F<(m9~r>WJ>Iw@RO(RKb$ZjE z{Le;#_u!3q4>I0-H*?w0@U|H{qd5-a?UNt!^?qO0ys2tJcFr49lWVmpM5fnj<<#K(ce~^p5b33b&>-*j2%4a zlM_{q?z5kB;%N@=1Bec+{@BbccH-g3iP(&cU;FuB=XsThozwc3Hz99b;l0%ZR9tUS z<+`SsTY&C2Cva`l=}3VRDpb-J+?$mGZ=&}8WHR2HE6%Z^;q5=~kxs%}LN76$5^t_o z+$XCIoPkGd`x9J%3sjw1CF1Kz1Z|T%SGML5K+(IV>f`%h_jYc7At{ZHcTq**p&i0S z_$H+8facC>PZo6dJ~Qn2D`Fys=J0-s=m^5-&p*=UipUR6kdSs`Q}i9|y|fvgH=F9V zCPC+U*0%_3#{TONbvV54<(U+^$D8RSbvll_cORDX|1bZOBQ{O{2?rz&3J)5aUmrvE zpn*ofh2}v{m%kZ)hdt<2{HttI{%5~^$!}_tg7)OjiR-+|E~n)qqsqn2n!5`VNxP7R7ymXW!vvk-ASO$Cb86qVFILv*+r} zs^6tK44 z|2Ifq`a+$KU!@tFmiR3Uu`4L>9_{aLCF9*2$jOO@xBiN;VG`cadsoGh@HXH$a7qK7 zLEig(kSS%g3)t>FA=pvl0%=A>A9b@Kf==%P{mFP3?}PJOJkF{CLcI-J;$QIYIwODa zwpb0mAE~>M7P7ABI6B^IH=b_X`8bv4@a{%*VD&fN#B9j(kQ0>k=qrgNW8*#9`7VAH zjQ7>f{^R0bu+IzNv~PZzztctcLo6ysK-y~wiU@dUbi$B0?>%?(uI1(3R}+_L6Bgwbb^p&JgqZPB?yb9l!hIrVgf~xuS?e-*^|qYVCZzVAGiY+T;0F?2 zAjA3C=1O}a=(!pxcmEjy>~k-9RLZ0doV4%%NaI2eNX@z{1cNgx@GeLl8&ms}HWhTd z&!l>kb6roSIlNmC9a#N^?3#UJs=@{2v@IN1w_xMV8$?)q7}njO*c zo;z=@C*u7YUx(BMevz$jO-9H2R?6u1u7^o9hxa_9<2FWrWlw6yjXgQR^g36wnp5vE z-8(}*{j8*iNB?!=1S>2!}bu9!L_UzqkbF|JbeHufOPb0pf#_b}p@kzSJ8>dR8jxGTiWP@}i1>TdFeE#R_ zExn0)9yGiyJombNgYg#jE?P#y+kA^ZxB}zdmnCGp_Nohz8L>{2n00}Se<+?X-Vfj2 zk~(HT_J#liS1U<$xT=9gEHwkex6$#g(R-%N@VXJthSWKL=c{)yqt77CH@{chQ2c=A z@Fwf9#OQC8+qa|}a-2ZYXX~dOga%B!6-)FThNe@X@=G;=pPo>$L8_YXc1YtC{pbH@ zc~t3ed`xgPU3mZRDi;Ob6E05=k=`%$FtKn6s$nUo2Z?4=9^|Z&EcJn=orN4@5O{~su5-6PNJNcZl&g@rmDYo2Yf+Zel$|2Zk}{voq6jEr~vBcGLMcoPLe z?~?G&ZT7Dt;T`i$6E0=wvVo;*jK8G!F{dVDMxB_Mj<4r5Vx;Qt?%0gB!eqRNVRaNZD#P z;C|rl>nwr`U0Fnru`~hxFG%NY6`r67e)7x@iv~E5=6sW&E>W` z5yrb$`FJY{?^oaRvbMo^=NI*Q27hq{Q*CB)cRs=A|0S~?NbewmOZu%3);1Hs{-0@P zqBW|(vbgGqk3KryA8%AC&Lp+tt&zIxN9IAnI&{3Xu9iecrsUEb-k%X20HeQt#;?v@ zlN{jvg@UU=Vc2+2q&l&NwB3acS6!;nlg9qU4o8eiZ*k@d0W`eLMB3I4!g%+c{*h0@n|n`gE+34yV@~(2tp%Cbr2^IYC5n_vI2Yc_FaLpWnftY*ddut19 zGkv&i*>jqnNl?*TDm!&Lgg4)ln~zusNUJFDp0V2APR84<;3hvB-t|7msz`Xt#J;*n z!aG=EHl_y-Ncmsi3Hlsy1u3CRW9PbEpk9G(v*E@>;8^k~Z*e^VJmd4Pcj{0D&!kFK zN9EA*UOj)uS4h1Tk4Nh6nn*qJtU|}zeV=MxmvJ`D;VppZ@WSX%uE5~Q^`9J|Y$=C# z&UtLSmvp?V6N2&nb>Af$=^Q6YfF6+hzZ-Bx&#M;Tl25=gh9)^u^#6FW|X%U)j6IxAqXh zk7Wlg+^8i0WBr@MyX@4!{TSyQ&1Q7G&16Mi*mpgI^}%>IoLJ&P!uz5|^p-;~ z-p+2@mkRxG10Q-X9yYXeg}f|Pv&OWEz-;66hK?Qr5biTnE8V6FZuhcYpRGp6yGJJx zcd)h_pNiCV|2*UUxf&gBudp+D>SYBqhj$;M1FOGv<~zo1ra3@$Cyt9Ds1?(_zo-9< ze;9Qi+LQ2_fw%{I2Z`6Fznrato$dpYkq31;uEf}V3HTF`1S#-lu;7Xyn#Baym3M^Rb;#$^4SZa;k~_j!yF0kyG(dt65dftwRb{cyq~Y^vOcQo28{L$X!rHI zK-O`w*6G`cpfp0n&#{95n1>X?H*~?96Jmxf?s4e(zwkf}OV|2NybV$}oE}(3tVGZM z)pyh-*d=KX@27~48jSurdpC-d&vAg{JtmHi8k;fQn`fzJ#vc89ko9vd_a+r8mbb1? z$}auML;sVLSn71FuUoCC0l(h*-~E4R>6V6m4(I>%6dtss-SZLIgFHrgB+)#Gy`awI zBkVz=SLZ@SVGk;~KJt77UV}VzfWb?By(i$ewCk1bbc0G>1f0o~C4xP3SEq0j@B``N zNN|@ail5Tl5Nn3$!0N9( z;06C$3r?_a-RGri+&VEmsF(1me0NL+bTP2CV*eWK{IBa9m11D4NB1679Y~#yecxYM z%Y-lF|8*32FMc$VO2*s&7(oIJZ;Qt#`Fml!o5LzCNqA4l=vOnqL+n_GhDT|K2e^b+ zNb*c~gI+-*S?-&OU<>Ps{+3Y!;9q01v?EysxNqWXxV;x0Zw_}SWATd5cn_p*w?1#K z;Y;)xB!}g>JLg-AX%25*LwM<0GCfW!+IPO|5zfSFFq zpafHNyzk6)T1?hE!(^X@=aP7wF#xYJ-!2c~=f+U(xM1mkU-^Jd5In^b(g)tkOe%P5cT@y3l& zsbl^!qvW6bFHC_q3kRz@8SiyJ_lTk4y)!r{O_-Lyt@YQY!4CO@6|96D5{Pej|m0q19nse{_hz>uD{)()0a*kDSfQlb(d;09!G4UoIHNT)xo(`Q( zcUAD3pyKPT)lM5kK8Vpj-a^#rcy+Me>_Yy3`JaYTK6)!~{@+O9K^)bhSIHifZOFa} z&4Yx>rg=MI531yDI=l|{piACXZC0=cNgOO?ymiqFWYinZ)!cB02DWqSJP;xRt~+O} zx3csB-l3%8`?e||sd(+CG*9#)mUC*DwN+*ie+{XVyIfSTvk2XT3O-opx4gsCoCmE! zbYS&&JC)tc$cGbn?@fKX*!Ux+2i=-lyi7|p3;N8sW4M}%{I9pFc->H*I^BDaEH8CB zro7Jt+s7>Ae+de_SEO3)Amgny*ei>MH|UZ7Ny0mD;t?R>eLFMyxh9Oa)>C}}S4}U_ zXSg|!KH8T-Jgz``Y052^qw(<5Kg-O%wq>m^(@u#1Q{N9ufL zohu~6(D5EMe4o1Z;|rR@I|9)$hS6Vy$_91r+Z^DnmuAmL7HquN)qU&UE1U&|kA6fk9Y73>U0!;ztWfe=LYEw6nHOpb^A!h+jrRm88p1F*lToj!FWF$ zv0hHX`{pZ~a9$YiTe$-zp>3XEJ7M?Nw*gC zns;Sr3_{0yz3b`23`Yj=9Z20g(QZX%2s+-9xZ%9G(Gr@&TN2TM)n5uPx1Vzt2MCOL z{e7=S52kx34|}(1=s$$!9()m5H-er2os*;V4Nq%<1dJP!h%bi;VNZhzKI%Ky$jPp*F^eIUKzd9#$gCm2=yl5e!!9l9h{ z=>JWE2!a(ie7-#cZ;&czZm%v>0Svx#2~Y2%<9)@-HIgl{A3uNWPhFDIA-}LBbi98W ztn#Xze@=6FCm}kfF#5YvujlL{#0hT1NbMs&>c+&oH&@M-sP_>1!CRwoJ%Nh+&vx@* z;0AfRKOl`;Mx_q_QCHFf>G0fJi~?`=Mb@v#co!FKmqNpvU0yb{2gdtO5=%ZM-ixI7 z%6mF_f;;E3Dqbvchl=KY;$KP;!SEDQi1ic!yuwSyOTv3^+m_$FzWy{i-kYRncUs%` z;dPO^h*fn@7VkmF`-iKv*|(HuG>5k`qGJN1Kf(^LzL0Aiz-eD1@80cQn0R|OA z&xA@36#c}vQ<48;wJMiMR?|P;SE$obb!zCB419abfBXOFv72W84eUX(6duG|dUz?> zgLJYMDWiE1af;cY74{&)*5ttT@DSU-QcvhBJj7mJD`4KqeGuqGUe6+?ctC5n^BRgQ zCjwRlv(%mZeIT=oBlMn;GT0`5+TKsu1VZ~g91=*2-()p}*Fx%E4&AM?NJ3v?|MFpN z^XrgOn)4uELUY3C|73#m3OXX4_=-v8e-v?8|q z{BF9RL2etNPKWiK$Mt4m3;AD$0&kwn?@p8P-VoEQh=w=Y#HpQaFy7fY$Ms2gHwNaF zF~R{UT~nsVxz8JXt^2{uaKZ!1O&IMeb5vR~K2uW!QK#e_ph9 zEGripIDa;wycs+H<4Tvx#Z~U7d%SUF)aj_{8}7ON=LKnL3cR^pdhV0)25EN`(D3fe z`>NUwAw6R%+UBrw4Q>XVDdX9wHd%&hTEx)d%>} zjkx1IltGNwD`n?R=y(fy_8g7!|B8=7>O6(=)vqg{q00 zEIQud9esmiT(pNbKcXWHqrYuJix?9hbAZa4JvR-!u<^bU5pi4q#yh1h`ogb^ROJ6_ ztQkj4pU^$txT{p^*gG4r?oa-gq`;f=_x&<5-fe-Jo6+!o6riQ}0ml2S7DE~d?}2mo z-H*X|Th9zbf^A+v_=P)8AMXw|3^3*^3c_!1)kjXNEa?O7%dFcpR>{4TR&wvL3GG9t*mtf%o*h2ApUmG=sZZbJSW~; z1Uvt~a;ccN*t?VNhgd~t>U7lY?H#;*c_IJHQ{XKSCHRv(#8$XesH5SXvQ0kXJ&d<% zT)!&`Z_$knL9b!FZwG?NXEzUmq#6%qg19FnXnnrZYJLE?>8G*sO7#Jy@uA90US&{q z>!bcFDRjI=V}3G;e;dJ@lw7I>jAHqT>cef0Lg4qnF?vr2TyAf~-NF(8 zwgl>QFnucNxb$cLe-j1Xt2Om}$#@q%_fbW|dyc34ax;uKhrA+@w7jLY=R{W90wLIj)Ser@(!+XsG&weLyLQwE;-zH-n1 zvb=>mIv`iK|2y6Zshe)@zts8#eR=EMO2R#{IojKtU`BM*V)SR^sOxIGmjfKiDe>K# zhP^p)cRQ=U9VfF3a-`wgTmH-cG?eqvT7mPw zDuoA$7T9kjc@Qc8?_jWILGz%_T>%GbVGrUweqvM{9%Aj3+k%+jH%QNA=xlSm=mWZ< z`qKvHJfVA=ZkTC2vWy( z_Q~t;!{{E=rB}kzCiI5phS*v}#|Mo5*w}{a&+Ov>%J~^F*QXaQa1#x*6>h9$NSXxyM7$$uW1f%X+%c=Mt@gy%nH%m=hz-1%u$l_zv)37`AL z;Q_Gz?6!y@%|37!IxQ7uqXb-tZrK&b_M*Bs>+(SUD;Z;WJEYDb%BjtH5*_cf+f7rU zO04mV|du!l^QO z81MJXo{PK5`T!ZeNBQ=do)GlY`|P#x0l>a-;=O}vAMmVuqW#bN6I^Kh` zauqycWB3-NF8%RW-|-%Fy!8mYRs*H9w>dF{=-7(U-+21#3#*toLHWiw)`##TPGpSH z{ya3iajs!$KBU8ZA*jM1`+~H!J}V2fMvUnG{=bfc)alSxjEmy%TiBdXq`-R(@rW}S zZ{OgH3}|>KdR;iz0OP&6`%*t?^|rk{FboebZzYyTtk<*lp7x^xa^ z&>r6V5FH5^{nZ2;T|9IczP&}?_MK`hHr~!Zbl%0mc*k&@J*U)0MgC7yG!NEqr2qU+ Qr4F`x@7{faZ*Td30Fh2Dvj6}9 diff --git a/planning/autoware_static_centerline_generator/test/data/bag_ego_trajectory_turn-right.db3 b/planning/autoware_static_centerline_generator/test/data/bag_ego_trajectory_turn-right.db3 deleted file mode 100644 index 0883307acbae0ff5e4a42efa165cba8ae262ae64..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 2654208 zcmeEP2YeINAHU9Y&{imWmc2Wx~3IVz62gYxmAhDJqERDX?yc-avr6TT& zhzOq^_AdO0FQfoc04abJKnfrQkOD{nqySO?De&K>KvqCtv#xD?iq$$5J=d(((k8P) zYmlo|bKysmB9Ar&CQlrZlsO_QW!&%)Q=%#ii5fpH$}udeTiIJtNg2uAt&#qcW^LN| zSc}by91ZOl=J+>&`_{~)VW}g^zNDL41%D@V#HbMyqtYj)q$N$98Z~yr)Lv%2L9K*` zDtmL>_{^wrlTuTAmH$!4=gQuSQYp-es9~w&hebK=b+<2q^wBdwCp(VOH3 zqdr%yp-mOPxVzQQ*G|Z(93jmLGBGV}|JSd=V>|BhJ-Fk2c_D2y!BbTxsAI$}Poef< z>1OTCK7>h`PiqzSt8aw|u;1%u|EJPlaptKJrmRw%%trk!e~Q@VJ`tBF_zz!50i*y@ z04abJKnfrQkOD{nqySO?DS#9}3jCKS5bWniwaB+l~MSKzQNyG;c z`y<|r*cq`SVtd4vh{q!yf-L^KBbGSV?O z*I`TnT$30jT!%7K;W~sF57)uWNVpDShQM_o(-*D-m_Bgr&vb-qKc)p-yD?4S+LZ~1 zYZoR2uALcQxOTD@!L_4R2iFePJh-;E&V*}}brM|LSySQK)|w30HrD=dZEcmpwUxCC zTw7Y(z_o=n60Xgy!EkM6g$vbmE?k=E;nJ9fOXM`TG)jj{!x3-^BVX2FFkC|8;1bdu zF2U{K64V4Pl2Bs*`$SxYtM4TCANUDhNCBh(QUED{6hI0f1&{(r0i*y@04abJKnnbK zDBzp9B7%4&8box1tM8JCvk^xk4n({bu{mO01QTJ1m>H28F@SyZzcXo^2~q$lfD}Lq zAO(;DNCBh(QUED{6hI0f1zb|VcXF6tpl`D$!m^+9xv)CK2o`e}?#{Fi0HYR+_#A*c^SC?dlyW258xviEfC&3*~-iHQmQq7&hsMx9HW3<{llpDBb#(Lsw&`-5rJ zj^E`PT4AE)DtIu`cG8_MRTS#gDmm%PNcvmCBPnUQQm-qdb>y4iFXbvUCYs3)kx*s}*@V zy~(Ur!vFjdBw3>{nbf&zS~a}<1Bh=SeCJ6(luW9U@JfS4ZXpebU6S2knMB4Qr3EN$ z^9z(vimD;5)N8d0ol0t=HMG)9tE7c=zFMhqN%+b3A<6cSf}GJBXcclnfD6pR00}i| zPStpaPSH8`JzEYvxIq(f3H=pIj<@Ntkcw10m5t`y`_R zj{DE`Jqb7Q8K2y$$;l<#?Q7gx@-+{`ZD92WAB#8KoTRBoD>WNm)8AYaIlbP0*Q#*-M zB#ADL#;BkNQP~J|mNG);D%2XeNs&uSwMH##`_K-W%i*XSaMTvYl#@EmsI4KD>x;%R zx1oee(>mbn@O-lx3#SE238Y;cnw+6eNNzE~743X6F7kpqB-DuPDoJlND=XOddO+FG-n+(uwh&U$~+&x9? zo~->(Euq2}G`J9YcSzfyEt2SfFChN!2RCoiYsvg}5~_DrJzzv=yCC#L7-yI4)u(WM!Sl4%K;blpLFAw?`B#v_NL(TKnp;Vz6t#o64!10X z@j+LFOf`9~f_QCR%MAO_k?crR5k;wp=9X2G9Xx|@?z1jW1lcpVp-6U;2Px7v(zTFK zvOEXc?FK%$%jH_Vie?>Jt|W>*fDgmdU^J_hqj(V#FY@LRN?MkLsMWKP2-fs*u{ox( z!;r#aB#AA!Sr9eV>f^w)vxzTNlhBWo#V??gINSRv6+Vi*5XB3ssf3zQX81e8q7Dt5 zz}{k#LRK`KTd!edPWd9JGQT3(K9tCtiL?RIi>fbh>WOV=kN@98^8Z_eJ{OW0^oC?u zz;6EmzMuKrbDPY6{4-7zV1{&;Pzln=B|W7%iae+aD4>mG1*q7Vw8^Y0k6#Sa>oxrN zj*f<1-en1e2hAb!RZ&s)Y76pr%PS;qf5k*@H&9vZ_GJ+%PjN^SQk`O#D0UZag`$)s zGL$psiR{MG6v5II8`TwrcR}Qmu~G#~Xvmky%~dPq8g*X2nT>op?wHhhP#;uo6IGQ% z0qHE{(;4hg0i#F|+VwtRKf-hiDqCJITpVJA)oh?**&sI=Xj%nT&Pw=)R`KQOX28%4GI9hr5Vusp zoW=Yo$bGSU!C08zLi_SOy2?s?l2djlYVm?vyxsn9M1?O8YY=*0NY|jJC7lD_@{jgi z>eI-{EUiaBGIQc2)L3?F<2+ANQ@%RaELYJ=wF<29JW#3SO0CKPN}l9|Q80{C=lEB= zkS6Cr8(lwg+itYmy2b`kMb>sipKuVpVz7Z2Fgg?K1d&4lEtDY}r7Akdk|zgM zn@i+$1SYB)OFBv71>WQ^u3y+ad7B*YX!6-)#C|MJ7dtI|0 zd{!2t5qepa-C*6f_C1pOV7U!6g6kmSsBmU$qxDAO#zlq*MT`{DuvdOt!6_g?e`B5DLB~EPnDUsAR_i|*r zI5t@awP{CXGm$j*?UV~}ly9e89HXoV8Z7>rHlQWvQh0JKiX( zDoP>|JJ3*d$@W+@N*J-2@4<(8$dj|M{ncDxKFKkLqj!xlUr+RTd;WhE6<*ZfWa#MN zXM(~5_5NS`CHOo?MG>Rl7CKl$Evg{+!4l(2)8)B(jYeMtrkDm)Nh7oXuz0R2c11z3exebP;Ii5CkK`- zqcnC1hHOP;{I%{6jOooruxhq)RCJ-5RSKlViXvEKdHf=-Z#)V%k%FyxKVVO1PqPPE zq6OjPSX(Ff&xL^*aIH#hqtc&DGU_2y`R&cdcrJr#O zsq9sEyiulvq1%P@9&zq;FOCt!{tuLdQQ_tWr$S4D{|Qo371NT+ecP2wzuQN2Yp zKs)`_CNPim1~>u1ZW&e51XG}MBKv;zqY3qe-1Cwo6wP){bWLvXUqffyITo-`U6LKf zO>_)H>I=kjnAt-mR7QowtxCcMz-~}jOfHC?&c2Pr79h4QL?)q%DoFOK>`jecm!~#c zRBCdZnMnh(UJj)dj?-B%d?s|dnmC)&7CZ!UNZn&bd05PqLkvTiV;{~X95$pkb z^(5b+y1np_JT7|)AbF5HCK?x)%fmd8JV+i#mlXFs^@tus52D9Q=Pcvm!o`J)3m4bF zamM?d>fDllv8mg?N+KlBt*Ip%buMi(D0BndsC+~8#JS2cMDiec`bCq@ z+_<;|kbttsMfxS82hlSi3f=MOjz@RAKu!P}73lM+_dXwz-f2X?PrdW|pi={#8nk=< z8??L7?yBd8MSVR~1yyBKmFvB#jB2v3HmS*Y6o>sN4wTI(o2xIINwL2#^*ZI-0xosy z#bl3=Q1(_*<<%i3xgsyG{MV{_s9~orF`c@uWeyLbpc9n!a+0*1o&xRZkhEe*ixL|p zcJ(DTq6g7~=)sUhZL-CLjxnm|ZbKvwdtN8*T)1=L&Q*JME-?4QiTxi+O`^hgh0Siz zHRRRcK9bJ@r}-c7%kX&wua+LXH#f9>zdS#W55gbb7_tJe7sye98*HhN`{k@3TTZw zU$5s{DplR*1bGrAuB8TJ9w(s`zA(ZT5qNOqBAw}qv_NhL}_ zvg_awNrgtv%Az8*IUf#ZFH{)S>=CS3hCV)ewpvjvO^ zq9#~LN$pao9k?Sv5D51^u}`eF-Bj^FFH_Fx2x(*+9(MX10+n5 z=IRyYePlsQ=b6l^a%yInjc^_mKS6~cSzo%BCXbX*ZOZ70RIGOY{}3Mw6+XAYU!gOD zzYQ86croC9f2r@6a1&qNp#U>|8l0w^M5L)fq15VC(j23rfSlD0XGqJ92D3cIem|~U zDx{J3CK}8!yn-PXB`qgur%aVlQns^h1@b}<=}KhHD2ATK+GMSYwKI5WOJpjR6q;xz zcZ!5chJ$p0lQbGTor!i!M)1-ZF+707@YF0jhRX>} zv{xb=Dv{StTaXQ|F^sfz(00n?TjT?4H;^9lJhVmmAkzC_lS~4Cv>$kVZgD?Y%xaBP zY1A9!Ir_QsT(t(gpS)+F@;id?D90$Vobb(*Q1jekgtAzv0sjzp5G^vnRlgo_p#WRc z3|I~g!6|*qa$vpB<|4JpEYG!=NDziw5;c4Nhh@i@~lIN{zI_2nVv5OmdapZm9F+~Q5P2b^5)R_IMG6jRN~OrI_g%!{jJB{+h4aky;>Zd=o{1;`uAOWs%{uMl~O z{U73!Muk5SHYW6Z$m-x&$rk}i|4`qT;3mG@qX3hm2du*R#brS|$BC{c0}Wo?s>JPN zI$y2S&>3U^?qy>3vdKEIYn`nxvqi|RMZ-%BVJB(rge`N%u!ODB597$1a79=_)wZ5k z2}`sZFlb{UmxnqGFSEWHW>*ZFU7Y^~>quSJkuuW@z|e>Er?Op$b*O^dw8{+#vqusW z>?d!Ci(D~NW&?Sheb!~mCO|r~I?McigpOp`u z0B7yVl&{XM+Q(8R8C>o17!`0t1t#a&DO;vK*(qD4P(b~O9Caj8;7-f62MNpfGZwPE zB7wY%@<1GMiTxk!b0-!4eAu|qKSO#1%?Nza|B~NOxP`CVM*&;kxsWKPVAJ&sv{6YL zNM*QGpEH|Qf^epl`aDu52)9%;)CaOZDK!?*JV-cPs?_V0Y*D8fazzwo1!QFFl=()z zPF;d&mR`-DvBeevY z>OIf9@_KCxIA}z$4S6My-entO4x*UgY756I)|pzX$fHR%F4-7K-gFL|FU_q&wsVaX z-c>?(JmT=cT=oG`{bOU}Tpo%jQfQ7e0W*DWH#2ef^Yre=OfiB3E7{3ESPV&*kYG$# z>0z0wD4GcGp?5`$cV*@r2{q6;=dviDhN?aO@Lv{rAA^6QeF5VPka0E8DdVb8U3E_D zWVOx}WD~FuhAo64_J0sHh6)=HVhDO&;u|o{Z>!H$xZ(E8*2@atWQ}o4Gb^)Z*9Ow!ZU$Pt|t4qCpD1WB-+d!ECYffN|A!y^3KR8lRrl zI!Z^C0MkZfL@t*|%Ux{Z10C2wqL5o}a&HSpOtW&CW>uP83`idAStO&t@wC7}6uU&R zJ^tT}3LoEKTc}U)M9DjW-Te)|JA9hC?Ev^MeZbb-8VsvD*e&bWpjYdlI~QC?OdcH< zY%gSY&X^Y&i0E$(0^a1g6^W?G8!@^cMv?S7FEB5`Dgoxnz05q^M?JldfqTYC}Z7{aJV7;YhI+TRzF}@vd7tl zTad@aTsx~Tu&S9`a<0kO+N3ZLl@8b?{2b z^+1jPQNJ`e{jX1DgWeWqjf6wC*n?NZdT)(-wJDBk^=q-HxijX;ni6lF}OUuvpmA8vpk}4d3bGkG^ozGd+3w)xU;6CH3ZnzuKMhf7Q)H#P|aLk2#s0bP_^LMQdkoI522E% zaASkxp&7yZf|>^A`k(O2@%aXBih0=@S=#`gTU7R+!XdcO*iLSu^R&>#)y~JNPXIz! zsi)a$lUQ3zr~<8Ul`QLFb1PpVlP%M5)GlKYtUwVgGvC?@&YFQU^Pn+|%VKkbkyfeg zy&bd)9c?M3jfHBH1*9N%taMp}?lgrF3T4nmCdx%dSzAh|sdI$sFFGoaZf8_k{XVV% zfi(cNVJ%>jNUOX_xae_fXH&3<%o1-(Z zap0}VDiwL*+**;3jT~2LmDKTBlR8hQ&;T20V|JYWGzS+BlQqqnFy^H5)T44Q{tG!HvkJCdbU$vmvg2Jx&y%h2PN zVGC;qU{lvhY|5$1HP0Ram}k^mbSiYQn7m$HZEIp}56o#-L+0SB@%XCgW{m>IRN?!o zYSmQUdE|PFSp$jzE~4A8h&ox@0k5D4|5iU`O?ZWC%HwOQskJTesl7NpRUIV8dR%X0 z$lC4yd@6hb)c=PE7fB8W_V8cp`?pX2f6})9*Cu6aV3kU!qJmolmBXN{>{D>O!}WUnm3U>`^Sr=wlhfGBc;gGTN6-TMY+3u{l{S3|YvEyv;i zEDz~}Hy|%xN(#mVU7e}wynORSy&9dJqMV(P)*eL2)r>jF7BEyidN52&YjgH9gj?Mq~8AgRK z3u_p9Ur4K<$0cn7Hu-n;eHm`zO9TZNowdJ&nlOn~vos2wjwI6?6y|(##o zoYbk1Vy~e=WrbnYCpl5-RkT7ydSJUFOf~9U+5};3_deq=9&Woa!4z2&CDe?HBvDEq4WZ%XB~rJg^+YfIm83uSXTH6dEglyFoo8536<>z50LU6qkNn&<@59k4ayzQ zx*?dk)>sK87r=a(n@$duQIK&;auIR6jgITf7D?+^zfeE714E3-8Y7`53DCaGwT)!= zkgzdZqa{?90NHau%~ru_ih48B-7|Ez+y6OK_{y+Gq4$S$4ticPIN*K%@xEXA z*OLKS#%LV^%{;1rdAYN_f-4Mh?g^aht%IvpVVtOrDvU>gUT7UuwF*;Ca#UfwkrB;U ztOKi7VXCG)sxbXMV~T0lRP$8xWNXU2SLxfsO(TsN%|UEHOFPl^ePj6{?M9 z=uRt#7Dt*I&>feFo$NM$>quyfX0JVP2(+rmUe*?!%e$*$40H;XrgPsh**;!xv}fH_ zKi9FI=x_l45n|wP?=YlgTQMX2YpjETYj=3nuHABHI=Xf}-I;;4|EalD`1l47g`5oT zB{2lN;CIe90d9HqW$SO91Uf;UcXR?Uh!r_-_5iVQP0|XesliG`1%Xo#Y<;bnz&yom zVP08W0XgRZt7)(`130I@9h@VJuR?|eGSCAI9Aupc4AkCk2BN3QGeHhpKkEeGAALLc zhb|}2re)g_tm(izVizD2L!zzYfNPVyv)t$$OCDMVo;D|Ky{&1$v+>^K85#s06peQKe+%jV_h`uJ z;8+P0@Tq@uUj?v^TA0_RX=@}OLR zM26|WwyZ2~s7z{|!D5Eo6=umhq_XD$AZ|$~tA3&;^gz=q zA;L|Q!`nSb?8v@pb26dXq^RoEAal3L&usocDVso zIj~QCd)bE$HqSWNi2X0|SxSY+H&__7B5-ejzh6B3im%&B0b38N4%QHHnt9VmBc~Fe zj#zUYG1aOKqL?r*+hFHAI&M<^*n4Qt+Gg&88& zJnp$Q-*ZP>^I^{o@baEpF`|pRu2*(ld;CA23QudWH00CZwvwpPbI(7vIt@9>dg9V>}4V>79K;WS*1m=;Vubq+9$hxI6$5~=oZ;l^L;MaY5=x*JJ%Ha zR0cUYsTswkcf_UCss}cDJJ+;~jkxk^yz+?sA4)w>g%5`O|93)q1uYF~8mRZ*gWpW{;iEFe|hMT7~f)fwDO7r7 zgNs*S@miZ$=K(CBlCvhTC}UftU~PpEjypaP+W>0`z=vdzd&lap@MNAc{?Sv)`E2@H zi-CK$DLml`;}JQ>aZYBP3!Jmuo^|KZ{7Gb?orT2y5Ar`nMJU4_3Oy7$Hh4o&c%TJt z;0q~$6hI36Hz;5WVL~L-0wMdN%n&uv8rJrgq8Gp$C4)_vV9*=d3B|@aM^c%gVAAUK z=6rI3DWn`LbkOI^tcNqO^ac{sapm_zZ=cAH1p!Qugfa;&6V~bCICU0Rh&NV9G$Vl( zGRiGZ@cLcL7LZ1*RYTKNlxp56BeMoGf#4p2*pztp2rtW=BOAalX9t9+sHaWF1OR~K zUJSmlmb4?NhM^b874~pHi{Xqvuu$zy7HafGa+SVFXODVd2+b>Up#|dyaskRqJuesR z9&eL_jqb|{V*mU5G@$(R{6l?L!VmTM#mr;EB~(_$*i_lxnX4edK$EmQOSUYupin6c zYI$Kyd0=5O*Q9VH`yn>sjNt`=@B%ZR34;SbE0W)2rfE`$DYuhf>Rj33g8muY$B_Ps zurG;I{--hx0;#DA*HWsQ+Wv+nOsIq^$d24rZuOYymcijCtT*T#dbW5p#!x zk_#}PVn-@m1D;(2B}|0yW?a@)3aRf=>VtvPqry3<)%CV{@PO@@Xf~I|?u;itYt&$x zfFfps!(7SVDgRxrfe;`qS6Pf+@{b@n5FPx73iF{OI-0=NWdr1TwqB4Tw|2-ziXcTC zhm)fmx%IeqqzF<(s7nQ61Tlgb@l>u7>Lc}09|8NnrveHom3ovVC`(Y5M91}Yaz455 zP)3~u-GtC|Oam{##Ms|DKNo?EhY33xsh8#vK@UVBCRm z2gV&3ci`HRiT2;qNl+j0bRPo5NPUd$VO&pK<0G_d(5|Vkb`9A7y*=Mt0rwl+Z!ovj zWWXI5cVJpMAPVzH5^H=?Eoy0~rPWt04K*|nq8>Vy8084c5tJhs#lk2SiDH5M--m5_ zi_-NrcMw1y3HnITM}j^QjCNwQ6K$K@-M+|jl_P_Ms>7a)@ zFz&#(1LF>iJ239R^?3)z-M4mh^hJFH^%2xZP#-~k1oe^nqmO|7AB~laQML4x0n|xQ zCqbPAbrRG`P$#KBItl6{sE?4Usk(3u6l!Rwp`nI`8d_b|(7^tW0a1(gFYY%QbuJAH zSvP=ffX^0%;0}xwsZhL*7`e5aA1Q(qiH(hmbJgGgF@hLDjF1zYopcMqf>T^IxN30K z;Ht?{Yt-gq`^oPrTA@OUc#tAs|Hncb0JQd^qHw>#{Ra0Nl&&6>t|(cf6WQ!;^ek3v z0*QMK?lrjA;9i4!O$7>AjEV}sqqT<=(Won80x9B2ih%tem(UNjG|<#5r4PEvsaxC47~2gco(%{Rl{SGd3f^%2xZP#-~kq{42DJ`&VNs;`fL{U0CK7k6NL z1_b7$VRlVLZzD=ql&;m6t|(a@84xI0QL>_Btw;fstSDJkw85NDS{+1_5?mvV6hVsM z36*$4B7++Pv(R@7TjZ$-To^;XoU zmd2r$<~=P9H8jkTSDVawJZlfn+QYN<>grj0weg%iu>UEnK#Iyo>1tN%btqj?x}tQg z+=>is8?I1SE4q{rxbVx39UEDbwCb2 ze~9fbKc-m_)vABwoxdkbAy%%pn2kyekkw2Za}`S3j^9*$o_JEm+=5y5ch6uphIChQ z9PvSZF303;$0%QN2|N|{e*&q+b;Lq)MA;XB-93-wKysL9lpQ)TaSB{4xL9zp6w|%|g)x1CC~HK9bBI=>Rw+mrT&Gl+X&wA8 zS1HU2xv5yE%s1+F>Jr*0Rna*X2&ES*HEN~Ytk%*HB{!>SW4xSwr#xmpQlnRx`^IOO z6)=Sp>oLPMdM z{kdE$j8hb*PtN3rERr@?p)t|SET)Hq8Y|-`t=yzA%X8IpZ$&N;I749`sh*287D%39 z%uII)l}7W>7-%bpj48bm8fxazdM#}>7MJ5Vvj}R{vef4MWPPE+s8;BdG;Vbw9g!BM zn}nL6tVDMMq=LzdfToa;=OAij%BRC9B>aG=ehKb&24S+8t`aI{RF#CUn$U=8k(kbA zx=5(Fv`VA}DMG8NRFH@1^%^9vNb;JP&Jv2|Pv`CHa04icFpqaYlwfkONV3yRCztkr zU$p-{X8#BI7^(1r(077cN>&H_<8Sai1~>5KB?>UJnZ6QgQi`*{w);Ocbgo%S6hBq5 zj+Pq~$^zPKD*L^xCSWo*B0~wfA74QLIn=R2HZf}%*1v)PTLUHm+)ZIsxSLpV8=*c! z4!P?Z@Famzqk-&o&eLQt>LH7r)Ni1-2|AZ}NU+<2n0VkvfcyMF&mXB^5O++gxJ?#Z zv2i@ESaxlw*rq5X-xkawBdJ${S|z(178i#%%A9S%Oe`=&!nZhFFa%eJr&mX5S0=_T zsg_I1Jhx68wbH0J$aC~_ao70w>UM8ca&E04t0(U8(hf|tgj$dh=?+p+Vt86&R5zo% zo}kp$kdcBwZC1tZCMNQWDu*{z4if(lqGnNH(?XsP?jTtc7~pU5lfVrRy-GVWLnPFq zDnye}otJNxR=ta&Y(m-OT%+y%z5%nD!BsnDj5K7XlsRG0DdUMuX>iI6f}Nl$rwmJO zbjpBYTi&6->*xok%s{)T~9Eq=b#l$x6VrCpejAgKMSF#OGW1CQB{avJ6IZEwd` z+MXF9q2{>-R20)Frf;i-&J-}iB~(@wNkeuwDmth`GmOs& z7hnj=YER2*TR4*h%xG9eAkQw1&__iQ5pJggH-s4q90{%tM{s?3dVQ33V`O$=RoO}9 zBIt?M4_ZIB-TEQ+f3Qz36>e_uQ|Q#-13@zaTl=r@{S$8C%VQLP7{Yk)17eym)v+dwdb{6(7wSr<5Px*_*g+eWa4a`;0z-y) zD!OV5V6r5XrCR*Jd=T1$EeRu-$*?jc)#3!^f_Nio5AvlZxt%Y?Z5@~f0``bU+eC&l znIv4}-uiILUMr;Y)k+PGTZhNCjxZ*}{k`0YBla{xWQfNY63$Gl(GnqNsi3;+*-d?d z`-CEwW4x{rGg=)PK zj$46Yyxsaq0uCm|!r@~^CI=EmZ>2fZMC9s?W>VdNRClK`LtGztCYMo2sAPLOmc2S9 z7m7*XoVQ$B3YfQ7sF1y}NMWSq3YEg3mKVl2RiPNQ1mHC&J*g*&-^^TQ796gpcakY( z@6HGC;%3ghM+ORWcwC+N_G8`zRQO^cE@B=P@(j zVBg{@>CJh`DwEvtM%i&gNpK925df}Bw%1o7`NfeRe3;X#>%&BknTO3B=y012O`hB{ zJvoOmI?Ft3a>BxxR^5exelia)4152-T~VG+SgC9MKh_+9hOp+2j#ra#2F3&6|N zK8b95oE(L-A~ot9BU`X7RVbCTMh?FfK+(OzAa}f1cD5Bcl^wKjm0U#^%JoVm83iYb zmn(ncl}ZbgyDN)F8P%xv38{UyCd_PLNK6eGqSRYRuLN3?D`!t@M#e^<=EyWSArz=xeaCJ+>AAv}hAHItt|#QVGl0pJP?7y3S5E+_xr?#r|5D!w65y)t zj>d;FB+!5;*VU+qAUlD;K~GC4dXkgR%;9@?^ye~I%6oOe&)}-h<5HXGxo~>4PN9*L z_(+-mEZJb0gnNV-2mKsIC80*-IniDZA%E6t1Cpy~HrPs+d*&;}p~gFglLYY^Mx^S= z&STI2pGt)r8ypMG2;LWz82D&_ub;-}2sO1vJ^*GBV*z!xnY0>qIGo3Bu$ZM51DN6v z@wMdT(Izvo$jcVhFuh(=eWk0OL>r;+iJ7o~?Z4!vE2JU|jEW-S1*yP-ks7_i92c8r zfsSiQMx&w_`5_R2v^8Q(z>gMepuKwhAPy_qXw)0!tX#BbaI#0Tm#+j zFh<}?B)jiak1KWt6e=_pkW*^f7!R()97|p$mXxm*WR6JYG-l=ibK2Bk$tW#GBWbf* zwsc%^2>BwCFA~N8d}&gB-yyfTquc49w$cho=6)Ys~yc|A+yOgXh^!Z@Yl65a}Ea?`E(v9d#N3od$&Y zT!?jQtDtdN0S3e{1td9FkwK!Jh;4D$wlGB!Dy=FVUZFHw?6GENfLGFBk{rYANQWzG zFCw%TTVtjWtp1uf^6egD@Vz) z0PoY8Bfe@S1xm960x6%sm7T^mdm?Q7(5We* zln+G(HY%m}T+R#hhi3-I7@XxmQ8@||9MrAW6~NEYi?vNY_+b0c8`>u{Q*K@uI(o~* z^qDWk4gLD^>V$;cblIBuzpTC6XQ?dz^4*i7Tb+B8nN@gthVLgb!*^>!S~Qy{Q>c@b z_iitc@sZ@$&dumg+x#<_=Eh}=?m7PXho|$7Z@7Qa`19t_J$&EyZ{5Gd&7+OL^My=L zyt(zyM!fUmd;Z0R_cV!mXut61@*gaG z<__+4b52;TLw6WAk8uLe_sIw6l*^1F zrK09>#$=jy-}6fV-F{B!9wG_a;6V2Y4du^=Zb_eS-Y4i@^GALGk=<#}Ox-bo$ZqZZ zLo%kP%X+<(zH}d;TXSKop%0)tZs_l;=L5PY?mp7!Y=zR1nvC4uLABkIVVU)>ccjM7_Bsk)m_H{z{p!Z(v?m%}!@Bv>wbT@9f=@EkN zye+$C6LcRLe64UWpu2F|h>J(3rOS$U_1cr-w^X*=$N%x(fbKox?|o=FpnFS;n3w*X zHeWWR?Xkv_uJEJ#P@j?c3upc_cqlh6R{Okc{RMt>@5o&9ch<|bPcu2r&10{?^UeC~ z%%G+n-ADJzU#`xZQ~0j%s(3B2!2HAabzd_{=_hI)v-+==rKJ+t?c;>*fgkxw9q85? zH~8?O`=PG%V+7sr9^T8MJL4h6s%Str^G8XWrL)pyUwzgj$_LPWOD*L*x6JKY9=3(6ZN6d1ROEy1(~xCx{%%e7R+t z;&j=h<-?o3dZkp>tJMN+49KBLtwUx`06CQ0Dy6}}x$|Ua?q7Fkc|-nP*6-e3tJZyf zbMRSiT;lw8$`gM4yKKt0H>@2ZBWj%-3ghOHA@F>=9e+TvXfLA^{ zU^oBt%^|uzv+BGYdS}xOQS<2T*KWlAr9_7ec0%{?ORpbup!=D{%|rRn{p!NclgTdI zZ9=M=pga8Qaf8`W^q zwO`#19Y87_u}spMa|>Xkv{`(ZX-HmkQ2I-_ZOXTpnFlt z$zVQof3RrIy9C`oQaP;spU{YTa3i35+XKNPn;6q&4@E9GdH#B-EZ1`OdxGw~S7wBc z0(5szdg(x6<~-RA|9cWEm@0HFzzkImLeRLoGd;jAFErroN?s}UAZ9d;$=h6Mm)mEbBal9dYYWm#- z-4Z8s4_m)%j04>_TJ8$sL-))d{+vW26TdFlrX{jlw)6eQxq$8`cU?Mur#4;I=wdg& z?bK3P)F+oCV*%YOf~a*#fbKU#Bm6pP=gGeK>bY)D2k>hq(S|O~9=v&Z@HgDJkq>?O z*%yEDqx-HM~q(L4oIc{rP9_9{Yp)=)QDfL#g?55s`@vPyU)WURC$) z|5eY5n@1aC$M!Rjy{2iqt{e*8f|Y9pNO0QWJlTcgUfveo2k^(le#7|o8jq4E1#oV*|G|CWW}&m22jDvMHI*xD21&o;mKL{{4jQ|F_bw9y_sSZ=Kg6U+N@o9yt$e{v+*8V*iIb zp?hqLcP2W}oieOXLq2pLy=0LQbQ{`+DhRp_Lx=aB0qFio+v>~Gl62YfRfQvFoG+DS zPJZk6UV!e0O#43B1nAy>G9xGP(9i}b){x!|$Mnh(D<34X#n()TS zY~Jzf^E9R&huhaWbWi8zalgRx9ahIIRIY2tJ3l@lxh`$d=dWISPw;b#KN)l-y6E#d zk8Wy@xOtqTT5m0kSq|t9b3%8@zPFk>(EY9YXapa+ca8qOn4r5$(`zicdtMrNGX>E7 z+8v{tY?zlW>tQH);5E^h!YY>$BI+c{aX8_Vy*KZSgz&=*pJ+2_N!4H}26UDdS&#o*&&i+r9nUM~B+fI&}Bs=CNDg`HHul$@t?t_t8D&%iI^w z{voVGJ{GE+_=xq^*s68v;62DMHM~S|Iy~P4&6_3^B61eeERTh zU$^hzzGiZH`|#64H;AzRXV2Mw_0hVIZi*2(k1d+O9&Bb}s1v$J%`x2Pkln3D-xrC44Dk* zUiZ~PZI>tK$&@!wc0T1IGx70+dmCN<(0@oCH}2Tc-J4QeWF|)JeD<4n$2G2X=-$lD zBU0e`-q;Xt7#Hn6y4Up$ZRmGeMErkKY4)0beysEMKh=JTsCl#~z_z z(eoJP=~CIjgkwWGfE;=t{nN~;exJzhPJd?d(Wxb}oS$E4^vJLLyX@u7A4I-!zVVP; zZrq)#dYs+%Z{)Zp@3B|^emndH_tAZ^ z$-0d`=S1j`@lEc&Tso%Cqnk=?AZ{M9LuX1^9kP)Vy2n4;_?iRVk01G@2_L#+wkr-0 z3+eNO5lVvY<25s_0y@tn*zG!BhTL1 zu0e_H*{AP(^YTOd=)QJ*MY}Besn+C?j>u(pl-De-Hv%|7I?ni zR}D)|I``3ie9nxAs}6Y z-!uIA#(d~*^vt=b1l?n16tUi|1$RI6zj=V}F}~Z6tk6KVkcHiNI z?leu@=MHoyjw_7hL-){T{g1u_=x$TcN`UKGZ==E1_uG(KBTa~xtp>L+}$K9?i-fmmgtl5w?+_-m}C2hKE zB!Ap(@q)zhy;jve&Ey|$9yWpJYn+z%>O%|MM|a~ZO&zT4y1>!p&o<(DMy$ z@O#GbI|SqSw+gAJ-`x6C!zIGrt;O;#zdY1CvCgA=akC#ziJ8Z^|NZ#EpSy^K)XWLp zlV1P4tp2~t#lx-m(7m(uwNFU?|H6+}vibi7K6ibT0qB12we8cUfOl)iuXp{H13Ki1 zz4PS+-KX_KXIlW>gXl|}dz~wmwP|fVoWGD?b}xFM%|}Z!Lx!~H#@*BZTjP;je%ZZp z#?UW&yxOAHp?f|zkJSRt_l@o4>6bdXFT1d|e1TG;;Y*Y=6FC0n1a^XOiiZWc9< z(6w>1eq2k?-P8%)nU))GIAr(GUpBPlL-&%yJ!cVgE17rM+O0RIzOp(G(EaMg=o3ch zZgKBD=lq9&ck7X!y`~d%@Af-1s0h$~^zKs`J%2Bjeev?I^33`C=zi~`t{b-{-7(~A zZrp3x1&aTv_|d)Kujm_vZ?>y-=zf=*$0C8}`$pYzW3k$Obbr4yC;!n8-WHbmz3*u| z@6#9RJi4hN%f!tiqD{wcto`4_3EdgV_m$;tL5QIRAG&8B4n9R96ZilAHCuPPuuJ%T z44}Jt&XC~`PEMDlof=?x?w3+o+nHfA2)bJgdAdb0p!=2n=JYq$mBP^;|GCoDk+1dYQ0vg`n8$g6=X*D1Q_O3<+(-AYDV>?? zSA{hbO7ni7)>#MZeEfg$)cvC7@ue!)xb;D_|8Lb~Ywz!+*=?QV(9AYI=N-H3?2w+F z_~g(eg*lE`NUtpD$y!KR_jT>bKpxV}mor|U)g@i_!i^De`A|bTu4TX8?LZDqU(_LJ zA;_WGig!i_{Zk?vl=bZoSJ&{%p(~euII!D%X7^BT+@^ZHx)<uhaWBw&i|)^(r=9P+gbN_+02Qe=8-yb%|D%X zlz{$Ahs%#)=zymR|68~D*Z{f!=qI~SkXoymz4t(Jy6jB;$-OT?4yh*Mo_7ek`~1>GPAsJSpiQr(eo-vjJNM^_|0wt^ zq=CjIy(jJcarb_1+_yRH_a02)w~$U28CyO*?9W;!yHmJ%91(cFWncA@b~)v~cdJ_; z^^6@q3)}z9r+-{n_4yNZUUqMP{0C9PER5euQW>EeGbqa(zj_&3$T#ll!HdTe5q8nPBOX`v5>;I{C$Y{ZpVxs z^XY_7ie)nbzf*rVogdxp9vF18`P-lFR&e9i_FQ^y<#2v<7d>|KhfmKOt##;Dar4L! zc)qu;6#P1_yZf5SwB2U^0-K2V|Gt*@wTyqH&ZC<$>|ZBp9*KU1y;=Ler4zcR4ogUK zpgU^#tag0pj*~AvMbMqyN@5`Bo?P_GFe%voXAiF18>>l|J^EYEqaC1j%kbrMa|ybo z_f!20fbOv)G!{?)VJns*4t-Kdd-Fz{es^mz z^T3KRosaO0zpU$stupsoo)ndfM9e;FCkk)9#)8A;_VBT3@sfIiyZ} z>9T%5M}Bc~64}+Tuj1xy zxY>`focVtml_Q8)q~#k2f?O;xV##=!@EL^LR+$`95wN{c>_A z_jlR6%bh;WI3cV<=8WDF{>Nffo!@1fuiP$b9``=FGcs)z(IGoHp*!d69akLa4jyu~ z8y~uF+-&sC0YLXt(|$1#bjKe*aNin0cThN;t%^>UozHvmu9pDa`_``igzU0(j~@mq z0NqQ@zHsBY3&pZuK4Fd~S^3eO7;$hpy^q>+h8y?E1Km#lrshZYp4Lw_RcGH(>(Jeg zo5yZ}=Zn1h=<$BD+(&nhw+wgXEE1tZ79M!|-8Z#$9^F*_x8mlp^slsjtPa`U3Ehf~ z*@+HxD~!9k@}Ya*xpS!m-OB@BoI}uk;n!W$mjSwe)?PcD-XmSsXZ-&rtp{|c&ep{c zbZ0Mob!7pddv2Qz`?437$Q~HF&zjkgUx#eayJ*^h-WPXoTcrQn*HPVeG38ITYnn1^HY6^EG#WhmFLTk?&+_`oY!_cwfhckoG!3)ljyVj z=zeBM@sBU9zg+9={~T@}PY66;|8b3ye?RIzy4A(Qb~o57jPB`EwmvXAbw-`{-M;Yg zGot44iY4bqcb16-;4b+oS-}Dul4N7MD6EiZZ80Ir*~$o zn_8yJ41cAJNdt8Ee|^=dwt()o`O+jSpu0iaXAQq=N@O4OO5a{^lV3CW<*m~1JI+15 z`y+1L&dIwcw)vGG-HpHL_+IBjf7d#6pXcTgF7SK>$F>;t-aMcAB-;NTG9Pcl*OX>=bCN^qOAB{8cG(1Zcr>3J^1W-; zTB1Y#z51w;=#cMx|I$6%Kn}f{KDX_Kap|(-LsJi|hd!i<2fo})Dx^Ptx#w5yKn^8u zD;V{_J5YzT_wbecY5cpax%)?B_grtd=PquXnr?M+=4k#1>66ph} zf#=&Y?@Ev?)cpwQy2saEUA0$4hcutFMWu^N>%JViN8CJAt3&ty@dVK!yE>sef7i6% z9OxdNdAJWBy5G(C^J{|ck)toN_J6~kXD4q3bho|sO#GQK>9Wl4c3w&XbU!e5updG9 z-OpTkxd)&-4^Zm4X#Fd9exQ}klg9kp1%@#)YP1X8k16G``^XSg`N!&cT^y-xV4x1s} z#R=Vci;{kKpgVQUQ@#1n?RR5Yd*Ztdf1(5HyDd4@(6$B8y=%^>4+f1)myPcG%-|oO zL;8&sk4@_c=>F!u2mVX|bYDJCpMA_!B0F__`o>V` zZqd5rx7mPhwe{C+q%%>B?~MDB0Noe*Bxd%WRw8?U#K>+_e&e^0_RlB?(LCR9&qv(2 znUTsSo4(;k_xUBUuUV68pJwt7HxHrbyF0pT!(p$uZy`N9WG&U{4<igM0QiYnrUB z^Y(u)**;P8Q2z1aM|&2M%EV4i=%y1wEe>>do|M*;58Vf{+I>XOt!(y95kdF2XC}W& zG812jS@2fR0qL^!tLA+B1K9tXyV_hOakn-v-2X@#pxgJ@n!n^n_v*W|Yzfb|u63HpI&L1T1fDNu#=!LLXWWnf-?8-c zGdn*Jmfee6EcgF-?Ug#8|4&)&5;c!)6Q*p@twa0&HW=<6`V*zuy`AKc{+E{(4mq@L zw_jgAIdpjC8ix2G4=h>D=8!&+XB_+_$f14XnmwD?2hRT+^W|O7f`!zpci#&{hkW(; zg9m$p9C{%p>&vU-=F1unQt7gP=Raj^VRoSH9X0G{@+cA&71)guof;oPJzjj}T>=O4dJ#&n({lB-t{ii>=x~$Hl zd+3&XM9t&52JN=J3|V%i**%@mtu0=)%Yp9V&Ku+S(Ea%7xf0^t`rWdX%^~fcHTB#x zfbL_Rii-vePnQK9)NlU~&>g(}-Gc<(;|??oZv*Jo?YKDMVE=it|M_%iZ2pWN-G>Vj zzB&AG*q)u-xbIfjGE?^PqkG|=ov$REu6;V>cicP{3q0TT+ zyQSm0IVoGduJh=o7?JZ>-99{;&2H)8gl^5Kvojs&PJBik%ZKhc7e{9hbhjP-1DoA) zx9ZUJ=K$UF_cs`5oR}^P&U>!t7@+&@D@#Un26TUt`SGkF) zx{v#E=-zMCZ@n-@*vtNB><3g=+qychLvE#?6g7{zKl*>xX(_S)W1P@!e&Vm69J}n& zBup zNI-YTVW}-b0_Mr~Xu72u9^%&_*PM=>mihFt-Fvxluf6}?q%$k{b;t?r)v+29e{$7pz{{Xpq;PyVk_W$BW+m;;t-(z(i-Bjo0qULe_`}Thvd5q|g z(N5?#E%;!T1KkJS-q@cH-G8k=bdsQZ!@O`dhxCQ5cOCj3(B19$xX8zQrprp-+W4$5 zSV%kajjs~>KjhOPD@pFw!@ZlY7t@k*0$}R=XN{B9U68(`-PSt z-LHHoiJ#Z!X01c_8g3r13q0Sv7Xo*T+vL7?tIy)aF%61^V@Q)%ZT=`@p`^}7NE-~) zikrtLe|;UnqFd^OZevFAn+|kecw5tt58ax8;%fxm?X&V&bbqo)*I+-Od+wS4U7b|EW*AQI9`S z_t8y_|LNvqV&-vtDni%tNt&?pDk+pZn&|mwmak+tZC&YkA{E zJAP{Z+K_fWd%ohv?J2$1^K|2xyyKr-oicOjtF^B((J_yw1fH))>^(bUs)6qK%y&)& zeszGCE@h_P#?+06zN!0tx2dS%qUK?|GU2U8>oNXc#{XLXLuq!RlN_4&!GNcT93uAr zkCEwtd~#_0xbHg=ITU@cAuERzoyM#=3v#H-vsx29C|&mR*c%&ugZ_WpmhFCm?U2?p z=>X{=eZAowhp$odWYa?LFGzFIA?<_g(5XH%e;n)>w@+m@KDv~DmwoWFFZbVh=8xUA zjof>=dE6)Pd|$MQ`(XVk_jlRcjPERJ9uEc|YJAR0 z?Ek(_=q`EWN47&cLHF+ubqe4^_pr``LJ7J}lb&XE$Q60Um45=d1LH1z{N2EG*_gtQ zf6u>BDtlcTKb>UReROoBYki~pYYvpiR=@qXEMLyAL#{hIH*?+>CkNlfjq{H` zy;7dWkM4iAeMHAkxK!)Vy^5R1Wr62={7CX^Pqua+-4o}}Ki}(nVGD^mtUNm_u}_^x zHhIgyw+ABjBTobmCdSq`i z9KGw_I*;zc)Xk#iu~h4ShyEer-HLZY_uN5e_d3x1@Yj2N`Ow|(uP+Z0bYE%t8tc1# z5YKzGv0;^BeNG4}Vk&DV6J z_|dI=eaEU-xBNKx95-&=Q}1p2DxM$R+hdQs`(x~%wN7?V=jQRW!1MKK)AjMMH@h#p z$6SwXx9m|75z_m|{P@nKHFX}{)DwNh&11u=3GG??Kh6o=MGf1`cA)!N+e#lkbX)1J z&l7atv$;2m?u*anEeiv54_L5ibW#6wS(feNn|g>$JkjCHlO*o8auu`j8l3;P`1wDJ z3l_|iS)>m=wYw>Q-t9|G{!-jH`T5`?ZrrMAH;bjg{CT%e$@UDGDK)FlSGMSNQw$2(WD58%qo$vG?^tDNU2N> zC{xMM^t$=YiBR`P>;UyM+ zw9_rr%XE8Y4tu% z6Q#Rdb_GO-Ax3_e=Dl9=OpbORBC_pkU8{)QA>|o3RF$r?Wq2Rb528*-y{_~#*GRaA zG@_t8D*5U$GTrwqCFY~i9df*=p7af=bPwq(yYqa*YTkhE{DYVD3|8VHUg7KM+v7dZ9X{XzFPmauq&s5Zq?l~dc;yW0gZd@vrI_$e}dZZfC zkb>@m-p5Jb|HHdm3G8EBXmtBEY+!=vj^w?$5B6^3sV^>;fbIYyZ|E-w4_(js(a=8~ z1BJyGyoC2|57^~hh9{&o)|wkE2jBm1x#$=u^)KK5?@%d@EZP00h8(wO^{c0!CeZJY znp{fXJzo0R1Z{=-Z~gN?M8_J8{FX=Wf1ef);oUXMO_R}_j|u8 zs&pu+O!h|S!QO2^L3iZxCvVB#9ry4yCmP)q>-H$Y_y5~gn3C@QUrt;(E(_=`?($oG z(i9J^^ZwMjcP<7x!elrBPe{X8n)M$BbT>uiX6_FrKpFF$RRX!tz5A8d72BDRE)#Ox zPkFt~Tc*(I-q(Nn&BoF9bk`v@Av%08@@r;h*XG_qyLa19f8ujaroy{J%A(@8{y*?_ z%lBK<>3DNPUWMe{`V@3W7$tR+=@z_qkOPhGvofK^@X3T7OAzVY?TWWl!Z6soHLp1# z)eX+w6ov3`Ipe$}K=+fe?Ja@EVbBG4vp|Dq=yacuAKBU;_SS?P z7b$)GIC~v>Wpbz`B>LXnQM#i$4AF4_BfsF^S7QqPgST5-YoNx}+ySeshw;3av4eO>;>VMyFz|-d#|Wknc$F>aIgpkBd?@yIx1RDo0%TL_ zp{~h+?n5a*Mcc*KNfS3Cak<_iE^J@WSJ{KN`If$qQ=_{M=?tPH8Y90aoA<^n9ix2? z36uEg`)^0FYsd|v!#~u0@C;u=p8ZIjj^iiIe^_|IHRK8kx?_*jqdNe zRy86t1=3*V~cd>BhBFsY7+M_9{{h2~p4;N2sU_z|9jDr&0(Y+qgA&ik9>&BR8M+a&5 z?n!C4#O^)V-fgVtEQ#CogyHFaa-KRJT3Xg7hYDctHl?8Zh<@Q$GTome3l^Z!EtVW* z0@EG(_;mzanap^9dzuC4#+Ql(2ZQ(jL{C-k*Zvv<8NQvdgij{+++te|zujUbkTrEy zAM9@7c|XWDqto5+JA3h#5D}t15+_#oh?h`?PIpHpH!*i?3Ek1%i0F8Vk>9%IRkq1X zY4869#h&z!Ha)<;A#L-bDxA>4@O0zCx~bFQvHgfD$-7M`=#HK~Wl5%c?sYg18r}B8 zd*xudiPgJFbbs2JGw%$bTjRJ9n?88E)r+M^&;Y#u*Op6kcWJ#rR&F1U@9-pvPo$0uSANpncWiM+|f} z>2f&iLsb!uB5Q#UHAE&k-(wGh&fR^o$vX|*hX&bB{j_``MI^^bA;! zY>=eC{=W~=(SVWPLYwyV<}0-O(0#=zZUr3n{eRr4%7#4`T^N6r{pCrOjtp+12+kd@ zAy-q-oseL1=x@5GI7HFtcDj8o3Z}cN{vGLd%lDVtubqYIHV%?6PQXKXIGOCb-(#Rb zelt8=L%N8q9CrkCr}g}DuzpQ|*aat#O$DOUJ#nWn%X+&EksMbv_;AW+2RhxKb{#D| zHmgo|HRL#=V-zDlbF)xQjw7_!kQ$AzGm3+->F)iN>!tGIIm6Sfba@3;I+$G>o`kTR z0d$*F&>bHbUqPl@>DUipG`dX-1s=n6$5_gT!`_|VS9T@?&>fq?qwqBz53M*WuvHGw zUDtGZ3EclHg}tls2Xt?bJCz*SN`N?vOkyi`pwm4<+)ebCmnD+pE`8wDyuS&Z?kL?V z6@zLGx}$p-(QybPKhDr!GX+?l;?TGJl5`b>chj%(X z!TG;U|bj_r-``XJNYSZLJT&-fjNu8KD-?-TvUFt5h5wQhw3# zdkoL-?Rln1`d5DVJEjkajZgPIY@clo|^&xdS z9s~=Bg59k@{r`Wbo2UIxjd5B};X}!nvg*h_R4k| zF99E7H<7x-auN?YHg`XH0PZ2Bd&pc>1U~drDfI1I@EuZq?WAvP4*|NQ%gnXpUpl0^ zn?{+ri2}q6NL)^>-^)YW(S7Ka&*Q%9QuOzR)ICH;8Ag65_rDT0iKKm%_1=^HPB{y^ zL&Djs?IfPJXZRWtx15(M9jfU+mz}u`_y3j@bf4b0Z!?*0#q=MNXmkhG9#DaANVl&d zkX}ej8tyW?0O&3=ChEALZ$;Lz+c&IAY}2)Vtv4X;a!)S-x!D zo=fi7Q+7H_cRl$g{EXr0{>W!Vm5z#=&$(Pl(=FFg(4Dl(R+db+UEMAQG`97SWhTNICXGwGn0owjz zMu$Tjo$ig}tkJD%VnkOYuE!{~brl;r-II>fPl*>5=#FknM8^b1etfRK=6Cwj?%j^( zn=PN-qN4v-J~?=EOAo`-jT4KdN=LS3-A1My*t;z#=sv~WX-cNs?C!aRXmsD0QqG3y zt`_tleY<6A#Pu=}&~0b1RP+O&TSIU-h9A)VD#mYsDG1W4`K zWX?iqx)Ql+Yn55 zn|)LW-2d;6Pd|1H(7iL?ci{k_o6YjaeIht_ixi5z49{*^wD8h@J#PM)z)Ql~tLh^XczqVl1LV2P41nT~@m} z=1jJL4k^6nwy71^W#2t)ptJp7cGD8L!i@?_{teXR`EdH0TTUZ`n2*CGp5OGMH+Vf96&HwU3 z`o${SnKCQ-qkFpTFCFJG@-y@ail{tGJKgVjxvvG8W3RHM=L6%9?9#gZKSkMp>)%s& z&z343x|%0tUz6tlSy9k^P6zjqO!v;`HL_@QFR1pDgXxw|w=0_YZYHUCry=>EQc+gRJeFo<2W@5<11^bW~cX0e_J(|jTe z5~pjVZc~?u-XT5U9u{ogwvg`Vwn22%V&u14HEgX)0_}8rx+=83XT{#T#eHwRezo!( z9o}o&I`9is>!6LXa*+4;e%A?RVWbbxa>mZFr_v(b_b?~`cVp2~K-2d|~G2^)m z=++Ht4(9{sZr`m3&W?fIt!Gc8T9p9Z!xc|2wF0{B<=!}}DTG05P8iKxAfnU#JduYf zXOx$?3W;NVefn-oF*@D9cE)z9sY=rw-7ScY?-=E8E?;I)q7=}tK9M3oM%8ryaEqEr5y|Npm2NSgoL7$;i_AG&-(Uy$rW$`!)OXg+j5 zI^F=DL*lnEk~D|p$$3L5c!qSgqh0UU^IIf6BcYuj!6-;+RUh*Dzl~q_>oy`JPS+{O)=hxPFNKG+};~=10W4j^~ zO!rRh`?g$Qm7Q_u3s2b=4y_e=Sa0$joo-h9^Zd`BP1l$saaleh`)eoB>5glfJ|}BN ze{V<)+x?~E2u6Oa(K%k1&1k2)ze}XP?)qcQ|5pU;uFE;_+mzwYkj$FyQKiG;r|eL| zvvffBW(vB~)`vKe=@!u`Qb42oXp#DQxQ2{b-A|g3mg-Do<_B~S5*4Cq9q>@a^}UPa z0p00aL&UWK-Hj&<62t)A(T9aS?Y|SC2Ghmthm+82NQVsRpDqVki4TxC!EW2nwo&Lc zqz>!au64{pbXP;JM|3R5$S+0pQ&}HGdkv}C<8Qb$0lPy|N&0!hM@^aG>HfWDhAJJ( zPxw5)9E0C(v7w;*;+KhLGTpq{kxS9&E^}Y|0j7Hjzl(G;@fGiz1UW!=d2%@Go9%dL z$jTX4IWHD^H1kDC3($R{revccpxaf#JI_do0I_(df82Hl{rms?)rKct?B^u@_WCRC zyz$p`u59%4f8P=Hmabm<+q=Dl=9m zlZB0)ROw(^pPaasbTiSKg6`Cg6lXHsvhOx8L8IGP`*;$(cdO|xMY`SMQCXO52z&R~ z##?86@Q}*-hZFjM?z@LpE?*Alj&;e%(g$>(RE;liHzGiWTz%rWN9c5iuslz+kmMxl zB5@Bm)Yqz3pwm6EIrgT*ar&d%7tt|_kzbScr+{C1w9_qg*R0&3jf&|OqXRYd8kP)y z?uI)(Nu7?k%2eq;_y7OdrqS`QW1Ji*eCTSt&)+kojCB@hp!pE<=H8QVhZOj{-5>6d z2F9|~Hv%8hKKIph4xIn*SibAWZE!*w*JHO;7x<9pf)5toK>uH(98BQ$4THFLLL-GN z=pE9R(6EmC;tNb!k+_a$MX_UF(Q8QQw0IUKk3~d!`$01i{?Z|jkzeWcUTfy7LYSS- zKlOFr*Lele*w`%Se0)0jAsIPP@z(KzGSHw|T^| zFsM9wFe^14o$eL;ik>RS^O#;o;*RJ_+}4Of@Bf`ySex~NCFzcCD@4Z*jQrl#jesF@ zw9{RF%xFp50xE8|?0pyHB9_ANbVvDk?4w49)BAG88~N}Vk^=?ZSBx!xk?HPqC|HI@ zccqC6H%#~ZleMJx|K4?;6c-0{yX_3j`~fDUF|WscndXXxTpvRhVY(xdwO@<@x>HwI zrK}qXgJPu22*O9v>CPXV&Gs7OGL1swPI3FaObbJ&yW;DypO3eQ(;eLvh>j|Z{Aw3! z7rG_WPPf)mwUzU!xZQ#q8~r>a@Pgs##t}b`QKKU$(IqM{6Qg`yTC8 zMWg$m-llu-3u#AY5=k$lXz8wV#7{YkFv&(`3f-eOA@e(qRkirM=POg9JnobM+< z_u_3jL#mwNP+z@KYk4+0-81nzKIh_COnZ>HC8~HOwp4VwOS@G*9uX0wJG$8t{?c(1 zBR@X>&-|b5Y2UkD<0a`HwSkJtL`F6AN{Kk*(=C%hoeo>BbLynZ#EydQjP`+SGTnSu z8&uHfURxPTqWej0NtbA0Sfm4-3!hiG(0y#fKt`@)=o#E z)4e6hRI=DKEcDkQg_kJ(A zf_?uV=l@J%&Dk3aPd9GgUFvigiJ#B%fp51sQ_!6!?ruP)J1HPj3yp52;Dm=T-K`%_ zkZQahKF{wd``UpZb+{;pFE=v=$_k|)%^_6ec^FRns_q-`aOc@ zxaERQ_W|LaMB)-Y(;rCOhmngut?SY0UVC}+n^T-L-O(L^=va@D-&0Ap>csz`hP2!w z6uo}{`wQu|{#FU=L(3Wd{Qqgv4XSiVU#LH2avDDW-$p@q?z=~Szulr1AFv#a?slUCbEWOC zSwWglCT?d+S#FD@!n-HeRnOf}V|co8eq2=P@D6+^&Uy*1Oq?j_&MEumOZM)2ng*I^ zbbE$qH^OvBoWD)FnJ6Kn_Spr{{UUNHZ&xTD>U=ZsEr2Z+dNc2e9=yB7{P>s6ETH>c z%c)Jd`jcAaRoy+c$fy zLSJQDg3Mh57pc(QDm#hjz{*cGPDLx;lJ*Yip+llg@E7bF^2H(M*I5mk4DUk@#S&EM z@Hv>FsdEsnA$L*GUAlg;0C|-)`qpZQM)&2VH9|1mS(;BtC!|>)s=lWKx=*|A&nZpD zL+`siIktic=`Le+b;f}1VEr5Q$$)NV9#ciFBm$%ox|~l-9-Zz_9hHUeYo$z=A#u|4 z^V(1GqSL+hNJ6GNhZ^0{J&Nd9gOOj!cY@ljbF{CrPkYT}%d@DcAv+_)A`6Tdo^ITp ze5!POz1NvnnFiO8J1OWckqi_g)9oFSVSq-rzq5ZF-2We~P4j_wx1b7$Jq6G$H!XLV z2xdq(ICL;=1~a5yT=b2F>Gn#LG(89Cew3dg%yWnUdHD&|-V{Wq+a~UvckXr>Q*R{h z!C5&%?i@+I-*l0z7U=6MAf;8RRJ=l zIaHLQWYB zPd9F>HFY{Jyh@ZOo&RsApu4crRfp`|=fsWl(C8i>=iUI*efjQDcbIPW6`|wsx!aLD zU%V~{;i1->RyN(gz{|vW-rtP?-JBfX&Zh&qEwr0zRMv$-g0{j&mA&Y69~-b3)c7oE zN{;i`$n~(f9lbJHeC73uhmb1W(R~8ZA&-&Y(%*fXbMelahFuXQ@K<&P zrMpOTNM5ENxp*4fvh!+BQMLtdNK5R}c_0M#A*%}~znTIcYG?{-^#VSWX&+f4VIKya z-f?9pYZTpwZvRq{zn#Qlnu5el)~vjp_y*mFzE0NE;3VnqmR%*H11mpe-OtIdm(yND z=5NWF;iYEEPGW$Tz{(KD_aVXos&oWogihQz2iK5Z6m*wsm&uUnJ}_UN4UO(SWkT^V z-O`8J0^wEm)<+lfyMXTSm?`_-y?AJHyPe59aEA0vOZym1x0H3z*1dr4aWx6E(BJbSvdEqwUZf+>clyRtrtDjk8bb8eZ5@a~o;1>LupZ;+;2!h5&1=Ho1A zbWe@B?t$+tK0nJOZ2{hX3NCJv+1&2QLZ{=-d%?rO*=L)Wgi31$;`xYnSp|#}>H=RKLU!bp@51&l1xL3p-26Qj) zI^M)HLx5^l2=DMdfljwPy%^Dfm0u8> zW1BK7H1%-%>-&)Del3JNnbCD-xaVPX;f)NnWPEd$%cw4y^o& zG6MBC2GH)^R{1g;@77_TyW!^AUU3VSG5-AjeIKdPA^&W(QGCUp{-0jE{r@ws7$<)U zAF6RMS0=Br&Hih-(R?VMt&KE?R4k{8)c;St+H@oGy4H$2OE|sL7UQ8~m*QWzfEiM+ z=WIJ6;6qdQT;=V651rQwvEy<8H>BsaT9^-^&mj@qKVh?KsKewE6370mJE-Uh`We#x z<|eT-A$@c=|BtK#D?e|8i~W6(wBNGBB};sap<>F8Uv|psS3S}UUqkAP%~7Qz@jdHR z-HUJyxtoISYKvSZGTkyq)aIknZDJ?g2(Pj~nCnS&XUMn7Uj=mEzR)X@qK1bOXBC2C zz?7Y6omG`E-H*?eopb|82c+boX9bofq+#EPdBbVmpUDW?R5&I zGbBF>x~rJIpONXFpFYBcM)$?Uwq}^_%e@^Wx&z&MzC8zY4=OH}vo*p)?W>O@9|Pb2 z3%|QSJKJ~y@qT!IF(g#a@w9~!z{q`YyE-KEDmW!JTh`(Zdy3-`7(qTCo9AiP6 zkmgH4cV%6>B$@8am)AMb=*Bmmc?8p)C-a6x_ZHbl%pzcSE2{ZPrK2St5{eb8a{;qk zJl2&&z;p|3Tk*gd(5-c9YtQ0a1SshCt+BFyc_DpR&N$1K>x)S+5_dfOU}AzcI^A1^ z_Px?O%S?Cu{|KT3E59JlngZr|w0B6+AJY4TS76`WGM$z${g!CP@cq9+;8Ln|H1F5q z{e2v+OnfNlzMajvm`wNKQ}G;VbUQ?3w8L~8>>nY~ZJ5bcxf{^^=E?h;R@?B9_{gq- zIWTuCVCal1Ot;+k%9QPZZsHntVqpUT>X=<6}np{nog)GqN zwlqECFz?Phx}%${V?9QGrO{?-!nbou(KLB{X@-&~+h$II5+ zYM?UtbN>H-cG~p$Phy;cD17LF>w~9cA9^irCV=KcW#+*t@Ep>G%ABM*r0J)u#yUX_ zx#e|TW4kUMI%ihRbP#+)8a6+u1D=rXJL+kdT_hz=o){GK<%FRS zy+gWcF#DWu8Fme+@pgJ)Y)1#f(=F)#jVc{t#|2ndr@(aYrJ(!n^nzkC-S}sHyl8Z< zlCjc(=`NUzCcXc6=CSmy0zfzGrfm|hl<|z4q!HQsQB zY)T|RU2eT^>t)gD{vPo)B+L0_%?l*Xbf>4b4>vm9>r{?DTv9hgcXUr9IxI2rdz~YF zFDHg}x(99?8cO;^#SLkJ=a<;RpE5k%xZ_W#)6qNNsz}=13ZS67_WrB8WV$O&N*18e zeRhS*Z@5D$w#*^T|6e9>+czH2tzmUU+!&lpjNu0C!6Vg>xzvNT@CoUuEnQ*JfbO@y zI-&9nVUS*=8&~ZBI^D%7hezJ#T&OWX;$&(c^9nvir#m&fLq*0bkM8J>Ms(z1B!*h3+XC`y?YM@-NX}%ACl=# z{JftBjqV@G_aDG?M|j>K_5U}WEVEo;x*f77MHb?r>cgou5@5QeWq-pY-2b0^XVkeF z(0zvM)D0WQFi5sZU-0$>I^A!#gs^SYt2J4S#69)$Hu3L6r+W?mOYN)fZ8bFiwEmZW z!vLaV6-It>6}J{_GNir#H}n&|e(yKzyk1DS3uS1wUBy0@*#(1%yq!;$+*cSu`n(=yKk zy01lFbc_LX*F;zMSb*>UMZ84HVY*BCML9MAx=&~mlD6(8KwD(Hh=MHWbPMW#JyLV! zON|{87rNEzc>gE#^Z%0`*P7YY>2G&S2+@&*k)IBC+|tbjw9|ch2iJ|+IqY5b4IhJ- z6VL5qc)Bm}?W9UaT8zBqk{q~(45pyFeq@6zneK}cFND$PW@r6U4Ab3o-H}v74qxB9 z3O++(4!xXe4(N_`#EHa!@BepM$ghXrklMrk;lN5jca(;_#I0=v2$u)>jDAMH-J*g| zbqWptQNx17;lr6W8h4@79pqD;9Pwm6-R<3~B0BbC!yaa*Qqljr z3FnV&ATT`LIK!zts&w=YK35_2|NANEu4~#zn%xS2-NN$ost_98@$M2D@a`6FtsiN3 zYt4QiXKg@tefqcc-@xq_N2T1@S#baVo}1<%Om~U;nh0G$_pCd2f%5z?D6GKlUP=bK zcV9iov1MO6j(8A>WAl()uW=H+GFhcQCa-41M|X6Sb(mx1$J_oe>}mt;bf2x-)}}E@ z#SQ7RE2<=Re`kEUUrJG>O;;|8oRVH=hM`+e#^CmV>$5Ja&Ci@avWZg>w8VfbPU&t?L`W{Qn!5a|7f4 zW&S^J=Y7yXi_#5QwC`^H%H5`! zWq`fAb;-F=km$RE;ptW}zE717u8PORR|$Xm|Np@T{eSsi72^~^;X{wt_2bDtv`9uv z3eAT&>o;n{HRKw14^oG8HEONWIk3taDjjZ~kikPvyTuKMr(&Q7OY#<|0UvT+)7G2- zd`PE%zV;HsFep;p<3Mve`YOw7Z2l|D;-?8Y?#|M?dC9ftJ~Y_zlyLkkH}QY@heh+h zegUGRA0xkhEn%PL$F%#9z=3dX&!zQsV>YQ_6t zx{v;l@Qeg>-zV(y`qdT&2@Qq+)bU22vfCy6ibpEwr-?8U7d)E~pYMb|Wj8KQSzxl3 z{^%y_IEsYsfGP zx?8{QH7CpH!9%0+l1AtWhcPxmTs17@iWta?wGbp zbwIa<>1fCvK)2l!vs#v>FleG(F^zv0I^D!sXj%KaS(8a5&VQiC-^CW4?!#v^yqGMw z=+3)q5gkz&`Sp!|#m~H|E z-7Og}n8|btFH2mAMz@t@pC?TB{T+))lZi`~EqCn%bjxT|st0@3O2Wa7&l7acb_jl?A%X4CoMhEBIXAB&EU z&u_XrA?-qR_+aFh>*83b^dC$n`oVj!RQ4YB-7VbG+uoO4_A-8D;#NSNj;-(Rq>$cj z38kRBIn$znOm_?4PH{B4M+e79bla!XMt4()RDRBD0yH(>JC7+4z3w(@k8*UdYBrfc z;vU#pyM?)+*WEm(CWZM~-E>E{9-`x$$-n29^=MboJ~`UGdq{X}hqNem|9{fH&EVHD z9K(C}GR^x`>F^u)vOH}+x&P0_@yN|H=Wu6@Wy+Q7IqfcV;%#qeO#t>Sr2J{#wOY~#8Qz7)RYj@Nk>qV=9t(CM0p3g$ zct2xP`TG;nl+R;wXn3y>RXzgaJ*s(wg!e^-EIhoq6|894(!q|0R+NrjW*Luxx~(_e zR04Q6jg+T!1H6ZZ+#XzQB0vhCEk50FM#uX=|Ax-*MPE!5k+`W%X{L4S(D6R=zAM^D zmxb;cq+mn`R(^h_nY$A|(|&}cqAz;wX$uucNImJbc2RK*k2fy+8dW+52W*00wZRS2 zAshwXPhNj_C%gA@vl>}6yi;CFoq+Mi$#s(O4n4l{YZAaaL;J{;OY`s$w`p0H@k9)? z_4S!lWq>zVu6z&kkNiSLa90+er)zw4JNI^LI>uZ@xJ7NiBx<_}MmqDX@Y}Na-Fx@QyKS^{KOj(b_0lL}O?cwC-#Y5%_a@&d~ zV<63pkYg%;vdM7^V;&8Qpws>O zgYir)W3tO#3?z#He|@rO9!p9tRu4(~ZmXrb@@&$PI@I zFTmyG;RMI`=yV@s z!JP;!roZq1^${Hr82L$Bdp<5XM!R<_pCKwP$;Q5!$es|-VLb4j;di$bd-qbMqxHIj zizb-e^4ItOS8+VD^UOGQu^wT%`oG`I{`nJV{0V^ik%Pj6UMW2+Bzw@N>w?N?9+c$C zo&xW%AJ^_D?XZ9Tt#nobcu*==;2Cq!9>xDI(fK_S11$+{b&>}jq&1axL4~CaQp;J? zZF4LX(s1m)`B(`3{;0#sdHcH-{W2lP6>W{a#6RnZ`fYsfw~GCXJbCDDg(d6A!N_lL zT=GjzA?+({mFVx%G6J>-S;n+@_QyLje0%gPsGBMszm`>WoQ)y1N9+`MzhtiY`|^LV z?WiIe-uX(?4`IA3Wb;VJqq@B(iZuY<8&+*L)@H*)2jZKL^nt_wBfHAgmjJvUl)~3Jj zN2_GtP(Z_5kw;(-#{2uCL!`Sch1taL^#E_5!`Av!VDHvnDbLXNYYZgrw}W>n!28Jj zk-Gu_@4+R|{fORB=)^CxfO&h+-FxQ@izcD`s|h(yq-#%!zb*Rh|M$L`()s%I*ZuE6 zbiBjJujTZ;>XiTBeza7_2aRAu?9+c7;lPHNxDm$3TcC|99XDEjb#Y!Jxi>2X-d%~% zW^!?|s5N3K8s5yY+esG_A9(qbE+(4rsg(Ewymd9djS!gekh6Go-Vw05)p6GS2aGoX zmwAj0;O%U^l|T1wD8$^R&>`=Sj<`hRA_mWgzLx1AMh!%Z9>x?CvV#|=*24xW5I zqX6)}ZL^?i8ub78l|#1|g%O~@@Sykqy^C$-1UM&6$Z@sNKGp}P(ed^S?ESnw zmHzN1>+rzHZ-jX1=j~D2i<7Al&Hv8u{Xg!yu-e9XF1m$;6Xb_J_qVVhC<^)p59mHp)aus&AV@`*~n%}j{6XE z;`+l;^ajb=a9@^Ms}S8Su_qB7SotY!ad-u>)9yjy1@(%nGO_O<;cS+?u3r29K!aqV zLY0oWlUAJ?q}$Pl=2PJP_IqIk8E;dKZZ$N#r^A0AgYmwwrjmsBt{~m3O99@&+ZyGq zz~z6hnpTb#0B=oAl~VZhziVo(MF+rpguC&^pm8Wx-A02N8t+xDcZuEzD1EK>fKjU3Y)unB;<9$p(fBk-+X4HKYvS$Xo@wHx8-Oun1 z(({r%ROvXsGUZ*>Nz&z(c@%iRA%f>Dm~c4w`)Hkc`ODDo{>Yzn2*x`~DV2oxxM!fW z9Kajr)tU5G7Hn_rdKRYw@ZNa%tqFX0>qsl}&LMy|M^1TA+m8_FK;Z7%JhA9_H(6Nd zSu3-e1|xCnja-8!J<#!9(PUN0UrK*3w>Bd>AdLKq9%U|Y{SVw*aSze_M>!RjTe4?< zr%aAAJl?oC>U5lSsIvb+nr(52ivsW0S6TkPApNv?zbYEuLcxSk81L;)Atbz?yneAm z65yTDy7QG6I3QJ({gfvN@a|3dTm$$2CtsEBWCs1eM9Ym+3wuJKG7py4ST}UM$IH%2 zWq)8cCC7P(d6}OzN5^~q^Ua(r`vvH(IGI3n%)`jf=A!gdr>C^L_hKDq<O|Zg4H*7z=fAlK`8u)p~Tn;R;{9F6o*8vY=cFQf98X!RT z>(*CDg`)34%C4=RJQT!cdKZb)lqNVTdZ6DyVrKuEk}yGk4H8)gR({*E=e6Z&(e6Qm zHB+134P!5{IJ3KDj*Cnfzk+POLzRxwJ85g0FOg1=_$csxH@k*F#@majQyUHMpn%7x z;U#voV1R^o$-E}rRRHh8)1%7>tHB4PY@N90@B`9EJA~o$e;-o~f&{=j#Z@xbw2A<+ zEgJROwFw>X8>Q=ayWL?kWkKTjUivz_8=>R<{O+nVwYtJ|x5VB=bYSJD_N~TNoSF6$ zq%VX=B)p>z{kW+Q@OGJ9zTv(h9=iU>Z=wWD|BE^gvBCZSrph;WMnM0+M?lDb z$$0{_>`W@Vj|w{8Iy-(`ymb*BSoyV=bO~)* zLA!e=l<&@yp2e;pal1Z@t-oHy@Oa}yK2oLQ+TBeSlBp#3UO<8OK=jhTcW*bo@?MUH z_rtAyq{E4U#k3tx>>asiXOl{RHjK&tPG5$O_h(bZ6%S?DP1hrF2l?L~Y!X9v?;UZn zyhW+>hxaI=11rB1BN<};iL~P_%FEHaKnWY~cBQdt$I)91e?a>6;uKXng1R(cFsG65 z=App5-)`ecvU~S88Ec~9edBIF3GYlL+VJi_Vx0N?dMK2%uJz?L2>t9$Bjep~i$`px zr;xZO2}L6OOVH2%<9S!yQeH=Ycxxg$u=4x7Dp~GX0_}Jg?Jh}{8K7eBR=avz?TcoH z#~W9sN1cvk99pvAa^j!+|8(8?|CJo*|3xS~=<||3(hX8BaDp^9u?vUhK_44_ordoq z>3YtP?jR|=I4d~^W{?h#ri?Oc7}-j9kERtgmc73A9C$ssY;Ht2aRr_7_Z z1V~ABmAQX6x(5}%5uZF)F=e8F#4R?tr`2>H-GjbgWWj``B|- zXm5}{i?iQos>WVoaSJ6q-=5OaX8)v-xxc|T6Rx%4l?21-f5JFgEp$`quj6?z6C++99{{a2J zUDXAtCoBZ$ckBH=Vlq13%{GQ{7m9wG{6ykretkIO9EOg!wubskgE{&e{zulKg^}M8 zn^Jrvrcy<$h13p(CH#hfa;B$-YBjw=&h_}d&E?^6Or_798s>CU~$I^hdwUZV?mbf<%BG*m@Ob0Y9#Ey@%A2s=q2L4w6eofdcn=*& zIYf4EzY#ZmG`xcz>D|sd=4K&g5mfCs#xX5Sv zyWVmS(IJhIA0M04wC*77co#<8l2Ln!eL-56_w}ss>Te9cy>)V6fGQpOe#d(ZCJ)1S z3sB(w@n~EU8E;w7m3nA+uVOJj1LHlja*VWlJKtUQs5QX5_43RHYdbvj!ExKz6)^u_ zYGGfZG{9Rg&iTTAfcHBu*{o)N0>l;De`X02`u0|gSFTi`Jew&e5|_NB@$H5Ybi9eF zcD~Np^mq0ai|D}0PmPU9Z9_2a#ffV8v9F7YsObOQ6jrztU1R+IUqqfd9gyE@zd!x| zKNoxY{59|(2?`JT!XC{5dl20J`%GA|qj`|kf!Uv={y!{>^un%_Ucb^T=>IJr>~d(< z#X|<7C9~93#J_QZL<=Txj>8Q_?%WdR?KSf?UjGQ||j( zk3J!!A*;ou*3{^T@qCiUlE@RmY!yvN9|^~=_$=hJD&TQ9UuqLON5Wg20`KuFD%Z()uU|UDf`<2=tG0tM-aB$kNqDdP zHY_~_@a9WR&c3%C59xlpusDRRHcqkMV-D)Tvg^u_A z0k^zMaTjVLkvM(LpVPjc=y+dxS{)&A=o;POJ%Z@y!^m$>`J#u5)$XKbboX^7y9{sPwa%!G|v#-4M?Ad=y-vVpZ`Za#phYHDW}sCw+i??%SQ+f<(_9cO(rnd*~C?k!4z_vp%lq<6RB+FNM+6cZZW%ZZZpFy2?V z8%b}s`WKsvj{>~ULdZuJGEEt zgDg7Uj~_D`8m5n!=pu0)Id_@(c+m0IFqrgUpPi#SydNPt)G_j7vJVnlJVHC(CcD&2 zTwJm77V_$_iQ!zv@OY2=UbI5gW_au*&-*Ii7$~jFT0<$Jpb~-u2gsdp)*3j^uPF%{J;Lu z#}OUU82OF%7__)+(0=~Ud~>{#nX?7+$U^sy^`09o}4sjx>z?jx>rZEB^=Q|2$oK>4yuk&;M}~ z@*QPAf*2p~-Aky_5j+!AcdwXKK}u2J{p~zHn~b;J?LjUyyq7c8_`rC(@;U}P{GM15 zSz+q-3*a3`sC>J^2@kpY@4SD6D;8qKujz-kx6F?(UK0rLCVq*@U!6^WE>1va^Yqc( zTmAdRP5P^+YtA5XcUk0xAIPKQeI@=tmf0jT5%?RAhk9iCw;zfH%H+;)*NdY z3(@g5_UM(>bDF5hK;rTr*?KKvN5{Lgq-LGZ7>@4nHbQh<$H;H8bFN2e2ki}#mrBor z_IfHlPMnoD62IKX@Oa~HEv8C`+@iej%yN=@OH$zd)zBuNjQ4tv6C7xGw>4OE!FY2z zwUM^B9xL@+fbZU>no5tl>Ej_t`|3${j#%imZ?F#!!274nW$QG6w`o0-=x?ySwRO41 zr5tH=yn9&V6kHldYBnQr+qHU~Sm&eTZCG7+VTr_dy4$^djp#7O$nWYACH4SS+TGj# z{sQHnQ`mU7$5fl&nRv?ZXKztIuTZ6f$%@PT*%9*le}Crx|6dzJdijT-|6fAkLBDy1 z#mFA?InqJ^&4apRZ&bDd59$~%3xk(f{(}d!I)Mk-n0%LoLh;Zp>q#YhP(dy}bZ`jv zAXNwTuG7GS{M}MKt2zmg{=$%=azAtr+H7~-q2QJ;)w1+<)M$Ci;Bq6 z-4aXIftBCht!E+Tm$WajoFl$h=T>7kNY(ekA0KlHVE83=w|WFsI*!Xa@x4AnsvzYl z@cvm7B1Fd9K$(Xh4R61nMsYCSyr(A!Fy5iVI~TtOcyHHGid#znSL}Lq&3XXduCpe~ z;RY#y^O|A=zw&7I^L-XcZ+w) z%g`O(WF1)fy*Tcm#Qz_R*y)yB_1&Eddy5_S%5_!GzyXHG8@FjYRXP;JT{^R_kSfT< z6nOuLuQeg#oz>aJi-tF!-)TD-Z>yh@B)qTsHcq|+c>A2{S$!Z3+}>g`kv#ymw-maI zV)+2x9Az(aJpkUJX`fogzyxVuo-ZyJc+uTkUtA@5N{EN(j>K8ZKhu9dhkpKVsO6A) zc&8-Y;jM@0z{;;9xMb#+1MTiTogpdYZi;<->uYv`-?NcDysTP?}t4TID0cal28yD35F9NWGUz1 zj)erX+_u2y|CXW)e(M6fJ0%)V##@F#EhoeD6bI1pUh-Ia8*dUj@gWj-MQj)nfT(IvqB+ z7IBrrKlA_SrN#f(JV5`i{Qr9po^@i=OR@(Qx9EtWd60@d3j{B*4%zofOKhHRgXL|o z#0E%a-Mj3EhwMM=J$VV1*t{JJE8s15VRoCQ!@z^qhi*BuIwA}Tx+5E#Eb52){~i0Z zotJ9Lg^9jM+!CR7?u%T`sPUhpA6PYLE}=UQBJ22sk)MN)S%e%f?R$`X8Y_b?LfHL3 z?&+fim5-wse~HD{QKdtss?y3EYT?H^T$K6{b#4w0=$XbDuyuL_foH{O#pbuaVw5YYz%|c-7|u@KcFwM zkdFLC*Dw*H0ur~abn5l1F7zd~pJ)Z`JEu}m6ChM@o$gg(SGBdvgwBzlsaB7}HGxqjY z)L!law*V%Ce_hEL;D3x-{yU!<9XDQe<+J`Z|4)GeZzjCm0W#jt=U)**!&|0Qs2p~0 z!wWe*@962qfOK#x`YG7G9S}~@hVkB{Vq=mH@ZQ##Ten{%4C?&2 z*g~Qh9dA*!K7;GFBE(iCPUEd0M_?K{-UZ&jt=_cKpL>&aVC83au-By5mUg_qo@i6^ z^2f&eBP(}d^llf1$9v6=;R0%OJY$y5dVi5roGhil8z-+|Nygi$d5<6(-t~9(yo2$^ z@q34pwzs~upKk|vZ(9%=W*35o7P)C84uI<|TX)YCa09%z+rsVt;@&x~*JTMJ@^t6knTQUo{6gD|K5Ayrj`!J6 z3nA7{?A==&E|r+{{v+e}|HV}5I2~P`3TAKpng7QCOEPGX)G0h@UVlg#*@HH3P?tjU zAh{dwg2|AEg+a68?VZj&=pJMsy2-V}jGs7(#O?R1bY1ueeTkhR_;1tiroRJHvW{7d{07}C zgZ5X_z6bfREp)waK6ZnI)Bnof zUnzuEfC_TAyNz|xzf_R&Dt#KKe(@7Mkhr~fAH6b5N5{KhZg~5?Q?hio#4bj36k_C; zz9aC!y2G?DvF5%dlhM1ex7Y=bo?ow;G|2FHXPi7qm5z%~q6`;x&xv!~( zjJIn?qXZh>%Z)#Z!FUS|FC*bSWSAFw1>ikcQu^wx8y<>gZZgRNc%S_7uxCEN``X61 zlp6qVQ$kI)%@_fiNq*zACKlbjLz~an$UYJvP9kx(>|>6d`_S>;Ab;#MuOt24-U>l< zVCDDnahvXV4ejn79<0?DbRYW$DK3MLNhWlR;qk`xQl}$hCEm&Luj?(U6nJxNn7Bp8 zo2UESLNvUczpF^Vc<=k9MZ)_`9{<;TfcKl}ex6uQJXAE_DDn`%yVehig!_M=P{p)! z0B?&8I3AZF0u(0n_LOWCI^N-|Ck@u!5hU(M;#H`{4=feQr zVQyy(`Nj#*8~q#YlmFu0PjxnXe!L?@>_Xzoo-eHm-j9y=*3UtF-;L<6|0nCf%J1`A z#n`D<+TDA>g=4aZuTs(fYuqN}i{cpGy`vUhr%H#c{^@duKkxrBK=Th$1Qnzw=RmrHFBfNMyOvj-kZkbL%b>4I43UQOz5 zxc`?RRO}iC9+c4+Egv}&4*C1_?l(-_je4HHd1LfQ==^y^A0+OPX?y$QI2Y7-NB1?E zL4M+Nx5Qc_I<{ftXK-e^WA-iWORU&y!kf1iEvP@2zag~WHhF8p_V(YuX4JpYdhvxC z9m4|byVw5J|7%g;&3ixDjg0sFLvwOyc;{3UeunW5E+#HC1_yACcz z+7}&f!8*3w6K)c8hj$aALl`5!S4lcU5v4-dnEnGxx7@D-O)8Htf1k~99==4bQijKS zO^tvEH9DTj6=YOIkt)dL6nHQ2(fPZAd@y!L77g#r2R~+DyoK3rlJGubHonms;N5@1 zK@i%7hft4FQPlV>ku6>82Pyjsn4F7q}{!=f1YAvIP^>9XjZ=uI^IKgH>;5; zUg8WAH{N7m6ylDKH~;2G?+z`OraQbpB02;y@>8_lPkiqsijC<%+?u=?zRhxk`|d>sb;Kfk_?4UD(F?f&wg0PocgNBJt^!yux+TXg19 z^t-oZBEBz#GWdwMk+}D32Qu`<(eK_`3HmH@H>AI_H?odR82QaeY%Uf#Lc4n>1s8t2 zNX6`}C4nCnj5^ygynDwRzobgXoW0NG{y*RU|HBOF^q0Vc3@AKEq*YFayu{u-C#a0( zLAtqWBk&AT6G0c!43ZV!gd4?x2Pp?%57@L83`l>)w%vv|7V4TFmW8+2)#edeF9HvG zx?{V3oMSk&dG(a};2gRKeRe!0T|G2jvk8eyg_e$fnMC)XDZYK#j)&=Q#Ljy}$1FyE zWjYVnHH6UaK{b2&Myy$>IR6ilTk2Ha$M6jjE?u{rJi|IwKpNn$&&@&5XHrD{HIYbBkUEY)e*@R(4gW5?e2uTDjh`hPtN zyoJ2Z{ypAeGi$j58s4&ZU)aNVuevBfn*Z0mgY_efcT_^a>DDcHXpQ!wT_a%kHnqj> z7ks@XGmWsf7U1pl{qvKP3&No}wpWfn3(@i3A*K~n^@*7{gT$3~eNvaWf{wR|_WF3Q zQ2LwR>Wt`sF!IaJi5|Ouh<5k3xs_jf&;t8{H0~XtX*zBj!{dz`3ZqI#$A<*RclSvB zzb*ydg6cYZ$i>N##Rr$7;k~cyDQSA^hg;&L>8*9LiB$^$-gd!7r<|Sfkj2g2LjNCo zXC6*fyEp!|4BNc7LWayF6q1z0UXq~<*%T?t5E6=zVN)SwiVUd`4N6HW(M+O2C7Dub zph8Gep+V`l)_(SVe*2v3UC-Y8{pW1&_4H4Dy6$s5_gA0uUHA7MOHsXT%mZHvpn98M zHFRu6^=>8az7r!DjXa5~i)uWDulKjx)7Q4&B-FIh+eLOi4!d87ueYN1(aj?IoOeL_ zD?JWnCjFDqiBt`L#J=7k1xV`F9Oet8Ty8PPb3av0dA$uc$Fda1Te+8lA9HDX>oe#* zeTmC`ptqc=<19SAO~>9m$Fg^D)jZntR(W0atC^_YK_RS!z3s4bB;S^gMvM!ySHxH2>+PXgdtO+dzh*JL-Qnf|qlt_7dW&y8ztR4v zB*zU-Hqhgk!K8mgrM;@Tvg{8|?q0gGHzJ9J>n-GqY~1ZzFS9%f;M9fzI<_pu@w!ub z&Oh(}aq7R~zxNBR|H%wFNKQKLUsvn~4hYS|%Rw>cUq@nZke(3UN_&GeDj@b6wn6&4 z=E=QlZ77IO&k@7TXbvhrvDOv4|Np7#j%sr>2VI!7dQyKZ8fi((xc1cye~SH{-G!yQ zX2IlUdb_ii(tkW7<4>`lK6uGn;f83M@{|uzd4GfIC5`pUGM;Xg9O#vm_hHE`x@4OPi)}pSK4@bkE+?f!1NwW z{S!z#Vi)&o*$!0i*Q?#%`>&uND~~Vgs6zEVFmjX|yFu#YZ`m#vRPVd1>N{d{qY=N0 zY2Q2y@b&i0&^P~h?5pu+db_I4YT@5?@%0vnv8}nP!Od}cZ>Gn=%cOrR2jlgKlI(wC zH#Dm5@>OJB|DXG^^y!hyBU4^)@wv-cibH3u<8JO$TK#XtptsD1H>yBy#emaVczS0i zD_dZ*w@%wGZ^QIIh%r?;xUDimNlNWbml{)pZG-~W~? z*E1&?v8!3HuDcLl@70~-l!G(7jaSm!MR+F^T+zYT`>RR&%DgR~IPL{0PkJ10ne?yr z+x5?(9_(jtckith@-LYeNHK!7btUTtr@Y=!@?)0bFni!xsD6T$y_YcPEv<0#U&mYY z^|#H%)4MmLvBJn;K)K<@cR=ffQic`Zn{u@s!uQ>DMEc;>c*;5~~qO)7y|iZz-ke z${>3uhp(K2r}rJ2jbWN#>b8kTezQB2hiJ9L%Fw3 zY{aks&khk@I|TM~-2MMb^f+pm^w0Lp!8^*=*w=g0>~h=G5*A)>-Sj$0(ad4W>kU18 z!CD-9Uwqd8r~d!%7oV*304L9pk$RZ+i8W==TWL@70igE`rPc*_dcSLM--?YObDSN5 zu>#3_{nDIssNNNOqBiBDTkL){TwVMYt^Yr^r?g;tC-HhmV|u??({qPFibiH@>T>0u z#n*e`%apC>`$Wm=^mZ>bXTHAmHw&al(5s;NyA(N2Zv%Q9WG4M*OPy`SV~Ukygr|AWp; z{o(!_z4NVW_qptuM&3qmCwgo}x8~pIExN0&pI26i6h&H^Mcd1ieZ%BR>OL3GHTILTI(z3S+gWd{?Ux+~Oj}t-j@$^2zqx84| z)jNd`J*9$X@A-*0M<1ek7k9@r&akH-hVS|K}%ZNc=`7yM;?8P)p>Z};LiD=A3DrbVk~quE=^#GnMb|37fRn>r8G8-7Tb zyB5vfcaHL3?f;wITj9K3VyCwAlR>+Y-n+eGf0MnT&`9$mU6LH9cN9I2$&kPA-%!@4 z`1)<^>s`L>rEu|n7V7_;B-@>m!&6>wXy0Mh;t9CU0nkAR&)8ko^c+k>=|`qKP1nu9Kd&6B^EfxbanTo_h}-XNX5 zQ~VWngVce|Kh9i4b5OL^^3xOVsfeVHWv0t6{3~{XNioKa0M-Y?#-JiE#So-%grbp%eQ<(904%~LnSg8LamS`5Z3r_tJq{V~= zD{)j_Tk9}CiDcUys^G2_WqwLbim9X)!WJWO;%np73s^)8KW5D>wVzO@0q>A zW5&JocJlefS!|C^j9 z2UcZFdA*^N1HV~`BmT5hv;g{o6goIDXV80=#PMOE_w&0x26%cuy)kZv>0Q2~gQj=+ z^{-l|QN5MNlujjuQxLm8jof)?fs~Q`%^TaCC@1SNV20|Agy;91Eu|t>+R+gyCir^m zw(fHc$^T=#g5GYq?ZTl;TKIYonfM%XcuwRvy^ZK`3^M5-SK&JEo>lDYtqQC6?q{L? z&sr849iub#cW;^0FJLJSjYnaHm;ZX4$c#a6l{X^#KyTs~y+wF>KYUw$7h8Kf_O*?6 zyyf;Se)A$Md)EdeulA)N4p;xY&P3PV)L)I%Vbfcshqazz(_3MQ+ekslQOKL|@fu%B2SmI(%YZ@2t$) zf{08O>i@*OM}mHZPyPBoKb^HWUhlcC_D}u)pQRdSGWvXtNT|H z@N&?E|Bn&u6Dw<#Nqd7NG?jP!7n+0O4c%`TqXkmnZpSPFTK~6(-g5XO^XX=n*u&}Z zyiLgOnoDslC#gvL-Yuh7jqpFQ_4lU7Mi+jr2JOOE+iAVf!2iS=#Yc`^oDY*Z?T37g z9)~fL{C=*FG$_FVb=ts zpV-A|MxWN9dN&idI<=t>q$d_%sVf%6*E>~(n5Q z|IeC1@3|{h3j)0lzWvUPr}y$C=bf0|QoPq_@Bcv?E?WUUe6}o#vyb6`~#Z zdQ1K6xIUcK!Et(v(&JEK(!Yi@bFZip_Oo}L{+e~YtgQcg7KJG<-ZS;Hcd`{rah%iK zLVW($`o9%}-g5*uWdgkye5vNb)BE@5K_g7>2g+w@^}m*R=E0Y!-V3>dEOum4kc4~d zD%w%Kvx4^!u?x~%w?F^Ljq1JU&di5voTy0FmO{RHf1~%xW8I;ZPwS0AJG0>3MMh8X z^$yw^67IgXjpJr-_tWF>V$wg$nR#J{N7&c<{0)OtmCwxA{|ltPnW_C6nDTmi7NxNi z$4B$@;Tc)9!O02+y)_0qZGhfsgd!ME?+ZS{V_5ya=0yT+?d`x>*(di=y%UXxye{si zAn}_Vo2pU0t=|zkXxCdL`@MOB*8k6o+q8adr6SAZr55{f;}1?AHXl6@xun$?w3DsY zTqyPlU+-R@jMhc>-*BAXBlI}BnDp_P+i?Ug$|Fesi*&h2pQ2*y{ zV=az^!}i+$)c>4TivG|2LF<19h8(ou@GDD@gAT-43FGCU_r>uaupIPpjR!3UB~FH` zudUEC>0aVzG8sidVj~PfwSFZahuy4oc+pQRsZ&Bj3;o0<{g@58-i|~@(r&E(uo`~^ znJ=01Qs1b*`ZK-VM4$mF)(Afbsp^W^JSzFdaU;kydK|Nu^sgydv8zam{ZDL7&GwP; z-^^E#VvaAn(2?&dM;pt7{JEwq+AT`|< z(MFKH{+;%AsNSL_%d@<8P>}DY9-Fl$6Oi}0KhAQadN*7DJZ6UK%~i1WsY-Grva?mq zc##yo-m?BebVSSWT|OEvRI=t}Tpw<6vGu%~|p?de3&936vML~}BUfoB95)t>atuwh$y-#Hy|LKbAtzghup5_*b z3z?cy8YT*bOebGPV5-;p7-a%1kl@K(*=G! zz26jk*pKPGc(W{R_V(M;qO*Fa-r9C)0w2-sEyS3%rrF$y$mdYqa0u0V>$?@kVW{4R zXXd4q8%HABVkGL?AK>d<{jp$cm(!2xV0t@e%b?|><@kCZ2+H^rdYzx+^sc1Gaga&> z_!o94UvOk!Z|F{agw7Y{^?zvGTg&>ssbBvqS5I5cN*wj(DYv#4(6aYR2EBFOD*kJF zYrph9K0LkU1dX0!dJD$SqpiKQyM5iLfa?8aL7}MbZVJ+Ut*>S!ArT?A5^E;WwKpR_ zYUDmt?+0bu&CCoVk*jq{kkvhWy-Q;obw3q-uLkX|+sAWTpTXDL{Xy8$F@Da|`zSpQ z4<`Nlky?}{SirvC!7KHKEm>LrPrLAW^TgY!pS?BDvKGg>hj&!}ssI1ydYjY!7X8Go zVaP#-3BTupPwbXKlj(Rl==!L_vPWnRx^(ly4(trlj6Dxd?m}}=QsrCUURMedIwBj=!V8yh{zg z{;$kDld|TCFvopjkJ00}#H4@qAuI2bH?p6D&U=MX(m%2=f^7YDpq%o4>hD21@|(3d z>K~cYN03eodM~Ejhy!{@nh8zA(_4yrTmaKscIzM7C)TCg+As>$J8S1EZcp?DsjwWM zbv>xw{1GYcSb@|$ZLca;AXR<%UiD%=6}hss+{*MWzTOm%km>oRW7VKtjGAP9)p>lq z6SD%uWomgiPVW`;IQB5ZFsy=;{`T9T9n&lQ3|9{|s^tEi3;vfp_ z6NxIJjUXKv^fu5c%>a7q@pO^!^oDm)A7UfOyOiIw0?FOTtadx9x0;5Yc?$Y^>qzp` z&@ZUoOEAnxK#(HA{Tcq5B6xb6y`E-_>202Ofwnl|qZ3`~jq06Z z+8UG-LP3NrLzm4!_12Ve55{(H4Nk@+Ek^a0=c%K7zY~ev)Eyz@IpOPl>x%xvkHOEY zYw7KFsi#~($oP5(AGsJ9^px}N|2sjCBZNu+Y$YEZJ^7k_y~`!8ddLP_|GzSA zfc8Mz*=_MnT4)X${>YQ9mQF#;R8*W~coUK9QQoCkfuvp3xR`?Gpxhs4{y4WqAvaRI z1Jt(RpFs-M4!!7?*;9R;-fsK13WWte_-ByTQ2o^d#6~&p6YE8f!<9+@`ZCU!)djPk zgA52N8)FTbk07CL!d2rpu2X&l390e36o*5F@CLuX3M3Z>y%EO-BcONV9xh2dy&vsG zu3>s}lTXo(*j17<#|=@v3wu63E{vxjyXI1ODCi2(GDoEVOz&M@b4wgiy*K<6d6<17 z3h~|kYNMekzTWcEXZdn@e^i5Z)vMpUl3j?eH??k7&6q#uO|j3Q$FYM+{|?>xWLK`w z{uaAYs+E7H`$MJ$lJbqb^4AGZr@Y=d9r-N9(Y#yRI1By6qS<>LgWhCCp@l&27lkbn zczV0pmFZ$5$Wm$sZ3KDoc}$r#s`rhGy*bH|6r}8(M4KU;h_uzd(#G@-J1t6fLG>0` zpjL988ijCCGnl75g*L&#JkhA->X&g7b^`0KbM<)G? zu8#3*_GLeN{}DJNHmb!!_RjasAAH(9<@JV6Ze}Tt!37eOqSLejX)S}^M%^y|TAb)5 z=8NO${epL4C8qb;rNy-AtYMzV=lsPmK?~o!G+{LlKkshZ8f(#BK~ah;y9Yf%G`` zG3noP%DWZj^VrYcHzPBT-M3<%z4JSyb_O1CnDPbE5T6W7aoiR%tQh($dpk4ez2s6w zH^|;n^HXp3vv-Yu>r=hC%r_@4sA_yIB-l3P*WLow zKVm5kH8Im)U3=pZ5w!B?^?TARViMX*Wp6MD?Gh?Lj&dezOvNgLKbkwSfY@L?rQ2n=Ez)Nxkty`#bau zl33#vJ<*3$BsF%PVwfj>4pOTZ4?pHOot!{#*Q(tg_m+a6gUnWGSn>99-VM^T>2WM$ z(m$_-b!V#+M41*k|EW(|ThSH;)c!68DoHddHyPjA;o;rY@s4PS40w>L;`>&%+} z{OA8~vlBfIIVSzflkE_(GGqS}s}PvJyy6*iy?@qB==z3?JXB%zi#ZuUqP}+yx(di%0q6ZxBIZ#YiUax z{t8k@?Q+x4Ibs~A_X>I(Pnh&?;JXt1A(;K_&1-r0PGrwLrddBm{gmbF)|@G?cZ~TB zmf{GYZmN?0>-Clm40@Zsy5I`*&JW9$!P9$#*e`obZ~KG&wC629ZK>5$LiOg?`c)>2 z9&hPVarRP1_3op1Ct`;aCG!Qt6i~fI{Cr7A45-LUgS-P98}aqlPUhadX3@Cub9y_O zmiZ|Pm+|#}?I@9PxSW^c^wy`x@rp_R&X(=Zi#pG~-hUdxLyqS%*BhGuG4b{Ki7Br) zG%#%sD{+W>9%=BnNt@nU&!G3xOCvcz@853z(s+9NA(e+Pz312wY0q0KJunhbM)fWz z3cPkTnS!*`9PA%N_y0Q&yfDVr|23EJH!VQ*b`3w_GonL9{J!s&h^WWcyCUZK`o49o z#=i7+H+!=W{Wy!Sx4KeY(5wN@JOAH8k3*hG|7xX&rmr1gU+>+{&Kk2x%=M1xtk9ZW z;5_B0x1g48mf{$Tl9HH}_fP%*-yWQ^^xsG8e;3hn<)HLl(LU^n z9cO4p05*ag_*}YLAI(AP^6xBQD*A%dbDJ(*^aknjstyuXAYJnhx8p){(82MzE3Y)8 zkYAqbn~vVbFOaHM{LZd@BTxQ8Z+9ekn^j;Heu1<^i=d*ds?Bkq*h};{7BlIe_>FqL z1!?T(ppBA879Z_qVT;{*4UrW!yi@-Zdu|R(ao9jlHC+zUKC#{mdRwp1ma7A+M)OVOFVH)#`Hd&_fCESt^X_R zpLcBJib5(#M_qqw;&&ra|(c85>Sn}<23clWBHa}CXe$U}Jy;soV_{yYz z<#`WevMB7=|CDyZf|4ZBwfT$LUR_ z$MKp;|0WWzo~zo;e)c{-T3KNFk@*TzOg--`gUfMKUhkMVL6+huinu>vewmiNH!|qG zyaS=V-ilpL-1#_J5l`qE3TA1{2By4ZrgS+hOU8%4bDi>m|cTV_|!;#SA4)BCl&`e97(S1LSgt-WbyZmU`~K}D2u420ij<7e-lBkwvq z6=slU(%Xd^rRgQ@#?RjAFXfM>9+<^(diT=f*vq7U4Vy-j9|*HQIEk<_c=oQAg|oM( zNKd2;w@>-?f9U*7*5bG!JN=*g|5>WO|ND*5`rn@+2RUrm5d=n%cUI2O#LGb@B|KW# z9Au)W3vG%$XSn3zQtT7EyQE?Ib_z1Q_-9@@`oxar$zeqrbKjQw3y zWMAB1R$4fI4iY`p8`St!j=Y!N?%d*|AA^1Hb5PFB7WE%Xv^XvY5$SPcG3lS~4vY8| z0qlQb&u+TEQ1Uqo_5Ze_hk9B62hRVe9%3nu+aHp;7Ua`Dv3?AC+iOnHp4i1kki(;I z)baF=jU0W2ePT~@OVAcb4Wf)RO;Ej8iX>k=j@JLAp5BDDsNO@}{o^)FMznMXAyC0`( zLH4elcWySG-rt_y*n{cKv+4q^K-##aa3LAhyY{@9;&zf=RrQKYKyJ^ zkIc#5DUa%X>gcxJl{r*o-svqv4>j@iZW0N9R`gYotV3_tH*&1vu_V6U1s>~uW~OqU z-XM;ACjC3Trqa?ihkd;T?%VOrV&VP2*BVyK(jGQXdA*l+G>yJ%u%}Sp?%K+6oy68{cH1u*}m(t@u#?iI6 z0<)9(*zTt1Iq4kfA?s zarAaSh!p|Wn)o^BWlBcA!B$0%8$qhm6`jFX!QO$R^n))}S;Rx0Zgyz*2yPVd+BI4qg;Z;8icaY&r~`u{|2hDC=8^ZH-# z^S2TI`%}OEH~5&wQXD^Gz6om|q}Bgh8T57>%^m@Ie?DEJg{OD4`8Rb;?`c;z(Qa=s z=hM`~UT@W0A-i?AKLycN@P5*ajv&8ez1@N7{Y@^aZ!4;IvlrrV5#9e^?qnQg`8WIj zTWzzn8dN07XXx#YUP6Y;{$~IGTN@^xP1}5|L@YZ?2PZ|;=~)C`$?GI#e+#H0jS=G%xs4e zeW{4^@Y*Xmzwz}xAzC|L)G(9mNN+dqj?l5_0ern9p6pRpmgl_9iO1=2gfZ!#ah3j~ zkgM$Ltr-^}^_`Xb|2>^wB%W9`^~c`7tXYf0H|**^_y4m}d~-k>wEo}Dkb^eZ70QAf zlzo(EAzlu8_rS~ryC8icd+Sat2Z^bRBs@Y#kU85{Y+Q-n|1YaJV7?t39Ckrkl4yr~q;3>)zEAYT;fMGIlHc|Dm&Wf78-sSnPKCxNZs6DdqnkhXbqP;a zbHGpZ-@34l9>)li{@r~LckAZ=;uAaTmC^XIYUU$I$kA!nx6R{IJ_p5Yq_PwTS?RM? zmscz{#U9F__j;@TV?gh(7e^Q1=^dgbHICgNRkNpwcK?6)=Yg z%&50T@BdS6wHUy*w_H(N6t)4?d)gP3^**zs5W=aj4$E8kdQ0?(U*1tQVa!8s7q>g7 zSfm19?`1#dA{T^(IIch<(&I2;(!ZR0O_GXL?0;gH?$QVn6k>kFE=9!R4BvCFDL;a| zAf3cg9G#Ed2dP3ynBE}_db|91)duvw{-Q_^Pw(APEjuy2yR84ZAYJ0-k=qTZ-UaGM z&&Rt{kd0c?s!yONNSDhQYGHc+7=Nefi|U>6_M3s;^eE)^e)-UpGx&N>b5HDeagm#R zi{7sE`kGyL^6~Zl?XYRh&Ly08{+~#XV}eQlEKPq}ssArdkV-G`Gk8D5!Vc2jH<}jj z2~%Egs4r(8OK~{WY&QJs{l8!az1N+~)dPBaKifPXPj719ehAY$bnh$L{hD_v>;= zU5eu)^U>QWJ)Un~brfIks@dAE9&&S^xjHI*?-l9YInV za*&sw$X@IdD}-*4CcScl@Ny8p+`{=-{U4j!NPGV;x+ro^4f=^ag^Y+=FQFjwrsaLh z|CxaFt=jejdtzsm+lL`j^b`ADUE*Z`DGJd`UD@1l3jY&3z0o7TX2odr0(!fYKaFOi z2k}3##>%rE9e&77=Cq%)EIkf{N&oaFZyJ2wzramf~>LXgG4Yl=g{@WYBvfv1tt$LC#rt+YnE0ipOLaruQ-HUfT4Q&&(T#>rlN- z^he5$FQXuQwqI6#NA>QxwfPICx2ySWp=GGv{Kh@wN54{$;XCI%ZPM`dPG2ovb2ss8 zHE1{K?bvlY3SaLcjmo9gBAlo90eT$AnDp;*!1=4L2iVu!Wp9(w+c(TdkeW{KmBp@G z8nCSshy4#m`cJSF2jNXhmre#v?+6CHJqFXa0=?fRWG=?jJKSEn4%2({m}Cq#d;4@E zIs~i#ZR&QCBWx+i6^U7L-st;(Pxu7~F};W73Uo2O?dI^_9r#E^8W!K*z9kV~Z@q%d z)Z;FnszJN;?Grk;w*QUZ@xjk~4oq^~>n-N=IF2*vpFs5ZR+(1z^>(lxGrG8gg%PC8 zu4Tz9b*8-Dkjz%r;-D1FpYvD!AI_k+dj%;E=&d8;V}Pf(>Df)gJnw>;pzQw!s9xYy;a}+*oEnh zoZX=E7}a}x3~4>Nj)JIj8;TRq=PfE9t1ZR!R=)OL(gxL=SEp*=Ssi+MYxQuLv!y_ zXL@@pWV&Rn<2=tPuQ$XS$66e`dO^k>693%)&tZeh|FJu0{lAML2l*MfJ775otN-Vd z90+(hNXwmMj_n|wb?>kD|AeI7nxZf2nHUPr^P3S%K~9^PsF)2TAdiZPL&9hd3fYld zdJVl|htK=?^sBogk>=4!o(*F7bCB=&lue!$jT^Vp+leTXs4+j*;r@RudA*6y${7TX zn}d8ok0X&u|6~#hjiYNxxbgju|90qKc4q09etN>Z{*O`b-ug~mbn1^F?H;ofN8+c& z-&2m#3Z$J3dT)ljo&mirF39uZ>D`mCaW|&7-NFId{(t0Wte`Eb_xvE2b;m;~Nbz3o z*xU~Z2){v^l@O};i5b7;+EKl4RvUh*TM>z56Yuu?db%0+pVM-BdF$=&e&hZ0c3)pr zMwH*c*V{v(#s8$$caHnS8qni#WzxT{9Icu#arQs46;kfU1z0#idL*dN$R>_D_4U5_ zkfk_&5?|f#+DFrS2ZP?5-kd!O^d`zoaO3H{{26o)(_7DOl6HFQ;sWuTLa5$#siR&Y z=;^Kb6VK`bh7%Aav&LNP^_Jluir&Mh-gA`3&xb2TA`5kkn<~rk^>!O5ds|ytYivMo zce2UQ(I*RE@5_Q-OP{W6<~Y6O>2Z`W>EE16>Xim7_Vqq;SWkXY77O+N#&yp+-tC_H zdMn$o7ROCe$o#+R|7ZrieU4_+7D%zd37k^Pg{Sw1L0(a8{a-FagZ8}TOs^!Fv*-rt z@4t;!$2d?B9hWfs@1GNp=hVy!=!;15oUqV~?@ zz4xwqFTGuNBqiNQ9e;y#V_jSG2dl3fSO1@<$I-&1f7ir9FNptUe{eE0oxlB7I}3*s z1)Ef|G>MDx202sa?}uNp6i1!d&PDxyU2hS^pttuyULlaZ&EM{W@$}Zc+n0msE&h8s z?RiW46BjluMD=ce;zFvkpdilG)+w3e2}qXa^I`0Ii-#kpD6>$#TcmZlq?b~WgAbO6Y8u!PMU*4N_eO`;msUJB*nxV1MSdK}Z3^e;O(xn<8+_Oo~1 zpbF9|%KUI*{oeYHqUm8%UT?P(Pg#oNlju8dC^qMx`hP0qtpt}i9)=tgq&d3}OM$PksgDgAk{PYIcUSL?(1bu)5-7Y?d~S)-0#W3&q2D2kXsjAlsT^c zccaHKk4gWkEe?cGgxSwQ6s7i?8#AkPwE(tqgw@C3j?f$P6;tUfzMPxAB1HJbzcrSpbcW8a@7EEuFQ6%jI>G8AN8%>B=UVhj<}>3zTWC*a;B|YCP@B4Z})oD?!{_0_ zDVcB^L*y}fyOE4vC6mAL^{#pO>XC9KiQ}@jAU%%jO#0XU!*!|qC-(IwAMrnFA%LAIP4DrSYKG@fy*Hd$n=x-51yPMZ8x@EaNIFu7Ziu0J+n(*! zutoL0yxk0rJxE2?6vU-8YU6)mRd&t_FxQtQyU^R|IK0b0ITL@29c1qtSd+wgSL~?L z<6zc5elj`yum$^i531iPRJ+am{6BQV;>0HDol}1Vxlj5eD{&YEm0j~cO{@R;81xRg zr4tFVcgyHg5}w{Yx4i5yy~U8%G`$tl+VUGvy-Q_J_9PoqkbSytehKLG)@l3JsOhNQ za#e0SJyE@nHFqclgi(>B-`6y}7sA&&rb#&Zg0Bp@nBLBEeD0r5-|(|{z6`uZM##7wxEj> z$yNNi(@?$h#;tQAP`&$7pFU{bL`81A>M^FS9O%yh`w-{7|CdOQV>Xli30}(_7Vl-h{;xZGzWx&n^?!=hqT_B{Kc@WH`-t!o zmg2a5>tzWNpMwaZ1#mxiGejCCy(e{&9+7HE7fB~che&CpU8G==H_4e~O(K(YNvb4C zk|6OnafJAe*g?Ecyg@uiJVxA4Od>`Rw-P;wtBICGL!uT@ktjwai2M*466q3Y6}cmF zMdXY~p-84kyhyl+pU8Rf0VzE{~7-S{u}(|{73k+_~ZG* z_W-_6S@hlgxiEmgj0k(LKqpf`Zbk#bR}8<3g0 zRyouK$n@0(SLijMrI$u>pjUuQqKkh+F99Kr4MxxlKx9Rsg-|CTqi&bE&~rdbE>(0x z&j1-F{GJOv1+F`p|7a$`x_uP(2`}J;?{4 zIzWm}9`kA4WOC(8rDG7fMhnjQH5>*l2*9+5V{UX zN@=<>bPdpqMrB3lDjq5SSTA%|DKdgC=1a0+4}xaCZOIQ7F1{-pq@*yr=Sc# z@8Z-hL+OCtI@zW}djY*Me7+A#1JpH9b{R?q^tuM!Ta*Im)d}u;sJGR4mX8%1A3whM?rCb+Ii>5La~5aUrl&J zF~Zyg7|q^xE!U*db^&M(3`*Du;PHyLlpO$?NS@Ns02)WPnMDD3c;p!u6~Kd|%kM=3 zxbNZ@8Udg|uG={rz}*ivN?`!*+_(L@9l-5f%}^+Sdbj$v5CC^ z25|KIarHF-jx@h3b^=he*Fek>K%xKT!>a)twvKRF1t9+7%+XFashPsmi z;NbRGMs@%W=tKQ00pto-C)onXc@$}310cKL*d1#CS)rk;tN>&#b5vRZV4rXYc{zae zmm|KG0QR10t+xP>mS!Al4j?r+^|Bd&6p2B?G5|@vOKeR6?5VmjuoOUIyhyVNfCLwh zB?y3cgR)UFfVgk_tc(G~-nP>;0uYmZB54VLU7M3X8UolkzqM;IfE`ORpBn&(x^H-5 z5ddo8y8{aWM1};Z=>v!`8m?UcAbgsfpB{kiz0aEF0|-6-tw$F?$d3E&^8f^|ioB@< zV4KvI+1daC`zt-P0BpVBS2GvDmdLbga{vTb4sXx|;ICP?Mgzd+v7J}d0r*~9H#8f- zrd>-vssZp>?FY>Q;H@vTT@`?rU_zh@0MCw#Ka>G@6u2x>0^q(~%2N@5+mgBo1ppi5 z;1PKM>xl#fIRGws84|Jp)}2d{p9x^Css2(K0M6ofe@g>!dZk@01;Fuo>j6mstG7?y zm;qqbvi&n8065H^KPV1>(mT^w41nDk@rmgGRvwm}I}LzsfL^O80GmZ07LWi~OW$!I z0$5RZYlaAb<%Mx?g#lP@3)(LPz(U1;QV@XI*!6A!0LyNNzvTyDnwwLGQI8c5ej zWu!vVK2jVhl;nd}|5hX;k~T?^G@Zml94Gb@JBf|N8sd4h_Rk?E5+jIyL|5WU0f_$# ze-D2Le*^zD{xbeT{(by${Gt3l{LcJV{6_rR{EGb3`FZ%p`TF@f`5O6Z_|Eek z2=h+zj_|(aZRfqqdxf`@w}3aDH-87Yo@YD{cy92N z^Bm#H;)&-88JSq>Rp35Cp#q z4hp^$Y!a*$tPm^~%oR)$qzVS0^A!|9Q^5s-YJyUNf&#w;h6TC>S_N(kTta6n@&wWZ zb_xUucnYi*un;g1&=imrAQDZ8^NFg&8AN`OpXkiXYmsJ=I+03|lOhL2QbeLfwu-om zIEa{`^DgQlG9tpllfomyZ-v{1?+RZLE)_076`=p3k4Ef8t`}~H!RW_c*g2*i2BRN) zp=IZ}VKDl!7x;CI2!qj&J^$n7`(ZHpvFE!w#~ucwAA5pJ*#Q`ge(ZToR8?Ux`myH` zRtkkps~^|GvH7_qp#a=d04X+3Ed^e;H zy8?RJow*5i0o2jB?-RTZ(34$a8{oBo+8x9m!Ono%7RklHYXG&3DcQnKfSPN#p1_WP z9;YuhhgSn?@{03-ce#9dQTLY>ecvk^i0ji5i`U$T9bjy5D0A3ELmVeVO*b-39i)SBU z3qaK;?rOs3fNq4nw1dq6U3cGS3NHh6O)py>HU)I0zxoEe6wu|W^g7rC(4{>QMKA)W zYSm{um<*^=HBk^Y22?TrBNa9Rbm88!W_Ssp^T}3DupyvxUQTP_#emA^lk;E$KxM!B zXTpmBow*kq3@-#!da^7D)(3PtVrM$M0MMzq7UHlTpb`Pf2s|IqNm-xIur8qD(#nhQ zJV3`o#Oh%kK*x;v4#L`ij!JsHfwce?y{nl6&jnO?F}oU`1L$z1-yT>KP=QTqI;;UG zUrE;lRtI!wbhQsW`(HHg;|^F2(1AT(a_}rbxo#R|uqvSaNvBA#3ZNWr;d`($psWVF zjj$4+%>DB1up*#+-t+ol1wa`~ofTnuK=`T!C?bJt z0W1V4+(FX;76gRtse=XRWWTmCt^#fV4?D?PL;s2aw~Eee>bl zfL6Ve*#XxBayU~A!F7P_drl6)w*XPR<~YE$fb66m$HF%O*}g4Fg=+xW)QN|~)qt#b z{)mTf0J3uS?}D!bTA|Z<3BCr%^8Gm@_$nZaU;g&+6+q@$NDO=#keOf4Z}<|RWg5;h za1|g^!NFL#5|GKKb`kg@ASCB}5?ld@?0xDRd;yTL?qyZ@JRl5y0lI17-JU6LA{2}p8! zr#`$7ki&?f;|=Bmgl!Ol34pNu6fiF!>|`^{0|+|^ z3UdR(&dtGGfUsjmFboJgl>tM5{IL7c{s5v~Cp8I(cKgn6K(xzBegUH0?Jxm|cFX!t zK(tG#e*mK0;rksB?aI?{fM_>Fjsv2-)iwr*_O#U~AlgenUjfk`PWb|e_Rhp-K(rU% zM*z_t$o>R~_MY%CAlmb*9|6%`s~iI4uwh3K^Z}5)=7cRYD1vIn3!i{Qlmt!rHuA)y zfBfecr~L%bJxJ&l0ho}gYK^V!Vj~`~2PxP~R|;~~n3UxvR2 z$+LIJUUH5KS(DzbaQtu+oQuB)N#@gwke;gf9Jl}9gB}O7{=Jt?d#Lh;{VjI7(H32? zn;+m_GzWBZf0xnrM=@f`Z?P+NWGxQ;r?a=JZO0x+j}u|g8yms{y_4_!nSrPG)@(Bi zOz)Fo2R37R-%Z(aS{&88L9&6oZZ-vh3pSlyfa+Z(!9PO+)jLbk#8VH|JEBSK(aQ&s zh@J6}&vzGmy(iTSUM-)YOs3G=5x>~Z4_tf^@ofVnr?X8el^eRkm_iL1QI;h?!9fTgX9EwCj z+$m3MHSqPeq>`qo4JwjByU(H1UlT;}^$vS*(fLx`JdV@bf*uF6{_&pBy`6oVeZ5JY z6xThI%=OkZQnT{dIXUI^E;O9QQXGF&0~S0#NXyaeEI{wpnFZo_dY1*k7cjlK zo2>mYy;FngUm>X8zxH2yWTi|&mfY!?*4CeZNE}tq!StR{Ho0srs`s)kN9bZeBoZqy zb~t?k|9VSG=r*q_R~5*h-MMt3Bh}sb*INod?7Mp5n>NSky^`k>@RYwGEoKgDaa^esp0>A)mc0cT^u}flf!+#vfns=iKbO1u z5z|{>g;@Zm_n+#_i*BgiGK!xXMHDDVYVA$w&*=3QWt6mMnBEfQ!?Eh9-n)#<*F<|p zA_*N5@d}^u^&YmHlnm_Ki^@^)@zT#xgV*W1%Fhov~E(k_AVyW{`4{|^*jocudlAc-;LAZ*

hgFw$T8${Ep`UU+oPCv|KD73SX>#+L96?hg^ZX`kQ4pR(sAeo>C$~%k@9E` zYM?e|<#IP6-`i6bov)`NK8CI0=l|vn5``x#FY~6$lfCHeMs&V?m;IYJNFMFC9sS+P zc{yk%J&r~u{VU8|uBE0rooOBapDHzcO+1{tfcXd#;?6RE?BF@&N05+g9!qf)^{G@- zN@$f3xPoIv=AOSJiTL#!y+-gm2bz;j@WI0hwsUwdTW28{@H^bkiNF5>Vgld zx1#5da#>VwnZ0Y)R-$^h>drC05l=-P3@K1N54sP4{aNk!&as$1cm-D(2Wdi>B ze_utBn=ev1uRsc-$HA4!r+c!m_YD4EXS-?4^=?-fd9kRhZOZGtZ|_%@;@B=f z5mcH_(|a0&-q^}E&|3w5IulQCuNUfbF}>wCn9b>!+;rupK?}D&7YO7XL5!?HXu4nu4>wibRw5>g{%4BPLyJ>rhLj2nB z>;DZN&mUBZa^CFiDta8u`d9x+3voEkzTP*8o|^ejn4kZL*2#KXroWx?dP9>lSc~Jf zxKF`f2c$(A^v1So0KLn9=E>mcT~Q7{!wRIbo)5J8KiA(gRsz*~YqGnRxIP8huegp^ z8Pz*RR%<{C)jQ*g_S~H)Z`^}x~7f3&U-Z*5*|B&gRCZNtzLe|H7$`?pszNRe2 zvHHlSi0UNT^cIOhZ*1=o&|6wCP#RBfy&j=xOz+@;5Zdgmrjy8 z<%5Rf=;DOR%s{F&Xq$AD^YoUW$HAI(P9u_5Xj?Y8=UE{V&CkgRtF~AP3zI)>OsIL6bqtxUegB=l506E=Zr@)4tpc z%|W83)MbK}6r|>?U)~71g0%DaJz)hj2a)oEq|(t(>`6-f$=%DM5Q~TI)*-L(3#87) zdD2hjijmFe?Tn|{SUq`!Umz_JpVP*Fne*=de@c(TkV*esmu+3Gy@dS{q@_`S{q+{+ z1rp?Hk?-TU?FvUa$WEsO5SHS|dp2+T;#;%=Ns>WtY&$W~+vC)*GM?UN2Ht(e3Z%G% zaGKt7rrREnQN0P<84r0?=@#JMQ_n~^1l;mtXK0OLK@JiyN z{~3I}F_tV?Gq;9->EDvArypO`iJ{?x&xDjM5Jq~95YYuzu$vwfo-kxiY z93JCh{)vr#^!!_2R^OD@`_uYnmg4X{UK$sMUa^B_?->kwWBcQQ-crY^mGJa-8!_m? z^xo02kf!&?EB=ocp?a^>2{+qeMnQH~+glz)^%f{gzl-T@Ib%X63)TC(X>hjJ02SG8 zXDPif7GLitC!2eAYDto}(c8UGlF|(c#MgVJ1|MZjks8P8-A0dtS^qpU7M@%_hkd>4 z7pWf#xXgTk6so;gzN4#m%IgjNtY9gQbzzA!t^b<6m0-{tJMaPYF1@x_5l`=fVbX1w z-d*!XXp0jXMB)i;RPVky(Lr6N6lCF(psck3_c{eR0WBm7hF^>+STrCxq}CRvW&&eh7}<75QB-gC4! zWgV2^yvvDK)8o)&(!VaZ>z7K;u&?*58)GtgD_OXE`-;&*xqA&${{BCx)RMJ0cCFbs z2fcgypZ))wn56!rPv{6zjv)tOXE;F)BD5=O;^m+t{Tkv}{ZH)|+=lHzGC$XQ|NR9$ zleE_xe`NV+2tAdIml+L z_npvjL2^93U6yn1=^Z=pbI_wlrOme|IqwB2D|#Fcne?wHUesuOq(T!>76m3o2GZO z?FYASsNQ*dB-?hO&s&asx#~YMf^LxZbl9wd>TNOh%^TfriWolmIlTE16)CZ{ZLssg z*V~rAz@^GYn0$)fZpkFKW|BR=-V~^Po?YQgjvGN*{Xh2JJe36Cp=ikqSvKbi9Q$ ztfs8K^Ww>I?|$yd2(v}UyT0T7y4NeE=niiILuYHvR*_a!+48R;0<3JLB{*>&p0JCyw7u$^22zKsEm{F{?TQ; zND<)ed>}dCtTh1&UF3KRkPe_Pz~!m!so-$Gc-m`DOZhy|oL`ft8v(@vF+#~Vjmjmk*Hi5Lam@I5GGyoVrrMKru)_HQCRPMrR7fQ0u#kH}Ip zfHz0YMIyf$0easQ=z0Up-n_)JG~wBs!ul&p$pCMD{zS3bCL#nb3M+r$@fW;%Cx0?W zEx?oGmU;`DFZxSy;x7_g>$6af?%cZz(Sem8xAww^&*Et>PC}WsNQ5U-(f=nb5IxuO z;qL#|c`@EUP76_|gHZ5R_22%VG5&tR5-U&PLGVpbWDj~)E3S>^LFKR4*1>O(Hc5OA zf&2d_UQ>d{L4#EK^FZl`00I=p+B!x284s1c+ffB?vCl^0oDKpHa>!&_x(h6^>7R>j zy#KPqPORKr;u1PybR3Bjk!hF7U538IzU5Gf^(vXEptt|%Lx_$xjQrMalihb_oc0Qm z`=^%24nFK97U$;CxpE~x*0xUz4e#wb$=hMP zKPBu9hVjl##5rXFydzY4*a`vOr}_Cm22RC8a~)>Ea0R*E^W@Dv0PizJR$MhPL`Za9 zMbvo_^d+|bq7j$t+G!(kB(B3{Tjot>bi5O5wh1gc%SCrfYz?9#9wWbvhGK(Ww`j+E zNUlTg_hRe;>Crvz`Hty{43GC%=U%FGRP0`@o|!saTptZ#Ye}H##(N4~HJK zXtwY@K*u|L!!emzW)A!#ByMMf*Q9qbx_kF^9&oAg5urQ0LlGUl82L#&j6D0MoOZlt z%TM(EuEXBF#f{zQUuew7@clndk~$q5mFEe?{P}uIngVb5HdQj->rJiH(eQqhD58wvr;MuRF{(t_4a3UwzgY?R<$SIB>Ko>qg=;#F=blm@#h$8Ty z-evi|a=?Q`bw%B}&BCEmEjHHPAJ9F>X<5qiZ&ni(XOKAK=iT8eU!Z%?%evOrQ%~pN z|0jw6H-F6?(b0jG-)zktmyfhxv6I;I%kQWac7ucq`>{{@Wg)|R5N-o?I&5S(w;LGx z!xJPWO1!}Z>14dc_Zloi!~3VXZwHKbZttp4xPsiVIeBylEU|GvkCmGc2~g={r$u`v z;-Q|?2lC(sX?3xBj2XcDl1(PW?aq*|mrc6O8;yI>Khp?xY>>&s%1Rio#U%|B?c}l~byW@80va z`%$HX&rqb;o%BHZA_~0WCoIT#ul3rcgNApJYO+`pz`I$+JPdYkFNfWehXLLL-RqUP z0>SQWqw5{#U*LL+V-8|c0PnF_bDm28@9RQ+cb!_op(9R7`fI$sQ44$ZzG%tD!gm!Z zNZdpxzseyOC)9ZU&K2`j1c&JkZ(~G<1V(VyZwpeQw z;}1xkUQ(qaZxaWPO;ceR9WO;Ll2ub%t zoUAeE?(Nw#!Q$H4WF(8k4VYhzJNcKdxAG6!7?1J1qr2JLazw`|jQox|nY9h7(~h^& z;l@OnGHkq8ExDv28GW1K@vfFGq)JCd{apBykobT5|Np6^ptoNG9;89xLGY_oum|x7 z#Baao=z>G@pkRm1E1!ZTwy^JOB)r7(N1R`99W1eqTb!?5*-e1>JxxUSfeBJa(LH{6 zi#@S&Q>`{wVtbF>U)ljG$Rx2NpJ#5Od(ijl<11bJI4Tbzai?F)$Zp6)uOJ8B>iXQa z6s5ZcX#&wPgpnT`i~sSBCbWCdVkt}h{toOtNc*L8i;ojmF?r~iB) ztxkbA{LC78iLEw%x&jUFQE8_xxPtWf78(KLZJ~JCvl`%it#4}nm=6KUAG;9~0{Z{u zUj&2U?X4+OO*3(TcbCG2Ba7b?A**(W&0_)Rc%KLz-Txt+rP2n8Q!NkXed&sh_f?L5 z7ZLV_bcgpzL`N=0e&$+VQ}+bXzP;6OT|l+d3A_KtO&lAXd$6A2@y2PSQKchzQZbD0 zBx(MyMu9i{ZXg-&83(#vIpH(C*%E`1S@Jo5IFh+_rVWz=j%z$NQY~OR99d`7Aq; zc$9R#g(?N!@I#nnyuSqO(nrJl!QdfY7;oJHNmBoBwyAxB2@EG5qwcK&@E-Qf>KbBhhW0Emb>3b;gq)*Z3<{f|m?w<)DbZ)h<( z-Wr=LRQH6i(H-8e5FOeW`LWC>6^DDZ|~b|vGTXRWJ;hWD}7`T6kfZS=8Z((G-)dGmvE0B>Au#Ov1m1nAaN zPS^Br;Ql|CJtvg`-ZGm_N2dVZuAe@>_6rP$*0Bn4vCc=|-nyv6_l`$&k@fb*|~`Bme|dRj%bYh)>xfn3(2H?iItD^ z-Epb84t4bK&tG{S-$e(JpA5eTiR+|NM@8F%#eYtaYE$41Kh{ph+e1)s9va@a6`YAM z-f^*GB)q?l`yF=!c%O4L4<^PCAYJ<>jT-^pNtMU_;q(7;^C$dw1H7-~>)IYWM}+)O zzPGu&1igYBms%EIv{JCr7l|{ST8gjsbs@mVsU1xe7ejS|NK90FLgQ&XSVj=zeTDb7gOMUIbdNO8Sh^AVHPyJA8dRW z4dWfg$rA;;H|}h2s}GE~NLN)8INq{;*r?z7#&3c+O%$m?^-!J-d!Q%03*j zFBRFLJ&um|uyfS+`MG?RTah>>=is{eAJE;~_G4<9>4pXiX9?eq;N0{{K(!MbAF~4_Z#)L3#BD{K+0P z@YIwC&4bojODux-ATK`j41z1jclo=OwgV4J*5Bf@tAGH_DjK#bf(B{OyQT!*gPd6{ za`P+LgUq?oyY|_)Fi3k!U+P92`Wqy810K8J9n%%$IISP6lHK>9FR`T!Q-*dmTy*C_ zrihLzjQm{slS}3~(e6P>VRo;qmS9(q8-n&PPX8Xr@D-%@$tbFHth9d7{3VOjAT6W7 z`}&pqL^9si`xUs+@LpXJkO1S|Qv8GT{r_UO7isPQ@2sB2qpi6F=+uP%B;5aJxj2Zy z1JaoPn(I^Hqqr?0vS%&UBi#O>TtFaARd9q$kLFyY1N zf^>&>0-~cIBfljTd3>)@X~+B41+7HI5h^OkyquKCff$Cz8z*~(Ivppjn=koOK`y1h zJ2!McX+R3^-dbyY;6%gQH(=8kjQ4>ZIi&OdA2#T_y8yg}TQldf{|Zc-4&{1!j<@KW|FUrac)MDe-XLZYApMg|@C5+x z#}0kB;Rfm5_}dT@fOkY*T-Cs0B4qD-MSFcMI^Hpoc1Y8Zn0xt^0MiOhq1Mc)Ukamr|v}-FfTN zU6G{YEjkok?{@{iDO5@doUjN5yo5T-9ggf#J%|2EOr2IEmo1#%_j*^^J>=G z&j9cHOkTtAaAL1O=&&2W`+AUDd!u_8BrDCStvj|0^{-`Pu>9In?*%KRkht)nd9QZA z+=d!ol_vjcrwjef-YgLvH5mClTizwIQH^%Iy&KCtn|EQ~y%m~vrqq0IFvH{h^5$8p zbbKu3P)%3ZQwAP>3BKt{}$?pOgCkOD?=j z;lP8K?^NgQsU|>E%e&vK0DF+KyzVye5j*uayGjQ@|L2*A5QSfyt4J^}i2D(UfQfcG)I!o@J&dEP2-;S;3zs{8F-8;H<+UZz7& zI?*f0^;Tyr_w#=?;zQz0+?XxW>(ML7c|TPh^Y;9ryHD&^Avz|e{+{36Lw17(#kAuc zS1Y^!?O7`N|AE=}TNdnOc)W2E6V&Noaj97Pr~fyg!271B-BvQ*$=l!0N5gvqr=AXs zx30wn65fZ|``H5k-Z7HXK_5y9P@nSn3Jx$Jo!4Q*3FG~XH){SDfcM33y3aCti4e2& zM)9RYbocJ~!TEM5^Q{pR5*Hh{Gw$&Y^a+wfp^J;#k0H9lyAIKT$H*@?=4kViU9{tE z7Vv3t&>$5Dq^B1Sxxf6*_;^nUP^BZfP<+wk6_R`FQ{Y{ogFi#Y`;*T#J~X_G+r8Cc zyl+XzlJK^2YSq{a@K%~Mz)9UEK&(1a)`tMzn#aX^;NgVfrWxB&fcNV|gmrRniBP`R zkH9oPbi8L9yc#W{YAUWHas8ij?@v3S z`vK{M8tG*^OR=}NIzO=Uy^Yz<@D0+(EHOq#tBTxpxV87hB+j(39EdtO_nd=NU`^+7XHXBK>}2t?xcM8D|Cb3@0wGdvF* zIrv3)c()-sK4au(evA9f2N&AiyG7xgs^A><>@8Z5$acV&iSgZgUN}`cd~SxQPJ`<$ z|9$_DPMXlar2+c?RTLg{_s-E;vIkvm)fGkapx^Dcjo>9V;Q62ae{xD!wHYk2wF;8$ z+iww|YZkn})W8!vFK_z^>wqQJ%O~@-C0JtX&L1)HCJ><$JMLaE=|yjlmKQaDoEDlk zI*G&;uN3V3@C3ahOKi_vt^N5r>;ux#{Hq6} zSOXZ}gHGV7(lIvJ7vO!FR6#-%c$XXuy+Fo0wVOi(4R0;eTcqu+K$kXB1)1t$IQ#(M zz46SJBjUvbXouL3=(k_uq1qest+WB&9}T)E_5i${cTBuqCrE_SpvGUtIp}zcx@ij! zkNq^tK;kr&y{x*E(ebX=(pcPY%}ICLTSADA8jSqT#<<5!?4cd+Hq+k+^<1&>p66dD z{KKM$;qgwgtENha+Se0RchgCD<0{*x=!23h*VeTY=x9p=4mYh#vkW;RKJ8LL9-m6=c zEw}kj8Mz>FR|0!8WS!CRj!n8bW%rJq?(oJVIwCRh`<6_2ESya{-j|AFJ!@*QD@fc# zna@j`FAR@2jc`)DQW=kzOV%AM*wf0{sSRD^TVL18!Qgf zE79@Z{rHvSZHw?x0Aq8;yFyP0e| zUQyxR)2q!7tNSoK-Z&Lws&p`I@9Uem@NfVBx3-&Z{vGK5*HU;;Mb0BNvIni5Q;|mV zpxVOo^I#7;ANZa0g4E~@h~FD{kY}`m;!5y=bP-QhWB|DTFRxwT3fv&Yt?hs30z8OC zO5A_uC72*-+v~pFg}w*5w8n++<|Z7T4TzGe>9<&6}u^cPE z!SyHZZl%3~G;7Mm@m5nYLAoE<-gasu<5!T0)aiJ%FU^4C5~)Elp}_lo@VkE+Bnz{j zl4y885bIn3j?1X zvr7&WyF!ElUcBsMH8nMBif9Zh^8@EcxgT?^HyGI!1oW zxAXOH6r%l!ojv{2i>Al1@n%)j7W)+VgyHe-a9vE5juW5EpFasERgh~a@V@7oYD{)- zj&F?;Xm}6)UMd6QEiSZ`g!kcP$?sDD-n&PBvL884fY#|3^WFmul5^?~!V-Wt`-)3a z_5km2BLjYmC?fRkI~PIwFCR#!c@yI97t9!SB5|AXTw$+&qgRlj{q1L#PxH_n-bWD~ z0T}s(oM>85w}y82=AS3Ftm7hf1sSb8x;yvvD~87#_wx%?I!yPUoBk9>a&Kb_yvudd zrO9~r8)u25;SGg7(uDEOyp~47yRa%o3GV-I-?rM?aFGC2^yU>-fbFeeQInf6-n;g+ z^Vk5q#e0JHZi^s7SL0llF5^dc?*sh1O>SiWHp)ffcCPk#+wl_}Z@r7Dal0qE=??EG zM28MWewuEC8sjM1@eU7{u#U*XKAhMz>a=(5M?;2hkc7WFP^H7%n|uG)+a$bKQ{Y`X zP;sA(w?>AW7#iN8AyuT=+t1&$&ED*#{7$|}Awmf;Eobx>q2v89zcFsc;Mh=G@W>+VPHvR(;(mO~v6vk6+QjeXkk+`+t^6 z>U8*&epCU66aSt6(@mF;o(Smw%_%&nZm_qA>_M9@DJ??tAYZl}>)|D~XgxdW1L>vr zIJ{556{KmRk4QQJG8^8m$Pd0j`pS034Q`MYc+?oVgC+L-#P`FSFB73ki|bkM^w2%% zke9qB*U+p{9TNBYHD{x^Jh}%dJ=znwU@`qQNO6b`8I1f6zdF&~_8&a4`{=f9E3HtLul47E^m+=sYr_+Nk@0@IZ&Dr&Z;mr7Naz29v};Kf zWa0*=)FS}z?zV&0Hb)6iUkU$JJikBfOYDt^vIl$E z8&N+!{Kwbw4%~cvqL}gVUKvM~j!^OR}E$2~bTyiex)D8laD z<{eDJ+bwt{AqL<*;%Tv!Jrx-;S9kT}zQol83M(D7Eb(pCFDMSpk)AUYOd%O0Xi$M4U%ZVPis{l6&%-j#1VzL4?O;)7s*ta7v-t+U>pC?L(LzkO( zv1*i{iNh>-ZbODIPBQq8P^F{6k*HjDAmiWu|DWoVj(-6Cza@nSJ-)gxo9saW zhQexS9&~mv@i=@3X=P3T=?+q!@H;L|z=QlJX4=NV4N{_STv8T;52PQgdKL-aAa!A_ zWVQ;pgT$(LGk#)4IApk*Nmb}2x(981_1v@J(x-~mNL;ImrRHcgx(E4O*K=%LI7xTk zAXy_iA~Etixq|<&2tVx}lta8L?GE_-fB8bSq%D`g4buLOThajDs;`DD z;V(!bxBF*)f+g1c${9xuQz9hSwpHA%1O12{B+jq)#wu>qCEGJ z6=JXG?gQyXhz>kPekT6AM04@9SCBHp4q+yHvA4H&oXd-Qn`y=Hc!yrUM3s*Hzh)g3 z4wEWK3ktmJjfktscq?_6DWl;X6}l=FzCmh2ZB00Qd+V|{pUv(8yc^do_-T5902ylD zw4DbkNG-YJE8!EQ6T0g=8vx!nxF#a{b%{{cA6tMj}WY z*VFq!%73}u;_xGqEbJH2%Q(NT+$Us0(;fBFI1@n*UHrhaS{_UWzGdrcPeB_$Xh zZ*MWKP1NXEV{Xhnney-Xe>(2^|5s|D|F@y=pq8TsYsnt8a}%dFng_|JF>i+VAhQ;U z`NI`t^nm)KLQvjcIG9Tg5poZ1G*XA>dlOYD-W3h$^xpXjdtFGX~iVC45(?4?q~8`?dn zI_tHX%1Z1l_F9&@kf}qJ4DUguXQq~N$E7UKYKowe7cV$Tzxnr+s?)1ZQ^UiobcyuB6T%+sL?@Ln@;tzvB* z5q$RIu`1~=52U~8Q(HeZ_^aYJ5_kIerLx^?(DB}r)>}MeN`KE=^ddTZG4k7&cc+kt zhjzU0*8Y50pF%|iS=4PZRME`vc;iBPsM5j8vB&boj|BJysm&C4Kh4-idO;e#|NqhP zd`&dGadit=;Qqh<*gVn$=~{UPM~493t!FPj)yX12&%d7L^#FJqsUDA10C@Z8oY|od z@Rsoj@x1^(Z~4gXo~E@D-MtUo8+}61nO8ZC#9a$5R@(NL&s!vK|GL{+NPo{;#3MSS zG4cye`R3KRiFUlZBnFQbs$f@;D(Q+D(V>jrAia#UrAmjRQs-V(B58ZeiURK@{^);R zZ^^Zb(Llrd%lGX+VZ5C>e~>OnZ~vI-(GBpfZB-9*y-a{wu3sFv33hLV0#;|k_y0%c zoSJ|iNNef2Wa*hrg!YV`;ONyy$NPoZUe=xi?3I2<9AR%+E=~d6z3qC-?>K!E#{aLX zi#~p8Lv(D#$nT_s?!K2PwBwDN<4YJErQ(2eN%y%Mss9hScfP}Us&tq)_acuI6DaU* zeC5UTPjQ0VppJ(3l)O7fGr+r2Yr_G!_I|*t7W4w(J#HYfR{JUeS}O9c={5NF_UL}@ z2k`TjfqsMhb^!1F;l^_NL&Kp6U+*3X0dLe(N3w-RUZ$S26){NM(#PUb;Y?1b@mJZ7 zIIHFJ(jDH55FIx$^3%C($(r>axc9Gfda7~vuxoGJ)Rz5;KRz)2`TwI^snQXra^Fq; z-|zqF!{f2C02Sm`3J+?FTIfvnpo(v}I%p$tO`zNB~B1V3`3Hy>9y=cdKz(^uEXaKwax3~RR zn3w*X;qiXzOq~wLfESln{Fxwap}_m4o>Vj$@9z`mb_{EXa7jv-8(M!~1LN8%r2(m8(;GVfPlUj{Nit z;O*$O$6W%P-pa8#-smNHi)}{dxVPG zTU%)9;EWODyZ1&}s&rJJf3Y&{>c8`Utk#<@{ypgbohdx%ZG!(Y*n@b%1Zg125r^hM z&Ayv%*8>mo6m{7Nd(io$Q~C-;x~pCh#Eidz0ck+PP}e=+LBW#+j?%z`oUd*qCIb&z z|6)_(GQ)7_-i`dZBdzEjl-mBF^6u_M_=iZGA4m7z&{}j4+NC@()ik0@cOG;U(Xj&~ zKWm+)=v}{P_aLJ=^<1qn>xD5G z@8|2{SPuZakK9w&{2>?)NuHF}u*pZqd%C7h!d_1SuY|D# z4(};MM*&8DBi-71b9%HlNPBZq?k0+1>J)GZ(EEoq z@iG8!j&ePXAb_{!>zi-i&k>=dPnrjApFqc(wJt~?cF36i;nj^{mUGC zBbLw|-rR@|W{ms>Jae9@gwl?;WqX2#K?4;7(y>p^zEu}6Jl;6N@6_qIFg&32=ls6| z1>Wu5$99tO-f8QhkA}CU&wdETn|Sx!F4(U3m3Q)anK zDo(ah;Qgv8b(D;^DxaPn8s2vEwuZoXTj$5@hVkCex-&Wu;QhV%faxfB-s1ixubQju z2~dC4ivk$$wB+lijsR~-D~+UQufidlQq!nbe{{V2@>e}U zU)p8ANrUe2?nQL$#mG;aFP5nTw-EJw16sLiu9a_BK7oxl|B^(n!W|9_@80k9sMB${ zu{mrY;@|K8(YT?jUkCla2Zaaq9Jcxddl20Jr~BEkp?Oe(O4@dK5Ar*Qxex3?7eZ}t zWuQU2QtD(bn@WIs=USUpz!{{+W-X->aD!yJV7451(90Ds+xotOD|WwST}e$uuORKk z4=$dsrhvbR#5r63GP)CpUO@^w^!wM`p}z*n7SXW~BfoD)Tpw4jroDnpzsKotVVH^v zlBo1yfK7$rJqUOG7Yj|(R+ws=T{ex_C4db8Tp{54N`&M-v_z zj$?oSUuk=C*DU)H|wl9A%G}4@e_bkZu%scgdN*A-nhGRvarD-exy4j>34K zDStz%AWaGhnTG)0h7Z489|yO$TC2`1r~-K3;XGOf<83;ywLcf&&C*<;Rb4`a?htqT ze%XMI_rr~&E2Eng@l{CNQ}LRD)aB@S7aq>mmo;BTcX-z#ItnoI+q_2OgSQdw?#-bu zp70GEnF~u4{WzUFV`UB&9e6%GaB9lxeEkgyxWfS zk+!#vdbXr`0lYUpcCB(aL4e+^y=fv1&i}vZ;aDXF@E+ah)t3eEeq%aNsJbT{QgWB* zDPl!$kdm(C&PY2d;kA)C#lD-LTfU*=t)skC*S(eg@IHv>Sd5XMUgL<$!&%yg6O}4n zSA}}17?5@meXLd47{C7yx=NLf7!SvYds!s+cA>!gU5=+98E^le$xLW?M;Y@Ufrk@G zODcB2wRhh(+>imlTXf@ggOyM#`~wY*|C!V@AjPUvu_WCL*pCY zZ}=>Mj(5c4Cj|KrMf`6hE_qHlAcGsd|6j@-dFa)5`YTR|h>j%~`L(m}71;iScK3EN z?%q?Rf!+TL>xHyR`DyCYRp0j?B-7fwo+=$g@wf{w!0oO7-v9p}{73$8{}#~ydr^4M zC+7}4*@GsQtmQ%Tpma$aeYpSU={`<6Vt4D^rjJa;x~ukIXWttdM}S^+Hpy(6h=(#g zJRZXX(lyWQx)Om0B`>rs?duPNmP)ncEek=vK`NQQ{=8$VBz^@Fx3es8ZM`G<4N_hg z8xE@Us?%Ks8H4EXz{pR-?Ttv(9om=JZ5i@jVP~kQAPLbBheoH~e;cp=<9}Xt2%ah( zab{h}Cw4n2@a|XL{}0~vl7if5c)RIbC7mD@hQ5>VcD8!sH4T6nKA}^EyIy@6g76PBgsNIQ{a1-JAW{Hq!2`%HS3EZvbzfv6sKo4-z2u z<-ep8r47j|8@$zds}#_$#@?NE95}K+yCSJI2iASZBIyeJ1Vy?83cHTO7lu2B!SOc zW`{K|0lYuX7+1pETRWVZqOJqHnQ)5Mwh~0>db-E$xB2LJ-SsEMy}%|_x7Z~`@=PZS7f|@m>yH80)*yz$ou`Cfv@ zi9-uxxE=t!AB-t5!+2lHw?9?_@E$A6+14*jgtncCcolvN9q+v==?=`R8g} z(d{SE@lFzaCT!E8O?U3S3(=8)k)KiL$0dAsX~%oQu8k<9iH$d_%ZTntJ8OggS3@1qX5Fi34zV!Lmc<52|o_!*~gLEH?uVrHecaY?)nF~4_ z21Q6IJm*zI_n=iFDopADlK2=TZal5%X)`an2Su}1*knJVzy4nj(Luz>&+fv~6rWLk zn$I8!IpG6#mQd0Emur^{Ox|St{@+~jCRI8lnAp|+RFK{jcn>fB(nrSoPSpGbXn4D= zx9W%SzRd@b=Kt5eMMo?Hc(34mxWvJa0JVJ`5e@|pq(7MZ(IN`)Hc4t8839Xd)0G3i zEk%gXdbL$teb>Aq0=Mzb2z0!w@84&Qn3KS#A#vU3jugweqvM?+DZ8i4mj3WAMRXj+$Zw{w zouzj#?G>ar%g0RC>)3c}t*}|3a=(P(@jlS?f`b|zO|p{D_xySPZ#MOx7P3lZn!~GBfKTyt98ma*hEd^oXr`Jq2hXrhugibT`XsKym4iE+o;hoeIq13{vye}cTwOykVCK| z<6Wv8#fygbmE~V#VZ5u&my(7PHL8KH1OeV7(!2Hj_Y)w_$XrFKAMwzPajHJNd#mI5 zqTw>Yd#i?#M`H;uU4Srt>xhESm;Q9c-tU4 zR59`kKbNZ3_K9}9wY%p&tXYDMcl53dDP=h!hVTDz;wQPO(Lo5zd&7C|-~RtUX~+NT zzX$aH{uCbc&2B>h*@N2l8Hl2J5YOo>8TkHxmI8A>_zaSQ*|gVM;6b97Ru);y5}-9H zS412};vr|{ZT@ioU&Um!mJ{^-j`b@g^?nfS1@XcLiS_V8^^g7L0m?IsOKZ@5lz83Vk>WY#Nm zt|CCX^{Ky~0=!uoj|ahcAKJXVoE_l(LGNj1ObiivYiz{cER2qK_@;dPlM@p7P9#pA zSMP-@4jpf;GwM%6N7d-gy#o*(${6`&M=_m09ZY-wubnPsHzkkV|C_Fpe|C!_pW*S& zy!Ney8XddqR)(2Jk}gQwM}hZf`BKvBEim4=r8;1yX%N7> z|74Xr(Ut&R2<{y!9gBw=gyxgnTluHqG(4Pmw#0SEGG8L3(|=|^8!I~Aexh>&isO>_ zhVB0Q&j`z{Vc3rc1QuzBwoUebX#n@lmTfom}zo{+#;T@0Y;Ks<$A}+a+bDVa( z6MIhBF!N&LJ#y>9uLsI!7{2yCy7=99YIH>1Jr?=#^1uE6f4!IgPyRsA|A$a`&`&7( zp9ZNkN?97sgI=|s)`pi@{(a%3C6+n0*k&78V*MAnzFVk4fXZhMXUPo2L+VG|xdlK4 z`CBD&!%ncoR^nCdpMWQJUT1~!D6ByDAdk&0PRp(>#J@q}O4Nm_?<_*EAcwAV#)~dd zpt}mv3DMDuk>B-=oo<4x@t-4h z!4!B;DWqH@FR@=8eoLa^{U&u~0F1X8Yci=psuOBZ*#hv^Pk0o;!69#@krvHt7UuWXw%DYk+t5;*(6}as;SM#OqGP zP&{NIESf6_@bqDCd6XQ>ira7t7 zQSzw3&E?O4G>`)CAJ_K^lihp%rc`k>yaNoFxZ&YMIm=Jd?rr7xvknV@w{!l@d5RJQ z=<$jI-0#ovkQ{3#n=rtexaYwMd4Tt(ga-q*65&wiqi55h#prmaFYs;RowpF*g~Vmv z{hT(Ig^stTW_`xMG5T}wWJHG&Mt&35t#I+lw7Yj=?Yk;Tp(mJl2b3BZeBl$S@Ds1Q1%8kA$%Yb z=lr_l-kT@r#fe2etMhmQ{XI@}2+^??BfsgeBxSyPw7WOgy+>6KzG4?A+s=;v;MbE3$-q( zZ;(P?VxNle7`8VE;RTU6=R0rCTCk%pvAHKqFP<<_q`M08A)+G-BR>m5`*sTp+Lzeh z50){rzQ?{|C%a^_O_c8d!#7AA_7ha;*q$EICLK;%V#6u$p5^<>PR6@w?z21^-p93% zE5LX^5HTU)&7qX+t^)8rbdAd`dKm#SdSA4?05nL$ZSyte1H3og=$y&`c;Djv=C#EV zY_S`i`dRe>eTfya-P+|dCWI%)70!NZ-}sj$wn(8k(0C91;mwQaxQ>zEgQ69@ykWF2 zv8&Yc?gSjb-rmBwRGAlOBr!bR(I=?W@#;*Mp=vT|{!gU9`}bQd6Efaxl~rdJl0)O6eU#B&dV<`cunjgV_8*Fdo4LrUHo*WnH^eQv32)%;z-t*0DuLu3%t&iyNz{oE_V#R)yBHHnu zyb_YUAq2aEG&`nZ^D=Lg;qh+mqfSRd*>aZI`y{->DDa-Xt4w;m1>W8wW~9ra;oZIE z3oDGbnnVNX{QqOatDoV+i7PlaT5Z%JKn`Ww?)-S2xgH(w2wz8=l_!PpU5I5CVjr-OqG8s3X{ zXnljf-nzClnuIq~!ugMm0Pl@vr}yh=6QD&u8n0@6iidVQl6nH;y?Fg(VFbW?)gjOC z#oa_m+uiQVp%C=iJL%99hbQL+!S$AZ;yCkcGA?_d*WMDc8q1!@(qI1{i|AO0k)L?t zc?seb+VLJPfbvQ?u+RVF1Y4rctKk?Q?=@{y>5%jZU&5XKZ~srvZT~;H#XH0@{Vxx) znzw4vB60<}=(&&@ng`uuw!Z=IK^hHY1i%NR%jB!ub^;ID7B-?WWln%zKn~6`;E3Jt zE0dM*fRv59+TH|s&~$gx7v=yWbnsF0@&tBt4{A|3DKym0gpWt!J{oWTDfbn9iPb5* zcXCnC0=nz}s}LPB82Rbvn@Ac>)879Rn$HXLJ7HIlxB*i_PBG*6|F|qFbtpuL>X4S$ zSR4i3tUPjoWV{Ph##PYp?y#@h2jeZ7agwyf{_T!qfHT0`@l3snju`dc0w{A$8;gkjunkd)ouB<|@Aa8K(JH2252mS{V_e^J`r{yw{1` zH%p2Vp*y_KBRZC1r!tVb+OvSB9nww?#CAJ`(Ivx1Iz{|VN zkQ$^Y3cQ&+I48(>o2@NVM#KBT>+c#c-VU$gNMCP7#3i+D26*3^$2!EamH_R`Gh3bj z&i}il-ppD6@Rn{AKIsMUZk2v?Z52llSu!~aC$V%CbM+zdm< zyES$}oms3D-Qk^q=%~TS@7UO^|LiB)@outXvbubm3ioCXOun#=gW(6HxcmU>baWhu zMQ(51Pk}ennUo7;yuV#IpoE6^=)CriaQ{DT=SZ6W-@MT&XaexghPni8RuiDGC6kxV zfsYf1Z8YNH25Icv-Yek%Z#C)MHlJriC~C)|P^F#d#YyBVD^-Qvlwa56+z)c}j#{3ie-4_C&`!*Nb=Iw?#tuRwQmSGqa2X z0UdARxX9%r+4R@{Uqp2HVdOXPtLMuyoDepq|1?d1e%N>4Wh!+1Ddz9n72vwNJ%ne) z|MuG%?jK#MT&U9VN-xOf#?{P!@Bd?jzhTh-vr%{u_nKQQ|9DUeuQr+ovGEI5!ydF# zwVdQZMujK0gn&Cp11+})TPhKtF1-&$MDT)CzwP2&A>cv$H>*@+fd{2u)9DFbMueg# zIBuslpjVK;&nK`J3QZbCB60FV;r98r&?`u2KGZICn2qi#$PPq@1V(-%Z=K#|+tR+o zZcM)TU^X7RL5h~^FA86p#_$aiPVfU&I&^A$kG33zm)O{O6nJy~zQjkyyUn~?3k~lv z=c-RI-jU~BNEPI6+`-8-fcH7CJ)LRl1gLo3x@U*M6}ugYtQ%mw59OWgQ-bmKXd0Hs z5uvB|ogzOUL&sZa+4^yOU?t z^B4brm)Lp2uyi<9Sx2xX)c)ObT|GcyWyxtmZdv$9+I^H_-T@-(bv(O#hZx9{482N3- zy-8ddNju)+{$Hxiw5b@7e)@hWK{t)z@s8e1osP2_76TTf{y&zP0&g~l{F7w7Pq?g6 zN5gx>n<)s!J6I`?G@OVT!RLyB{{IADx;iV^-nzWMXS@nrP8?cqvk1mJz;jiGA;7yi zM#)pgoe2FpwH<;c(D6RId1p$G@s!ad5~nm4wa32;9d9dR!CL=9cDlnm9MPeHk>92F zvS&uhX~$cnbL)Z7Ane-vZEcwokJ=c+<2}GlosM&kt&cMg|2zL@g!Uf?8YFHC4_crm zv6bvW8;-IqNAsX_9MdB38Kf8E1EeQ*cQG%|Ee1>MRM`hx86g6+YlN5U2^f&BQM23v ze}lwRRAdX^|JTSxoHV{hgaoIp4=u%`??IYHCU7R+;m0pP;#$gy{#vT&dyv7M3x3Tf z$kLq$twMC{#mH~CMSaPo4%$6vqx_QM9Ya*y|2J=wH7kb@rQ$gU0q0JG8f=&^ZrqzuP6ah4-97&21~5T zLeC%Y7o^sNWw-eN-nZ6=vfeTZhZgLXn^@b9j<@X-LH}`x3(tqdxvaYNYUUw2-c?JM zq&&(JqdUA!5FIx#^2;*JdNY_#JKi-f_m$LM#=am8ci3Z%u1YrJ<9$7XDjg3#TyU(; zBW-VSQsB*3ZP-9|Z^;c8bkXqUFOTbh@!ofqiFAV0Cy{vNJiz-SkI|HcBN=wF_dmL$hLAtu%IM~Xg5p#mXT;FMS(MO!&E68MX*7elr z7~&D-%_rUeAIm|3H}Ad7ATr*sxcBLx;a%?6VG8fw?mkpc`n)Cj$VkKyfcO27C(GY~ z%ZXioy*up)wznQzd&t0e=SD3P69;%ZI!xM&iiATIpVqUK-bBZn>qnf^THP6=awM)X z61O7kJUZU<9Ud8*#PZM`-k-kz(J{R3@A(y!)kYpULA!g~?%ds|QH=d@BF?@h&_Yjy z;qk^`a*Z=??#82TtA_8xg z!5+j1zCrTtbi|=~(42F`Og&g)PxVET`u|O_(|-M6iPbq96Bj%moFLtGaJ|@YJcRdB zkcQtNSzuhlb_2XYqIrGChEdsYNPj}<*vm3>56W@e@a*elF}xlUx4-%-^x!JG2fgFy zjTvHBr8^JGM0C8w$gkB;>7lR^?H<&1E?&ei8M}hqoOn;t(uwiU|Ce!5r^Dw>mW}u+ z`1}9Z`4o5y4JO)>msp|sPgkJf{nq#H7>u{#Ju?#C2WL4BbpgB=)yuYmeJ03)psdgc z@a79%*a5#FB`KnQxdz~UC1agscrSX9|KJtC+v~lo_bGk?bjURG z#Zerw@oWEl#_8XSbiUzNw78y*2e+r!>-!h2a~dlSb6( zaCxv?N5Plm-nCrG@e-2@M3=)^# zKk3K01|4seR?gc&G4%KSKOWH`gOT5=$1?8)ZD@CI`3iv|%Mt7WDXwW!!@QcA;qi{P zpiW2PW8&TqAtd+ap}<>UQ}Q7)-f7pg_0aGZVe6`e@xEezh=ljqJf8jc0N&r_$NBIA z1ZY@cT|^%Edh6mc&D-$o?Zb?Y8Y|e|s&OyB`S~>wlC9b8A>@aS_l!fF5=2Tn|2S9GWcR} z;~^C%NFz3H&0I6h@OO~n1nsEPk*%u2^Jo4qNP)M+bE`5k-Y>RF&qKp|{vFSyFy70C zoJe?k9}nfa5AbFcv3i#N&=Q&~+NK=`2Bhz<$(&RKc>l_|L6iU$8$o659 zL4yJM5_@+v_)fqcF}w{D=M(ZxZ2w=Lx3C{!%Px6Fe|X$26kJJxIB=v~l`;oXiVOl@@dC@D#<})j<;!Nmo_qGbr@dzV7xosnU+t(vxkF53G>M%F88+mOK%Qzypvpf$E1$XAKng#jsqC^d8B!BdtIg- z?>^qs#q&m~IGo6R^rb>PEBl*Sg)kvJrp~O40z36y{ZCJml(~th}9zb;XV&oV6yon>rop!vN zPI0}wTY|lNi(|XO0_J|{bv$Su zq+)+c4)&nJEIv{Nx&7sq9{BrzVvW*Ke;fgt-?}S)*ROaey`txu7Vw~D89nt;p#L9g zKjxQTN`ykBIGD;ep?eS$``3+TEy8$m+?oEus>=rG9waKfF38nHiS8yyGi-l!2w>#* zIiA_DuAX)es*D#}`_Kh@{$IdauWFy<%kUoL#rA|M9XZMg{nN3e36dBE-f~TM;>mdP z@`-Vy;eG$yT{Rf*A(N#fyu-&XsYe66J?EmY)_k#q^rM2O9{!An=2lpxXack|+hMPlhV!{c4GV~8ppd9zLn4~CN5TZ95{8J{CZ z$avd3lyIQo-PRHd!S3D3a){*KYZZtGP652{-~CzcTww_<2tAUaJQWY!IGAg!4)B(_ zS|eNz@OHdu%qb0CZ>ihqTT$_s*IU*c^|8BJB!aI+;$nACebfER>n&N=(i*qQ)8FwH zJfh1$*`~Md!#-7?6hP}NNT^(25YWDv?|9>l%Djlt#4j&yLz1|WlOo6ww zo{|I^?-g|i*wOIbrRlQ)#@kN(9trQT3D@0u0B`;CvDcL|EuoX%Or;Xw?yb76Q}fjT z-p|KmyPE;t@2Yi!*gT2QTw&%3ohfwpW>Md;Db-RGKa0fqN3qwg>_K<$H_S)d58tCd zyl2(^=xD{rkM-&6(^nVM?%p{p&bd5$urDWCp_8qzD>TaRvp2yFSEWh-Ad;2sDI^FR> zbHWMTgBoS3F2}y+#FOLJOv#DfF-G^G^d?#6RV(T51L-D2$3cwzT3;t|K5C-9L3%dy za>~yTdxpyLh_3C24!Hf=Z#!kg3K!;6^Q2ykoFAvG%{ zY`kaKBM+Sp<~K#-76^@35tT$`4NZAF%;;4P={QPXZ^8J=TVIZ@oqY{~c+aK@Jr0NPF4~!^!6rpeq+dmRcvH!5`RK&`#1#6g z_r`6qj#KQ4D$At6b0T&i}lF&|H1Fxo)94N zVc~t~qw-D|?}Scu^5sO~Gx36U5Z({R-)v=(CxBm~BadDFoe0|gFj8L#;mvX2(}oZT z@9Sx7tuJOGz>%uyHr;e=ycgfLv%a-V)D(@g67s0G3dY7;qHmGG=1RtUy+sf4F^@`q zf*k7A5qIgY-T;?Jgx(1n=KpzK8V5J}Fg@NlOHZ17l;THx?wz)^Dr)F5R^ z>Nu)FHE1YK{`7mO21WKg$_Ro6q~?y9)@SEo4@i%6$9=Nd1DLKx;&_yK4krJ^u0by+ zil2XEVZ0lp3J@PpsN~0OU)^DTo&Fkhs_<&;%{w&Ipak>tNxiXE|B(S^`j;nY^RZs) zv`hMV@(NOs0&nemetS{8^J0FBV&R?nX_vQxP|5GCmzT`%Ao^F3T-yXUo}=M<3kl-AB=*CzOpo{QV%mIc zD!tsgD22R&RG`3HD`n&?Q&RUR2{*A=@gj3B&MIencSOdx=Y z=X$pra3_I_Jx?0L6C^L!=f2et-h3fW&$BEez?qezK{hXaFc%-a@4e#E{un3Uv{~HnKov#DoJ+|`d zlckXaaE14mpyv?Ymy^eg;rYMA!nnPcAiOo41YXqZMu2?Z%`8}Iu<=&CkYv`V%wmeh z^)6g8QCo@wVgV!R0s7@N#0twf6F*qfC!C zuKOx&KAdtA)c@?>%2D90A^Z8C(_0zByM?jv&Uyiuz<9rz$tL5y@@m^PIS6ml+UJ7L z0|;Q&)_{T-o+NNw^vP=Y^wzt^zTTq{-Vf8V+fP4;09B^e>IXYuFHVFeeqZkQV>3nL zE;~OL?plJqIQb-K`qXtugyD8?g%Ka`sO0D1v7DPTlYYE^R=svJ<);35i+WUy*beQ9~Z zGx!nfJ01pavA1p*8i90Z3-jA#Fhp3+*#WgtG-8Mg&`5&=$wE3{#qpY~6l)QpeqriJniBv0!x694% z(pY$(c*pk{{=^PGHZBy#J9K!odk=*7IioWZx=#t<841Mc2}c)vWC&{=0$uc zP|0t@-RVb@2k7tr8ywCAP3u$N-s-Ll%af7BGyNmB{4{MoIGbJOrzDd5e^m;+^`m4~ zqIlPwdLo5|_b^NAY8Y>=o;LCa(xQCl`R#)6zO9_vA90%i^2e6sJ%sS~^{v z#K$!%`2}Q^`ER~WfAuz9Zu_fvhWhEPnD;O4AK1*w^myam(&pp53h+hq9JzX{P~fe% z22Z}d6&{clNgk2J!n^jX(LuOD3SBcsKAfoACFs5t!rQB4U6RU00(j18W-5p?33`hw z^gTSBFfI)-dI{k@Fuy3yG>-_5v}O6?G_mnc=-gGeppeCM9EsaBmTw;doEX*H>yy_dnik5@!{RunI7*6F4}x#>1(9Tc$4u~ zrodZQwrm$#y$kz1C9v?mY%uRBynD;?gudCEwb5dMhtRjT)_R_d`E7!Yx8%XHq0t>I zrZz|%`^(y%Z>rdM_viR+`aHyV+gs9zk9Sn^v%5P}BY1BO5KDN9@b|S355~CV+x_hx6>9{(t;wYASp{I?&^BKYaeb`>0E1 z@I&Yg(y+|iid(R2PFPgZNOR zk{|mMVf`94`fE^y$~qw-9_kY$T#L@pe#sxF|PKhT-sTKzz7R z$xqGn%Yn*|^sgW%6o+~fxau(n$N&80WA}He#IZ5`3KF-2HXqp@x39&dkXMje6nGmE zEy?%)!wu5S6?f#Z@UA}E(gfo@o~|5DuHMCaEnFbHT{VB<7q$?thiC9O1#(H8WgnO~^p2|A5BNAI?Sl#x zc>Zs{WP`><2yc;UjdSyM5y52e$C0yh*aOlhCBOHxb+M7skT^oV^3oT5*aK45I)$~e zF7p`otha4deL;Wqw$V7fdG93k#Yu~G+R<%-o=lIo-$B}ZXqnl@xaE?o zw+02?hJ3T+ueZY0`v}!Rvt9N2hn)<4Q*_xwB9B1;1g5Vi! zykjJ6MHOEOK-0EFGL;o+bM(*qVN#^hW3D&gvNG`U4 zUrzkn|NpZ*W!zst{r@708f5nEB_H~T?G%vGz^XyAYmTzP6Qto&^?`5=@)@??WeU}x zx(@=s?p!B;PIaMbyV#OIu?yx3@GExK$HRN0p&HZ?u4EIL4PB5{-aFT(f?b0yzw0vp zrq522LgKDGy}6SlfW3kgP@CU(=rZFyV#`n;RPx&u!1+~@i~bt4*HbXl`WOv0=ym9L zb{QA*_y5=YY4hP9wNT|x|F2JhH<(j?0L6QHuv-laZ(Wm@8)3XBLZpLXyn9cMq`-LJ zuF=eOuOfgJJIx%AKzNt6eN}?-c4(S^2*!J(APfGCbR;~ne5+bUBW{e zN8(1Ch)p+&uf@h5-EL@ z`SG5VrpX5ZmmVN@ioAlNO;`}>c?B`O}nipRE3zn zL9&_qK$8!4?nmuT>E!-jmjZ7Sy_-rX-nMQrDp+`D?MoGb`+v(&#XT_IM>$*iVZ7`2 znO>K^O8`HtS$>xbYLJ$y=&QqcS9AG&B42MI`s(b!XCgQ*c5OB}9vknvfv>|cmxM^) zkvPr*<*yI?vGHE&SRi4vLZ0F9evJ44spR)TX5@uaIsMhUc?)l&Bp(e2q_>aUe#{}r z^mya)hG_D^Z7d+3UPi9o3n}n6=Gu{s;(aidpp1q0;VZXeV7$wVK9bMgUMrZ@0U^B0 z6CxWz9}vLnG6Lle5Z<3(L}y4f3Iu<`b&(UDEyW<0!CAwGPlH_a+UxJpUqT_+jIP!dpo` zXfurWB3Tad2~x|&+Rh6hyxmycBJZ6ifa@QxaJGT2w^ZXyIS=DKmvA~7p8xA`__}YE zB7(D@C*IeV{tMpno5~|^zo_|*#N8WyJCvS{jkn@>#@-M1T@3enixuKyAC>$(hjve_ z-AVr=_Tk{w)dufr=>IQhy$xYM&h&WWbXL&hk8BBlRdEUjs*4_aI^koIJ`>{9~Y?PH;?08 zlbbUA{r~oyy3YrssrUcqQ%Wwg_lYungB16?h9(~?%4*Gz|Eb;v6nL*x-z16R{mmyr z3k&awU#f{P-sjtHlkwj4?#qkC5Z-4-Yu=qHC4l`OBy+bwx3>f|G>|VR&bzFkp90~{ zpUit8@L2>nkvi5ivIQIO=UG|Zd&;M3rjR%@qm|E_OtJAM^|G`DDR3}c|KEi8cts_@ zWty^_77p}R@0{wEd)4o$H%Pdu0GV+PS*FJumzznG58s+cc>-6-{r_SLyv@0XVo|*J z_pR5&!h4y!)Cm~x9C!HuczbKw`$;Q&drPlUd3^O10*DhRUmXR#y~P!wQ3ap9bstKz zPJr-!n6#Y5{AmQZ+cEk1txec?FL8MGfMq$J6oABCP~{dlY>bU}Lh{VX)K)=;!`le) zaga)W@dy0^-el2_x7pJ-nXe|OA8&bmo?9&baun0!?R!d>CLdp>FSe}7_}l+eblHsi zOQ`=hp{PMN_eK7>AdNqX)ex%&8FpDMhW8-%n4ThUv0E&9cB2rgK@T5S7_9wF00+{I z7Gy&!$g%C=@8A{WCXeQZET{&ZoxUDjstR3@cBFvU_7-*xx>qGE@Z|BEnte#zhrK2O zYffUMlL*k>c)}Q&mF$Lb%(bEa&BQ~t6aWNL&isJlF;Q{HdOM~PAsd=s5`7{Xcc^_x} z&vg*MdEc6rDL_~3B2}@jprmEZ}FJ_>Sic} zce$T{@zX{E=;`SH?kR+KbncO3Fy7%#$?Fb7c)#vHbYo{65$s={RJ=kI8}DNwZ*9)J z8!#C};^xjhNl*HPUA=ownkv|=`oVB`A3=QFrjlRAqu*vX|BL(odx-aqWYwtSokNiO zb!=f5)8pL}tU{BI?dd)7Pm;)ZFQdSF&BFE@DBe6d!TMNuUx{&Sg&U*^{~27%@tQ>LA$qkzb-_;cnkUAByu6VFU4Di^u!Rs_PyFWZ;D{!Egtiz z%}{N`F*84hnz#K%c0`RyTH?78!s{_1_8cja=+AsP-R zj*X1yuk2=eym1<1wD}P9QP=phI9W=8x8>&Mk3mnLiu;!w^#g21ykn07im>zFj&34*+ zq`eNw{Ih~IqrjWsp=poeeKzCDQY^f;dl=-vc)MIvCgaULW1;^H!rOeqOV@U8J8)-A zPlpeLcgcmGT6luATcRl>7Q%bmn)S-8>XG2+7f|H&J#4&_e!oqLtiqAdxGkyfYzr=9 zS8t`glP69%Fx~_y1@WOxB|qJ?0iBjI`tiu`P@1pL7WV|ib$f=Vcyg!3_yBz>K z&@}Tx{Y?n(%;sy`V7xC#`#pm%C(1MTd^y1%2^#GDbV=c$&dH5_ABQQ`j5AmI+-38NTZJTiJ}! zr)cs4D*4Kv`SW^+xPX!d4yplBN2-rE1BQz8?>o8zu)iu6VzSgTPq)-{Mdd%K@ES=`j~rRF{o zXP&)a40wUPI7wNd6ZCE2oC!r&!4SWEg!s5ZB|nZ1mf}UH=&#<_IRc2`NVOn=(mSfM~{+}WK5>QJ5dc;~%)SykLY{(4~-2XRm+OuQTAem)r z%HTUlp0u2agwG(Yu_MV@S1vNEC{WIi{z(8!8?w84p?8qx9Z<8>gKE%Q!{@wfpc(}1 zV3GZ_lL+4C>i7CFgI$AGg>Th-=?T4qgv6-_kB!-MW7nXHa9{t~4Dc_x~0YcyA;cjlqvt z81EN3s%%(zYk1cOzMQqT&LD0tk;3_4;5%9vH^LU@me zKDM=o@D50kP~W(M2!6>A+8@=5jkl6{VB3NX0;I1<-1?e(PQACV@iwzaYh}r2y!-#O z5g%4m@)K%m{C(;f{dnJ7@=YZspN0w2_)*2gXbYyt8+YLXZ9e)7XW%P#pz6Jv0&k~v zzsT2Hz<6&C16Z-}PPwO|1>?PHQzrQaDJ_E~OO+wKXHq}9G;!I1OWsuGl|XoB2%1a4 zcrTGR8rlls{XR);v0obz^d1%dkT`$i*6W>O zy!-#IBR&MF#{K&`xq7dn zzVvCLUgN=(q zbE3rcUH_k6>iS-{r~58nl$-Hn9Z2I z6HR_OaU})b4n2}lDBd{|X?QHWw@vnB!FcDqD~8_Kc+2m;7iS{OK|*xOOddy$F*=h5kBe%in z&e6a9Keg7IA^v}81!+T3gItPQ2GJU{uXimkRt+M3X?+f_AeY5S?}Hnp&kD6oyP-$y zXO~+hbu4zE=7uN%B0dSk>lgRKkJ#-W*y`P(8sv0~ze;q72zs)rKU@}rU4ycfy_D0! z#YkRA+$8tHgmb&FYfy{u(@R4`DhyYH@(>@dspRJ(TW%E@On(i!VdZi57BBTHc5pm< z+xq}>rmsOUFQRDjp<)@kEbh-2q^v3M-sU@b7sdP188IF#yxn=?T4B7mI2w}iUVnph z%NxSGe^$h79^MX&nVb6%1|)&|uk3Y!8>9sV?hbH+WGoB}_K}F-q8s~a@s8MdtIxZg z{Zv$pv>1sS>u+h^VSIKqDV6-xMY%d_FVT;8fl1f6vpMxg?AHTQ z4{dYHm>zGlC8{*}D7RE{aym$Ekk(S*?QHbW0mb{;)4iY!INN(_hh1H?xJmHZY*3GZ9+UkpeakEHB}2ND@sx!iUzmt*IbaZz~GCH#fvppm@*tL~>x^UDvr`0LDAV_AnW5 zhqdj6n;^Wkgj4eFeTVMR4nXXg{{6jxZk^ zZ}ag-m!l+wNp?t_*O*jW0LwPazYfN-ULywQ6&Mb0OT-6ACBJO1<`U7J^lxto$7DGW zgq~skT+sf`H*CUiQO`=Iuimp+97|~NA=Q1j{X|^O-~0bj02uk7Q2%d7QG+}RhX2`O zf81;~532@Qj+lr&hicF+D=-S~|HZhpLkFNeNTs)GkBZ+D!1go_+hFJh>3FG#G58G9 znLS4h;0w~0#)!%6=Ocnni8cI|C$I;k`>(gJjXoew+JwYCNV*=N6puY1tt__<-cSJ!fr@h*7r==BtYcSi+ZL18xmd}Q6X{~ol0 z+;X1B8$LmL(zTX14Z{1pL}1X|iwMwWRYTu~9oTqp-TJUDLsOiz9*GNo_K;Mw3L9@? zf%Dq3ql}05cEm?CmHgs_ZqD=gKtJA_B>YZVc2dWCQxv-^k4hBN<1Mbb%!3vm7P1*u zS5n9mBwGr+-4;vfqIgdwz8Ap4TW}reC%l4uee?x+1=*jF)Xfd8AaUmgb)yCept`l? z`*EoMPaa>>4dd;VD|jIu!n^5Yo=e!V2=L`I%##iJB6*Bz_5+`kPl@=fG z-{Lh_|M|SddJ4Q|9P@KeiU8-DeIE=7W8-}&XlYPTv>53(68An%U?TGS z7R*L~M=$pC#SzBaz0E^>2vEuIglp}$_2%^Bt+!n~{e?gE?X6y};`*|5ai;J8Sx4o9Qu$GiJhiSeRl8t&e5l1Tf&r^NJl<5tPg z=0h&qUme=L{rmktnmU^QZ4lJ|J5ki2UFUj5&>A#!beT9-4T_AvEZ7LuAc+lNEZqO+ z6+BE0gKCh+&yXzf#{`h8VE^+-sQ>T%)zl1sgLLwXbrt*#Qk6^Gy$Y#B@bV4MMI#Ha zCrE50;&@oa0@76^E<*FIZ#x_I7W)akXKR&zYcX8^&xQCXrjnn?)kQ{J4fNNbT?=%) z1No>wVsT-WX)){GF8SZW_W#50ek(eiCLgauGY$VtkTy`@?PJ?%h2ouJ$0CM>_ezc% z?Qs9^RkT>ozHfd5R6320@kS(SZ8}DOLvd6DEYcd?(w-6siRPs9&eYkbr ze){qDbTa!iz+R8Jvi=9C8{;9;qFzkj|KqI2LTT}l{k6Ta|0a0_=}3XMw^HnP6z_5S zH}kRZmLBvy3F94P>AxSw+vlfqIlO{&x%`7qwwVC#C>^Zd3*lWp^zJQ;_jCbI`WXms z|MLpv5qyzgTItn0L1(b5_cEfL#(Zx{QaTbhIo$E_WEM8wO%?{LOP{DS9Ns2~kC#;P z8{p#{(lDieg7jY8vr&tM`UFXB+n(V*jrUBCchN1aFSPi`zTQA6NFZ--IZ)ue6VSbi z;{7bISOg1i-WMq@Fy8M6+@oQ^N+-2g2KXg@-#loOt%3 zDESzKH~;5VOI4h8x3+Y+(y?i1Uky@;g7aCna( zJ_f1emvYNpeWxG&)jQx*CI8_f>gWG)F2M~ypR_SO-Z<9cMp}GS{{YQ8&XB9OJq6yL zmAjHryd8MGg|YDVaWx~)-ges4H+w4(yt-tDGZIX8%vFAU5*zPJI#K491`?zcB#y&U zTlPyTHr{U@?l+JxWIVhtBR<|y$q#h7(Xm>W{_1VGtYD+b4(f}O*LNOkYrf`Vdc1S8 zT6AdfA+p-8@LSa1`TswQQ%3#;)cH{fXOtT`Fn#EA|A*JTLFZ277IWd&Dk5d{|M*&$^+m?;|(;HOP4< zkCWH|>NUt~{f;%~wY-_W21P9NqRB_c*VFikd`8GJEgp@N_JvzvD-f~ntJ!1@$kkQ|M9VrN`C9Ee-$6r zqkjb{YIBmaIDq>0*89@4|iwX9?NC@v6t3Xp2?~AMWH7B9_{}O%!t@E!FYRon@o{uiU2qF z>Rat{!5)x`TF%r&P0Ns6khp-88I@%#uoovwcAEt3Hf21#r4b({RPx(!^z5XTH2rvg z%TRjri-U%j6A!)%8Cy5P^wk@;Vwxr&pIzRZ_9!6t{~Iar-hH>?HHtS!sFws5-ZqVw zlwiE8Y_rICTkP@|jEC?xbD#Vg2H|~dl}j53^!|TD^DQG7Z{H7m)iB;4Uj0l;dmI6_ zY#ZBm&Iudu%k`<{(_S*9H%Qzs^K&=uEXBq<5^vqL{R-nPPAU)|F;w#7ywvOX)QNt) z*Uv6@V>hFIdaFWT)<)fB?NUZ=18K?4Wq}V(KF+S|d%ZmM@B9C>{7nDnF;M^SN>PKt z{LQk^8dSbcS_!KL0Zt~d@Cs5i>nnMS-SOOUi=|KvN{9s~TdN3Q_Kh6kdqL=mU7LNG z@EN4z3rvFppc-^C=DS<%01@0TY4YLzaR`6& zPyfH20`EOb6t|#wKUzPmfQ5I{hnHC}-h8EMBwLM1=-V-vUEZlnJZyKM`J=fE`eM=WmDiP*6C^-Pa9E>bX#79WZ# z>iNpKT`N)^aG`tS9csW8rPpc%3}|cjxye;~krG_nIw)chSr7Wo9)5(Acqg zCp(0i^)-4|Jx)|*U^cknwKIa+*- zKOa2P6Gg^*8wK9M0~yUI-iIFM%3kKLud z_QsVdZVJxtVg9qXr&Ve4A!yA0q_6gG|NlSl?P*B>>i<0{YS2EPu}f$Ta!?f2z^XwW zT9ujbBNkLwB|l;xpJ9n#2R&kqt*`5Hmk>ZTp#70Lw8dW6%C!%^L8`N`I?)k&#NOU} zE7T-0666qy4N{cFzJui5gyg-Rx1uB-B+ew@*L(#&>^n%R#x{9$tY^G;kU9|`_o(C- zBpT$vbB6vJw6yV=K?yhY`9IFd_*Bv;p^6qH7&=CCIZZxnDrXA!<&am99u#;->X_G} zcz-PKRKvo1@!MAiV7!MG3Xt)3-PxOs=0R#^DFMtm4@@OO1JV$|_0}-nmx-q? zI6-(1Jx_PUZH@%pCeQf39>spdZns`;yK@b6y(JPSdBiWIwgdYS8$bVc!|iIu!`lP# zkxC`MN7g0Dmag<~Z*5nWv|l9t4D%cXifY2ssP?+ukC`6t>d8o&e7H}w`}Q0pA8&D| zz?;Y)`_KIUNy`;gEWCetM8v^(H)($-@7~VxvM+(Rx3Ybd68BvpfUm+x98%En7B0sN zqA=b%T^GAHL3l@{e67y%B!XT&8>SO~U{8>yLVd*UJQpMFM&fqGMqUW`h&@5FXWcja z&4lsZ|DQ#CY^IW*+7{d%`2+M<@7Z}t@>Y}7kGHV-S9ZuBtz>$d#gbC?CLUiB6$3r(2{~lY`h~X1WmSwh?7nsaRCdv^!9zg z#`|vKP2bXwjE8qL;-ijAez{Vs7Yp2{AMeJqB7SbPe7z+-JWc%2DW=C8*Y87{k3Oa2 znt%HL9Ta%)Jy-nC{Qv$r2W2e0cU-Rzf$<)bzeUDd>{hh39)$Onspy45Hwj=<-@~2y zLP=nEJogD0Z(9}XliMJ?N4Kr3xvvrlUUJD-*h#`(oET-@a6aKCLArv(J$BrkI==CT2LF$(i;k^9IG!{H${{DX}i6$R6 z*he#U%KrBM=;D;2{|P-}cTv=!xMQ~e+(B};L{Jy22Dz=+*bLu6QWq{mzJuh<(zX=1 z|BvyxTy^$30jwD5GrTsJ2V|5^mqpev>#j*3tXDk#!)3fV^lKQF#_dQbqn2Cc{t z8$6DiM?&M4OU5OePhme|E893$G#!>_xB;mp;-i{MeoqZwju#}-UxQd1hU*{GaK(5o|MdSp6nMvKcK)-y1zkz6gN64=32yQQY5e&OWV~%8 zl4RFIc=JA~;`{-vAmbFq6T5#Wf_GC)m%(_K)`djtKzMik79PL11$w>Z=WvzJ7wi>e z=JS5pOCiD}{Oq4N;mX2aW3AYD>-f9G$^BxyD|T}bABI%&6D7?yS>B}|Z{a(Y6MeKC zkp8IOD2v~~^mya!Y4j0s)fT>D2dduQ6nMw54Btl^q=4p&+E{p7synH}D@fBlDdg)d zrDINgfbqV+?ab!)Q2)QCxftgQecr-(mbhCV!h2!mX8vUm-n!c+jvwnLg4KD+8#BYP zt9P5Hl$y;C5z<{G?!Zfx+Hg1Q6{Mncx_Utb<6V&6f%wp*lAlZ1`nlmf^y3{Izo;vn zn}!3@13{BNayytG@45h*e6-bWEx+}r|KCZ0cXZvtlPKP&?IX0X@WyE@cP2MTs+-9T zQm4K28~Aujn3-Xq0knI&)BOCjH}w9$oX)~S@CE75Ki%Q7fbh1xR;KZ)g9v`G{x)0@ zij8*$hf&)KDN#}v5~uO~$cE;xZbRF#QE-jWPgDK2D#>cm4PWZ!ZeGqfVE1@3}7h@zxIByO?QoH;%O8*gKiulN@=L##=`u1-Ki<4n z(`iIn?%vYsQOVy>dy}F2Kw6S})J>ZYNx={$XmRrQ{y$oNsQ=>_XayNSQG*UxA9Y7- zQ0k941FRZkHYq3v_y3u^1o9W8!xf9JorG!-QPj^RxrYEse>&gNJCg{Wmy;idYtX)@ z+_4*>8kALDs`Q#A5Eup*S3O0;86+KxAKz#7nSTZO)`%t_{sRvW85WW!Nd6Rf zC#xQ2L-F1t_;N88-lQA7CNSR0@lVNk`-q3^&W7-AJX`H7`wp5QDRYU=`8z(h&-MV)rx>=d$6P*g+?3y!9HM?yhIR zPwe(1K2}i4Z_dP-J6)6h`G1qtt_@#2>Z#8E_X(w`vH?|0k2kwQEKNSn4X_EFOC`_$ z{V4EG{ABEf;@wbmY!MdT{$buOFy1<|>xl3LX^Njq(_$gKCzUTR-td9|ayoj{SwMK- zzjp5t-2aPI>!~h<@a}ne>hf0T^%kWz4F%v|UT;afch({63O7jwiF;hWpfg1a8}EI` z-^_yWan6z@IuW_nn7^O5iuVZ8Yiq9ftz4XzjyglBJMEX6Z3(EQ)w z=m~`;2ycGYL$?=0c!xGVPZ5Xkj?Ai=Iay8w@3Jdg-mn@Q@5e5RzVlK9Nwr8^Wx~w! zv443vasE(5FFkg@CV)S0*7Y<($6HS8883w&u_I^d7Ro|+ z8xs5~!$?H% zCBttl#lrjP=xb<4>9X1Lhk0bYCm)jx+#$TzhrFv7gTCHs`r*gt@!3Q$^VqX)xc}El zpByuQ@ILuU&hT_P5j@q_7O_hX8}Dtue-)m*Jy}zX#0`#I*pK7H#(R3y*7<@iJHz1} zjQ9{A`}h2gq@1;x8=@cYwF-Tf`?IK@|Hlo7xZO2O-6MO=;q5J>jDaQ3ps%-{HaR*r3N=U*&(dPy z-CK`&x$)~Dyl;uzFHtjz1T6=vpD%uejdytA$&E(FGc{|FIPamZkD9gEcuy5=*gwCJ zi{bE2M|_B#`uF_QZLVGG{4YL`COGc@^c{}+?k({F#e4PjMN6>oW~$(o>DBtwRLRsvncsBskR9tSR1)jraEPhgL7tailLu+}0%}I*~2dc)w+9 zeta`afZ_1=Mtn?D$*=e#`}Hz&`nR|C+)+?G&GwAya3Z)N{Pj$kcoieBt7*y2p3jjc zAIr5jsk}@4d;dQzKhytt477rbpr}DPfo~R~{r_<7Zg#91^zz1Hn`clBQhzzL2d+Vx z64EsuPz|b6-L){ioB+mTtu8Z}NCX9lEG%&UudB2$L;|Woarf|zwOb=W*QA%cp%d6O zXm3-O$tA9y8ZRV{UBycg--TU+_yo@;>*tP{{Lg=$|DOcTAU=$#ZV+slrf zg7MzKX1N!}yK#i)qZ5R;?n>#QT9Yo`)H#pU=TFy06&E!V z37&cO_9ojA?CUMO4vij{ogJyUfW-B3oLv*2jD5XD%5eqGz8oCGJ!1DEK2B4~Z>R@n z=XrsCyj|?9_{>9TINl;2U}Acrh57N8_NU3mk9qgppHz~Mx9p|B`%trn5L&&@zZzh{ z!g~1$hK$ytE3!TY)2f1J8W|XcBa~*=wCsGb=g=J3Q=#6l+IaCnp&AM{SDGf_pPDHhn?@*==E{r0cjWo-Un~TTA+Bp z)vE%q@b0T!>jgJRqq}{`!--!lggcrL-X&eUZBEY#V58dCcpd2NtG8%*1kvUrS?5T;%ir_=|NQwg@-LwNKboQj6|A_;ht{Cm6SllqHAv>Ivvxi7h?TC} z5Ck_!OMC6&lb}be=`|L$?O_Cv*YHg>FpvlisQ##g2c$XaO@JD-f-IJkm<;eBg2t&6 zTjZy(Yf!Pj{P^z7ITKSPPSjfO;NE|^V&{et$KdRHUJ|4Is51~Br>NvNOJp^$FQfkv zJ9}0q(De`v{eQ5((47Ncn7;9-}DCY0~KU>k{!z0JF)+U;~g4{=e_mRG`w>P z?JgK^_jUHcaP^MWc5#OXq%))UylqklU?8}xUU)bW^tx{40OS3Eeg8*I2=8wiJ?xDy zh~V^`$BfcWY`nkdZFsrn?x4vW5+~{DaKn&*jrYFrlUIwBr)wCkdf!8Q*ip&v(?V|* ze_8tb|2tONuUWOIZ*MJ{v+U8^J;C&NH;HJ|a{nJmfp^~317A_RS3Dqb zV&NS#t&|DlePUS;8Smrbu0>H0-r=ccacgo3VB3$$AFN*z!KVw(O2K%~$eozbhVZ`f z{GinC8X_p)^J{puJvQD!v3`kGqs=BNNZf9bqAl;1VdFg=$F_D$W+%hpEsFR!MJ2x| z&**V=8~Ura!06d;K3y~%kWOioVZS!c^myZDOKI}4*jF-2?-03q6Djb{4K;?;pR>2) z{RcR(@NO#)oP+UhX}K5*SMR%|k@Eo%-m7|!oIG_Ay57Rkb?b@IM6h#DZU7nY`HyCl zAiO_{|I{3ai3FALW#&rVDH|(eKocH!H!o9H+y3b z{Np3*^}pvQ)ABS%x|V*tw@hRVS#wgyTRL=6k_OI<>G8Iir$dvElbeisRtWt)|IcWv zng5ti;?@KfiW*e3BHIkDLCRlO%)_cdg~j!T@B~SxDVse1SGl17I3B7&tVibvhhqs~ z`Le^7``;&mfh+kRs6&s~^n3OX`rsAh^--6fS0lgxnQ3r`8Fv34FSGji8K2)KXdJJ{ z@`EcCu=gNM!{@B8Xj94WCfk*dVgJSb|EAIdnnUZT_y69@2G~wKV*d00 zHi!CX^0C_}K%6rLe#9mK6nLMMlAlBIR&|{(goXFT3lo#@BUY#(gZzlS$>9vgnc2=am zg2efT&0DPXh57N;r_G1Q>ha|d_mitPjsoxFM?CY;>dl{6%8!LNJ~z)3##_Z|Il2FL ziYJ_hhZE-(*^f1Z62Jn#pVsj`iD2Qi(rNho|H{NCY4GPQG7jDnbKDULwtU~KBsGJL zw*Y5EcM=P$DH?YxeBRKxer&w!#?o#sOJh8|*$^MqRPwX58$JDC1>%dh3M`7pk%)~laQ-rm|zf%h?QV_6jM#z%*>n)KzPr@efNFjPXGy%J9j_sPXsU7mvoSa6H2iLDiGc>_EXt!^NHX~O;d>m zEo{7Ry7RU1<>O6XA#rY3``vs*u<@QrYq`Hghw&CCrHGFaD*2`N3GZ9^U%Y#(w6XrQ z_c!WqZ)q($cc-qRlj&z~AxXZ~y-v`)x-1mr#SmNl}B&X*?mnAPuh| zH=bN7j#YzXY@)Q_8nke+6L~%sDIq>CQ^{|U=hd=bR`fSW5E z@jiNqj^4oFcN2h%Z{dj-vOG*FAO??F^2%J(seS!I}w_xQzNt2KE zr{j@p$pg{^HVV8?=T!utc&k*L7s0~YUvx$U9!``-bCHJ=w-b~#4nufr{j3^p-b(=M z9uyX4wIzZ_yLhr-yw}+6Oyq^|ett3ay2Sbja0{_FPp%ys??V!q;#_s#O*SKO_>aH8 zW!=KYyDxDgYvoGD!+SsC<29B1Zg2B29=t_A-frs>-0eUb4oJrw4nLLpnCYuGuIM0b zJ_PTd*Z8x0%SwUwDfcU%P`qb(Lxi#LHfTH%M1DEZHa-mQ|Lc}7(Sv7i<*J6;&L=?c z-VPUeK5kD0{jc5DhVj;44!jhC@E&}3_6YmO2=JM*;jUzV?6r4%E4wU9>5NG|68D^~ z@8tnI?BPUuQ5piCM&(_QXu_!f9YwITX>&(^^R#77ayq|VEX0HrVfn07}j$9U8MqC!f`us}#qWqkEGkl-(A`#yGmc2{}u?i?7VEh z*hbj8*yuk1-t|{39J<`7SIup6PPE!%0J0Jz~9c_z)#{Y=ReJ# z!=J<-&cBP_nSVWm0P;UR7Ir|an9ttyR;meb097Wb2a|zhR2heEYygr_wOmG*A4o*i z(l6i=AOTfI^{M-TcvLOP^6UiSP-VEe{}>R9Dg!0XF(3w2i+;Mk1@@y#zol6ih(?v( z(R@)L3RSv6aXr93R4p{#M*<>IrNef_93Y}f>($<)Km@8ZkH5YMgriEsH!m94iz@ZK z#BLxARciCsT?h7{N~POo1_(u!^7&tEKnSXolEQ<5U{onu*cJgns8SG?c?krfN^VTB z1PDNtY?Glr;EyVq%n$njKU6IUDk}qgQ6;T({2Z_wRgzOj3xQpzlDOMa3;3W)JXa?l z@J5x`#si(ePE?8NgyjQXsG1KHrU0I(60Wyg2Y8@r-W#0-fIF&$_ADF$+)yRxw&4Y^ z162b2UxffyRPi-!eg|wv6>mr3Gr$E^Jd=m60NYT-9j_b(IHQVdvuh8q6;&Kx>h1tr zP{n@V{4TH=RcxVGQh`mVVqI5l3T#9bi{ke-zzJ3O0WT+D1FCRW9^e5-MA`j5(tZMP zK-I6~JNyBARLyCo-3RPYH7n$&0T56%^Q_Gnutn8$Mr{YM9#ucQwI_gesG3r3mI7>0 zH7QX12CzoeMEmbiU@fY~uZb!GYfv@jX)z91p=xybDsR9NRU@*ECjkpoeeG3C2Uer% zOM~}GU=^x9hwT~yR-$Tn{c=yh992Vn7pj33s2cck<1Ao?s!x~M%>WQp{SnW-0aH}< z5msgZCaCI_;RpkaQPpENyBb)Is;-tXQ(zgYI`dyH0G6WaBf+2!FhW&_-s*$E5>$QQ zzG(*-qUv4Ud1t@?RqdxGyn)52YTJ?L4=h5}+qF)TfIh0;2o{(DdZ>E!T%jG%Mb*m! z^(tT?s#^WL?EoEAwJev<1+-DsJa=p(p!JVpyCDZ?qN+*xU_79Ks^^wDO zd>^VJbG}r z7f|JX!O;OYk1Dqa*=FDzs&<&Ks|U`a%2lTG6>tVsE}y;z1I4J?_ISV!IE^aj6dya_ z6soooKE?t?sM_LXn+u#o)uu1oZGaP~+IXK+0VqV3Q_ApK;5e!_L}%{@j-krY-m~tyhL0kcX=E7GNfji>h_FZ;n6?s;pbfM}Whq zT6=L&6Uau@n$R0pfkUXWGIa|D4x-9ZTXh?dg(?f2M=6krs#TTg=|BdmR_;0S97so% zxq03!kcO%inyW;CR8)ceL)<_LqU_)a7r==scpw09pbFkU1=vvqZ#MyKsDit5fE88n zIaz=ORq(Mw06-Od3Jbua3O=*~;7|q6`0>9{1;1^J|Ai{}2s|0DcBl@SR=wX;i^i9N~YU3ce8rKZPpz0uB5ms^I$u@ZV7d-~5fAKoxvZGJYIY z@V&D5F;v0VaNahTA3+uT{V@DDRKcHH!hb~-{B;`q7gWI?^T2;b75wc3{4lEE zuaM)1a5#Jg+CBXJCo}v6kUu~Bohw-LfRexW|1-g#88rXrqu7Il*Er}Nq+_YN4AvfG zc(8THQ)r95{Idx83{r%BnYPunMP>u#4HGKR1WBQ&)LNt|5$ws?KCA%kL3VG=)7$~= zK^~7%2?(+vf?erfKU{l@y$5+iy#p+r;xI+yWLAhB2_|9hLGrl!8glIvW4JxY62u2P zmHfQ7S;Vx&(Z2_|nyV|HW9}*D;P@W`91*G4=peDR@y>G7^;dO(v8Ab4ueBIt@;sCx5I z;0<@7DBh1dA4*~2eM3#Y7si`YRfmkXg`eP(c@W+(z{iwIqT{wm+Jc zA-tOqULx&S%RlGOhUM7NvW@jDX z0qKxq=t&U>Z~cTKq2a~|uwtX`HeDBNyc=`49haH1m|jKV0#|7-=rhB{n{Z+;i(UOZ zhQs?I;$tn9{0<(wEmO0I{^~8U^U#)i1nSlM_S$7DZgZ?=`t$#5iwtS<;h1n%+arNo zy}2mxhW80kyqi9|OJL!x*`PcO;~l-shKzT0@{X))5Z>NDmqo1HKmZpR8CO|CXK$aX zUG0JoCtmW~uxc7Qd#kTfb=l!@1Q_UTR^{e|jrVOf-+bOKoM`|O=W*2}w%Z6B@74c@ zy*Cf1a&6{dC+o1#|w=7*3R4LqZP%E+35T?N?DpCu}6fkm)L;$IgiFfUNL+H zxlZdeRXSKXm?S$7la^RM3cTUb9~tlVym3i1ynlbocBlh*e?Hx|6UN)#OQvlF!21S& z2+w3R0b1z4+0e8;781~lQ-txZnJM1t4)Eq=>Wh8#g$U{VxYoHX4ju18a8&(rF+W}x zi95>q^jY8@^iS+^S9*TBrY}i%c;_QJPGjV^$28Xeb_wkj(i9VapJD?Df-IDd$Cyyb5%d$K?h8}DHW%{!yx zmJHt@U6rOzhvt$53BD5~ym=__h7V_u@t)g$SON|2@lgwFxIt1l`NR*#JM>BQ;xzzo z7Xg>8F(Cv;kft}`}J1bd6kjL zV`dDGH*O`BIuuPxGJW9ZEn~PT@P){`b3Fo(1iZ*Hb->0V&wPb{@z&SO|-jreBf*GY^VXVW_R%M z^mvwF%J9XBK3^bJI_$4@$y7!Bd;jmhdo{ZJ8FdPgHXdZMybC()i zL6(JRkQ$`5!(OI!U=Pw!?xW@0DFVbP6nen5E*3iaax6pzcu;ds+__s|53=aPk9ku> zA{5yh>DI)J?m=Ds#6eY$W%y_$uCCN&)xvM+dyp#W>4Orb%5=BHzCd(f<=3_P{#O=l z+Lzen%CCRy*TJ43eKU{yG*|PH;XTN|K7lG7Rr{JDvuslTzlZ{F_y92(@3Ke3@@RN# z>}lhN@mA8fPukwuztbK|O-5Y%1P11ptpTU#)J~bz3 z$D5_0_sjVu*mytCVS$)8Z(;ZbY5o9pI);uJN=Snnq(E^ZNP#!}i3b_)efOhe(eQqs zw*EPcx7&$Z+u{D7SuoaX9N_H}_QX0njR2KAW)nXI@a|Yt#tRQfOEY;bctL~2T`>Fe z`HN8K#=gYcXS~qy{%IJsG3=ly{uUCqUc>P1150$gCsswOw6!SFU2*aQ(Sem;@nUAT z%qH6LUNg4kSj;o*%ZYI+CC4*yo(zvS&YemfLpxu~{`vl2fC6v$n zrd|T$-Mv+ugm-(-%?oUx|JTvgsOUaMfNYFKIvoqvZ;=R0|2O}q%YOgAlLAYuD1`^XUu}{- zD5G+@I+_Q`;4_n94-!kr^oEz%;bhZVb+E+B5)>`>f-82mRdIW)0B4X+=V=wg4bs|A zHhuM=f>gWcb}y_n42mAV_o8VH`Wqw%eY1+H-WORb{#RY+X<=Q@$6yy$qFo|St(Pm2EV zmO*r2W#? z^<=!wg-TS=@II#aE?MwQo5(-o|p$2S-ap@%=~~XQXhVJr6qGac;BUMRD|pw?3i+ zE5E>7BK{jjXvcegxagLMaqJtUu1@H!C@bn>c)VZ5>r5Q$BB*d z=y=DNK3>Ung8uN1Ms#51cck(zuZJG(#Yx~Vqcc3|RP_H6EZR=ejf{UlnwNt*9s5@o z2>b|-3hxcAY2UdRB!q4XhuF>w^TQkNYq~Btn-oizguDgcw zVtDt)saa5^qg>?C!(HI@mVe*>|97)Zhd+bsH*!FNBAJ?PNh-`Z#%WU7A303MKT zIpI#4|BDHo@i`AF$j@W%uh$zBpjx}n8U^45srj=v_P|^0LfJt^@Ha?7Nd+Gy^NG+K zgJTPR>!R;LM&5H>Ys9h?KY+wZ=U?(ymq7QRDb~n|qwb1yw+9)9=)lTv+uS$5*4MOq z(37$+Njyuj`~U8oO;>cy_c6Q&MMc?Br9(3GUPWsXssERtz#G2IjEpz`iFPeCy!*SC zGQ)T$qy&>1qyxbzK1bl~t-bF$N>>q}>}xM|+j?W63C^@B7;mZeFY@q!^z6-te)s)} zP`B{aYFlP>ysfYLiJByd;`@-e2e+Or)BA`%LAum4f?wB5e-k7tL`N}3etf4cK5^lr z9q$K$na^T6sObN9h!uu#{$J4l`^!?LW8snCJRN`fe{l-D;oJGhc-v*?tU$v%BPy;I z?*FrHhmy9p0=LU8-45_R@OotF8*2hIJDmUV4S3#iu4hFgJpa#?S8N;tcpv^`aIw^x z2+cHS%{(4OACT_3*->p=xeSkc_9w1trzw+aJ38LXgN=3^oGNtZ-n+;;F!Fn;m6woe zM?2oC>mROg9meke<6=h>Zu`Auc=u+~o}fxcyk6ad-egk$FGhhkeBC4&Z-WO1HPP@6 zB`O?(@jjyINg7Tl7lte}0C-=Y$Z#ofB0z0{u1l+4$3hurB>5Bp-mB9(B>Mo~w~p5w z)pR35)p;8X+{V%IR<0Gf`O{Pk{{)Gf>o;wA)rpR`(kedZbBXkaw=AMV5hK6gg;&bU zPSTEd*E_4ki3BS8e@nrbr6X?`9&em9A9Xrxs|;qglFt7xqre-!Kb4I4z+wXpG`xpC z5#3?Dn<`&>!Lzr=jjDGA0Nw@UXO-YRUPO2^32SBsdf{`LQK*zNzHDS`f9mcoPJ8>C?m z;sfvhjcwk7L-U~3_cp7--yoSynUOxRPPe7O86?kl=5iN6gLLv~^9`%NG)R?m_XWPj@!?M+arU7J0V;oKkXDN2&bEjy zr@IQW9MOT5UtQd`;efNWd(g)gL6K?^?EatKTytTg%Wjfx?Oi{z^aWs&sHVx_%E% zCE+bafj9hU1sU%$9xpvKya(ch3ShkVOA3+jR_ohf48PvG?hKRiNj(A-mRlEd5A5Cw zdwt&v-~TuCqk1nVz}wf>Lc39n2tDBzUl?)~9q)q<(L-HHi}8&}+|7*g@h$1-ct>0l zk5QkKr91ZyMs$Q@M9Dw% ze@P0w;a6D5c)Q-#(nZ7j-j*DH81Gk7x;}7mLg;PQt$^|7<{KK-0pH$E@#SoO8w>sJ zk{E~ae(TN3$pr9D&d=9B`U-q|EAa75YXJIiqV-bo_T<&V_&6kP`V6c7ZWr{~TQW~> z@s2C;M1HW}6QG4(R`tC_JbIyh8&pWHgJQ~9=#**_y2p%SJak(J;?RXna}S(778`qg7a@N;6VUyMGCy(ht; zKR>)@Kfv45L7$xoJa6&f;MaXO!41+{K}@{x0cqUcXZs%kycgBa)E3)?Ld9*{nWEqB zM7^2RBB3NlUvw+;pWK@8|2H zMmSoi=>NCXx!pf%UrrlK^cNjz@Qf-Q^A>FjS#LzbTY&;^_@zKH-py~n&qKqzmzhHz zo*&TYIl&ZV~ zns&Uo_>MS!Y{uTb#kC)OF+28*;qk^XZ|a~%$ISQPjB?Rf*uCW`@P?nhB;!5%sEQd4 z?~`$|tuWrA_e)5}TM~C&cohQhHhnP^_`#6?Da$b{M0UnPZ;Y0Y!>6~bD>$6K1H5a_ zY&g56F%;6~7!471LB~62^Dc?ye0+F)B<{?}8lxY0bi6Bl^mUtxB!Mvf|ABhcRgmnzOlQ2FH8pDAA^*&%f9)9dZlOkpkEF0;Ml@+SAxD8X z{FW;j@11T(nb7dIYG+M=`~O|Gd8Gb-TjKr3Fo5@bvrK~(>j;p6s6)0nnEwkoN?O7F ze^CfNPeQ`Y$y3~`NHfDm3_cigi8CSiz@mG+zx4qR*6{XSfZnCH_ym*EF zZg0Ja=xD&mFT6sjiI7RVdw=&Kj7fD;(f_A7A7!^wXZ-K~FW69}gQ(IdbMy4S{+}Ui z3@owg6dnY>W=-}WS)%0vG!Gh$|JE))7r26)uf){$`Z{=nB>ngqha>{T95|BN z&=U*2d|=)OpFujhOH%wHSYms;C#%0t5TWOGd4lan(DxvN3twIvmy^SHB5^@?-^zX5 zhrS0n#kGH+Ek}p$me?Rf$0SC6_w_0?p6Jo;L2*Z~Rb_QiQ9*W{)l!>xm+|)?KU}6t z$8ZvtnCcNygQP}*H~c(18Sj{l0$gZ#;~rjL1>>FAY2pgwEuFsb%@n}9Q8hK=Wjq0z zI$H>7cgI50aaJoy-~aDEwxkl^z1u~`Ij5QkS-!ZWXt4<$?{NLo*OnH`;H{Ck3VGrZ znU&~xztcBbFi%dK?(jZ<=;+7D@1jPGbkPj$c%KuIzGd|kyMnC2tK{xmqrvbEQcoEV zRXXes$}5PZkt#@43cTC=c5EQy{Y~c+2O8ejU9W}1ct2}Va)a?UJ@;UTAgCbuKXFXv zMiHRpRTD`rUEq03NtX*S-WD-An&K;r9ffgSQJ8$#~ayUD6n02o-{tyy3 zY`&hy!wS8EY&R{}vz=N&cX$sWI@&PuOa9X9z$#BW-ko;B51$oapZ{03R`y$6V9M}# z_xXrXrK2gIbNBl{ySFM7ct1B>o=(PlVbdLUG`xLErS8FayRpe{f$`p7%oJe+@HQWu zvlXf!Z>z(ey+w*CT61j(Vffiwr2A5;bR?HpnL(HT_5Y00|7%ltP|xFwE@TgC&@kdh z^Ps-X!mYJniOsFrxfxz!TLrK9a)Bjw&siJs6W|7EhX{?-Ch-0L7TcAfYG8?dmABzm zG+1J9zT+sBY$QToHqW=?*oy8!MejQgd#WnpCy=<3J+&i(Ytb8|yIxL_Kac9uod;b+ zbYSK8aZ63(CqddhsK8zd|KuYTdyoOV@k&MW^%#Q5zb45?m5vs5$k-6vK?=6Fv?%cI z&J!lxAPpaHG26k%hlaP$dE5&a?^_}vB)kivxqsjQ-g<2dQ>8KpP>mqVoXn$?Ub|Vtz#E_`@LmdpLBwPdVI=yOE`U&p_gy@Wd_&8bq%kNA2YM z+J5QLoqL}|bYSHdeW@>Pa31Y=b1`vk;bX#{2%VQf@T7!=8-3hVf4K&L-hK*qCL}5AdFu6&6iMB|sY!7rwRypSMKB zh9<+?TZv`9Oz`7Gd#>+1Z{|US934JpXHBB_|0%WtONfgU@UBRlcux2jXAe5wAEeVC zT@I%|yps_f?=kX=@xOUugDLHJi+B8RDc8n6y;YvpcldHg2gBoi;Z`qII#LhB1&RMD zPBbX+?&LkWl8kp$RK!9wy!V+dcn9Ncaqlt-Z;!ky+v@?|L(xPnBXIx!t!*rs%HZR~ zq}!3P@a*lrS^l>t0Ppw)ZT)OtBIFgu(yH|r_vX6(CL?95Jl+S1>(yOnGVuW&Z$7_$ zLrl+f>CU~$I(RYiGbv8TZ;7TIZ^5{s_QOA@*xqVyJMho~V*J@#_s~JAbnq{m5eM5_ z|L*_$Ya>G+zX=*70}2m%`+NdV_8@6{-6d!qblttz5cZ(2YKxrU{y#XlglPhJP*CCZ z{FzMzDA>9Ac<1|AsJ!x8zzX0&%9Z`ac;G=ciq99mEg?b?vzom#rsx%5l`FKYGO4C9R(K0(4;bjj*{-vQpt zr~KX=@+3g1XC`cZ4#Yx5EMd1b0p3dZaKc)Ex3SLE>s;%?pcA@Bzs?Sz<82ffr17Lo z5ub^~9c)l2Skj7)w^u4R2gFZ*cpD%(wqfKqGxGTvVPbwX%(Cs-~Hhw)zKCFTsf_k#5%u5$qI zj+I2^#rp`*E3qefzuv_{IX0!=GyvXG)2cfh0p5dWm!#p8!=RL!;cC@dbiAK;l>ZvH zRm7(vaXE%j@$seTcqf)Bq+czgzwNCSM8^?~{35^K4wIOr9q*xK_C0R=4VVX{B|i14 zsInR{{0Y*I({HHKu|+8Omw60ndrOxB?>8E&j*;=cbfQ2I4et(VWx3V0N(bhD!Z3k5h0dEsrH>c=>5Ns z!CZ)=wj!PbiMyk#|17H-y+P7{v3y@$2L0i^1JR*}k>8PX1*hZwhXE;*VkW2E40dr+ zr>|9Ep{d09cu!NOLu>8XCx`yL-l{`^_iN7E|2e%SaX3-{4evKImzrR_yEeI!`v1_6 zL$Bfc|2_yVyxyJ#zTV=CIKC5n|6hEA*;5_hEo0@gU_Zb+wA{4l#wM_PyT6O2ZWtZ! zFB6BVMAj7B=Md*?e49++}34hHWmH9 zL|OH2_F%^E|F==8Lr%9w`d|M~AN@U67NGx!C_HGeWd48lAP;jZh@p9qfdI4#_8<{_ z0;xfg*Zs*a0V>Fr2Yrz{))Jr)z3)G!zQjUJ^8&KrJxH;Jk)%7ogA@`6yWbxmLYFlQ zo2q!xE6Ag>b@<2=iukKYoL~LQy7cep9yGh}c5>|m{drIVqT@S8ez(09itf+xU{-?v z{hxDYsO+U%JoXklu2f)$o8&8oKZArDzV1nljwtn;QXd|W8YDag-XB7n{xknC82u)S zhWFUrw`*X$1H(6w@b2F9Rlx+{ZTs~^V=cftgZ*-Z%;#9>b%E(=ctAQVWgM6d@Rs~) zyk5eN2+4h4>i7Et`V!mP$+7OjXGOdc5;yCRzoxSh9q%xuhS-N|>97B9M0A8;jzCO+Lu^f{{Ve$U+fCfViQMhk@d>*|Nh^D(SAN9)SE+%4wKc|dgh5Fyp1XFeort< zCO1f3^IDdo;Vt~q<x0qLl;*@3q<{in{>b2^_2@ir@>v&>!A~ zhz?VX{C-$ey;IpmJKhonzh$?zJj8bWE3%I*L-ZLQZyavRU8;1XWd1@9NE=b$Js`#w zM8-QTJW~V>?}D$nsxaO*iSHcY?Je&7_eOaD?{ytHGbaJw8Z%MHlRw5nmibTm;r?IW z^vO4SfOqeu)76W+iO~3G4mJ>Pd|dN%+jaWG zI||X^jgeo?>F68M;+ypM9hE0J*n`iL+}n@> z?{^!1t|H@o=*4znG`wTRg2iCGr%cb0@UAKx%NYfD;|yBf3a=+X2Y;XC%J>iqnaTvq zYXQ6$mv!vX1bF-Ko*Et=B0`4wnWcUa=y)rwtX+BsuY|`VaSxtt)MVd@j*XFK-OFu&4V~jXRy}*54!(Kf&eeEaa#}fX#)?EcrO)HI%5Ml zJW|wi8jXcIq_^ILZ;+aBXn0o-JZQ_pW(OhZFi0`4|H#~3bPtNr629`iSOu?!#Cd;t zy79{ebPqb=GO;S=yAj>Z|059{M=|nyIJ&6r>QdUT*daPQ$L$Vpz^ouos8%~2bZKY! z3Nq4`Ivox(vH2%M)8X^~W)ygj1o;e;@veL~Dv5?SD?jfs7;l?3R<M17mIcFjm!^m-H3Ph_J0|++4iKS&`vLDy5Yh2A>xC|8j4R=b zk+=@Q<2>Wr(D7cjA-7h|(va@(h7cXX82R-E5z`&iXkTIvl(zC0ox?u=kK5ms+G!ZW z@Ob089#N$uQn;dAsen{Lno{8X$=cA1jCcI~JIm4VcEsIY_7LFB%9dyc<6SJ)qbLpV z=KQSC*}aSaIgi%A6b8GuIx|;wVZ5_#yNU1%Qd*L!T2oJmkiU~^);U*nyvNSfXgP)| z;`bqOk2ViVthYeNd!$9uNdG1M?cR|^9@D)g*^b(; zoBhu4c&ok+p-RVEPdnM7L!|k?2?gH63k&a&@qRLrD1nCemS?%;Fy0pg=52!U4xjrd zzZl@XGCh@Rza{~4RBd9_8HK*swVM2BodeBaXHx3~F-j&O|pGM0$St$Im2-YQkY@9TT9@m_qu z*z)X(c7~t5@d?IRP@}^pM}YV#A?@G!e@55=01c8Ag$I4Tu}F&SLEZk#6wy3rfmuT| z+#q@TFC{fdBP<uOATW1$Z~{>lDK`NNYJdefbRV{wVr1 z#w>#fz1SPYSF4D=#8xe0Gk#H{j(>^7z20SIt;~;JLE^SZY6Q5_AKqjgb8dgnPhT}K zWL%kcydy6e=2m{g-eSjnj(93}FM;tZNSRcsbi{h5zmEc2?7+QOQ{X*rX#St$Eh?OM zvY=<{oL26s`Zs-Si zr=Fj6aRH~d47>~-4gPX^YthXkisFsxcnFD;%{^2z_YK{>yPYSwV!Y`OZ?cY;82L>f zTxq4Sjdr{vvNOLNQ^UraV`;y4vcwp}@L1<4uvcywKxPexK3tt`C(`?NX;dyvaJAV&n(4 zmMu-mp&jqKh##s;`=~e|J?(F^^ub4l#~UZRn>rn8!b3~93c>EZiURM?1M*4a;$;4J zCmA%n?+Te5hws=b+!h0&se(gr#c~#`~1c>u&h_ z|KHC--)C+NgLrz?))bDQ<6T(R^kh6m4KIkqb;ax5sO>^8PMZC=OBc4_>8|#^faqwz z$WKnPXzIEP?RcNO8Rg2wioJV_Gq~0fU-o~&^_I-k=@^(=tsR;W{jdLLkpADA!h?P! zSHB^9P{RBL>S!J$tKcgNSCC)4Lr4{5ir}`54ZwqpTw6wPH*6r6WjRlj!T0|!#+L(Ht2%Y3yQxc|+?m;|#@(UKYsNv5bank+UETHA+9(1H-r9XoP=lIyv^Y3o zw|@@58(v}u6kXWi3R2?!2Ms8c2n7x=P!(B-j`wE&fiqe`YWPqjF52o{V#8PT3i60* z|Gp2m=?`ybL`N(}e*CL~@1MFtJKhOa0%?PvsHh-?Q<@DPg)%(exQe6H=`aw=RQj{M zwT=Ss?{Y0m$?iR&dqD*a?|VB_Jz%^g-HwyCw`MygDhdJKjTZ+MXY*|!rVT&4^#^02 zuOSzF;QqgzYk|yrfcJ4#mmhgzVNk+0vF!(Mq2sM{?wUy32{n8Q5?AE#s>JFXx_hsE z^zwIWJN@BJ)?tB>-^?;^pZx#f3({$Bwi@CMDvq}lxNtZO&1d)r(r}^F>9AcOugiIk zy1YN-UG~pXK%o8qVwI$EpbD! z&|&_x&G7E+?05UdDS)?U>VY*k`NN=sz1f+j#prk!%JgpR{-B00LgF}2q2p~Z zYCqdA1JPZBMAo5=k>81j=eW0s(SA5lL&YsVEgHK);+q}l+NKl2@OV$izo$yay^9-5 z{i8_7Th>tEJ=y(xoQ!w%xU~`*-uPn28!+Cnvi&5yAIa{D^#yoO#?7l}Nw$HQp_MfP zU^sEH`qxT$_V#h10xKJM|F4dxwd_9l{{NkKNmJEdzW=x0eyG=AtvY@XiCdXEI(PCf z-~U(4>FaN5r9ZrF5FNKL@@r3ib&hKd?ZwIGOG}0(y|6z{d@iR!sH~n~_}SaLa0{w* zT`WNGL9%4u#7~V5--e+|o)l6AX-k3k+$oR$T#&wOtX&HY@9SJHco^^f^M8== zwmoyjAQ|AzJ8>a5{GknW_g;pZIlz0e*!~rK|36=8m3$Jw`_ik;JWJLSA*UA$EZ_H{ zA8*;U_P2&JP95)z#2qe9eZKz@I^L?Y6?kcg{_yrebSPrv*ZEd$RN;SkAboz?ydS+; zRP_H%`i4^vH!wWjxJ^Xrbo`qCS@uu=zkvepUrLEJWcR+SaCQY6-lJ2RAu!(gX>ZrV z?yb9Mhg~kfyD{lv^W*~?NF(g~Z)SjZlfdJJFy0T1TJOQvTljn1m_B?@go>;2-KGc7 z-CH5}L5W_t8vYUzSO4w8_A_4S4bq_^Bhv+znkzX9o;^sFSX?Jfsoadda zVeAv6xC0)N(t+<7A8&s*s&tG9Sk|iMliZs?f%i{7KSeU$gT6tUXm}HMzP}CQ-MGA; zG$1{H-~A(1{#_QoW2QeZ@tJw)PrwtF}r*C=|zBdVeP@7u-8QB+|1YX zC;QOxE@gJk3YS;IpGV>rHMvNSyP)H}>s*9An=k$0eFf369V5R&-@rxg#I z(sZ%6w?z97Z@+NaiQ)VI@H4=&0P3}ER>i=yh@SbUSX+*|*gE3wM4ezZNT7JQJ zPb&Q+9dEH7KbqGG@V4A=Vj!r(25N3_f9(YD{`ADq1%BS5{_C6_{Jh2TY5jbtj|lDO z5MOjE2p#XJ_~f#ZwQBefB(8eb6~32S(D7arF!IYih5qn9gy`VI$ZyYwtKTlIrro`L z<6j*8^b33T7U{8vr|~rt!@GB+vKv)8W{dKgEy3>Xzx)3gU2!tD41;6VvCCTrjdlG9g^zX*8HH2d9o%&%;qs^mtuFW`xtH_7(~ zbb$xybZ&b+!vs7ivn#!K9L)dktWL;2jP5~Sc1GJwe^$rmAaT70l0M4<&^<__rzAi9 zF#R2|8%1=eV&u2r_o9vV1lm1FM2&CPVGb&;*jXy^$l>K~Jq951?W0pHJy$VZ1+$hLi9f4`q>9QA0UEqLpj-swH zc>nLjnQ{pofcLSSmAZ?;5}V+Y-Nsx;gcgi;=2rgY18Mu>ay{pF>iC67+=8CP943GH zKw81OlG*4W{o%b4(IJPCU*%Jq53l2C$D2>;qN0L1_7eMQzvlkTO)nT8@2j$^ROztl z$husZMQV^7DDa*qHT9BQK|Wu4S|1JXnT4yb!FV^x)sXN`ge0TV0p3ekS#v$xY@prB z2ji;24btX3>(|0JNPStAn4kslj=bX^HeL!QNQ0jZL|37^cSK;eM*1^#`~VV{uc7o| zfeN~Nr(8ZbG_sTa@D4|GBx2-eFOd>lSWP?L0Xk|qcNb#s-r~lt280MA zbi7QJPy(O5UAV#SR&S;r~WV{`jTv*ZY zeg(Y^g7LQB@Qj2v;gz@NI)L|@h#FxFLGZ-x%13+RTVo-G@cOkd-lMk9-!uTcyQB|# zoct9EZC=k^W|M+G|97?Q&#>R2j(0@jyo~I2=Ilksd(wWeQ`ZejQe@_G1ks&v@(v5J(mX2N)HrofxS$^9J}Z}a2& zENFOZ2opnLyoK-dknn!<@dthdz}wA{eW~_B0+i=kxpc5C7W&dSI${9ub|~<1Y5{nM z-BUU1*BT0m1!dJO@j%D>ra|47vKV!|C=zFvYgF%GhK~1iSwCNw1pVQC9nmp`k)N$b zRsNA@w7d6bpID``Q7Y#D$>TfbCj1#5Z`{*&ROxWGEX}a9Pl54vrofwR^zmIX-cm2_ zF{9yKACYqa#(NuKn1uK0n?eNmfwa&0Gg7};2vBbG%v4cFEF`poGYZDLnl;7#1;G2| z^oqHtq)^DpOI$ix1Rd|3qQm$0g75z=k+{57yKz#p&Zvz*iM3avng;#horUNq#>j8x z<;*fBY1;e$Fx#~TS^n7DTO;qhj3$M*GCbY|{^3;VNQ{wx{wkZad+S7j_xu{uDl*;) z#4}82c%S~(9znu;%?}dZ-UBCmK7#&#V9nU<*>5&b(N;nK;g_+{`hCLuFy1-AE$g}g z-U+U=Q@2w>q1pPIMIEB(cyGLA(((L)I(`O;V~daujQNF*_g&uAtg@!`hc^MyQI3({ zGD7e*oh`KEtz8Q}z0*v^-CGrfmm(xQ7#?q2Tmf}D-i+^&1iQEY=Kplv`Tt1{EU{ZD zJcut)ZH(+eo1|?Ppm~toquRc=K+xZzbd1wQm_08s4kYil<<_f6Cuq4dbnT{k_#0fcM$-eq%)@0(7Lu zjp;4e-a0+>#RSG%cR_aLnN-QcE)Al zHuNp_^L)~e4X)E4-ld3+GZ^`O`LXBvR0!=2(s6C=H=Jv+`+uCp?yWtyIT(J69XI6? zK#dN|=RYIf+$2?y?i6_QaDV0_<9*KR3kMqB7p&Mc;R-VKdzmGS_Z!=5)-eF@RAIG? z#o&31kH!l}t^&M!_)@>a+gnZxaMCpZZ<8Zw8?BqdAn_#;4kA0z@fI(A<$yN<{XY`- z_$If;-A(9t=d724=I+xU-lB+(42=BL0%AXY`5$g?4X|lZ+ZKeqdn@iySgAVb!SHy? z;`E28(XnvctXU(ObU=Cw1>OsvIrWh7eqVBh9S!fnybYw`#1Wo{qy~xF;l#aL`eLu^ z!=RX`7|{94uuL6042 zcki3=9GzO0RJiw~Pe^6ooGt^D%YRQ%$CN4^raz`){0d3#?M8w3f;Xod$asGkh-O2> zyOrw?-pdx!hPQ%ia_7Y!BINfzu<7z%^x2z5ZahyXnE&rY;?xt$r@WleYwvrN>grFv z)1P~rB09=3^0VXEao%2q_S*Yuz(B5GFt&R?uzYsm08AZ&Rg%Kj_#uPMs6~ z`v1S11%3Q3=>NA_G9}3%M|e+ zkT_n0RR?B{qk9l^KtP9=pZ?w;CF?N2$nPEDH7A!9?H)9>w@9cW344i6Rhwwrd5iJC z|Ifd1sGS-e8_iWOi610Yklqw{FH#N4BIE7&nu`w&@4l4OYw#y_L$7;CUy$0j>&93C zyblNkGZDVpK+-$1Ec?OdEn!Vp_QB`>9}mgg<_CD=t>fRiEg?b!7T@ARi_o{&Z|Vc)p(dVr=v-K&s*L=bSPuwSAOW}aixB4)Cn1y7uv3KSiE>I z_V!lQ%ds!NUTHCWgJij&af})rHxkZ02}>kZkX{sc3o)NQLdJXZk=HzEc;km%e!~6# z*6c~r2~yXQ+NPZVZ}YsB2`(RPARN#4Yc1Weke`ryvL3+u^6BjU3DE!7P4=$a#6*Nf zAFt>cI*yL_@`b8vX6~!vN02yozQnfa{pfff@9g5!XQ96@NF@**Nf`Mh{M_?c%9i#9 zscUGROk^h&6C}Ymp4!TK439TX9Pdq)4xO%8j%Fyx)WfcpIb> zp_Cuv#qJ8|#mVmbx%Syy>iA?NZs_coi5M?>aq`S#_8!5W{u(5IM8{K%{J!a1nG{se z?%s**-%kYyVtY|qrJTo2CPB5`B221Y_{=y=EXT?~wTL4SDfM|2#*$dAKf z<=szbX?O4Ly#f2{Y_LC0%+pIepcWI!@Uu6!R@+Ewbog-$k7*wL_x(RwQA<~UAN2pe z6dtr}@0BZL5Ar#tvjok9GFDGl!EcZzwC>mpPmp?cwp>vF9#kHE^Yx40Hqezs%X5w3 z25HT2t8p5@gSOT39`gnbQhkf0{yuOAiT1CXpB?{l2Z;bv+vAFU5xf=>mt==8t#?EB zAoDdk0<0?)>F$bMvJQQW`~rQV(q^a}D_sd)UeW=VVu5|{Hq z;kfcVbi5msmt=FhYSJCv1Bi~t82QyaDzfzX9|okNibvu~sCd0aP^(Fe_;ukOx~d%h zhhz>cXr)TW-Wnf{3&%-#@1($6xaxT|8SlV-d4gzoGvCw>gz;|LBJ2R;ZMn|-fds(& z!RSc>KRCUmxOK%gWq^0yAq`RZ`~Mf;svPYB-W3XGkGwxbgc|+N{*D$x$2)e;u3OJb z249cFb-Gm^E1X5&-a7yIK5N%IExN-y9?@|YBR@VzjU`$4X>X7Q1Jt9_K2vdftNPF8 z`Fq$I9&cP9>ocl!wD;Up`Ln&Xg97g*>8k%3PI#}_BY=jtr*6&!JbUZt!P&uh`!#E% zE(LhsaQT&$1@K<*J3V|Ce0%E-foK?SzF9#78-O=B)1~_my#M!8=D?;se|i6J*P+od z{G=TI2ND-?MvwTY6WzTP7i<*RwN01q@b*P?$YSKDlBPa0B}O~m7SbUPGpn&{Z(K$1 z%9Nr<4B!9b_WPMoqhrK+>*L3j|N8&`VS)Vr{vQGT|6U3YlCrQlOI~7Ql;p(FJjm%K z&b1DBP=UXR59~pk*S%nK03OtAoBL{=5&9ZjhQQ;Cv3>L6ZLH)ILApK|vA6 zAJi5Tp-|zeJzfy{65AYL>>3q5em@9_3m5+N2L;;6;}kQn`UzXT|lG`GqTRj24c>>GpT<7k;v7Drm+Z^N@Oa~&Qm12WN7>@;T#|eH zQ{XNBOh=Q9_xc4FM9}a)`Fte@jQ5g@*W6*ePyhZUW(e>;a6iK$5L|CzDk71g5Bh&D z{)@L@yj6vK++e(KRD?C9xDp|a%pdaBW9WD<83?Ir;^V`sAaTy~ZdFCTK*xJ*y3^OI zSc2~GUW({=kCC6fwTX@PN80i36$tFf%%-CMUzsF6JI=!Jc;j@b)S=FEP4Q3v??-{R zSjy`IWW2M5{Djf){$epL`Uv1HX*K8q<2{%AHChSaE$F7X*#ykqc*5L%X@ci1L-X?s zVZ0~U4t(7O@XijAD9n@yg96uV5aldKuf1cdjz-rM2;ui5aY@BS2YK?)Yw!D(jeVt( zGIWP`9HQeoMt;+$>(mX_(T?}SwxiChV^rMUa@R$lFISrJYi|};s&uG!RoI@X_}Bmc zy)&ef-v#}D5QPUR1QYwo9<*OrMjFk7PA!uWg8Tn#j~4HQJxI1jCCM6ikm@B@_f}Q{ zBzMwDYT4^pC^hw06#T>vJIhj)Lf}DKb?K?0rlC;qx-T+8%{x&G`!$!mjK^>Sm4Qec z5AUOm=P#q*LE@wotZkPfiKml4)&Hbnf#~qS$S?NPgSz9pX!juQAikaAE>w6BF57vh z3BY$zceC*R6zz(;4Lq-{w5jkC$GjO(eU=%+Ghmg{p<2w65h;5%Q*=E zZ*~2A?bYA|>62lbWr_gaN8Y;2zz?MDou{pJ8sP1y^xokhXDFn=spBV_j*hp?^Ec&U zV*HhINZfgW4{HYZqT_A%c=^x%tIO#QZ%IVQW{ms_hffjs{b}$2dkE3#JlnAG-Un69 zW1Zz?_zLo5>qDw^?0V>0S&~EQ|MyeiE!)3thK#p_P1SNVyg80dZin%{y2g*Rd#kDB zFt7pOEt-A>cT<1>4SwBiy9RvT5^DCd0ml1`RQ5@>icA8gHl@&2+ybr)Qm zRAh}C+X1|}`z8H0i4vdzryt#{y|EA*@j(#$IPs9`VZAtjcLdj$4-pL^(C2w~Mo-wG z;~h0B`AM^ALFFeT4%$Dq@0l7p-qC}F-_n0Br8~Ss5gi#A`30nZYQLIFJKk9jrZzim z#P0t`U&;zx+!V#|cyF*(q)LZG+8N2mIi%twfC6vnxR3xc-UfHJh@;_cwtV6#jCaUy zoG*;`nFWV8ZUT7Qx}UfkDNBGZ%JS9q1H7vZV`Sj|zhSSL8WG@ayK1m*8o0OKs=RvF zt>}0=uNWV7h-R(SM&g#=6ng*pFYdkN=jEnxCLy}Rn}F!phmqgU>U^y|Otcp#1xn6Z z?=)&qdzk+;0kPc2-?=e9-ngGs>e#+}vozS=`gi}|e+Z!8Ux5BUjKYJ|j1E+iJ;+d0 zP!Y|8#*d#$g$JbHW0^<;(%}thH|7HmstLLrND6Jx=<(6`vt4*iV%sl;DthQuZ8SeqNV9({{lVY}y~QziX1NUDeq zWsLmlyEdfV^`+f|f>JMg?q;Q;f;?EckKMwH@%#UG<<#leyf;bp&lWq80&i8;Oj9!6 zm-oDtN5gxqyHF{N_fw7_65c<#M9ldC-gRy}oNT_>K>K8qn&!aqmNEy6$1vW%UR_PB z26&g({|KsLZN`Kp18i zjQnyt9L}E;p&jq74Ko_t%dwBQtlIl9{bWx+!{aT>Tt$_R(CSMDxAI68WGDsR$}fVm z$#_TMZ^@zI?YK^$8OEE?H%Y=f@Voywd_Z~$XR@dMcN<87XG$RtJa38fwcZH7ARVZc z=5`0*oxMH%lQ(Om^; zhUhqik>8$yb!uh*!|Scq>sk%iUtl*#I8IUD@(&{nk2lVJ33WOOo=74Gq(dn1Ryx&D zM84=gDYMLt`xpy!H-ip2% z;bgp()>+D+;l0{Yfi!!o?VxS;R>0-Cv&oPMNfs7eZf!!x`*Dx)g(Zaol@dtYubWJL z%Gc5HZu%L|lAu9$`Wo8tmUZ8tc2cSy6K~m?ZbRN%5e)C%JL=w1 zrDF+C=ZoLI|K9(j-=?1;v)IkCI0_HamS&$Idr-yfe04MrdiVT}Pa{}jM~-$A;U)I= zdZ*j)1nK&*Ep4y(2vC?=O|T94K>CjPz(obH#7?J;r1ya(*41U*ro?=32dQj?vaufe z8KfK8(*Y{$#VdCraXSX;?I3aVGe~n)tKZH)rb>4efT;*d9cv$=kkXb`QgQ&{XjXs&w#wIx1{&gft+Hpul^@ta}$3Z@cc-s%UtxUgl=k z0PyDK_YQ*b-kA4T#vE>tcvL-(aS@9@M|ALEo1Th$Z!h0HJ`T#knzr$x~77L zcT`H6Ts^@1+V%9kFy40)g+FNmydCG66fy_;`3x0z5jo$V5WMff&MDUU_?hBMt&P& zGrm7tPdnajp2;G1Wnuf6arB)5;@@y5*vQKw@d^oRVP-P?l{cxz;5Eh6JRSQ@O1 zhIdxEVIMpoosD%Q4M?j5eh@?f-miQ+thK=QmJzc}h%)#<+NH%H0LEMC+!Fm40Pmf> zmG$m|;Cf3L`MpU6=y)$&>8ZN;7;oh;68F@7*lOl5x_h%MX}IdIOn=8)$U4|C^0R&| zK6wmBJKjQ@MdYgIW8eRWyCri>u4;zy@s3-4lo}mt&-kwYok?=<0~C0x?~VG;>#c*S z=1ORITOQdG0&j15%V&7Q?!BQ#*7X;7|8L00wEkGX4RmqGX?`{E^_GUn?0p#T-B*gl zTLIqg+TlCI7ZV}&aJF)XLUg=)n^G;mZ{@3GMdGsEeE8cE(ebXHXl&q{p+CIII%+ZU zdt1fMrDH%l-oEbTJj@XGaAH{I%#h1z2gb*HI-M#V{l_b6pMvKt|IPm?`fPgrCFuWI zDLlwfOr4v&#P-j}>7aSg?50ak;r{>h)b<0g2U)o)zF!Xa|JyG-o{om}P0TqMr%+Q6D6Dz?~}*&lXj1~R?}Z4sbKhvu*N ziz(OOB{r6Y0&o3MNSBN^2TQXS8s1#|&qiRpt2?Jic(2+d>efNqI zRXQ%7n!n=WVR(Bhb{+-Zdi4nrWW1A><*Y!%+st>GzX{+yC35T_?B0SBCmeMF-Ycu; z882Q$fHZ%{`6z+i+r|#o<8lCR$2%+5&jWZj9`LgCogW50tmJ1qaT*=(#{~+vH_s_l zRwHrJUit-m@#uIPq`fSX@zAF`yz3AhMi}}1{`n#>&6#%hK5(~D(r6L(=PkHZ=i6Uc zOffv(ksqt6(lMSdm=SfJ}qt+#> z0p3{?j&(%_o2 zUnU&`h;|QJqmrtgGlD%JRg64#A?mz0!&i`9{Ml6Lc&dD!?d+c=mV*Ls=)*84d5Jx$ zRcC;PcLDQC!c&0v#Yr81xPoltnp$KD@K#p~Dc=b2*7~|vmlZsaCKud;htK~nzvlY- z8NhqZ-~-m(r@-|VuiX2-DWc;&$Si*>@rq<+2oiVHRN3q(7dqbjS~g{A#+r18_Yk5( z2qQmPU2dtIy|m+P-O8IMolM06X_td?kG=#jJl?qOIO=rlN|MkZ4M=0zDe%VMNiZhk zZS^Bf9}Vx<&x|?Y`Tz53Rnq+5V=4Qcl>qM>MUn@ffd(nHP=DU;SFupw6yH<0f}D$U z-1q_D9n-ri@}4LW>OZimz~u@$-Vet()LeRGE8ih;vR{XnNu{FWJs12iS!@ISHAuCH z4yKU5=Qp%|{0QfA+VM_5S2BF+F%|v)ffoy&#V|2^gM_Q@ph|~#iA6-lIZ}hfMuE3+ z!m)TV-YlbDdT4md=xTMqcz;#dvmbVEdH*6;czerMLatmN;H|nrv&a~n|KERJ+6?ah z7d&!J`~~nXSiZY%>#tB~o~8IE!xVJ9P1mU|eU_kD$%4cUpC6de-HVR*>au`A{4o7( zZiaeU&$NdzC;C!{e=d^DI?5yls^)+Z`b7-p;4M z+i3r$Ml#+NE@rxDc=MKjxd9(eEC`7VCvH9XGMNm969b}>yh-5g?G5op zm*C;V=bgsKguw1?!+!G|tq-A){CRwb*FKThe3YZ~0Q}`9JQ&&>;ci0EWjqGUg*yI-(Lb?F~%$ zH~**0e*eFd0{uS^g$J!xk#mJT2=4!jQZ~*<^PspH;}Q4_Qq|ZY(kFHj!-Cd<@NMs$itxOjB9^~fE6_rQ3 zzuXr?;{15=pVAJY??HCjrsRAV`EC5)^8Ww+*%i^Tc;nymTR%E}vh;uG|BEsQ)wT>_ zFR{2hLuHk~1&rSyt>IRqMu+=RJwh_+1L;_93cM|Fo|nmZtMbdSqTwyGXucr4y~VXy zmURDLd`P(SB*6Rn{a1!L;PaL(XFu&y0vDt$SUjB#zC7ci5nu;)@qVXs}}y z%iJz>ymxaPT-H#Gs~kq+PW?Wr<6?)7_uTXFB0URUx?5uRAUe3){+{2G6#=I-SZSaC z>#%sNWz)i*|F_GQ9%nil$MATE33#PZql4MAGmkr#R6#DJz}vhmDT$2t3jDWuXm~p* z?S){xZKYn4@D}h}pvnm+I4XA|anV<_@nNdyct64`9k+BBraQd75gqLq`SJaVHq=wz$nbPB`cjWd?&phib{Y4G;S%cTB)0R`S>ftgKYyq{mY$Bc%z zh~uO`jJNC5Dbn?pR^AI+WdYt@>}%G$f(A*e%S+ZB?A{)DGrS5OPK1O$O{)ZW_m!Cn zhLsYb=Y<^5HFI>lC4Uz7Khox}>_Fn)y-pVwRYu2qv79^mohS5nIT2Zh7)E{q@fAuc zk+kFOy@%iXyaG1f^$Fj0SFK|F(_7Pt&jP5?aZg#0XqrL7n~MT(Q`3x}WW1ecqnXg~ z?wOD$&EA}t_R}w|%1UnyXJ2SMnfne2qNPHD>5|^M_t; zdZ#Z(ckbEVeieu zV(j1l|EX!;wXY;CinO9_=1SU8Bb6c~S{0QnO^ZsUvL#6rDhico5u#A3w5cdcLXo1y zl91^4y2ds4caHmbU-vchK0e>?XXba@|9N$sZs(K7{d}G0YrBr9{rmpk|90z1-=7cq ze{mWQT7?^Tq9MLAp_7bMM*V zIOuJ8bOpSFRKE6E)eA7inok$5(`X<=J-GgR0vpji$j$#wwal+yggzv0y8dtQZa6D;{6_NX6S=vphc<-t%357QuLHaz<0|E)5j5Tsv3)#g7^Qc z%k~}l435~nG%3czSM1(KM;Y`0ym2CKV$m67sBz!4)km?&Z`Tk#=C=K4WmxmWn@vik5)Fh581Gko*?*q56tC303h*9_xpM3~ z!28s0%~kOI|1DK~4lv${`B=~DKI2OaNK@?OpFc|Q>(kT@8d!mBm{G0I`q<3~FeHnX--5}xSjpY*_v;GC? zs4n_+sG6rebf%sk}?8_K;@6|$kv&AQ{4=2XU zCT3pJbz=Dq(#cf%bPU`ou{KDg6el7ycv}-aLa2DFr^Rxk;a!@xr~$@1o_Cajx83v4 zR-FKEH)oY4kA+B3ng4U#ckp`a+tXx^(nIPj&z8|LODK|LrKy|I5&Lki*wzJE{lGK12{j^PsJ1 z3eVsr_7&-dlqYs(?a6sz3_OTq-3QfN1rlVG9jP!i5eI2ICVz#e*u}D8{r7+e1!=vo z9(4(W_S@?>x_(CYAVuj;!6C63LM#$@bt*dl>kD)bD!HIvX|z^|=_*J`L`Nn@e&WUf zMFeTaJ*aEIDr03A9sU1<#Erp{d@SD};o5oW(otS($F?JrGQ~>M;Jy0M`)^ddtFFzO zg@*UO@YkU*-b**%qU<0I7(Ol`!BgzI`3rYTlOS{Ph}la&$3d^O+e2WyQ)F(ed^<;(uBK>^S{zyT#xC{4hj^ z8%BOsr>uwEdKt&t`I$feQW@<2za!18xz2Jw%j4Y>+}A{p4mau7w3xE(d2)o}&rc=L|Eb95;YV>-Nd zAv%7I{&Rj8NpDL0MHt7s$5$|ATPJq^ALTqAe0Y5<%j1m;Or=Z5)h5j)U;pg?OVZ$N z?{zqUiudc|7lhF8F8@)T4L3;ESF9)vQiSmH$YTKSt-1V0l3;T}zP)Bj^g|rP{^9N} z81E~0_ba~!c)MJvj6Gl!263kMC+j>$$6J^0_Q`qDcp@(n7bHKRDpZAzcfZM)4dDXw zxwj6YqZ1>)b6?%ach)eDci=BmA)XJ|{r}nUD_n;bb+defB%fVKmyXTd9OiGgQ;HJ_ z8occ+p(9kh-FHL_qTy|j*hIm5eH&wVKOpOTj&UMGn>w$4${IpH|F3iKORDK+HsTf} z4*#i7;!z9w@|Ip&-lp5%M3~OKwGbVu82PPHiOEr0%{bnL3E}oGC+X<_4aUCpRgJMc z-nfOM^yx_3c+&9S{{Qc_GINeW|390?gIq>8t)zO;6Mh|OG!HtP5b*-OVz(kBigLwn zLn~MDmts9r>lvfjxm+Y@;FlX)?~gdBsP8!&JjMF?j=qHV|68GxJ?4AJ(4xUE$z}ZL zQ*4|W;nRsnUn;ecxYpuI1>;ZX9u)G!>dq1uJdxS{l8+-g5-{@H%~et{w}kN>q*ps` z1e)~F(f_xGPgxwCVSNuGjnkz=_xshmA{QxBtO5<*YpZ#bsCcU!osmStTX{o!GK_cO zDT|%(6}$0|aHb#v5RRRQ>AQfd>F@#gU(7Fy3SLk6FVzNOtbe<4#+Wp-(+R zcf7mNr&yKF7n|+9dMZC7aXG8Kc^6fo>mjQpN9s@&Wf%=i>5 zwo(0zr5twuztw!nxoR?*Z1Nm zaQ{F0;73KHf4Ki&?@_qeOXDeFKN5H4OV^IcW9WD<$eCaNJ!6pRHb~PD9i7?#oZsps z+ozs6jJtRDBK2&mC)oWzZibL8UKPXgct^FIpi9R@=9WjN|J>e^qruxLGKKQIC44#Y zYV>7sG`wTX*!$tvTlRk469~Jv$Fh*qLICeW`212ac@kvptucBS;4S7ktO;+B)@ojT z3xD2n>on1rC_#pjwf5hAnuqS*Z~7hyUz_+yIEKV29p}^cNkYe4#I`gq?lAKmZ+V93 zn6mlj{MJcK*yO)v9B+NE^8~|D?Eb%ZuAgg;%>c{etqMJ*OGmP&TZvLMr8tqL!P}8A z<3n}tvt6NLXn2#otQWy}M^vW=z<672Dc`*S;4Lt3jlY}{2^zPPd*b>n4zm1^xeLZy z|In$na)9^lE3Z6XJtad6k3IdVxgEXsj%|7%mtF9Upozro)y)5#>Wsd;Wx6-;!Vd4LRr7|KD>fH9qEpu@Z&`PzW>i` z-ROVF2lW5*Xgp}+yRl%Z2PG&joQ>u|Cv;AEz!fCBYGg3%L7bYT5gp(`iblIFt~|Df zM&vj)sC|!v9`$BW_WyggtNenm*h#;hGq}r{3`soySXwlUKE+;>PyHaXil<5niMzHl z!vAqA`V<=wyz#Vlg%s2E|K*5|JsA113G#0{bcFFK_NwrvnUrZdDoCEFMx~r_*7u;N z6?EyCBGjE4__P17M1%K+`k~cSymhy;DWKs!Y;^w+jQ9Jynw0*3)`|~2Y5?!=TpB(1 zdhH<`bS_~Zz`OtW`n7O_q(9>Mr2*hQ-M8-i3pH@W&QYd(;ubpIhc+eNn7+(Y)r`cM z-t%(&at0l5?!*qGH{#Mvhj$91V-`k!Jmkv5CJl_^-MC=PL{k$RZ?eUc(uvQmEMGxR z^YfL_qoXCYnPX)JrGlJGgST6v?_YR#?Qf7n!&|*Js{+PbA$5d;chM3_eHnmv+w|=_ zYu?#IzlNVm4FbF`{cJCRm$!QD?pizscn9rNe`3f_hSq533ZKnH$9sD3j@l3Nc&eO{ zIPbAU(;G(_Sqp!F2B3hv;~Lkzb!-!sz)b#@*XH;f}R*Dfa3uu4_c3 z@bWv>$9uodEP8Zo_bU*;UqW&3IW%~$^Rhod#k=>{78x|WJ2jM*;rIWN&gblcYj4kn z0}IB$=0xfSzE(Fj5@aB?k}wYNR*^sH2tRLWc>a*&Fu*%^_-k8g4H@EmJ^px`D>~ly z?|$vO_jIO`8;M)+)g;Ph89Lr38sw5#DPg9=y9Lo_#9SjOG^ODFG6MRFtN zM~yrR-ajDj{>1XNH{MFNjvgJut12tiBUAtF|Nld~&2&EkQ|x>i5Ax(Mp}ZgsFR=&A zl2u0Ypp8(y4eUV|Idv%?NPq7|?uVDyw~7|#rGP7T%jetrMgNL}c()zs)CC?iKi^@Y z0q~%Vm8SBF3Skh*LBMD3b#xDsKhwrj*~4G88i{M^PiUBZ4&8%BMbo}-)Rkj84^l#O ze8tG`&8S6G;D7PNj(T!SdZ}0wrUzZ?$>w&{Ud!@RtYEo04?Q~apM74~8Bf_DRinXs z%O%G()G1cs&A1X8-mj|2LNMOj7Z52^tmucrslm9!24v$%6c65f^=fho~IfA@CE6sdDFz64ZKxJNZifjFh{aaa8^p z2R&@dTd4)`-tW6FKLp@y`a@Ex<9jHyW#ZC_xoI{yE^4W0*v=WqZDO%3;%X9O9S9N5j1(I=Z!t|lf7X2 z0%(xzUkZe10=yj$?b(wG@IKsBa%f*B89F&fT5X#SdU3K|zDj0tAy-v864x?gHee-< zUYxKuZDSwEW4``>GophZBfs=}nh}9#8OK{F+xAn}J30<0?!R}{WTJ!h@z#2LjUF8i zc{;^~=PB;3OoO-k>{p#symQIx=b+)u)^ghz#yg0omvVYbh$riY5y1On+SM&BP4(d(MfwFR#2}KKHgkbf{zGw|+P*pwxr${=Z!6>4cOX_VQNs!_CTp9j{rw|5wnC zp-abC-2nbe`~L0!nXcFWPYHqkUz5gz{QAUiQawn-U0wstgLsYzn89a|TnH~IXOMbh zJWjF!58^rT-93qi1l935#c}?QgU$<_zXC6@_qUuaf^HVb^XEF$KG#FYr=eAeo#`sbCy0)n82MF;8>YKmWPFNMd^He! zxwQuM@8z$5@{e`Pw~}75ya(Zu!sye{xK~o~PX)P<25;XBVt+l5Zr?aG9}VvmgB#f} z-pej~?|_%sTYA~|umimPk_N6?@R6V)@y%-`0N$s4_Lsp^tg^ZldlA5Um1XDmvGGud zttCA%BMKewahp+HmsPl`ndU!ny7e>qyj##4B+=$grZJt&x5WMx(V>KqpJHHi2d^vR zcrTq>C921V{fXTuU2dm6=Ym+if{a?0=SYu^=u`D~)lX0=$OSZb`&_M*03>zype+-xBOa#|kVvqBmQ3H63YTRjt8>Hu(TlEeCyp=;% zsxPk&g*^CnJ9n){$9v$Vgmdj6SCu;wSL>%0t*VEP_g1~4aC`vxy>J*W-S_Xc<$ zINdV!JvS6m_m#cyQXd^}?yTmvOfi8fH6+f$aP(=k1UlXwMz38y_%h$-gdn1$8za9C z+>N3IO^oAh@2xW!B!azqi!;*P<#X;W%j1pX*&9Naj^mqe>HjHC)M@bc5@uUM#oLtZ zsDg%f#>JE0V7&9IUQp? zzd1dJJ@5J458EL$Y*tK_WeiZM@0G5B=5+^&fj~*RmkGKcS&;0xSzrT7fX8r}} z|8;3RD6qf5mFhtb_vdP(c@Uquv>E(@)bcyklozC?wF3m-fHO#$CPtB>{v@c9Uooo) zy#IG+^KdKtiJbthv=ZEk?}Rii6HUU*<0!Gpoz+nIrmnw{1kg{dpcb@ z`k$?@f1%?QPd%wvX{CR4u(5(d?2_W zaT{e~&DuxMD@e802!}TJDW<#s-;U_u#>nrQ+_^2o1jgO_=>?TR+dew*PTE&AJGGtV z-8(vdJzY9J^Iepa`}4e|77gA3dNAyNK2Drj60#5tZ^!%MKVZCL*OXEoC%*ao^4&>* zcX^3PIsbeTRQTlBb`fyA<+7h!EPQ(_W^qMf4ZyqM^zysHo5;{?&nLn=KBG5CAByg! z9Ui++kVWFU?Ou(aeu|EF`H-M)S#&$o;hl)+Sd5XMH*a=LxIg3Wy>Mu<|7;ZY@)piZ zv#ZnY{|Ed3+eGNnG3Sv;{ncE`>g^&LythpTAE)BI!J4oD4ez_!@0Y=w6G_+l7}|R~ zXrasz6i9{?YYwRzbD+C-V8d%(kA~h#c_fZ7q&n;AFgo7tD__3fDm%h-j}zq}IwV&8 zbAD3EJ8@qxGmiI8{p5*sf9&P0Sl9R!ONJX+e(&wt4_>--M7M6qG&uHe|Icj2`hUy^ z^#4m~JZN`i%U|ChEjrG&1kHoQCKD9kDb`SKF{S@MK7DXyJeXpQayQMXiYGx{i`Cu? zvByIzY@J*vZ;;e;Z@CJl*r?=`2P>1wP_gu)6TQml9%R|7CSbTklz0t^J6n5NJ$m+2ZL3q;3pjQlKQW3QVRFz!LpKfX$GK-g34$SZA{Vo4b9k{EFc-fvHxR=f!CUTFgzNsl2x zkH6pVE*XYIO`KsIZ*#(P-A8P6tlkR0*VJpQWqrIi z(x+o0$p$ZSf#Tl!Gc30B=Rd@{GxS z;BexbGZqS9dF$b2wLutf^{U_#X8_*oPM?d|Di8+Elk(}EIFF9Ej`)n6Bd;J)5s53l zv1!l7!{~U2$G_FS?<&u9cxxg$c46eVstea3w1x5Its$=d*W&ml%nj1dUX~GtW(tNZ zREPY>RPEeW(xqdE;X>o|Xv*b8JsP}&@oycdcrV>ys)L4iw9qvn*uDML#(m(!iCGRN zOJ4!JO$|riJqjm56@AK2<-f#1_v(FP;L}@;-}+Qe0=#RNpVG|~41>J4aWw1aqT{WN z%lv8S%R}6X#8u5vi@JOS9q&gMy$W+XrI-%yg@}#@jQl1CEd+bh8F%mPg{S&gUBEv7 zkGmvr$Y9wcmhb;@f#V11(J^t`;htaqzy1Gz^ay7AA?W{2Xgnyqtei5%ii7+AV!Jlu z&^)MCi=!4kgLI>N7Uc|5n@=qFKHx#l`HO}cGf9v}FOQRvT{?Wu}AHy~!IDfcF83 zM_PD*_r)}kSYz%m$mH!@@#3@Sc-M6cj9e(=BN`%c$v=ggM-HIlE#Y*(*i1~8>89BG zhz%`xNGEm2)jX24QwpUyi&^YcoPT9>C&;1ZA5-=BBg>fqQRT& z%JEnKAARkZAsXI6+kB3~J4jpPl_=L+B2kyl(C}iN3sbCc1Y0 z{Y{EYhxa)|M>0;#LV^wzLK}W@ z$3tsXs?^}iiCmf4@8HXcwfQBj_H)Qk+zG{LVynzZnrF#vpMSD|riZQql1? zioH*_%`DWlF;1Bp~)6HE+^JJ-m$)*nC0=tt*fC=$HGO6 zmH({X8qnaqXDH~eZ*OImYb`~?`(fucMHugq#mgznTRfNMpCJRhl}6UMc_)w{N2Lep z$(->}iu%&G@bQ-Grq5oN0lY&7^pl@IBtzwkQl;89p%*8MuV!46%@-w>A#q6xLAHrj z=*7uWXSD}rhRlbz9->1JBR_|#Cl2R=8OK|9dE(|IE;=qJZcc2^lkHf_Y^@)o`9xjK zpi4)i@dGutw14}5M*n{QSK>kczl_F%V(L#Xg{N4!|4$gR<3jVGb`kO}xPs)ld~Z9v z1{v~v+NuJ0P_mQU$+jINNRQ`ObuO4<3;Gp;=K>E(&gK`OubXF@5!dw2A=zWUuHXzL-KgE>6$kVA4!1&nvcijjI-fOn>Qn$1Qb zGIaJ3=fL1Obi9w6e=rnQA0T8PaowC}FS6}N$6Fv$ZvCb5&rFAR7@}h|;-B-|RChmS zF(>2w|JgYK64wl{m$!Ic9lB|6k;n3Qi>JJ&ONUO)oAE_|4oE{ZctBYxanB?=XJHba<~ubc}ZY zbAC`;;_)&a#@#!{-^)}Khh0J9gl`8Zr(I@wym5+0w$r1dU@dXk`#=3Zkp}O5qRmNE z_g-`NHai;LU)h%JhVg#%tc!C0zwW+iY8Jq|ZgO$9JZO*tpVW>?fz?~V=VPm2ysLOM zS3m&o^(R&h)ZY$;(nQ3(Emol8U1oG^G{U8ua2$zSB78V-)k1W<$1?Tz9;+T=I=l}f zItnrJbJQ8rn)xrz|Ibcne&wl+eK@iCRfeSTDK?hBAbsj$sT4groT_Ju6=YM269Nt1 z5xxrmw?#w6k%9-z zcY7-o(V>iyUx~xUO?UGdcW>OOm@N$>biCdgRo3J$^O5zJw?=UE>EL10oDY__{{8;n z|77Fyf9byk`hQCr4@$@_@}+vv*UPp7Xdbkx(y#z-klb?5QFf4$^zSbH4m?Oh%lqQV z10-l9VFaOIiqI> zC0M_LERQy(OUJ=rOW1<|-WD`?AMknZPsRKDIdOh8yxX2F$${~1UO=Yc9kXSt^e2Ef zF;`^10XYAE(eo$&KDKx${o-Ju6u{fX^7YwCFvZ%)P8sv&lcAD;VV@`neTm)M#!IjG z$}hqdB#z5gVDyA4`VzZ}iNRs}DFLR#dp)8<5+lEf2g)wDJsHPa_RHGS*+Pw&CrELx zHG;uo^{kI~jr>k}bm(X5^J@RO|8Gu%cf84P9TjiC(mq}^ymb%lPKWU}&0kHy`_7vP zEBJYfk^SQmq$m;;9ty==1-G{(gx9gj0=!R)K&p=b-U7}pg}LEmC}flRy6+-xnUH9B)}pgLmAlBFYES;pMIO5#>B+c$2>WJ`CgC zX{buUo3r$=#0!A8ZPU=D$}kedbA(hmiz6QDNi6Y^2Y5qu)1*9r_aZ6nZ#Tf>#Gai_ zghl`GIB~-I*R^W}rU;vnIJSk_O7j2kIPvQ7CGTW*FyHGf5r_^mjQmJZ0mRcJ#@+jF zquF#G4!i%4+!SpU(k;gFc%N5wx28vj%B}4S7dKG)e={1q_dl;ZPj&ChJo~xP@OGZN zD+b29-gA<&_ZIvx-LnVXHj1b*^__x}?e%>$jl8>G%SSN2B-L4$N;!>^F9anR@& zV>4;sLEOiTO1}aRs{W~8qcs%@Evoga$v%kgK{{HSb8OqCh#E-T3X*YG(suL;QcwR8 zd9$e+(|OP$M29v;ew8|JYatzB%u4X@|N7_dZ`%|=#-3tv8!dj!solZ)Ymla&I>H@q^ z#`&xBflurllFw^``~R0Wy^W>;-V@r{()?Xys7*#Y|FJ)MgESTUe(S>r;>2boPJ&oE zXQ>l<|6kC}6&_@z%yf8vLv&oi$nV3Zrpf~c8J}XWCvpW`@@vNa-{SP%kiO70EPsO( z*T07@9r;3?&g-5Yf$_GX!TZqLcWzX?E4mUy(D0Vt&@Tp`AkEH`rJNw$zR!?M0C-O| zEN_cQB0_ZM{cKKLvYH}ye) zn2f|3%%6Vj^9`Q)5#X%=qV)G>d-VLo<5&{74{pJ!++ z`UxDw93)P8pi0;(5*=^nb)Cy|=xHj&~UOMH$5^T?kuXm~$ZT=@p>|C5%uQJ&bj_8?*)9^jqV&~@NzFbOI;Hpp`v;C)tC zYONT+TfwJG-WuSow9Yee{ey7m%TxajXP*Gnf0o%r8Ghqwio}md-2OKFPn``LQRBHB z^)8L;FdyFXhz<^n{3_L_)lS4S-XPhRoxZn#AG`k#xO=%!(BdG=UsK>c1LIxJx0tfL6<;sR9SrcsDc;|*0-XQ9%%w8? z1K|DR7`Ylgy`^yK$>})&?*d}H+pULT&@8DLoj5OlR9p{@?#iyWQ6vf>ang@ZpA~T0 zfEs^e&r?Oy7A>Z8?<7RWb&UMNw(?vx`!7y!5i394RsMjzdMn9|Z+z3Si{^kt7z~}{_wGvinoAMnm8KXl35EWn-e()KQgpAA=lv-J^V5Z>TbH> zr5}Ngckw3NQ0>{-#4aSRB~9PO)E^!1)(V-Rt#34$4(}pFM>9r#m(AVFE5{jckX-8Q zCtnI-b)cG!z@IB_Kn-bb4zLaBHw9rYJO!~5wEa|+&m zLS-Y^*ouohkC8->0(acF_yX{9JRq8}3HWpKXJ))#$qB10k7qVAan)8U+t>2c15BDuL=jrzUl0qj}KVz%7g6J4o!Co=|R(3hC7xO9U09^!@Dh((6gk zgMLFN99Uvcypo#B4=P9-hZ}=6pn^P_^=evs7uZ38Q&aX@NP?J(#QEsj zDFu8)UxOrOcfMI!#e5s2a}gcJ82JsjlcJJrHu!osK7V&Lu8yjpt^0 z55m2uqfbZR%UjZa&i^~o;C(7`;RY(+zK_)u(D2qDn%fI6u}|Feq1^vZ8!UD_3h+)J zw^TfyV3FH`W|!d!7XXx z3=*dkdn=J`6Z#Z;_G-qOzYrIx;Zw)6+aOrt*OC{{N)6m$R%Cb_E%w)}S60 zp33@o*YRo4qhroPnL~5`+#p>;gLk^ownQr4JUWeXXm~3(k;pLKKWDlrCrCFwZq0>P zZ}kIs-z5ONZ=6%*a|6d)G(0B-1pwZ}S1#gr0p7_Hb;Oq~WavPL*i73$e7!Y)urf_z zT8>DKt5=?CS+NQo?-#ceFSo2-z;t+DKy-9t_lU2nFpT$$Mit5ishxc^ zlm+nqDBa9 zf9KfN36{qj=W&-l9T}oQ8~+q1t7-5)@vA<7>fSo>UNUHScf79lfcM^RIBubQoLJsL zdBu5v_wI#;7Qfv|P%KHc`y+V&|4B!3g%H5ote98(1i<^!dG4Fmvm&55HBorOa`ep! z(tgAJWfF=+1tcz(%k`ni74*#sBQsszBi_undTWR1Sb~vX(N4LS)2jak-Y(+Am0onb zy+v~HyPzn<`gpIr?N5&mVoX_u8z@fxz5kEawK37pLI1yw#)Gm_-3_Q7^xb5xGMWdm z-w2-r_y1!Df++p}p(ze?AK*a=UE?X26~Plbcn*inV2X{^yAvx6dyvTc69<3?1>e27 zdJ|t5q_xtoRO25$vD38j{fuWbp11&s(<-@ej{Faw*ojqqer%N!^Bu9PMs)1Q$j>IY zSRyUH@%eg|KOi0GpDRX>4#(ExUnId9B!IUo4c_N0 zzGzeN-cmHGgobzCey=4k-hB((DR}3;E`8|_@E*~~)BL@F1TD9lbCWz72MPXkO@XJ_ zq)AtgG=TT->YjJEkAM%P34J8PCc#8;-C+N|!GQHV6 z<}T&*)><08GanDxQQiB>h5d?Xc;glv^@H)Q@yVy)owxXv7a8FFB(7&|g*6G9v%<-L z`Hwhg$EvVHaQ~mMvGT%ofcL#7d7Lyc40;qh?85#Gz5id`eo3scPl(ur#D$ud5%$%f z_y2?DN(Tq$&1O2htq>jk82JT8dL9`sWV}Jj8`fL%frx#*5a z=&)<%$vV29^1OvJ4c-~ogzc$##|yj8LBktAicf&?-qowT6TX~iXF_}*3-GSUv<_Ph z_TJ>hmVFie83$EvU9lV9oDllys8t8>Zu(WCwJ3`W5$sg6HI|^`ed1ux8Gjp5qA?Pu z>P3+IftM@+C<|)dEsItst0kV%WI%{(0!}3pWrpf!HRUs zCwBbKabLX(JScr_utc;R32N;O4_xsf4ib`?3WEFpfP$GN$-sk}Q$ON=g@!>f!L7{& z66g)mo}JZd$9HoRBayf$m)phf*wHJ;;b=^;s`n_{;iI`T2{+jjAY>jrJcE694` z_t9gwusuk3k+7Vq_yEhVK~7)drAtTprnNPn(kcD_MjE_xm#v|EVi$hiVuovUJ{sQd zzSUX6J4l0@Cn-Bf9A&qC&j7ru@tZ^RWx)$lC331yN8_Ncs}|J5cys<<-JJmNUbnfj z;&DJ2G^a$eY9TK=-ZJ+0#Nu^0h_XoBa^v;$#U|0G*gao;&Q9K7zU3`JM8__S{I2#K zFEDUl^1?r`i|xC#>J}8r$c~CRQt~k(gqs5FUSskqq?_^Xt^31 z-gUp)&ck@`cL$(hO_4bzgXwp`Iw}X?-om%C(H~rI={mDL0LFXc_4*Z| z0Pi`Q_AV6F42Lc#SaNcl%uc|<}%gaE8JKq0l~ya*axJ0e;V_bRJ~+*_vSeJh>so}OJ00>&l6AS|JT#t zo!w}AlIq?b1+FS+c-yCuDR}D?Gln;Jx4GXE@a=8w;JA+(9q9dk;{xXc`Ip#<3z0az z4c>1qRiYOs0jIJbBpQe^oqOLybZo=OuO>nL-p?7v@7@Y5@Uw{K$F99`PKBLWiJw^> zZ=7HNT{>Q9guECm{oIh9i?$SpK@7c9GUk2=NL6!b4b!<%E! z@CA&ws@($0{r~E#4sXu^yvxfs8@KC`ptA9b{wRQVNRR$?81GY-d;E_8ydR1kb}_6C zg$B#x@#~$?@jgAa$3NXkoY;@VJzG(C;`UN>ygxsexbwSv9@F8ShUoZ&k>Btox5o;# zjN>iww(?uE1$O^$Vly-S&^CbO@mA{jMVF3@kD^XWe;OnY8ocv4iY=&km#rz(M8n&0 zWgQ+~z4elKNWptO?*-v}fH&#qnzNajBnba3qF@`q8#pj41Kf;Gejp4=Z$58lvM(C{=A!6=l9JNaGM4CK&m>w`rdB zVHV^4|E5BjHzjiP9FRUePf{f z|Fl{Y#@kAHC*^UX;<_}i8vt+fPa45?sw8MTQLMlL;Jsm6nhcEhuWP|~(*fQ}+~cb? z+sM%D4?3$`z0n(_^V4=ol+&8% z(D2TCGUq&uce{r(<$23%{2N570NxWjPP{%NPl6Ig9yhmUYpJQ#1lxIibmdtRov+3{{<>s?aOYC)jA<~hfuBK6<%|4iBN|1Bxd z|NGK-P>F|E9Mywl=J72-^PrNkogJ_T=|zcB_Wxu0>yEkt4@$Z}GEW*JLC$&nzLo=V z&|?nV5+2||7jz$#339eV$L1=L#PUO-Nz=WKl}6|lq|~CGMjmkq;sg?RxO4PssyuoH zxzi$C>*{glyZQX{WBm&9hzeag z+LC?G3B03Jklr+SUt@QBPsMwK$VELgygfq|%wfEDEo-GTNaM#pOa=hFTi^elpAPW; zK@yIVc^d}}sg#Jq2c(s>GF_Vi-dcR`tjEO35cg4)I+aW4co#o7eR3vBn#h5~-4(hO zcZ#aYH~Lw9zwKHmIB zbm_2KVc5MclCnYSMT2)ywde{e-gOGwbkXp(@2mI>uij=`#88&E?nttYhXcIHr2(=; zfOn2a^txq(anQVVUUT8wTf;gMUY7yhDmCY$BH77MQvLk*M*r|YdRKl&`GqNIVgeGk zp!?H^K`6R=-!}c26yw2sueUr#bW~vEcOLH+OtfMg@B6#F&3CS&<9N&Uv)>*E?qYqs z1qqVH_Y`~wxiJmlgU&-s@q2gT>XRU*V_tz??Q!w70dn71(Z_5*01C9Z__xd=R zHxWosp@H0|9I(8#T36i)KHid&tJD|^@SeiWn)xn4hEl7!%I5#Wx3^cg_e*#dN)eAC zaowpi*5?kR;~gi~x@Uzv^SQSbq9Ya~zvAR}mt#c6S8v-gmF(ZH!NxoJMw?|r2rK;C-tS9KzAJUd&$foC-9({?{4|Vp#Qhl=DneCJ`_s3 z6-a8)L$4rrlo<(g$pnK46uVE{d1Kdp4Ao(LYc4Fi=)i1fE*qZSM zX-<7+_~&-)`~SFR`UK!f)UDc=XwDfY|kY9lnfZ=M&8 zgz;XwbdYj`be~%F%M$?a?PcL__su6kEy3Aa`g`IapWy~xE`ax-$9--CfcJpkP2yZZ zGF0bU`DJq!I^OrP=N>P0;2_o_aaRQr9(Ki|<6Z5Ywy*su^PT^%LUi26$j@2!i%G0J z<9H7oZGEf2iG6}JDzs^z?A#RA$D5~_E*&!3-^OZkDE+@b4c^yBc>n7Echw&=M8o^g zuSLQz-b=a^DF>vL&t2ONpZ~Z1^enn(5eedsyQsnWA`bedv|s^@w_bmknLfaqw`ekN z#YiZ$tTg#;X(T${bp2$iAdaN@JWYN9_V=6KUn7(b5V}z+`AUhVTY05#z&gX z!eqwr4vq+ylrg~GAZ;j0b?BC3{R*-q<^)|j^a5>FxOP$S-bRCW+2gToRQFym=3{_{ z_v4F#Y4G)yQ;|B9>n*#|RzKeX@Lu=&*DC;PaN+X0|Zi`*NFHwE^Cb z8eV7fy$*%e7jL>ScPBdD;qKlCfA5(^bVcHL*2L=iIiurkd{*H?g&^}?kPbt17-8f$ zzwt7kdN1R6OZ}8tiQ~mSoQRVj-7;zZjrHBzVT?W<+Sfjr{3%ZSXz(sg68-CXOX?%t zrD%BL-y6+>@iricQZ6SJ=c=uA0C-DEY3#NDdv6P33%Zi};~;@KwVp8E1MU&476QCS z-mDw`+!qQZHjLl=6o`&@=a0o#6<3H64DZwsExb415`b90J$aVPVg-g=DaaL35c z?V1()cm?Bl2YzfCl$FPJ?=9|CmJemOusq(P33TeHd-dvE^1tW*nX}>lTUMa|-$~;^ zRZjh~@DvO8|2kspxX?UEB42zO_MpH|U6cpX*W}{I7L|e{cEPFd->Q=!uVqBuoo#WD z%t9EMDuk@gOqZdher|Mot{6+X$t!P zL$7t8hqT8*Wg=VxY+#E0QXQ9b4B#Es84)e5O@e-e*|_p^hF+hM%b?JiQ5w^}}`qzMANMML%+ zTni3Jx6HE5J<|~f6>%=tU4?iAj~QTE;* z{%ZDl3h?$g)AVllToM$*{r>jh&NxU@^Kl#p!29;4<5Erl@1-AKTvZ+23(YSwZ`={; zi~7$p@6a`?!mc+2Wh8Fi@jbj1&g)R)x7+%~)1fQXbLD(Kr9s+5 zgLe%#PKSzjj+hib8s3*6w=o#+#{(BAc)Kee<>do-Pn6|NZCMHW|H6X`f;Dka?hoOe zya4Y4nT~J~Fvae{b>8-SM26Ci-#`E2A8wG|-zoCC_s10BFcSB8r1kCL)#!M;zKGGU za^_F%P2S)E%Rah=Pi`!)G@kCY2p1iN(H%_ z2JicC@B2~l4znNUMZW6R%}U~Am}4;kB|7fxqn8- zd+pAs`Yve>rgQIEhz=)={A{d`4bfqXkzeh6Lh+RV#;>=8rbp~PHGz$H zT0qF!BiYd`UwgYg*-4j<2qiZ{Ecm>|zx_WG_4#P2fc`&%#)BGHAEmq?4NtLpf~!T* zJm`k;v?II*SWHpTcSc5upvg<6hauR-E!_h&X6EM<8Q!bK<0r6WpX|L=hHlpUmS8oVEJ z2boc)SfN6(S!j4K=}{0-oJIcyy%zMBl0md`XV3r25{;+4Yp9L%01EJflnefP6#x}i_8Q|^ZY7D{t5 z9p3v99X~MgJ3q5yk766+OYC-bA<+7fcKH>+l3?(Ns!f+6x^fg zIOss`)N?6-cah{tF_o~bYx)Ux9Ls0p$R+V6=YUbf7#vQR!qE4M>d5N9>`^RynUqG>C&;p z$g(lJD+9)xOoMmbiB}R-ymhrM3!&kCedQGy81J2O>nV6Qa6xC<0p9+4rWbaGlOW+f zj$eBB6K%lkbouMW)CIw;^dxn+n#wQzXb zD>5AD#YxNJFKXwKm~V5U64B9&k)NsLkpKB)#@&0Z+_J!9BiO~s1>x`UXObdW9&ZQV zZ*=KM5f2yON~84up)`0u2tE9Yig%u9j364`6~DvSV7%89e4{LH8SB{i@`B9?({FtR zSpg)-jm@>q9_+on*Z#>T3hNMJ`#O1>b|xpyw2;|fN8wa>G^=M6EAxApS*j_VK7@%Gl%q)Q4tVJwd~ zt|yT`9XljftApz;|MvfAO*a$$JZ^nFJBpYJG{gm^)7ci zeE;92cFvdvm}2kf@d;f{B0=v>?`%8Y3O=zLDW0hSJV^I(yY(&5AgvfXu+%M+4CU7y zZrh=UUO`qgRX-Zd{6@$|;?C=8RiBnauOPYYrCtyPnQsT_I--LMBfpHc{to?xjQ9U% z47}SNBk0&ciWK+TByo@Bzd?#)6QWB;Q5EUuz2Eym1sTsqgZHC($0n$Fi_g`ULc_aq zAA2^8_wbV-$_-M^hva#S0p5)t_6b=ZAwlHjH*>n1RFHN}t#W1n?m$dLcH)Q&71I^J44xMIY{#t2)HxJT<34`shY$GggUB2Z2DH`DDPDI+@WVC1)^ z@W;O4M~vfb-7pq(WtfiFTT&B53qI(uJl;6bNcwd2or~7_b3u9^4c^U%msL>lu6E55 zN5k8o$y^L>kZx%%r}Y2jhP_H_0N!=>?Tvd*g2#zo*hjB!h=a_Z_VdGdE7`fp*2Al} zf=-K<^MygKHx-TLFQDVymdd}4WAr`20f`gZ#BHg16umf!9GM2|XDlmyI9i2Ix=Q#fC|3}i`-Q?Q!*Y%c? z<-THQcuywaoM61|zpI5I6HY4pKjElB)`)Sn}JT>oQ=9T~lBcuCs{@S>C;tlQx0A#Ga;h zb7oSEk4Qk`0!tr+O!c5wkmc4pp4jY?VY)TQ6Nrv7jQs9AuI}G`c^2kQ(BJT=R52ysKA_BadbR?lVm!)oe>?i82Ra#AD3D^!8qQW z-npKO2eJGA(75L_rDCi<#nwK3L6?qdSQYR&;|Bz&kVSw&PZS_tvj$xyRMO z@)nNmd+BX-yzh;+oIfheK`cY!9_s9EXv;#!d!BmwmmMdV@Oeu_$6Sp3NIwPd#F{Z) zL4Mwn#dB~U9Xm)Vjvwm1)mgrR#AP_qr^Alxkp`vzkLRGlyCb&cB^B=vgK4s8c*i`b z<%5^EMxO~&9!R^95)eHG@QzAeV@d+YTl{$H4adO!|BX)u6chp8V|o#<4g$Q79widL zHj|+_U*%fVJkcAZqj%kxYv$pIQb^o-v9+>0?a&(}_S4ZCZKfhj=iY}99c&o+ebBfr zd|#Mxy!{L!MVc?uaXInycKJTyRo2J*W)NLEa@eAG6S67pji{G=4Kw(*aIYp$LNie4tRU(Sx7@Oyu8J4p~HP0;JtAB zLB4l=;Qjyho6g7gpyRz``0l%P-qVDGNZc*%K&_3N(eZ9~s9w9ff}iQ|_C<8GVdR&Q z*P0PGz&PIVWxXFCJi^BNK(>l^ z0v`qX1)d1h3EULO7swPi!dJp~fiI0Ofsf4R&$p3}#An8*&!@^K&Bw<(%{#{XinoKe zmbaYu67Ol=L%fl^fxI5Pj=Yw<2D}=)^1MR4IG)cuZ+N>LvugB;H|8aeK86mev6q;SM??B?*{SjVxFgUF%H zp~NB1!G-^he~<6Qx8m;!L#IK`{mi9!>#=BBSOUk$S<6Wqu#k*A2 z;nz|}`pXw`;GL->J&Em~@lMo{&WCYLyd!m_ePfOkehqb`bwzg)??4?bBJH=pucnSP z)jwUrlc=Kwqqpzl?WrS;7PD5o9d)FBL^B1yiaMI_(P4>SNgb&zc+Q4jK^>_~b#&ux zsUzi_xQ{odjui5J z^YP26Bl%sAzTnNMBe~_ooA_nak*xHz58jkIl9?@0h=-^nse+4fcp`NqNglAn6R0Bz z>#oIk6Y5A@NAD=!m^u>u>Ukb-L>PSdQuLi$_ zIuiIikcnSR9r4%RiNx#wHIfV6j@P4(c)J28@Ve9ykJb-6ybg85^_z^tYg0#@pKV6) zTGSCoa&`xP5p{(3%8AR~vF?#U&14eIFkC7}kqI(77G z*Jd;PeClYLU}=a~qmF*gx^M)qN*(>^*5k&jP)FbM2CVVQ)X}#+Lf`Q7sG~{SWBPa{ z>gcPo#dG{z>gdadCpmaU>gaRD(H8t1>gZEm&Sm^;>gc1-#57)kIvQ6}^ux$kmM;(yd-rr_-u_kUV=J$ zo0aVT|FQSx@l@^6|Nn80sS+}iGS8GTC7q2FNjW5$63Q5v!x5nj4N4>prX&?nlm=4+ zNtz>5MWjeYDMh7z?|s_){?6m``0TsSx&M66`8>M+Xx-N1ao5XzKGu7!_j>R5n?%kCsMQnv+nU6WS}%?lc#>wK z)^j15A0$51>h7mllV+e+*SQ!D(sb17%s9(Snub~(9<|R%yr>25x085K3*Me2aibQz zn?vG4Ex7q5aiSL7E09R21)tg@5m5_1(@fT{r-~JJ& zPz(N4iueA%;QJ|vUr`JGoS!(3 zTJYD;#4o4?-$P9Nj9T!ut;8|Zf^WGbenKtyQb6KI)PnC&BaWgL{F)JQ1hwGDUx*)2 z3w|qu_#U<3rv-@bPz%0^oj8nGYeH9FTSD56S|KuhyGXlGD`+Ttij<04Tk0&zNGYfl zn7U}3l#E&dc0S)pNvO41@4`pYPSo=I6u?E=fm*)R?|zaJQOoBP`6(#@wY=TL9+Bcv z%S%Zuo3tIZHj%bukm69w^O5B}QY>nDWQ6`AZ9^^hdfP5i3~FuAzI=&9MJ+ew@mNwc zYPo)2^PCigS}wV1;iO2^a*nxwnY0zPoNQx@NfD^!$p0XU6pmUB{gVEqFw|OmeM2NE z6t(R4_)L&OP;1TdpZcU=)Up%KDkBA<7Ui3n1!)Uv*)+IBk^)g{^|n*vqyW@fb@X&R zX)|hBYnp!|`6HGc{K7TyEo#9J0uzT&3w}S9IEY&CbCbk3s0F{yM|_Q1XLm|j69-VM z)b#Xq;w#iD;jCCj>_@HB&pJJceW-QnlDHi4C2AFK6Q&S*QR}4X8arYSY86QheIvd= zt->~roy6y;b-cwYoA?a13J$t2BzB`#{<6>7#4gmz<2T$z>_n}c)}htJ4%9k!UciRf zj#@{L9!VuWMXe)on(K*esCC$A^Dbg5YGqH~)_s(io{2#m1%P& zh4>J)G8BAv5+9&e`n!+MiT6=!|J^Uq#CxcFu?DrMPMihAYSfCJ<6J|$idvCFA=bnzsI|53{!ij%)QUJGu0_0rTHy`} z1;i@U3RC}fo_GRxWCznSczIe$3A%wD^P1oWNHTSJZc5%X>$|Lq1NWF zp_#;T)bj5Uxk4;MEx#h+y~MMB&;PT2k4FFlQa-vpNVuv&_aMcV$S7j%K~|n!oZkrc zAT<)WT;TKnI;U(C;U{*V`@G@I@}NLcr;Zw%>py!Ce5oj+UbGwAS!%XAd)g*!jX zW8tmOV-|c1;N7~|)eXk`z^Y%~u>kJ}hKrUP`BR`;H*uK`fcN9gI^h}s@8vrtJz4tgE>oct$s<8Ll8gvg<3KFG1zz?{H_v`?5@Ugc)vz;WZ=YS z)Tw(;`v~)Rm(PD+bnz4Z{NLZp@ASC?YuJ8*^r+RJAsvlU#UG?|X%nRBba=ykCyMu$ z^m;igytA6WuW15!b7cMYfbka4*t{za;9Y;?@|u<56lm?k!KXpblOVyZ${Fea@8`Xa z37r7%l|~tFls`s8W@-Iu=Mu5;HhDR4YR?G~vJv9ki6d;ho6IZw)_?e%Ilv7mWAIUy0oD0PiPv++Eb-DNtBeSx@{jgEesww1_??8Y2c%;XF7owtb6F1W zM~IG5ocIO>bEd7xXCCkS%e;E2t@r~{Lhfi^O4tzl<88y3j`XAR_;d4V*_)RRZ+K@A z#e2-tLk0`)pUVc;!>6~7l{nDO-liVO5=;bm_dJ{(>jFMboOmRd`5oY0?R}$M72ur; z^+$aLc#C^BnZ})KJE(bod*J$pa1*MHI1$k#=rk>q4=HR^|B>wUwiX+wlJi_xZp_i(}chG|FJ>$ zPk{UXS#&uFo{gY6NXArJ9V-Xf1g5Ql8>Bf#@7BXhtf}U(AN+}(v`ySz8xwE_=|t7q z;rmIDQ*7<6c_0T3eoT9s3v!U}#1_*Pv#F3vXi7y?Id%mZGk>Rzr=<$n9`O^RgdUH{ zz^)**xJFf0*DPSU92AA?I?EF~SG~6{OqKjGUlTm)U~Je+%*( z#F&n7(Xd5-Do8;(yy0OViZ{o$H>y~8uQ6Fngz@I8&vk|IK78Hwk~Y9QZ^-M4)iMgS zNH$=1061dzaw5hT#`{F&0b(JH_js0_#2G5&l{_`o0AVk&zA}oF89^#!H^fi$byS&) z3icAK?Q~z_Kp*Sj?TzTr!ig`l+hm8WGxK=6T5t7lt-xPm39FNS9{oA<%D<7r7Js+A z;2R@4L|VQ0rk$o$kOFjg!_#XN?~jugRj}|*JYRGM-o3S=>e6;^_s6eK>5p z*h&hdJIWQh4jhnP)7VIY@lKdnw7wYNZF7BggG&k(BBkwlW$b;) z-ZCY!KH~S_p~?~2VeH~W^5cPAs=5Ko6(?4R4so3LN^^G1RrwFuJ1$npsAGVE{$IFf zcYf0qw#S<=t&brcSAy=V`*+c@_e?sx;qyf(-ckN`N?3S*AYblj0C?*LjIE>9-k-AX z!~neK28;CzJ5wOH0mZ9*-ANGFbE`Qp-b<^b%FhA3w50GQD!>(FEtiWqoP#cz%sI7d8puK4 z9%|3X!S4TE4Gnrk?PbZI5WgAY_jaz@j-7+zpT+Ny=x4q8zayd}6eqs3ssnYa0+?@* zCPVvoRc15L|A&k5evuks|Ng(|0}n$wQsU3a|LOll>F|b+45N6Tk$N!?3-9ZjwPj$u zr4v@sCP>0Pxt%ot@0;z1Vg_|7P>SME)g*Y{qH{>r6UMuuiL4G+kYXaXVgY-o&}5Ls zTWLA$B{uNZw;YEZ^5k*EFZb3D$&)~rz5FNZY@%{YyYO{?p^LYFE zpPVF(GEhM}b5C+9#jt<>fBoqMBRaYRgpMz)qE(P0ba=yO;8DCGu@WsTysKT8l)&@< zVDW&BaQ5DKWR2MwfVW%Dyhp(X6iB`$Z1UjkB&g=2#&H;L>Z`{CMF8*nH>DD~e5laY z!P}PAKe4m-(i?YrQ;#W6{G|IqMaQJKCwOC+waU|NXG@C6r1a5@bi|*!gP4UA9bL3`&^6B#KOC{ zahp1f_Yyxh+VPe&)8L+TxH!4!kr1$u0#*5_xkTSdf|9w5dttn*e-?%21H5G;5t_c;2#G;;i(1fcMR`y-$t+yltLM z?~GVWgqzv@mUq^ zF{|CkJl?+RtPB%X@bTW%5;$Aa@HE@k-amgSF{C4(&|f?i{rCPqcIp3T)8!!eJ54kP z4J@3#04oR0+Ltp6ZjgQ&Nz)pn_>IEc=fNJNY|mB0-KrF5jEl?B?MV`JPi#n12jrlK znxb0aAP0GLEUA7A&LG(fz3Tn62)jXQJUnMlVwNb`7V%r^B@l2^7P~>R3x2$KiI5V@ zRgkra4s)FNe4lA~d^2M{2W`5Tek*Yqeh#WuHId|z2xI#t)_=JfLpt7GpZT@nFs(t7 zqQe{h@EFBgMd_J77T%X64x7Sw2Rpx{;XT;4#<3URo!qRWU#CWaP84@eMLkS{TxD}? zv;p3;hQr)<0KDI5^}JscL50j#6PIcH%NF}Jog$8U4ly!>_>JaYlw41ex8F7Fy1fqFL}ciq{O~&!LvaHS?F;|NJ#_W9W-=U3OsLdFM3BJ zTtRvS`b%a4yt^K$yI+=zfqEyWHuhFyXK&6uzCACM#L3SQKaa19Z9_%a**mj6T-Wf3 zGRtM}soj5cB;mvtBL4F21w-cXp2{6tCpx1Acm7ZKsbci~B-d58s3`s|NMpuyq;oti zxK%{U-V$_p!&gI~c<=M_)5XGjTP5E)7;lA_`LyALYVkKK_;F%)X$!GOniS~R+RRt- z;Qs%U$we37{{NH49JdnyZ?DT^{CkCCp!}B$ynN1L>v4YL}nJ;!f=TUwZD6`vKf@$d!oS{p1h+ zuWPZ3lT)21yKEdZSq^VeM8^@F_ze21@3`nNkM~z{$IiH~_{GVKU;Ca`7xuG#|37o- zHimR~9SXkQ4=yME`~CmFErl%dcVLTMmM#auw>`l*NK7cnD{+|{0V@Y>)JQr7AF-R` zZ9qFgDyS={lLH#0qva)By^0h_*|NSN5}ZL=(J)d8e?hAB)iD@c$VT`aD#OE z6}`>>G9Y~|eWFe0`y6sL;&O9Nxn)HsC0thx)I#}uVV6OBYeHZr*__ ztW^-V68xV@v43LrqD67|+gpSPsBgF_gYEGq43HVpar4G)i;)Ag25BxG-tc{VDBjiU zjx55$+h$}%8I1Sobw0ESl1UypCJW$gy(8@aNtpuWz2j?@>r8@%o<%Cb4buI`2E^k4 z@3uh7hsuRiNWz6%k@Frl-iEf021oXblSL6fs;WRJ=Xq?r-zmSnwT_^|a@l(xqT>Zl ze4`&--h>G-pS@>`*T2yX#;+jFBz@fCmwaV=yoWY=Go-_)y}-@#&+hFUI=tZvCQ-Zt zS8iU2g?G;!BQtpZ-?*ZMHvfOj>5`TX@b3PhkbV*1t?IK)`V=_-Z+y{s65ie_@-AzF zcW>(*=5LZ-0CsQlTSI;BVB@Xp_uW_|Ta*kTe(K%r=9|i}@y@JjC)EkF-tMhBq9X|> zzF%hZzbUU~9`CEt1LbLt8F=2(sJDZ6lKqdj5bpIbro)Q719{#;nhtOH##9tcQp3)*1`Fk4Jq-WiI$h_~$86%UYuq*R~mhz_Pgnh(xLed5H+$*PFoV?KWFIp+L4q{CZZ32K+vQ zT|uTd7AtCQXFa^nAUbyA#OLUw#|v#^{u8@{Bi%gyRrq*cRCj7rzc0b|6C|O5bqwjS z8@raiGKIFir9g)_e5*f-_tjhPNLYB2ACuR@cpHoj(ms%$%6{?YCcrzK>Oi?SXahYf zKCt#Wxc|?5VoNmK|C{AL&OZ$B9>^{>QJRc~;;6@@Ztup%+xyh9h+U8ZnTq&Teb~5g zDgYbrtw-JZueY$?=PmAtj$oYl`ginbTs_Nt_SQOL^k&gT1}ey{pT|^N<=Gx@f(v6h z%pLZ;mHv~x<>~N-pQ%9cUbwWHh=sS_xbjLEZzIJz8s75~lmx2*-X)u22tFJXNTYCQ ztvkSbP1B27c=uLl{@tu9fcMDDUIn3^XsE*{6$lRo8|BhLUioLi|=sOh9NEHixZdqI$7(EF)*CqeKw@>C7JE{VZ2132P@w-;r^`X`%Ts6$B6Y0b!^%Mc!PR{51j$CPi*`ZUIt~@hYaj=i zj63P;h1ozeYmzTlf%*UFDgIpsAO|&EcipB0a!_K)_JWf}R7lR>Yw+~HJdnQPw9DLO zVe(`J#82VZ-713$>>T8M&t#PsiS;VTrHBp>ocQts-g~}IXMTw_6Lqc`dx<~)CwQM1 ziMVrw{rmqTjOj4H>e=k|=l*{+I=tbh)KI*gXG+Y#!n+Te_6c5MPjmUw@U9R^=eq&$ zHm_cF`bw+~^tiBCK^!cxHwHaA^a0+PoSJ3Y0PiQyNeAXmMMI+3AN)MK4||F2-{s(} zrl&wg{iKiTov#nZ#(T1?GWB{r>*4(Z(eW84KHqfPx(EvMOKjh8;ki&%{Qh6+?g2Le z1u?c?VqXk0rbFZQ%CzIVY5l({9p3QUfGFOZJo~3%;jOrH@(GOhsQd@o>8(mrnGFp9 z?@dQKhdOrIKvhq>7N-Eb^R{1~3*%k=ebn3-;Jsj)M0!eNG<11w*!gSr*mx&Zt*yDy zt3bYl_;G*f&WbR=#`|Hd+M}gDthc=tkLYN|iLY4Ks7`P@^V$2P$*1}4=n%t+FZemh@KG)Ecn5Q(9+)#7AMd;^0wurS zB(Xi-XLd2BgHyr5nJ0sWw=x~x@awH8-u%CJ@L=JsdNpnzjCX+SQ`&IC@uPw^e7z;X z&%yJ^X&cBs%X`)dfOp#arH6C@-YO#t8tehyr|*xs78FNAD^fncnzsNO@4%&2!MfFo zWDCU4TG%MZSPUC)13k5pBxBaQy~P*NF&`&Bx$x2#n*ZVR7TH=;Tk)$5+`Se2ae=q% zPPWIJaDqV{=|ko4@s_{m|Nlp?&59=I|L6bzIcN?1el?ndbT^p@VdWrqtJtOR8Kh$E z2ec!0dfcQ^NAL}jzNdHp>N7SF|D@`nZ;z9p%X@;1;ct+RJn%J#x7e>Aw`=+OGa4Eh zq^i6BOM~=&DtpD#hhpR}h~Kr28wHF1r9ldm^UYbZjP<@CeTnGUgcDz(qvtgT6Xus# z>o?DQTN$}x=lQR4VNDhG@BhCxF{I;edl1izQrZ$bj}CA6L3R{x4gTq~u<)jQ3K4+u zesq7*9X{T2i?4vk0^lv8|I{%1xDCWTAQP|%T#)WHy}Sh;kZ$=gmUR^1{q2)%*Wrd} zs8uvDqHqoN5-S(M{c*BclH7^-J@340EuoLS#6BssYVy)#z4QMfh>jMV_|m@HYdFU< zkGE-I(mP!Z{0g!@k+gOH6ZSv%4w$qNB2 zybmUhx5K-)9t(wOc<-3wsiOn%KD;-(>g-_~Xx^P8gQegEX_L@TFZg(ix7(5Tad7q~ zWsX%Hi-r#D@mm3|u*UqHW6Sinq1#%e$%hcXp`Y{0S53#pJ6B}7dy*pSeL?Dp=*Yr} z@5Z9!V2K9i@!l6Y%Q)g40~O@RVPRM0{{yGDzC(=Z*mQmFyg#?MYSQ6N)Spa2@owNN z<;TK1Y{kzbFy6K%Qnb%o%+rd(MFHML!3iZx_t`*s0fAqf!TJAy!3uu3L7Fzp*vJ#$ zop>lYIKY$&y^#uXLk0TJ9n}1p5i^XO7OHCSs(G^J3he$ox{dkFU0ZJPh-|Q-trC6 zF&`(s%c4uVb8VR)PW)Qa^<>fZ7R*%;ZTCbrSydV8WUxKnCZ|R(GNQxCvE3~w?(hBo z=>LC~{s}5beYzYpqp>y)%|W^A3?#5}5Z`1|0=x&=zCW9`2l-ZwH(w7dv9-%2Lmm&= zKow1n2d9Jg|IYJ0Re>K!uj4Zjdj@jQYvosqT|8nSCu+$)w;$N&|Bdg63g%ack=+qL zV?p7LU$6h=ik--a9d}e%um9IUbco=@clo(f{&{oebCA;V@0aSD@pF(ihq0}|#01;- z|2Op@hIGh1+MfMCxjoJ9-O>_Z{tIaV)&2X;gH=c)L{oq)m`wNBJ`s0lYcO z9z05WZUcRjEnoi&;Juq_Sp?&4w|bT56M*-Zy5Z8(t7D+xbq`Ay4q@ZH;aEk$kdFvC z67k!)ooln#6KuTKr+P@deW$>3N9^no9cyvo`w+WC)4Z7Z3i8lBwX-4ycX5|kf{9Le zh~`YTUt$T0x(w;K^60*uZ)Pftw=Nyt)7pc-pm_T@+lXP|?SEC#60RW6J2la+w-6f_ zRWOD7|Bo|=mOrq8qMjY)kOJ3R4wa9q!Uv?Usm+{m2jHElcrd0xBnHxZu6-l(Gh;HGetrT1d@HUnVeiKq>1NC5A4w_XRAdluCRlfOiv2u_@m%InO#IAU)MB9TD{9riU2Q0CxZ#FLxlLQZ>b*VTc zfGc(zxTN*r0cpZCo|ICs#Hw;TW!_Sbfi!tCcW$_bor6@WS1xMJn@wJT_(lBC2;XrU zI|r#A%r+o@Q)jsfat@+H7AHPELV&bd1sN7TzL(eH<{}CY3Zd@ZsflMu2 z7w!fxNR8~SD)C;k_t@k08->%Jdgf4rj@ z(-CoooU!!J1j&#NZvp4|{~VA$o8K@S3vd0hZAakkty}(IX}hBa@fOPE@Xg%Z z6lmK-nC#7#BuGp9{s6qaHGJ6FZ%Jz7h z<$E%uq8l(kuc=OBaHK5s>9C}C!3vVBzcgir{yOzt-K9C+gtng?az}x=% zipLS3ZJ^5gTn`t3=Pi~S>X*PDNJ~g4G`|9PPZu2Sb*PPj2&5UI`yH|Iu2@`OCQFbe z^B{iLxGH3Wmto_*-!ar)%Rz(Xijz}_juf2unkOxZX+-85q#LUhWCDLMaJoiO$ZZXNXL`XdMm3FfA9Z8TWps83HpCBT@Dg2J(Yy! zpsm(&idZ?QUGBFhyu=<3=A~7TM>Uf5oWT-XecGw-q6`J1PV3Ej240ZfLNc2HpFz4C z>0ROimRQN^#XPF7sF1#~P>l!`yZ<*<8H-=LRf=qk_)+agH;4So9i&I?HDo_NWxWH^ z`iPDUocJz$HI?&pW`2qNQj>6m%D@#n6Zd9*uU)#6?Q_s^UPXpOLQ$A9SNRY)5zZcHhOEdNVWqT{W;meRZ z>n*XPhz?nt_^zzp-q(1DdA!YYG!>(d<2Oizj9*7qd`xG1ya^X)9c4&ITq;*SxMBxn zZ(};VMJ?M6(Cj@gqgDvew=yq@jw9ckA-bp(Urp$qtC0W7lGn?3vhjM|%W0 zUK3}%`~O=I9l<#99T&gMeXND~3Q{}T-)-Lj{(zJ-YH!KgM)n_&R+OG(NXIz0!s)Jq zwCgPv)8Q?mqqiT$+rB?T77K6LDbWKk-dcgLX~T)@l}=~20K9Kr|8VpHc$}!G*oZ?N z;BCe^YbK1hJ@JxOEWq2G)8I)$0u>5}RwPP_VdH&y?EX1ot2j9p@te6uEl27H_5ta} z&8G6GCqApgd9#mBG5>l?_?Wxs;&=wK_lSk+Kpy+!9e>T6AswfwJo4B7 zJa1`4hqutU*9jDFInsI=EW8(M)?b0~&OW$@cD$vxIplE&z&r2hwL1l}6sSUDMpiDs zdra$^75uyfF-1WD{y6ak=V`*y6*15|9f6vPer&w`!=KAI@k)`uAbuuWV>rw1VP|ip zJ^JGt{aLT}c1Ltb;u zy>8^--~OMa`+hVyP(d!G%RzHW{7TRqbWcP~9V-VVXMfq(0CG^1Xr2T7fppHN_yZQ; z8>Ce24Ckx@8;JaQ-#_~>xpDKJm*D$<;jeSXV7#lSzh&0~ywfk24Hi~|8>CzEJsqsD z@z%Q6U!dbAM}CI-_08roQOCyH=xXCl$#K@ZVpk2(VTco-1$k3jiVXAp|8FhI4~}XE zCP*sdnL5uB*dA{}!Z*froV=2$@n?c$N{9FCrQ|Cp-ky~6Dp+{`-uJ5-#`{h4nsspY zc6@wHI1S(}a*XUZ2A;QAx$Bm~A#i(3$wO>{j_CM;6QB94J%0IJ%xCXM34EdD z`V35vsuNvn6xhE(A`s#k(&7Hte#5#y+1rE;Zz+kNz9`<}qN&PQcn2(A&<5kZtG0%Q zcXGw}NFBiY%C2Wc{G;G`i{r`9-aSZy>UZu~3gew8G}CAez}uRWTpF!Ih2rO@dJ8pT z6kfp@oAQCFZf=-eD-!ISSBQW z86WRUwI^RR{ocj)=l`vB3mMXJrmaDvbPsKN3v9e{aPLuEDSl$+8p*k$XHmSswp0vE^*;4Pw6 zt2#@T3f)<^>WgV5Hs0f*i+R@$%qBlX{34g8FSvdX8}C)?^&Yw|X1(Jr9}peOaN_d_ zzw~Zp2lLsx#DphQqK<*Xi30wj4nn)x9`E>rjOn;k%GX0)E)a}r#!(=yZj z8hrl$&T+$X_ywt5QLm)U7sWsllzXpLpJ4An?))q~=+`JimO}iNc@7*2s=?laJXu`y z&YY9=D#$2AM;=ami&7f|vPjG?u|dAKeqLbYik*`Iy-Bgr?B5`@Z)Qlx;Vtcg?SJn7 zx1hsY-e<>C6z{KtZS%13&VH`c4$uD!e)Z7i{~=NY^Axy(R8+~dueX6lrOph-0le$9 z?5f}`_Lr6u{iy)&cV@*uJEq4#t55V6W6sYTEVR+>MR*8q3u8 z<3g;ry_JCIu)&E>W0LX!y2(7=%a>WX)h4uHeiwnJR>e`S^;es|usz;!YK-X!UH9no zk5pO(xttDfIinp}DBkS{%CxZXR!rIw3gaz3WllT2CAslYV5o%tJ@6+;4sXNyu7(b>J>JCcp$zG` z++&cHc7S$zYZ)EhvRoY+DBi!;M{8o?efTa1H;lL3>J(aobaU|NmW=>!?Jw=(R%dOX zr)`k*9Dw)u?wz#bEiz-fi-WR>~ zq#|s*t&XmKn#h8$w`@anSm4ALGyXuDQ-k^Jov}DO>0CVnA1B7;TP7C0VSBs@>3NLl z_^#b1_hTwY)vF9Db zxnGV`q1@LCl9kf1bI^eoN#!PXBIG>8FX2*?_N8#_98`1U!nA_Rm2bJPhgRc{{mh{tj9NX-$W>s^^pCDBhv= zt@>Da*LPJ#!gvcU45s1zeXL^Z5`g!4Z@q{j(EqEtx*ZY*c-KrDmV&?k*IKbWtODSD z^!Jw^u`N{SO!DdFm)x=Ob}fQdX5SShmm+?4h0Zq(EU@uT5L&pr!9t1Uz96+jbj0Aq z7e#7+CX>K?1^GZLwn=me{sie~Ma?lMzmIH>ch}uZjOp;6`Vf&t>;G5M;jNI-b4XD)H^l0ck5byp_H`=|b^- zTo|T{g}3$w@pu^T+b6SWcprFO;2#F?K1}`{vb_o1-kNjtkPx^aeZA71bQo{>`Nx;Q zmlF+E$$e|gqe2Ak%ab4Uu<;(f(ENK|y(F24_}z7$dC^r88}AB_CPK74>m86DKy;Mg z#P|5h2Hv*+Fr2ut;ebUP1FyFXiJw0eT4>Am1JbC6=NQtFGIzpV`Oo&&3Oc+M??2px z;>}ZRs)L31aj$`$Fy4YM%4m3-kb>-T0p1s9mt0T3YXfDO%u~D#wzu@uo;-%}4)Gru zI|c9#jaEOXc7X~xzt}tQ$PydxuLr(wYm1jAyCQzQHSIdCZ?Wrt?`%8B_UHcz<$a9lkS}h94=4V8|Bt0R|3ATj z{@;!+2hA_j{R-zGaiJtH<&Ow8^Sy$i+QpdF5c-c)V^doL|XpJLw4!V}JcKNb2E;8z;skF(0 z0Ac4KUU^l*$LXRh*C17(I^_O6zSY)^S1*h*UqSi{8P;j=<4=$XX2B~0o4nY*K_c9Z zWlYCsb+P$>w%Bdy@SaE6u?$^eC(bn*Vd1@J>8KTqclqx7wC63OGNkO_{{PFhLs5LE zY#<3cyBr&UckLV*B^dA841>$(0p5~63S93u#y~y4rPudPVdMS2?rPa(^BH8+Ps`?` zyW$Ww-e)gKJ3h>pVmZ8f5FPnA@d+fZC=@JX9&eGzYlh;}@#p`9=lWFJy8iuP zbVx;K)kOTc|Bph4x0c$c((;jQwrf)~cy{81h4{XZj7qPYRUo3G{65e_gQ z4e_}eeHzAlMK1xyo1D6(r4rzMi1*j4I~FmJ&Peg#%syh)E-N z8Pnm(9V?>(UXTLCi47gz8Xs!@8IZm@?YR&O@6(9`*Wd=pTQ8ILf%JiBpGtLr_rzr2 z%&rO>Xzr5pva_BgLAJY7yW!!)9owGI@NmLMrRDH7KPqIvr<{Fa3VZ$^+tJ)IY%WAz zfcQPtO1pKX4}1Q9W|Ng(U_0yG{~w0vIDr%2+syot;&aSrZ~M2~%MHfyixba7n+5yM zu3>w;d0H6LA=~$HX*l>m8sNQ}4sZ4QW)INp9ZEJf#KPNTXKFBvch1#SwEll@xcfqB zfcN=@{bEnAz;ACS&ff>{=KtA9d*0&hRItHifcK6wMwNs(Dzx~T?niea?CibpDc=sV zqA+<0;`ex8)xfu}*mxhT>v4}hFVAw>TMN;#4<|m`LiwtVlg#5C@LkuU=P&~wCmO2m z%Pk#X|NeiL6k|G;`t62~xBTt@*`xnoN0);PB9xrb{{Oldg&QjeNf(rwHG>@F*7MvC z?*F@XM7V7QIY{XBF17QV6iD$Wv8lNy3A%sP%N4#sx@Fq$!WNK&ra~^b0GdZv;$jyeHJ4AcFFJZOc_yI&mK2ChI-n3_#sWYF0 zHh%Q$bBe>CAjLv)GRGgK4f^@vF?g-*XzW&U1W*7Dndt5n^$8KIF%i&!s{71)gwSSMV zRB~FFw;%I(lg5wq?efR3AfIR!#8ym%vif6O z(ijN~Z?8U528{RoifKMD-s%nEbzT5(&R&Bbqu_bV%HdQ(`ST>`v{LCBxIxlWlX0j8 zcvFOrG>~km&~4k#)7K7Q<9)=j@%B2Wp(Ra---)NwI~s3e<6XGf!ceX0TOF%q??6OH zAWnQ+%cWh6N}0!d>xp5}rl$-Xkj|MQ+F2LF_IMMvEMQE>d!ah=pWRz~I=pq>jcTEI zUzWc`#KL=Y!+;iyH*a&07mWAInAT(`fVX*;vCFONHc*TEyBbH(Anm@;*ahQl=6t*s z?*9+i-z4`9Q=#&?Klp|du!|FG-Tb*}TPK&4A%1ft&JU{lVHYRy`}m3uKIdh*21y^$ z;e``ljd7$@(SOL^gU3wHH1ad>f%NScKGgRdY~TOK@BPJ)4x8<>*ZEb^viBM~ytOaO zh@*HnKikWJg}1;Fvup6~?Xkxt8)3Y!-YvRg3Gj}pKg1=TZv#c_5N*8eWMRaQbNMfKJ1REb(FBQt&xZtA z4(~WbM*vQIr_U$`d7o!Kd+QwU?v^#duf0Fcog-jX@5J`mTO?kUAst84G!x`g{+|D5 zwQA;njR)*Oy3*yK#Syaw(HwL@---__2WgfK?Sq%t$^)FV3eqVr>R>p?L7j23>m(E? zkfmV4!0VwT$ob5L%Ss>zZHn5FElYX;@!pR6*0q@m2^S7MdGi~)g4`rk)12o@s24>1 zwhH;aCk|j&ko&V&td{*OK>lAf{y+Se0f>%bocQ(}?D7Usx8G!DVBx*ng{vCITRQOq4e!A> z^CKew-qulmrCi{OUCj!go{?ug+j6@a&~vTG3$;2mP0T;4qq4Lv`kSthm{ z8}B*m)n7dLz)|0g`1Q7YUbl8LHr@>>o|a|_tcSNUqT>Nhd}4}gQ}vfHpS|~Yl{wq3 zz{mS#Xtbr;;A^(W+jv$OLpn;HC_8o^qT%gChqqyO+*}mzGa8q8vG8sVyFMEpPJ||# z(1sJaH&%XuueS*8&)``nL4guRmYg6DBtd>ZpPf?$c+1LteL4mjq!R5D6BWJD(C(k5 z*H#B(<9$fOhGbh$s82!sK7QqW@ScK=_gJXw#?Ov|ESJ6W5gk)F@$Gsuvhm(F=JCG2 z`a-Hm9)5#FxS2yxG8$uhya_+E7}GH~ZO_p^ueUhT;l1F}#sC!Wa?d0lEWB^>`>%oV z{_#@YAMXDj4e>Td1H2CxZF>+dOo5gKlzA!kCqZ96Z@Hxg@a{Bh3G4@WYdxPM7x*9= zvVz>Wa@?@-exPsnqIPt$&I0lK)?Q7xN5;nc!CtE)SM8>;9NztijyE{*?W|fMH&MZS zaq{(DU(i4o{<)Gg8XMke@a`;E{TIZ~?$W&Shi9>Kkp45} zZ+q25SuO{CM|6;J;*%b~r1Z>*`6c%G9^=Q0Z!j=HQaRXuBBYT0&meh!WK74$c^lOK zOpx5^@HWxQ`)5Epeq`n>EWA%=zt{ug{l-~jGmLl22a+fsSYpqw;#<9uj{?>1vzcoK z@LpcD{jDs(`<2C)(O`i0WlCz)hSOBYY^3An*Cp6n>=%M$8j~hD>dA=T?RU2-^A)hS z*rkTo2%p@`dJR$yqC*iUzFH`(QGFKkcuy@pGtoWFKm|Fw+i9Z3i0v!L_;fjEMsygu z{@n2RPyfGx4sU4s$}ed4KJL{ofQ9$;g<=qlw{vkPtwGXEKNYJ4@UHI8{8}qSfjWsB ztAhaENxSMI~-UGD)fry_+vvQY`mX|WL&LzI#t()_%*!PD!X(# zHs05Nb-t38o5^z7dl=F26em8;aL!#qHq7I_pi?PPih(qP!MS!>AD;YaufcK@!6e*2;RA|+Yhq=NE*m(Dmd&Cyjey>}J`004O zv*qW-#=CPG^{SuLbe6;WBcfvjC%)dTkJe=GXCCkRTW!U2t}<{yI^EBDhUrDN$D3fu zpboo)5u`X-Plvbhu|5Kd_o3CHGqLb)^Zqk?JCM%Y>}}PK!V@o?W1zb;)4yH%f{l0W z=EU!(3a0ArAbw7~l(dE(Y`iDa=3S$F;A1(w?;<(`_WgT&8B3NPUALNfypzx0e>JuM zfA&VmoYA~f>i@v`|I8n^8PQQ2c06~i;P3pO;U4_|r6cJ7z3Fn0#kLu<(HykC-ckZ9 z2Oad5Ai+y)h>r^nOmLn&NA#AbYJ08@6Cp9b&C+c##hcVjT+cFXw2=!y_xzvESG}@5FH#F z{yn~D4+=hqX)?bDNj?@jD>Dp#f<%mtIpjdv!S+k+#Fy#28PTDCLUY!QAE1MAN%o?{ zdpV_Q9L4+7J6>@tyj>K!Vqv@mo-}*Icu$Y_HJuCael(%l$}yb+x!b-wIrJ(CT79;l z8Q$KKJ(1gy4DjwK)0x4WMukdy9`etT$Hv=_SbxQmVy5NWnlJ=%3`+1n;=)km=0OB{%u~OFy5Q! z@Lm?aj&?yBe0xj3!D2Biyptx~dSJY}@7d8Bq~el%o>>5I&%*0Lk9a81#t z#BRS_2IH;ST^+v<;2pPLlw7ta2J(00EBc@ufcf3}=Ib46kN5J{dn10frE88k39ZNU ze@fZZanDkM<+67KqN4{VzJ*#Z2s+c4uOLHmUxahrxR3dJ`KK_b%|2GWWacDq{DmZ&HA5c_BP}_DuRXgvGaLUczdfW>M?CVDku1={5Kd*I39Xw zYs5u?Dod3L-NEq|@0u$Ga{=DE`f1Q%fcNv(=DPEeG0;k5%~sh;?ChQY-tp9;jv4jK z5kIp%D#m3;v9tHkqnIe?d9zs#@6(8mF`W2*D6RUO+rvEGo#m|tsfjJPcwd#zSah&r zDcj>cCw&h?It;|*`+`zvhZ8;N@HV?W`OondjhjKjSa>(*Jr}wI@YcHu1;WKiQmOLj zAi(?PfbCT!A_bcN=)%tla5%AXXUVrY0Pm1VUx7k^_q>D|_riRrkZ#e6yGcK=XK#+0 z#?bUWDiBB`5kK^}$c$|1yjX~@wPyCM) zQ=gQsIq-cK+t1!!x>~PgM2Gj7%gd3pzy1F|t2ZnE0W7hb>2lDjqo?E1B{oY}Z7x<0 z%DJFD1>ZpuUU-IfgOm)nrrQ|ELFW?>?7gT-fu?B%juJox*;aW-Tn^+Q&J!m5@PM?g z(|_H5wHU}CsLv+rCiW70kjgpzvo3)=5AiFv7i}mh#a?17C9-5)3Iys|?N^9%Wy*!`4;pd=V$ATXCE_=lGIY`!hE<-xbkZ#!U2hk=-{&aX-Ynp#T z@#gx#GY1Rr<6A~G;7{yMEbyV-|Ch$qQosQkByByy8cszD6uHsIKF0bAR7v}NKyI84GQNq9kX~SjDLv$60FXiRs5@ph@wr`_JF8sm9N6yUu{)$>QQBn1*Xtn0lPY;U=mj*P>* zw_I7h=fVKqgNZthq{bNNq1lczb?(^xzs-jx!;bI6OPUeCPSYbxPprc3|Gj*R3%0HO z&T`-X%OW~f;KWBh5kBL!Ec19r$L;WMp3cAoY4(at(>^Qq-`;xLbbt{ZKix*^EfZ+j z+m{aS6&L4}qj=XBrb}VrEg@cg2*z9Bg#_&b>6{sw;yM6tefKZD`({!g11@`GF)*B1 z?-nr#T3ML=4%<-XK!ui1!2An=%{{R z?@~6D31@E~I=n4Y2a{2}4^G=8iG_FEw7WFCOh+peMwP)`C^8R06(!0)kLSIprcs)`Gmjaj=$&s|0gi4XoDOSOqYY!EdQyG z=AaAHWfZY;(B_=@RJi|7{C$^p2dP>%$#oCt|E)Z?YJ0DwK;)g7pEtivf^@f8aVvl& zmdE>dvNc#@`*bIQLeIrOmB;3EwXVcoV)yHsa(cB0kV_FigTdALs}^D}vEgcW3x;@Q zSgt`zLUaV-#COH|=6T7d%;zANdgBTKJ_d47;?(6iPbS$u2N43Y8PYM{m>9JPoIwJ3 z2hrheC!AG=;%(?UB9Dc)D`6l5#+&QnHyYmc*@ANU0PoX-KDAeuQ=p8dO)t~H3DS>m zmxRCvq?a|l?sfop8&_yQ3_chGwVPQDD`{inJ<>qFx^8eL`61$$*YGCq(`;~7ZP&?u6tsXbh9uI)GiO);@sk9i#?_%NXBsFZjzuz>B&M2Be_C)-+vV(^eMX~XY zpcb66_{n$t=2khM)lc?k(ZA>yb;}*0Md`1e0Tj8Pf5k zZWuWr9Y}|_O@m7$iud);du6fk-gnTg1jajhzB3K);o0|3J_mSv`$z6AF`_^>pKYPq zfcd|u?rLKgZ_#+IV*vo~$P0HzlQwUI`X@UY{rLhh8-m@%ooCh?@RFY+ek*QtF55GO zjrZ+4aaTVb7iYQby&ciffD_-j7n1fy;>_bM+hrFnIun2XPxzu9VAk)!{>90>@0%IX zAs=+`S7#nAdk4_ry?WcJe-0Z9OIKTy!9Mho!RwjNO?R%;SCW+Jf44@w=F50&Vx2b6fVjDSFQK zc-x)c#E=fJ;5kAbk$=DcNB{q`^iR+rMbPCSC)?O!bct2nEuoH;gF+i$yElRy6nlQA zGkgX~^5ons1+c}QJ`xzv3sInn4IC@HK?SMYI{!S}|685gDX|pfAdXd^%dH+!q0@7k z&e{544@h$lY6{7J7bPD@{4#^=cuiMh4@f0A#15v0v)%*gIfxDsocJ^==Ir+P4<|@J zloEyBFhmE(PT-_>YP?+3|_-VIoHGe6Ljkjo5X5+#w3M{w8E{pd%<15B(;}pk9R!R7lw2MZJx(nTSRM+Lh0~cdws({{r_UmJ<3>k zAK=}f0yjvqsf*Xcc$0u;r%{H#XkS!YhA&XcHu_K>SW>S6F=wm<*x&9j;z9dqUFzgzm!@D8EF+kTJF1e(34 z^LQ#@;oW;*Zaa*3>DD6JaALed;a&{DThKdDCcuUQP33HQs6Lzoh1`nDhO_t4LGL|g z0Pou4M^2tu90NtKb6!AxijBA3y}fc3rv=F&h~J65nid`P*u_cuY4T#qQr5$J6{2Gw zPJE|rZfne&%Y1QiDYN8|N(TdXZ+XA(Ry(_e?fZX%)j`H|1jVm|{=Wam(ry1g!GZpt zN|%E+XkWgB=AcSJer>EA)TUEC0#}f`d{)vb$l>=_(q@1L>5FRYncZ_JkW>1s?<(*& zNE@K9a1P?zWW)`D98|F1PGm(U722S$+}Wdwor4xhjo+*ql^{DJewV(rsR71&=Ym{X|Nmu6wU#iz``6-GT>HWE7WLB%3dI55 zp0Oi6Fy2nWJt=VipY2$A^@DN@WcVoYqWE=eyq_M;lXhs7Bx@snx6V%w)H;KWx3+ou z{1z28mczRp(V>YG-?>Cv{^26#@$Os7_q1*a{s~foRGZ<#{{I6Hq&1r_U_{6A;`~Lq z4YUd}iVknr?`xi;cpEM(*TTYE;Ly{9Fy5=ndT6`1(6(hS;1{I*GsKUfS5-*L5xijs}Ye;~cqztiw+1wP(#K~w(2>%Opk|9}5onI9uM3V*)t zE{dgXZ$;AK?UI`oj^b^+FB&}MN+1M!1QVu%pPn9JUK;}ZwrmD}rXJqz0pmR+&rid< zO)f7}4d9*Qy7k=yT?+KpCTzh7nEyZOQZ0k=?sq#}4-Y4n%A8HTJwb)c3k(_`q+{dV zeN=r0>9Qo5jQAzGeJ;2bg^hQ|#>CF+QmltJs-q1jzSD765gk`Nv)$Gmq-F1|ba*?*+`o+C{dN5c4J^C^*UGEGc%S&C>I83Z z5u>zz8v(rgl{ZP&a zUP@}&XbyUw^TPlu2lJHj_disSu@{Cfj3nS6v2)n9(=;#2lkIbmkht%O zZyO6^J-j0k9UM6EJ?*Z~65q@G65FE}uwuF|{shV2#<0Fn&zbG8kO_Hj9`hlRIF^0rDC?@)<#wC$~mx)rK9S9$x)%oX@@F0FJj}}li(tF?v@z&EaJCeYQciQY;3#@ z?%d0ES5iTFpP# zTWq7l+an|N7m9bOm7gva-k%oE?1%9#XcMOmCk#~U9fSbhypIWnJHhjo&V6fb@&Mjn z#(#Iic)PUMYMTPQYhUxLnqHzpzK2^ZE?8q1Cl@NM=bjuDBYPr#+hiWxo6yBBPQFPS zi%~YQ9^Mxb9iMUHJ82|t$h(bsyf@@}KXQJ}!10y{f1b}egY1vDJ&~6Y9qSKtIPA%x zW$zd|yxr?<|GB+&&GHpGSa_Rk*&qhb|NHpf)9_B7Cg#Nj@ZL9H=?n!tZ)xUduDJm0 z-rn*l;)9R3h!U=3E&+IppCp;iZ>B>1JQY3y8?f=tJiW4Th%#-`!pJz>;-b79a;XMY@)!mV!4(g}}!-i?J(6 zF9Wem(kxN(a>Vb+llRk9XJc28gWB8dB@ZaFT>p>i=*Nk#^6CRVM@{A@Nd4dZE`3~y ze?XeLwrk8&+?4H?Sg#My8PYL1qkq7dHbF`u(c$g)Dd3;yEqSlqGs402f-A@rA|2ko)$jhfAbsz&1BSRPCi@+#(RU*w=44QtXDyzI-GFgi@z=w^09z< zyvzJ&*ms!WpWZSh1`Ydey1@2$M;vENhoj-zO%cg7ygBIb_BlmA1*S*fQ)_Gp%$r50Mh4;KH@uM)_dEd*( z(_7=ktop_P?^<>xtqC0>d0rI^^+I42}YCcPH^@DBe-=3kp|5u%uS-@vH%WN&;cSB4(%|#fy|G&J6OQJ28@v?U{q9dD1eCieP#N^BL<1MiB z-h2OX8j6!Dg_bnKx6FU`HvS?_I@lMSPq6~U$>06|e-a$y{s1aSE{YtqN3JUt?f>iK z*0W>fpnWU-=fPL(&i}lDd_lU>QX!|cAO{J)Ty8SQo(Mf7kd&)H{|~*JrJxORP|lah zPCwR0Xu;Q2r>)n6_y6K9*YE#?y~JK|owWNF&1q(W_?^ytS+VvRcK<&xI&J*%3*%j} zlZ)u+rV^i2YtrK0fAK(CRo}bDs8Q-CNO38$nlBX=Gyf8Mer7%`I{aRYdgUJ>SCE_( zc<<^<{e|NFrcZ?p3-8Rcnr9rau z0p6{pqE9XWyfwuhYY8idKy{;L9-<}Kc(1w>XZ-abuUQr17bgAb-tA0my!+YVflr}!uwMDlXviVYk10xjQ5=fH*&~$2brcBuO&jR_kz!U z0C?9vDVG76&afK!w z19^t^t=Gueo1Fr0pCiWP3({b`E&3j_V&Q!xuH_z#w{!9t@&#$~uf$)#c(;#r9oP*% zkam=ol^F+kZxQ0DRD!d2;{ZQDXpm%W#IGM+91JyhH8)H&VB_5FRdz&CCNZA6sr|+GX-nfPc zeVXhN;y_y1$L`q}XLfBnwXqd$6rq4L$+zIp~?7bkh54Y}?_5wlXn@4ces zs-X4Q#mSUOHV*dWW zV>3-UMp_-!lEBA_fBS#NZTtU;3{;T(6geo6|5!JggV=ah@M7hl^mVzb;TNPA+~puY zkZ!+ct$ho~LA;vI-GbnXo$dQwEn>T(p<_G`QglHMGKjyaLIf4$E%V&5h|FN9Z}S`v z77gqiwEn=1Ftn@J^dsVzY$Ikg#f_bVL{C-i>gyP1xF>dqhz?dN@v&{axiM0o{v7ny z($>OeC-n-lr#rk?X_p|=FR{9s+I_U>P|RCi5g$#iAo(cp-q)s1z90>*ApI9g@nGQ% z`LGJXc>hY1af3gx^NF6n=mEf6#Ue1Q11zyd_FX?@!2@X?x7Oc=@y@&T>WdY?Tdgy; zXydM6NceuxWX&(^3i4TBSN^AnZ>9o>Uy-EZjlwtB6(kRS%-W0#&u~j@1EPbKN__Ve zLfzf|#dym)si94}iH0k7k~8PtD3E7*ym8y}Y13iPlV<+-r-WdS}*{o-$OotIa*+yT{hmP3UyFXLLm4Bec z$rZkPoLG2Ie_xsikWLinIy0dl!u0q5aeNx2Nyjg%M-lQ-WW2d4@beEIX2#EzM_reA)*Y2 zw+W(SE|vId<7=|^meG%Qc13#HFe~-i8@Ie$X3zQp=I{SMveBj^VP}@)-~0dmX|Wml z2hjhEP~@QfEHmUUNZ|_dBIi~m@QngnuC%BkRIRtJet zhK5As?sw6U$jmZs4UmJ5%bU$A13Bn^cbBi;?hwd3`RU7B1ne_Nibp#HN@9db9*Ey3 z6E*kBKI|MMDqoaiGE32n(SFyc4sj~+4K=ShFL{jq4bnufo@J56G~}Q%mqo4(O@@s2 z`=L9YQacNpbX>e!ull<|5~jdAw4t;PU1BY?1%s#~>nPq4(~nE5JLL(e5 zg#hnG%63I3cM>77O@o_l0p7Dt2rFm-yj2f4D8~W3XA}zJCvc$1H-}- z4OIWVoIU&2R%dZDeS^dm-%XQ_J~MkGENK3C$SybyQM`PsuwszmPKmjZsWGJ-gE*$gJ3q9TCLK@bJ=*R=zMLpVfCBHJMHxvb-aAwR`LOVI z2x~t8Z%#Z-e@EVX>-cQq(gW~za-5kTu^L=XTt0bE1>h}qXnqY~Y zMUjIJ^04hja}ZH>@hq$yG}k*|Gu$98dKyJ;kZgCU$h-tOs7mC$O9nYZ0Pxp*7eQB>u6f)TtVIQXb-Guu=8-q8r#1 zWM>qouf=w4hN~b^9n|8>TB&HaIh+0l$#r7)?DV%ZY>*Dx6y5CYV*VV|XF{6}j?p=q zzx#g)3cMq$=SiV>51+?LVBvj5P5Ks$x8=s6U2p}N#&yx90^lw4b@sROr-+ck+gT@9 zwnsyU?&^2Kc;BfOIWY>B*x2f5woP|Jq1ChZMLe>@eqz_ZQdqvJUY=x*_+1WR-~JZD zeqy&#dc_{U9gK%Js^ck@_(B(pUnt!`Ki*;H4lI)zG;EO0En3GppZTx1#7Q5fNypYw z!LWhLJM?JD-CUO}$UvJlHHHD~(qmc4G{ zyDK#4c+>6|UcH};w-^Q92OQ)NqIeg`rHf+W9rkPB0F3t$yt+S}y=MlFPDKN}w;$>_ z)EG~M?9a&;gnByLIreSkJVC}lJ^DfN4 zIdOi*o+cf6b~lZG7bl_=c!%5HQbX|$PS`1eiTA5oGTw~`)ab(d_=Ah5Yl=gl7=o|n z$ZG7`+k0de%glKR(m}+}@ts)wHErzLyZ>W!^GPvfhQk}xF-Rr8wMmLc_uA2qwx39USo9XekxyVnGjy-RZJvC1L?f)6G;s1}QK>t6RA_v79`ZWHNgCsR% zv2u{4_32~q4Dz6s(hhium3=epGXj>_DNdZv&Q>Bc6{J(a`YIZFuR6;b{st-hlBbg$ z=>HGfI6ta99Sj{cI~J^{jy;3KpEUf*dPtZQi};P~mm7V?g*}7xb@`=uOqB8V|4|*g zsKh6DMLu%<68cB%%VsH0R>jfK|BvQsIf>{oeFcfbkI|-s--RdLNetdWlA*vmruyC* z6z>cXw%J&CoBvXJ1mk_Hd6bN|S9rnZQGmC1I-l~#Mk2IDvPALi%VfUneKV&$NQM13iEgOp8VpAVdac4;J7$=n3r|F270qSH%+ zw!URO6xkXLO)RSSQ3N??WJmBTSCE6kG8b&m1P#)1n=#_kv)DOE^=lQ!+jIfaQp8Vb zG>U)I9~vaR#7~>D-^emt1*weapcdZ=0pbs$3jIs$3CX4JpxZR`|0bmSnk9+MzyDA8 zK${NP35nk?NW~~n;GIxVuZZGZ^>bJe3-3?Ddn@53cC(H+`GEAtn=jeL0p6__o~tT$ z6QP@p+8xyZ@2U58=V82CjSlKN1H5xfcF3RK9|C0`_+}g@j6GtPyInN@<2Wzr4C1H! z>9AwRIQA0jSP|=Xf29n=;XNDCK`lO(y0{ene)^Bt)nB-AJK!k|6=Y@iV&!*o%-{c4 zb1k7o$8&Gh{r!353R0c|@A%;9e@<_m^}nxxg|`;pWp^0w?sX|%aQ5~dA8XI>5#W9Hr<|jJPYBfGuXXn@3wHKaKIi^0l#`eA z0r3+ZE7tVx!Nyzf<@tGXF47E#H>yLQN_=y>SNrb$7w`Yw{33Jwa|8|d|4CnZB&T(R z>G8(B$)`<6mD@_)-~0cv6nMvpG;pAJ_n%xVhlO_}%K`G2{Gm8m5*#5NZXihNMf^NhdK>6{$Hu!~a6uw>o*cvBjp`Vn5?^KNp5txH=&!x2 zpw7;GGwRv<(|My!oe9ieoTSwk)1>3KjM?!2M^vEySEk58$vxbIXbxIe zDyfE*gN~1`SPUPrlaEyKgDXgXx7X*T!4k`Q;@$bvV2K@adE#LFG#WbY6zHk|mRPxJ z-ebXFiB%meQ~qce3OO$f9oyN2y~KJR|2*YXAWqtX_`MXD&G9Y4K7-`nvhthr93_U! zK^};XJyhar**kM5Po4f8wDabz&d+Mp8zgUz={TY}eS|GwVh=gld2yv5z-dGo+qA{4=%@JqQV8v0`U zJs-xq_sz^Ee}Fe@rXi%M5DK-`kKR!z!N$AlQ~0V-Q8Cgh#80eG>s?X~Hr|ff3%PVp z&1E>eA0s-}QHk$$Nmu_SZ~E~*dO7M`)h8M%$X-a^uLsZk6{PMG+H_>U>NWgbLC&MV z`$R~BFN!ytN0~Af-q&I(@4$GAzxhG_yyg0a)W@;_Z>4D8*tuZ5^)b6oJn(rmv?O`) zD2%t-dg(E5fOqYhY4#kEP{{4@h}fb6Y`hiEZ5hbV79nj%{L&BmvfCzO<9+c#iI=I` z9EQVN0nu@RN_>kC9C@kzFQ&IDzFdRHzX(~B; z&!xcoxY=@h6z?^ALY1)a#*ajL!gy~wa*zCRqIuR0NCDtI9H15bq#x}68x6f*0dG#E zjTyt^t@^z=8{7fjL!OFB-&8`Oy_)-nc^_fpO~_w6Y;#SRCkz#S?zcB zo?9lQVMY0TV{^d0g0qTL@HS%;m2`VK72^tjJ>ODw9Rn@W8C&&ws!meaq)Zm;&S zWbL4S#ZF_q!)IBEV5YAiy=$y#($QC4!}0S7`GGWb3cS-v-~M?)iktLN6ASP8Sr&sZ z-p3|xkoW)9YnDDd4)8Yf@R?lpgb1Z&441tGc;A#{*Mjj*IMjSS65xIK$bj{d*&)#O zaSlJ0B5b^u>>u#&5)>z)ej%D?f;dlLjAb9 z$R=xv$>mgRyybTs8ZNS%MMC||lLmQ3gR$}6TBJ}LUCwx4kjf!CoT$Wi?^4sfCq?w* z?OFDyV7mwP3evo$zUyG}N2bTSbflUl9i8l>)d2})yj3aiPF?CziQ>IM=YR$l-c#|D zyzu6PL;X7P^wuMzaEmp-djvo6%=8%%>hd!1cvB1R|4)hhBQj)X_@iP?r(OLNiyz8_(xi%Lv-sdfTh>jX6@%4VOwE6yp ze!L45R;aSp(r`G@#^ytf{d=az8z)Yq4v9uJr2ki;z&nL&m=nc&X5$KVEW9N(Wy4^+ z&u^Vg{{H{2pKXd1z}sNet~#q%;BaEvl+CGzXh=Tt$}Bj0^PNgOb^zc#cQo49%QX~o zN$$GxYYKb3r6hZMGH>}Tk~8ABCmsJ;s26*@b%lSj^4oRB%ii-49ha!Y=QMfoX!;QS zc-J@d*^N)rQk?i+)frD_`u;z{E|?}AF@fX4dIf*`e`e|bbtrOBc8&8mnuCU_*$uFA zkcdtGMfeR8u5a7OPwWsYwri_`92BnBlfDcrvAY)ca>#=H|Ac4`4fukz%XO)mTp$Nk zjV)c(a4Qtj>gSa_W{Z8r&bEzTqD2nBFVjW*oL>BttTn^FVrR>)ytg`%BMf)Nt|Owu zgi3tGy{Ws}dg$-}7nOC!&oQLo3)1*3|1VdAn16{C%A`rh#v8MCY(7n{Ahjv*K70Lr z8j82aj<5Pycw3wi;)OquW=-NCzyFsCd0w;vc*g}fo4VB#q4$qf#J|@^Lyzv{O~7A} z8u7nhp#|{vIZ9kwni2}_GupKCzAiT24;;LOs>*+q1tEUlA32BX$YSFyaE9y0RwXWm z8?oO*bWCUcIljmbi#;A*rvDQ=^>P=#rFW>~-Jn*Qbjsli)8nmgcAq94TRz=;i#tjl zZ)s8Bea6)z7{zPvw>55(*myryPMw1+^RF-o&3b~c;hVVY0_aV z@6l-b`|}n}3cRxv?q{KRo6K?3#lm|@V&^!Fw{39^`TRd&BfrRffVatUe6!ypA~g10 zI^4NB8q!f1+zK~HGy8@P!VOY{&uS~x*ih(fa!^OzTx`5e+`Ds&ytzo{5Wk->8gF|A zu<_mzG^y_Vd=|suZG`A>q7t9QJH<9}Df+WFx9NgKr!1)BeWUTX_r6n|Oy3|)6vxn{ zV>qxzDdP8dYd!_ur+<3BM)59bGtt4qdwb0g8Sj!2`tY_duC4IR41xSOp;#MT?Ee3$ z=l6@}QUyrX69blQT5* z|M6C1-w5BB9&g-obJ}#MMD?Ba5`*}_a?i$c5yz*%y_91c;Sl)o?>~(88vy(N1{68y z(x`1ToP#96`+u37n{ik<=%(r?$H!oaU6s!71fTymY5(=K4BSCd+wLE5vw;Y4%*O91 zYL14~w%3=#FG!W%5q^IJT(P^%Le2E7R0!mrqSUtOD)xw7oYRo?{!(r;FT^jG?Uvc{ zW7s=LHA`#X8=jXWG1{+J3enL-CB8NXBM*~U`YTA?)$0Uxwo>0g+G`&nku>SU^cCcj zkRY0L-1j;$cINjJy9+4rzL+HZ&kNFPG#X5>@OF?$4Tkal{wtM?_XbDKAMguO%Y)53 zwml_60gH!K^8ns+MO;TU0p6=UzR0HlyeC)rvT%+ELmy0dHF{#O@s^Ga=xc0dGwVhC z0y}rE81%r#+i8?dRm@t9;qaD6bhuNAFU0qvVd5kD@s4KAz^|yFVFzg{^@-EmK&HnV z_bQn-9r#}_4St^>)u+Jw!Zv|J`ICZiePeYorx zX-g9ks(L)xnFH`{b9pWg<6XFIL+g2fccP*oajRbl6t#Zw`xPA6737Aca~liOXG{+x zesw3GJ@gpF##>%`S>Mbneul%_1<|2RCBC3YDOdg=`th#qPq{DFO+y7)AOCQ>HY?NL zAcfOQph<`3*=KqF=g8ArJqo6T*&Km&l;v_lVNN~MHR7F#)&L6I~(68D1Loj&6 z^f2OgRfQ*8;XO9qUT?3P-Q-|pIJ_4kIzp(#r>1IT?0k!Uytz-EygSTB9q)s)UDvU$ zc42zF)3(s2gN5(Zh5eyqymcw?J~w?Y5XC!kJ!FW5cg%$4N_g*0!?tHDoV_>IjIM%j zZ{eLOxs?I%p3frbKK?8kk{McU13zyeb8O+}Zh*IQ!leVp!RIZlIn9;b53#eiKkurb z(-v)}ZHV8@iXU$2fB3wmNI%ZA=UhL-z5jO<(J@9PzTm0J1Ve55`+xl#Jl4efG<@Eo z87@^>+|T^||D7P(bSNHf(*niG-~OM`y3zlSctHQZkRk^a6x<@8L4x~#uYs}%D$NF;ljbR22D*Y)%wd5JZlz&k(SO&vPk@?JKZ z4GZt2<=2AY9i$tAPstmk5O+lIZh*IJh{3K~!9?g%i{5k?xMH_a#cW6&;Jx4zr(7k# zJLz$N#Jk-gkZPIsuWUB#C6=hW{m``#4zu})UzyKL{jq-R3Nrgn&@S~);tYqkJ)+|R zmH58VG9j^sZ*~Ym+o*LYA8I!^ms2_vxO!d+0{BfOHPpSHm1Nk&%5*! ziucu2E&>+bRYIF<;R^E5z8UiAt(%E!_eTP}A2pX;FG(Uo$%Rje>EMF2%`vKOaD!yy zq%u+f@V1=RvJqMz0=1OsEm`yld%V>d#}>|O&TsY#@%tig!k_#U8}E&!Q?tDjXEPk$ z?-3nNRO0JCpP@l)q95;oXT0^%gEUl-OO*%NvX3%7-ndFd+H_Q`N}d0Eyk$gzcdp<7 z9>qIauY?r~?{|CEcwoF0n}=QC2FY74rYRNRefUi>$IE;oBxAJ1$@xVz6t5yQ1dq24 zSGayn26ziTptE;ylhm#N3GVBy`_8)O8Jw>Ga%+ydi0>g?=!8{jQ3soQS~4kzZW>Z!X0##?#N zuEW{@@8K7>M8W{xVgd^YebS+j%9H#9Z;G+;{?Wsy(4@t0rh)h+Sy~j!W?|z!lBJ2u z3SzwM{R`3YgGzjCCFKfAF7)^R)<(`eIuW&)r`phNYoiT8;PH-qOrO0UvrY5UqGKTQ z$!+HY$$$HQ6aYs4U(o+ArpQ4z?!4QM<{+HdDqgG{bY>_=4qjp(MlU7LAdg+>Q@I9m zkhs~MYxaSl|1WR(kPaS5KYTMc8SejA-`lGD3gn<=PIB8<0=QcgiT!28$Dhyz0hgQ3mmPC-4w*mx`2 zxXfVzpQ|__eit6qzJK{;Bj!?~xoh3ozC0F&!&@EEp+_Y?XUzu<+DGWed!6UU%Vx&Z zPmo5CBoENiyZF6`IxRZ*PCPcW`@KPGMuB(HTGfvz-uY`kb7A3qbIcKWBzsEEP@!P1UY713=M}YUc1)}CwOM;

`qk&3%TwfI<;#bp; zcdPCD^ zAv0mD98{XZ!VNb_wj=%I5qs?X#^ykfgW}Gmzgm?^gdA8DE5%<$LksE@XW%zT&33n@ zi-S+>&U3pN^=AY_UZmV%Pc`fY>GT=5y=!*yn|ULC!jE6Rea(s8|1VhT=2&%`@n(?O zhz>(4@txO9c$z9ne}j}L9u~u4NJ9mgX_cRNc?0wJ|DkIOY0`0UXeILg-*O7P@9eGJ ziQ*k+EFpx2_k3SJJ{a#I&IvN!(*3GJ;Q;R^)%-%gQi#yr>MhNs0PjnBdHKo!?}Waz z8E$}g|J_91SKJ{GPATX#e-<|0VGAB5bsXb0V@3S7vGV0xgk$5qZmuY?=)E+<_5Trw z4o52SRcftOvCJ00Y#9G1AN}7y3D1u{cNtIpdQ03wt3mr6gUpY2$HFhP=qTI~VD+_% zTtP0Q!234TIECW9EBTE87T!Ik?m{r$GDe)_>1~+`TYWUZJHq901-`xI%%s!gG^ilc25#>5coPgAZ+r74$Qv7Pkqrj>LPWXEP9lB_?8+=-tg!K} z`(o7T5Wsj}Z;2y18mPo4@>2ZcEnfPwx1aBgjYfBo4Y>S45^V!AV1}SYDSIh{&d&W-yjS;kK-JysX6}gJSg%|8 zxF$Byha?Fx`yf=~dep6jT9q))1sBfoiIrHP~yYLe& zI_jV2P42r!#(N0`-ZwkHHlujQaqZ{B!do?WmlTZmW8?W`yydn;Mq~oKKQ4HB#yOG* zWw*VGa{*^>B^K~E!+5{m(Q2pG2(z)w)Ff{My92X%AY`k4dMt^*N!)m6C`02Nu ztu<4^#yfs=!-7OlVTLPC+z}m#RN_ls*KJZ4Pe0x^#X@JH^VAO~y7K;f|9(K8>HGhr z$;n63oNm#DRL0$Vo4a9gIc*3&cez;z7_W$!z1=RS2)O5 z?C4xAI}MN63zl+}XB;9zKJ|HJtzd}_Gfqf^`~L-TXJ^U44N`xJQDb`u#JyiNNMSGb z8Klp=t&x5!@n$@TU!ChvN!&*4Ge{oLru5^_87~KYMRa&liO)GyX-3J6{uyL(u+Eal zHq@8cr9VE;FBPw3`UWYqql+dT2j1wfxwf0U#IB;iyUg7@2*rEQnL`2#Z`r2q?J(ZZ z_h9n*|LD`3`r!uYO6!b@7N{V*M4w)=26(fr)V~7by|TvSi4?%QEF$>(>%tJo>(U;) zm^n7y5&J{l=8AEdc_V&B3hsBes$=6VTe)Xn#{O9hx5P#vI^?Oux8Gt>rb#gUc)z*3 z(&6E4>Psx{%mxLP_s^IfZ``;AZ929ou0Id1*a6vlB?aE4=A8dz@AAHvVpw<^Z3&o! zE67~o8uI@Cz*FK;VtgnFa_WzmdBMI={+4pj}VRQ)O zJs)?}Lkb&jH$?&69wB}+AH?s*E>iI2Y3vHJzj(=tj7^L;z4btJ3{r`2@s9_#M=sM} zL3)*cPam0~KHl1rSCzEyxh>N-NGIhBY0|M|vE=J5Ehz9V`8f)#-21SF!*?*=>b|XRqo;3ev|s~7K6-YDOs@pQyoSkUr%Wlg}XWI^2|9 z3zpdRTl!~jiz7m=Q|96I@1vo2KUc1UXOIt99MSIsGf0gT1xt_V5XjL=I5;TxPEZ{%okHiX^immY($49mH5&+>Wr5Cix;GWa7B1` z(ORk-t8&&-(2n-SOh1G4vXiDs$7TMMh;NQ3;0DQ>0`H1FovbL{Guv2ZW8rOaginQx z_xMFJ-p8GE-8aG&549Z#fhu;( zw|^1E#yhScVfXPP>;=9>i3CF|q4HB+?Cv7@14pu|I4@j?}!26Ms-6<4ro4_a1Sa{pI#ms~8 zJ}8|=#`{9qEKPTSw^u`j#>&G)D1D{+=G?c@kb|pGAAG#!ta_0aD`=3^|blv*`1&6z0c!zZ6Y6&U8qWzo;WONLCbhmk(Pvpm>MgJ0XRI_q!}# zMHp|9-WW38iGH`w?E`qbZ|LH?d5{SGWL;Zc&;ed=C2i7%@t!XgohShCt}sZ+JS!0j z1xLSXaV^5eyY3oq+N#1~(@?}uTlKW;;xuf$uNADk<}>z-;qZQe=qRQVpLg=5sI$-M z$NOHRsSw9C>UgK`_q8^SWn=o{L_c;XO*(1?mt9WTLmqEgQsDjIYj8J;_rjJPl2~~2 zR!+&ncn7ZtAmd$pVNFdOz}r5{d3JUL5fW1WHD(3&|D~Mu1K{zN=sa%c*#PfF>RmD- z;QRla=wj5EKiKFRxhDl5$0QJ;X;EBtT5mK|SD2Fl zUy!y=EP(I;G)Nq0mvMw!hC-eK!%+u%uyfEZQ}z6guajloh~H;(sfol!>>NZ=j_FKa z$zw)U?|<20C!*s%mH2$rqdNpx>CZt)m)=%2?4rKJ;_`~O&pfhX{tD9J3{5%+S;xP( zmXa$-I|{sOmOkZ2mssNUK1D3N`=1$}g7MZq;zP#!Zlg{!TtNnKJ1Z^%c<=ObJKz5? z8alarn?8)U+s(|mRRC}I6&LhY%Z5TW`rF#{?_lGdX*AMk6)|3Bi})`MI9d4crZvc4bP1Oz95<{Rnz86fFbYq_&^|a`(jwO; zQ;ofYR9>f!8+gUSaCj3C9c5JF3)ogMQPfHQ4pN%YsX&`v>f^0-FO_0aJ`?cF%I~ea$Q)e>X&xcq?Hv_!AcS(GT z0C>-_-Z(J72V8IQ-fb(4w`v%t*b9I+Yj;ZhIJn+&xNr9X=^<>qKaW)xztSBl`-=E! zEa+aT^9&nrc7kxttH>#ao8I;zI#{X1SIupb=<_eeTgP$BGN18L|3ErIFTP<7o9}$wmsz}hlTgH)ts6z-YVgbe~-6Z7o1%M@E$IB z8_o^zj;>9R6zGnIa&IY*!FzAdEH)3omlG8peX;c=ODI(NV8L7nvO_xF!w z)rcRMHQ#rN#4b*H=0dDzy~i02Z#hKAJ1X&s1j>Dh`bmHGRzH0!!#hbv&bANe=rXMhH2x<@n}##?FonI(k)?-Lc@ z8z108p{z(2`N1@7yoah=6;FL-BV{9gZ64gALJ`<_FLRQ*`M_I@;qV?nbS$9~-{o|% zz87}%8**;)jR~Jc$kQoADaw<50wYAU!PHdF0s~5r)HiJ)$FoN_;BB zN0~eRMfOg~YT*p|Oud4Pc)a1rGo>`<$9u|;CLNb=h>4xaC1-C33cTw(DjuMCyUh<% z!ovIPj7~k=Ahn&d@rLn^t*ummzuw9t@<-GHyz7YbzG(M>$BC^Hr{U?Xsza&tU4Xas z%^GO!^-!p;_>g(^8f?66JKC4HZ($`pMf~DEYfU&BW8=N&zQPCHVIhXY+Xm6Gi%NU~ zvQoF|*VCW9Zx4pOvk|3^w}tK5(fD&0n7%kU!F`e@9r|(UmUh8pyw_3SU00R*&-7L= zee*mlya(M>$#|a)rw{LDF#<`X7JQs2d~MBF7wqDMtLf2-@dH-x&{vPeE|XqtSg|(|b&hH|~ilZ93ME z;f?>^|M#!j@&Ee21p0p`iX7D1O5A`hv8k0J+E_VA*ZJmydbt0eIvfTsvD1^yKiI(= zq(-NXo#PAwUyuf`-u)dcv8ujB;zwf;zw-GH5gHf&mF zJ2p9+^bqm0s`=8MZibzMNNb&hlg;NdTn=(Tbd*tv@6FV$@YOo>=b-NF>n$q;srUc5 zI~jZVEjf+;>wNuh|Aqc{Xw%_!L>PG>eG3KNFBWzvqIjpPv}t1D{WH*W4vcqE6(I!1 z+dOCUt0_=H=FDV@L19FQ+wb;zJ%IO~hzCdD3bJ#y!+ZF6i`i}e@i}gx(Eg1T{6#a^ zc$;r;4<3IjK?+0so(RotGw8?0d-;9&*jO87hQoU~qGK7A_$o}=?hp0SKVpw9t^T-L zfcpMFZc^j)4~|sk$6H8`CLK!^LeqBMCs&Z0De!(it>%W}{Uhr9d@Q`vb1nwf0laNh zmj%LjA9}pv$7g`|lb{_d=YkugVnr9~+kpN*Wm&&G-2cCiJd<-9;GIw#oH4p86iRw; zsnhlW8}BPT`*PS`36W60+@_WaCl!vbiAb!Uv%*IJ&}3zXKyD5 zb^j89I;vl9an1hdXywLd{J)({|J#2aTk}_%blmo0^Dzn~A8*-2fp>Fj6#0R4_;F(C zu@DU`ypx7+mec~g+0+*9h4J1w$5P}iz}r`=;n_#sJ4a+jrEi>iapK++_-p;^Z%m)PeV-koNyprtF^x^XUvJ$=fp=47 z&NeiAD|%R|W8pp7w67GN-ge$n-VNhjyWj0^yKZ!Io$bK%!p zn@Vc9E(5$xN}t{MY7z?7m>e~VY{AA`{OR-E4aMA~I>hh6@{2A4W!TxfZ%tLTric{7 z;Vp{j_(&zb(_I0}j%=nsd-JlyeA3ONq5scNm|dFTW%%FDw*TvY-^L{}H0iK{)Ghw@ z|Nra1{{JU`An5&`EkTdUT}ldlaFF4T7S4fDu4Ibg$nbz zq)NoEt~o}0_8)GL;!(@kCR(q@a5)Io!Am7RhXkSSs95@!*r#P~XC(JiAF<;KuR5YFCYM}O3 zy6MPV(q_aDT2)Z4@Cv(vd=q^t;{>lh!{NOE(a}yNzUfnZPBInr<87W_cyly_dIkAp zjgh_vV!>Aj!hS4r;ww^HEU#;#O?;yvkjUJncJ=|z_^VZ5_nPKLtS z+b48G-#37_dG8D3_9!A0UOm@k+fX$0U`gZ9T!43}X6Z>)fOqWAO+oc*LZFGIDjp}h zu<>sCW~Keub1rEN@$+C+GE}I<#`{&;+Lgzkgj#+SV1jgI?{l@(; z-kUZ&-7y33CUHtVHV4z&-Ay8^uMS2-CoCRk!QcN&aUNX@KX0+=l*)*8UkIf7?nYMg z0qh2;=B~Kb&cHb&CB$z~jpd<%J9dLq6)m{#G7ID3jq0ElpRQf;y194h$9wt9WVKQr z8a|MA5wF-=@r3E|j&PH&q(w)vwX)&f^W^O9Oo8{ya~5hS-iBMvbg=LqyjDwW0C=mf zeG?Aj-E&q)MF8x*y$gAgC8s_zS`*F_^y7WH zeBQh*OR3l1PTeU{-sh*7zV`m8KS7g@G|j`V5r6Oh|9{f1|F8d{p#S%v$U*O&3gqA% zBn3w7YFD=4uyWAT(3)594w8dXXAqo&k{%>-JO@jxt!0{9RXP!J(>=nn?JIa#ce&g9=jlm%>uX?IDnE!}7C<6WA4`!&x_CQ-uOa4e=ZN;a*32gIz(U-U+|7 zalH=1<)C$l4r=k4d@j(;`bGZ?QmN*GC1>kKR80e#zMua|QS)tG7b%#I}8_J`vhhi_WCvWf`kDRAST8#MhhgcltbH!d_OV@mM zx_^i9@IHa)D5DbJ@J+|$>Ff04ZLHG}DSnH31sQSb+se__ZOmUmx{lGL!&-d4KuZz1 zf^?_A`|S^bpD5lZn$nE1@FsCMJcaT0{c)R&cj7y9aS^HIgBR+|0PlkLLO)g=Cqe=O`iAoX z-goUa_QH5;?EiT_2jJZ-5m@I8&i`k9&f+oHijB9auWh~Lc_X`Z)#$ll4z z#ui%GGv0U$)saFaz7Go|J{kOr{r|R$T#LM4Q-8fhm$Ov5{cAPT*WSt3jbv!i5q+p- z&z{}M5I4vN@9^a~ff0djfmVSh0wn?k0%ru01fm4?3b+fb7g#N@NI+9SUO-rYz(3C4 z$KS?Z&rjkn;?Lnv=0D6I#P7wwnctdUmwzt5I6o)fPrgrloqW&u9`P0PUE)jQi{lI9 z^W}5lv*laPXTYbzC&kChJI(ur_dRb5Zx!!d-aOt+-bC&j+!wf0xQ}p$aC>t*aTB?h za_e&|anIuB=9=Of=6c7~%vH&Co9hZ!23I^+IM;42S1x-lb1ow;H7*%0el8s62xm8E zE9Vo=63zn7Gn`4BQJi}@-8t8DuI60CsmUqNDa=XW80YBYXyd5oAaN9N6aLziPNhd2i(`%m^y?49h-*dMVMvtMFQV~=AGWA|luVYg*p&Thc2!Y;+m z%QnsSh3!3C3tJW2UA8>7OtwU}2sS^q?Q9NgE7?rgG}vU>1ld>#qlAxySA<$ZDd8F+ zn{a|~h!8;VAZ#R95zGkM1Vw@@i*`n z@G1Bs_z=7|-U&~{FU9NQmGHCh+^kcq!>sREn^`MaZ?j%u&0vjZ4QJiW>dI=*YR+oJ zs>UkA%Ktx$0?Up6`T6fpjQ<+7e7q zYZ<|KfMASTOYTVV6O2%6@rk7p1VhwAGxOITA0JRp4q#q^dqt?Rv3xf%I zsAZCr>`l-`En_F2xda{5GExM)w%Vv=h?k2aXrb1Eri!x!P1MpqW>!R)k6L=J2VWC3 zP)m2=+9w2c)Y6{JdO%P^Ev??=cL=JerFlv9D?tUd=KId`Cn%$qhV?TOf)Z+}&r{q> zn1@=bZMSa`=AxELp^hD44r(a}-H;|IqL$JcmkR_1)S5TX{T@LcwdQm+>k#BnOR-q^ zEAc9(=+oO*Ygi%Xmfnyp$2(^So z4hIkfQA@CGP?;crS^}4NQwjX2#qaYpjlhRme9QMq5_nOISDJebfd{p?ht|3ixKWEM zZ;2^^3$-|pZr?%RL@kcceZvF})M6Je+d*JQEy52qF9I8C;fwP|2n5t(jeJo=z@rw6 z)tm$B&CAO0I^4coBT;YUzwNa#c-{wrz?e#l*f|AJZr1v?Y*pHZv-Vdyk| z7`6IVzMa7jp;oVGzaIV*YV{0lUV$G(t?nDSGWY@1`fvod8sCpv@Vp)0hg$G>65oqj z@H7Yi5w+mv7vFd_9Y_3I)PleL z!*`+<{HYYa1GV5UOYrTe1s}x6zdjf407V-X!gkc!`)k;auno2RtDf-@Tv5v}$73a7 zD{AfWFxp0NL9N}U-@*vasI|+OyN=+5T0TvJ9fU2YbwOlG@G6}Y*<$S83g|HU2oU9+#5s0X@Me6<_m>)*4L@Yb_g=>5*YQYZz<7-e0em@oe1hwGjCh^t(Sm1R&d=+ZlJr$^n ze~emp_SWviSEAN!sBsEkfm*k;zNO+Hq1MgLug&;}sCDDcyY2XL)VdyXQX2mNwTjlN ze#DbdtB^m>3txs>SBKrW@TI6#P;iSAe;>8-1K!l(OHeD%yYv(O9%|(Z4&d>3QR{No z1tS{IXqf8cMS)`e~S&iG=~I&a)Lioc0k=cexk;%}f>!-w$&h-H7^@=;@gH~RmjlfI4N z^HD3!tz7}1hgzviJu30JsFlJs%!$8(TFE`!gZRs+buxG7UHm1~IuVlKi@%6k$IX`8 z<1e6AlDuFn{yb_W4jtgf=b%s)_#_mdi+V$3T-H@!=FH{kmS*e_~WP*99HxOpM+XL zi!ze%$51Pf|5!IZ5w-TUse9oQ{=Wam_&pvD?Em{v%pl>a2A)B}`~OR}*|THKAmv^N z#KA}G?v<92PmtbDU$ssT%pm3U9CcoX6QRKa=NoQ~fE%Q|)*hM#W{~H1JH~wjGf0h3 z5lK-CLZHUkO}NP?*!%x)KM_`($y6XcM*N~8N*~JPWAFbLlN#&@x{S9$+KK46K_$M4 zkOVXPkM!>#^{KU3T0f%U1gRbG^Jj_8Oh1Ff$$xLANymYv0(_lv^W zY*=`Ij6AR%#yjzZ0vYdT$|03j0B-|c!3oDhM2Kap_m6!5@7Q$_sgeNipHeJsT>$Ur zopZCkUkrib<7}$uF2WwMKd&W4?YC1PMInAtf*YLq6|i@ZO4ci0zc9dfN9>vr9rvij z*D0fSP$ivyyq!g4KYs6}VF&3ciA}xSnfZ5+6Hk9^RdZj%q6L z9U6SiG1g2!-fxQvFDG$P$J={x*1GzSkC-0s^%j9N=`decrWKJu#@mYmZ+MV`;=Qx~ z0V@{X#(56>Fy5omt3X@K|CYTT7l zfcN(hkDasPL!h?Ib3Vxm*m!^F*d|>qr9f&z{7$*}2{y1{a@+bQu2)*f7ao_gG~VM@_6_8dZ&rd#-Uz5Z-6&JG?W+K|9@7BQSCLM2A7p-hKL#`nAP~Z)3_Mv#2rb_W(;r)D?^*xMtaPtKD2C0iIw>;Yc-g6_D z2?-$VMRbe>1uOK=&sKiHLU$bB7H2rwbySA6rRxESrb zacY80|3Eq}Z$3>rGSZ}F_Z5({_bv*&;o}%6-VK|tabn^9lV|igjQ8hjmgEL0$|xXb z6yTk-%SvzGW+EiHWx>fIaC-}MJkA83-WF!Qs~Z4#&)n#AQq~TE@Y{pdr&VC%-3lde z%f!i(es25iCwDiDlz$O>bD}f;pzicM#_Ru49UWBS8|*!@tyhWu{=YWCtD!lfmTLBX z!EwCok>(+$$NRiZ98Egf#5SBT{QY{XF9qK4`63kWo$c`)Sa`pC-K`3bw`$@H$kW@O zCmnaPgZ}?eBYXd_ClMNw=luKt+`V=Gex(b%_jXM7*xv5|?;~yb!#$qC(7EgDx`HOK zixb?J@7GR+D3H<+zp|ts(kEVEXK#gz1{WR)GG70W>X4@rUv$l^!@IZApS`ch=B)na zPCa{js4SKd`mu@W@lF&|ph<^ckl6k6S%3Tge~ME^{sHv=ffP9iK4FRGAWIPwVXPdK z9pKyt-$8o+@C^A5(#$>~1747W9D;0oPDm4>Wv0QmOhNyDhckAiILJZC7X2A=1aSYK z%Bc~Z>>z0DRQN?%HS8R8A;ix6?l=qS6XI8M`uR#1R_q+Kt%PsP^{5cTRgk9<9b2iy z*YkRr__}}bf>g6(^VMAq)N>H;!>F&KHv^cyL3(nJHXZ68wSwA@kt@gm3cTSX!zkXG z?E*qrcyHt{V}<*F`D0#t;0EcM#O`}+0PnP`SCcQu6Cvob^OJP|@7+hOmq`G;?`L`~ z765o3*I(=2;1dLutV%Tq8u!4gd|DFrYz%nIMk+-7R!gth>esLV(|>s6Zr%FLjQ9Ru z9in59N_=M{uXp2Z>0e@vPJMs*#)RF zNAd1|^I8B4@0`Y;vM}D~%sc)MduJY2Q}_P=qcqSwkD5#KoaVDhDx!``2o)iX(m%P~$*4iYzYp%Y%@e?#idxKui?o%Q_54MiS?g4o3c7JIFSC9&Cy9mEP1!*WW@LHk^ z?A{i|E%Vrc?%w%5ZgDphII4aY{)wCS#50W(LU->wyME~&jHbUAq_YtnH!<=%v10SF z2i&ydEn*$9ym}+{4N_diww?xQK8CL#aq~Q=(h+Kr8mDuKku9G82KFz z)OF5jqaE)ur|Z`g*I?uQ>1RIk{AtGT|A##asL~NocC56RNcy}*5Cz`wEhRGEZ3ZD+ zXn05NwRVT`mTmn=!uw!aqSQx#_c0>pCoKa4bRmqdzZBptx;xbi-o5Q6wq$exyxFg8 zkr65hg|@lZI=h&o<2^|1V!ItHQ00uoT_}B4@>>WU@6*KXJ0`g0=??FHM8_$N{CrPF zD;x6Bj<-qW>i~x`?Ajam#<4ZsK8oSpJIc$6Djgi1o>n$T|Mvg%-1h&I8|eS{Q+N=3 zPm}CH6|6d8Cvu&D`<39t=o-WF<(! z9%ShE#SNYy6*ZL<2U>?gRhOBaPPC$XklxrLho_q3=4D8n&QG&g7b%Fo@^$;#Yhb=y;bEHF2hH?KEG2#Eokl)SU7|$D7mB z{ETYpU?rVU{ZAS~m;dPC!N`w;t$K%rFzrk1p~+KHtq}GB={&yL#G>{YhQ~YB_W@Np zOnaLaF9uuez`cnSc*8g8$#^$9zZ62lJM&5N5RA8}#0=>J=|@E`=)4DbXO*9d4`U-h z9^3GCOaSlw>Yjyg|9`&nDF-}3D(-VT;M5ul^2ck6Wvw@+}f)$Zn`- zYl4pVMSJ_$+RFpx|8PYoKYWn?qaz0+zbv!f6Qb*A$NN(bM^p$46&2*{$YSFI^BKN^ z#8nScr-Ru(8M(a`Mu9i{Gz1y%3YHu}RJ|zJxCnK z*@N*`|8aWj(#|h)!*lcKu0i_j_eVz_Mt=K!h`AL!wBsFFt+sNbG`4$>ncLi7c!|jH zcptlFL6wfEH5zmJf80Bi0&n=O6Efbpo*@Egc=w0PC&PG~RwwR;@%~LPp8Nsu&hD&! ze_4P4S$^B@_XYI-f+eovFy4({+S2&|-mUTcPfgE-Lg#fX@oFmQc$emj$d8Hqtjt8> zN?$SU_nU|A-eyt*n$6yvbcc5yqQe*?zbb;XL$D+5ct6_SFmSDfis8h?(L_1^eGHE` z?f{iK+S(7mZ*Tv-|4%1n%zvd3w<&SnzaHcSzxG7-poMyhQfMB8ue&nkL{JkC8v0Vst0F3re zIFrh9+56WE%>QrW)Q=mh)(J4Y2iX|RP^CjAU|`;*+HBAuCF1_YoAi7c8Sg_~R*TT^ zu2OJpg7J1NJVnC06Zfch7A&z(zdtI(0lc?Fy{=aUOYHcGF=bhR_W*Zvf)BtO`t)&K zhe{YUGtTnTz7&0l&7BHw$Vp(r|3KoB7cD-#C-i#ir0uOp3cTS5CdqielFbxH z!`tFxdp3;s{BO@lySEu@hD}BQ-Zt`%xVGQ+keBB29!t>w_j61+`LAo2j<&DmKm zVtF+bnqb>!R%D2d_r@(9_?=JY%)cUWcZ8?Uy6~doU1_aT5XjF-cX;nXbYSJDx=Fum zk2vkc$w)!_VD?KY-rlNzeU0r%D8suqZiq@9ZhN?t{`UW9EgOCP9yCa-|9X%U{AM)S zgS4Au70^6r`Q{yOYk>!e&fVPw??DJ5Z%9;}0A(oNcyS9 z6wTjbx(axZRcqOxXb(nFZPxF^XNBL{BtCZ@1CS_c5FJ}E^0SaCvNbtK`xQHOpXP6Eqf~fM^Yp}(PIiVLkm4rCsMFCBUoJ;FAf3oU zfj9gJIvH>1!=xM<-pa@NG~p%oCpQ!6c+2_(*Tp!nz2$EBeAozVvF{c7a>pOwZ6oT- z1miuGzCC6&z*}xMY=N(5I3ylvoz~3ci`us;*qDjeUT4NjAaOgbbZ@^MLC3q6{|4@m zp#a_Ct%K-zj*;K4n)&zko6?TAZ>iR{EJy6)Ex79ga|Vwx7#{Das<%|>$kZ5kT}V3K zk~p6NZ}?SzGTs{ad$MSFGkJ+8z<6)2@FrD|Ns3OlV7!aC`IpLa5TK*c1Z7Ep_oB=% zAK=~Fu>~^Sb^!0e*HRg$)`de4N^pkhW9aVv>G6IU^MZMJa$NAzJr>$s=y*STByt~d*D|*CtPh90 zwcj=jkE7#V*M+~}ZOVlALgF|t_GV_kM#no*h;w1vbNa)(3(;{HBfpv#fj=vaXvdp( zCg$|$!#dO=?_Yr2tnsU38Q#5dcJ5T^_{i;C=W^}u`Tu|a{pt88u*7muco6*MDY6G0 z{vxD`=0TCkr(V^73i1jed^_C#m%8m4;Qx-#{Fc5pVxl6;zNL zR#)=WF};McT!XWhRT7~q?iYRrJE40}g3J#U_W=R?RU~fF^N8JYCg>i-v3Z{lyT3f$ zHAsgM9b6dsb(VRy=KdcZNaO0eAM74PMT3-e@k7~i9me;d%mS)(9JnggdEykQf?P;} zH~c9zGTzyK6Uu0K|9V^e8OFQ+#UKgqjl@mHTmbKn_pHt~>45kDmakop+sf%Kw_?kzWK zW$6y@&xnr882M=iKQX@4O8XXjNryvY_($vp3Fom&=d#op#>d;oo+=&5dhXGx_egjz zpuijcHXs>q@1Mns(eQ3#SLB3uZ-eH!?||KVDNlLb0)Y1nlh|1cO#&npQgd<^;O&s# zx@s}NI|uLPzzX_*Cf(n{Extr3p+;0nk_jE}_aRTk*_?UtiAbE0^(UA1e)I>@l#W7m z0e#YRhj%}sLm4B#dcU1wPxxrBAVbOx9u)q@ZjkIYbuYVN&&==>B-MzwRO#Tb9xX`& zH%LKo!cKuV{IN?i-t97JN@#e;>910U@g6YzK*D==nb~Ui^_J~hLrX+d!TWz}C5NZL z;lu=wNLNLGx5V3f35o#kWzu2S!?qEj{eEiJu~X>p|B33~mXojH#2-N7n144ew2txQ@Yi2gn@qgxy=salI!zdz=4EWCjNwCkmD;<@^eE zZ>=`^EQN;?-+6A&w*h#+VoAQG&K(Y!>`E!xk&o`)(aV1%T;p1ZH$&p|A{Nx>q@vf} zc`MZpPWy?`9o{L3j(m*#cGybB7FyAc_qq>3FT`W9-8;7P(T(5telz^`R<>#>RXR+L z?HnG@`rH50ao7KEYG8@wrSKs5`_*I*3Xf9cOF!R=qSXF9)8)RR6$9`gGXxXpq zlb6*PzCqGlfICNxjty={l|5tO1Ja2+6nMiQWGCZY&i+Od4R2MiA_&IY@umDW7;l{U z&tnS#-pNBHP3N@<(AQ?GYHfhGdb4jkjQ5lqo^S==U0oD0Ph%4ivX@P(?)!pXL7w(i zi2pt$iYFj(F3kBYbIs@#q*d5Y;UGt4y2JY%qQeFwzghyv=2xt=<6Z9VmFs+oivItJ zMi~@p!0>oSMQc)}qjA-=&u`NA{}Q<=@aDP1d6JCxaqS`vG`x9^itT{$W+UDs;l1|R z3orQf)*qq^b<%YSQ0EJM`^^CFCe`?-Fy8BOJms$fye-PV@kXs6LR?2gRPJ`7<8Aj@ zDtcqC2%a40UVWX5P=StjA$Ld3A%VqohqnWw;|fN83n4?VcXqVnZ7j4d;cXsv1!=J} z=%>(b#^2r=+7wKcj`0INTppzF|0Qx!;LYvVkV(e-nn;*B8s2wI=N*CZmUi9h0lRli zRaGN5z#y>&g-aH9l>ZnA=J2gDZe%Y8J-Qm3t(Qy9C6zQU25ab5h{VWf>wy#@jn>r5YOEpK?!^!+0Bd36q8snVk2< z`2pU8(66H7h6G4g{&Pn?!26VAZa$3n@UPYZ81Lp+xTCj!5}~!emg$np$3g2km&@P-fNt)_^^Giz>@+ ziP-g+;rst6*~?VvNLy?${3G{o|Nn23O~*fh21$s*gG6y^hsYjeC(pVB&4W_ZehI)H zRHP9}>i?ssj^F(Z_8=3xzsO$hwTD_q9iK_|#z89vqZ{G*zsgR#l1AV`J35sEFSrmP zaoywRb^fD4>bQSR=Kf6y&HlOxZ5K^Z*59&g6Y{AHnMY727@g(h6 z?7HU_tS(c*A3^m5!;5`W2V|%>M-`@D_f2BY}+fhJ7#f(eSRQ zQRjj2e)rvzg!j9<*|p;UZzssDxq8MPV%epZl@IXV(7ez|4d7j&DSf>b;2pYtZu1^p zA~aO$7Rp(JUO`^oTfuYUr6m3n5+@RKSMXatdIjk`nWuD1n*Q*BlEAu($s z+LzefcOTkJe59g+9D1lw7$?K1+%1_bm z-YrXStmFQI-Tz-%uy;OJ_X&o_`^d#0s&sr^a>TglB5D55Pl31K_PC>DyrqnG>!RVk zD@$`ejCa_y0SWJF=vv7yfVWkE79=M z%14AoE95UWWMFoWU5-}nFMxbG*Y20Tcd!h;r# zEM5XHu@d}oJNOk{acCYSVsq&vyu@0j6_U2tpJ^p-@C8dO&e}BG^`bpAcfaE#9(-a~ zw?+Pe4)7pVk%{_sz=KBHHiXU?6QPiw6+(G0(3jX-3f;SBe8up4khrbStMN(2=u7Ol zF($R=&i5$=y=DgP7d|#7su-(aXz6-_y0&l z$6KTKyVauC^mn`^4$+~7k>6>yq&2T_v@fytkHzdVnyGl+;-hKX#sdKik2lWSh&ml6 z2Y2fIsUSru@Rmqqb0p&(r+?HK4ewti&$hsLD?YeQn*UqlSSzyt-Xrq72gdH$LreNz z&Ut_X(y}%8Wi1Kq6_u`$UW-#6b?^Q{7A28Ods{nX&?u1+w9@#@v z8oi$gU_h$7+XjLgB&cMn@(#dzpY4Y)Sx1P_&xy4QJQUFJZr>76P1qobpF!e8%v56{ z*wOLktFzWyd4>M^{|-cl07iaid)n4ro~9jdQ`Z267An5p@|`bGpmSy&!(VTC-a?&@ z)SKlY@`)t8g(>hBGYpy`;~k!%ZHR`q;9*};81JJm(@Fh*{w9|_!vJqWu1?#D2774J z)*ZTeAL1aHyGID{>}|<-uy-fGo6j!%*@d%2Xd658=XyPKyoUq&D$UPG;p1U+7d-5~=;XR7z_=S<*J=unv8D_K>C)ur@ZkM^RYj50%Z5w%HPcnZ0PuN18 zj)ea6@b#9z{XeS?)>y_;aAF&(1 zK9KJM_8@)tFSt|D4c;L2Y*vH&|C!(N8NR@S!sSH1ER`cdMbg>VG;X6e zNavh+QbwmF@t2UeUGp+OEI)zXAYI7Yr|oD%e*@Aph>nXG`F-lIQ}o+Iy9XIvRI2g5 zOGO2FrOz9mafIP3NLml4CDQa zIl&#qdr$T$B{A5&>!M;~yX~Qn#HGi0K?OOFHBM3&;9d0VPWT3Zw|v`f!o=+`NMKIw zteq7)-Y<7n>ySH_Sj(&{%_IRE<|GSrVymyG_ z&JWJUKD~w8pEcqe{r|xQX@4qp)R{|Xd6NdDk`#E$*xq&~zQ@vFR9$_mRyfhStEv$YNx@OEccLx1|be0#+hulxo-}M%6LVGl^}9CPp9>KMcD{lC^;>U6Ad$!#!7B3(|Dpuk&Nw~(8Rw`^wGJT$zYwhOq! zcyE<^PTJmTS@8PGHGsEhu2lbauzOpwjo0cTxc~2~rn*oM;9b~#a>fGS?e1yO>KqmZ zU6?ZFwq-}hn@>Ae%lV@S{wxwVdn+N{r5_z{PuFJ#&^r3Vn+MV1g^^#R+q0{CtZCog z(t4QP6GP3{TaJ!Y1eruJJl;`jsMEpWaAG{9>_Os2 zD>>0Ts6s551NI<+Ng`>9W#hC;XD$H~B(|iv`QV7%t7_Mp)n!VQp z57G?OxSM~D2$kQAd>dncz6WVxvgGFHG%5UDByN)fZrf2Y^gT$ibf@e0+coI!3=&y~ zBu0Mbkp7N{WZIY5a~pdVI;nXeO)g>A=w?aA@Bh0GQl+CM%ITflpY#9n6nHBa>yQSd z@b=cTUNH_dym#To`rrm>PN|#JAT6A;+&%~zq&7X4G*LkUG~s1yy}L0Eiu%=*16PnS zqNRSD0p59w9`QSc5TTOw$9`)qM8{j>m5dNeq%{5p64%~panX1by+O)xsWUOXuSs`! zt0Ow{F!GZ~XX?E7gm%0~r}eHHabY(|!9^c5^smG*Jl>sZJyhvfFK3&r44&8l?kz`w z_u|l-5@h!ds2W^=hPP<{uW}ggbM_h}yq7Ip_u&b^Tix00ngRGgx?_`i(1}-Z(CUYV znlRpHYYelu0=ymi{c;1h5Ft%7#j6j#qF0dq8=tp1aLVA-khtq7R-~D>pyT~pJYch~ zvliXq?T6@KmiX`dKICN{beu=~3sRbqL3QEfR2+~t`83(pn9T5a<3>JHrz1_0UFXm7 z7Fi0smDafDk?~epU(Sw(x96B@3XHc_^6o#ox35p1%LI65O%zv%vk;(@>ry9Ix5q)F zR>?Qv-P_6m*55k;-aLMXFU}(nq1O5MJ4}7(c>f5R-K@tWgKtLSBo3B3>C~X(y>s73 z`}$4vhxd0xhc`xkVqc=qd)}qpy}uru+AeS&dqBE<;S2VR<+F^Bw|)y%I&|9QC@iI8IRLWjpc(DCNAVjf$h zC5@Lu;y%UJdW8SS^OhHTs*lJA(qD1HiRdW6$j{*uPio8$+VSQ!uzq?=lnVFOHy93Y z{l@t7e-%7+I;5Pn;Oi}a=l}n<*>w98s327+JVNMkf&O30|HAqiWdandSdcaHBo6vn$JSsBme{l{F?A#JUP6Q!qY%q@B4m5^ z;$063^ad%neDN8LBni9?5;rz-_}hhF=u51KilpiKKKdJw<{>)7F!H;$P%%!^hjtHY zi4gm>HHQih3epf1KdZp_OYE#FbvjOa&X)eEAeAZb*1V+hm5g`2-9kPzyzvfG9WdUn z1&c{|Yp5THh5+76{l<@RFD5`6>T*?QYT_UQah|;qz`Ln*`{;a7K_>I|Ci>0~hob8Z ztg_Fb&{W7V}l8yd#H$1K`y4iTf<*5h>Z6NyVpEuc*oront<`% zUoA%3z3s|-Y`FyB?doRQ)TRL5|BtV@t@ktz8uH9e)_Mx}0v+$=t1q51ye@&?kHoQ?@7tU1fsVJgM7nVZJN=y?CF}6R$S>EP^IPV6+VO7J z-r^d56B}=wqFkoe3Ngl?AjwKlr6Ymp{au{&f%HTr3cS_r8coP}C!H(hM#J0HD2McV zOQZV{65i+7jTKb^-r{?mSRgq9w93eED(_hwl>A{<#sJ_Q$-Ur-A;5dc0NT_4ng}rk zCzommqvOpv>ou|)FNyyh^d}DLP?ox}5gqT3EuOE}WY8bpT!@Y#jQonF-u)=cq#bWp zEx%#&UMlczdGs^HaxcTG3(T z2b~u+7De+QEvbr`YT!Yv3skniCrE8>S6(*(9<(~Q`r_#)_E2!*?xbnZ|9`hs%rF5S zq{Fo|_dV$US2#X&PqidM^Fx?^jQXONB%)ki9Wu?M8M6+MScGM+L19;CrXs&se_tb`i>od4IL zz*|2RPx^v1Jpa$Gz=@#Yef7~2S-3%}tEeX7T{IAK%pBl7*xrBBtH&PNx51(88Nj<^ z2}dQ2_ucfwuWta}-;|3y^Q6H1pXYm|{0(%xQ?K7RTvslMzlp@H-?n=+|0p`%9OWNR zjBwH)-bWD~oEZ6;A8q#aAEX^`*F|Pf{yOXl(zdm%RYKZ&48O!)(O5v0j-oro+L?bQ zNa_@L>urnaB)j)|&1NAqyj991Y+=0p{QXH2Br&BDXc@rU1Lc@4)a)DvFcI+O68B%NZW;s5R8-7zujc&IS%hgW6k_ z0&nfvv-in(k1zKTK*M{U)m#ybci#F565fa3eYmt5;NASj^g{voyru1uL{}z&_xS@V z%V4~dYg_iV0=zp#e~hgz0oz+kUJMdfqT}8E<-*#jLlSr#61Tug_<6ksI^J$!{!N;_ z^f#R7Ky@5FG?wY@J9Eb4bw|s^-lBS^^iD& zs}Yy;?a@8x-nf#(yLdUeJ3+b`(NTes-<2)N#sN{Zd(iF8n!zGd*cYUu_T;DG6nYuH z|BsrYPRBE;bA8AET#(kKz}qD4m@gUcoo|0iqT#KQ@LmwcJGj1<^aW|x3CVhHfVXl0 z$JUeM_7Gm6MlKcL9nH0=3C27524T+}SYl=7_C`I)Cqf3(@%R1B(edV%ZCia{P6Tg= z#Dy&2{w^PLG2AKu>jAy+SfhWGhz#XI2%(s}7$qzRJjx8#0N zfOlRhTaM#9d*}i;ORfsQ+ka=YBYb+RM5D$18^AkuRjbqcBqD@w&8+Q}LC3q*tUgr0 zUJ?%>aW(Vv9)4v;$D6mn$)GKl{`&t8L1ckJ`|;`-QiG&Tfwz%dt{&OFdA6pDqv3tG+oAw&kT!q*N@|eqSlX&6 z0lfDI${slT)E@dGeS+sEIKB0w?rb-V_q$gbzlH(c@w@8P4#W~6{@K;)o5j%a7R+O> z6&aMmljAAT5IEc#o0a_^c}5LWuSO>BS7KxxAB9^#4yg zx-=YaGQN8^w^OIX!{u1!pXV*KDDXC9mOf0zn{UWZ3=QvlYpvSh*_&I*sm*Zh?LVJ? zlM%o>&HQQQ9`HEv(o5pv@&NCjJGXknySGVKpIGz)y!FBkzxFspgo3wT<@1z6$NOZL zroNeu6rLRC9{PSdY#zFMm#AI;bec$icW<*09k(#@TU4^qqdAOr_kQ+aKCfjP_VJc$ zxqFozwC^)~?QIl6q)JE0?dj@)0lOx)Gum`cMGQJZ5uGn$vusm>Xw}%FwMHK!9N9?p7j77pHNJR=R*vf+bKYGiB zqCHoLP$%a}_eB=y9%No{eC*fy=E`m)ZuA{LPmLnF2U*WO6OWqcF{hM94?oZ5|IuNB zk)M7Te%aL_+C6AF(@ae+6ZRRT`FX9>ECK&I# z#}bqz0p4deXhvzJeDq2v8!v|Ni!kkYM|KVd-h4|%1?ld0TlIn^!{d!x=tY%|#DUDT6RYFk z3DOb@ydgV@Ph`C92g+s9@LqX??<|bBaV{qbZ`VE0?yCUr%ymNVi@(@I-LmDWc!2ks z_a=)C0p3-tFWQ6w-b#bV7QfyAK5toc+COOoeg3cTK4+(f&7}DV5*On0&Qtp(I^O=f znUd_D%%{8ETYW@F07ic0J!g1S2(;rJbzCEXzXE%L)Z*1?pfpm*@OU5Ve?^s!x`9vO zZ84<&-+%&dyxi6yGTu$4M`h6PPBhaDhVc%Q+35qjw_upT-bR4;`|F=vM1R{uK7LF# z)!=%|qPJ#IFy5&zhg|po-bU}u0u$B|Aq%^dD@vcx@tzjVZ#0o(!doJ7k9e5NDxag{ zZJU#cJ6FO-cX-be`=etuMt((3A*TcX504YwD5%ssyON5_iJStXwsn^n9&cPaKXp2O zoaulcNC)n%Pl31D_^Bi^-uy`$q|xvm8IiPs@y*!_Q0|3Lws(7g=b|Kl2{ z(-EL<$*hw1_x(T0LYZ!V1|DQi;X&5<^BTw=q?RwJisnHPA{)c&fCurh)$W5mXr9z1 z*?6$TmQT)`k>wyj2iWF4HwG2tuhytd@D;m&bKPP3z=QO*k6d_T84ih#HWAg|qI-~_ z=&|WBBfcsLB<}ig<4>_q&^<`Xi>c^llMJ5T{+{^|9a#A#EIZ5Tx8(zqaV>y%sY7Y|N$qfG1B-mP z&ogwq9fOWK#uFA)Z9?LF{qr@6V6ZTK56GEsq`T6$78QNdLM)tOww2iT}_K<1J{o(?|{A9Xwllu%bO2I=WUd z^Hi`e>dnX2mY@|UPT{JKA#q{@Rbr>zwxGtVyPG%PTf$3sc)vt+sAA+NA*xZ<8cI9f zX1m)>FFwJZ|3{6y85OK3Wq7=!A|6qtW3!Fc;k{2u?rlPWw@Oa~vs!^w-_fgGRaJ=R3 z`+xM-jsA~(K>u$+;X!M1e)f@?bX{kegaL2|soe$Ir4N=^_65vGt-unSnVHwa3Mxp;N?w=tAoL|RDd^Uw-JGkf$!)EwP6Y9R!U0M!)Y8%Xln+S|R_Be>u{xe6MaRjC@9g z2NfKtah(cg_zDvDHkmpdEKK`P|2bl}i~{e~k$UxHytm*!YNFvi5i8aYylwG^BFT6wg%xX{;msb%-v#4sw#tKq zw@UY`x*GuRF#>n_V^IPmB5lih9-RNze6DdD#(Vo*zwJ_hw@Fsu=dEYMp-ry&yBmzq z@qX=8T{B=HUFC+v#l$2zt(HT_J8U4M+JdM_cX*R^gk$7K4ELXKQKKDib%9}*p)qXt zj&f7%sq~*@c)W4d3RLNkbavD^{+QGtK@@ne;@19W_crB2m^vEXT)dxOz;aWIk)X#TdW+gh_ z?CE(854y#xOp!Q$xfdmUdgyrTomCOoW}-@Wc(Wop3^4NJTzG4P(QexDX4XviOy|VL zJN{<>#<=H&4BsF<-SVC)9sWHEwZGCyc;hMXwi(#}jqKj35mstwcz@S8q6XvbF?W&( z*WRCE^KnT4Z{Izx10CRb3yzVbswseXPqTtJynDNAuhJ_cfOk}-56A1h;gDO6{--T` z=y;cI+g&lLC|u=%#2pr#aQZxr-v5_Nju=npDAFC?w-FupF!H;Xrr#ZVop!wA_GZpV zR8TRTc#z~h(Dna8|9>}%IvqjTC0c*q|3_=t=_Ajjj?m1GavrOdPh&4V~U zoS%R_=yH4$X^G9f!|ta5&L9b15N{p?{r@mWC_eO29CWU=wNndt(8a)a*~fqfJ@{SQ zxH&Z(%6s)#bgwG92d&5p>RRzYv5Fk`Fl{eevH56 zpQPP`c0G{Y8F&GEiH%x(y)I#r@!uf9<+9aNqeIDP__=E;X^FL>z}sP4*(x&L%v&4u z(eVDJe{>4Q``&>b65bjqTKeJuZ~ajdUM7II{H*{N{>O39p))x~@E4@Mifq^y0r2L- z^ZrZ=4~JUBtYEFr0p9*^zvRN-|NA`d@4Exw zy{b0=Xi@H1>S`D@~&jOWoH6( z(eQ4$-HCev@K!fti-a4beNvsvW$GdOQ@!nPFybRy3P;~)`E1!s%Q>{nG+x}ro^IlK-!+R&9gMg7= zmrVb+O{;0g`>^->i7QkbZ^0#2NW66T$?*L@F5(_lI-2-XMZ*h7?!BA>Z@ahG*8GEa zDWrpjx8|JN57@o!@x3JXR`O~c8U=XQha^p~g8sijIT~*aW^d!q=2^gaKTJ|dSqbpo z7J7|Mnt4BT!nytI?;LczRaTy^lwwk-I)%gq_1%n`N=CDYK z7c9I1D##UcANME%56an^A+?nGCA74#^!?fsL}-jBi5R1Xeg^5DtEscmoLm(-u7j8N z$N_Hj1}WfBQu6yl^f&)6M|5E2XD21JLUNe){$E|`4sQ2HDk{kLV`g01IEMEi++_}P zs&xEzJFNDng0!W;dxNvae)1B_yZNyR8s1Y5#v5R~J9cdfhbu^yt&f*T0lXt;C&h-8 z2++AG(JV`VH?Lon&0>JJ@vn+WS%CMzcm4NEJ&DlgLnS%Zv*DZ^$fZf})s|`9T0PoFo@$D3HMj%qUE7u~%_T^kjR3>2%#ahXG` zPYkQk-Fw9o^@x49=@0J_M8|TB{I0Khz%o%lJKn2A1_#~ju-$uk=tG|LJ&b?6CDebK zDjiZOxVH@j-cD^(|7>rS8!a(J!#l`$lyvs?Q^X@u|G#jAD?}aOjn7lcxGV&U zlj3y~6A$Ac>m~dNngH*sIgVe70N%dqHEeuj!lB#CmgaWeMX$ZR9&lF*S14AI<0{TH zx9FThuf5sR&!}q|)8BA{tb+|BKj*yg z3RLO1zM@F_@BIINw%c^~OVIzXrSKrP<5yb9{lBgI239l=S~&Yf9lrlRnR{w4TtRl< z^jfX~23zbNYfCim$3gpU`mn+cQs7fjKNV0xc16VYv}`3pk`ETuj!dF2 zvBJZflcLhZt3;8wP;I@y%69Z6mfPP)uXRj??)D)05goi3`3-+Lr)YbK_9eD_;Y{g< z1}Z!#OGry%7vsPGk6WNlosQ3Qv$;rzn434(9)T)>V+qgE&ZLuLz_B@P=5HWElXw^q2%PR48)v>Sbi zy`jU@y4_+?l_nCGeI=@-Qj%|(Qz6hKaKX6Rf)E=<8A%;K{PK5 z_7;0o9oI7V>Oh8XkfK&gQKh4O)@i!%&+!&}3cR<7oi8TiJ-TCr84d56v8QP;-YjRd zLt*ze8oCuR4^)t6HrX~D1P7#j(o?jJK?Ql{?K*#W_txTMtEC0N+iRz|>gq>Ch|^l4 zplAa+-U)8a7Vjsds}>@0>gQhhwV0vfUHoC+(-V4Hbcc5gqT>cee)XfLBTJ6cj`xo< zCw06a?9*Fmdwli{?doKByeoc0P^IHr#L4`rNYa4RjsovZ15=J$-Dy_a^p zc@D-JZ{Wr5|8Z@Da_b8_7#?q2<~!PpZ97#A8l>^-x=Oo@2~gTLo1>dSgT$Is z?JZVyY8d+{~z9EU2$E_TeT30gJieIapj=*|F&rt z2sy3Nbmu{D5FK_H`Efo7JTWpwy9aGbwrx$c!ETV)O9q#jct8G1Wc;EK65H1CHXHM%k_~;U#9Oe90 zet`G4O)?WQ0PkDp_8FxBytBD3H9q_r2JP5pSYsQ5j<>l=#^>){d{yp9TvYz|dqLaK z@h+|J`Zc{R5nJ zM!q2BM1i-5i1jjZ1-Z7lcL5sSg|)o>Fy1qF!bo`69PD*@0PuF$G+eX=oZeDzX=SYf zySKt~FH+xV*(?;{ZaPKrF&?1Z?C0wlL>FJUyzoHDu{XQ&sFxn7H~%T-3f>~ z9l9)u@2|v?p0{wMz3ikt-}!k~WbjH{m%(ed_f6l^QW5vqEJ#Kph( z7<8Wr9q;tBES~SA=jQmdY9Q@jMnf3?L55K#iTojG%-cjWeO=p_;7#?q2 zBy~DEW7w__XOoH(2MWC1AOAi>#@qFH92*+mLVZ==VZ7TTt4Me|sk^3i1H74}l~@PB z{NKsBe)~XG97H^MXcFGNEqSA4ZVK?e&U$L)e1Lc9`)EJo|G-=5vuz|-r%2UJBu;rc z^~C)Dz`I|+ul(7{#dPQ1e29(#jQn1WzHP@((vJ76$7;?y0odDH$?b#t4`uo?Jl+Qf zsM8_wt}n^u{NMhcAy#J4|8Ju3AfGo{%gG+}*~*+B&4X~wkM-aucE6;?`@{YJ{bzkw zmV!OVkIto68n+N2-wj>bXYa;AUr!Gf!xiMo@AvnF01wLb{^hTdNrVJM2Of`WpzlHQ zjE`xLXnd>WM&fp^{rb*}4}A~v=%`(F-d$$8^Pst}e{>wj$nRISG~~2__6pLXaRttG zC3gQGmEW`5T1A`j8>G@+s&pLVFe3Elkd{~%3cS7T_r#L%z9%fshlcmP#PK6A-r4NG zcEflNzB<1VK0zv_cwXzVGXc^Txc*YIJPx|o!!{}l@IF*Mw=f#uJ^a37STukLv5Vf{ z{(e3>-mVqqVy}MSs+f>CZ?2N$wFBrCWJt}W*cD{(@w+<T-*W(Uc53x2=CjfQum_D@&1 zLCREh4uaiVXLx&8A83#^hdXkQSQ4OC&5ucgm2r^!Qms|+?(Mb4;EYoMZ_Y`}8_%~8 zA-)7RABn-|muxXm1_b zcW>nv6!iy;Vt&Xdspx~gC*9`>?}vd^DqcXeYrJi6Z#VS^+kiZ=6rU%ITCj&=&j+n zG5QiaE4d;@CP1W$-u}*K5FOJP`IYEzD0e$f`yOPPB%9x>J=hf_PBC9eD&-5qpFzUS zUZ+Zjnij#4XAU_L>*{}0dqn=f;Upy92X8Gawe`_$0UT`=BV)+)cO0p3;z zmVGJ)c&`zE&dYH-4l2BKZ4Zq1$=`$RE^vc%$YoFGfdPO_lTp!Nd7i**9dP_>d*Xq>u z48O$U(ymdZV_a>0{Hlv2yj>~q-fg__pX)8`!mUDRc%KO<5r)4Yo$K@63YL|xq~ zxc|RUcjF=Vv^PjAdk#vU41I+C)tA8# zwYZIU7$5KCz0~Pw`!5mQ-jQm1a(gNIG)7~IyCobD_`UXIt*vXkVZ2=fuUL2kyj%Kg+fm2tk$68JvlcqRdRHQ?!N!m{``*))}Q~KpXTbFar=d6$J_Vd zVDzV0%d$$i$r9-`&Q~TxL`9Hn6{r}Df%>Q>#c+kGgiGL1ATO3!B zLi3=SjNbL|1gYbqC}}`icn4<#4@mb5Wb?9ZCqQ4bp1Mzg{(t6TeFr@Mw^(y$D?I-% zNcni8|3(;;SbRFk$pXEC^zhy!yXWKrd^{58<|lO9SO&dw)_cLDKE$|Y{w##|M z7vR0h!Pzo0HVk@pjVJnr06N~HlM`-k2Hf}>B(8e&i{6nj7t}_e&wu2+%>G4mhqpAM z11rD%CtKc*%+ii`!TB{(qZhF8R!rSmpLo`T;Txpp^&V8|NH>XWI}%5#AU!DX4*vQ1 zp9|7bMNcKr@V=UAvmVA<*6X)7+#so3OIV->@c#9n@pu=&`_lWnx6%RLT-Xm|^LU-Sgty*+!nkhFWd-!w_r1mJBH()sxwz&l&ZZ`J|eeV`_CAH2O) zXq7Yv@7_A%?Yp`?!XTx%NW*pG=y)3(nH*GZ;l;}%aYLRC>!6qDcsu{p+5g>_{_r+N zbYSJz%$hl(lteq;=Wdi_Y#YO#|2sS!D~-X|FuZ#&NS>rhhp>4Gui+um?(J3zyaO-n zvLWL=k+Me&4R6n;76lmZuajasVfPMT{*1E(cxM)?J0Ayl<2qxzSOMNy+Z(yy^Z%8X z%=WDXc;C8CyfJn#3^Fq|&Qat?FHRoh%?L{7bKy;pxGQ~=;?1AY@$Nr!z2noEB;C39 zGek!pMt&{rUCw%MX~#SDS>>&B5>yN)^e1gt9=S1o?fvK%bvi!Jj=*1U`TPF=|8BYI z>bIc(_oncmi1nS)WDnZTEw6y)L1~pM&eZ@9y0~-F1NNXNjWJigf+Kc;E5rGhgD*(G zCTtXY1tv(Vw@pUD@BeA2Cu%4I50ZQ7np)`>25}$E*p@YizQn5VrrXxJ^5Hp^zf`$piOuhLQ7dXRW|&jhzxq(|1!>$o)6h#s4h+A< zM!j84m5%9n!)<0aNK3321>XCUrNYQ~yI=b*hlcmWcf38k#D3WIgtWw-%!)3X26#V` zS;}z(yN-_c(A}Y#2Z3UAx5SPkIz}+^6W%;ONj62BUgFvu@R;Fa4`biCi0vFau| zGUL6GxHOkG&h@$IcqeDM1vI?or#rm+5gjQQ`LTavv01x=cDzmWC1q}Z!ETUnk`6zI zH6JrP-Z+&&>U4a&(CG8$fV3wC-eKk6_LA|Q6h9(^hWAp|m>wAK&|`X}-P_6TcDxNo%q44IV;@d@Zm{4! z>jhngpZ{mB)T2sAk;T};>|-SN-bsOXX#Q_mGTy9@+@#U)b~=0EDLi{CPV5hWYwz!i z7d9vYynnTPG!+4}H~I7ztjT0PhXI{Z?q%he7r4KPZ^LLC2fF z>R`@=r1|*gNSuwkjoS6Q=y-QlR2{YC5~Mr4#StA{82KGqz_cgHn|8cIA9_7@3Z}xn z6MeRszFE)s{ePf8bvjgCWZ`db{q6tJx;8rcJ?Q^;Q+QAe#H&U2AgNk@RWuLU_3`mK zxc_fUuiXZF&_2h3mX*MRSa($%GUXyb;h~uaKNZJ8L1}jC@D;mXMZ6O5`+uu+T6)B6 z!4W&fyl#(o=zEYh4#LZeCuHzmNStrCjhx~`^!fkOrU|1{$=Y=1K`Rj*wHW!$9nKRA zzD0ZgKb(*6&WXfskaT;b4z;=|GkgVk$xx0e9hm~`FEmb&mRNrZybtm|j3?u5?KY^4 zhId=_CJPvE{m@Vn-a4FW`tStFf6#FO4&aT)H?9@F5eI$DmeqroSo@giOEECs1!tHY zxrtDL7t;f&^XPcr|5EO{XM+qrABmIF{{Gk{8XfQ612^ZmhqUMp?+1tuto)eUmX#%Z zp&jqd?{TjsJh3ZCTnOP9lczqzbL?H;N8wUxJ0CGV-WL0*(m@cqzbp9;$-R9k@IH{AWK71}?@5Fb8s6;s zi9#^mAvq7X!o|s+>Lpzj2v59ksWk*J>n^PH*{8;2jxNHbureq+qQg z8s6OT0Y9Gryw^Lrk?>yEC}S}Uh7-X}+MnKX5TJe5tG14T{$E)t`ie5Zd$WCLoglz_ z{Ao&;S6&#j&bU16j6QmC(&WplsWmKwcS7RAq86zy;YTk{Qq7ZBp4_2GcX+oVI*wxG z_rUjKz=s^#-P>D|D=0pUiu3|K9(nqb?sk70~|& zQ+UuJ6Qu)W4`SC`sEy`9MlpMX-~s7Q?RBL4|NRx!LTkYi+n1%wF$58yX6cucD!_x5 zPje3n0}o2^;XhR(_u={k4K#(2n;(PtS+YYbuV|=}n8Ca$n5wc;f^Isna1S zovHU{KpIGacYJf58QHzL+zK_&@Fw0enuZ%Bx6|8pzztHw>~Asn2I=bhGYg-9_y6bH zP1PiT{$Dq5`7UvQH)|Imof+U==q9aq{0s`YLa1r?;AZrtN7)3jl{J|zTEz-61_nx@YpdO*QG{xODtJO5k`L5Zw|0}?WKK*y%cy~wCy9d z2kAa_URQi=1H)I4&&%wn(vg=G@%G`!;nza_wU2X8w< zT4H;jxkzmVc+ZTOMi#3Opp7EOl_Eg}sZbEU8Sej$y8>sF0Nz{5e$;!*5Fw(8>WPUG zbi6Z;`WXwjNZ|J)arc;#1G|r*qy1OZ)Ul0{E=eX@%|NT5iN9( ziX(PETMwL%-OliMK3g5x%t>4A9F39FY*n*N)D}eVsDE0pD6BJlsWpmK^1^9R` z`nYkONuVrA360xzH%j4!0zTf3c>(Wh+E@>7%!f0b{O**tk{z{}Z;+zOZ+!B3O&{+M zR)YcuKX|fz|G#JHJBEA+v{+aUCQ|qRLuv5dpKBd}Rc}Ypg@$-|XRfY2h2UMb*@*hQ z#qcKcb!236vSLSqpEVgi+B`dTK6u_TTuySKB*6Qvi`R5#fVb)S5lx8_3Vf83_W1hW z9B=XP?#-C+k|X7#aR$#L6Z`+>c*`2ob7^}ovfkVq^Rbpre*1IERJ+zNU%j75`%MJx zp})LE@LYRujovx7@Bd@wu4KrEF3GR?&A;#eu}q8qw~2uMKZ>RX9r8Z87O6oq!3L@B zId=kH4J!Ro(2mR?=iNF@ok3dd*Z(XBYLH2G^F*Q*8NMG@HGCd?|Ib`(pENSWif$iV zzXa5vqaDe=7RgdzUj<&-muK)BBHnqe_7&>`yj>2xKg3%S4s$j9K2>Xsk9YEu_B{XXGf7xn)}phvRTB7k z2QQYArCir#x#g`C)WNCCf(GyO60g4wCvIKlZGwk){KHNM1n>QwmDJ4%Z=(@mbAWe@Ra;`c0qFmo zV}qB2{(r&lupnghwj-zbqzb@WVw%Jbl@#Q0;>#pcd3?N`ZYeF7?wCnRMB}uZD*DrZ z;9rndxm&LLS(fzvwGzr5w#KZDGO zkM}PQ1@eLe(qQgQp}{*XcwPiny|;=O&%?u8s%}^b!CQ9bAocwJpx)6!RlW+KVzjDlyQ8~kU)f@BCODDfq?I&gC?qMG9gpf7fg|8XdoLDdLBSrEN+v80T zbzsa#x!iiKfA|0YZl1?FKZ{?J$VF3wj+#&|VEun!jSDwk4cf=?Kpt6xEUucOo*-T6 zfBR}TxPx>z=hpBJ8!~Lir{5|EKC!El8z(IeY7pU&%8qzYgKQQ#>(q^d8D#$B=W+4) zHHd5>5b!Kaiu610Ph333SLuKc{tU9}nB~G zeY&}lig(xX$_E1gZ^6f#k6Z>z>|PvO)-SA$hX>wS@=XJH&q?|j9R~1r-|y_ldoLUw zOW!E>&f{zD!_v6L*et;o-fi&*3{V zgAAJbbN=7u>&3%g0N#sVyVO2i3ikgcO4AnA#KSUP2e~8w-bs>5kT1adTCZU;*_Hy^ zNjx3U`kU8Vu9Q3K>Xb>7tkJmnQR|gm{^s?Ta&7M0z7m=&hj%UN;|!hremSm7ZJWb9 z-f1h6Lq9yB-yjjrs`z=ed}V*UZ5Z=W>Yrb=C5KwQ2{d>g-hJaFhByDFI!-*i)oum# zA$XUQ1*p~g%J*?gZqOi2EO&FcyMzquWw;4VzZwtAQ^>r?2B~_H+7z-uYTY`^t=EzQ zyYT7fBtFBh-j7FWl%ZA`k`o#?*0s81?^XQjyo|NqQW#%Qez`|rKAFJsI{?&L$2 zfBXM`Rzv>Ve+o26yfiiFxTxW2tOm95*a+g)paZev1ubBR%?R=dL9W={QdrBw35Hlm zXjuG|u;Y`u2^3_%&#FC`@Wo8S8yP`VQ)2kWPMzQr{=zHi*#O==`5}_?7U8d9^Zd zgETU@?AxL?_OC&vD^D}xBjNVtQbFqZ|3n@dyz@I#gE73=?pMeYyB8O( z*oxq7`>+f80UD$aRbKawgZuyYIf9$a0N!i+T8{|=ytjwAk8}gPRU*7?MHW-wjj{D3 z-~VO?xemO8{Y8t1Pt*s}SLf_e90zz;5HFTUfdkTO;bhep_2B*g_$^Yx0B^}h^-Z?`-lyWWeqC=s zfmd|A&1-7JpFxI2t$n6^R+O|1jZ1$Kcxr12KHl?`OJ7a5WxcPrgrh!;>Ex$RIOcSz zl=&It3l8|W+#mxpNar`(hVJZVd%OwHh8gn_d0ASYdc7r)NQ3vWkWL;9?=jMOUOc=L zoCLIy_y09KmQp`&Y2Kzm=?8fG)&2k9xGv!1J(R`eotZ2_QbFVHykF91eh43LDL;?XZ$wmCu6mE6J|yYnxAxAC zvB7_EK>9+HLe;A=`u%@xM5o<&H2W`aNlkmtkdJOY&GtU(;lxCU2Jc+gK@x`dv*~+y z@bKna^Gy%goS6CDf_lAW!E~MjPXONB58k@T*^*)L&7oI1!QR`PW4Q)m0PiEyyv8yC z-u+s|yoH9~apD@{$oD3Eyw8T^JXej7Bo(1?Sxy{sd8PPxmxU}#Yo261yem;3^z!pO zK&+dQ!+iBFb}`!VF@u5XZPdTLMr@S*=idBp8T0YI{ifc({r~@L)mT%5{$Gfu29SAznTQ@mS24f=g4ZU@pJDO8P0><2Zd;B4N$TXtmlZujV^fVOy8ZPENi z$O}?DJlu=N!5bvq6P!|6SHT8pAS|)g4!;K3l&n_aBJtN_aqsinI+p0**C3^!J4BzO zG9*^}C0n9CROsY)HQ{Z>tzXR7pxA;kmwjg$*g=w;8+s%7e?k9Geip)z53Q%-xdD>M z{=Xm%-o+0dQNJLCTyNoM6%xb4d&fyfPXzCN$_^^tDel`7vH{+DPv6;Efc^hkg1+32 z)_C~S5m*yBAnhHRsipyj*w#Ev?b5(-*yb&#f66cXPwdQ5ox>r$oLIjMjf0Op{gT#+ zf5c8q^}?sj+Y&5?w?67)8lC)3?tjhsNR@fK7vHd{PyI~)ddu&G%T1T|tz!EI$@hIA zLp~A?-tLdyg`EFS6rjQTM0MACta|GjJr}{l`=I2#bqLxkCpR4*v zSd!tNI?cu=cjDnL{)P$UcuQpNp~iIp@A!RUCE;_z;S(2|o{lu&;~i(EU&?_*2(CoI>o zJ>CS-YkZ9O;0cYo8JA04-r}dhyQqAK`hj$$dK+#m5yr!N&-`&$1n&f$HB`KRl&w{~ z0q|Bmc=(yDIT>!>`78D4E%16vnDrS^fVb3Xf8#8G_gvX%u4LJ8_{@5PM(30GcsD)g z6I#9CV_i8KSA0--a&{a(-nMi1)h%ixupHi3P#??b>^Q*UcLd4yfrS$v% zls!txd6yd49`DQk=aLxl0Xxi4GsvUj%}0ZGq5XL;ta=*@?i0epd$H&lCj{@3Vp}TS z^A6{}N6y|lCdtIk1e+5pQdb)%+>D1C%nvOS0(ig8-j?10@NS&om}Vgr4s*V~d8n@l zA8!ZS0u_NL+2$N*T!xi&ZC(^U-k#grf|E9!s$;de_nGB?eDrMl`}|6)a$7C;Fpqb) zoZ|gpB?kI`multk2iMsiZ-SKuV?K`CJU|X7{`>wPtNlOX|B?@wL5kDVpfg-MoBpan zqsG#BHK;A)%%Z!X2Awq#jX?VUl$kppDS;X^*5fcBI)@BT8+rfkVn;k&((!UGazWbW z{^!}VK@E!L+Zy^dI~>j$=CMS?J zx}rYl<>&UTW9s%M<{Kn?@521OCm5JPhBg+N5WCrb4YJ9RAs^YL6E5pYsY9$74c@2Q z-u$)yuRBPXj)!-wz1K_x?;o{0CgRyRdl}J!5?CeY<3z}HBe(Y zymz5K=;i0>BJ%lWKJ$3HUi~3uT}XchxpSdnT*j0&+YhmU36-&o_{gNp`2Oe!6>m`* zyvxcAPGQwMDXd2l5AP1SkGf7AarT-nVT zu|kFA@ODOh+@zD=6_{V=@nh!kp3M_QDwbtn2HE`~m(PIxm$wM1dl>TpmO6C*?Ej0< z;C;%S(t+Xq;d!nE9^Q*HeeWQ6Z?{#X;;px~GjavM+dfKNDaL{f@0WZ&EDZ2IuIHbO z-2c!2eJeo-;B7V%u(hE+91gnL{JofrKRMad`Y|lsS*$)7jayc}Yh9T>{^TUaQRqs+ zpd!oR?Th-@O((y;c^W#ViOl02ei^(1T1)@*7NJ=3mAYUz+gESGWvd=Wd<=isr+2!V zTD^s7@IGlouE6jX;MhD35AT3ZyBq{>jkq;Ck?MV{j>Fgw;GH4sswxAnw=9ZWwrxc_ z*qk`Yy8*fXzbRiri2(2p@qhQ~-nno%Z+^yRw?+7PQ~WFH?Iwik^U*l>vE)xgC49UM z6Fj=4%xAJ3-rG?hv+3mb!PeM+w1IiN1N#;{__~}v-UlCCDQJ!~W&7(btDjWmGvY(~ z8;CBN5`$E!h(!F+N^4Z79r9fs5(!?oj2 zw}BcIre7z-IURh1WVcV%M=-=XF0|`HKCvT|zq76h?EjC=N!ur7LxFEiy&`Vt#;-w7 zHqCC^a8IJX8I22ZO_=fUI(`k>*(#H8bcHI*)u8*Rj~#UKD;A$-eexgd|8MB^6FPXU zh3?K%Mcrcki4P8JKg8;*EMdsUSZm$QMCvDY6QyYIKHn?)3d8%=Jeiqzc#rXgEl2R? zAJ(NVv8zOy@AC(EUq~Ep)|x?v8>L^X3xodO?y_{=41jmRHZ8Lk0Phv;!!5Dj!(nn} z^1i+U_;?T8l+M?Vm8xHf#u?-H)mt#x^)1r?+xiV!THI-nkKdA(hSH z@FgpoUr$}}@qR^lwNaHvy8bd6xB8d7hWLDZyu0_-kCbfJV7cnuiTa?IpU56hZ@uTt z<8555s~~ZaKHeAFzB*c*ea`lH9~>QL$j6d&t;Fy9sK;9*Xz)Jk9QOgk`+7>IEFRu( zKCZ4q@NOy^r{aB(^NkzQ|7-86Rz08wUT@9Z{lXF89lGft2ht#I<8XqBph2q5X-m^N z5)Qw)Ud%g32OsaWi`)(BzohH2IP&52XgfZ9yz{pSpT6v^$#Qrnp+4y4w_A6eNXl>K zH%LXknPuI$K)*pE99k$qh<(NOc*pEDW5~ygO#Jr_tbDF;|%n!yAtEl)=Nh z&iMNjg7=bNpQ+1RC+;_>BCEG$vmDQ8=#t@Ca^eSeBbyT|e;r3wZ*8ospUePw?^JB& z?L80<`^U^&eDrUgw>;@8+n_EWQ;)^9We4{8OyO@%kT!n$;kuRe@GeAs(916~Q6}Q) zKX|=mUW4766l(_Xu23iXkD0N3|4%rl!jO-O$dp?_;PsY&_y1Y1-Tyx_0{y=nO%1v{ z+MV)O4Z5PFidTa!OlVC-J0QIR^>K+#e!7bb^a8gtKZCrVxBk+b)eJn4_NsZSQ;r(j53z(h#~Jf6`Ao-h zJ@x$m3>v&IU2OepgEarfureOrL7VQbK=7XGQrV8+EtPZDObFn8b+%iwC%8dcuU@}- z3LLTXH+k?}5#U|_HsVbZz4| zNJm1CEpcd$htmo|jwk@USE-0B$^&?tTAnU`l1PD#tvZjKRm8{pRf1RJ-sY$Tcu!?swcyxDf!|xsn)>+ze{%BNYpzM| zb+P&ZG*11hm8N13e)T@Q{r1!4o3w%yr0|^pzghe-Dhs^t?{FwZppj| zxMn|;-tYjwdXEwwJnXZYR*%IQb*ZF)hS6A$l>pA}0Gyc0|YsCdueZ@K#d;4Ny>aG)cI48LiO9P$D0 z|8I8U&PMPax(n^u0Px;K@;K0J76Ip-b=}(Y6n}^nCJ1(~6?j;ekH)p8Jq*&hj*s`C z7v(@~;%jqOs~;`D1*krH>Ex$d)XLvHi+Q}u91QhONVejZ3GDZAd#73L&bt$AKZBGt zWXwlrlW63Y2I>Z>0uA1^kyqof>fL^*LIV%)M&prC1n+^iQ$a}ej&i&x`WfIYzC`R{ zrXLxW4|^*}1TRR1?j8$6@D_UnTloOI9aJ|jtmch?>quMdty z$YCK5aQ^?6-tOxFZ&*v*5y88?(N5eK;QixQ%jn6U6j(D!5#>=G zfo#9L)hx@HkF{2dl=d8?R_~cKcwe3NpdG`T{C>F_9^Pb=oYx56#zMZ-$BEUKHB>DE zcwbl^vgD-`88&HlK3o8vw=5M=(ns(vH);6b2k=&?uimiPngUxI-+xp15`TFMo+j4i zC%{pU#X;vhmyKP+U*0Oc=so%TxG2lvZH)RTrjuWL-H-hB3z)Co7e-V<%H`=_PTV(I zdNk2@8rxUzI)?;?eB|&G&WVA`iU0Qh*z}Zz{}=TC>NGW|vFA-OR)d@tiW}h7pwsi> z?V3Oh@>V+LjtsF*ZxtIBf*GW}y|8a)BpLp6IK0^f?Ek|HF7+Ta=+G#?-WpJYK4{)} zr8j36tg1aPU_<8?+@WEs>(0i9&lE|TXj~Pnl*ilQjvMb@{qV+%Z3gwM_M6^@`dCjV zzl}Gy*QtFJ$MuKjYiNezC)npM{Xf@U+&g>L7~9t%f;MA5M%H|K+Z|1vL8{Tzz?eesHa=YN1+NP^JZsOxzykg^}E0vO@Tr_Th*3YA*XVaHW%<+vXm1?p0FsG5sH$JC@g;-=cGm?w>2H+U>KsFOKbJkYhh$81nIbWO%%> zEf3isRi(kZA#%xIc)#R7I|~o*67ATp2;L8uZ=-%7t@d(n)MkLU^|zvJG6>#r=j}Ve z46^*_k|zk>e!;J@*8#jkrqs{>xD)|*MQ*B|a>8G|eH!)q%A+z~QV$yEAHPq;bm2PO z|BQkqFC}(MNwZw_?m>Ns(8(`vQbTy36Z6&krZva><2>{mq?cYR-;M`{vOV5sa>xw% zXz=PVz7|hykW^^!zTwedgjMg@rQy1Gcn^CezDFKNH||*Jk4#P;Gzs@40lZBz6tnI| zkYRzfqdL~0{~w(b^9aHF-es;%cYwF!y>K_hq6j#my>E4~1wP(SdhEf09 zuT(bb;NzX?s4Nhw%FA+i_n|(r=;ZgoAkC^ip85X2e?`)CYaRN>TL^9kqn5qf#`bu} zm}N5LBTV0XzHUBsa-vLw_jPgO1`Kb#wM%sH@PthBWi1Sd#2510t6gBrA~U#8Ru)S&vWvRB%c?}7*9 zm*gdV!EcaO3O<>!tIUuzg2u&Fd?~8>fZrf}IkO_#4PMA{L#zYpgI<1jewFlEOHRX` zA>+ZrOZf5Rp*{oq{~TvbH}C9Y`x+GU>@-6@j&016*`!7tVzp`TzEe>A8^gP|_Sqaf zybtJbiZ=qh`*X5f5xjMh)=3!xycZ2Vx#*Nah9^l`hP6%cu%P`FS2cjQxrF8#7~uW> zo#)~n(k{4>Z`PnyKR(`-!`GC%|JS0y`?jy%U*G@R z_aJvR9^MK{O)C(*S5;)VA$Tv_yXgXgxAP>tbJbolEFtaaY0wxCd&(a^t_twhZdw~| z2k@Q~o7P!vvI{QDxOe|Y4?fg=f15?BK;yO%6vxgy!pA#S)s@q7u{q1(jrrI^ zCqJhjO3sCe%;Wt&)M?(~ZS;4L2-ZJ4Up=s4d%Ot)zZml&m@cmN=YX^(4c^Vht7c-= z`);nU5gy(gW`{EoypLs-u0imYReO+Z1n?IAAXVH5mbWyUzHe}8h==>``Sv3XlBVGX zq8q^5r*BO}mE|s2dBgB7%Rzj+XKs?5x&M_mNezvwh^CBKzQV_QTw0g2*xZ!m@Wy<6 zqLbeS7qQGD3+D0GeBCiJ^_YJ3zIZ$I$FBoR*?w{&D9M-)gZkqtt7EB?6Ac=?Z;1*N zVt7x?v@yiPyZ6>fD&CZC=I}n36jzbt6bXNb9&>T{ir@d2_A0;+_NkLb&^TB{d#g`B ze*b^H{I-n4@3}08H|FC8o&1j5n*A0eF^@O@nOeVhpBSj#{FJxyGyWHRy+t>iF&}3> ziYS2U{qO!iUf0G#e;>>s4QOgmNAD2zfi!vWiJj+H+z5CzD0cDCDP)L!ZpFVA8Df2& ze)UlYL+pjzifhq3$na3dK$$c6f|QlMwvR3tVkJ*C%iZQ|hpVOs{}>yMfHMWodGn^? z*Pvc_iXd2RL^^`T?bA}7Z54rEgDip*DXEr=Sgr=WMtv-#lOI?0E3aAw=68@hB%aOb zJVn3%kEwmQvb2W%@Bhav8DPjqh^u%YxsW=<>eJwT@1V*iY=|A)e%lle@1viLd=b2V zt(c@XNJ=N)j%Wb9lM|oKa*8IyQnG7rEC+apRxLKs0eFk{iKKM`yqEN4)WtrEfGZuv zW4>;~$NTxJIo~hLm`%Ej#_?3FF->#F$Gfb?aZhV0>*3vr`Z!G|zekR_60_Wy$9u;G zqu7Ne4B#!3wIw$)o$Y6k7ITXj@^Lgcbu6cXinksO-tBA7Ex_=WX-=Duhqq~kr#ynU zp;sGqdFyKCM6VXW`+J?k{?G(6yy=9lt0lm@OhTTZ4e;LiNV#?t;C=L()Ha(Z5pYKT zyPA#=e7wukzOQy%F`JZ)#*Gfn`W)qfk2lAC2c_9BSP${CbaGACgvMeg=6h zG;qU~JO(aEr^xEQeA>_UcoWj)81r%WvoHGo|1283+cbksFudVU-X?f>?>bS~j%-f2 zi0-9sPV60g7px2LmLKt2F+Y?AGT%fja$U0w)TY|KHeiIY-Dy;u^!$(P#^U2+te>|)8;kv)%)OD zx1yX7`VG>R6ZdX&&TwY?<*n0O9x&uXsJl4g5V#->=H9wAc;DsmI)mXIl5RQ=5AT~r zDJ2Nrb<1A4Aan2a@t;V@-kY^m&_#};WO!cGmIbqJ$HTWLYwMA{H$w6vS9O5*i{y{t zEjJ?JAkyh+avSlNw=UZ>u8O>7L<&XY4$RdPyzYX(yw#bn^ssq3>*0L`^+7K`XTFRR zdp(%1-hpe5%IiF3;O(uQyE?x(yRd)tj*Dc>hv6Nk=U)Hz|18wyO63=(_Y-WZ0Qg>EK-O4HCcP z!Z%3&f3o!iXC0V9N_^HmE1OP%our|-7!CX@cCtN>#~dbRk=)R@M;EjUZ}H<_vD4SN zChTp&dOJv%k2!Sm8_(GKy>%1wXOR56c5GS_&%g|l=hr*q0#EjTgJiD!C__GY16HC> z?98FT`*D0gBZl`+UR5F<-d!qR79x1x7}`$7n;cp8egNQoWPgXYDfs^1jMJ;gac%MN zYr`VKEP%JRi(^U+!28{`h`|ws2>3~jZTS5w_;_oF<}99q^+}y*oWJvjt>p#yc)!#z zp0PNV#B$49n2%mM`IXE%uvt=%dAtqFW;Y~WrGLaOrtVzcYr+?{$2&&I>;xk|7AHI0 z=qRAhAZOFy{b=RNa18IU@Q+-0cqei==plIT8djy^{iW74XB^;d663(P8a!`V=ajE< z@oqePIKLCY0qLg=<(B#QcyCx_^IF!?fE0tq&3vMHa8Eow z-h;=QzW(TiSq^V+)W-;&{OpO^Wo0{<$9s!rgn#x22Jo&LcwAQD#r88ui_PN<`S@PD zjl=L16>lRNydTO*|5d&BRMc?d;VtUWEsfya71h2DX^@)zLi>LKye&2@c3!dqOirXv zhc$!u|90H0g%P}ezR}!!8Q^`5tlfAIyfKuB4|iTN8{#?2rWC9 zgpc>m^Q4%FV%9soRfGDV(8=#e*52@V7v>wJvmUnovXb;yZwdS(N3x&>w#S>0Ju8(V zAL;FdNB=xdWJrVe{crnAuBB1~0O%54~aVNvQ zw}sp)TH@iLWiDO_-hm$%f4YcFPKtjoFA|A>XXjK{E;xmccM~7SdfBIjBvUl*=KS`s z`>FVNKd>8r@FIZq&feZaeLSR-pHGadzCsT3%Uf#BKQ}BoMgR2{1J^c(UCQQczr5xB zOnU(%K9aM4ChppG@ZbG^{H~jIeggV`Q<@soRXKbXt3hTO%LMUiP_eYPEpo-qPUQMV zWQa{T|I_R|s6mSp8{{fTWcb}@%VsaI#Qr!V+*J$IpsR%h@gJZDeVCs+O}mW(H&hds z4tV3&Ac}wE4iY$n)QrY$70OnOx52MLM;86gU;2yn&LBmiJ__jM$20U}8h0!6Z;&Xa zS8ojqr+>tbptR#)=EUkttOMRZ%;ffo8b*9r+-`9mJx85E&Zoh<7o;o7IjI+4eS1VgNoNU$NYLHcIlrobV9 z_wZ)_1Bz7?_}SG1k&A5c@s64}PmasgB)vrAWO%mLF4V)v+dMC9-59qC%QZ+bs1Hjz z`NePD@~z+>yddS!K3J-@j{XkPae0pYQqb@SZZ0*@)nsDk`@Dsov>x3|9C6ye$;>m?nYcEuF7>^nF2t)RVGV6gl2f z-l?$QCBVD;ZtI0@=O{2V23zf4ijQ|+{~)LKL2VK*8khGh&||j_KHixo?WfO<&u2Nj z`%xb`bn+{{K9*|j%6$KSyzPBe+(iaaU~_Vc`Wc+a)&eSXPoGagdF-g6C6wyzLEFOqXm} zz;bwFJ{;-f7u1#>KB2%o-rZ%pe{|iWKRJmB*4}cwMUn0M|ClM$Z}|-PsCDhVWb@~6 zqA?BLPrFwNV|X9!r10S3y(Yhzy7#sulDWON#7JZHhdU$S4L8k89!cOIZ<#)yf9hz^ zERr7@x9n4f!SkQ^c&nzCO?K9ru^ir*4{bX6=@&K5@eX7j?_F_sG+X-VPfo}dAC~dG zwPX9u2|wFx7e;)DmG3TrQ~tgG{|`Hy|Lz|H{Xa}ogI?!LhG8|xUJDk-t3eN^UD}Pz zAor#1q0S(+rhadW0&kE$+0tk4>`R7;l)&3WaQ}b#Qte6P43elj$9olU21#s<>^#00 z3jD+Rj^SfT{2?}E`?=JMElQ-{Xx#O&7)PH;{5MEHy$g9A=5EMxH7FGIF-a#s?y0); zc5mj_ATLZvx^Pv|UxOTwyL3(KkkjS=E?ocb|7{bqM;P)^y_C|wGm83x6p04!UcW5r zCw7tk-|Hry7#`kNJ)Tz~cyB%L;Egm$!Am}U^9OkEPf1c6@Fc_G>5o2<0N&*C#zh(c z?_H}GOvnSg6RRI>w=$=|lfJ_rLhj=~v0JTY{ODb~66qHjH+-t*okt};-n$Q*-a6pL zdU#_#_R`6(XzBTx#)p_6Vl7%Ye@?4pU z`;}#TDOSCe*1r+K!`sng%?AYU>Gej`@he~SUYJJ?A$YrP{G?lOAj)&}q%x9{yi z@V;62ElL95y}e-m+n?MN__cn{%ibJ(yrcU~g_UZRNdsuy%s!%QbT~fVZ@0*cYuFmG z+~j08>f=3~{5Ge2akZ9UesVJQX5v+E4*mY0(Bl8}^{E!N$D5$Kk1-!Yvwd>@?Ef#I z!TaUN5iJbw*qR6-JiIl^K5j(tc0Xa{i%d>RE&a5)0p7QRuP54WzG>!D`T`vVk;S4H}j?un}2euWlNmo*?a9 z^8`KyYLFx0@(|}?GAyWKKJVncc=)|n0~c}z$@8J@cjSnj??=^yjm8u>x>2BNO$&Yv zdPm6Sd;d+9v>S~};HxVCS%zPO1TV~+xs5W1;-uDYx(<_wuHmE zRZ2F8*WlwFp{Zrp=%zx-L*s0)ToA!ce3yPm9KSK5AW-!k92zZeb_yrJ-|HP zv+BHp@-8!QIgwnT{QkfUw#S=Lki(b{6Db{?KgU}vXz+eBSR{wxz0n|i8Xn%m5_%*A zZ|B<0UP$#G;%wcP0Px-$KAtr{gbb(lEaqGX&fa!pMw=o1|MaKc(}h6)-ymS##}!C{ z^GrW`x^v<0y=`Bgw=wmD5~%=<^RMrDzoQQy?@5(M92vVg|Z4nkSa{hM)8D5-si_;cdke=MK{w;F< z|LH2N##%7M#%z%@Ge1v(moo5}VK(u27+4EbnE;8dvj^Tdud z4c^0RwEnt5dgsBU93I|x)PiCVyn`EqsK;BP4(t=-0C-2Pc#wY!ydV{;<7;^h;4N7o zGE9BmGDY_#a{u2ZL~ec20Se4({eE7l3O?RGYbpcYg5@oKG;T=ouH!mx{3CXAH6+5L zSa5j@^I=LSKj+Wer1ChJzd<^=%sKzJJOeXGH_a_cTl3f+Z-SI6V?ItdTcOWeETzGF zNPqrGta>+B-JF4k_d>myItboxb;PMN$R~u^w+6rrGPp9}`I&>DK?;g4Sqhf7w1-{4 zAb95}<%}Tr|F=dz-qWrU0k69CLoK`xAMe*Yg*anm)JaZgoT`lF^wA=Gyian^3AV{( zz1v%uk2Cc0ljOTFag+J#t$87O`n5*-`~L(1`=@I(wAgU3BZ5AR6<|2AZKYoTcdb$Kh(@?QUKfOpE4(64pi<3t;y)2s#n-mYE5 zp9tQ1PwXeJ0K78~Iq1EWkAQP?8gGPL#>d;gINNnusX8eijoX))75pF%AMar~ZdH|C>a%;UX2%Ey^-hyLm2X3U58FO6JqyoDchvah(V6GX;E-ikaCxh-;4q+BFVBuyk%Bt&GR$Z8Q=5i=1z z5k(Pk5lDDKctH4t@Ll10;d8=;!Uu)-3hxvS5MC>6FKi^NDl8?;EA(AxNT^$=L#RRM zf>4Q2w$Of|NTEO>4kX}qz#A-o%TSM%EPn(^xKD)Nf+LOc^Z13WKy?()?0 zoZ~6vImok@XD3ep&srXP9t$2L9#tMG9$xP6+(X>m+#TEv+!we@xU;$Ub4PLqa(i$) za4+UI=GNqvUA1jNlX$@PJ&i>saMx?qgpHbHMeXF+R0Q$bxp zc|lP@PJzz?{Q}PfS_EnZDg+7yG6ePrgbDZwxCz(^kOT|_lm#RNxcMjfKk#?)xAR{Y zw&1GdI>D92mB2;e+RWw7Mdn(>HHS-`OPY(HbBc3>^A+a<&PL9QoF_Sta3*s`aRzgG zaXNA?;WXjY=9J?U{?Bp-N9BM1`rp4|{ojBP7dPkhA|a;@@e7X;bui^+*m0bwjVX_b z@{L3-Os#)#Y(G&GQ|@IP=|l}ot=kwlL{!Jr+J)yRL^VvU5$5zJs$$BuJM%D61yid_ zvm1!Ym~z>vai6G!Dd%-(&WfvFXmAq$DJm|Ff_wTdW%DZ8tmBZ$(NS{66HoCsFd|NNG09e3;|N@2=IU!tBU zi79J+hpR*hOf9+lWDRi|rmPO9ni9n^wRi)+8Bq*Vma{DCiK3WVB%>fs6v325+tz%d zFs9&wm)D3wm?Gt_TuT(hl)3S~RYU9{ zru6!=0-@iSnpKlO2>rs8?*6i^&`(V1tQjnTrZA=bSg{8Bfho<=s}0b1OldSFr$XN_ zrJhPS0!?B{&BM|S`id!4y9jA$0#nLAbTXhXm{NKieir(SDaE{!nb0RpDTKz#L*tl| zH@B;SK4NO7aM%iH3{x|nt%9LZOv&c;ia{fok_q})2MuFN+VZX@G=!c^DGz^;W*AEtyGCP>g*ObMM{ zAOO9=lwd;281x!b0=gHbLA{vb=lPTgy}}f4^Kd29gDIX94P{U_rnq;y4?!<6MV#X| z1$AKxB06k?Ix)rB8FCSN@t2aZxeh(Y6k#W~5A+OGj=vXG`an-H^-C`C0rUh@Q_s#c zLXR=^qdI62^axYmx9xoiJ;c;EE15aa158bNmrFtSF*Wh_F(1@{sV~>GmO%F~^?84w zA=HkkPfqK*p*Bp7YyF6V?qcer!1IStE2c(o4{AUym_pXup*xsDmM5Xxm_k-_pk_=V z%`bEdQ%J7>HDL-lwFfm~3OVEi-NY1fCIo806taa5-M|#G;|N{H6ms_ux`rv_suWa@ zDdc7eREH_#AU;%!DdgNTRD&tx1tI7vrjQ3$pevX{-lu>rV+y&>4_(3(a{C#&h$-Y9 zVyGHZ$g{1`1xz8YTtZctLLLQ#Dlvt;p$47D6!JAA=p3eykH0`?F@=091FFCj@@WC+ z45pBm*r9S%IqknJ{G4cqsl<$!tHfoPN>~xyu6>$-!cAXsAKwOBaNN>qS zL<>wsIIiF)!kD6Pe(5KYFtxMi<{hFrrgogQTuU^=RM_qo5^({hLTxjOh^Ckd;om$# zoR6t(U*k21CYaj#XmkT{9;SkKjO!DPF%{(gNt!qpQ-KmkRETphwT0hrDRDNYHeJbF zPBg+)K)TmHq9LaIH;0W74KU@W=$S**$CR(&&M=}LrhNK4b%?Vt<$X9|B~ceuj>s3T zq0^W`J_rnzVG8+vDs&1{$mb@ZlbAxj&IgrZsC?8Wb)?e+RJWO4k_Mja)hN;V= z-6>EmrY>D!f%EnaXm#5j#VN9Lx6@3L|Vd~tm zL{I1trp`LYeSi*Ps$#A(AC!ryGh92HpbSi%ZhI39rDLkB%-|H1hN)BTlny8rQzwnc z6;KMMN;!RhLI+Uglr-?gi?|&7S@DBMVNf!rPE>cThmtT=R6b-4?Z;H1{dq4a5mU!S z4NpS}n9A==4Tkn%Dz8M$7TSxcVfN z0-|6lRfkXxg=6Z#uLYsdPD~}YiOE4bFqM?`H5LlP)c#!S04NkwiKgn&Pza_HWIElU z?U>s8pw$f8hN<|%2R+bMOznw3oe2eFDh?Lahk`H_D|%xu6!`D=|5(4rBY^#Xdzv*! zWLAT%L8^w#RK;6^G*~-L61jtag4r`#9>ul}>&~W{6}THeh}SY4D2$spLKV{eQyV38LMVH1=PEtej%VM*!b( z?RCegOYF;O@J6QT7~W;8zbfP5Eh~12iuY{j0Tu7?anYZbkqy#&*Dmb@*ISYb`vWoo z-fMP$ia?Iol|OcWi+n-K|J|9zH?1jff>d0Tz)O6*E%t=+oJ^QWN=D;2_K%DY)#2kU zdYrFf_G4X^!`l+|Ax$U0^d_eg-U;UM4!V^ok`>qj(<`J8$@0A&*5YixgVdz0!jKO) z1@A>O_fem>u%p2n={qsJ6Q0~q!o$0H`&TO7KkhxG;_VtVpxgrR7S`;PkIDiMq{m24 zzyNP~pTlv;0cq_=vLc_s2I=&%1D@|h!TtXON(oPj@bTWdKxfC8n*wP!8pr4Ku5Wc5 zKHf2hPoCeBtH*M9hoC+Z>E!p~9^d(CI?Us(YUD5N-c0`nDM4c1m8-rp*&c6#8Dlo}b8{y?-JcCfDuS`78k+?^`Rw;(oO%l2)N{6$%F2 zmwoZ^COyk|IqqY?a(FkRJ}l|vr}1UMjGoWT<9#Viw2<7 z;>`f><#UoNk;{o68;|eo0C>+6PuR6?ARM0GW|-|v!N>a?_!70bq%vs%8s|Pqx!AiJ zA8#K^g;DQP);s@y9`zAGC%=f2yWd^)na4YJSU+~~H2wYmm}-h->UbvG<4p);%*XTb z)CrsVf6xEZo3ygT&q4pcilzo3dm~s4YIr$K8?Od!T&Ny~46!~+Yp8FKL1I4^>mekA^#AAH6%kdD2I;NfA*teUI3z#kt>0Yy8pQcBK_U5y z6lo_K=Wry^*+3k>24!(*C5Gy&v)m9%M135gli%nE<8*5w=4(*+ro$aIjtm@-PBRMg z=D*JVFGzP8Fy@1QWv=$0D|QYvcq5yA7~XLBTTMK?yU$H{Ab6V(KvcX(-|zI@3GkLy z_CJyh@NO?My`9<=4;M&R7$bQ5$tmno1b9E+UQXN+6%HTU{Paz`5I){-&B>zQ-c2VR zN8=VeELvOm-VL|UU83^r=>=yEmczRr^`G$~EoGU$Nt_uBn@xq>uNbsf;yW zN01k!qJ>l)5WJVhym%xB@Q$^p*{iT49KN;w!pl|M_;{Cmp%ltV z$&l`%aZh{oxPJ8FRb}A)|GLK+ zW}FMz9&f@*27MH)+phAbdXs7JMvh}(cpEK_R>#BJ_vJMM1n(JpEvR@qLt^6x0p7}r z0k7_Z&52QUgYdcF{{NetjR6SWvAbUiAkSOYb?bd!@--a(6c|9sO2o(8*4szzzP&7I z5{)zX*ytYUhd(*FKRL(ubA=Ym;cbWdctR(?BRS_RQ(rS*z0Y4ZTbHw!fz64@*GFGG zZ(x7C^BMC|W`Ffmej0UoYXuG7$oV1+?-N&+tKs2IY2l)--n#5$Ztv}s@B7DfQWQ9L zm2_XnDSW&G`8hua+07s&pm77?&wRHh;^XbDHkgxKqRn!62cteV(aA5tN%+@}+00jO z_swEyfj=3j-a0Q2cll0df4uMYG33KlPTdR!tGEB||FcAg|My9N{(tp0&$Pjy~ z&*JBFFvPn4w!Zl$CLBKWlk(J66u$;7i!3xWIz63q1dR)*R$e-12!93{bM}@hWd`dt zNXtm2h#Z2Yf>l}h{RH%Np5PNk|)IrgtXzeE`Gq4us>`p*o~2yV#E%-yMLze4mj$AdC z8)73-AC7eLn}T~CvbQmh_jH%tt&{iZ?;sI)BWJAAJk9=id&e;3qjCOL$xq;k9Z`*i`uz@^PZ< z)dt^@j}v8Yo9TsooalFPrbTp9I9$=rm6q#_kN3^qb-MSGBuJHL+`|ip-1O(*<9$QI zgl|%q_3&;&eKgU@FCcoL)-!_n>Ro*dzPGxL{st-Gu5Z{8HAS|^oA8w}ANI$JWHbLf zPUJ{~H*!k}!@Ko{y$&AU>d?tV1n;u&GV11pUBR`-8v)+k8P9dJj*#J+bW2a48}V@5 zsbAj^ygPIgf;0f$NlVyUo|L;-x#k3-MHE!d?-za z7a`3=A$W&+ zOh1M^kUqZbamVc4WcY;ejn8YEX@-~psTA_tg~Mry)gzn{|H zkL>XA-mSrJxlu)yv>A;%zPyp7qK#j@Z`h_Q)bC-v{r^3vkDGMzt607N(9}QJocO)q zeDH;2@)-2N=jf#WXLG`p7H{y@35Iv{4GTj&yx$AeK0%(h{GES= z`n=`+OGiCAz~;p3fl;p;;Oi~^u_giPPvYU#Uq(%k)myiak|5;smKpoQ4llbL4$Je| zte3UH$Ggi#hJ!LJO;SPQQj7x*u2RRx+jyU^mZ~%Bo!;t3eaxeiU+4MLtA721>b))? zp`~|_e*eFL+^&$2BFgsFo15~KAs=F0RddcA`nUgQkq-aw(*XUy7flU9UVB1nkOKHX z`f49H0$vR=OpBl(4btkoL~4WdV|a$4=TAR^)Szb- zU5|J{4e~85wEs3mfo~t_TVHz!{|!>f)x4)9W?wgNLgR9#WpMID;J-myo>zMIPU*e6 zzc>5e|LGCb$LjpQ&+lICMuR|C=68_NZZ4k~SwsJcUBVIlz-`e%Y+r*2d&C*?@vHH9 zXM72D2I)zIH}ZTLHpC9xZ8pWj`;4f|H3V6hhQB@C_K`MoFo=49AxAlB)sJ=ykTcmUw)!p&&J`ixYA?I+d`E4{VX}L&%%p!ce zrQ>HQ{2Xm%IlK>ULVeK5Z`JpAQG$n<$NQAm`lA!I^c$q?!%rjblU}er-X+tT81f-1 zylF}0pA)1WG6`@m|5D1M zs#9I@aFFHaYNY>PcV=<}(*Ga5mO0FEoC4ck^tiis9zNa$7Fi9^mmitipm95nr$0%Q z#mD;$K_^br>@CaT{TlVrNhiOF)|=Bc9x{)2N5vXXv)lA%kOaLT#kBA@Y>zi#PatDH zPIKJiHG!*{?bJa$A;W1L z*LySp-jq&0LuB=~oHR1&0PyxmUE^C97Xgd7q<39c*o=D{>$Aaw+bwb*&9S&o7DKN# z@~*>;*BRdzY+g-Zxz$_9@Q;sqbn<)V4DD=5V;=9yTSMztjkemP+k z6KEVUT%v4;I6mG-#HV?@4VGXzykDa}3h3mQI$@`K_p2m*O#kBb&tG^eZZDR1Xs7$< z7S4z9%=am@L=DuSsl$$?$P&Bb z{Y{%!zN5fze^2W=5RE^B97(eHvRL@0ITp7{%zwJ2H~tJVwQ=IufxHJSH-mIf{^O&Q zPJZ4ET~AAtm>*(=^XmFMY8f~n?Y{0^)^snnuR#RqO$_;1#6Rtj2RMTS@ZLy+H}VKN zhIdw`A`uVolBRn_2;MQtbEtT~JN=_u5Dc--3OCEI1(V^Pq}7XK0N#s;VL?d$f1r8Q zYgvGI`y&Z$v7C+$2{H+U2k5*e4vlFVE4ecyYsr)9`B3SzA@y(_T}EIKJnB8(mphJBd_{n zc!vlKbK&8gXfPIs;9Zw}p1OKFxFFI`7vL@aczC>I2N`y7)!-!pyjy2WSRkvnYp(`@ zSFzjSXL_@HUM5lCohmgky-N6auh=Vj_1CN}^Brj1$K9FLju1ZHc}h3te%mw1a@G3) z>Z6HHey^%SpFRBt_y3pQ^{>pxq`$mHAiJ1VsP?fv-Z8hF81k{R>R78>F|~So)8LJK zrUJuztwIea9^RMYG(8c#H`Xds@qW-9-0B4IzMFCRYZEw}xXFI&yY1ca@Mz9MY2@|R zIiEgG{00xCxh$7+Nr|Jt>RXmXxXa+_5nq7dUAby+0Mh>xMovbj0K6^aWM1t^B*Q#~TH&|A=7iZ= z+wTb8dxL*Aegt^SS`4_a%Amj>{Rd7(YvSWQ$z$U;%j~}S2pU%uI!9Sa0Kaw86@%W2Q?~*+gT%2+{YLDkaCnny6g!A#Cazfm_ZhV zp1+(o#QrsC+JhoSeB7z}rc?fBiG33d-pHraFuZfiB?R#BZqiYcM^2Dx-1+mo#lo3- zd#?e!DcxI+ow6sxgKq{GIsv@pMvM0$cvn@$h9docgX9Grt=e#SVzg35b2&cVyWAE} z=)UG7eMRH0iEN|z{>=$euJUD@eXV3z4(~mv4?a5ine(aUXE!sCcMJDP4*_NRc$c{t z*0kpMuziEH#4_RnBR*zW7Bu8@F~1Lw9dJKOr}g5+B3ieHYOohLNAV=f#)Y|HbRA_}4d*N8ZtJKzh7>xN|6u>G8&W zc6myZj!3pZi$C-K5GuUkk6lvmJ~eZe6AkaLcrG9KdQ0i_EcyQb`k=yfJpgacCP-tc z8v$y%w!vf(*xnlHQ*MKY6VLbBTu=gdrz8YK4adYnzg5lI@SNy)m*4P?J#9Z~PKnFr zd9m^S2>RnhJR=Wvyl;MGxCW^O(IJhI-`h-%^V@srcki$Ufxb8z4oHV)CT@5{{LS=u zSB?GhqD99~qA8)hnC#xcRCvQ*Z>8YvzdC~h4R2%r#lmp^Usd=v1g^cmXc-CK2YAQN z*#GwMAwa~oocAYSyjwM0V7%L;ISn)c-U=rPJX*w9h}6?ul+A^X_du8}YgYS-mR2P0 zl>WjkI-}@#O9_g#mr6F8|KE+p|Nc)p8~^B-n*ZznbDfVxf3JG!N3uEG+8) z9@JfM-WB$s8In`=4DcYF@OrmHCkfE!VyhNDa6$UMDf=l+;6d)Bs+lUV2l;IHyx*hE zL})|E3x8WK^gYOgIZHm46fD9AAaM#S+wO3@N3S5u-x?lm6{tUZ5|r`wa$H)%q*oiAY?IUXuEBJ38Ld1@7u_8yB{zOmEt+(cz15vJaf^)iCMvuo z2Am-Z-VgML=Aq#|u|Yf;#+wW0bSm#sZD8T#oVd?5}aQ>g`puUGJI6*3E+7b$X zAgwMx`^6K0_j$cy4~Zp2XeVhI7uOARyrb}oAK@3u;ggWKdp)ypR@LZubARhhKX!)k zK9IH<(ZP$6U$CEhE{TQy3R08(Hb?tG8Y)OO>E5MpRx>@`xbs@H>EN)|=lj$DM^ND{ zUi?CUg7;g~U#k1>5Z3-TS5p>jPIa*Bsl;7h;^hM z9*{nsGU=QGcwcc)&C?hnLTfjN%9?IRFHWpf(6+i4@jM>S8uHo zX1uSrE=P2@V&r#Wp`pU)HTvDVLClHk;|uK5Te!qrKM(mE%#U}`ZJKoOhxJO|__KQ( zPKEcvO1UKEKFFep5wKt#v8#UJNzBcJi`rs%-R@1?-mu)0h1 zTlpC*#KZ(RuRk8Nlsh~GVw?o~2;D?PEt~jCSz{-z5Qu|Xrk$$|5 zZs!Sy^wZG)f2!yYkr`%wyh$f$(y^lCeJcM+vU^8U;VrXumox?M&);K((C~InHGp8e zOO8seh28s>(np)Q0B`-ebCtX;1c+bOaGw!)z199_n4vbn`?9pj>wN(4u5arC4>l1Y z-!;LPE;yp&?YHw${_hfHygw3$&nHyqEJ4Rxw>T>7^?XBy!<(W*4<8Mrc(ib`~Uy#)}E&SKIs4Bs60rmU-qB* zKdx0%8qI@hia&6|9%LzL>H>R^YKBJ}>_Mr8R(+&11ZWNSyj^{uLGpTU2*GENye4XY zYlHq@-_KMbONj_sPqDrhY(lRf_Xj*Z=iRM}w?X3WHl=cR=A&1TdnEbgG_@G7f;@oe z$i&Fcnzxu3GCLphEs_8HJ57vpm3JDz?*DOj9{Ifeevj!r2nX$4Pm2zxZ>6pA$H+@8 zkqU2>Pfb@SOKe=ilq4G7Q%kzNV7w16IzV1xEepoR*#X{KS@+L(UL-)u3pKuofbFe2 zZX!W2-ko_~YVZ*|){5U55cvL|{D_X<#eL{_Yk!)rY^14*S3=?>`j0xV4MWF!)d5r7 zm0ZTFAaxKO4jB2J`7zm`X- zl#F*Q72e97d-qfD_K&_UfrfWdonRx3_rV-?a{uqu&HoW@kd#ta$`&^hpxb46+#vvO zJ%jW6VZ0lSv>-KrcWlx5BR_{@q15{7uaCE&<1MKg+p-V_}_G4kUX+_$LNjDEZg#%2dfpU}|%A8Oy>v+4@-p1iZ9kPkgy%>pOK1%3#hsN-^)vQ#-KS1IfVjD&;aH9AB<+(OR zJI^v6-V_~W82P1I2pX7i(%=7AOt9rw$zb>YAHF^Kn!oo6)7Rcbaa!MK(a~YCD8VcD zZ~y5J{eP}JUS=impvT&2 z0&8;#5T|0O#GU>W=<>ITGq4A3=6L%WZjeqL2%Q}R{eQ{DZ-?UlrT@>o`8JWGUmahD z#D%#_WoQx z49OrpNu7+RO~;3RW8FU$Lpx`~i@<|>I?{dhg1IC-(a3LA*L9JF33xIdv ztt%Hb!TJ9O0Ubs%;0sbWR1*%sc$=2_vccP18JxFypOq0IxkG%oaAWi(*18I}xUxeX zuYkl&hR5hHmPB7-Ma!R6ZkAv?yq6(5u<~nqwT$offAK)t{hw`V+MP6f-a_K(-qzyu zMtVqM$XLhgH0fCV*3v%t47vYLpu$`8a>;uN-fA}Oa%gzV3rx1bcqdl~knx_Ub~iu| z;9b;yv+q_h_<~f7)8le5L2?=?4Ttf*YTm1@1Mucab5dWIM1;2Gs3uB^qT_wEUnMJe zk2*dEi96$04)Om$ckh$ujwxonG+{XRE$RF-CM|we)mpt(R-rrjg9xJFTDpg z#D8XbyxUmXY0|+{Ab0m^1{v=iRCsG-)hK6l3kSEij8wCi!FX%>+K1@^yg62E7MI%sPH*|HOV9k5%ZdClR|@py z)bScf+{EkQ!z%xBIWei)w(@yAf=^mtnjWzsx$rwf6`MA&>*$ zop3L$ z)$qAU+$uJ48H?BG?p-wC9!I>(c(b>Sh>k*x{Em&kC{Mpl|Mr&bsW*0GlGy#fN^k=U zJNtE}@Bbfkd$7@>!?or3_QABj{Xat%nE#m+=>OTNJjh@k%Lj@F^?VRiL-Qcn-ycfh z3DQ_?3HgYf_Z%LRZNP)3bId(6&l8|QZ&lKGZwe$G809AqJV;q7Tq_iK(7T;Ui%olp zkYQLw&@+E@4>H}$yZS|=3f>rrTe3|=>#Qw$gY;%W)KLiq#@mCmLUdr|$HV)ud9s84 zC3gK&kNHwj-I(VFl=fGRw13>l^cCdoi%KtP(Q!N3?CI2A_<{6HHY&XJpQ(0H@YX6B zRYAl1cEYwO7;l~QLGt{+Okc1e65!1;Px#$#u*626NMyITl>+@X9{Ar zduCC=(jR+?kOIfCaV`aPyzlv0X87Gv#V$ZA_0h?o}yGI_kX~q(6~AZ<)zTh4;c}yh&zMf8;OuQ=fS{Q96H{2uCw)9-%`VCA#oc&x^d1MMz0_TuZleG*I>K`=>ehx zD?g4+7h|8Equ;$#)>IBVe#OSy>HJ|K(N^YfkfNl^Y0`16hC{$%7umg8sPNW{8w;S| zy(1%02@P)xkw|tJ@7ISE$cGavq9Rh(1H6s;lSS(a2@v7(>B_x#Q=p1u_YW}Mou^;2 znFGArOe{`7&P3>I%z-m6U!xyyQDi@vA-PK(KZV2zd}Z~lyN-_cO66qJ%}*E)Z&gGG zR(_Agg%&-3MZbHSx!X5Qm1Fn+iP71vM&jd4@7{@(2WZlfqWFA({f~Rkp~72t#bh4^ zZ-s}e7NOx?eeie}-2b1trbOP}O4X3~;0*94oZH1OmrZ~q+vauG-3PC?NEh6K`~NJ3 zrU4CrH~zjTx9vJ2G^>)sV(=9m?}<=V{tJ!jcox+^acVIgNA3I3@qQ?>!tKg@#v4vd zB02^z@-y+gF7K~GzkAp3_J3nphJ85k$gbB(kE}j1{p^i*?GQ~mt{qm5)ZUZ)_x}HX z_S%g2GiZ>wsXWNcY#bhZ~2#!um^4H^LK>zAe+ynJ52!(suyXv%>@of zukycdW^z3R>Ra=0C;WnR@SJ`n_ynol9fK?KT14pEhPhck+R;7e;+MO7J111}-;p>! z)@2+|kD+_eMxMLb32PazL25yCgkj{z$F}XjnjZR>*ovR!+r}lZD@fwY=NBLHL>n<8 zg7oCX^?8gY9SxN72YO4TAL|&pFBIGg@(7^=-WUT??H}3PB7kSE6skt z0eC;nJ6&7{@IIPb>o@}NUhHm}4==Iz*2NVV0lbr%wCt?AW1(be@4dC2=y-qgf3nW& znF>A~iF0e?`9QC@BbP{`s#VLjD z9^4ee^myacf@srGmd3Lz0G=Raa#G=KTz_wzf_Is8wI&+gW!`Tt!gxnC4w5HG*P~Wj zJ_LA|c}5+IXdpl`oP(p4H&UR0^Ssq?gQOZZSYQM2e*SSD*SZx%s9vnI=EXB~ygl7K zq%Jlq8j$F!p3ZE~~OX+(qZZji1=bYSHd=5q91e+B*S9mi@T`;ny^bN3e4 zK6Nr631>`?Q!-@i>?4|VByUYm+f@Y5|1&wL@HW~q@eke^K|~ESyi>M9JaGRXX=p_5 z{|V~uO>F>g{u0Y%LL&jVzk74%C2&b_ z_F&?@VWQmWhjKL2o_{z$u6QK7jb2LI1)E9Pgm4B6&>#aw+s*8EXKn-6VZW{-|)GupKQ+2@7`h-X>V3n zVbA|@B9YlEJp7p+Z(L5}ep+-C6qHYA9{$_^Gvo^VpGkowb{>@nSuK! z51OvKwL9K04ssTF8Pk0SeS&mzozWETu_@^001p;%@Q;iJuB@i{7Xb z3f@)R_w~{6j#|w{e*fQI%AI_Jw7%eO>u!MewuIJUGZL8pZ+O4;_{|ikyj)2WUSc=0 zx9^Jpco$w(w>dp84$9l~dJ{`EI^NcX`~%tP>i9w=ZgP3`P(l_u-gP6*GxaYRZ-TS} z(SeoU0Xbp8%Ov`j*gTm~d%YLf{eR+N#nOp1N2c%p6FcN-($SI5a*jm4L7K@&g*Q|> z*h;~B$h&ee8s3k?$|c|m@|9%_xj|Yher5N0fcF3|AAfQa0ZMJm)h-7O(z2oG6>$GA zB>LzVJpWI*vu!>%PaJe6*@X>XfsVJ z)KUerCCAb6jy&^g&G{pYhj%riBMKwGPa8Lx>)O#@oV+vNEBGdZh7Y8d-3>J0-N5t* zq;YjawCPy9L4EFe^6o7U72f6sY0eb9w@e!9qTwBS^ecJx_EUg9yzlB?@r-W-+gnjJ zNp-8y@vaR2pdQYvj$ez!1s%GtHD@t8-p8`saEZZ;SDc(gbd+J_7msUN%JE-(-tvz3 zJo{q`*vDIN(Q;}7T2suA_YystbP#(?GSv>m{GI>*XRpnOKZ7M!n974}wVj$^50Vv3 z33wP3f8mhr?{~x|{VYw2hAPX+;k4di}Kxd=f)5;&DKnH)lbC(1a zWOTp|$?Kqklyca@t0Wi)$t=0BxwaPFgFKs#t#l1ofR{kxLg%n7vp<0DLB_r>ql}&{ zVz@2#AVh~LMt*rl_*GWv^e?e>(b}G`G-%j^B#7^^(M@Ff1_>v#kR~0;bu6!oE6Eci zAu7C=-+bUnSz@Q(UN=F*`(XCtAQ*2`oKO&q_YK`)S!ICtE}gFegF(>5$?3lWseeVdGu&ZDH74o9|4I_X$lgnsnr+ zl_VcZCU0*EQsKQUZ@&oz@45GKjnVKvv*oE2jQ9TDkpLL)$hA3bFy4vI$L`dh1-rNV z%H-C76QsBD8=PUh-zUuz>;`!2DyU5@XeL5>3K5Di&ggij$+`u#YRlnuk+=-62bJ#) z(D7D0nDMr)i}Akymxbt9gpr@N;f4pqRQlcfv+>RJgc9ug|G11Jl0Up>m>zH3*+Vqx z@Ro@aPi!Q+w*VF1OZ~XbD0s_t2OFW`J*x8K<~4wKzsC`O7;n|KIXNl-Z=Hyz_l{pC zKx1#E>j%O4e{tJ3Cm8SRuLGrf0N%IesyupfjtGT`^E$JxM8{i;SA}qOog$tRCw2iE zFxNuI`>b$?mha2O4CmhZhz_j$1dkkCf9WRuc(Y}T568=3YGlkw*NZx9_=`DqK@+Be^Y{^EpNnK;tpK|}vPAbBBz=l=(9 zZ+A=3rh})&F&8{|CrxP!5gH)Zztc10}t}6 znV0q$c+lt-bCE|ch*0pBqKef-^d;6)wAm-QbE3r$iR)T&-v71_x(B`a_`oTX*?W z<%bqV!@CmEp@ETKk4r&zKM(zQ>%6=5(r6KO|G%EADu3s>ai+)nwSFZ{Iwo&VS-sC7 z_y3|)c(2?&?m)r&gZ&sQ8s2yE)U{!}XR5s-V7$vVYt7~Yyp0|Up6fkAfUb|}>1+qz z|GOx*?+A?dbc2`i9f0>dIipFlUEl_(FD~C%3?1)QUH;kj*;(^nNSxgMv7wM@^b@29 zEJIFbTh3#+2I(!LBM&3LkNuvui!JGIkUDdkIHE?d-8&JN;Anh-`M0+c+v8}`F;@3s zy-5YRL0UkC_lh;!lPGxC9cyDj!#hWD;^1|F_tc5!8)3XjPG-yQ0=#X1RXoZ9_y1X3 z64L9z_y0_qM8Cs$t9S^mx(V?1^7$a3lR$)QXU%Msh0*aYYMpN`%*KOXhQ!Go){2*z zM8`Y+PHv70IOj{G54^p#Ou|673*ddVai}ZoAQ9r#Nd59c6&>%K^XY;=%?0pWNZc~@ z&vxFt=*0>57I8O&2eJ%@cQK-a7bCyq7wf%;dg*uXRk<(Ni!NfH-oj-K+#SyS#QgLB z2Sc>!@E*#8-`@V)|1(;-{y*dc`hRIE4{{zePNpoesv8}6(LAVL%jY<}#CquKhru4y zEf%gxIJ4Ly;;v5G>j~o4Nc1JP)_zLUe!B?6_5aO?juRO9DMN$`C4KrEq_nhK z_qMgr;6XP%zPR8;nZ7~7WgenU$02=TJ@WhinNn1EJJo9IQ1HI^WC0Hv-e-Ex&cb-# zbUPYOUSeC4cLxK!FFF#=&ejm1mpXMz96zQ&CyIBu!&~fOOVy7b0(eVA)?Te|iG@}u z-LaHkjgGffMAF;JA}-Q0ByOsWEi_029q*~7Wf={>#TX86Lqx|{jQq}}U7ywcLjMxG zVtcH#UM2SV|0`m_J(h7fOpmvk5_h@egjqZrI^Lf|k6-#}EWvPiA3=0{z{oG&W?cA! zA^q+xIU-P>n7V_uyEcwejYe%D({fS$bnt|9a$1$wAxln6ISu1!N<8v)*1PqXZ7 zS0zGMU-k^&Y(dA{+GB1;K`9TZ4T<~pWcjYPqv&{d6v@fjPKq-e-ir|(tr+?F$n>tl z|DxZ$jqXaMr(eaM|Kn8Jiu2N?n123`D{CvEMTf(ruG_so+gsvPc&}F3VoAaKOvHW; zG`u@KW{lz4o5Phd^6c$nW{3C?!24rJy`xV70eYjKG)LxT3iNW}<9+b29qh38jozdoM7bi`hhN9GU#vb(18+2&IU z}UJrkBu2-O@D}#;sfO{suttG=dn;{Z)%Qq% zHyfMc>!}g~w0dQ*@fg6HASG@j2k?&UT|MIu@V?G-P3z}tB6MVVZ|;RebiC`*f(922 zeQY^^#7Q_t`-KLeibF80DXth>mKE{CbXle0BUZ{qEg82WMBQf_=Ot zx6-6E-BXn5E6Ac#YiQE(N>d|;kWO}QSt`8OdY|4+!Mp6`DSkA(UwKB!!@IY!JA^`E z_co2$uiyvpHVXQl`vh!nDda2|bpgYPfs!{C@Z&`HZ1XF&0KBvFYRBy#5+T#wC+{EK zgpPNXox9-3%9$1eB<^rs;Pp4o=y8>oc-@%TVF%!u3Lmg7>fVNIo>Y>wc^v z&))bZ7t=L+i@xWy$QHPF7T+`B>7D3!&nq>(>@LAV%0%KcMa~?r@khrye)i%$iCO`M z!Tb~^gT$zy@E?p4|wscNZb~g zo_gzM^gT%bW8;+@RU{d%|6haX2*Sv3VCb7sXD$6pY=hN3g;hN?Jh9Ukw5y2|$MhbA z)2C5K$Z;O^KNBQnD!hGa<{Y5ltt2lXiiUTXQ^+P5Z;Jq9^8J6FMDsuefcKTR4w5Tk z2++3A6?1w=QXqA~?{0Aa-i3)voE?}Z?WU_abK1^%wm4L z8-IPKMaQKDcUph^PJtgtQ=-D#J1~O$^;Y-RE?|q041C0EtUx^quchZk{$>HP9x?0#3WTwQ) zjAI>NnI7-<^lF-PGz(N1oy{XRNQHGPjRA1g|{a^i$4YL-o7v)G`zQ74&4speJj!258mG5 zxbkpECcqot9wgiazW?Xwy(E(z?A}(_q`!pm{?NNK+8E&djO2`4M~s7(vn|0_FF?Ql zzbCSYbb2lu-U5lURa3H^`HhZuP}b<4XIVlFhj$L5BNQXQ%xfbt`~HjJL}K?Yj|=Cq zcW-fDBbT=YNHRa(SBNy}a8m8j+*bX!|Nqy%n^FEHs30||JSgDR6LpFQ{f<$WM)RQY zCwEuDN9_DQekR`_P5YG6)CxQ(T6n$Mg8kqVJI(i#_J9gUKELWKB?Tx6%*(U;g+*YWCt(f8(TNSvBw--F}k=pMAo&?L~w@+ZR$NV(nq=*Yy# zZ*O7YN$z#@FR?y9gB^~UV>d`QUv2stdwVm}d(hR~NSbsUO7trWv?EuL8dP}u=cPMR z@GctuDT#)6iH;g8jJI=pBl-NlsF9oH0Kj``_lehs(g{%VQi%)PqbX3$A;I0-7_Qe2VNFsF6o~^QUE;`;bQG-b*PO;+akhs;YAD`R2LEpXY{In6j&XDmc zNL=(E9bFjt3BN4O6MaN~|KE8yj(6!Z?Bgx(!Zi9C#>BET^LgEypWZI%1qT{XT zH0^h*N0i~*+Y`~Dgppr_J@2%LDE)X#-46@(+eL$W&)>r$#m)Smw@h4=Nt2Gjims14 zE|QBARVuvKPo4~<;9Ylr{X#UnU2z8|;N4q^2zT=R|9i>jg53b#yUv&v*oK4cEy>ph zJHgvq&hwr+!Lv8LHI@dE0B@6nFSkl=BSQPTrj-SF(cQbYGxer+4>vvoiE~Ox9(+26 zjyK`z{MENr8SiplXOtHIU-JO{zaEtbZM<~wpBJRYm&qxjc~E{tV*-2!Nh$W$W_S-0fA@fr zC-9)uua`8TP6FhQk5CmJ0&kG!-wPB49<+Fp*d_$}f3^?)8S^uV(Dh-l6~|@KJ?NX- zn|(98L0aFnR(e64DE?oy{xAGXiVh!){7P9_KP3L7--C{sa)v8# zVlT0MZi*9}j*(2?|6f?EK$DK)--B|wyU9zeE*0LP2R5Wpme|tRX?ZlfMU@V&gz-Kl z`I~&ju9L-TE(GviQ~W)55WFC*y~9)H+Vd1>p3;4J7;njwWjIlQw_z(sXt*B{s<5v~ z=KFzOK~76g$Sv$u$4Fkm2zDj_44^$Zt@IL)XiS{{COr z)Pcw5G7S@?&*jF4C5TLqH!krQZ91lLKbHKNAn8!y9TK+fBL(kDg%&w9yr1Sp3d490 z1WA(dzO(h^atVO9kHs9jiFyL`-i1@KbvOljUm*Q>0l>S<&BsR^;BD&}{l%3n4!YIz z+3ML*bocfxIsDDAWvZnMiE9xJI%%~V-MuTfxN(oDaxfg;K8TJ|jQr*nwcsN;=*L^H z<>1ROBN`@1Jl#6MciEY~|Ho~(Nt2FMQS>JpL-bXAmWzq0nEfoI{ z-n}(>EFT3ICq@<8&L6<`R-IF?l_>Z)(XX2tCW2u1)?xXhJuu!UJ6j%00lec?&arR( z33hKEZqsYYMaO&b9sUoAks~bxBref)mgi+GI^Ic!L1txN#~JQ=iyERM1|z?mQ;w}R zkLbtS;KYT9@_KB%x4n-EBxP=4dc42?jH5{hk5}dP>#5}JEiEd%gLq@MQSeUr;wFQJ z_XerNTo~{6BlF46TX@?1cwYa-Uj8Bb!K2qH&<(?91~A?SaHZSi0NxS< zTp?*QL`X+}B%uE=I^IJ8oPOPR8_iXaII*c=JGOXqyf@U@pBf0d&Tz9gjle%T$}#f8 z%P-1WDM>%xnxAX#tg6GFz2W>ed4zqN%k;%bqEr-3IzC+~h%l@A+yDPBw43z*Cqe&j zNaaCM_doejJV^Dah#Hy)C5&%8+Y3A>sdXX|UScyk;@k~E1(}_Zm*&Od2<5Q3jC=(R z5|?-v4t_x@`{IeI^I#8h{nq5shl+8KM95}2`&M)hdg}bD)oGDDNeqd*lyO`gDNVMsAAD+Fo z`p@_O45;vq+&->N!JFVcqJoAu%lpS%Fy2-LPy&p%M#Rrf_*fS8ivO;}&$h zPp6w)FLl&lIJ`F@I%+ZUi;6nIx`|B~^O=hO^si(gtD0mQp4f4dN#79={E_MLmcN`v zla9W-nNqLtyqY`td&XDrBg>6MOd-w>K~FTHrUP z#~YVQqmI$rdU=12x9C&h9U)wxK*4)eL!uHI-laA@89e~+VouQ*81KpKsbDXFckaG- zdh*Y}>n)FbZq$GQX{DL~-$H=*RQR&^?*MPYHj6ps?L3FNYIJN7jt8D9bV&-fD=BW{mto5-*88jiae zB-8i*Cu?cbktHu4p|ykD|1YM(JDfY%hJv?4r_&-dyxpzto`QF8C9Jczzf2T{AN2n>H00Dh!P(pMOCn>}dZ4?vYr4pb zgi&77DJ0G;W%&ykJi2?&_wCP?*Oz2CyeT^PG4i`pv;J;g1O2nN9~q4@@h@p`@AW$U zD}J#szkBc2rb&n0rf|W5qQCwBe-^V0`7`MM&8R$R`)O-0iU)~{i0GhsQ0Ckt&*2Kv zQzm~0>_G=7l~mG!2Ynr#=Og@@0NuTR`O_ir1*!8JcMIzP50WCNbi}jtL9sp(8s49Y zP}joQ{fQaq9wf+h?}rJyD(MOmms2{c7Z8E&L0t-0e$my8Y`-mEKI7qCis;D3$d4%B zy={F6{qB8TKCWG^hK36A3ICZo*56EzH}2&;nsi*_iPX9M=YX^^72aF8!zL+sXBuqR zK*Rfi;ha$z@3swBli=cH#mP4s1c0~JgSpGwX2J6oInUiH!1mVe{_=*L@E+A&jthOf6o8?(fjT6!>j|34kdN|O%J_`|M2f4<&gM1^S%axFetO{19*!Hhwp~*E{}@3tPSu!*_M3Tp2ra~h$6D5fa@)zW?RkS>n&ri z6{ku7-bT|(Ug>AS;Y8nqclB4GtC4u{6B6!jXL^Psi=a(iGRQU$B-TW z|D6=*|1GIJXvc|<|IGgbK5`kLc~JP+L;$?RewOdp34734FW>8mz=PO+ur7Igod6XN z7N6(`-ylgEo|=OD|G7GydxJoOlr*sXXKHdRv}2Q>*KuL=1Jbpv#G{;xlu490ji9SX zmwxs@9U#hm>(!of#DL*Es0Ps?jgjB6v>!bA_vqh)tn`c8_+sn|>YvL$f7yqjSC^yagphjbXfB2XK+`e*NG?z5&2{ z@7=+Gyrymzo({VX>W3-PWWS{EOMj(2zI`-c&N z$|Pz%)@xUrmmyhrW_TROU6U$MiTaNVPB zRLT5!8wt>)Lp$^$_xi3R7;lIQ@3=LqxhZ&$rZp@^!#mv7lpDs|JjAufKyR9y0NzqE3$!90#X{#-cQ32kh>myDxh++j zd6h|Lkhq^-hHG}%q2paM##!)HT7TG#GC@72ZUaZ?7nLr-y~`bqapT5r z%-Vb6#p8rpqbQ~?PDB!E)A9L+&cirxyyb8I|4;YDxW52P>~bm(+MUN)4||XtctQF% z>joT}2X&3luZ1hfp$9|c36j&hH&W)ngFXb@T0PW8fI?*wTjanCQdzOPm9>EfacT!o zqyi7R3bCj2tYd6XUc?Hq12N~@sQ{hs;{CkjQ!nElKjIEISb3u9;72dntwm+jR zvBnFpnxNtRLDZ%k#@laR8yRmQpV>2u0p6)08`n;@6QG6o-6jjb_SOZcY8Q;Rc)p%% zBEZ{XL-4*Wi9{&<(|)CW3(%L?my^aEA9g5{C~;fokOVEhqvKsol<9x{k@4^zL3C7M zHOc_*^S_>)HSZum`;O%p7=R1XyaRWKV7wud znV49BH~!;Q=eyg9(2tv*ZmoRic;6=|#U~t4CQ;&=ZnDeRenQ9ll%tf*&pC`&LEb}j z)L`UCT3GGwtxbP}q<>w?VS%!Fh6I{)G>FHQN^p^nw^&o*z4QBu zf3~-L4|*A);a&ei{Q!)2l)^SL-hSQ${{;YV@Qm5kj;jP{P+(0&7I>U^>%&?+Je-g* z2ylr8c(1S>E%wL>5Z>gh2hsc0miCz3|czer=3h#ue zNoPuN(sA9=5Do9F6>?;}=Y8Kw7v85$_nh>ujD<9VZCor2&};7<+H%e*%E}~4+?~%$ z7M2O3en(Fn$_!1SAMfjpyWj7Z!QS555&r!4u(A9<-9mgEDdwn<)MN{xZT`G!Kd%U(ZKA|DSC}g!dp< z3Ei8(fhE@Cgo3u?H3IZ*olD*<=>PkbS#(vw5-YZAq3T<(#LC$Xc&d%YLfelKjGeZl zdyvAVkvg?9dD1o{F0Q<9(fc*%9uyX{U`ex%9>dN5@ATDMH&F1t+ab-4hPScp^-vh^ z;ib*w3(~$WudeX|yf=96E&2i~$oDFPXVU@R4JIoh)BxUG&6?lt1H6wIUo~&3h=tk= zWi z`Ty~yKfiK_U~hgoNkauGF~ueE*p}(>#_@1+)1u>aTJyz_8gl<{M}>EqzTX`R-nBk6 ztY~=akb-Z+c%P~9CJ#u}dKcV;-~X#xoXFz>`v2#w!ePI`@fO$RS&i`ZmR6SZ@2voD z`SV4c(z|1!E5daaUj)(d{^=0dIhC@AM2Wl5;3uH|5&iU5`KNMS94q6UAe}~Zlw#z! z&95-r`UCxVZ4E`I(w7hbST)pRo67h^8|R??CqMb3Glu%@K&h? z;QhhI`-083ScnaOtMCpxI^J2KF5BW0l}PMJ+?V<_i5<_;@s7dQmgGz^9^U&99osPS zldA8U`fNmhapIriti1j{4a13VX;V^FrA&`E?qDu$I-K$fB>oI1Y^d-~nYV%bc?)>< zW>cI$2MuqRqpQhpZ}Irgko$kr8$;`?LVwhhKdl z>;riF;6#ntRESXfFFu#Im(lTVn{!igKtq{y1&O=&vcht0A$oE0)c2-YZwce||E-9Q zM;Q4fF1%sBeKq}fzwszL;5&@n|KDHt?#`R;eN4Z-W&ipFO**1X)_L{b{CofZKZ{w0 z{2BEB1S${OUmSCI0>F}AmOlbL>r zwb0v6la4IMzDDm{a)Y#*3hylYUJnZ1jd)oeG`xrWsy4xRhn1Wr<2@5&b+!`V-A9V^ zmgpluYG+P-F8lyakP41Sz@OOFB-Na>0eBxZ8DG)g8Vi-YuTJB4M92G#zx*R9*M+1a zBu>nt@>R7aI^Mb5B>i*EDh!ABX+%dBMt+M|21R~(MnB$?1}0h@A84o`=O=hb>0~iI z-nbYdZ94Yal&buxAXic0y-(ooJ__E;9u0G$;eFCxF9pV1<0cpRfi$nIh}=s6Z$k4@ zLED=IsD4c9g(LVtx@mc5wIaa#oz%I*+5qn|QN_3)E=1_%RQ&1wcj$O8oLr|`Ge?p% zjKq!UmEP9qLB~7!&b7x}uIdbj_X0#m0!Ds&7W8*d6w;5km3rIY^>f&}x46e_TV8Gu zW&Q)wleFnrpg1=WcZlrX4peyWdGqa`-P?B~mpIYz7X7~9D2#W|;cznESHH~E+=Gjg z_O)Y@-2^CeYtfk!@Id;hV)qqF0B^zL7I_N*-tt9G>{rc*5MJ^DKl>eYyw#5S9Qrvc zO)^K~&bS(-x7MTMT{X%1P|aG4;qX>Qbd+M`H`aY#VEupbfi!{7pgc_L#@zJ{(spe5 zQnZ`t@%GT7O~*3ckBcVK$ioSHD!elr`5#f-`@^+V4m7+EO4>HSc=z-?CgUBrcqkD5 zdaLk_-VZyw!10z_{ci)o;Y8)hC$sSDE%DxaN`8Un(15i&Zz|*@B70Y zPkyq=ktlJ?di56`DMH74yr8ng?WhjJ;e8L$@d+b8qu&i7R{urq-L`A1gUw6q(_1+G zRNU?z*Ob@y74)s z^jDAxUkfX{WwG}laS@Bs`K7a&zd>50NShAbFj37v4bmDaymObkbx`nL@_vB;8s7Xm z3VP%dq|Zjl7o@G0bZV>yc;7dRu0IKu*qw`t^!ld2^OgeHk7NPfFSfbQ2>^J1BzykdQ>EXI_>)o$Ok|=R`sTbb+$NSxd?nsg+tcRTT>n%p2cQ{jD(?T0)C?@zAx z=Aq$zPeQQ^p8s0~Ymw*w@3bDIy8*nDrAa}tHwaLJ&IdM+$rPy3VL=^?w>w|?vtWSt zu{+ii_qGtBPE>dwc$$+$ z!J9YvBtIJ7KNs?mKX0)+&w+e;tA6I^Mt^{J(}QNdoE`#n_52aXDR)_}}z81F}$ z7Y&60yrp7x7OMosLZ(aCZG|R7Q2$zXZfdg`7+@*T@=qtE~Ij18v`rZC>; zEp{L}vN7`Gt}yE2a;4wB4Q}zCjk3iaPH;AVF0s(v$Mks5_Z_22hw^BBX-qxYy&b9W z&ORgGL&4kd%T7Ktyx(Pp-h=yp&)Q|N@a!#hw-x&qfcLW~iI3c1IB|;bVPWk!7)~s; zafk8#u_uu&3gG?VJh3|3B^FxQGSVXU5*_ay?7gZgq9UXfNSserstq>@9q;h0$_o{T z6&cRG;}9J|82OD492^KaN~U+W*~;$7yJfk>OtRKum=SkOZ;I0Jjm=(8eShf zkTw%J+kD_2@lN9z4zLDzzi|$qYX}CU zVjVlf^QKcEqGHfE{6PBeF*9`wfH%*apFPd<;vk20!8JP7=y=DCy%b5ls7SI$;xu=^ zkXFh<$NR$f8J7YheTJ(bV-X$o82RnJQh#yrBKrIPA)mDZeao=t{|{DeKHE2$%=CCC z*wUtBiS<0Yia#GnccsER@4<*K1@EcIQeiZ_?{?&0fbq7kWF_P6>*1ui4B%Z;aBg-j zc%1mjfoBg!!Ei$BYUwOIoY-IJxsd?y=8`JU?*w0OJ%8wX;h`*ayuVz_vtD*cfpiv$ z8*I}E8jVKBn|EBFeX%s--QN0)=-|M}FKxfxA$u?S-CJk1^|A9p*dItwY_RyLAI|)E z<0@#=p}y^RRO&IZd#|O!`|!~_=P7ve9|#sg!~5JdzFZjZ@3Jv;&ECv1pADUyB|_g7 zf>$;iLC4$q<1zQy0D00R5*O?yCA@40I^OxAQFh{!jQ8zrCqzdsMt-eYxpIa7#pT3x zqD_;rtFgDYf=h~ZZZ0P>eeFFrt%xQa3#>M-6hHX){6FJ0`~O2mpg~$kfdZUCMjeQw`Lo*)r5qcp|9603FV6cqK60Ld>}lyAk73N^M6d*BPw zyQj=G8o?PP)s8Ui{tA79baIPUJzF;8 zRghkYj!KODq^-Rgaw6zoVhMJEnX3-b(Epz>+4^dXmFYbQCuK^TjO`_b{dB&kHqn@CS{!3jK0L?c}Edf zHZflRAC2fZfRUfJl;OCaGW~d8<^Q}{c#wu8b{BTF9l4sz{CFqrrb)+B(tI(K266@I zO@(&}+shmZ-h2mcNTA`}888qI4cfF2yZ;aK6O%ZQ&(HMze?i_tnsn5RG>~k! zljr|lRCph~`J|PCx4CYSI2zv4`!{sJcxNwJO78zFlvFqC0=%D_&mQ;gCqQ|)`f~!m zQy@*-=}Gwf|BZ+IqtgIyjs?)1<-J7cnsvt#*#LCBUv3=RXI7_7qQp5Bo9czwqT}r? zP;z{OG~>PhH-hMJ!^m&9p_IOvJpFi|T6!R*X9&ANO6+?!FK5ntrpFtnI7E|9(&1#O9gJ*BJuUE;lH}Q>^CE?lIo1Jm(p*LUMF8)Z0Ob}zu)Xym@WZpy!$e47r`rwwICQ+Dr^Ov_*(sAKak1N0e0<@9 zj`x6BmZVcN20 ze!7A(H||IlqS-fw~a-=E5ZjvpXKP?lJk4ogKe4~o{f{i+*yklT@@t?>MRyEtg`j#3n9uxJJ??f)Avvjce&dKmUL0 z^PZuZtqVyUNSyDhwqv+T^#0$)Y&z@bW5&B6-Hqt5#>j78)%%vmR`h$2nCH?B4|8bf z|6?8t53Cqv{yRtyr)kq+>=KWh|M#Q9yGq6A76os-&u4iwyuB(Fm%>Nv+J#ui_x~He zFWk2Y;Qb)Y@%{nui5=Ao^Z0IpCH82WYbuO)@j?YBk{*@2FA^cahtajo4(Lnl z5B=on6IY~2^N={(*CksBI_OI*aTlj_8J{M@4M@KsI)X9so9itzetdd9>WNx3Uwjo~ zGQ#qdhW>xQ(Za}r?abf*FQQGy++%B^e_S9}kQ=D*uK3m@N5T8awq`jryidJ3Rs-Wb zC31p%gS1uk8jCx?d%4w|%C$)Oc)*S(0D_QW#x=_dus~O;fs+U^y1l*+!p%XyHF-Z zMq3QK|5rUH9W9$Q&h&T}ZJ?Y}0V2jhKytcRxz;C=WI$EM$Vh)@{M zPE#X!bi6$iT%JeXmM4WGac7eBYnvO`MI9@vRCyB{q8*< zzrgX%eeC`p*JiikQ`}dk$2+l)HXZJ|?e%^YWcOZAg?Cws>p!oz?Ah-sgNFBw3fy5B z@0#LB^7sGhdG&q^0=!K`INdeg5TMrJ>kcbeQz4$bwpsY~R=op1L&^c(ME3Uw-yS1E zW~m&+(?;lc%NvBRI{j6FWQxSy`;_c{UmP88-_&nCo8lPnc#ABe!yO~P!r14cX^ZK1 z?-P9!=}WP-H3wu@pgdDMMm^7 z9^UPU4ik+0cCD5Dpm&&l_x4FUwBoclcK=`eljjYe`zxl$+fPoECLO+c7wlwr`GqQmbB0}~-@WUT9adKLWB31wRg=Qo++H$0-nhJPH0k(ys>w1Y zkL=z7RCu4rGRdU4w;8X~A~d{j@mOcWc#jNAZh_tVvw+%({Q&RW=697v&j^rIl`m-+ zTyOc^wx$QhTT%Ar;-dg>TbD-fkgV{aPom`~L#D+_Ue>`&dV#JNk{e$ z`n(rp|1(sl|34=K`u_+j4?4H3;-5E2c5w0Qpm~rPpZj-s57J!q4f*{4Jt(PU z5_r(HqEAs?-w9CkLlb`eu@orZBA6S#V)tuTky;2igVfTp{pYfUySELhY%gb82JgkeZ_&}r~d}2o8_3~FCXkH zc8?^V<|(~q{xe7)?H|&l<6LIG?KrrD1n>^0!uu?j>pusi@23uEq2ayq>5pa@Z>^z8 z@)mnwxU$VBfcIB(JMNjE1n980XEPDtO?u_Z2jBl+<9hWV{Qm#6(Ne#b2qF}^SoDq@ z8#> zv#x7h>$=y4`fbZT*HZo(e~JAXs&>MC4)cxJ`JMeo#~_XP0(Qo(BCcf|Z$FjVq5MkP zJ4nJ=!uhnvtpAA}p_q+69g9*|C-0|>w>U_JcYc?^BWwq`V(jW-JiMd&E&UL@!+6Ii z1Jb-S#J{`&cwfJpD6@oM25)~eL2L$i54D_>L2i)prz&^I0le$CFS$3v&?>xKPosXHe_UDITZoT$Yrgb)g$>MCAPt~8%4o#5>Aw5nau3FLkmv7x zPq-{byZ#UOw0_rF=o`xyNG;|Y>C$n3!=V{Af9n4ORCwn-I4F(by>g|83Lf5RMz#`mVONJ_5j7&vVYjVP$Z7 z+cU_KUxAOe!?79p=Z?)R7f1a#4XkXkQ}OXWuwiIoVwMck)&F*=4l5e*9nrabHixz6TkDa{`D4uk}F+0E{>NT_xjWS-%o{iZmex4hIcq=gEAi8?K8H# zMNV(!LlY?T|K_AfeyRg_KT1)G9OE&A6$oGX(*fRHR$&3i$BC<&US~W9^?%ir!|%xD zKJZoJ+5Oqg_;?riPi4Inm|32Q`rYv<5c+ZbAMh?*+59An`A%>1Q5}{v;!Dxa)HpcE zINqd(zIQU|=>Iq0I8bb#{+Q+Ke;spIx^$=&{km^-@^AhBp9^j#`za`p+^KTVUF%gF zu^e>o^K5Or92EZh=`iw%oi(YF@`>Gw`ZLnMKn}A15Tkqh85zDAv1-Xt@IYFgfa|9@ zAO}6{@5$){ODtiViLFE!xIwBKvtC~czd%YXFWCz7N|hf#{j6@^=}9Eu*Z;MIrLOK9 zneU06XjDfrjri)n80l>AWxPPD4{*Kb^MiJSbkr~;kxMp=<#&*KB_rw5@pJ4LxgwU* zL2{$QyO{HrJcf5*^kYptyi=nq?jv|Vs+>c?yY$Ft-%o%y$L|km+~D(;wCQ_^F#vC; zqhiW)0p1EiOI9=jyyF!@u9=wn!0Qd>?E2V`zr+qMZEIAun^(RD^|MmtJWy7Nzr@bh z-G4Xa2J_AT??ZLWq!C}=aFIbpCgTN?<(B*Fk7UwO|GPpw*>~bt9`68{hb|pY?~cEk zf0c5)b(jk8!pC3#HUFRV1O#t!_dS#eQX_orrxCm-3nCm>fD6*gtd2o9 z0N#R2<{gp*cn9uEpIZpp?7CeyF)%K!m-akB$cHu@@dauCf7naAHK-8d5 zhxNVcMSm_Q9-_kgj#K^#kC&GXBZer4wX$ zN51UsNq~1O*OZtPzYekOO&kkr% z`u_&chs&El4!Zo=P+aFR8TJt?3f}lJ7#`G5Jt+=ykfcqO)da{v=X2(KQCjH>e?O|~ z*7X!W2fc{PUGV+dyz*t`QPwCR3TNyp-_J~p-c~RkA&Z!ZJEwNDsZMt}P$Jx4w zB1^27=Vr}1XRc}tjX2l;csA04}B#CP*4dt!bn z<2y*pb;9JgJdHH*UbW5X_rkaAEI&a?w&5UMI;OVUgvCWtj<-Ci@GdR){?`Z6uB6!I zczF9CZ`_68tq~kaDUe)026XlUyob4s&+U6chV@TQHH!kgpYCRI69&Brxiczi4Keg7|j>LAjHk7IGI ztZpOY*}G+#3ukX8?fyUE^{lSJULKamo1iX2mkyrm=Y{0{G)O(D@Vn*Zpqw^5Fy~}=o`U3Ed z_PpsO4Ceoh?=mU-vm%GUl!j-@D9_cIfURX zJgy=%T<-&KOYJJUx(gp~*X`A(%eP6FZ$|y9xX*maFv8E?{Rdl%?!0Bb&B;MjM>~!9 z^esm`3@aGV-q9R;I`eC3_udF&r`D_u=4buAw`4S3Iy}qkbH0J>{rCR=e=fP1>ZhRo zKSq^i@&{)c(x>zrQ(T=`9WYE@4ICh#@lEt5UGy z{`+89=Z2 z@HHyxm6nH1r%J{&?9F~VJEx^aSTz%t`v6k88Zm3_` zoQOolcznDGO`9rQjO3ZF{=bRp_}ci-@qKGeK3LktINn`hswIb8AJDA-33Yrj_F+ye zk2hf<4}Ch^Hc2b}=^*)1;ayc4JPRBLAd8?VPgR~yiAxI-W13|b}G?{U{a}zTbO!LsuL6V#r?2ega zeY`h+qf5u9n)Fw*{*1Tqp~CxqxW*WU_llwlHaxuR%@ooQymzL0Qt-ZcT5kOZP#|gd zTl1uKk>QX-8$E)+@m7msnkRBO(WNUle-sE|4-b!Ux)PGGN!f%wq5suWx6AmaT(#`ZF|XH z=&aS;axv6zrolb&{qp#DZ+K{-xBE8p-QF@obr{f!?@H2ae^thhw|1I7_>{;;d+$vU zc=RA6f0E_z{}XOJp-)Fu!Zj7JIr&@vGgYPkpMweB9>GSHgBn$>rm-AUW@5vKmxK5X zp?Am(l8o(pDI<1H`P7G}fE^?`S+jOy8W|RjTbH`HFBrD?)fgiUa*)-J9&SI7gWmEV z$XFoZ11}fdD@(}5FOWuhHSaVDe=A#p`Yq#%lIV@ZFOWPw$mwkL<6^o3sT|d@l}3DD z*S)>iBf$6)t8-x@UVjel9VB7IDEIR#=i>hi0So=qb2VK$&PS{6;F=u_me`0HRCw3F z==h4^ZN5gB7Z2~gxP+C+Cw4;FWt0JFkF#W+!~neYS1sH27=O4Y!|ky_n;Sk9RuP*wPP19OaFupF&#=@1zMn-lKc!l$JIK zGacUHsE%G5@$Cy^=l*5NINod?JJu8^(cVGs)4Eb9d*cbq<85|^J{_7~+(IdV$PO}s zK!tbRohf|`Z>3Xjx$*E8UcWL4!Q1?o8fALxN}0Z>lK}6g1f5>RVluq3ZM{s-KrnpM zMaCGxJJg8VEehbheQe#G&|BUx^l_tQmmxmhbuS15k=?xI)1!al=+hd8^ z&0Mv)Oow+as>6Xse6Mzkj66EcINrVUa=vAMq~n6LE2I@}+0OEK6TIlu(Rr3%{m=2% zaVoqYdVej&@Lq5+p9>G~OC;5A2;TR#t0^By2a-z*+yLGK8;&m8TT6zG1J>V{e-jLk zJ-U=IAK>lcuwDBs!25TgQ+t=C51d?h;-&g1KHl3B`m7BkXO%~zeq$CtBvV`P@%|XQ z=i$y==KKEN1l2J_BR-QFziPMtB74g|_jqhnLdW%%l@<@hSFOIwLfer49BMCpI{X&( zE$sdC{+~Y;-nC|XFJgELn+0*=;msbcmEp>2B=XL53 zGK2JnYgZ_;gVg8i+M<<5hHtD+lim+@kp1G^aY+3y-WKZP4RX-4Z?i4gVtruwFKf3q zEW$s7eubdlvoebaG0*}?d42HGmJdQ^2*7V?%@Bw)5H@4lo z)X4`vrMjr>*Dw4fc4=m-#jg9m^iH6Dw%(Bn?S1%5ta8AIlJk%N)8V}X)nP&-K68#^ zN>iH{$2-X-hEMe??IZS7$5}!JZ+%%FZw}c3L3(tUfB81-{0DD{3h$O4hdK;ziR}Y| zczCmY;*&*AZ%JWVZV28z)t)Ai0PpdN`w@F`$neo(`8Yvh-kqa! zCB3$Q>^(8%RrL-Z@5ZY!`>#A1)0>a_8NXQgO1J?ZZ?Ph&i4zA2Oo#V3REHLg_zHCd zOMb;Lj`!`MJ5QIT&{6+e*!iCh4Pbe^3Hs~l(@|oau12ZG>;^%?Udd-c8Hj&cX0b z;dbT6!`tQC=eG#nB|?n#-s(HnpRyJ7g^jDHi>2v#>pKLMaL# z@BYA3`}U7a=rJ4KY^aWlG~#Qw46=}z&v^Y`(VWW{qDA|7t6_6y)6NA}ERT23L;7?$ z4fgsKhy1PoneG3F{}>Ob|M{qLP^X~Q7c2*H)vpl8%Rwee8SW234mw|%YyF z-v*Z0r8RXTw((@xt1cv15u8Di$wEpBU8;9iJIFj##~B*&3GTjfDeW-hIVc-;IB7`F zh#f15m14r&ET4l22Sn)8u`#Ad{?87QmkRHWNB8bwct<%C#qjVxVx-!R;5`y`-x0z4 z%FJ_hwg}!IIiG$zM~3-cXZcwT2EzspH*Dkq-Y-@KRL%xF$e9rtT$+VhNVcze|H zh`QR*#`~z>(6*640?Ri@7dgiks!~FdVbxmFe!y?87ak2pK6+VY1EdbvAx36BXYxjY3 zzCVA|au6SHW3_sN6<#w*X{g^^p}=<=$oP0`d0I#f^2snA-sY%|l{Dh}6nTCAP!8jG z8{fFpId-3p=7eYU+)GKUk2m2mojR%-)|{oh-V(t@h4*8f{C*5?#ghkw@$i0TeoGB$ zPDEH+yC8UXmh$Wm0C?|TZ?-w&CK)yh$uyY&y|)VA841YgtwdFF?@@sF%8Y8Kj81TR zYj08_=ZcTFqj}uMSvUDeQm7w0Z)?Kc&G>ltUnw=)z$VFbcppb~e54Vdd-w0-v;T|P zTh^zmcbuC;yZ%qM%OziLrg!TZ#+TSuxMik*3++2doh_gEV)liwd=9c5tfEWDiQX5X8NtYi zod_W+yq{M;Jc8lfK4U@>5AVF*$8!<9FIxO?MwZxx))LM=$Pyc9am)nN|DQK_-0FD| z3`ZW_n}s~FJIS^3+8u!RRo)M8^f|zIi`0!eVM+LS4;o}WHxipqGC=))Jn>tS?}3lE z?7+u^&UTBL4(|`B4rLngP5p$IXI3)aAm!Q6zQenUjtVf-h%1~qY>YF3!rd)#6?dy}6p-tCl4yZ#TT$PPAKKZoVjUD zWY}ayAM_kY-cmpjYhELs$-ac6FW{UJgo1^Wa1Zq}_vAlme+f zYp`MxzGU*r&d;N5fAn|7ST z&q2;_9&#RQm`U1>`e~^1+duNc&p~TtiZ$o&V7?=EcT@+NMtpZH$(@cljOQTp+2h5p z=@_vSpm<|zPwZ}%FOXzyztE*auD48hbr5BV6{W)aWmS?5hWAE+PqKJ;pD`7dMDVse z|DA&OW*w+;0^mKMu|4$WJ~Hh0&A{MFXE5C8duF``zdZ#Nz7wz5`lxT7Iq z?S)jB2;+yhwvT3@OI-bk-@`T@<^CEg17p> zHcAJnuj5V1IKcbrzL&uXhskh8&VAp|F7Sc$mByE90Pmx-8l~(3-eNsZ{e@k8;E&su zU2SE@?;yGD^^3kGEle6h{T|KmTkQH8AMblGM~3!wS*EN1kD@xNX~cJiY-bS5AToS zKTQz4V>Xpi@Gda_BJl+&kPO)CC61Bd>v4yTBA*4rYEo+*mjb+J9nLND26+F>oRq1)Di~-Z|8YRl-}FE3;i;m0N#Ny-yi3Pli}~9eA_F!gW)sg$uCp^-We6yW^n-T zCW~~P6p{~YHoBj<>Iwel#9dAFxcrCNBoowcmEq6j^|$cx?%C%^xV}rC>G1YJb-bYw zU&FlK2-|YTv$vO8?snHK+Wmh*;*w?8Zy#rQya`+0)1@Os)=_FRxSaTR{@;JBxS8vR zp#Gmrm4n{CJEw)^pnUx~N_aWQqcQ6!l7se-dQoyvV3Xt4ZjghfFNYO-x{=`y^V0@K zV2O=u9_CaBIq3fNrII^A4tjQ2S9gyEcp$CA?qSd;{2k<>U9l_O?DJ8 z@$Vp6kF6Te&11ehNPeh}{WRix>&Cq|E0^&cl;*V6(X5n?9Hbq6XJhRDg86@unRMyU zzmev|nMc_{N>JfFbk(yA!@GB?M*$D-%N^4@5xl2DXHoE;Fwhz71$ZwtEpoi)0wzei zcNMgN0x9H>XeNSpWUcl3tpM+d3zsze<$dAuJnMvkN_@PhD$c#Hs}>{`pni7O*GF__ z;^QrEs{KfwU5e?JSYqWL9ojVF+onNy;p)!#4zk}H+7J~^yFfbiVovtw$8T7^{x4Qv zOqY(H0mU^}PEfA5%%Q@2@c6C87~U`K@)qIYy}rVc<8sI$w^%x_^Tf&p-lF0Fv&C?k+L?a*g=!xd#NnQ9m$dB7j9Ddg#L^_1} z-I5=2{a%E>gLE$RF+Sla&2)HAqB=Zi#3y)Y_mY$>#Omhg9=0<9Ju?ec&~(jgHq_6pgov7CmBl zya}ds>M(ogf}Y-rQQ`esx;PlaTSVV@As*ghwtsqWCT|$)y^YLVSgQ5e2aa@1$QF#i z-<(uMKOV^Gm`Msk{e%t6&3at$Hz#ZbYj1HnF(2Obs19Bl@qO%)KfC5S<9MH)mH*~9 z7wxaN2ud+3A8f~pn5*#nFQVyhpi77Q%+Xq>OMmPC|Kd0N|NTD#>VIjf95niA^fQ)& zKE&}X#mhnO%`JB#caTPNU+hILNT2S1qv->d*jn{|kycwW?CH7P(&0%kO!PfczZ@*F z>n8X|24=Ltdgim;>WqEh9hWONYQMnWL4MHe9oh6=oMemol`lJda(5~I66+$|_}X}j z0@Ljv$59;~G~x?Ycwg9hL5Sv2`TqoDDqx$Zs~a6TXi#s4OydRCUt*h9(xt;rrl_#K z?HF?ZUy2Iv56>-4Fua9{d`s}~=KH`_fZ!c7w32eg?vqpX6Xc2=-~BI~I=jfQ>!K~N zX?rlNmHggR2jIPU)uPwa0Po_V4^@h4KJaVV2S@m8@bOk~*)HU8Sd{b<^-Jrhipa~r z$D0tz*J1RL`8r5TP#v5!;uAfP+QR;falF%qM!%LUqT_h$Xz9_>wAn0w#2%1!k1icA zo-cWv`a2xKdp;H3BmN`e7~ZdRa~I>`z46@K1;_>I(^>?|1?k^ozrV!-ycOcd^yEQ- zw4muZheby)e9=WAOB>*QYYV|&6ck8Jes5MU81aUm1b8m;t#1k`QbB3k5E64 z#LXXfZpX*FqeIVwD9wC3NPbjD4~_WTgGie~<}<#7WZPS|r9_C1>|M>dPH{Ou%i~Q@ zpijqmN#R(*M@s!aj|%Vi22vsz-g`@qsNmu4W>*x8;5~Gq<^Zxe`P#*sn-1`{vDF+d zcOt`AhR-gF0GAV23E%jETuz*pXJ zVV1{xB)N$$9UV}mr5v~*4YIc+72d;A5kVNd|DV+w6WSmLEu_jp<8RvBu^a^DacJY^ATP_| z&$S>2*}af)K$h5NN|O^vfwU&KHt~)Z8FuH8*|n=J7~W}p(iH|dDA7&UDFhTqv;55z zpSAhGmy^@^_B!F8L8eYd*c(pEkT5@&o1GW$t;auu?CX=O$~vvabU7#u)iFRLzLct| z$&ZqZH%NzfZH_*WLVJlN5a+!!6H#FO`oB_=J{^KLXPo~tVn>b&?=M%gT`{~r54LOK z;qB3!!GqNQ7bXHJcyk7=S%Exnu{1|+=sLLGA{Q2}TLbWxIbS0|0(h@7`LO9cz*~Es zpS(hf4}7?oNA-{zKHfuVz8A)nWJs>4-yzY$An#fDc(e5t3#&X}zEA9iQ5_JC_;ycv zb7_zn-$8Pe+qipn(*8iY{H>mAUfXq+$J;-aJ{=<5+mfGzQTqQ2sPO)L+^qw{d&$Fe z4LrP+9vqiL@P5%WLcx36@>$#`0N$1nLETRelHpS-JzJMQ4u%(OTUopk;2kd1Ot=m3 z{w{cY2Eoe*cKFGy=Exn*0WNqbPg4de9^S4Qx6ka`lIeO|v_!gSd?9M!R! zMtqyrbDPx$F@C%i-)iT)$AgaSJ=kz|D|CzH@eatOPe)t7$T@E;h zGyuHEGnH&kdHTS!9h^?H{{!B0)?B+PT05U4iu%=YRnIi|2fP`nOj&Z#6FMbxU-%k7MtrndGrIZH(EMFi==f=~e<6KpX_`+BU-ZE5pkFiC` zV|Y*GFH^(AJF%dP(tCSV+Q(4uEvJ9g@b_pRc;lhCk@@oY**ii%Q2A($BxwWcx3Hk5 zikB0Ab0S{&@`90=3e#opI8=uejrh37JUSZ%8Q+{7OR);nDWv0i%Xm`acV|wP&)x)4 zI(6{fz7@IiZ~f1N)&Bn*5~%-`sB+Nv9ZxBDkQRXV{~Xu7BjDvAar>>ekosRvY5pFh z{tvq~sdxq~v4Njc<(ebN@O}?l-ehpZe)#7)1*AawnNfHr2`sU5*76#i{0ip(6}%TO z`-cJPXD&$h-90Qvl0*HD9#`8{jOQ@bfmyT218P%)YVv!?uMJl|%C9#=eOKgHpoh}~U8V&nO z5xhNDtfAn&w=Y@(X^={rTNT!vBExS8%~wM}gVgA^Sq*}B_aVVi({}X06I=0RaVST(U8tBr|WY2X)&DjmXTY(DisTX_FFucEaaNy!yF+Na@ z;N4iakAk3i3J>n*Dm%3C3)w=z{Q9P$OodDE{ynVn^YfR+=+d#`_Lc8jBF-atFQUTx zt1^ENhPSB9E*-q={qQ?)8-llz<5>#cPo}*DA^_gK-6DarPJrRW1`yl~>i>DS=0W-h z-czF2d;#7YhIctyPy4{O-(=bA;_$QguZn`KR>=h<%&%_ok@SQaaB*dUPD=86EnWPO1Op zsqmiUPs+sb9-6Jb3=i+As#z}(ysdrfD0okJ$8Qe-c=JHzR z1i@P)!^+?=zYx2q7JFT5yF>gk8e_;@R)*ARl!Wl5MHXZ>Kp4qzl#43e-{5){&0Rjeiwc_esg{! zerz*Kq4_D{)J53vd&-K6Ab1ddgMDRl;?h zE0rsTE0F65*Iq75E)%YmT&i5sT(h`1I43#Za&~hzah7xDbEb2~bB1sp<=oF{!?}@D zpHrPvj&n9A7jc?6LhL0zB32Ra5VMG9iQz;)q6^WEXihXDY7-TR5=1`e7c>S9K8YYtNm z630>wSq>2nBKs8kFnbSs3wtGB0G}J*9zF{`V?JFz6~6g=LVRqz++gx7aVUC$gVn_hCQCzJs02 zZosa|F3&E`&cpVDZIrE_?J-+5TOnIETQXZDn?IW?n?2hWwl!=zY)WjBYy$t@o6NZN z??3oCvsrcp0BE^M0U*D-SI`8$c9<=KH}rV z8JM+e{S9y#8nf)=2ZNyBn6=}BychHfvusQ3^`M`aWfSzC7y5x&+bvbgpzoMvEtOIN zO=Fhj`%Tu+H_X~rwKg7_!Yqrk6K9~Wn6=eqOa+?6tSzuy12lnI=94uqpmEGHtBP`h zzF-#lx|RU+8M8LoR^5d@Vb(^Hb}=-DSsMiUxS)@iwZ84!31}3vOs>^!gg#)_x`@>} z&R*7?8 zfZkvhJTjsRy~ZrkFIj8o6=vy09aDq`Fl(hcA|OCob2ZcFam7PIC;L)K6YX3e=5cL%D*Eb$UcQRo3?i8=4G zhpI4Zwq}qDbRV-sek@OdDltpAtL!pVfmySzH2Fd0m^IV!&RnPrvxKzH=R&2JCCKx* z47!I|0&_2DLnWBSmo88P-Nh{45bY_b7_)eccJG9WFpFFHasyO|S)2o11yBKI5sM|b zpgWiao$4e&w=s*u#{Ld;3$xhm$llOR%$o6iXD^hGS%gB{XHXt$ZT%f?y%NgBtY5AJ zW6%xE`l&RB6S|IB-@h&+K-d0df%A6gDrOOPGaxDg|A{Eab})C>67ii}=t5 z%tG!hL+3FInIHtEU=}iP1xm&&WIhFS4zrNY`JuCzg?#-CC1DmahZsu4EM#melz>^t zluIZcvyh>H&>74^W~f1Nn1#G%1jS+&^7soBgIUO18BjE4Ax{fHQJ95HVuwznmPL}t z_8Y{-n3YiB>_}9>toX>p7er;uI%A>ul&FMRaZAeciHevNJ45{wQ311}9}>!li!duH zLh2(?9=3stgyCmSE4Ltow|G=jVOazp&{H3L}|n<#`??rLmZL_y4QJCW5x6u>Ok_GCRGKWc47Ubu!LF$;MR7>d9w z%xdXzsDpwrtJ!0W??uQTvuX^LnxSKu^?%gig z3VC2w$wrtlO(E zH$pC`WpQ??X*p39`+K*zx5Yuun3dlp@CZ7HS$Pi*N<#-QD>v3Q6WWhiH!OEbKu(x- zU0l>3a>T5w6GlPMKFrD~PozFS=0NRdO zDL3ttAZyG@HuUd?tT5}G_;dhdiCIZcU+sdnVOHXWwmXmoW+iwiH$Yo4D}IgT1856o zo#FT<3vI@%*q*o(kU3_>+>~vE%rGnZvh;F@j9F2p&DPMSzxV%{zs4hgBlac#K7+JC zb~VTuB+~!qtJ+A!JA<@*VA+FQu`70aMfpHF{G`s5)NKv@#3hib02r}5%POJv$fIDm z%Oq|0YH$W=?>xs!4xB;Oh%e%btMY+KfxCxxTH&8T<_IX6Xo@Z%tw8KAZDO*&v1{uiXZv6&^;OPKEq z(g&!Hx3uEhEB!+@n(-X;ZN&ae)DZ0@_L1H}n;XipEMFj9+;oU89W4qe2fv3?c90rW zcq7d|4DU6&=kns=ZKSy66oU8K8DW(A|BUzfBoTo3`0h{NVDJTLCHJ090|0NCCB)>l z0B`ZgY!!BZcVt1w+wEt)VTs*t(Y1^4@%||5aXes-G)WBglkNWEnK=U=?@qOB*YmE- zhxY`kV}M3{Vw=1qHr;3Zie1m(%Olm1w2!w4c5+h6+~-&x?|^;Ebm{1Bt)EqKm9m3W zr@|ZQUSoJS_zrU8;hprx;0c1ab5tqi^meRr+3W=X@2OkvJXK&o8uyCgxoet&;rmJx zdyN6!qpP~(CI~HXgoq4>Xs9>b^=XhGI~yPGApKSPyOgC#?WkYrSp&a}kJh+#Zc1l^ zYQP!h!#f<+kx3&yzO5StUa~Qsy(gXg=REbJeY|!4=lLzQZNFF^Z}F#@bm_Pezu`++ zI0bJtD!h^F7#QAensr=wc$fHTFGS}5<@NAU##=&F+vjQnya~IOpA!HB(qvSQ=H3H% zzq^p6yAI%8AgSRy1n>?KJpFc4v^VT9aIyXTe0;pa+Sjqyrb&}_p?-EBUzpfW;o}_; zCiKBZkNKvzM58)_X~Y*@=;v#+mT|mmHUt|gy`$p;>2CKZ5xZ%Y$D3e(ggzZMydmm; zUT*}`sUdiqt%50d|FG!4qzmwN$=G)L<54m!-Ep6@swEgs zpY8Av*_`+}lc#?Iyj^VhCwSiYz{(QZy_fv(>;E+AA*U)Lxc`s(m8PiAAKHOm{|}#& zmYY7ue6zQ%pgKO%h|l1?)#mb0f@pZ5KKf?HkWY#|ZW$2);O9Y0bNYbA63 z&i`lTvj1PPf%<!^qfPWKoagcbRnp~8$MJ2C2jv|{3Z5H%*wfI&1FcD zs9&ca=f1mA_ytk`iLI{d9rG=*?@=AWG~!c;dVg-~L&giF65n}gC6g{AR~57 z$}H;TlE`rRnx-5MfcK2Mlk<@Ne^>LkvJJpnS~bRW`6+L>^LzxKkQhGRawmB<39ptR zwV{67Hb^aA}7`5+~zJ?BHn)d9gt{M(kb+7CnD7 zg5~ihIEK=vLv~ZM+MgZdGAg{0JMb9ZNrhd4cz8#M`hP(1&i=^rXL_s3pl$=eyVAGL zWf|!I6S?1o!Og+2j+odkLx8tLTkPms29weG_H* z4iaHm3|%?`S6vdCPNQURZ7RHxk2)~CAKbeufQL87E6XVa@7;HFD0u71G!6Cxyls|Q zsvJH-h8rG#aoPsze}68|TSfqH(Yrfds{_2N8|o{U^ZUR~ht@QZFXH1JtT&Q!y%mhN zME#bO9F~3Ki;wpWjdSY__cI^fk*JPaG~&yA;;5z_!+7@oGIGCNWlsa{u^+YxO@uQ% z^eaxXJl^8%S#;@`b+oKY%%9Sn(4xW{`AP}HyWGr!9}jQ4H)}bN)7$H>_fzohRG6Ij z4e&NfQQrLnyuEeWq>a}AG$*eAIwg$s-kzJA{gMQD+mysMZ6Nx<()Hy5tIy)&t+?(| zr(T#eNdom7bMIVMdITSDJ(s3+o(q`|@1>{?LmKgkXof6|Z(=-qUp-N<$*Guj?~U*+ zRiotU|AP8IDvd53N6*Bby>jty{g0(Lrv59a|4CFi2>DJE%RwjPG{o_8kmPc%ht(hl z9UWh8gItgv;J1iEI!L44Rh7R$fm9G5B%cSCSk+tdkB|vc>7|FQPJ$dXa{H5$v%e24 zA^XvXUl{)kQr2HOS994yk_hS-^YLTHqR;p_DEZlDUEd<+yMv^F>bOKBzCNDNXUhJJ z=b)@-vGQB#xnie&^Rsvq>-YZ&CiLmB8(AYcqmZ(L)T6>1`S2LS`$j&y7#`lc{EjWJ z0eBN^1$H2KKb9Br765q5ht0WIbDj*Z-N)~u3JN5vPw~wN-u9#H^ANmKb60tIf)}Lu zu6Sz|cH%Fw+Gn==S%)tm5mCR*E|xR*7vSSvbt&`dRT1X9|GyH|QAZ=bqY~-EmsT^r zgPeW&c<_)O?E>kbYwk&b64t*UZE%b}9W$T36{!iL>>yWC;f;JrkKuhZvRM=l?~jUO z1qj|bH+k(4yp10>=6?Y@$o>>nqb=#+^Omn}fmHzSo%JL22;Ld7RWAbp-h{HM-CqQK z-~sQc*6}oayuBRfdPpkEl6p|TI%Vgdd;Ib7Ze093_Hr5Xb&!ssI@)N&M=p_L&*<|?hd&y6(;Plp9<5@L=cW3&IYy@wC=hltyzk9<@ zna6*6p2o-fWud~EN+TJPJ?iJeZnn?W2_Ns+7eTkKGU4g%5UL}IMtsSKH*G)hUmS1E zb9ek54byH;+~O#+K4)~0o#k=2eWECv6J092ky$4g-UY4)h4Jtn%ADFNHmqT^jq!C|2!O>J%A;vc+ zv4eAEI(TT`-XcVj?PhXAtlyj>i>6ep#C?c%0bAqCoBiq++8>y zF9*GI-L~=p$U$tU2eu+htmKB_$eo}-5(p<9xB@6NIAZ_WEnyv9=1=D>& zYJ%#pq7mP)hnjgOk?|b#JkLedabqLRBX;TDXc3O*f-Jwp&MiGnmkznIG>)5p9!N8w z!W$W1hT)y)!Z8mIZ~x)~X9VwLwOk7XZno0hqFc)$C+BOSqe<>t_B2;O>PCys9cc>gf_6>#Pp8P3jaoA(po zeRQC@Z8^YOu%yf79oRvx_@rg9YMVDKa$h#D>a`PY*6Avmecq;0ktBfnIoB;L3@gRQ zd$mN*4!4ENnGWw>REG(T`0iA+f&uW1<2}#0r-$t$9oJg~+!x>e!TR+-!PS*M9db7p zpcka|sqjVyOk#Kk?@W}y!`n*e+;ht2MA6+6!Tarp+dS zF}T?7N8`bfhMtp_lhvT-WGmiIZ8%J{IFWLo?Y|Tj8>|Lz?dW-3n(&@I(4j4+p7RB zC;pxP_wO>BY5xRvkj7Lw2$>m;<)9=7c{#isbm4uXGm?Xj&3$N%Oe~TOtM0?|_0)aZn&>gg!U#arJ@2?{+TMg7EAASMcl=Zqa--*e3wd##T%o`bA^i1!vhq2m)fm4O4d zT>lr`L5k?7PY3jMp7Ngy(rc;kMuwnccvo_a%i`gkbbpyLg7=BMLdp`G-ks)n8sJ?L zp93Gm(#y3TYZ_{47Wftb@f|KSt6;$y|Ff~~5g z^{AiswL@y(Z1In`#ENaA3Pnjwhj%HeV?K@e8sX$RR~^RjE;w+Ob8;3P4N{-*pR-Le zSpSH9^(ne^Ea!0VUz|nhAg!Uo8=2~l;e9WwOa>3{lTRNEAO%vP^=V3hl-7R`4g`1y zy}tRq84O74kWKI0`T$ICc|WfKIlZ-$KlM@y;C;$%v(WuoAK1=qru0Hv{OoEb)bFgnz|5a|_;@$%tITz-V?MkuqdK0@h>x_QtvTo@<9LTWu6?FrO8a#>0E_;u~iWyn{Q9DaTv4<_smf z1HAXE{(Sp1o(w;G{i%*r6ATl(pZXwp|GMW8zX0H^o)((1w$uk+wdBE-edhRhmkZUZ zEl2&{4{);mP{+r6pkzhu%dgCbcNMDREsgkMIWAalzQ;J;^6~`!Eputt|Af9e znI z-WN9D9V(I5!5?qAQsB8)UcM?x7xnvf(qeS^eEjj2)^=|Qyi?4#_tr;s*wKiuGj5gN z4L`>5z8lv&c1*Pa_Z0kJH6KZ#+&C$W^*1M>@^tA?=o^$+18#5qt^fZ;0Q3F<;8u8UHH%|#Y&v*`k!qQ8vWN2TI4s<9|Iv1C~@;PWY@*G_{goezf z??h29NSjjOjXb4>;e9*dg90Aj5uxJQ2;NfcsgxaLm;CNsVgT>*()Q&i!SU9^YZe8w zii6?stz)&i0PoVx9pB#oyi>wz1H!*}!+nQmt{Dl!$9tB;?ro3etB{_eetGbzb@6ui zc&py^PPp#De0YnZIy7m-_dUbx!Q6Tw+DqmCNR*Y+$}75_(=Lz*`EREsdDB@Q?|?nc zbmy`Bnh31i1F+l%hi3CbCPy}q;%hDP0$rymM@U9 zk7?7T<3O7cTlAmlEhbcWBadBTc!!z#%j4mFr9pN+a(b)u;soXN_D#^@j$u&$|8h&} zZ8}MYgS*|OIqreaTcQgMk?SqSUoVXR0C-2Pv|qfU&>Nm_^VWX;8hpG3_BVgL-L6a$ zMg3NKxW6!v#>ZRXwcUW}V&=npCaPmGjrin(x_34hGLCmqQSWwzi*z(d4OWbI1kPf4 zya`Hzbn5Upp!ui%Uq^*E@_H+V_l#p(7UJQ(#&6>;1n+r^6DYkmF(M?@0PwcS(Mv1| zB*UMc3~hW_8Vp~~d+V+P@c!XHCd>_vw-&?^-FUBg!=7?d<(&N1ucLz7y9G^SA#0AA4EmG{FwioGJ$)?^k0vXplp2DP9h0y6jwlro%_mKn_ZkzH#i#1XyCf25b=v z#m_;9H%z!sPAZVZQ9n14xWW#5{2X+(GTiiqoetAANROgA@@T}D*|Bn;{Vv9r*s)lb zlIgj$>wlR!zl9Sg?ODD+GWlg7LXQr%O|q_+|J?sKqrw|`kR8L@C-u219^O92rNJ)BxTqFYrzH0lYI_YpLzK=?&lM zs*=!Og^%~K0{u#=AZzp}*8d&q<3@g|slrc1|89kXRo*_8U9Oog`szd{R!_X35i#dvrxY;jqQ z;QjNwG-U^=HSL%e3-ET_0;zs-Cc}2hV$oILdW-mvh&T;^w<(Wtjs?JbKUWId&j@e$ z@*WArVF`S^kJ>n>a@#1AE}(wW9Y4mQar_&k!~A#J{EL|H^Oj?%j*m3rTcfF)<=4tM z-cvSWb02-Ay@MPa-BUh1GRX3H>n4QKrDNJix_fgR1@BE%c*_r)I%0TxRUTKt!~5a# zVF>U+?tK!aR0ih%!AHV8OUl7`%Y~ZaNdKQa^Zb-5z*}`Z?wN?M zH<<2X_%4APA8(nNAtWg?6%q;cd#>RmzIp&3Z?EOWD;{MrUx6f#>hPlx-~QTRp>iR{ zHz)mrO&<=#(oz3c#>8BnH^K6F6E>fwPexhjC;t;xWHB}n~$?)m2y2;kky{kCsJ z-Uo)xi)@Lyi;uT=u+@UTUKP@hls|qw)*^1+iTIlnx&5!!>#D6}y1lnQszZ@Rd|zeC zAEZBGJbQoaG*x}wMaTTVih_Vk`&hsJC#2k_OGgNSD?1_nZ~f1l1^@qu3e^AGsB+L! zXB~bl2OW$4sfCw=Y_8SiAxkXpwTF}f$zq55LuACRs!5qs`yMhpdYk*_doV#NqI}cE zB_IcRxST#14RX+;m*WS*)6(sNM3W4 zm;JMYw4lO!iD_LFhW82CmzsEZ|M0$%kKld%LNf*LiMy*5KLWgU8dRO50N!3pf1l_B z<1OE`<#-@?r+U8|hy!@@$_t*{?B@+fY}s1Q$&0_lM$Ug6})@lHC-+`<>DQ&qRRtmPGZJF=Al;|G?zVUpe@Aw{awmJj`B5szCkDl-NpUh2ZZX zi%X70r^++m7o<;79c47)+ghBo!y%P%yrumwzYo7b`}CF|bRg`U-w&3@o1kw&myWA- z#ivY8QSjbEg}2HRmunc_^_|Y@czBCE8@h$yy~6A{1#cs%>@#8j?sAF=t_^IUdF#t2S8kI@x z`n|3DJ*(UtA8)TqY3GL|m~XtrZB&OJjrg?3lM?EZ7|-4T>zZ9Ib<$D)Pe>RG+FPy2f*A8RI!f z=yh;{02l27>Cu>raGAaU%kLnK68-4X@iNxC%Vj@h2f3XJZ>?q9E3qZEPpw545AS6? ziq8?e&ChsH@E$AJom&9#t`@Ey={`V)<7dQqJ^|w`A+w=i1n;A>Y@jTF_YvWO`T$TM zy?f1FEqE0l?@Kx>EDyNKlHQO z<9HizpCu+%)6qeSUo4$z^S|JDYd(oS9T7bbjQ@0ytf}zU`1SNAhPURq*yVV5H=LYk zM)1B^p-;h^aEbHv34r%TSH9vwCo=4wc{U>i3`jG4wC5Fqx3Ic#MJmAChS@oxRDcu5|--tqzUdpfc+{NPUf&B^R_A&0A&@b#9*s16Al@kJh}TC>uL zalF&d4|)m7(2>2XCfe9sBUv7Ag83AEI#NV7DE-OamQ;AF#WwuwapIzAg+dVXXH?K7C@-igfV)-=dHgf;#x)E$Wg_wMh!ekt9&RZ2immOT_WVTSSxhN5>^G zU+=96)p3SKe9qU5cG@js9B&7$V>>Q1)9$?mOh&k`cg|SGq!l3jVa>{0Y7gY{gX;-9))&E>MmPEW9w958PKJo_1r0wKxkA z3E8QHM1xYP45eY01`R@zgpd?XNRkE`Wr#`&NtB3+QlUX<@>|dL?DN{MdwDtn@YW6M`#|PhJsY$Djko`T-0$%Ff6F&~BEA17 z*pdAq3GgOVwKXt+7o>OhIITVfR&R~;$~lw(?}LXd@;(6GCCZ!1WQ&N8CAJp*h~4kT{$$`e)E!u~wC3{=7Y$qwBr5 zP_h5d@IupASdad9kXFB>Dvs&Y=}Su(65;H?J~_G{<{dZO zMS8vUgze|p8o>ME-mx>9?gYqQ@W7=$aR1-QX#HKvfcKb(LS_Tto$3=<_x=D8D%7_s zZ&--V`>25_*X{S>cyc?=?RA#l`q3vRWm1-3wh(FWfwbdD92FS-V>l50JJw|WygTl< z4rFLxZ%*V~Uvxk^jEnAh$2f6N702rj&tIQCL7JR6QSjC}9h^$$o#JzX0gd-UhtLst zd28(C3)1pdpZr3%-*EO`>%4c`j{y0sOAHVMyxmjJK3f5Jvu~(-a~trUV2cc>i6%nZ z1(RDR1<`pA-H~GGb(X+8A?@N-@wfI&qVrx?Aj%RmNqfA%A#vDX^zU||ice!17o{$sU9gMSZ(SPzOEWb7(PB6<_uXTVgGS%gdcyU8f|Z<`7|1~*XJ*VhL4nj>`z%=sd?1|@s8=Haa**Fs z|LQPM|1a5AcBl4CDCEMh+i+MN{SML?+e!`ni3NCPq+Q?8l~#Wt^gBoecCyxLk6RNGijbLCdB5SgPOA+9rN?2Vg{Katm}R(kp2rKaS^KG2(I3lv*QYBh;^sn zZ6wHkk<7bGNnjBg@BAOH(qP^Xx0UaLdGD4mXORWG1%z!RV{HkLwu-?*eK5qbMzfuf z0=#qWOhTOi?=NxJGTnkhA-AQ!wVv>!^EU9V3fi5v5KnGrd_1-1&@c1?$^F-OiT<1r z&G9xy;y8fOKOxq_>BDvN=iQkWx}kqb1Lm^W!6d1SI}SZ`&wE@%nyNUazK?~;*`0z5 zq@5JJp}|2FGVk@tpV`rPXWmfX1oK`bbKV2yy}fH`r3&D^(XlA+#0CPSY<4~%4%GiW z#@eAWfcK&HeX<6CwyVPYBOP-9O z^L}P-{p8h<1kLegSoSB5*BJdX;|>t^dOd&MrL5jT(x-tRn(b7@ z0r3OC*s?5;MGYHmb`H_5)>$pre| z8}0;trP%kD)a_XxeJj4bNi=BUf52Sx?`LX!+J_00XZa(@8%pmte3|Y&;5ZlWW zG;sqAv9f8e9%XL}g??O9)3`Q)K7%}1D(aHFyrXIaX=k<1-e{r|eTe1JyXna9GGOqZ z1N`6pC%#A=r*;3ne^ItO!-c_YQ%WLx4`-THCZwD zZh`v$TvJ>G%sV|Gb;B*ddnhC6tA%kWB!X9ny3mQvdp|>~-`Iji19H1uRaUcAwdlMX zhHULeliybT?_&PXzj_K1$D`rD?;p#X+zHwB^XEOOxN5``!X9EDMc+$s^Ngf>-fsT2 zRK+3jGk_?2p2XXWg16bY&0#Wc&vRqkXuK;}M{Ydt}X_=PqbOD$kYpk!dg5Fs$QY3F%l%mBppCg6%-bXPg6SQ=dyUKbm3_Qn(B@blZuwj2^}p(rt+ANRxBd`aKImmA^ugg+jr_j9;jR5nw#fIl z!F!~gR#@Jc?iO_3&t90G*jmCxd%Tf2zG3vwp=RO0p`Y{Tz5A%=)%qUn&55i#YZZ0C z^T+>r`b1y2>N2BcMRm9o>S+| zjbDU7K6~#GC*9E3AcNe3OP34_R+HN?mhdkugwWR@pMU$NWoa*ur?ubmKqQU^jQ)jq z#C-Hontu+mk$f=nW{`?ANIOSpdHpcb5k9 zQZ(N0Jl?-)1iT-5h=#ztdn>~?tOUFRFRXA8x=DbhcVFhp2fVWy*iB&G-nDb7Nr3k& zrfa_zZ6-oY$IE_C4WjebUpH=pH{h=(w^QL6bZ2;q&inY;p9ynyk~GJg97h~R|DGM) z7}Rxp{!8o&--ep$ms2r=4Au{97Y5pW`il6uj3y{}n~%?a9!x z7>&1v7tzg}fcJXo=mRkCRYX=9Zos?kT>rdCEGDeNRg>FE`s}_xdky{e)>y{OP@xQNn&Zum#Nmz6 zzn%K)%nT09KYK^YnU|^iVlQv$ho@fmO+7^Syd|`$i-Wy)N0bz}APvmDeJFUZIcBC! z<~`&Q#*fB(j_12R%zNy6*nXJz*P~6541jm*x-HHOF$AbSV0N<_INowetyl);9b$eZ zE(`G9Q+B2HNOuUNx%fezuRnVBZXC!6+j8oAl?Ku-V3qnMrw!=YyQ^&AWV1Yu=6F9r z;;6;w-`7r$hl8^7&)zq)hF899e1MuJ{;EY5OdiVSiJ*JlxXV<=p}qgjvVYG1|Mj1r zrvC!upaT>+$PSWjAm^aWMAhYJIjC|?%o=!uly%uv(*D0jc-fwCut6I9mME-plmJCV zFIC}bjfKuO1lq#i|4VuIUtt0{=)k#w-;JO^I;d84sb>g12lZ}TFg_b6R2_k|V=LW$ zZ&4F^4iXC*y?$qa_UiwSNF2f#{d+rX9ishTxFFpNRUET745~xA-G| ztZEDT25ELO;Y;}iWttme$B{TLVf63xqZez>a?O8;Re$NC_Gyrc1JV<2Kbm{~4}AZx z<3&{*Rx^8fh{dECq(233oBN4gWZs(+9*Cgv_W5!p1D-)zNlOI4yrn)q7OMfgm+u<% zVM`-G0j49;-OaI3AN!^RX}~*NTyBLK;C&{xf5Y8-MCdN=Vx;wEbl#U8nwxrA#H-2e z4qt7kVAe(FeI!EtO7ohPG{-v=iQ^DP|MF%M69en#&l@)#9xtbfy}V_`d@|+rUO~E_ zL2~t;rz#Gm=AeSqC{q2upMp0be-#&*_YJQr!f3n;#p8Fv%Uf2hhNR`K@zzIE-vMvI zMbfw*xdcemS?{zEc${e9qT?A!zxqvQauUpOn4#QSjd2bpI}ycgd8K5E^f`*6pOdHyNpddF{RNd^m9QZUqrq zxn#6l)E1rhxks7tVP2xu71I!ED8>}22Rkj@~rFx&_yf+1FU(s{RKC;>8X8+$6#77KAcsGEc9|MZQ= z=ThHkAY{MR6TfG+E_}+4q?(2Wc(#d>k;wb1ivAX8Z`+p%6 zyf=T{@Yffl+Ij<$XuL0&TZzI)?D|wbl6b#dJDC;)c*obKT0R3$?AGaWFXRTiMNK_T z;rsv29$Q#60(f^Ci*wrEB|@*wnYtSZ=)4OE$+i2mSgOhG-WJIxZBa+(O;DUYE>^IZ z=6Gi#aadyXPq@>m@LJmZdCNamKi*%3J;dTvXPt}2PSZVa+|&SdacnjjP4Fh&{})Wb z+u^=N3ORdoey))~<6XGP%L?Z0eEA&dfV5hV$dEta{Zu;Rd}=rW8v7}3F!m}In!LFy z0p=ZKoUwEm@E#S9yf&RggeKnk#0ATt^X{AsvX;x>tR}ac4(Y+Ou%YwDFXr9%vVR%P z@oq)pSdGy?*SVp`3U%|JL1swoRT<;QuK$lMcRVwOUrP4{Qn8>3RdF;3F*R-XCe{Bz z6udX3j-Mj)?jB1KN8`=ISQ!fQc39`S8(!YxW6D~%2k=(xOmwY?1h2O)b<=7EytkBo zA>H0ua;0EXKj6(iE+nlKPK4f?dB>>! zBxsIzCK5+7M*j}4E9W`$dH(f(MnvS-r*E*ccck+3#5SwNbk94o_BK^Qn!B-58_hpw3($`x|8FG=aaVDvlqehdRo@H%NeYI0f(RL$X0+-U5dG@@TweLc$YZ-tQ{%Ni#^o+mp5V zfcN$uF9D$w1nA?J&#Vq_V`~L?icsrH58jyJ(^eB@<<9)I(XCus8th9zy|982R zif01er9ruZ_#@y8Qi7hJ#+z8^*3G7Fxc*Q5$}Z9ecyD*rKlEiqD73(UZ>P=^^z2^M}Jw#9V!(H9XI{mbhHYc zx2BDI|ChZVs}hiQ8{bBY-OWVj9r<8E$eW2DG?%^kkT~2i`nS4ny4Z3dANE1#|1i@{ z#I=7ntitA<(B1PsWAj0}=PfJQM^zm0IWgryF{H^!C!7-gp&z88qITJ`^^= zdv87;(@A%4Z(6s!ISlZAs(=5|WC#J8d6ck22W(DQ3%XUndv64m>X2!`+rzNJpaSp~ z@a9Wz{2ShW*9+uKH;z`3+daASu4LwKc=JAy`K;N_NOSeS6A}j#M*q5Y;F>kH=AXS| zY@Ssvx{tm0hO>WkMCrnEx}TijT#KoSBjo6L?<3j&)c^k>8`9?A#yTb}pvXZU+_HbY zAaz`jQxz=-S+0C}0v=-ROR7l)lDmO~RvXAco3;wdYl1b%vm4i6T=gy%l2A7rgmcil z@K)(jkb`<$4wbiT358yKF@CH(jy}Zx-gs*#>#jQ!2 z8)AEqI0zX1lU{bKLfU)&IjBx{yX-+`>@P@hi#K!c%!sG|9AxiIRUBFAnuZ@P!!yVP zCJNp=Csh8rAboB9M-?>Qr<M6P|X=1yb{$L8h1O+8WK?h&l5-^uzaxPZAT|&mgat`BN3g*`R>b zyK(RgGJ%nTx7({xb@B{SuOW8@8t=|mFDqf*y*~p;yoF?BMVkO`@l~D#fdm31U$;x( zQD-cqFlx3EUf$|+y%pF6cr)|_oY!Uug-qA^NbEh2&U^B6c49^RP?ZtV&fnXNvG^c5 zZ!7=I@Ra5mn&aJp#G#7Ozfk|qix1Y#KYO2Ery3iahg~4yikA7U31p{x-nfG0RK z=)C3uW{`k40|jqaqTm>r_fnT&Wi;Nm?gqEPyx&Z8l6V)Md*oXOc!yt;$}2fZfTA6_ zk`Dsjv5$n_z`P4~OkI2lcuVU%2o0SeLLm%R^+8GKyuB*+)fy&$tqMfiSyTn6MERrh zHqJHnO6-}UIo?)C910lyyKmz!QO!R8?5&x+@l>Hsp_?Dvk(^ z_UHFW^?w46g15`s8_UVOjXErp(0D5_r;Wh8O;k6KE+@`+lQyjaycM^|JNc&)p!Fh- z9ddxTI&XhG{CewYt1n(p0B;eOPZ`F5_mFF|KJ+)d&-ztr$=&Fw8bI2))LoKX`!~D= zZ}L{(mLH=z-UpC4ei!_G|Mn{@=Ju|hfA*GN{IV&m7JKgv7rN_Pm-7PppL_3grYepl z+1sLjUHqs1r_F-@KlBO=vFsE%$cO#+Ul*i{STL_f%RvEe)=0sh*o|zq2!xN=`KOE} zRf8PVwrJ%Gg#ZF{Q|WVc+k5cDj@Eb${DPE%%Bm?D@QK|@m5`-!TZvHh4w-(tZ|L9u zZxS`BJY~&ReFtgB>dGOo>lyk6>FcfBQYPg~X>JXYfW*;)(Laq(sayTk=bwWXM8>sx z`%!Vlj_C&VB@VuHpM#Pi0#$Le%e`E1;WTLm$wtB3yI*QAd58^n`KXD;o3}#j1pI-t z(}#Y4nD4 zX1Ws^(RqJ7{oXg|7p{60(r(4xoOiWX(Ro8zjt`HX{pAYahR2#Y#Sw)0q zR^Sf_*rOLn<-%uTV~R(rCXjZ`EHY0ntwt}9?vDD43>wnj4$=)Ij(m*%Eo&}a@OI_= zc~6rdu=IdZQ$8t+HS z9R@IO-qnXmmlLVW{!D2GyxX@_KuqB4t#@V>pA-OZZ%M~1@cVxqGMdj>0dIzfPj_A^ zBSOUeO)K~|pz}WOuF8kE{8)7WY3C^2kQ<_k&RhS>s=O<$w735sfy5z&(LYvsdy$<1 z^XKgu8izMA!aluqJe6;8t%)<;^A_!+E)E0kzKK_VCMV1kymuKsE+zBcl#EwH;~f&u z9R}C`0*!v8y*HuWQU5o9_tAj3%~=rysH{4z&=qV>7?s6tg!kSY^P(7LLH!@6qxAe{ zJrS~grn4>41)X>Jo-@_P$9t>RAno2d9o^?`g3h}p*()iGd7S3ze>WtKY>fVi6ngCH zub4k?J^YX0f`!;~Z=A_fv4agi>Hm2Pqh{*j;Ai?G`_KJ<|Dn*P(Z2=tKNm#~+8>qE z3Fjag@ctiu?^YaI4oYlM{Q%ehJVG|43(_C1W0Bi~q#yL74Aa?^vt)en(&9bNGshQ!f% z4?DK?ZRk{>Io`!c90M5rJD+gQo~S$jA$He$mi>oUVDskbcF^xI@1=X*c1Ng-V?>jC z$m}GkK;od_y(cqxoIHcvUVL5$jkjZ~>l2ta)5pPJczJ98OMzG4zzp&ZacF%6xc`sm z?OCTgU$Z$-&)fh4V+8=?l$U4O&TZclCQHS>3>PP2oyEaFu{Fp#>Fw!oEsmt@# zGxY53vuXF;axQ6_<4r)~@WSYy_!gqeSMB-p7WgrHJb{|mTP}Nvh^*a5_w_$6iMluz z_|1M?{O5SfLJHo#>Wu5jysLMv&_d%Kdc7nc=3UnmOyYe;(}ceQ@SfWs!=k&N03D1e z!5Myth3egel;FKLE@{(ED*9gL`Wz2%|Z=67;Q0d$|e8>F^S z6^EXXM9(pBIFS>Syvz*QI8KR$#;k4&V!&Vi^9QZ{4uJZfpCShZ4R0Z>LBjR_k%e|F zXgR3r8Q}|@gYGtZk_se6|Ck^rP#_5(NSDKd2h!9D`uW}96Fbgz6(!3+4oZAnr&tSe zQ2vL|aGkyoU?Y5ERxtVoX@YCi#Mni#YBr>umd5#Ijdti8r0SJU;zC_2G?#;pB5|l- z^snoS{n*0f`Pcu}yZ!jiQgOu&?sN(Fw&wzLpMxT!3#f{t!_@us)*MoS#7Dt9u;QF7 zd3np-QIZ*rw`*56iFdVw4~h4eVvck6fOk)-FaNzF0<>I}C3eo9mQT^x49E_w2I>p-Sgfz9ZFRkFV=quJxaPkDuI`R_kk44 zBr@*{KgOBRc<=UN?1!^=0^?p1Z|;Jqw`&3KB~F2hYQgKRs}qjb^a9?KdMj+DK=!t? zFT1`G@SbML9BVxq0$K1K+=3H9=dG_#Y_wApt2Rd3t#~Bx>fIRn18G@XWZKkyX^*!S z5=RC`|H3YZ^$W1gzd&;CI}jyE&Fd|DMXR=19H)EUxWpyY#lge;di9_BpNE2XfPG*d znRnyk3Pv>Ew!};lZ^idN9v|JZ}s5#;*6$hj(lpI{A>Hm2P+(&7u;_#FujEEGGCMVn!y#3V} z+sVB7B~LJ*@g8gw8Gy65*{5I_5Jl&iov_`agH_{G&KylZH1a#haM;DfEI7@r? z|5qY$lwkBP-Oqj3*~9bC-W-0ceM%bGUvKRlWEMVlFrMz0x03G93Q-fsmiA>4$0Gl! z|7oq%|Nr&})c=AMIVgN77^aZ@|E#US9B4UcEM^JEGmwKe*oq&5caR=LJ-ZwQ)*ubf zg=d@GB|ww$kr8+LzztFwn$3$r4mx@${HFYZXVA`mKA-Q8L!hVimlizPf}VrI7LLjr zUze?}L)vizIG8c|H=X9uc&TXqysgbz(#7(y z4@l!eWhGrA66wD{icF^}4%<;C-X-qQFz+Q4yhD>ZNyl5@)!Xlzzq6z9c0Yc4Jk*DO;G=vhs!xje2j(k7ezY@0^ZKOsbLI&w~>n7FL5w~T=Dqz z#i0Up-s009O|vf~s}+!T9wB=fLjGn3`CLCgyUxOP^m zq;_`*bTdif`7wWV-tUzglLV8+s;?pKY*w)(r*1&!ZU55{ANPXxR&U91*kJVUThdn( zf2a9pZ_{OFN7jg9*Z;|@e@CeM9-w>Pi5IdXsflCTME*wKBmdO@|KEC>*8U+FVnr!( zP;~D=4><=V1ex=p_6H5aI0BTcdhGUiZ!GjY zqss#xV)=_MiVlMuWN4AS@Wq2rDC&1-fQqXR>cw7B{JLwlw<=VJBJC1*C1ej-Iia@S z_40z6wU!Re4Y83(9G)2cv(G-4miKo4L+nFS+wWq#8&H2=$lNaUT+a6VLjPxw?kdJm z702H0+_<@T(gkVDD0m-wmP0y03eO-vTvO*oDqJ;2pnD<_RNb_{STlVVO zt%2Zq3y4RRTNx~GX&D(C!Ud9T-^H&uP#^{F#>ID@4~5#Qinpt3qw_uyd)uk`m}2#F zq@7M5_gJ79I`7qGD-vA>Xpc8J4y^tSU#k=-`!C!eWtn+Cq==d;c6@e))>ix<_`IbU zqAHHbz{$ReO41IJ2nFw`kP_1KmZbV$sht~*cjo0TZ158xd-$;t&UZ>0=)`U(Kv;F{+^kCUO0)Jfh22UO5`H)pSGl_*lI7Dd{{ zuibYja4|Y>?^it*joi94m%YhxcwzMK%7C&;(bM^7Z`+>uSM3AX8>AeWpEEl0`su#@ zmrO6FDvn%(H@sV-NZDJMf_Ef7r;t23`S3c63yt@Mh>fJp37It#^V*z{F6LElJRJ%h zGd~{Dua3?;RCV9aM?Vy*V~}?5US&+p2%+U60eZ5w-5#I2=U^-zP;U9>CcJAyWUfm z#M`THetU0)=Qzc2H;52}8ARA)ihlloxb#?zMv#2jZ%=U@K^`W|J7OT<2$nBvL*NWJ3=-Sg&%@S-Y?BF|RE!SH|X z|0CC4H2r5#|4UNjpd-)6{#s(+Dy1ffmV=Dg9v*`0|J9?-q%}xYQ?6K3FoP6KNtokx zCP0anKfD75W1(+Rr9PZs28nliv8E8rAm8(zmEIH<3h@L@E?X{yKEyUY@|YUJ$yBo; z?ab4czN!C>o`Xs!Z!b29qP-2$dL)iJ82w9PyZi7v*Zhar?uucTU~TLnHqB{??lQ&g zcWBxo6`gxn5JXiRHJVXBPrHzYSP2T=@maew$umd;i-k+kcw7CLafNw%Cafj#&T>;} z*a3K(<~vV%?Ib|jyiM{61F_Kk{@_twz&mpB!&DEz+l#?Y<-)E|s7ut&=q7)`rUgytyt7-_ z)lS>UR_7t@ggz}+V7!A~AU*iWF8{fH70t~cvyeC*V)W0l;W3BKvibAgrpb`|n-P2U z7H2Bj%wW_*|GWc}sfwe;dN%jSp9|8&D0s&ihLEnefS0$zTdoM8@wPtNC$Drtc^|9aHM^Ua_6j5cB#s1({sr5#<9>XbKkvQI-PJV~ zHDYc~1RL*GzN9rw_XSeRB?GGBxGkV%I(Uqhti>3b=WHNPe%((7Yn*HaB9a#$A ziO0mgk%!oY0Y8?Z@s3&-yA9^uS7%K+Anjih?{O0Fe%M!>UaPkOn%#G~J`eB?VhFQf z0K5Y~K&ruj_gt=WcM*JfYoYDT1;Wunpkr#a}n6CJ0{ocf_b zb3<%55=Syd|EAK{?ESJ~{zI(USB4w2N3jc}^wUGzf;{Hvp7(VQ>f$i>U*PKS=lwq! z3f{+eA8I7?W(#~Gg2vnF_cA4zchGPQ>3EB;gZ`1*fOi&C{a%@@4N&Rn72XbjcVyx9 z{fvOO$o<3VI{|OE-KRpVOo`A}!7l+<-=Lo$ZGE1q-6JMl{RwFocfkBw=^gYFq|kBA z=!9(A2G-Fzj^)L z{V?tEE<)nCiP68;H9Lhl9?qY4dr98#+GkX}-Xbd>XxsIP?s?2*Qmoc)1Kp?09$m{CR)dQMeOg#r}E=S5mw=nr*!7f4|uKZ}xz@pQ<EKA{}6kKovJuI@O{%C{=6WiM8P{H;mkWS?{_vsl4!gW?ME-byjQKz zCk?TUvRh8J0N#0R5^j96R?wy>8*Y5{NIkhEgAk3{JE^%u2E z!_av@-}J~+S5CTm0BNT=^3(d*4s_n#-#MmF<Q~mrged z;-lh<9Vxe&c84=ecmHQ{=D+V(sY}JZp(c)7N@jg;LrFVGiWIz0ZBl3>^IjBuR|1W< zOJmM=nD-#_8B&21^hERODBx|l&V1Bqb}h8*)_Nxuz}r2z;x5d4fs^3Z62SXcdWY2l z@cy46OYrSGfAjv|8zu)W(bY25dPqCh&y%Ba+UUHyR1}3Li)n8L*@ndN38R0fM5DSN zo6kRcZ!R=HyzMvk>8;2lMGwJEY;?~X_fmnXINGmnt?5l8o!(NQ;GMj(`mgii@j*Tg!Eo)?q8PL>)rZ-F0=PTiQ=N%y?tCmvE2N6S!l`>sFd|K%xopJY(~LC)TZ z3tYv}cLCD90M5r zlZrEwk7}KN_HO9T`nZsq*IO=gn;gsgKT!W$3Q!k^|MDnhu)Oup{r~^IiQ>QPCxiN5 zjUoqKDDnU64$`;RmMWsyE=d;|0yD@DgFT}A7a2qEn=P|> zMq?q-p)&<+U=8w_N!(!;kb~}g63Jj$L4=rj+XU|1N8dr(d(KQwQ~`%)K-$@aw%ld9 zjJ|^;w=|U@B8t2EU-tX*FZw|T$Z=rwZ-@Gh#6Z{i7f4T(JNIvTfIYQh);?*+0(eVRp5a~rc)Rj1wQ1}PfwB_TF&BoQ^Oj<|S&%#Oy($A~ zcU$-KE*S@O-tS|6Z@-&@qq+TmQ6vtQ*uU@J%fRks+R5`DVjntPb-A$&`-q)%xM6wfA-FP_4RYmIQH?D zFZ^LLBR8Yzo_A7I2vu>Y=BN}_og(pGLBad1fa47^Z}t}+GHASg-dN{10N#D9)&VeY z&&gM!cL47@yfH8NcUnM1e|fdrp#FciSnDjjyjAMeE^!_3KH0V8IT7$a{mX*I{BL+4 z+u#w56OyP-M%r!TJlJ~fZ+IU$DG7<(qP^=ak0Nm-V)So)iX^_tV*b2?YE*wjoTK9I zZGV-0r5TZQ&l@*KWgKc#8Y=(P|No*2^56VpK>fd(A_ryW5=d{5!sq`}ZnCSQ3-afmgB}JrIc>UvUH?axu&Np|nbLjzAIZc?RUCUN8nv#ckcQY*6udJ63&Y4m zY?{a$6*S&?XO^hJ%Ui6811>P{tqDIDj|1M3OeO7|KDv-wfq)FhbS%_Rb)yxo|ECto z_DX;uR{caIugd3%ZzFYWJ;!tX)aovUm0?2tj{?NDu|w$@pL=6HJ{ zacsospN{(jZsyPP=bbf?fA?H2_6)L1wTlODTS)i3htoe&701@6GdG2^NW3*Ecwbt} z_t*V@ToyN0pz-c}yHOkF{Y;aMw0awSEw%~X|Nri2w9$R7K6K@3*4M~i;Cc(8JS$ef z`+@rLabdvw!IzDPH=YcEaAQ-01Sxdhg70o7E=rfc&yN0S7j&TR>eD&&_y0tn$Gy!| zRiioH0+SOB z3f}4bI=tlUogNmTjK(|3jTwS@59LUac)t$uRUQGnwc}o<<)G&AuJ`322c^Xy*MJKoqYd)IJHQ#F zFLNh*k7%hwMOg}8xaVRawU%4k>_85x3Fq+=!99cG4F#|3n1({n7o^_2^#T11Qcjc6 z`Xd9;_!gv{{qE1K@9NOcAl>A5R3`2}MRPeQ4~YY-fBs5uuSqrYK`EtO*YS>)r;krTrcIuyQKZzRWr78d@24K_WnO^orI))MGf8a#vRqA zDvp5V#+QEGB-Q^q6uh&IN6pE+qXV)u(0E%KRaV~vyx+8*TT9}dplqW9cn7~*k!<%% z6Vf`S$FdFZ#&@%yS_OE&-gQG+7`!08cP{>>>mU*84%<`wIS!q-{;NA)`m?+6T}Zn{ zp-!|0#NJMj-%wR}*h49gtvuR=`T*Hb<>%5k{WRCbM+ zTlh3!wtw{H)*--PRP6+?Nk7~@uxF9;Rn)%I=er{wGpAH z$38qK_M-D%mLIE=F=&GiN7@~5*(Ypdht4~7wnm0M!iDB|ljAsx(LaTaUnG`}^FnhK zTi2u<%*Euo@Y8;o48WUV%Eb#$&Fd|$Rlcu^)aaf!?#mad;Gr z;T4(pTRuHCG~S_VdjsLUH^RB0?J#fh-rMBiY_*P8+7Qn75Vs59J$QTAV>#fx^YNLz z=fVAdg_Tu1R`n90j0IbsT#P{H9UHwQDEG4=J{@V7p417xYDDL4BB*t|F@ivIykn3! zj4}H6S>*fPUln}N6S?qb3tf+6@^-(`a9McNt!B-pCcDf@>~C*>Z@;~;qFa^jCnrbR z%czRO|4g&yj@WO)Q0tzHUiX3#KtS3zR> zA;Y1oy$3%xW9Fc+k3UTa${sa&`xtKQZ=vFfoqGFdw!QpxpM!7%o2ZN9YJ9K!pB*HK zf_J_f50N~?E_(P_7mYV0xqQP7!252^>@>{#=#ar#PB4Sqo9j0!%A^EwCA?3`To4Co zhFrR{51v61p9!eWH9>9_TGF@&M5v@_we=-O^dZ(Q3p%3t>N36@YtFYeyeTa1m z2+%QiFQPf#u1Fl)F!~qW(m&!`#S7gEKETlN^(iKAqQ0E`uicI{m4oS$+&tJz?2!?# zB}%tkp?}_zZ>fsIhT}+|*lp4b5>LVVy3W~AGVk$Mr*zPGhd*gQT?lwDY4K!-XOQxF zS0|+b?++cVdX-Eopte=gZ$B``L2qjuOuPZ_NrM!|8-RDbL(OgHt3>E(tKz8?BXr&w zR^VZ7V zsg1_F^FjX8+kkgfU-A-|H^Vcw923CXd0alCcjrn-p22;r85ak6UM=tR1iW1$+R`5Z z-iK@kW{tCnP+I8RjuQsxycs?Qa(vi(8h-(4Ct1?>I8Y3oH=q0PyOQr&G{>792Uh>2 zYQBAVvxX1y(CYiZXNJ8RyZO>%&m32L&CQAS35P}4r?+rv7mD^((?4$t(wmnT{fOmVsq%6$)P=C;MU%;EE-+Lx(nHuy7r)Rbq z?7cb4ZfkV`yq%738q)jS1kH9i8!m_ng=~96i7m^~@Bh>C5sJU>ort$V+HEFw@NQ;7 zzyI$_wE%}&@kN^Bt&PNi)xXF$W^RgIsRdHDx9aJy_ws!)#F;L=+!MxD9ep`JVEh zeZN5cFPb*3TuX#Zrvm*JZ$=+tt#|_anctP+Es%E01}tJ$>7Wm>p0kBGBb&!GmxId4zW9MNYlIoIzeUDqtR!^Qhq({kdnkGWHD8DbCL35caBQ6_$29Momc-J1n?uYAy1|8}Yg;!^C~xHOdrnNP|~JF1}bzQz^kYOGm; zw?x`Gc7=yu=R)V*A1d!!Q}&SNcwa~2!0O-rzI9S#v%HYAfK}*dEH>}$bH}bNm++{O zV3o))_=-Iw$By6jUQ*D76C2)LXODw|j6=lF1KvE9_eB$@o1k1C?t$Be zq0qqkE5QaG=)6~1`d#b1SA_qHv>WLX-`G@x&fBqQC@OU0eVXG1 z-gyKTi;d4Qv$rFYpw)4`jWu!|<#)BqunQ_2cYbrh9{Rr^4Og8+RUF%w&y?LfOj_PD zrr>>Z=<_l%@2|Oc7}0otcRj&>1@P9ATk-^Xq-LXk>i>U5b^h=F8KC~RqR2sa58fg@ zu>%)K!*9$v&~nhyn%hlLAP3#!?pp)rpi7&Qq->Mj4 zPy=$%K2t|78BqUQKQh{ICXNURXNs^X3Zv(s&&@K?Z8`VxVn{pXCH=FEztD5gq`zn8 zd)*f_mxIW0Okniy`J01Hwf?-2*A6AGExc`*L+mNyQ1PBzQ>gRM;k5iQ>>PCO*W{3u z;&bhPKd682uTWt!N>vFl7-sCt0G5WWlF@8 z{|b}$LF*TJbtg=rqWCnQ59g_<|9MW=HlBM=_q=g_S=7bB!SPA;PyKI6!MjXYV}#5* zWlt|V8t*K}%8{dh_jwJQJuvT|Mf!{G0^T3kOva)emO$CNO|p*y-fj-Vt`7n4gNqv+ zngQ>}#XBM-XNb@%N%Kt2Q|Q^d$?ZKu-2EDS2hxu7o3Fvr1Ly_P<6#$u5%y-9<4umE z4x@iBD_5P>2;_zCtu4=}&2Giy{q*BU@r|!7Ys@Pj?|n$k>n+haVNwF#I{)6>`akf~ zhqI`PL%vO;-8z?)y)7tsm-I<_lX(la6|$l6{`{yc>;&Lly0Rw<=KWf`dtU^cz3=y` zzw8i#BD-&nmjK>lA*)qj-VW}9sV@NUN|p}ibK^v4dK)utECHQ&^6U1^!opQ}oYS9n zr3W%Meepx*-4!^_czo|un&VB5;~hr-MouQGw;J<75*$y9D;4 z?})VPviEgdYlvPTZFF~w)Tnzyb2%smiDLss|6IeLW@SKpP;cG0(J70!m_zKk{$2ad zuo7wl)Q^a^Y{D*(B01Uk`L_$x{SrHFCo5HPjK;sb1yzt{kk%Bus}0Ra@BhKeTN7@J zc+q$>LbI#<0PjJeJHKGw+fF%uxDNB?`SH;3MIZj_Sp(^4z`Jv&Oll6`ZLfMVy9V%n zt9{wOwsG#D7i_0F-bP3qkr@3G z6A(Wv5y1zEy1TE~nfL~icirX#TMjeYLQbNYZ)eo+W48b4{rvbhk8rx@J;UBYRUCqh zH+x3^JdnPgf_Ifblma<>E5CZpjmA6EV!e((;60_G&jrsQ8^&U1o&esFQ#IqZ0h4&| zQx#sn0PkO%i&ho@-lbivYmESJ0t?UfP0B>5e}TMhVI?|mK{>lETBCLNA*9_c-qKLB zbLhOY+B{^c{n}`b_fjN|OpN}8&CRs&g75!#bDo)yZEMHmT9m?Tocwzu#F1mTFw+p5 zH?Amj1s~7h(r)`*xs>Zl==J~Mj%~T3Q>`?|8;`^hgVDbX*T!=HU%XJsxn;bU zlwM=<&bn?VXu@U&C9oW8eJp}q|7R^W%^lAlru*z2XQEG49LD|Mi?zT9(qQhrmV$Tr za$ct24&scHvaZ#}ORZTr*)o%aP>ZHcA)5Ahd~cDoh#zj?2Q&fAQ&u$t@A zOPb?Nj>80_e+lsp8%#BMp=;-N$l*(|_udGjdUv{5&7iQtY4e9~vFm?atMCR-hwb#g zIdOl^nwmJu!=Fpu`KSK>?^fpjGyguwL3R{5=n*kyoScK++|Uz5%|VZc8rFjx^Z?v< z4i`vu7wc88zy;FSZC`t{r8P%R$JgB%j)iQm2NB=`sg~8d={1-^PHiUO)?EvMgtOa9 zEmon=AaCxwu-3QkIbIxTr&BM;9LIw`gN)M(Xl&fkO>;S@5Q!reqkqOCVxnfOd{7jx z6GzUC_n1Sh-Dbu56+gDuB=y!B7hI+y2l=hLV|UAt?uXb&d26cT*i@9JSCUSu|7|IF zKh*F4>wxs;cGjh6yf1V|?Xv~Em&nQ_z`RE*O21x&XOKS@-`!)(U!!b0<8&W9Z~2w2 zTlx~DI7vvQLe1{}Wh#!hjNKg5 zx6h$_-dZt5RK;P-cF{Qg&jV>2DR@5+;))_?Z|Ajd7o+jka9samGvNL1d){T3cbbN; z?pZi{$BNxv$jw>9u={p?I=KIze_Q^7%YgT9b56abfcK}7GW_)Z5QxoHd)2mCFVz2x zOwZTbk7_2K9agPnq9ss{yE-aL&3ZDRZ0?> zH*QV302=R$zAN8s2fTy)+R9G~SQft8{k)-hxtHEiiBC?Yz4W!P$GC zPkWlt$Lgx`@CA>+=PexyyB_BQ-eUEF(OUrT0fA|^w>(71fidt=(j|1>gJQBK3W87Z z+mLoM<>iB4L(zFFnv1C|4eX#f-sCuBG5Tk8+JWf`7eC}#=_~s2DfZr*AM|2wR*6u< z^-|5+$r77)Z~h7c*CYINpS|NYP#1@xy#C4C(f{24M;B=f)c;#3a!})0g-LP_`YN$% zIa&^KU!p&|0^}euzt$0Zkb}lgvGA+`If%!^?$Oyz$~7HEUe)GJv5;}NiXJ?~awR_u zWdJkC9JQ`%EEyrtmp=aO6Y}Ue=*0D2hla0h_+g|Sp(EyrFe`cv61!~hV*9Q>n#)1t zII#Nn+|N#}WgQ<>em~EI?c+zxA@<^M(=I+4of>7%D^K3{Q89xYJg0qc2BP~Mgv&^! zE)J*UqwpJ~fcIt!-VM46#$?_LCYeOhc)wpCzIYYjy(O-T8y;fqRo?1v2E6ZeSveE; zE7W{9oEz+Y5euze^Qi~s{mrO6VFV1ZUCAefx5yKroh+a4))%Amo?3?I*!%hw-WzH6 zKAvgR;WRq$@+bM9O}F&Y9B*Q6!49^FduU3S+BYbYt=+ET}aUTWL~b(5mjI zmxsNBgqxZ1*Vy@#{&~+)7e|h7WA4;7(hSmpf_FXpmcMRqiS2$Ug2vn92LCBNzC@R*BqmwY7aLtC)g22RyE?Nm z7w}H`e)xV1;GHoW2>E;ofo3^2Ul$EP=l!Ibuh`(xOFT2@pLQ*_+hpF@p!0U{wGtPw z{X}!T>ybD%Vf4>}W4fhhAs_TAI_1V(!v{>RsrlmUe(o!3{FfN+WvRiwARSj36!bnt zm+pB}8%Of9WsETwNZH$-f_L2ocGCU-@ZrS7Fb^R#-uUVoSxdnC;dH+f%zJBM#{OKu z8z=A0CwWh}W(~e()8>I#$S!8X@f(158izuoE8tzx^{{`z_Yi1o+o1xJFm&G6{~vpA z8c5|9{{3&$ZJuRlphQxXnGAcGlOz&Rrie)9MpH5+DWQZSNi;|$QBqryRO}{cl4Puq zGSB_jcJ}@J_KW8}_kLbIdq4m4%K3J#7uUBwuC=bU*1gsVZ^yc)Z-|rBxTV%oi!VE2 z8&BS3_JHz2!O!c9Oli%6IuY!H=ML^H|DzRK8e7sFn8>%uy-AL9^`WJPF@$qg6 zRd}FmqQ&%+6QvPFx_mU$-HsQ7)%(Bm|4gs~02?G%ni}-l$-Mv_VsGfm$YIqW&h?7- zd0`FuJf7}N>HmG>Qk}G54RYTlxq4BkCg~y8_%pfY|4ob=j#4cZe1L*|y*1vjaF`ViZ&`^a3}Yz%^VUwbz5`YY?Gnh&~^nqHmyV zZiscE!TXhb*J2cJ6PA8iEWE*XZ#hwjcdBw<90l*N1OrcPi1*3RO@B9H{yo=jl3&$YJ8Z-$eK?Il2=USDB)!wet_CfWTC*VGTPnZv0M# zVdnz*E~dx(a?221KD6Ar7kWR*r7Ukb)8I{>Wz|RVjw*Y&1QT!PTYID+-bx)$aw&Kx zth!XD1M${bFnD2kuNukZFXzUhqIlq3_A~Yz#QWJ>vuDK+@A_K7m$EYlf$2VnF3uy^ zGsxs?}J`p!i<4kK_OsxNx4N}tHh|eEtelQ%~$EZH=@(WdXy<^2u5g=%OZ}`C> z`tct4{bX^iI{xyO^}dF_^q_Z4kGF^%eLnJvjJKI3%=Q1l}$7z^*W zIV!%3A>JzL;64TKc@?gKx)5)bP=2}FcB&-RiBb2|@^}y*J%39c#QRZI%tH@|cj+1) zwSdnDfsu7j>d+2syk&KOyQR)Yq6IZ>`OV0bt>)Mb(!&wy?4yO>84m9yR3CWxak7LK zE7b~v+(TV10qppAH+NTrv2IWSUyh}{+=?UQv?!B*>9&ZAd2wgsAO8*#?|MPmw zRvNq;a@%lXlZ|`p(8ucOG)l*&)9G_N^e(d>TyrVuI zY^5fSW%O9)`mk^?{e)yltX4PY8$rv#O2!MH@PBCmRiF;e~S2Ye+HbgL+nS9`UxT!+rqbo(VotuK z9;`tSZx0&0n`JhSqIk26b}h%kJA~syZXd+^@=mTE3f?Z7QZeMgkndl3`0JT{BgRtW!~@1` zHdkZgeakcTXII;AhQqs=>Z24VKRsZV!onvC@=X?%u)g??i??xy5c%~Id*CiPHP$jn z$Mcqf^9MC5wlF>3gsY3`^I^l8LOme8od)lwp-cTJ-d9s^Dq!LLwltw}7~=h`>I@fU z205$qjDraAzO4SYF)B%$ba8M0jG1RVSa9s8HsyIsi_-=duE7V=$Wq3gXJ3W^6ZzUM zJ7?_b&6@m;7F*;mtzzftTN@UB9%~J`(}F_5H;* zk9%6lUQcDpzfqY0~b zbdU76!hKq#=W-|WFDAg_Ez5joV<~zUXJaM{Cei zH7*sb8k8LWJEH;)u^jTp`6&&OnO#xpCRl?Cp2)5^!l6&9%)LFk>T?`W;C{7Kj?y6M zY0hx5lfl}&ug&Yd!$7jT4cGO4>;~!0^MlT7a=VBpsc}12UK%|76T3m0oca86h0F-U z)u2~Y9}_tFiSL$-=-(m&KCYKg_;alnw+5N%BpzB)Y74?xZNJ2S!asvVIMCuL{K}K* zXOM*ZAL;UO(tEH#?4S4lcGBS8vf$or6z{N+wpCbogBY%l)e!IRda>#hy!*xp<2DfQ z1Fp_*l#l9>q8>-c=KqKTZCgxBS3tZ!c1CSZVm0;stBb%PY z|GJatLygNl^ZQ&%AvWIqCWLnr4#NzGcQw@qUVaVSLMKj3iUKLKZ@2vB;p3exv%m6Q zwj1y>S>W?=DgFkjnvT?`{5@??q?A1{MKAY3f}FXd#9}--mkcg^c2T+NxN1zE1OQnfn7ph^0Xn|w*7uyH(ANR zhU6jK(0dSk+m-NFAs8F)vGW>ab)HUQ7d5V9OvyUM3mb3$!Bdx-T z7=LE2LGq%(`{TVeUs1e2UOA|Qh4-?_w-aw5-nCbnA}M$;R31KH1@X?@Q1V9EMwfI! ztw|_{KOUS_NlY|_c$dg>j5e^4!7Wwcq&=?=g5p~-!e{NV@xGxXlrd)7LA*(g)A#=+ z+V(FSq{9_<<33G;42O3y)dyaFxn~}%Z-mENPRDOk)YQSpJNCBr3|H^a!$yf9?r=7I zyz9jde!fJuX8QiW@XTJid@Q)~Wgh3HIlOn!;Qb+~=Pio&@UwL*vG88EYtN6*5bu)F zz4;Wp4~8R3ly7f;f49*LJF$jj)>s*g0B{90DX9L#MH0Xx{< z+aG(4zxNh>p!B(@^q+@9u5RHXm+AQSwn52=!@!E^@g^uK)90h+Ld~-O`hO;9{$Yx+ z|M#bpLF?H*qv-#et2$(-A#jc`#e7~ig#W9M-42zC&S2#PeHuj z<>#rJ0RZgCAUWTaFIdr_9zyEk}$A) zr}bl9O>DfI0}_ZH+&_rH)VNkz^++uvY`hm7&ffQC&p5;3{g&!uK2CnWL|g9I&5D3F zH*4F+y^Y+u_qhLTSsQCC?|L;eG zciY4PFBEUJ%jeax@V*tlgDVH(J?a>nN5PxJ^aDE|oIz@A4$0lNok-d`pgS-FZ}8n; z;B{^U;=R36X74IaGN?LzIx_NT7*PM3Hq9-Bjd!Z7wnfOg@5D9KIDuoxtMd}rc(eNQ za@@N&#&CG2P<^oA3USoQ^gKG8Y@*yr;p4Ipd-o7+=x1RZugyPNnVT~#l z-VG}rq?JItZ#QIrr{In5z3mz5;sIRxBzCD@G0NVX+V2{hg%IzxAII+|!M(Sd+Z7G- z^20#fp^~plR$y0e1#!E+)VgkBA~i1I%Y;nFzdUc@c8vTiz>x9qmZ$n~#mO&qe$A@U zRuN#cbJfwmr}6O)o9Yy}qp=;B&F;T+@Dv^W|6t<7!;#OKf9`D&PoIzOpQo4q*Z(t3 z{~tnAgMO&xK}8@az&l9P#hnOPHR!<^Rm2I_plj@35;wsbbmMm>zY82x5i4w!}~DR2VQ=Ti<+dyvqS)k z=1qyvu>oAXg$cub)|ih4)KRZ>T@S`@+VK77E^PM#O_xQu_aar}>AIj7UD|!Ez!S z;=qW)tMVfdZ;?o$t%(9;V5_6T@?&EdXiet3_U>OkZ!vX|_xL2)N9>@+?T$<@=Iq1X zLHg7lY&{S-#c(S+7_mShl??UJB4xquiGkHNH ziubxJdfHfcE15V(ABK2~`q-?d;9XY~Iqx0ZoM_j2aCeKRAxS~iy4`DE9O&(5xmW@5 zUgYkz*^ZYCWEcAw5Iw^{+IW6)Ko2(F4Q&Q*Q`3JE&rsuXgep8b#s^-86FHBmUl70_lcd4REnW?B7p zTUdh(bc*J#*jc{wZQg@C6Oy#3hOMJ)9I$Da+M6#mK(fn?z7@KN4E9Y5rEr9XfsKiO z{nia**P#B>=4X|j{3dRq#x;l@>sI@hH%PC({_P{~LLf2B-zzndKB^DA{B&AvcrQi> zgWuoUZ-lS^gWDht_)GC74IKoJ9!fVTPTyN1XeYQ3XaBNaLs$Y+dx7Z0ei$=HKL~d#vubfng*DUrB zo8xnKD0Jj6!_6Q?sXp-XQ~J0*mz^XG{9*^Jnq~3vPRW12?7Qwku=Ko1T!0Eb-dnd8 ziND>vhw1UI*mIdKA4jj>t9@EHhxc9@y!+lc?nLqCyTQVag}0mvtI!&V_pY{e9F+cF z5gB#a0P#*drWf0*Z$e7{%0K=B;{AP5z4S1|d&&3mFUpc+z^2`*AFdn*Bn09fpT3Tb z_o64dw(EWm5EoG6%q6%oa=u{W&68p7yIhI!@LoXmftO!ksFjI6y9l_OY`gS2J3ih? zwY_||wBRc^g10IPf6_67R5!HqMGi7O-h@tL`h1MlmQcPRg_Dy#G8$h4;so{XC`+?_t-&Y81R%W7yrcLA*!Xn?$7uCZxgs%_Nbfap2U}o%)inL1M4@ zo%~@Q87TR-tMa#pfzyvA>Qr}PZ%)WtonH1(d4QNjjdL%O>FUbB-kjLyPVihEILmO= zdnwfiUVe$|7Po(WDhyWCC4e2*@i!-~98f+qxHK5>ZdqbWxP`xZOIT3DyVhWW`SJFu zqsxbP4r#@@{JH8KN`v>$aEY^M^-dN#&Vq&anLfKa))4ROw|BWx@a{vT%K{+Y-M{W2 z0{4tb1@YTUydd7z^A@eufq2gxIucYTN(QUHylT(s3j=I%Ek7(nu<_0wIsJjd?-!Ai z8uwv&)g$8^Y`mqnDMSq3nqfG+GpRoC@@qLTIj)o`0{#jJOR)yv<84!4aA4K0AaJ1J z-G}hV=eToq$Dj5;-mUFr`n|WP`P=C7!D$>y{s3=p{jdLLv~Ki&lMftXBWP;Sh*8zt z8zht=Hl)sh532@sG^yg?G!b{KcaX@50)3 ze<*lw@NAJxf_NJm{_^G8xR%tkao^1cdU0SUNBGzhh&Q>sp8cvk8O$Qzj(LcMgE!*$ z*|f8;hgcq?4x+K!AhC%W=SS*#o;-w&cUr5agExG+n$iBPxT!u;aPqrsdCc*#h6uR* zc<2;2KR(_iV*Qh+l6=9qR+G*q2RdeuK1L~(e@-$z-UN3*myfE&NbZJ=5K4m-MvJ%B zB_kAXlTIfdEWE?khY1nj4DyQO+WC~_t=-|4R)Y}l&0!m+Pi;0QCC?+~XJ|mYJ-QOq zAl@f;vS{bZk%8wkp|8Fs;oyt3N@nsiY`k;HT)Vfg7$knB#;w%!@C;nyf?3r>pEbHU zS1=ylIaD9QIQiLg#I7}6Bnk>M_WwB3fZzY;%UQ`e?h6H}T~_x4NchiN%saOCRaJ(x z9;5yG|DWcwt2LM|ACAJkRzXweD0m;F!TZmV^))Eof{Nu_Sa{Eb#2E5Jyn7pN*--G_ zR`=K^3~rE`vPRzxT46?7^{Zh@MJWypE9=#7gLv;h;BkCv3A~(m#d+lX--BSXyT?Q; z5_@^;MoezJ%JDzM8ERbhk~6Cx*I+Mi6&|hO8I@){yi2G)3UKn{iPqj;e?S=AQ5?+g zX~f4no{INr<4wOlc;WB=zZx=6xVdkP>HB};X%o79{HXn0UYb1D{~w^i`?sg+-2MNQ zxpzi%JSP_3o43f_mV|h#Xn#LM!Tb9?lLzXs{};OOig(8|6Ovo@TXjXadfTG$@j@iT zn{eioe3J|ryxC$RJs|=&Cn7A~o1|jnEpRJPmT$!$A{RBT#^~5V;%jWYlX`Ur;LF<# zH#y;_`Z$V{pT>%voUPTuz(^^7vZw$b@4|x@oF5zv1tJkPMOW(RxSW`EyF}`Z2&V7< z37vHMC@(OV{BQsN|8#KtzY`z7?Klff4VscUIQKvrr3MwGn2TW5ph0Va)7N2xw3xl= z$wpX%9tv;`kCwnEcII!1>Xo%7Meu}VzS|fFID-n$J(e6G4a=U8xwaCX|4;A!CY=)j zCa>g|?O)-KIU~F)S1j6NHbR`B#?nC<@-orQ?N1i>*i@hOScq z@PPEGo&Hv2i1)(GBfT>#$UwRIb!%5l1X!mLFZ^5(8}Hq1XOjn-hKUx`I71|e_f{4* z-UZ2q8|17Q5AOh~j|({Y0ow-k0ufQrvMKUN?_zwsmn3nYRxREFj@gK`#K^zE{dKT7 zaNeeN13%OE|7pItboo$VF?+G{;N1EDLo|4g-~J+v;@yaR62!vW=h2mQPa)n*SZ7yL zmbYY09(IgCye$Sy){6{Vl8*8q%I7TOKv$Lj%C8Xb=chE5_9~LWOSaal#=9dxApbS9 zTjRSi|5?t-T-ep>GfWJi#<9-3&u1BijrWr+e-f{DurXZq&Y}9K!O5?O;M-kmDFWvA z-rVuvCmqXM-fVHlZf*g(=XpaHzM*4zYf-0TTR1n<<4t(nPL~h;%TGQBh0ireQ8aju zg;vF)c(dHUAb^E;Opm^L6T~~`^9C;p-uDfHgeZ7h-qTAl?6x3T4s6_~w>A!>3>8ZZ zK)iSPen0$uIT<`~wb*kkA_Be7qBFCM%wEx`SnTpZ-MD;!jRwCtk4VC;evn z$%*U9=XCj~ZZrB3l`~hpBWds+T_>N3;$6mdfFBF*P0G!Utq||Ow+N}Uc;{{s(>mX2 zL3+Slw$A|K9jUVS`8dQo1-TV%0rCFcejw{vMHpC_I>PC`27C3^BCS?HQ+J4n#&s_~ zXk(F!y*Z)&u_?^*A>-}6p*~b_@|&$ccVK?rv`0dVV@jAYf!g{nj}^Y605nhdnc?x9iyi&TEihWWM$o6Ww^xd z_NkpG)Yz8fn)tK*3S5Ic(0%0WdRT+T%km4N)XCti{D$`TDdFJ3s-lC&V%RgtbonU( z*%f2Nd(=4DbM>2Y>acf^O3h54yCx$HH-kJw^-+S8-!82K?Mruyf^tIltC6q6m@{jX zrO%DJ9xVNPfJJh7qhB-r0cnC-kBvfYKGP4e1Q9xYTu*wPy^FH{f1Klg@OJpyQu4o+ z*w-6zNMPY@8bHq63-MmNSihBmch4`8%qh4*+IMQ<)5`+3q-!%;?JMC9Qq6Scz9342 zG~FC4rAh|B)nfhMI);PWR|VA7TCj&$>x}O#z9pl?o76am4Zpi(;;`}dR{s##DaLqs zZ=(9}#L3SyT`MFp2R^audSZiL06yNqPu6Pgf3Xb==pWrYYlz<xOLj|r7$R8RMZX3@$v2~6yj`q zvJJ%45i`qqp5j(}LVnFrE%B91k2gVsJ|Dg_7iw-6Q2PJlY&3Y!oct||;>{6xRSXO7 zMOS4vr9!;9yZdb@c;D};F!6%GqnOR@2m9Qk|aN#h8Sml{`3G!~v*i;Xu&s{Ht{9^>J?fa-%4C%?ce z?PtyiiGaeMIval;e7qm`7Tf*sbpWQa=RV0B;!jQr7Z;FnN)nhJ?@w75>GI+JF?VlH z^c>!-Gke8ti_VV#4_S zKVfOx`dvy~%s==3{*^u-SC_2(@BV+ZQ)BR-aERsopBl6UnNZh8YtW{&WztwR=mpnC zQ8`$HTs3zmZ-6z(Jp_r?gJ+Or&o9a`J!wN?lW3CI{x%kzdbsy+p2Pqtton}B9U>Xn zoe@vU8HxaZlGNOTqOq6Qebfst&A&83?4!ojjQYJ=AK->LQxbdW>8bjgi{WOF{!||# zIQdQItseffL=@bM6jmyEK7#2JrAa4A$>nUdH~7sTkX0Imzr;?c%zBz5FTwOfETN1( zA7rr~QtOV)4Y52lcym0vl!4-Hb#ihc7T$mOiMFZ`@50V)k12TH5!F5}4)N|3A!!&_ z*^tW4RvIn%77M-_+-e|4#=C0QdXc-KjEDCUs*ig(`3bTFUg-WI3Yy-h%FAEH$Gg-ru~J!oKbYSW zddBnH3*29a1_kT&{?(~Wk9XTr`h2KX-@4olKe2<=o0|r2_R|s$DBhAiPZnU|y?Ief zD-q(|D0^~>f;SuQu?szL^|p-P#^YVT4TiyNwmx6av zNXR35hK>Wtm!yh(c z_y1FC%$(Eij1h&YaYy$4ezlYzyZ>holqa!@G9KQ4sXhoe`7Mci^Rre}6bybl*S$#& zAMdwRyfb>c`DFs|S8ua*&TAi9$oyw-C(Y>dao)6JVMb;g;DOCb8(TF&a8R&QuvxHP zuu`yCFjw%TV2t1%L2p4vK}$h>!Bv8b1w{ne1x5wF3w#o25O^qXQy^d9lt6;O0fAit z&H~l~Y65Zs;sRX!ll*=Bt^BX}Yxv9f3;8qollUX}1NhzfH}RYDYw<7VpU=<7H_P{% zubr=nua567-&MYId?$EHc?x(kcoKQScy{x+^4Rbg^JwraRkDCBntdIm-E+^Al$S=R?k$ocWxmI1@MzaPH!C=CtNCon^x);88RthKD=te07{S(90#Sc6zSSU0npv+A&}U|q;6fOf0|0!!)t{P%zV#rS^% z{A>uT#6|us;Y~pjNI$B=?ra-E`cQT7Ora{$i>d>v6D`P3RPE>SQ$T*8YHw%jeB?W- z_FRmqLV8dYdN{uy=|)wEW1$h!g{t6rIo?Pos)AI%FF`s`6;L{mhqR;0Kg!z$`G%_9 z0b9Q!ZK(27eU*oNMV0U1CvBt^RX%r9yOA%b+L`7uinO50+mpQz`HU*BrTvSLPpI-7 z<=cRKM3u)Qohal3s4phu+J22pLuOuWyEA1aVVo}y}lot`FAhbk*2qdUkGR9W^$ zr6aYdTKCE`7XCb>($8;iK<=VSZ|{gHQh_R6n+gM@ z993(U-=BxvL6vq-ydhGCDy`?QCy?8y(hR$K4k<;IhUxq5$SqW<^N(FeZlX%HPcsp@ zfhv_dq+p~3RjcC@?;zJvwW{%B7E+8VWq*W(Ttk%-=esfFDymjIl(>mpL6u@oh8c1h zRm*otZAOYvr69jc11Ut+viXvB$R$+Cy&oVV1*lqD&?t{wM3t;x?p-7wRZBEf?2!wo zS}f+g6UjrBbcd}ZavoKS?ww6Ta#6K#@9kzJ2UQDnq7smEsG2{on~a=AmE=dM)krp~ zByR88ie#ZmJZknml8LH$>*I;Y8B~cWb3Z~dP$epT>k4ujRl;Sd5y&Z230=+NM$%Cw z=pSf+q@hYcMg13&iYmU}{u#(gRPjFUe2S!?is!_*7;*wt+|D0Ik>jZ1QfIk?B%_M5 z-i{nY6=iu6NkSE6H3vD0DoXQrI=4Jwgp&(Z*J>_IW)u}f3)ts!TN-ql==43%tT9|MSCjnKdn-{)E{-WxnEJ+%f zMb(LKxv9tus*V?tb&zRPB}WgpB2%b3X0zorGKs1r@v7y>1ga9JHs&Mas59ql)q%FtQs}l=o8+KU7hkn?!b@it;)i;)|*;`q}Rh zA5^t0xOW@biKixDC{D>#2nq@YRA|9w}8oJbv zY)94GvMhhZ9aV466>%eOsCw<>UVylw>Xm%gV#Ebi5+ zqUyyN#c{+5RnK)5jS)vwJ>z!TiflpE)929#5C>G%o#lRq*rV!6SlkG*8CA9VKMo>x zsCq0Va2VNysz>imokVO=RegQ0A7XfKw3te-91Kz9819dLVXK z5!ryM`@I*$5i3+xKK*KrtVh+o$Xgc?OH|#pwJS!}p{ioO`XFL~syp3FcOh$0RrYvT z1u;j}?ZlL=h#9I%UHV-RQ&inrmVFR0LDh}^o`r}ps!AHIrVt}kU9afQLkv+>>?st6 z090LDb7lx3qUy@*1!u$nRhR3;6A^t>6`gaiK=e>m7-Bkx=%VV9@sK&P22};Z{3{S0 zR9)mveurqI>Ozst21E;0dHZfgAeyK;zg}c3qJgSh(KW(|I;zeMPK6+9s5*Nm^aG-b zs_f*MB1GlC`~Mif$0NWUBq5qLNXo1RU4zuPw@40a4f6M+tY=^At{Zwj;|;cgYmhgm z{5P4xHOTcR%YSsT+mLQ~jU@Z~#Dcryha!UD4w9vK&st$)GDw$r_GZ>80xWHRq0syV zdkwPFKjwy>{4{Y9H7;gv*Aw$;>@~aG9 z$Ci!ZE}8%NR`OeCegH|FuQtzmIUQ$^rYx@$8!j;a8KiMKeJFLCs?OaYeO!4&O{o5m)$>{3LWuJkTwSgIHf*X!1NoW z-hTA?Fcw~0WIOk~<#7QTyeWMriZ|OS(h@AZty@;fOhLT2utl{~@Lqc;Yxfn1_v;&8 ztDIKbkesu+<5!)G1(Bb2lOiDARw=xd$`J4Lx6f=R7DoUdn-!e>1=x726~OC}7EBR6 zsBx}$yA&m_VdHHy?{rfC7RJL{i|WG=C%t%*_@>9v?7u*d79tt%bJTWsF#mR2lae!SPy=Yy;zw_IcHdCTK`G+zS=Q4QcnW@ix||4RYVj zcz7S6`Y^=FZ*RzR+2&qRaCh_af$y#O`~NEj-q)=u^9B+o5$krG#y^}WbRlSq{8e72 z$NQ!meLj|WWIW_M@ZbIaOwj!kDEt1nJoZQx=U_;McjWRteUi2+QkMN# zd9iDdUbRh_+wNJSFEws+;84g(Z|oXWaPp$lsU!RhH^ibo@^JDKY29d98XyWBwPQ9o z8jj;ONF0hrH90OjKti{7;>}e2Ay(=5uU!txl1yKN2()Q9O-&UW?-VxDiWw=! z!}}A}M>0-+>%9`L@Rx`H>7KFdm2CKUU;V?^U+lO86iV+HiyyDY{dFL$<~jPr_5Xne zX$^foY;zb>0QAT3IRH)Z!4#aqFoLIDf!@e4hTWt8gOd-ov)?=sDH_jri6gyJ88 z`EE8Os|SZxo14UfC%U(0oFLwz30lJ0CS+jn?8*jP=LoQf!!_wFAXz3)(cxZvdHnv_|2I7SpWc-|V^Qh>jDo8y}_&%M?j zSbfjz88^qj-XihSE0YH=&M^oc4uyAHS99bsTO^qzXzO z4t9$G0&&>kq1k55}m;2)4CynJE5`1&cP$2JK#h~)RQA2G1{-f3 zts_WaE933G4N`q*;pC?m$Rpwkm$wRTeYj*`gO7I~zrZ^&r2x`C-mfd>+u?6cXq8TN zrg5ES`n|W968d}uiDZwGhuCa2?cwlGr50J(buFfp5hF9!_EZR9;8Ud=0 z7KBGBVb>tO3qB@^hY6sH8uvZ-%(orSuxn82>RsngvIsHU43d}X11~=zPwS1938KKJ zPN4D8i3!|>=Zv*x$D2Vr&>7i3B;bxegCv}Ava8Z-WcnIJuaEA}$D5*Z=Ncp_8oVh- zhEcq)?rU9zg?F2@D&JO!_m6@~GYZ}g`kCyjAl_TI8wGHMZXzwoe7d-5Q!J>I2KhA* z@8z4f-8R}l1|QuG*ln{TK&Nei*4qR#mBoEk3;}D-@k*rY}j~*$cUAF8vaX^ zrp6^a^g)iqV&fgLHuIMhf${K0eH_5aPxju&{?%!s!1wHwfUYb)-Y@;utU_*hgH74{ z*UU=LvAop~9dVF-1JmP8Xr#}F{^wxUpYR50xH%y~gE!@)4ixWoei2Goct3i>v+)4L z`|JACk12SU$nRah0OG9}F}|WB)RvTYh$q%jKNgI1c;}5mydBJ~^QPC4!G6md6@^(5 zpdlvc)_^!R-Z#q#eon!EiFMStAosxvo@3Z}&)Scqv&9H7T=hnMOycBc5O6tp;;Sey zs+w^cYR6x_-5K(0hUL#L@YFmYuc8~j|JU!kW@n>vmFe-G?5EGi3B6bm?te~iiPPXs z`AP}J+xnU1N-VsGzp-pP0`WGTSjtLS-cp?h9`HfD!(HZ0+Pt(OJ$T4@_lt5YaG&>5 zL=5)-g~8*QOD)J?6MNk^<0lcIFs$T>y%{#%lHQLuZ|k2Wo~OnYuecqdQ-Y26?;{!! zyVw{HZ`4O0PJYHGH?#4mih(QV=WR78#K$`_V&0pIU%Nntj$;#&j*mA%{LF&rrD@DR z_m-s72amla(88)gYfi;p9D8!zaNV8_#TKvz z^*UZ&auMD^T09Zm946pEVmITB{QW)_aGG13O@>3PS>FAdjy7aqq5bsw%9jyfuhH2% ztOnRMs6cz5L|Tp&gi_-cc$n&^i@9U=#qy^O%M#Ot8E%Npr}|imli$_dZa2UG5CIqT zN1i!;o5b{q67{o~XF=CkFzFocwQII5_%$ec$l!ZX$xi04K@Mhg`Pjj2YtsJD2B|a+ z-jolIQM^sm+cdE7-sFF~hYJp|zod1CDR^JYPPzXS;yr6p=%{aOPttnLBD}pK7O?CU z=}&-o=Ol9OZiIMqW)Jvou8ROGKX5LZ@Nq2%;BS5+R8Wk2>Y`pDm`4YME zSU@Q?PT?|7LAf9{-hH>qG(_ex9^RX%K6-KTD?6HV=sb%U@VuwgU=e|jci-z5!Jk|= zlIm`MCU_C(IR78SYV(?t`9E(V1kmZDVOgruKj;4!(%?OHx-t zyf1oZ#ZmB%w1_^o1~y2!cB?CYud*XKh2Ps@=ot&n#CN;rLA*J;HmB~~NCvgJXZsh< zMgSJU;AL5%*m!H)E{)#f$^vEt{)rPhQ8x(YW8)ntIF+@&nejF!P#<{tt>*faY*jA` zq~;sleW{F(H=oR+=Nze4;7!lb-yl zZ^~UKDBcRB!BT%GXAk^9V)9@FDZ$fnar(zEp| zVDs{OM7iyWQiGO@#Cr|qI1#XFkibuS(R|qdYl-BoT?>cUr8gBn zIl>uag4MZN@O3MRuY)Cf3tZxyJpWxc9M&L@Bi@}Ia0cn7sU5XbBLckAJ^Rq$Bz6tz zyZo5UXTb&#jZhHRia0}Toqxs{=b*%!vQD1-2Dj~U+xkCy!oyw(_>Tk zH6?nIwf@ZNEJ`$IqN$e@5n{s^_I>c&A zl6A50_BgkX`!>Wo&fn$49Nyx$fGfm%`R)5xC%-w7R<9IK3k{6}C#%Dr9EW&EY|~!! z1`e@Ld<-R}RU<&fWUqU03O3$>h2`8|McF_pH7>09N#(?CY`h;w@Rd#;U_8A2sXnT4 z@>_Y>j!*xA2#}Ht_c&OKkGFuqW5+}0!KC48<@U!5@$s%KsOIfe^k#azeUh5!@}XnU zGZgTA4sTf+yeaqbp?HIUv^7|GYs|jktc7@o#S-69@P6gwx7iEg{l@9@c=0_)((%;_ z-~8bNX@aK{7E)Gk9Xv-HgkbfybJRywx1yRmu3hYRQU`W z?~k?%eVebb0wHRgvyNac@){d&#ZTdvGv_fL-tVbCmf_@=!l_cytDWzs@vJL}Jlj%zBvfUE8e60Jcxi%tuu6i$~!JBep zDvG!3ejRNrynX6DmUKhBBaOCuQt)nmT)r^@;+;|W)zILf18Iom-TMBaSYXClrk(=v zMz-C#Ed}v@MGiNL1rdM@rV<}t!p8fGyF8b)7b|F_#znFsuFYq$@m71=nDgQ_x$_uWoZG!%$3T>qa-^-+$KpTyR{nwjsyU}F$> zVcMD*%)b|uml91R^z+^zp!Ah=VsSHmgA}cly=_6p1oPLRpILPI@LFpBYUrO&?3UBu zO}PXe#k*{?3I`V6gn4{Rogv;P@hwZuA>MgOQXP~7(h+T)$trHHq_>a8ZU!!o2dNs1 ze7WEdyR~#8;nfy0c**Wp;(RR}lo<4$;2y)q`%2c$Oe-mNP=v-U+p|e^CpO+u1+f7Y zA&iIjWvY)boczYl?h4zjB?6SMpT2%&Y8n@B?X~H%D@)zM+sN4zvtRf#NW1zUmHm6% znZ7})IYpljujzG!hpBTjNCg_aDYyEgcwhT8%Z7z_a)H(xe~7o{lFR-Syc6~t$~3?k zq~eTMhxcI@QrpCkvOPyUa6bJkVkyM?JMrpX6$diV?(_@(eK#Bo*<9BA#fd$Gyy<7~ zGOLpf^ity{&dpSQ`xm^`{Tq%18!{f=H>f^VZpO#Ex_4(rwSX@$XqT7BYNq4!mUYSLUzUY2|KubmlP(`gj{=|a`OQ^t zc^bSa@2;SD|I9wif`#{>N7U3wi1!Ccdje(kc4hhI?9C8wO}`vzxqI74;5E;x3lHMJ zC-qP9z7X$QFZT}j+LA%r?6VjbS9tzk=U89gU2MD`oSVuki(~_N)Hp5G`$cWD*prip z*J_KETN!V8tBUI508V~YTQA+_hW)=yL@%j&K0e+=-AwIXwI4+9@O5H^%J?5AMrU0y zkGC0Rdc4o8l+)$o5J5BYDf~F`zx{u-TVvp#u>W60Q-dfkPoXu)ugQ`Rs|K|foM#=V zy>3_{QnAex)}Y6mx1R8WcaZX)LzH$IyOZ8m>S&nN#{-L&inp<_|G#9h@#Y&hGDwj9 z!6{rG29B9`ugm?h3$qb0*8FAbKFSW_sd3F&@5^@H!oEQ|=k_JdIukL5>;D1O$61{G zPTeVX{Lv!>Kr)9sn7ikC1jO5eH_5`zoeYHDh}rj^3@>?r&q%rTMFi48YjJgK!@wVEN;?lm;9@rmHRa`Cl z9QW6uWvO-Sm#+IvkN2L%^!X6p%i$S3ok96PT8Rd4%G-b_-W!x%c(Cx!Db8{if_NW& zDbYj0TUnE}#dmQ3j+i|7M0#qcN9Uq zMYoI2mbt*&Tc^#RN(+aBg!R9ZF4$tP-j1ZHe@wP#2hr5HF9hF5)7{v3C!A+Vy?B-J z`u`!Sj~JZ%`jbu1sig^nBJ&9M=f(J&6V-(*J0#pqK+_@T_ZPp=(f_ZvN?&JV#`Jg- zCfC#D(|tLIDxZ0|mw|I-l;ijjm>H7l|Ee`oK_w+Ca` zK_NA6;pp_LxN7YFe{@a#z0miJhxb;hk3Ts1l^$iEkhm@a{7>rL2=~OtJ0U~oy=7Do zkn?AMJ}HYo_ZC=oP`!fv57YPm*&Ouw5V9j%&Sd`A|D(McL;r+BtU65%qP$;?)}U(* zYeleX5ZmettI}Zqk5v8mU<_-}-KLa@i?Bgj(juO9g5*ZhaJgc#s4E_5Yn+)r2Wyb< z+w~IK%b- z7E~W{IQeZj{WSD|qA)OclqJ{I`WLt1=^jZs(yZ!7n)vQ3V$4U!2ht@YZ0G)JGW`xx zv;}=W#%fgq*WQ>LV%2EyraZ`w;+-BSD2#>o3thsxOAzm)X&K8+Al_FcdI$0$-n~yc z$07yXNh=yck1t=ab}f+YgPr`xm@#Raq5iW+Nbq z8kaj0wzOOY8}Et!dwLI==P?}K#Z(_7IQcyzr}8`v5C+SIe+cf*!N;4+^W%l1r#(oW zLh%`fMEv6|PI)i<=MhgaJ>KO@=<_kO-&aob+#KGjGS~*fYpd`;dciUI_R?jqBa_eMO80Hr_<9jJmV}#>4wM)rTHVev%8;E?-e0 z47P{A?tU4BkGJ%dSD}ulJV?YpNOuey{_z$i7RDG0mR$I=GSHlZ zerh!@C!+(|<|l}pq9;5SHww+9HPd;TAIocJPrK7t}c z_RhaLSG`x$;H}!HnTX@dXJNa?dw55&98?rDYjSQxmVjqrU_#9rPqbm_JkQQ`pE)VOqUo$gKqyZ<-6 zC(ZM8KjW?5>Qj9fJtwBFTG$pZWP>)KVrV6Y< zx2C=WBUpo`*KLb>2bb9I@@XxWxZpxsW@0)N@-rUfD?X}6z()2J z4F}W9EvK7huxk)&+l$7;AWkqwje8Y!XuICOyg{1Uam)VF1;*?DC%*pU<2X)!)h#mV z2C)Bs`DDw68|Mgy=syqE&qEzYvTt%(f%lC>lT*LwI6*o}_~n+W!TdAGg)H>>IB}VS zI)l`v!CP|hgQwo=P&OxWZ9+URLA>+6yft5`>_+1L%)YB_ARg$R`1~Oo;$3xV z*9T*`yybN)`pr)J2(Z)Pfa=&j?EZi2=gj?PuzGt?hCc91}Pze zJ|CTJ+bg;M>Hjro@Ye2$H$?F+bKWhAh4+HtoeGB_-oMVAI7-1g|0zdp0mNIp^3e2x zAUD!ow$_=SaPHl%)Yp3v;$5oMdG97X-r^n{?D%PU1mH7!tJGnIjkgpb>CjhJPQXcx z+v2OfdAS2N-m9V)`5a)t>McU`u@Wag;;x;AeuKi`L)W^lSPp!=Z*EQFuhaD-ooY-? z`?3aqd289%{_7^=DokI!h4bn2q4Bfbq$u*g{vWG%W2ireGe`rP8f09s=`C7=UgWQm z#;QS^vg^EFKE7^v=rFMuz#0_Uq!73ho_T!XahCMH7Y`K0#Wt*lHE5R` z``b-kWFVMX|6Pa}2A*!6_t#-H_6#ztqVc1^A}&xvjngksx%_Ym_6)M%bzx|psRYAq zkOotIT)@dM$?uxC)q2O)%DCb%R#Jk4L z!l6&lg>*YxvWB}R9xVG9S)>Q?_AXRB8nc582D4He(;tU{^A*NfZysXfePC^g`N}R% zkWG!_a0q|;HV+%`+fL(r?t+YmcOccrO`QA?Rx1V5{X$?7Pu;v_Gx$R+d-;h~?y~Mc zU*Kdz*BBi$NSPsD-|)B0k2iUcE+4Yfs;#+S=XQ|vXz(^PZw^E8KF#@T0T$kBQ&mQz z5by2L;?{-`@6e>4tN$N+cOFhv_cjjvP(tP-Ljz?dDMFdD%qc^rWS-|rLW6S%QyLz1F?f z-fOo*-aXp{Qf~_Aj^lT$I70wIj|J{)pGM~$ zJoDOOyqF#MBI6pR?zP_wK7H{6E;ZY(<*thymwqk^Ot~!6Is(8AIiC1$%+-nhQ2(H2k%?v6C5CKT~St* z9548J3!Bn4!~_E9l&Bs|I*iWS!C|}W(Y@^82{O(=)MSdJgU-8)P2v^qBIEJig5=SO z5#PDh``TNB_<^D8{y`H8Ht)omD;67Gc!Q5A%S0@HWAEO^^z}|jonZdw|6^q7%OmW$ zfyBD=bJbguhWCb-BaKwvpG3SDqwy{{qI+l=S_s4_J>*fXShP<~tlym$25n4BNr2Yjoll`YG$d7t#?I=4g49Gt%`x9iGE zY~G`xmz2&FtYrGdiB$!Cc@#)T;8(?y{(Ju)tBGTTUx)p_0Zk1u%@nAo)*y3f32C$% zbivWxJP@uRyBDXk=)xLQ6Y=MHX&JnObk7NcDL;3zRDb2Nh=cLquB*jfHduocG;Yrm z3!s3G8>L-k&j?_j|N1Po8|YK)H_Cyv-!wTv2r`bRsCs%cKl&b|cfASmv8^b>_5VXi z9v&F+)hz8v?UEG$i+{gwx_%0~|1X#qe5m@K6Pb9IQZ%*>dj%=&s{GdG$U~;DL8ol! z%R^r?{!+s~D@c7B-W#1xRa1FicseAB#yg~98*4P=oxDZWVV3u^BQLv$AaCy7ygP6c zZe%Ox{LAN##siy&@3hz86F+J~?Q2O$4-T6^I{qo!jQjdnW$-2SyRNg+}cO}qx3u>HskP3OP zCUIPu<^5>ouHAa@1}VEXnF(EZ{_mx_c#~OrJQzJlvfzZgEm#zmbU@zGR^d-#q6ol5 ze*D2%FLd6dd(x7Nn>c_jGS1_R@t3-Pxk38O<}<(j`WbI~D-y{g7b8BW0WOoDN&EmO zI@%-=gw1=)uU{%TTi1Z%SK(D0Yp_?4^4e7!o5$BNegE&kOJ5$WjlL^nljnE?8s5f> z?{!mo$B0~9fyR4DV4YPV}b^h$`ZMEu=$EA>W?GC=ZZy&po!>VNRU!RKyh98~T zgdp!;BI{Qk$Xn7jE+S|T0mT2@l(57dop%$SjS!x~0iuv`dWqNBm&Kx2@Au0(_QjPm z9`Acd9=#ax-B=;u-`m0ul9OH?+wO?Xdxad~j#=>Jj^OwSu9 zOJ^P_n;#neb2y<(!`tv#*5AvC$w$4Hqw&@piR!rnc{_gi=rqf_ejt3KKHR;vni*XX zjdvyI$l@G7T#EQ0NLA@7pn6}$QTC?NUlT}|Z(0&t2yYh34#&bzkh$N~pf4q%In zTe!?i{$Ln7@45iR!LPB5$GZ~AgNzYh3~&5(t^|It?e*T`4qa^CJ6Udd)mS-zt2=)6 zCm>8U5$8t~E9lqy5eh_dx#!fgMWF4{NmV`Bku>AX~ zW3UGOA#yAP29dzPyRX!Y5B(XWr@Bc?k_Hw6Eo7Yf_0H;foSvxf#oOjvuPzx|%y9jG zE0TvbMtqB_(sj?a2!N)LWu(I^SoN^}-YiS=s=r1!l69^W`AsgOX@jJ`Yuztk#goSx%tOvBrJmHyxBE#>^L%c1f9eeTkk zm5_HsROPQ(-t5H_8MTmip^u1ri*0*G8n*GE>+@?ddC1%MS@kq4dz9`A=p9$PWub69uurIHaI zke^)ZyFG@zf*ft%cVhonAM!ba>VeNm*t~J#;mfp!Rxmwp+zLALs9Rf-6(ltKdW#Va z@6BJLPg1M*z5Xa!G~O;OX{iA6_7y#By8-fEvoObIKjdA$stcF?(4BmBa^A&sLOhT& z6%to~yq#h%Ja_>gP8_IX@2rI%NLL9i`?+frowp3@4VP-Eg+LJ*CmdJmBG-Y=yEwtA zkWG#8c#9)>T*8RY5?|5jP7nZ2qs|K+v|#f#k>}`~PzxbnI$w9*v>*{~rUVPj1=A z33ejm!aZ}6YqimN^IVV*->+#`L^#r|HY%NnKKCQR;vFKefCu^p9|gHK(aTc6-O!sZ;F3 zUEIoOHR$D3D#(Cig2kwpJI>lKllEj!3|a-<8(MT9Oz$+-v8H(^Q)dy zUdnL&{~;ugI~eiZOxSU``+@*Ccm&^5mx3}%PVM%(SvuDsnbGjJHNKrndi4$7Ak}-Tboo^h_?4TSIRkl@hKdNy52S!56|IUdgGAsc{?2&dG&=7WP6OWc zlU%?S8K<4RrFSVSI&Xs}t-#RnB@D;A6Ujp#BfgqIhh*Uo0-(mBMUFoKn|Iv6gEeU; zisbI!_d7`<*u1$~N?9}9nZH5uETk`w=%dAXS2O2$Z>HgGBV0a1-ac#{S?I~-N$$J3UPP;z1Qy7|_bh}f$kPfk3Yzfgtu~v6 zH`n`#;FbJ-^{{+&-koeOn~qmx{b|31Ct^m_j)G~PQ0!|!!M-pAbpGiP~U=uk?whrIjEZ}uC=c#`GR#I%AwlfXcS zp4TGC`+<#v?jhJ9sodGX(>+QAxh=ALOD?1H?mBMbksZwi(vWds3l1d}j-vDa@nC{e9SY4(Q%){B;vErq-{D7MPagSwVd+qgu3xZcMJ#Sod1$}ww+ImUC>iysM|8R`|AMF3FX=;#D;PfME4LTX{ zM;)yOoiy%#w+hyvZlN3P8n6as+qwkz!gr9!yZJVj=ev_P@Ndd8u_1x)2lna6zy_($ zjHN_pAH4r>$HdKJ(*z)H^y5^-A@n^+?(dnx<6YcfDKakEI!WLS{9-cNAE-#km|sQ% zNFG8M@#*=pt~~~?*lE>aHN887U4sG+c8+XP*agVK(h~_C*bP!l&QGC-!S|WI z2E|;ZFOM>rr$eI0=B8LH8s3hk1*}xw6MF4xXuJa)e(D%N-UnRLR%t@sNrRQ6=wGOPjUyl+glUF$l{ z4Xz^NjyB4E@5@Bzt;X73k(kVQyssg7ti_1$j9B33g6#s}!I&@q&=5B7yp^~kS{wF) zTgub(#J^*&AUA)`=oXJwV)_P&S0t0JJj_dF+4cWfL2jYp?I5p}LFJtnTcL`^+vHJF z%r?k7`W}D6EN}AyJxVO(J+?Jvp+5Zn-{w}KE3Td-fE#@MdJp6sF(F^RFq8s{AF6FV z+DHHjgcXZ6xuElwZX0f#@52pbka3Gux88DzN9X;=Nccm|Hpb(<0?FeyMtq%b^wx!x z34qYRv)}pNVDmO=h~0ZyYcJUUi~r`afQS=5WN70<)(i(0sg^ZK27H``45}o(`Gmit7 z$TA-9OeBwc81dykSvfeiLjY`gva0LbZEW6^ORA48RoxA)@QS@T{f>?U(t|%__3zwZ ze%^`nmn|{LNDM%g-81YH8ebaoh2M_vWOnd__VDqlsS`g6r zb}NXrirF8mfc@_6guQSid*4;2Uwiwh(3i)KZ6tk}nE&qo!!g5uu>ZHGsX-o|GTUZr zkOI6xx^Bc7hgO56FIR-$xmTuF%Kl(t9jrlTPfC5ChEuFldB|$jSQoOQs)3O7E)pn~ z_FiyCaD+UleTwD&0l3Bf>SOAX8w9X9nn$2X9DN0;u{CI)*%KaMij3PA6fX9$9({^U z*HPmyy0VPn4oKCJJWgT6SHYcd2iM0BJg*D#<@(Ii!=lsmB)>K9ge2J|BF^2wH*C3n=eR*66?C16=n44m^((rb-jhUiOvD&o{wa|Ejl=L0#khjc{w5{tQ z@A9~y&K7+1S7s5YCr1yk36BH z|4(dOqU2-3{QbW?eR=q`Y^+_rbFO;Z(C~IHbxNc1zMHAJ9*y_*nqgZJ$h+BKeBUf@ z)lI+l&x5?>b7Z3oE#1kk_7)xL<|HtBJ)n^V_W!}G^G=f@C}7pigDmWZL{Lyu{Jg9Q zoi`VeV7qq_4>*gAd$BLW(%}<2ZwXu^$B#dZ*Z*@Mc`V0>FGhyE^VGBexWiRj+{T5? zyZ7saLio~M;NLE%!^{lC$f0`28{ZZZAhq`#cLJPeOJ8`Z+sTmC!$$Liu3;MZaQ z?@UvJ{JiI1oUK8#{eRc!mIY`v2(O(RunDdp9rlhcQinC@_8F0P%i#*r3yog zJIj9neGf7+i+wN15o5UiUl+*(E50N451ysy;DO^$n?JV2*fpr=X6)5YK@+l(=Q)p$ z1udwJ=3il(CzLun9y5In!gY+(l}Dv`Yo+{!xhd9(hPSWOkQkNs4xz-6jk(vCE| zy}xr?P=Ov0<7(m zmxCa0r-h$gW)4z-o^r|KQuy@N$@lCPa*pULNWA;Z0-_x+NJhr3Y^}YpiU*x{slWQ7 zONxxgn-9qYE54&DI*SA0`TsHT>kn7|FL*D`sm{yT-;Bxo*gbvHi|x#RLAsO$eR&vJ zcxFcs=U$L@pyBOxPa~Sjdurz$Ry5u*&nIplhrF-bZcv*&oKRi;>1PS#U9FnDI#zU-y9OwoBS2z}z=qsR-Ik#XBZ z6+RVyM{ke<4u;-X%f@)T=OKCcW5hRl^ikGVcsOzS$mNQtcA+$^+V9LG)_< z3s33j|0THM(q0=fef7o_FQhAv)#o?<{`JqpiQ8y+d*(|Wq4IvNoyvm78@I70rU3HZ z`+DA~S>7*KlXYj$-rjzivZ~^6As<^;&^2!l30w{JCm)Br5AfCQeHlXmTV=lt$4(M} zrR3YqxPQ6ca@Wb+quTR$fjKhnnG%;s`UE=ftJYFu1#cK{dus=h$7PK8o^F#Y8?O)m zM+-|!x^`ppCQm11<@igHb&5}%Ok9fH|LYkPT^vz2VfwWbiVrAFM%tRudju zx7w4H8e1Gf;RmXgO0pl4hc&2-Qx-3DhyrdEEveNQCjyDzZ}6+vpf^a%eCyBQzwv?P z$hbv3>y0CN(N~bG&A$X0UKeM${$CWyV+}@p4S)JQ53}Myzqah)#)b3su*hh1uGA?j zb|iDC+FI-u$F4!RfV?Ft@7tNa2I2a1>B=KB_RRV8e?GC}PQ!b<%9DI5?~soQTxh&4 z<#-H+A#YjBRcW)l-#&GE>;rjs8FhVZwAe;=R2S#Vdr1P9+g3HKguI)QY>d7pz%BL# z*_V9liJ&R}q+8y6bl!qz#{x%g@PUWOIJ|=&S9CQxZ-qSKmwuuvk8KC!k1Rei z*C4sk@DBX?a_;{B+1*?9$`71qyq{g!FgPEsASJlYPt5YZ;{1lw0`lJ8tjrnpZX4NN z_^mceC+z?0zx1j@-ieaC+yLaArkmDWmqi582`T&ad(ays@lz4n0#SS*5*au1yj|jB z7CP@*ncu~VhK$F18IlK9e7$)=gxsG3z`Mlbj@KYI?<0OY7GA{bl4~t*R#oq#9Cylb@pdHpK0a#}(?9}e?nQ}NK;F{V*N!y7 zv$u{l0n(azL?FPC5LP&Z&ij~|Zd)lgAK*vEjVX9q?u$p~?c1{TXxIzJ+ulk<^6Zwf7-q@!kpxT)pI`inA0fBKHgLutp@3Qmm!{+c1fc9-Uy*$z5cTAvy?K3) z?je4lf{dGLSN0@=wD<*SQ;{eQ0>^7RvLZ^0ukw z7C_^z&}AG#guGSqiPvU%pY&NOEC{Dq%9G8_*I(I@zlNpWeei({{9s=kq$b$T(Ni~lAAR8IC&}|J{$#^fx7$L~pY{L#;LCCvOS%Q7%VG39*y4PLJi3pA_ zGiNz^5S{net&%Pa)cOC8%aUBC_^1HAdcSjZ@bi^qJl-Qn9v?8`D`JT>d%=MR>6{Ca zeKoLo;~t3BNPk*QcI&&g)tHlx>Me3qbD8{o=C9tm^yN|aD)i^X-MRkXlZN-sXg^nK z^`^)Zc+hw|?~+cbg}f~i?{v)aKB2p(Fah$`_HvONaJ45F8eWVqcuxY~G8fI0hP*G` z^k#R3XK#n*Uv#p8@Bb^=fO~@b&<`hm=k&UIE#U{Nka6l!;{qJQUZ`tK!P6I(dyg{S z_SR1%k3|^q^=P_Qy>7>Y-Yl7?6~frOA06N4CVSnHY(WuL4Jv6y{d1uf>CL0ue^QP# zFn#|o9#3B$Dus&;jpF`0|EK=_GxU#eiVdQvLHkvH&V6Ec_5>-dNl_H71~nXGRURdm z=?&KY@>v6GP))+slP6&R?_J%?r_gCb-rVnNs0_E*N7q#DyaXF0e*1OpR>>65KT$4q z@i_t5L@bNcZ9wn;H*dTWH#Er)ERk^yo+^vwZ=+AKIjgqLFECxfaQ**ABoD0kt}1!S zINid7ubCR_AHJV~yk#XK^zVz04lmls#zr~r6-g0~_5f5H3K8q;0onsmJX|HFM;dJXeW zv8O~l=*okurinY|%-jkxfQI*;4?Rn$D@Y~JP9ZejGfe@P#365DW3hrV^DVMDnf+zGz|k6(p{h&OAo#%-8<&{=YvB@9^^n=kEWXt=|0|d5h3^ zxA+!{u7kY&&b~f2%lqsTSM6rVyJk(Bg}^;q@+HpG?|!@{f!K(YHC>SR!~>^%tz#4* zo!4w)oJas&0TX-997125tc;yfkFVwj&yjI&I4<5?yaS!LsJ0z`J3r&`mPPVdj1k|& zVR@$?^Y9?(cMBWaNo?N1GMabnI!wvFYMrSz7IgIgo4ay%PFXU4|4*hbkD@wJ=a`DQ z>g`9vJ1q9x5Vd++D})H5@fP}$t!DvwFK~Q6Jj)yZ+;iC%$h(d6H2=HRc4UX*W4;^V z*;`(;*;GH|Z9F}#EOnFu(l?H-sVX7>vz+hlH?N@c?tI2JEM5Y?hlh;I<+>JC7>dsO zxVQfT8yw^DZbR}&!iX<6Po(>^9UidYo;W*`uzB|%)sOJ0(kF*xwrtH=jJ-HXY|MYU zdL{FJoT&c{eR&LOCb$j3`zQZ<|DT~d|9^sm{r@hS8WgQ!u1u{#?IcBUv>LR+V_Jy_ z`~O{~x_gvh4XOk}cW=WQWN8w0K;OffY)~0;f**bZ@?2u>vS3()9;{m!rgD-3NY7Vr zj9ef9nMUcTjNRxp=uq_w+x;#AKoS|ZZ)B(P`se61Xz`*G3ac+LUJZ&v^1zDkd#ed$ zdK(@r5UISNj%U-ulJjwj+tzr*pG(|kj$0LK& zNeYCy{y&(8cN9LglFEDcnt5Vqyyav4&Za`%(vG=Zv%FpJ2L)Y&ywy)H;<}J$P5vXb z)_5eB1l*#JcaK9UDFMtn=;4AmB$5CC%FFE8*dz~0>HmXJf| z{dCgk;!8CF0FZH+&9!P9Q_*>63^)%t#4sN3CrBQc@pWxaFzylnZHK;QicDayAl+n~ zv~HCfljl8mKBuIJ&AZO!n~IQvz>?w5le)aMk?;SL}2{)X_sl16Qxl7P^ z!?*3-??K+r*lwPlU$>S?bbN0v0B51eAg)SVPqu<_$}qOjEB5$B}jSXo}d7Z z14dWu%n5)k_15Xb|H3;rwyjb|LIAKJ<9y@aiCv9D=N-8r(1a(L@pxw;c@Qz;yYu<> zs(X@nklK24{nRIH-epD$JSTzA zHM|_`n16B7PhTDhCTmVDxcOiIPwl-J`bXIRhtt#`lA+h!_y1p*3V6Fe zI_sk!5foq6vHQ9N{Smw7iv?nX*9AZ!GVT{=uD3b?{TZbDHSw3(elT7QdWhsvhY?@R z@_Xy}hyuVhWUob^Ep~&{Eb@Lh_K*jtuGtmL&5M2hkIM*XXpw7V{u)$IUmgL9EyjY^ z=2nnlG`!uZb$f6}*~Ua%RP_sQTz&nHjWfbTu|q3;A9VXh!M z?80ub%os5J3R09vUmg>s!uRV*bK6^?G`wT$-u~Uaef6PQ0*$vUpG56i$XoJvjQ%Rf zyO!rEaDlulxicFYhONkFM%8MEi6n4mY+;i;weC^|1w1s;upny_K&|Ro&W3+^ zyruWT??S&6c%w2hZp2-6-3l`L3KDnuzNL02sX1upug3JeUGLGChr55Arr{lPo$o8Pdb_G;uR!D7 z;YP%pLEe3P{#=^nJ>zJTm;ia-mp}PNeW5jZWynF@oACYXrxIpmCXjd2yWY)r(rzOpE|ng^b%`BQNo;44rrHLPCyi1LN@yM)G)v5#P41 z$rbY(1;EVL6N}q)v3Xmp7gPIlzy_!{R$ly?QIA=@aZ)`C7bUJ`dfqrWI`cT`s*Lpi zAvC-Xcydipd8dguEJx$rr{uMwC%oDhpyy1y3kW=pl{?N_uWmp%%~$T>^` z>Lus*xI^AcIvyU7Jw*ZGqCAVrJ`jMN+mbBjQuM{i)M8uSMd1R#3K^&V!amiM4SjK9 zZ1+aX;11*Q{*L5<72k)7fn8GYa6(f}LHe*HHtzva_2zZAwvwA`k4X|f&~d$G#-B%j zV*d|(dn=p1Jl6VNcF;QgU;oe0eLpogIK@WL)Sx56)$-IDRJj4a60HVJMkSp+bhk|J z4og*l0<1xk(;Gi_TvpY)kSfqIB4JIoSlo0`(w+qR95uIXhW&q?x}Qn+1qz6;<#A&> zOaSTX4~{Isqt_sNt*z>~}TLYtSX9z+VRH5@c#xjPj!AcBf5;m8@({Ztyf+rk zfsprp8s3M0Z8`Usci|U#G~O-SzpCa#-dDv#+h%#M%p)xAfxJV;UbHOWu_pVToay=Q zL;_-4ANIII-WwFpvqu(CfCTBPzr6XB}v;{oZOuc6wR zcbT3yZh+1_4*aS?R*?H>cptjo_xA+J?PRqa8gGsO>ra)C_chk*S}P&%YW0fN&ye?K zuUr}52`jRL#JwA7@cVxb?WJjvkau;hY{A8I6!3BXmEyN=2w=zA!F81c^y>Xfw!E*p zM*#RC;}UIaCf3-X^R}I;sSy%mJl<1C9$4}9iY?2{mJ|Si-JV%u2e5hHPgF2{wcigs zs-Qg7;G^UIzu4liy-gdLzd<@oUmgNuUfGFP=c@N!8r}&<4yRD7_q>$}vS_@G+-d^b zAa9vm+4Hl!OS)WSenQ@R60={az};JRkJ@}Se-hX-xaxd9#1B0Vyp%yI-~w zz{ca`Sg9~{-r`|--PfK900U&4q30gadVtPbhHFuosvzU>UWVj>6<_%gd8vI|2t1C+(Fg6l8Z!X=c3ua9MU=uQK;m7U8zFO$KPo;K> z4s$XdZw@4nlNj;c6**b-zD5AB3FD*I24eGGE;X#a`#}JxKl(J!oBsj!_Lf$oQ}B&- z%)dCvqce{ep3!Rm-T%iZE$F|;0c%h+O$|zsB#TpPQ0@+XWwaVpEA`!o3)Y~r_oH@l zum(|f9@Tb%caVf_2;1i0U`77aWNVSMh6G|tcdhQ=A0gw#<>rN!!3U(jh*z1x1JbH5 zlkXBPpx2*Z+YAX_XCqd7N8tS^1ww?4oFRC-t5_ zLFHXJ(7hUsH>GFZNomMiMNQ@2EN}OwJL1bAZv%_9yf&|_$nT$w5!Ba_z;oG2nJ8P!paYxtr z34M8dFVGM9cyVq88A-$Ycp*iD%DYy(Knaca(Z+%F4Ul(4s?I8T$h&T-@wM3(q!%ki zef9rlMLumRIy|_61gdJe5066Lzs##^av|^4+I(l#+lXMFpZ1G0|MLAm-qePDQBruY z8yV;Rdhw7eKRRzwAth5yXU5~rjpQMM5#QcY$MmnULcrx}*iP{pY~Gz^de5)s*?^A6 z_Z+@VwW9vBr%v6D^M8J`t*0=3gJiytzC5~;ImGSi=00ypq~U!mW}=76+bAt!6&mmR z_*>%kkoSQK!?ao6=X(%PZ50C}6k7 zXXVm+1hC6O=a#zx`r_p29d{QCK0F9O#%WS z^o}AHQh-%kRf}{T0i--lxSwW<&iit6w#_z9JUEPubNlQ*;NgSLTdDB?rNNN#c$Xr1 ztj36MrYNhio^XKgK&J&7-M7=?WzesWqs16W2Pl8YB@?_x)H6e8n!Fq9Fro zkYmgp1I2PxJ&l;arw`=K$?G-dFX~nz0nLNABDCQOQgA$9TH+Q3L|u~Tygvg^kQ!}v z&bLLcL2iEjM_LQwd*pfvjO_;oclGI=J!&WMpbi-~Q}Fc1a&`0uDe<7BsQf*~ z<6VX1aR?*6nJY`oJRZUGe^;rzFACVaj~rjU%@jBQJuCS&tN5BQ8zkJQrpCv@KIZ4W zQj4xU%rDI-v=+|x|4A$~yiZ;y{C$Fy^-sPk8t=V%b}eMcJ8YdCUKaA+r8KZU4f1aP z8k6|R!IGT$yH8Jk6?}s9Mf`(k$h%9feXysT0uE>`aPiwm1n%qjKFGXA=l$&W(}n8} z;DG}&F0~}9>%AyC@Aa<_?D=?^@pyM2d8lE;C$gF-xHiglZM~e#!e-FGt8uG@`@J=NNI_d}A zDFT4AKexkCw|WJ5 z{%^K=Z6)L#R!4HszCr;4;!pP93nqf622X-dy+P-_)2J+u*8>k8A>$OqiWiGbqp!VF zxiz#Or!pSz?MNOe81Y?bs5qW2f(KazHHASqY~HFPW!%C>RzTR4$4;Xhd+lBRjlNTccoOoDr(v^oGD^c$by!-9H{vWH0V}M_WQ!EEf4a${I_%>UER>JrHmqfea&}z`z z8$acEVGY{BEx1ey)}R<~O;s^C#a8cF)YYM6OkQ(B`eNEj5>Qf}-c-vsLgpa-Rv5cW z0re}sm<_fOz~$_P<|b_DHHhcsyL}BG@Zb_ME^Na~6Bj=8DRyS_86aD`} z;6(DkiZ3x(>}=6`0r2Hv>r4Cn*fl6nAaTgL%$96@Qn~- z6W#0Q^=1n?Z=HzTvA#cyH^qKN^1zC3`iCRC#Si$!tN@Ef4?k?)3m<-1qdH>`v^*|t zBxp5Z_y2-Z4xuM-OuvG}anhFug=4M#m)mpw{{kA`S?5Lnz922GnW>4!J3-@&tUlyT zyzTmJmiL|2<4PwX@8}8l=IT2e$x_d^jcLRF|Kxb)+YgX;j*U{q>1qn#-!zjwwt)zK z=Wkp1;vhQjpZlLyZ*9SYZ^*a~!C#>tRnd9Rh&lPLn_xWN6G$F7@qdrcYysy%$2tLU z?RL8BZ+mRse=0M{wUurlw{M=E`BiM*X%^ca{fgYf^t@&D=*#1WQ&f=Wp}GE_jfQt- zz#BJe_4X<8&_LsTZNeqQ3Gx;`yuwo&^1hrc+cmp;>to(_{*2=$GSR!M&J^z6#`LT0 z`U82B8y4=GsiJ_jKIb(86^LLe&8YNkC_3+G;=VqIdOR3M#@S1Km;Aa6o%hf6+k~Ts z7>_pr$zuv5zJpO0GPnKV2Qdx)&&{@A^FD1P;hFo;4OCq|{wT1Np8j9t2YX5=)ANpb zOJ5!fY*bh!|2dqPPs2OIyy_5@_xkT^)}!&huA_A|4Dy!js%)9%?YXx7yazmcQ+ukR zy=;>i`PvFH&ym$6@Q5s5E(-hq*NLpF?QX-@TSVj}{56Sy{k&Q5szh|&mahWV3Dw{M z4jC8uUVPYL2|Dl3Q)1hRpBRt#W+V@+_@)hH4=vg(04kpYqZ&hO-s@@x_I*3%2fkW} zO`7Y_!Fwi)&DeHYl)Cyd|R7Aibd;QZD`bPBx&Sq@w=IW5O{ z{l5;92UdL9S4(d`3KRgzW6j^>PGQ#|ccCHog+=aUPKi?zr_-_T|4Y7kJotG{EYtV@ zIaT!Kp}2LDt@_H`3X+?KcYag(M=I~}1CnfLy!T#>Jb4N7PEoTCl7PI&)n>}xLf)39 zd{WL8`eX~z=YxktNnl&hWKRy{?XZ(vX9jtz>TIbRT|op|4U*nU|MCQBqvBG~i4z2> z$hh@YMG30{(0M=5lnowQ!FasyBY9xO7gERX)04*!xH1~E1yitjCvIyRIDEmKEKq06 zq27o61Szh5@@?VDqfE~mcbUFCTsGHsj?~We|6DY@&*Z$Rq4IwAVq_i~?|2q>o;t|e zYK{E!S>Cnw5qqWJ3DWSNpe#2p1G3e*-P)dFB#^m|JM0|fZJ%NM?sY8%@YvfczL-x0 zMFBUevhw{j`t@wPznz=|(|*YnxgAOR5l zL?-lMA~tWw;SbX#BM#*4mJMeNq?<6exBgt`T@i4Th3OllV}5HUQGUB{_4$3 zUmnY(H-9^RZmxQB((uk(Yx#xBJEuR11&z1ShL5!qkoWr69am;~+uyO#8Hc>npLaW~ zl{F%_#+0QG!SjEoidfl7$lF49^|L)>3h>-t{yUqU2u^PsTYYRjI`2x+V@1cm;Xx)c zF7=bUDT^jL?}$afwO5q!cvm2K?8k`jli}um&0VCx5V%)gs%OTki!wwqm57 z0tOm&qSM|G!ARR(sn}QOHR$sf;w{S@K`?-f>+`eUTrcH=I+Z-jd3$T?6~?PU)I7Q{ z;;Y?wSv0AaAKcJCUi`Khy9Swk{=Dt*9|ge2a%y=B9arr9D(-pvL*xe2*Pw?a`ts1g z*SZ+OJ4hjK0UF*HD-R!_^7d5|;X>mr^F{TT9OTV^$IWm#ck>uQf&D)Aw;|SMA1(3H${D~~* z1Jr-^e{1Z7&gs3!?l3)XTnC+be5+EC{O9o&ej45vjy__i@-||9$BD*!kqmdW{%rMr z&|ERgdm{VZ%Qm>ZHEFqb$<%gT@*=6XGV$yraLagkS0d!i8Mk;Zv5o@d^2J`+Cqx2& z^QoYt>FC#6#Iz4O=_CpQPh=e4C&q;8IP{J`?? zR*k+J*t}=g0Vml*N0VDH}Ib_nc}DAQ&7{vQ`iUmo}!eu9fm&Q)(d8r}t4 zS8Sm2zW=C%1C6)a@l}tUA@Ayr3aQz{i3Q(s3t}N}HRYAtHL~@{l51|PtKo;26Q>e( zoq)W5KR&x?3hv&Xa;{LyKN$%IYIL~Di_m%7?i&uOj1vSOka0e4IQtrZbl$J8EDsCG zVLaYeNFF^H@rm3tc=NbK0IdI%efZBsY~E%44r&@F?8zLydk_8Kz`ng@Rd8#fdi5yN zACUgpM_(SpUqzod`pj)_@zU@gs#9>_b&eSZoq@2a8h3dbBh za<7&3#%jphapRTPBapYXlmbT(tloK+Y5w`?MDR#c_-J}L`r?G&{mr$5f`Xs{8FzWG zFu9eC-v9G%S~1M8!g#!SkUaP>;;Rox98t>W2Y!pq`-{$C^L}Srl<_6ap8RBzJi4m9 z343w!%;0-Z$b9BsoV=qi4}8Bo-X!q9^Z&n#Q%3#?Y>-4~YEaoA-z2pL8L;T%(Q449 z6IoqH@4zoe?-DIo2B%n)Pn)l;gOAwh@7^cf;{C* zUmlCQ@0u++GB?Ev)9@~RldMPO{kBv_0FC#`EpOLeguJ8PY!?!Pyj33eeHDegQ(7v6 z)S4v8PfV;g4}XmVJ}t6>&5-v(=XUl23I&|gj;N^4fG0>iIKD6fI`6MgRegoqTPr@~Up`^JlDr&jG`~L<2LzS+21g<9cCkC9DlPB}(lcf0 zGw|yzer#u|oI=ofb6k1uw#Zlzcq8NP6|21Q3`6Igt&%fj>BM-v7b1D&V8rLsNGa2D zga@P>v+PYiV)MR!_Sd2^O;6y~`uMKhPVDWi&D*4oi7M7JJ#TkM`tn%zsZrGQ)Lj3+ zh=zBun|2tLx9_oXUNqhb)6xwuAn$7if#b8h#}^p4kRfjkj*_Xd(<)>u4&_arqj8`o zWa(}}*dSRH^i9uirhslghx6lE1R%R`QbX$yI&Z62W>M=61c4+n?#!5_GdUEU_bTxp zmIoaekGBnyhZ077wv;e?7T6$lmwY&OxEGuEK_cZEVVx&$m&uSniw zdfqq#I`i0VR3iP)?yVpV?;^P$WmMiTx9;OXRr8i2^wU!5WfAnaP95lv?JRT@?P~?=Rjct1#t7ki$`)rg4RnGahdiBoAqf_1#gn|E2Z(e=3H z_Q3OWi1P|gI-dW3A9}X=nHlr<|5xeDV_rbk>Vp~o_5Xhtr;Pj)xPn|pQ-dlxpFg42 zpa!?KqG&aUOHaCj4c4H-vM)YMU=2FQy`*mgY>+&j@&^9!kOV%W#XIeVNkAg#-uPXf z5wcNv_L$2X3gBDOMtYGE2?E6GzikLauR)dZSC>A1BM5wvaV<0QbqBto*PvTI!jDBi zFCX)P*m4qgcnG~TYB_Pxs??+BLa&RO2Qq{u(|kT=dO z>Pc*>FkoNLVlc{00xbjiQUj28Mu?thX*UIYxA>xVo)ii6xUR+R_?HXP&D7%ZihBfs zE;25Sr$agPEjn)z)qYQY2IOslUqrqVI8GG~Nqh z8kVa=-kW}Ns4RuN?{6R8vT>F-`vu}Ds~@_#ODf5qS>Wp}*Lrs^g#AB0!%?~9B?XLK z895w&H4?})^ocDdp;zzL#fcKxe*}RPGR}yHC+Nd3bl#a953+{Yq{xi+*Yg<3BMT$G zoQutOemL=i`I{ZxEoZP-kSByPqR&9y@rQ##P6cE0##!~~-6{=YdfqrY`tksGiC&vp zGG}=&rr~{6GuD>M8>g4K2#t4Aj*gTA$h%x~ zo%iavZ{<84jJG)HqvnAT-)o}Z@Ha&PkehshCGQtDZ=)5F+V>0h0-$?d@3dDlX7%PK zbsKNLQOooVlJs%<@>m|dXDL2*?r=hshWC|#)C4MT9mQxtG~Rv#Z@=z_ym2aL)n?D$ zsJw9x<6X1TxX5xI263~z_Z$ zPg85qM?pn#v>G%|a`o<*sxrOPt4C!;VGSB?Y;H?{Q!IzY@uhkE8vv`|u9Gb$B+#8m zte1ifl9XDq_*6dykaXBS4?HITlFMSdti$LvC@N3eJUB`a97M+b?C;tsycB(k71+M~ z)UP=M66N}!)}naa9YY(>Hg5weS9=y>Ld0ElC0OVamoFw zn7;oH;G!=N{u^Fu3*a3jkoO82-j#(jLR8*2KTIw|<1KrppeY;jwm-v?ImHFQ?DS}`K8FzQIa2MZp^y*E1tE2xugYkG%^T3Ml>>t^th(2Dh zZz+M}fgm<-!{3@=MKeJ__GEjwcNKPngxloizxMMprmx;Hru60ULD7H5WM#@MZ*dyl zH_gxdeK@g}J#z_K^-er2#L)(MFWG%2W-;VltK-*V2YDZ6+qd$#k1BZ6bvAUqGQ7Q2 zcf~b-$h+vmmDdd)D1fuHcJS76BDf$@={nMjUcIkeSB!AmCkP6Vaqn)HPOp|h=bdhN zXv8m;@pxZF^1zC(m-Wl3P49pf8W6^N&~iB+o5Q#AtZm5Dhs(U7RG|-o6-(cMboh{a+yOIP>@8v%KrQhA(JA z-d1le9oZHo55907xifp7kX%QGSGxS#^f#$E~-Y>H~%|A7d~*OV4kT|}?mQ#$j9 z#oq~ntH?NZ5ntD=9CY41lPcr-{fx)^7m^27d>WfLl^$sEgL5|t^M?emdHesq{P@)_ zZ!o01W$T1W1NP!1c(al1{Qm=slL9*P_-OiMDSW);zx)6Gr-qxs{y#Xy%F@&za=qw6 zY7Hv$lafZOLGy;@Y5l%kruT5G=CBZ~LGtamS0k_ni7q)Zm@Kdn+)OCC-sI7pPqBKw?n8CT z+)O{k;1RGtJ{O3_L9I@(ve+XAa9*})oVNkDIn*=rRzWOk>LGO_xB+;(0N~a z^di=+Ul6=Q#)+5nmfvJU=ban?LUTSc9`7O~k0gxvey^No^H7i%j5_7Ib1cW^ZD*IW zU(;NYY!XnTIwp(F8~4h0PxyyG=I8C_Nmm|07dY-6-V!?7AW75kuKBI~jLKVLOc9m0 z|CUVzCCK}zr^WqQ-iq;?lB*zZhg}Qyw&WTBp60;uBIuexgk;>}7q4Sn|ky)3{x(HlF#+_K0oc~=8oj2#R%-bq6jK^CZ$%6wUK9XhE z<vD18F*zVwaobH^S4xDFTwZ#O4_ z>-VlKSPXev2?$4?`%D2>hUz1&TO&c~gPb)≈e?NKFN*MhyspB4ixpZIz&oGdgb$ zt*^o4&y2@g8p#7Iz8_sa8Mz#MAZC$o)FyFk-o_=#sXgf$!0ikGD+w*eyrn{iL%@)erK%UTk}lmUl|uld65; z0F-NQY@OvjI&ovEFyzfSZ<%KsEhZDv~9`P9Qh4`@zQP}yxn0Fd^-T&h3ZSuOyfkIa7>n+@xR;r|N zC^LQa*4|5B9$%&Uiw5A=TmI|+8LZd;pTdDFNJW|&^x#uMDRqjyrn_V%S`C^GM z{(m^`W}P6MVntcClB(epYqdLUKqJ-~yb$3$`KN*e!i#dd0%3#H)*}#ZHbDVLMTmUM z9z=p4PkOq)yP!|8Q%35dQ}7Wx>Nu$r23BQf(5KjpkJ?vr?lImJ`xD6{3nRWiM{NsY z!uWuxj9XaxBJ3$P*CD@C(ZC)Eg(z%#t%O~Jx^KJ1g%&ga1?e;O-gM=Wx+OrTDShq{ zyOlJ&>no(psJxy12ISFrr(ey}OoP0o^av`8AaB?0tn6)&_t&nQHPPl)K=1QMwkvQ3 zFP1(e9s_x|SY^r%ex-o(!?!_m2N9Gy4aWgb^eNV0DpTNbi{RgJ0%zUt#Pgx^zG7O{ zu&IIZcvJJZiV!?4!00$^F`l z1LxV%c{jxrUjOxo@pyY9c{F3hCzvE$^A7NW3C{bU$s*X*`&YeiMY5VbuuVQvVR*eB zbyxfEgdIMacUJKKv3IBORBdtNz>jg8heJXoNugAxkYb54L`X76nL>&*nM24tSCk}$ z2uUg-r%|Yo4269!q~Kt^DT&X;~`X_fPbeqP)G`!j@z44iPmpsV7fPmKXDqHz!6%Z+h-?M^%`7(!b)(zN`lUul{~v(tj+(%#s-S+%6T^LNl6?@CG@c>Vhn(YXHP4PId7Rg#uM!_!;&Q^(#p7Of`L z${gtUE!Tk0ThgjsveS?8d0SY}l*bl1UGeIFE+>|u;(d3Vl% zSf8)zL#iGVHt)9TefpX`LV%aju5afUm+vNQ-V4@E4+_1cKi(abJn;JGQFN^_SeYN} zDZj#EB#mFar4_g535O^E|NIy`iyVC3tS<*wM=YITc;4}z{WRr~)85UV?f>8U|L^Ec z&p*KRzXDYadQvr1fex`Z-ta15)gYb?4+MTzmS}$fi_!#P4Qfo!t80UIkocXsdu{1r zE8rfv(<0<%1ZaN$u6%-fgj9KEP$6}u33z?l-JL`V1oeaV&yj!m21!&~ayKhU2t1** zTPoqnv2`tW4VrpcAKOw+e>EtQk_TS@W*#59-loe3POaz)TSmh>NOGH=w1>FwBt`!e z*9mH*;fkHrF{=WCI2gVL5l%ku;>Vp*;E0&o3n0%_(Vn^pCL z!06{ACfgdZ7f7J0?$noiLf|{4-LH^4m%sXB^Nt#5zMg%P{&;Iq@;HIhzlbbN>lH=3 z;Q2({%`MFMLu}N~-ErYPioog0@X04E_#335OV^GK_NOvD@6a+8n)2ZNtSH;+^k@CQ znu>RW^-3v}w?R$GDlFb_JU{$e1$l4Y&wPl?+won(Gd;+Af7|(erF|B_`HGnO>Z%BE z;8~-N2;_aObf!P>M-#YnV5NVUUJw{RWD;ue6r1;%4GKaAbwc0=rQPIwnY~p9uzA0V zu{z#UO@F*IDS33^^zU70dQi_oK5)fz`v?aYKJOhZ_YA{4O#pF7bKX6ZI@|@)=cM68 z)|OF*=Pe*bTOLL6;|nfa`@?$`74Lfempv%&`(feoSiBFg%vl>i-XL7&6PdS#ahS(> z$lH1(w%yKqJLporn2}r)0p9W18LfuA_b)6wGdtA;LJhC_KC=k|W1jK{Q{Q9rW){+~ z&1;0!o6>IidattFL)g4cPqvrI(Bb9;6D1Eboc=95et3CJIv;pZ&CFcFjnCWOJf_t? z*#y+cJ^JM?{0Nsf;m5)K#onO|fB!#W;4p1@C{=S)9&gE0@vfV?c?9Jx`oeT27VkNC zt>3#L?^>pE3-aFE^aXeCV#s@P;8Dwt7<1s&p8Go;PEL+$&D_$1yude zC)|gEK+w5GBC7v#drQE_Q%58lgg^+ToyLl1X&fYM-uX+*`YP|zU-kB<=EqP%Yj<-Cs`#K&h$ne#hVCFzm9vKsbv1Rb= z_ka8U^t|w=^bM~6*HYD>=jHN$U$N`{&8CV~gO+qZtrQXMR|N`m2Xt`N8%7 za*Zu7S`zJm`13t64R8nP=inl)+i?BwaJ*@u;qN98E?%!4tsVqqk8)>ZU&bC{%fH!j zMArxbc}hFm3$JcytB+)Azn|I;CBN`!)_Z+32_^Vf`&%?2K8#it~yP}x>co$IeFv97d z;c!a%f}>HptUvjN;dv8`Y0IP1;~U5C zOMezf%2d3Y?YQPp-hA%om9cp91)0hfldJcGyo~~o_cGsUzDUShFM7q3#Md@p!&l^n z-_-~psC*-&9`Y8*HGXOid51rj3%2120+q+kM427K=52V|T+Q~55U8fK8~Uz2uI-1- z+x?elhF~fE@z$s0f!DwC4fzN87V(3<-C^<_-|>0Z&1B!mEaV4cVRp02^_}et$5+6?v@Jr<2_EvLjk9M3NbIk_8jB|;`VVIBNO<%2}e$) zmRECwJrCwT$quf=UH^whq-FUjr7`^aKa`oaJRXMGrcT2Tq{F$lA{FnaQ?iaI@8uUZ zC}Q#6v|w_)7xM1y5s)J9y#cAx;S$JO@?6^^4rXicH0X>J$BhVZzU<4-uaI{};z@O$ z*(R{=t!&iD+dyz|u~@&X6*lkrVWBHa?h1h;ly;ZzAMx2}hRs`7twwmqb^7BiLdio1 zr+*T}=5hO1yx_#}LSvV4eBK88IZ1i}J4s%h6ZKE_Kf>odGbWWY@tfg!2Q8;9kARYQ zlU{lMt^e`XaCGtaum)*R)u7HM(N=N|S_yBEI`hndfK`L`2Hv{=<5r2bgud}QURZ-F zZd?!`z)$Q}z3tIq`{e+}veCJ!x|*CGetB8 z`-+{!VP_Jvkq|gcX=e~wCO;>HU4ukJ!8SJy`l~^)lsx9+^sn<|d0<8hH>mvb&hN(q z{2Fw*Wd2TXX9sYWH>fDT3V(x?(5RO;cq@bP7f9c9Y04vMSA&9T;-4XQ9To46bvBVs8eTL+uf&@QU3E?>jz+ov?X7yWXF10Dj)`CZ!!O-@(UDQ`oQASu=+_9o|TP zyc;Na;Pubo^m$H=^*lhym9*?a13qu%$j<~W8wWttM5cGy;`0vmeX{NPN&>?#kO&zK zH02TA;#(Fl;7^`Gs#Ec9k2xxW@_y6#avc`$>CGEdRzTjw@^)@M$a_8_^EL|d4o%G6 z@rvjGxcALlcQ-QveEt%wZ4G(v%v-g>nyne!PuR>NKOP7+7Z-fqM@_}$b;8onUqnRI^#+XqV! zvKe`JY|m5N86-h3Okns^FXQv3F%Ra(GrDG*63M*PsCc(6mfwT&EY@=+HK}~ zkoVZew~=JtNw(^(1CV$AlMrvUkexu0RO;ji&tGRWdoUk{ymhU=J&k2)2J4c(J?AY7 z1VN8%K=?vz-e)f*^|n|Efn$_*r5XZ8w+yj)?@2j+_qZYb@y?*+f!Dtig=eSqW%$83 z`voJ9xA@iDt5q+vkz@p}^BPB0{>I;&s41y5R~=|zc-~)%Y0JYsh4{2T@XzBdRVv=C zBuegL^FF%uc>f+c ze0uwWk_TS@TF;zwWFF!L8+h6eRD8hay*xG1ttH(EL~Jx!n3vmtU%fL{R~=G!VEnmv zIBj_dq}4C4h5r8A|EG%;{=atu4zYl$2E9&B+Cr{DXFh*%7E;_sXVls9OI#>HU#*df&hFB&_9$7g3``q&@N<@|$ z*gx@Ac~pvDgP7Y_Ie%E}0ls*yyZ-Vx{t!z@etuETP>$h;SV9kNc{FM5j_Zy5v;Nnj z;@#usEsye6Nt0s3;{D+L*8CL6dtqUPKbdz&d7)1zE*efqWP z(<8`RNI4_<5MMLMeId~B>laktz~@ao=oHu4<3QnQ?jnZ!=h4dNlU&SOB=n_p$cHX6(mXtZqD# z3pNRXa!NbWB1d6kL2TaF`;QDJD9|5o0-6U-{{p%XO%FtKgS>?cRBZnbyz9?%o$8Ip zpFvLkC~xd;E@61yFSlQ(DG!^`;j|yKDP-OosCd7ci48}24?G|-WAXl+)aFnJdEZ%b z#*PQ_u1QtUDuKLT7KA;5F zWu1CKz~;@F9Hir?E(Bgt+P%CQubSG0{q%OswXpmBa{A-VM#?;8*XDOZaVfbT|Y3Qu{$yH5#tBxVz=xt6zDHzd-7xF^}r`jVu0nIdMG|@0T43 zuTkDiC*zo~cu%Z+WBwNMj^6pak<5GCR$yKWU{4#{mKKLVz%0&J`RyJy?@j4%W%4!)0ai*oSskt6WDV@4}1K{*8zht-t@#F>rXKh_})3Eo(&7rCOmFED6Ql2{4_lt(ji56YyrSdWi&pUL@ zMw;>vYszpM{%`&N@9S=Q`CB-|ZlbC|?_+^6O~MEh5L&3g`5 zgUa9h+(?5q4#m&ks zT(CwX9Hr6tLu_%l_@3{Qmf)P*38gbC_%letTeHPll0O)}1`(QQ%Y!(}%QX7W0cl+- z-tSz`ile-vkBV|*@iq&%l_Lm;*vH?NY~zHy`?Uu0>mcs{|JbDmavi`?(KB6K@Oq1h zy@jl{kayP&{-R~`nt|R5pF;&sf#5aE+ANJ**t}1iTCFMkiwNFQ+Hp4D*v#pL&3o-- zi;1bv^v64jl7|XT{~E*%*Cs^qfLqGGUT2QYo*CDX$42(XZCZnZb$Egdfc+J&0IEVn1KJ)A+7MqZ3px`xera6*ht zUPuUBqqN(*^7Q@+cWmC?8$Ghqe$gNAFO)p+`lmV6V9WWP3v65>_L}K5KJPCzM+l>3 z4xntDy>I1KeBOk-OJ(2QCNey4!bRHh80O1d^K*LwnfFF2-n|na{w|Pa%5QRD@h&!Z z`mhP|<~!oJh70oMYm+Nk3>Qe!S{KyqL>$5C!L+H|US;)`raUs0=8eDq z=l(x!D&B8;t?r@KdwpdDg2g*spU=Yq^6nnv&L;DAW?uf<1@c}Vk#zmcE=Ry`X`MY@ z5CIUs6F<*G-aiE9K0gy^1_9m$laZS6?kxlBOx|>C-f1tVOrI}+cW+VJiDZ`C&DO)_ zZGUamyfK9S*8fSAJn;G#FT#IwPct`2mX8xnzJ$;Fu9e8j*pF5qQ%rpGw8kS`-h|>b zjm~t&znqBhiN-t%m;&d+$6NpH|D&rwI{p(5v4&JNXyBx`3R;7T)%1y2HR#sD!r?%; z{!e!9t7nHbC|m2ry*N07tnCOM>gU}Fy5|Y{Jc3v3Snd!gQ-C$-nnqV-_55bAWS97N zLzh61u(E9QSQ&N=dhQeZl-N!L$&_|q-gakij>E1&`66mx&(_f25Zg@2BM+y41AVp6 z*pqnRH(E8{>u<-eL6Y0U43&;qkSx08tG))&@Q6L9)C~jABk7Ix!UcPhXjmW-rn-4z zA2B{}X4>+Q6ibNfNemz_ko2i|e>SPUgz{b+C?tTzyP*E1&lSj9?}z^>GVi8#8?6M$ z+be89Fg0x_AUZ`QXF%R^PJ}CKA@7$h-z7XDZ<2kPSAcjBP$^hz(dvuMdp?jX&iG6O z>Xde}$lQSi!`Qqxev%QWXr@2j^C)>}8f&8G_3s2cR@U7?koRcT5^Xied%EgczA5A# zTEx7U9lpJla{Y#Rk|FlwCc>R+y z%uV7F#6eL(K3dw-eNT7VHvUC$S?5E;l#~U zyg$^;zDIe#Yz^ea;$0N*V0$m*tvknbl+2s|^!m0W$os?3tlt~9I)J^}u}^IwZ+~S; zj`ff?;q-WuAmn}MT}R($kwCD$f3!{PUtUgJxF_qj=`a!OptO7Zvbgo65jO7~wcB`9 zU(z3MaY`N*IQ_e)n6@#_pBs=0{oB-!;PbxhBc0=6Y)eX$)Yqw~qG9em9BbL!=EV4W zZ+$f8@qXt^mH*cNj4?>VA=ZSd28}e2&Y(3YC?`@Bs|Jl}M>x;jDA8v3iOFY$H7HLp2Y>(eb2f|*5LC#o0^gKrp%2bJMma<yKkB1Ska>GM%Pz`-ytONr7`mRY2dkSu zY&s9WAT``4b4C{O_IUKz&<66hwRw3-AUhBcHwTld2e5f>zP;IT!!sh7M`^dpd*EY7 z6*lj(gY3UO%IS|cn#Wa~{@qW$qkXoW7hIW9+;M&bKJUIgUCVsk_K*w;cXVuR#(%t( zp&gq1LZXS`d53D!mWNQ<%*$i5e~z~pQSlxe>FY#!S19BOWAXO5#(8H8BL=EyD7O6bAHZl-28;&keevZw1 z|2zrjq9!6}rL}xIQ@HdLfbk8UQV={x%b4BEpdj-qvKa!HQ}%S35zz6B;PwSJZ}P^Esw8V9+khLKUlrDQ1Sk9Rk#x6Exc}@ z5Ek#rGq2V;L*AVptPbS8wwbIFmvH^h|AVQCJojFg>!AM= zuK#Z|?6?(@83;{1w|nl(vhFowDIg% z7mcpUI%5UYTJx^{7R7%-T7XYypVjR?hJOZG-LsLVJSL7tGQE%cbH$E174M0SkE>DM z{>sdYuz2_Ls3%>3yf+5?N{g6Y`#C zyw=}!K{I$;u+!A}7<|O;{dxN9eQe&MN3}2URT6;-rQN}@`U|QgY~C-Yt5}mW>5sP< zC66|o{<)_e%vvYG16rGkWxa>+d5a2mH2TF@0om@v!^>*%7f6J3u5|_FgAC7`u!*)j ze(t#xzZzc953Bb!D&FHliBTx;4&x^auy_wS78u`#yyb711(12`zDeHN2YKhls#l%b zZV#3pjasz8J_3Z@PP-xqXONHN9{CQ5HG|SG5^oLm1cGzXp7}~e*u3w{%UGmU5kUr} zo!H?>sgEVtytf{RM($+MA8#~|Ejaya2zz!nFNzmL`)z;jIE~M{LGiS=)F~a3h;&r+ zsRaDnTLhSuHZH#4#PBo7MfVhG%H!S%m!zJkKh@ieiuboZuU#l_9iLO;SiBF7y&q_S zyoD$4ye0E)Ww}+<0C{J)?|UqzXAd6n{&>F2IRc!U7!wkQybS~*&pAQfY2F(KW~>6i zb3L)Ri~q7YA<{Sv0!I1pT$WwM%z1JZ}O*TOJ(ZGMT~f`xCHw zn^N%}y}s)2>n&0z_laTgPBsq<>xaCRT*UOrdv9uOp_>aK@2-7APM1~ff&S3?2|lj~ zu=(_s11ll#$3A|~_2J{KW5gl<@x6f{TF^)(?_bW|de_GtwrU`PC`!ATa+{;i3$b~B zIr!IMebXF)Oq4m5SVCDU8WMmWpZa19n>xK)YYo7~>cPwfKZW*WZ z+9m@)!dT)l!4=pu$gX*2Vq40HAdb>*9LL6n ze0hL#-I+#*v-mT}vkM>mOxD^>Qb>=Vj<2TS43brDAp45D3}1snEosXmbgPHqCyPJl z|E;Ka|J<*59_4N3y<#aA@7MQ*HpxKVM~ANcCi6}LR<4K%hj5xqGr2oA<9}8w6%<5P<@vU6iKlgGVjcyaRT~ zhCNB6Ki+5_hjIGHJG)$SYZ@=ue#E=7sRW<*53d!~-UhZLrW;-x9WLNM-rBh=Aoavj z62l*mUPxmeh+w}Q-)51%1##UPQybolhvsc~16LvbJ&98=2d`Gn1T+3&%7 zPAx<*KxxM>k-Ta68#eC*#j~HL=x_$PoRUX0PX7!O#JiY^dBEX>V13`~_`Hkd54Z(y zv?l5C@y})~#y|fbI=mw`U+pQw^LD2(kM`lmrl#zF&j0VA;yu-(JBjiR5sa6_;_YK| z%*+<@7VdiSn#}vC#!mN-khh<_yMNMZdl0A}qWKi^)^pd19EQAIgX3D|Aa8lE&K+{| z0)c(Pw!ByqY~K5`QkTS)5`hh+onbqVYC$|U@AJNUwr@(Lzv}Hx$>R)8|8!roo9cz$A$EAf5Nt8Zv3aW zgzDv{Q+h6pzc~>_TOLgXquY4k^{W59|4$DKe4IYO8RX9YsX^9EhtB-@#16Rz{k*NR z0;>is$?uuSs3_5XV!k7NZtk0Q{;!;26*$ChDj1z^%eDc7ud|M221S5Fm7;f_!y1&4 z**5SRE|B6BW=}j+4gm8Ox$(+b?ZK=mLwdo5esM$~L}}N5we8)jCD=o3uk-zc);;uB zgT7Mo=)vh<-7(!uJ>CfxWTPA+MCMU@p-RmjRge}Gvg{uZ|u=EZ`XuNj^NQl zu6Id~A#Ve27RTR^x54?%&Q_3jH2h%NteY+1)@ckF*b@O%lDkzqAn!BxMe{E}-tsSc zPwZY02vla{c=SxM7f3SCg%3+-5rHzL9qB;y<}10_ytR(M_pI=vKi+5_>u~y)J0()H z-j)YUOHPCd9>eF|8Ef*)*U62<_u+PTPAUxtq*LWToFdsX{sM`{JRHhD?3P~^Mdocw z#rqd&!AG=uJ2eF^$Kri&*9XStcbBdyoD(-eN<=dp0g-Kg#=&*VbiNyr{~nKre|sXr1CH)bWL^A!;H|{#670)? zU%l&Hm7`*IGyd0GI5cR><9uzq(Zuop*8hJer}X>-9AcgRrv_Og_V54R|G!sZkpfl? z3j3}|kcKsAsR7T)SvbV5w*AF3Q>?6QawN1nyUYscs0UP7-h&6ElbPHrU=6a`KJQ-a z;%2Z#cRIbfDgflY)GrKg$6g@C9WMB&25ZnoN;|XDU03V>Po*F_b(i zaQc@#`F$5jkOvHY_kVw!h(E+S228L2e8!37#Ug(*;L9W21(M$zxAlYlHVnT&de=!? z9?DCUUEMDHS^w{*;?2J5MhrT{mhpUAjm7&L(~(u{A#aVvIx}S6@?X_u*x?X6J*#s0 zgtRsIaazXIzbpbQK5ton5Ar^hcX$~|q8acNyt`9a7ytz4a`ku~VDo;X$x(s81JeAI zc7s=3LR-UJG5;Ci19tAiDfGwtH6@Q0oc>L&K9egD$OBBe(jvD?;PX~j_o%)BdDjp( z$P^!^;do2(dYMa7%VzcUEsooi9D3XAviHN`8<$-Fyi zcKw39v*q935{A4#E&Z@%xY!yDl#8rAmlXkiI^R0n0(n0?q2~1#&L9^(JX*I@I}nV% zX&buZj6H+gv2wCk{0R{ZQ`$+@KI3ohz~)^dHQLFWOMkpAD0vj&^zZIe+?gf4++aUH z@$d!>eBNBLgpXUboJj7G?dtud^_c(L|D8A}UT?PK`@s0TSJ9ToCEYl;+wk+MaB|{E z#hax}-vQ+yo z_qz}Bekxll-2wOi1AQO83f>k7s=Z`Ry+4f2J9u-l!ok->P)TW*FzTS!`7gJ(K0TgZ z+IOA)cn4APXu#>;k7ADpw{3X=XRfs6fB`;l(&9wR#7Q@j!}8Zc6P@_HjlQnr5w;mu z|I3|0fAAfoEsp{IsJ$TQ&-&kiiZ^rVqyozOo2}JKEZ&FYN>#%k?=UX8RpiYHl(%Qz z@Y`w=8z3DZ67m`HKDIRM7I|}`XW*4^6|COzLXYw-cLji$yQDmxDD24zd%NShiAZ?< zpVChBlih|YP3-DzwRrbsq7(h`W~1a`fzv-}C9M!HEpDK|a=3HQ44-%HxlPV`-`q%D zU6Tt1kKwQXL)GuJZvV{A@YOq1jkY|RgujlJ=Ki<-XNW2WhuA$-HHg=|W-nTUZg#M# zV$~o;V&P2L^%8CWda3N6um-U&F%douhuB=LQQ|UBOVFPiYSTCs0hn{Q>V1MW=#IL^ zauYbjCae)z`O`2Eoc1V*7x2LzVhx|(ChGVS!AVNH*41xqTmR+#|EVEe2Z9m()gXOJ z9(euR@MK--;*~r=Q8TjnO&zN?o}KGm5jmro;iL!IYX=879^=m-p9DA?9@@+BHHdJZ zwmjY}yQc08Z!m+r-Kco;@W#ADdFLs$s$lV!-+uYaW61l^jW(tk$lE_T+h`x;y}ZeP z?Sf=W@F20?ef4MrNS%uueh7K*y3E7A2d@9C3g0N{tOx``Cw;>jwqo-Z$osg{H<$?ozeTTexlPw#_yg7TdwFcqlMA;R)h4ZH@L8@h*saH<~P*m+d zSpa!w`F-D|FWC%g&h*?-`xppVa=*H<^NF=K$5#HWPTzoOT_7^^H`D*r*Dark$B4$!R9TN=)q;t&Uwfa6W z{Q948mbN@5UsqP;U;Z;Wai-$Uk;?h^?XB*ab&6QLeUqbVc;NcK-aTS9d2?b_b)m@^ zU;!|4RsMd7OC0KH(Oe{@?k3yhR*6{5>3Ey{KxC&_;_})uF|a@I%5eI5}AT8s73-VY)bsw?rMmQ!mSwW8gxlxk;Fk+`Ws@U zD0vj%^iTBLhFP1nLO^Hk_PL`W_(QCBI#_vhTLNjTitmd@T1~h!NQZX+m@Bio41dH< zyn(hnE~^V(5Y|6WoAZu+NYGCo+csHnY2jo4Sl_>NB z^1kUWCol+ke>qcKtrTPlDqH!4BV{8&=B*aUA*=w^<-gVAT z)?x8JIl__a33XL&?Jj zr+?Y+j}JT~@&LZ>8!MgT@vFD|X2Ywt#tEcfuc{wNDc9rjCYW(&tomTU@VrCk(Uyme zgKBAjXB@eDdr~84JW5;Q_%fH9ewp@p*gv7U*=_6-{b-H@q`t z|07)98Le`8=T|*v`1Swi4%+faTy^yRs*FGDe|IY0d`F!%QQk$&Dr#7~3umiz&p_Ua z=KI!@_uiiS`%m41yffrF3{qR^hWyQZAHl=8>fF~`{ZuCeZd2I z&ii{=l;HE0Oq*TfwlkXKY`AznYcmZmC%XIBlz6^oc-{mb8uM5eGe*ANf(y>h-m=^! z@Q?9-;P2qC=da=~=FjF&<`3sT#P7y$&A)|z1OIA%Nq!8j;76S)>PIA)+4O$thTJitXixJ ztWvDPtn4h)EMHi9SejVw@`UpE^0@F=@)+=F@W}H>@CfiQb5C%8;(p29$X&x-%ALcV z${oRdgxj6lmfM(Hi(7$Pid&eQookxw3s(+WnpI~FPft{oQ@++XcYA_y%KqbMv*0(iO5qliU_-W7Xje<`+V?iFFQIOoB7~~-u1q^8TBM;EX zzij;nKyILs z2d7E`Qh`Q$UeCrN*U`xBii;{zjz+E_X$0gN8oB80K82K_ku%SSa^xx+?d~csK}ykR z*H`Vl;9v80|!^pwZ5yEapfN8rgkK6h#Wr$hLM*4RRTcY;rU?kODNa z-fkU$0eo6h-9FV-eKJX$Z0g%yk(;qate($iI#3cPNI>{`$Tsn9gQ~DX&pn-&`A5pM{y(- zjeyA|c_ammv{p>6LXy#F!>3ELND>;YuiGt+B%+ZC(sAND5{*X6EZWj`QMl#VOB1kYA zE#DoMhXkR~GGUo*NFW+59lOeb1fY>rm7g`@k48(5Cu~Lh&`8qKFbp}0MvLv{F(F6L zXwjt2TjcQHDE{zQ6yNn|e?k)P%uo@hi~{30G`L|!W(?r20lwTJ9M zBl009#0`zeXF?EHG$L=IBQ9t}-f={n(TM!+AL4{Y{-Vva`SZ)G6c(1`qL0mKZA$TzVgrj*F~ zstw0hWCV>$56t{RhS8{aW@H)}LZd4KJORj8G%6}Sl!FYSQK2{2O5_U~T?Vh~kO4F* z5Zow)^rKPUD|t2KGa6mGVqSrKLZgfR;(W+QG|JT=u0=ke(S?<=_mTH#bpG{}5b_R< zvah__i}azDk0ry zbSf<8HPVGfC)X}Nio8OjwAl=Kz94OA zlt{=eMqZ#%{No67q!o?gN?G%f=V%nWue=LsL8F-UK5a-dC9)!a;TkbPBk~7PI{{#hG^7p;C&4-K%>tl)t3-`H2TCPT#x9X(TAGZ z_sC{6dLR2M1=)l~?_AG{Bf4nR=X_2P(Ltl$i4U)ljcD|y*XkakjYhANleQoLje6X? zaO1{fM}x8tC`qvWCI$#>_~WxtVg5HCecprrfwcV+Mt8?q+7KBuB0Uu4LYAXZ?fG0MWEmRWnO)z3NTX4W zreYhi6pgB;3%4UuXmtDOuV2U#G^#B4Jr9xm8#!8zA&b%Irt$e{L;{U&i2B4Li_qwL zduI!>5RJ;~e`z2K{zi(=oe^;~Dq9z}9T7vLtL~{$h$tGBeC3};=A%(@Z<015f<{*& zM{gkW(5T2^{Xs++jS6L^N)RD5Di}*Sju6o(zcTt5BKY6^fAqh`Bfv-O2dJJwl4mvK zXOQIm|GWZIcC2TRCu)8Uw3fp!NSPS+Ou}c7Ix~D4Z{RaX>FDw-X=f`C8fC5Ytt=7@ z?~{D+67K&m4kCTXn{5Ja9rw&$?+yeJ_M!@BGO!=9SEm>7B7K4&iqfubBCG3uJN7e3 z3E_gA$-9yydi#yvrsN@w)4%h|&7z~C0^r;&X1@=b_|G6Oudz6LK0_PHPOc30_H zKLvSLM-JP)hrIRty^2q4vI4)>ozK30E)tx4GhR>udGDIb@|c`!0?UW2CPt+KfsVw} zPwOnPc|Thcmni~yZ=$qw*x)d)tsI;8Pi<{hdgT3tlE-hH{_RP97f^ME59ATs8x3^u zd3TJ>q%HXpK|1VHqG+o@!|N?Z>HKfaGgSm z!|7jXTssfXPd<>~^DSt=0H6293}utD!V{$4us+!g5q#bfKJ1~<6IU3XckUtD@_0Qn zlHJJp=l;L_RJ_R#Qc&Kk?e)x9yo+!41`ELr((Mu^-^sj%1fP174=1{e@2z*7wgd}o zxzYx`B7sh%$u4)u`;GoQrCt{Jd5fd=tIAme!LMyc+5J_qdF!v7|7%;nAoxvbSDDi5 zEPDyNddIa-4?TKJf4nzS@<_tzpSM)S`XX0;P!;{umw7urZ}-*A1$kFakV1GkrM>Pw z!rlKTV_qFx@PI}`#O;zH`}I98}hb4eADePdozewu6wxrToCB`Rd~I= z3;XPC?#lZ=uNx9UH>I7=yw$lam$1*?D*6d?8ZBKycXRI?N*-%*`uAR6CiS#5Ke&HZ z(E<7!Vx=j0T*c|%_X`2{TKV~a%J1OC^Oob+pd&YO#}?#G8ytFMi5-0w0q@arSf$XHg9msWAj~a`s2+-$wLpPe?O%wmXbX9 zz+>BOE8i`}=dDwS{5*RxoMdCDv4T?tpEqHbTE^zkYKG@ch@vfzO1~`@tRHrhA8#F^ z<_&kRQQny+Pjg}M&dPayIu`Oa+_mijnRmcDWuJBM4N|V~0$EW9E6~y>^6qtCB+xyd z7;XxAo2E=o5x+Nq+#!#Y#L56LofVvTasaz}bCxb!SbISb{G_y#UKbjv?TXFYRNQM1 z5=DQ!xhZ+su!43zij(n=02-W%V%9WQ{qcT0*$k~b%w^2xr- zhP+2v65t0{tN_Q#c%G4$ksx-e)=CKSUfAP!0RNA@e@6`OWZBxc>h%=alEX&kA%*^PJw<6bVvtyPpif^*_7ggO6aQ30#bl zl2}p}08;O;J#_ej%{$jE^^QZhAUH{BXL?a7livordUq@f*{keMf4p-jd359SPkcsW z&^VY6Y`wHC-d+`-ce6S zMroIH;Ly(73fRveFWo%e=RHAxHAs+>M=?(SHgQ$_uDZh$cBkaA8mE6MiE(nR ziu|Bjzaj(|E9VALS#n{E6YDw6MMulr(7g zDEmhTK5xC5p&sJbj||WI-r5nG^6(MfXnQK^&+RQosd$s$QbKuuP(Q+p#XB

I!4X zyTWKJotigae{yKLg%!9xHkG6Sd7pDLS#$;Ro_d+$xMidXd`zm@TJx#O*<*TcRV$~p-cBX`2xc(nKXTI>+mDWVM~fTi*{?PP1rI_V!0Tsa5zx zEMaQ9*sVvdxBpiIjPxJ-Y0Ja5CY8`h`ZI$(M#Y=_;xWqmLfkJAEZz>kR>Y=5-c|L@ z$H=^WZ|sVB0D0H4SF^fX?Et$e+BoMatmrtD*QeNLR8=whMc9GCc2PBj0JtV=jl~$!yr48Dt0*Z}OY; zC~q@~)_GXGYZ8yFyaIU-5PJH^yvM&Ri+c}wPnTCH{dl|ss5zT`JI53SS|%446hPif zj|rZ2>umzM>m7{-PX+>{lkX(+hx-j55{wLa z_P4V{0S@+?T``b%#QQWh-M%I;UYS{ER}lzgr*7TO{Fe*T{SJlrzF{T;8A>~ipP^X? zxv;Buzr*?nnGf{GJCKscC{F*FHz$mp>f-|w3W|jrtnsV&`n=rf&#-#?xIWvcf1id6 z(nb${(p#m%_!p#E_|ulh;w974|2(}7qT)@y>jdQ;NC*|e;@vvAXu&JUd%^P01!UeV z>gN|MfxKsZm}?dvg1l|m<=A2MCOU_>IYHie65otT@0&p9NfY;j^MXKo^yH=K4cL>D zSYDTJR@`v!jneMH%NJko>0t9d6S?AW?jZf~PN3wGi_^cCpJoJ~>+yj@?e;_kBYfVU z7Ii;d;t)ZS;Rwwv`cj8my$Mrg4$HKkGCuFKH)+aa^DmC}pi}>?{~2Og1=s& zRt@AEA^DVgkF98J0zx6r6EYtJ0M_jz>-%0|pFtX3n(uzuRuC{#+8G<2;Gg)HGe~{JC$k80QRq$ocO+*5pue)S+L*BBJ!uOuOXaYN8LeCkN2Y~H0v$5|U zWAi@!l3O>_Nf2zKwCg^~ndr0~dx69xPqf!Gr$63jDS2?=^lwG@Gu@&Oyr8%2(Fy5u z_`Dl0cs}-kyeBL7s+33J^Cpa{sJS+8V|d<#lQiaWG~m-AH}VJ4l31vClkek0d9Nu~ zSct`Y%AZ4dE#$p*q3b&`Z!aI|jvC0DPbBbQ%CI?Tk+J7_IT;B8l7DSAhPX8o+zwXH zx5(p!r?<}eZi<$Ly!Q@jSX*^AffW)fQr`#!f=c)3Y+nUz-rN^kqRZU{K?SAVE$J$g zl2~lsp=H@x8J6_No1c=+Bql1}#jtqmD@L4fgS=00)>o2w zpY&hBngMycI8~q2F0=q&v`S|m%|?QxB;&k=koOCwrw)QIn}Fnv(MhgXf#7Rz#`ZUp z*t`>;*19^p5Cj91cHK@qF0%8m*Z(q2pS4DA(;x3tN*-%)`e(qDQralS56TzkJzf`x z&pV!NZI)a`C~4)l%#*f*5AoOkYkzU5#J;NhmuW3y{ME-<+VVJeqIxBKy!GGxe+=-? z3Wr!Osv1PTGa9WyOkv{EST*SOd*pR`S&6p!>QhQXum-8!NVk%OGsvg=7j4~r$pnlE zU*3tp7o>C6@7XEA55NECVRB{UaT8F{c;LD!I2i1&efpW}k|*Z>JC@$}f^MA^{M&9* zpzCkqFm??(@oV(-@p$^HLAI1Ul5zT{Bm8MweWDQ9ts`aI-hy9)9x@#`*mE?D)c0}O z@}`0o%-?qM->aKw1a< zi9x`$;d*f3a_mR!x&xf53o`|Q38kItaLTCXGHl)l4C{-Q#n2yb14Jz)-%g1mz&T>=d9%m87&&cK1;NN{vviSGcMK@OPL zD1awT;H6L2gK_B~kl5B6Dyfdmd&{A((H*x0K?0@SZ|^PKI;z;b348@CUU~G#+l-P2 zCrRlQ9Wv-!IrZ?(wPyM`g}c>?KQ7eU@CXKboeL$?9t zmKK(YZ;@cKa>0d%khe>3PyniNShB%iCf+|WoR?YN0 z(fQcCV-}wo*?6A*coP!;$s-k~e}{+%Q{(_YC_c2(sP{HL?_{6*rF;CtNLTj`s87z; z<5us)?NJWHp(KVs-ZEAiNmCv<>pERSPLNM;C9zZSCVzJY<$d|xuEkiq`$KmZjX~ad z?`9rQ^M0E;vTb+JHlW@ktVtM)1QIvCr)EOlhLz){x-Ct>?6(!MZ8`wNp1-x-O#plS z?;cvbeyg=0h^DmjELa+oa0L7D78jdZ7_x=_c<-a+A%xSv1HtF5BNIZ*WlK0(R| zjk`7>B>U(B_7WR)I;yny81wNiLhCq(lV6rWd-lj3A^?xUtWsrs-W!U3G`?9yLbl|T z{G66+#9d;OgeT`v+PPSMK+;(DouN7=i*$}f$ItNQrQ=O~Hz197%=;=?EZ#S(2S1uX z-WINPzo@+D&b3XBguJzd`m35_w}LaL)0zvrNZ{Lsv4X>p_jSn|k@odu;JHMqa^*%p z&~762)5Hjyx9+%DsxCYr?L^}u!Toz@W3YLL*a=M^wPQZs`e+?zaPs?U5?om_Mg(=9 z+>M^g@Od8=pIq0sl7#HG`s9)9&cF@QcOF08JjBQHya@^IjMY&z@5=I-8>C}-=y+3K zc1h!1mm9tui?=d&`P4zk`&;h*L&K1_IOik3eUSH^NB8+11dIU%Su*?jOA;6!)KWBs zynCLBKlt822GPFTiU<4sfu`h>#?E=zhZFIi9@{AH5&+t0oX3mFdpG^D=YP-IssuAr z=Hs1&*5QkjpB5$1{7L~4{OTh--17&2K$=$QthlQYifr!QtVI%L;P#eQ)z6w4NvzMC zM}?s}cB{vyKD#l~z30*KroO$E#+$&meHj*S-KCRv0wC}8r90cHy!&{sSgwM+8xrPu zIbJXU?*_R{``?j3#(44^O~|{g#zKgri40l-&CU)b1%b`>f67IkxnM4;V`Ig4I35cC zeKgK_tJ%pE5$tYn&|5gw$%OCT`i|DI9Vb6kTc5Esk_6E85P4YeKb*bUx_bY7uKEP? zbENIz+sKvV1J=GQ&)eZUV|8RayBx2|pYz}OKMepg|AYgQ5M2+VzQ3B*gDRbQm9Tn{ z+M=Ik+1HD-OMgYne1tvdSpeD0Jb$gWl4><&?lwbkJw2c~x{n05I9i&T@lz1tyGvi@ zmyv-`;D?xk8@}LO#ojq0W!N`JE4^9!nYU2@P|&!7ZZ{n*P-!Q(_weRK$oqWB@@Oh==i>X8fsl9W7-_xlaYMjm zJu9;w?jTdUii}o4-lO?Xa*4OdKt8elOtP{c==WL`a2#MSnK>%9XX>*Bz$Y~BYo*cL zT^`uH<&#|oe3v zEn%YP8FrfGmsmoKF++6>xYxUf|J^|n>3C}&9~7nW-l~0B0gHFgGUJ>s$or=Ci*YLN zv988PWsrB@_CzVoTtjfOb8GSe>I2g2P5S0R-UDD~8CxY8T%%OmpJVp}?2|6T0{?P? zt|6Xfm2BRBm6@-`0fk4SuJ2o$&F-!^+f0_zNYFTH^S z($w$WXG^NdKo&{kI<(3cm~w@MO)6q{2D&ZSl(v zF&}Ruw2n%g{Dz(ghxB?8LC$D$*{}bBcWKR&S;^}gF+Ud?neQ)4*eE}~v3&P_=Eztb zZ#ob8QsQRje||dNTC2V*(0F_Gn#f`CR*+t^a5kL(DO{xuRNkk_wWT|#m$%%niT{=` z0^}p}3wN}U0Oxk%i(8QQA+_?+T{UE2D-n0aTFw_JW<$f|9jYjwsFW^_J>QX$NWtW`I%e5?JsN6w!9{R9?R0Jiv=ji(oy1gS{@nP zn=4qqvEL5_T-W?~vKf0o8v0oz-c(8iVQAd3b}sKLf3SCuJ>v!Xb90s;%=TfAqIC@7 zCd&{-ehO{Nt;qDU^EZ&?AVj`O$?-L)3{i(b?^TKu>g}ggs#Vgn(3;;RI zPCFg)?p?oX^Dj6cSuA@}b^9tANIX8|lN9U^4hC=B$bA(14pO1P7$8Edh4H)}i0*#mh$v|jgt z%6sFN@y7=s@2KxuUGgOcpxk^-9vi%RYm;{G`*X-U$LOcVw`*jOxLEbfO@Dt78=**i z?}5#Gm!fBC0py*G##y8)czn0S=6z{4kE1FR^4^2iQGk=5PLKKp?Lt8y)|U<5+{5S1 z!>;$o;x-AHWhU0VX)XTct#__^-^2K%siA5h-)=|Mj8b?=909qu^! zxdm)~$2CO+Z7XFDncl|dEple%^|D(egGh4jzVm%t~b@SBMVDWZY(U^1=^5$)KtfuGff6#6H*4>7{a9%wz6!IQT zy0|e6@>V{(aE1L1GI;q-+3HrB9}r);DDq1R_TKx?wy>|e01+%h@4XF4 zn{qa+Wj@~QW`FD0fs^0%TD?_blSJ@S+bA_NAD{P!)U@`si%H0zKfLTAvQ4M4y>_Lm^dXVW0<1lIuQXrBJa(%TYVD+GY zr8Wx+is3cLg)7Gf;1X-S)Jrx6?jRSc?Oo2{qX!nJ|1NvgN&?cwEuag||C{t~>|c11 z49HtNAG(M80U7^GBW;JVdr-jC^Vp+XiC`rfw@uGRyYmKi4>IA^KfBwA`Faout-}l_ zzq=-_3R`%Ipk2(Q@`mAT?f>)t72O}U2p;VjdwLo%3Dod^Zj9f9R-JQ+KBFPS@;gX^ z8)J2Fwcffonm#iiNzm~&$#|1aTVhL-n>S$b=GI*nQxADxNs+P}guIm=YcDttdFN{> zI)r@E0|fuM-*$G8K+@AEw{sxx<6^<)i!PDj(wZg8YwHKDO6ad^(8lIHT4q@MPL~LZ z(YVV}#=C9Ouz7Puh^G#1Vm{tK(K>i=^1BkTO=Hn+A_y%nOB36G&)el$cFOhc(@4m~ z{>q078*!Idg8ufD_1r3~&s&ATI#LZqE&g8K5~t&Be17deueZp2iKt`ozLdI4?Iq;R zY1qM8R=MIe##a z7r&u@5%z#Y8T+8J)rbf_p>cL8ceZxV#~zTrmURz5&}Tm06KEZiIQgZ9PUrpDKm?lM za$C6t@p)@@?`Y&b6oIT=>Ud!PIR5!R;bO`Ksqz-q=bgk@9nF8SA5)n z`FOLb{;fj+CqDz9wUOo`g5b-}HDPCd;}1y5CpYB}<%S{ZJ4qIA7H*z>vSs^;a(mgzl_33?OficFX^C4jFiVdAaTjyFaMg#r`$_J@)2gi~B-r zgWE*VjK&oyg;b^rV0Ui`jnU57Ys|;n6s==9PJX5r4IKH4h+y|_m)NlXh4*uj^RnL> zaW^Libe{>9OqjF${C`n_u{xH7~yK-ezN4BG`h)71_ss=S#$1VnY@!yjkzSd_Bk=ts@L4 zzkT^z8V0ijz}47|^&9i>caTQ&7TS2Jl8~G8qNh8?@q3VO^2Y9M2kKeA2aTO)td4!f z1NTNEX6AosI^Gs3g2go6;p{7BVe#f{ZkW)8ygh#J*L(|kS5=)}?f`k~83-14h;0I= zyB&D$QAl99wN~{O$XiqLs-L+?eAi}=-XNna-*34r9uV+ zx3~04rr%jYW_jKOM(fDG=ce>`{$E1J+kD^V-!$Im$-^92yx%xyB-udT$dSGRDsRoh z?{Bz6-ux9$NngHf0*Sx2v?~pgz_G}ccUD2(+GXiYY3Ip+f5OxI>O4QdckK`N@Jnpo z1B2h=vdoD<2#sqHmI!fh#peCF;9TG0oy^DkGg`+8PJZc~D<$q1!W+Wl?dh5BEk(zB`!-Qo8gKrE zt?XF5xpL!XpMbm-hpR-WhZA>sHBN>=-VMhN>NS7V0fI;R$M3+ew>TQE$Pj|Oe|PDG z&PySK0>%2RyXO0WHMRR5&v}c@dt;kSO1T*ksG@Nq`Ko=J+_8BN$CmMY+s=HvbLj30KwK_`I#t=1z)AlaK`Vn0`I}`?%dZ zcuLFevq35AZ%!UCR!8V7^~d{D|C|4rcj%|f49@>6=z7qen!|T!J&4`bmd(hABlj&!?n6C$ILF>TFueggn z=Gb01|9`yySnwTw4|<{|cCV-96mo7?*sCEA{5wbqjytklj=y649%RZ`9nX*)8TO|$ z@Bfpf<876x$wlKmM@@bn7H^WVaNRw~d-ZZ*;Wv=C*^aemlpybgg3}L1x334fEuwRN zE(iw)UzYMULf&%}e@GTZ!55^FIyni|@D{t(yuxmQ*h{SE#N}z1!$cr~#@VOIe5h&1 z=I!w0M{vCd^YQjY>o|aupL~d9dWa$s+zB^_#?LEgT|SRK|$s)0^~^V9><<#fDvTkQ6w@jfxw&yB@f@BI+}E6BTe@HC0a z`@KW=@OsEQ@@Dz1eHrTTd;ifp8~MY5V6>M{5#;@8;_ReS3>io->$nz1@&jGXX3OQa zV)M4&)ZXf0PXy1wKHiRK9X2@msmQJ757id{JA|t>?zZCd zwza=qwi@yt4HjKRdDe`(gCrcvx~Y-8o8@^E4l`DVStH?-@P(QAe;FO`U9#)#XuN|j zmvLe7?r05r{vGnZE!O#!%6p4g!o^LH_esNtOVV~~03&}>yW`y9;G3?>uVl!(X3?&- ziLqob+$8@=E7%WQ$hZ|bWq{55r_MP?WFHY+MB~_x?D?cujLlmtL9X)}6Y}QJ{aeRk zoc!XghmYur62ZXSo}gv5_`Dq=+us|+1tWSts@*Ry#^0Q*)+JoKv8;*ZdE4tTR!5%m z$rFR8XU_kZ((&H;^GYj?_rcDHIas_!Y93tVhx5NTLCk@A_GZv~=Cvv0Z5Ew69ef^u z?v0eZDgxY`oB-RyAa66@lb|o{qO&NXE?LEvR2_*_%Zaz~Ze`a8q6z^4@5xJwW9x6KntB6s9c1&k0BlRtOD89>-1= z8Qfvu1gXI_Dme822j~CI4Ay}-u}l9wL6W26ZEG;{l-9ksh`!*%;;oEy6zqY#FWXpK zzJ|QP=9^1zK;9)|1};^n6~Hr~=GLhm4!V6EwuwRB!v%-`EQ}z7 zMDcm=ndDR44zG+8cq~p2y}|F^1aJAD1}(c-zIzi+Fj&X(uB^M4s#ms z(IX}Ev3L`@gDKvS_g9UK`&8b_ws&2QL*DjrRUOXLN}xsYkW-*yICwjFos$dl7Th8! zWgSTdg$u$THfq7kTVWOBePh_XFaKG*eG}yU6pecxZeike7Q1^Rze;nb{g{vURkRMg z{Jy80Z5Q1v01B)6eZqL~d3PiS78v9OBa@qZM^>=o^Io&mqP$AJoaK2pE@P~Y%(olv z9gUjdy^@Z%^>EBW8t;SFe!N(`t#d6G#6sTpmiVbr&))WxR?J!sdGlAlzg(QV7OeLT za2t~f2P>9%uAQbHPAroDx%4y{BIZ7}x(MXT$y#O7ho|1EZ2>Ea&n%ZX^*fc3M% zrt{dmM>(RBJeZL8W3&#u{EqF^r}!oafc@1b+V9!$c^{VLAMwo(Mjkqax9eYL;O4}p zDh2ml#wp_RE9Z;q9AkW8Y3$c1o+wmBy z%)%n=-;=vHyo5bS#G_%h5}f}DoR;4rwIsmlxgp(Q$>E^bkt2d2L_vbwzrWphk_>!( zU*C4x>j$iZG@NFQV=u95tX6oPj3k0xXxyrorMjJ&*gZ({S>&BX8O*oDu1D)wf|H*b z?+VBB!TdlxMRZao48I4(Y<=*3`eZob7JWyt_BZ|#OYqdb8tc@}@;xZno3T3L-wV4M zkY<+HHFUfW1|||{yhn|=MX-2(+y82LHRP>QAy!D`T^*@URDitg_01#|)=Glsy5a8H zXTm{g|Cfi);SN&a*4OO2zGUEFFuJaGjURXg)^zB$V)H)Q>SoviFK<0Z<36;qIl4q* z^S-GSveGk|`FNi|>nO*`Pv-O-6LK9th#89ioalqkn}fqi>wFpssZzTzo}rGqQEWd+fb78EGCzfm1i(Q%FtwhKBfd0PoG~V;Fo(N;{&Ydh2?1sEAPaa?V3i1wI zk+6LwmG_rf{c-hDpq3(?`^YyO>^^+2svPoWcMvfZ4j_a58X0S*Mf|{re4gC-<=DLW zz1nBr3Lt_(G;VF{@9F>_Y~IDE+*@|UGaqkZw2l&-{5Fb71ai$509IFAo+-NG^Y)Bi zSC$HS*Ra3Y+5dxq9c07Tnz&khmgh})$Y32)(Fc_OUfxEZ&O` zZe2MFdB0hm5Kra3AeZmpQpmf*rjBdD3TaTEq0qNIf0o7(0nQASKL_HQ)<`cWST@>pVAwny zIDF5I@r1lhKgmy=4uPAK*9s|NJ$^uL9SGhOiOsv~*p&^BgW$8b&^Sd-DMN_??CyQn zjVN`833>ORb=2VGcUC@CC;65DxcEusSNZ>N_NEtbc08a0|LH9;UeihnZ0lK`clZg$ z>iAlB>Uhj}(tqp|Vps}^JRAT^)zo`rCUwbwX4^&Ivf z&ZPO2@;o^I2TGN+=CFZQhZC#gYQn*+y>Hp-;r!qF`Dswa5i-yRLq~Xo`~myxfOlq> zv3t-7zSxvq$?$pjy?^6W@}#vsa~;CGQ&OnyEMIpi^DVJ~XdS{h`LUN3M~bZ%09W`& zoetc^Ut+J0?>L?MnS@B$+3n^H#J@qh)ILA2&9su`d(hND#_G6e@MG|<%{l7%zbYN? zBe!*h{|x4HJmo3FTl?$d?aH7mn`cVatR z7UUhVC*@g}D;Z23-5?dH;s-|R>IlWRu?M8~A&+79EFu^}<4Sg{IUJaPy~Or^@SlEP z&3wGO(K-fj^3%9|G~V?DKTrwhDjvAQIPcEW+a#_lHDms@r*$_~)9&_e@!KrV+tPxu zI?A4A+fR|Asl3(piCfq^lj0qlvyq(#f#C-H11H=1Kz5b)VVCTp(KNDYU-ZvK<{FV_#1ZHU5 zi>B;FXB@G4n|XU*|Cz&lysOYUEO7FZI?-)fR>Kb#_&A;6F30D+BdK_!DeT@}wYEZm z$qdZ@(kol#?fY2%>Mda-gLOPK;a&Q7{#T*n?ZmATP2;VanIekCduz_tW6qFwa!b}{hFSI@v^3Dv^IWQh83`7lc#qM2$H%N1xYS{{TZ&@yAVDAMVkpA4H!~B9DP>k}U zh$v!jPU1f{>^L1w1gp@v9ht(P7dK$@ZXyh}M=&Ap6ts>9IQgk~@vpxG4=3(zujX-2 z!{_b$X`ubR4SYEGhA}ro@Vs@S+$osI}#%3yS5u5i;%5eVIcAhe;P7(vrHoC*}u7rcHY7bRcK;A8{ zegjnyUsK+mV@l6r|Ji{N4a-GN>?g*wI1s1N;6I7%GHd z?;x}62h#1+iNFqx%k|Ri*%*S|gPImZEp$ehuLtF#bu{DT=l^G7MPM2q5b}Qdb<-j) zZ9Fs0T^EOCeNQ7F(tqa0$uY2ltlcbAdv`v|_aH(agLU||Oi29QL2jhu?RngEJB>Hb zdV&lV@41SPO^P6Icu=bH4D#M_jPtrEHS-bt)l&a$lA%2pPblBtbQ1~j>tv$fHX9Yj2yh>dJmiT_ME)Jt~<=f+Ze6G z0w=#$7qW@`Jbd7quglT=Df}gN?bQ`(18!%K@*ZG>+TD zEb7m{e1p^~Xvc#zCcM05h}L0^lV5bI-qDk1_&|qYzr@fGK5usunI`v+vxrh@=VSFW z26)ddnNzIJ!TJNzT*m4k8Xh5Us+t*))aiJ;FJ{xB@pcF=kiy~}`it+hPjl-j+Mkv`HvGB_t$pzP!12Xv42>u0~m z=I!e6_NFl0oB%Yg;m;AD2SwQ3Teya^kb?<%d!uzMz{yXr^Z;3S4nNq;UER3)Ek1AM zg_&`-jc1XtZ+$Pt7vl2{POlGJd!6;4-a@#-SRJ)7`PuhF1Hz$YZ^+{g5Lo4l{|W2Hwp60tnIEyV!;{GTxP-pxZsmG!Y>plOt2eE z`S1CEcq1Hh{Chb6Z=&l#Cr>#U(|V9lA8{2{4~k4{{x%2ppc9*?0=r-jQazdZ<7O^A zLE`XGAB0QYaMviu9nEmC-RoNN^#v5fab#RL&X^27ckR|%cE}%;IQ$WctH$m@<=lzA zv2z4LF&a0W^C+5q7j_Ra{^TZkS56vXjt}+!&EghXhY3!8A%|5qk{tN~5|ip4yAyx@ z*EhOcVysO?y?quWi99=+*llha4%8#0r$Qm`w#8x( zw{0VXE!p~OeKz<5>E+w@*Ct@|4oI($xy&U9q|i9ddKtr)TG+fx7r7>DGa+xdbDOE7 z3@5+0mp0ccEAxTXgX*MlV|?BRMPB&lQiCa8*a&B@!mT}JOn`AzHYw{cSGLEzTYLEL*Dj^y{VmzqKN(8 z^?bei!ofS&sSj3=_sLM1+OONmU~$peRiaA%VE5)*Y35Pbyh~oI_=(ID1eR!=q4hF7 zA$4rtzV9-A@X0e@_bx^2@W;uoHf>Ecu;m9@yVrP?0({;r8G^sWjlvNjw(K=s6ZpJa zoYzKPte9eX-tTrWR>vP+ZP|CeGu>N@j`uOCj+->z3Yq@Pv3P$|F_pK5yc;YOUs8Fy z>*de-4tdwgr&9VB3L`Njb(xJm;XwIUowGdTZS6OCvvmghQ~@_c~e-fmA^htJ#i zxKH^(lW>IJJzV=nK@)!W-sT$9{v-PK|GRBs(ceNCtHYvxSZ5-6rh9AB@%HMdpF`sv z?`^RRi?>IO#+&1iciASDZPc?j8t=^PyshsXg^~SN!oI0P-jhOAhrh$iTfcHhDmuH# zfaBW|KP>}4KokuWR4v24yyf?Dk=OieBH%;gmV_lqzrKWhd27<`(UAOo<~y7SMCWfOqjYeGFY+B>VQs3EFzI)Hv%UB(^ zlRvDRzWU$u|5&1l!TDdGt_KB1+uWx0AYzY@5>^k|fy|onD}d+!gphSlU=JdX2uy#3 zODy4gdm8UIIb_Fe9V_cm5-|PxHrY%Bo*;dY+*VUd}h-NaaleYyT>l z;jKr<+kd6^X&P_23)d8|ct^RK9xsEuLp%Jl)zMhK za4@#v6`K&`t@|O`L0g{;rWbWNaZdz*B`0++Ih#0R?tFImN<0LHfsmb-tu*JK;C1Ti0PS{;=*`CYbp;g@__0>tcTx*qdC98N44 z=*wMd`55zaq-~HLIr=4Ht5R8hb29Pg4MTMd@Pb7#OIZFq>fywWnC(0AAa8zUz7a7O8KkAhNX2(`ILH^cVb}vNZ#joO`Q2(r z1{xEZO0Vt*fFEbthsT#;ckkKe+c_K;2!cs8E)4O}*|`9_dmEha{2H^7`FL}obr|C0 zht$6uPuM2}rm_cl{+F}2g6k6MooCx|dAF4+ev{x&V0qq$t}|ALbS!&iJd*L>_y1}A zjhTPK9<-IN2Ze>?AEWgkOZnNVSUo7ZMfb_)t8j@O|M8{+_8^z0!X)bb|CyKj4rNi+ zAktMpYiAn?T>LucE#E>4q9&qnQdn)Yol5`E5ckG;?4`Oo6$J-LE124aA89lEr zNC|;~Y4!fA_4vGh{M6FcD?f!;?m}jtID>zCOHX@z(hCc02hgA!=bq28y~! z;J)n5iQABOK0n#{(MB>@*qIw-y2KyMFJCbGi!pZhKJuGmf!A9>Kt$ul2($W+Xkhbx zV?U-4#KU~NozOb)^2@y>_q5JP5R`gf<_Y>Ac%RBHi1Bm5@7|i8$2*^lvi=RyFWnid zBVzrd_^p4x-eN$?=9H8`*`ozD^R4FZgawp)`6FwNucMNc6b<5dT`9Zt{T649~(OP+`sG;k`-Q3 zbgF}ax3@g{y?ztl71lrhA7`+Ri606p{(d=e3mxyEs-B%R-k~I|HCViTU-Q1TgS-Rx zYSdDB|9Lm3ViL~(1mi;EyGsf39)l!crN5%f3-bPzX6V0On+z7EyX+*S`h(GT z;S0_^!RCE!^$p3;96>OS#)XH3|Gst-n|I0ZqIOan^YJb~>%hxzv^j83;(9^gDEQ&k zo_u`Xwkx$ZPpO0;4y*F!n$NqBxyk!y7V&Gl@z{DT>+ikO8LMM;TUY9b^#9KP|M~yV z%)h|--;AyYopCLFLG3|`@C9joKlc)_dXQFrl8gyi}-?S8!n^g53zfSr?pzvfnGsy z7mXWxIk-pG{UGMwwddtQOV$Z9-wyI9TE|nI{8r{7&$38FVD)HB2}p8lv(0<11C|!`V>;Sw63G&`X$NTg~k51YWo3Q`> z1}xsw4HZ(pkoUJb`yW)^&nJcA7C_$iL(2~*u9ioJ%$Hip_mO~-gd$% zB?C$DAZb^sFSsJAVz}TcHt*ivcNw)W1VJtuw3jZ~XB8)3GURRLE9un^c~@HLp6P@GQr`zZ1=nds#Jj1* zX6))> zgw1D$I6M|QC9HFR4#npIXQ>U=c&dcM?M*^x>$`r{|7gF zFRw_JW_jMhY{wX?BQN}tQRCk)NSn~{4u6*P&&`RSjykDf@$OYA{&^GfRtp^;rt;?G z+w&;^@*bJ^(O)XL2HAIe&)4Y=5^y)YQ0E4DUpoGXUq%UjLE3MftwxkDP{?ChtO+5pp3?;>3D58Xok&ufBtxhDnIjeZ(1D=IQgw#)o;}zA_%mSzOT7Dg+Cyr zDw;U#{uYh6foQKoy7&(#T5|TX&!BBE%kw_=n6Wy3&RZkA_wUPzjOlojiZ&Bz-TU4C z4ePOZuX*D&+5vg1@V$1Vp1rjP?HH#XPH2BfeQV;Uj6~@83-Pp&K%w(0S$)V`{82Zh zL75E3MRs(&I^qWwtu9X#2tJItXRK0TYicwQ0*leO>8a|oif^%bUkamallNji-n2T> zaq{~n@IAn_Ob{$ke^-5c44-#d|HYpPqtQt09*tuQW$s~qj{oevjUU-0hPtx;-rJVJ zI-HGL*1*eKyzm2<#g;?hT{2f^&VJ4?`0IcFFxw{p2c(^JJt)q8dgePw)cOBa>dx6% zJ!p1Vk$7u3#dMjtH%0z8-W2 zt-~HCKUwXknQq=haB$&|g*R>ScaRIF{btYGl7;jZWI8_`!(U>5%La>?=55J zCnC*XN$zTpcfi2Iq)(z0#4^n*j&lwfJRnA;*>Cg%yojTU|o{3kBc zZoIqoCiW6*Kkd8f+H&UOO{>EeC%@TOID-2&!3V-0l{5@A#pm6XWB$tGbvhEQu_gG( z00TEjU$6VjHnD@{caVe|jMZW85@*#p9ZKbGLB~6WkX18}E9kawWatPTp~ooQ6;e9%=CG2!U<)q}i;gb1oukaw_Q{uUR0GH@}k|H8J!4`i+M zlH!%Z=KT;+bE_H<1Xs|w9trcQq#SJC9pQd=ES4}IZ(1E>ocv_D66-6)1i|x`8%`s#oQ`+Y{V;PH zZzb`&>{z@HnFarlhP+$m@!5<>DtvhQ6Rexk{w=U(WLv77DMJej^BOp>Z{?3p6#Av3Z{ok`6jA&V0OS zbp+$&cjoljm|1&>fVjin=EDELyN2zPuG7Ot+yUuiNdC4re&sCBTQiKYI=W_kR@Vrd zIh@!|$NOwCXD*Gmb#^iv7Vr5rqz?e{-mTfmNj;oMf9VzN4S7q|oax~SlSO`2T;9G9 z^4_!Nk7^R+o$`EE>oN)I<1O_Iw%Ygt(L`sv5BAu5@A7hqZe@7)mKYj$WuL$3Sq*I7 zTT&cOmWweT?+Ubz%{ckZ8W-5IqKpVK-US{M+koG_!!#Bv9GRbtqzo-vX=Bg8-g`%~ zh#xnR_4nS+4A#-3_DGaab?Wy=RXC(E;KITTT~kIFAqr1 z>lGh3yqWoUx1)7r&8ez;68=AAH_%$wvaK+VYVtx2GhMM)A-83HO92 zs|`n3o;RV2u{stz=G+y#GqZ!-O~*TNIz^twTaD)(Hx}<-9GMcwA@2soA2n3oMsJP# zim1F#7G97D>#Ye=k&;{VjRXRtBT6eID9Ef`cRu+(YXeU<+a0>i;|FvmPZFv>WA7k2 zTP|+x{w@f%pmF_6s~3-?VR!Fg5%C4NTFl3r9j)UdPJXA!kIEF{h~R>X%S+&l&)c!= zw?ME^E>d@FT<)?O{^hO3TR(_7A3w7S?({e=fYdMX2zyi?{tylfLWLF#8Azv^40L4~tWfq`m1S z1%qv%c&9|E=?7oX+j4zx9T}T9|DHUj-xGqMAB`&t)8U9Xjm^6%Wx!iVllgehN9(wS zlV4~%*Zgyx0$|zR6Tb}|@p&KUDp{YzpNlBh%LfRv-N&8(gFV+;3G?h{dEUVX8LMM+ zLhg6tzmK=Dq~jf*A-|W#JN4$NIas`ps7B1b4tZ~6Z@Eh4Z6qOM8A&~y&{y`EyfIR< ztl-08DLDVT`ZgVthP>B@F0pDIYXgE^nd@TT`-1L6LHcb^uzBx^^w&BIHzzO9IM>7i z*&qMH+d=ku#k2RV#_$_KWj#Tn^&%w))K`{m38-;Yokr-Lc$q^XCoIzH|el5~f>|2zNxzejGS`cpXn+tKx)i!R_Ptp}Bz+e*ah zLA=C0TG#T5v^%y9hu?=iX#D5^SfMfwIJQnv5GsY4Rs;G(r|!>=AWaL3|mxa>ZEUfl-$_b2+=%z$J|$2(2>T?LIdC%1qA7Vog>X0K+*J6T+1n#%jc?BYfu+T2bZ>ca`N>a##|co<_hlHEejuS zfyQ-Q+H;d_88&bGoJF6sLYa@ZHd==rPJW5*BbVMg3j)HrJlmgX_`DaNFaMaZrWgro zthkspiO)Oxz^VBb5l2{l2l-Nhu{xGWE59-gn;DR7=y<0N=VsG*-(UBF4~w^=X#1H# z$a_iAUe9L8drBjoPn$ zM*P5!KEcR@>)5<09jdBs5<=h?8u!q%l;SoIn|ILg%3`x)%*T5Ot-~KDznA;j#0Bz+ zz;$WQd7D&x-cs-0o(NPdMr51|zg-i;zq}Q^WkAvUyeG@^CJ-5`gJSvqkzdM8_ufm# zJEfvv5skMEU%`AV-bW?*!`b10bl{EKJ1TE-_7Uy5)XQ6+=bD}K{#v8^Xx^%wbHc%q z;i9(4B@{$`bBvN>N*n0mF0T%F;RkZqZ;d>-jLmzo)Fs{#At7)Ljq|CnC>dtQ=55g^ z!1vpc`FM+=b(rDgSJ~$J{^d6!_-3oL`^Y(b-V(K0gYxUIAqSc}tZon7$6N(z8{wLH z9q!B5x3fHNsjzm2>UjE`==$d`Z)-Z<$qC%bG~QW!e!N(`H^23Wl7zgc%>P(Z&)$L} z`!hJGyjQQi9+LG&YkX^>oy;#1IGdwl86ibM>}<69c3o`)Iy_tFUwP&S-u-sAWXs3q zJ*?7m%9B?J45M)-Ck(;}v#@y!U+s;0WW#*CKcaOIaq^1{X6s$OSr8oJ_%b;WgU?(1 z_T>|ns@ISOQQh;RndvAXR>-ZFzmFE24{r|M~#?(LI{C|M12W4#_ zuA}v!u4hUMv3gLgWQDm1+(B+&WOItzfCWlXD(-0Jz!IN`CE*J^%ZdNrW$WEd*|%aly)i8V4?8_n=vt z=f8c~xfEfx&)N&EV-8M!#u-sxW21=RZZr2L>1O;MB%Ank`HpQjkW~qRfsSwRcaQ`D z?g5@#Z&<$v&1bBRZ26aG?V@LPko)O)UzS^OkH)*+evt?kZ_TcC-&G**1Mf8psk~?L zDj(E>yo1AHwl45qf{3-b?RlOW4z6?da$H)fSc@p6!_pmTU0m|4g~ED(+@Wmft~sl4Y!p*}u2$8IPZt{~hRfUwSnmNaMYq zyImNI_wr!1Ds#wNSXFds6Xabb8mz2H<$W#aknI;SMAK#uDQkZ?$mnO|^jbkdnx#I? zdngUB-kL=P$~5}}{(X_kZ}qWxw_4BER(mW2M9{c2b{q9aXR&$n2_}q)YBC@1CbSNI zocsznofiK|A_Ak^${$p#@p;SK^}J*Oc^8~F%=kUpggYP+rYK9F=~%El@8DmI)v>64 zphEfY>n--t@y@vR{0NQrnUZuNEZ()Xl_xwPZ|-jf7pc7KwDma_Lf-b}Cnj$y3nCAR zv)TKk;p;8Uuecb=!ne0x-mTWG+6HF1*lyHn_XmIC>u!WwVe^*f4!N1%E(B&L{EhoQ zYDqqL4x9Jo@{exqD$K`Q7Of)_C%^cv*FUG<5W#_C{SgHv_`I#G?N(XqmLM4(%h}3= z@p*@f$XC=|+sg8r6XRAnhUyUOjkA|NKeIWpr{kR-dM|{=d)&!O5R12x1m9FNyy|2rQz|2xt3 zpnUMEiPnRH=gBR`>OnthvIc^3i?om16?fl*J!qFrjl7?lY3?NzQpfAJHPk5m{VPbd^AX+eD7vp z{+|vbT#}Dv{T}pt;?Mt)b55(q32?FefYi#)SRIGttK?V3&CLIY>3HWnmtRlo z-i5Cph+*-5nx36`2l5^;Ue-+IZFNxfnGWP#TP~un>L!cWW_eeN2SosJsr!`kiWEft z#1k{#+pXZzefdS+4Sv9<)P`fJAU1Ey!Iy-1dm#{n#(mR&x=`XiHgD7Oys}>@%*T5> zT89}8JqI3Mx8#w<<39D}q zw_AY_&O{2>m_z_jF-OBdfr2#VJgo00w}P&&FE@`Pen4%~Wjsy{oA;9YmdiXGg@7g+ zcY<_;t*I58_XAI^wE;}ny~WTv9^&NpCuVg&n-UQ$A>(CkA2kCfU@e!R*<8ATLc@Y+GFm^2H2jqR@ zm0%5(xA7PD6FVU9%)=q3lg`VLG0C7q;goQY$Zoq^P@aN>X-A~a9cYD{716>25&j_5 z(XH`u(R_7w8~6t#GuCW}N&Ur)BZaY9oTz zI=i}7J;LYxQebaE^5#Ew-`Js z^knDGj0A>{gVdVUD9G(FJLg**tsrHVj`Us~KTw^|f8&EHc2BWzVxRr}t{}LB#@$dR z<_SwN= z8F8T1q z?+?*kOR#wNnbnIdgS_wm;&iKny!YfO#9xKH35Lex$BI*0nj+qV9gdM8y1%Zpc^w6* zJ9`vaq23DWZ|u(abJGv(Dix2dtHb8K_rpV{P4ES2d(b$cKqc|3&e*&s3)iG`pJG1V z)@U75IQi|;wc$~QkGHHm@oRm+TYTONGlmwPbuLGgg=Iq8yYZj@S3CDtr(Yt4O$TZ3JCA0ye0jb^8w@?ygyh- zc>nL37h5l!u+@(Q!j>vGG*l?ax$^-+$vaxXk7gU|=6qiuKluLB><(%9cyv&dp7u4scxqL;6+roWeqUSJFDl|>T4s7 zn4b%6FWkqwal_k=5SHhyHHWb}1P^qVG+daO|DEZ0Uv-}=N8=sgWhaTndv9fZ)IP|2 z`Cywh_3Z8IYVU$F>hu3(?H-fgiXd?g8WA-Tk)W(vU#Cf#f=FGK=<;%F1%W$D)>dTu zf~reX=(xIe^SPMgBsX_OovV_iiAt-irni?d$(x;KXF+p zw&#(+dizB48*K{G)BYkS#PcE8cY6t!Mvg!5=OPZwUwjyIX>chX4!E2s1Om~xE4AEm z+h1b$EVjAQ96J-3?;4~tS_eB$e)G;BEArA70J)Bd0aZWnd(gwK%J%mXl}O_(!u(JE zO_-nKKlnCI4(obHvi$rXtj<^+*8Kt;Tvuk6*rRm3OGnzz(|9Wei30g-GPJZ!cQ=jiXEdbbW zm`yC4!sp#9F6WZ9`8G0C`_up0Vf-CrzM}j+a?Tf)=UphrSREN^FEh%LXLx(k@xF22 z_$-b03Afv_SiGzACH-R|Z@sM8)d=Lhf^%^N1@cZ&to`g{wgy;oW>Jn+L;@~xeya>k z3i3j0{hFtR4?(4;=FhXI`~mkx?{j)G*u0us0>sDMQG~S&a2FtK`cdz!n`VjIih@LA< zfA+>7aVezpr4;Br+p6#r@?L6x`-Q^>3UZVZah>=5Lr_>VSJGb1A6VvSNjY<4^A5HP z%@^7z1a_lwMk4{PG5_*%B3{?Sn;Q6-k9QDS2R}}Jy&B^JztROjz1J<{LI%2b;q>mx zF?jZtVENJE;v#(BIx35L_te#~Jn!2IjMec>Q`gz^;(yQo`)BrI=3n3vdy=jPRY^N! z(R$G6doCrc9(3-KqQ;%O%d4i7jZAxV%jklZk8$~SMgO8gIzks|)4mAW&dH+~;{*@lQL0ama zZ?BG*5jYt5%0zfH64=|GnZC7!f;jpsj9mWO0yL_cJojY!frUO>BTf3SxeC3Xey03U z5Qw62DcNE2m2BAY<6;SSWyF||HxaF40w+JA?(^yH1N>mF=nC`FulT$_0%YVmQiXh) z$9XOIeIxGWEy`g}TaSnAEPsi87K3%%)1pXUJ3X_5JWj{^R%QMV8t+}Z3KXz-|Fq=3 zHVJu?l%9N{@-8u&zvCX{ZST3|ct)53=nd{NNQAr#efAZ7-wfX%ojP~Ra-oNyV`!x4 zB*_n)Tk>K-bq_XI_cNg-6=Q-R8I8L?pHlgi6Fa`C)MIbH2=noFMeDeali!!i-sG57 z0^q>xhL(Bb_`JVWEvYbuyuD>+{ahZ&K=)=Z85v^|90bfHcRY!u~Ggecp_H_z*lGttI?8`E$EI_|dxOFvnOV7+bcb zN?nhFOcWE}uTgmjaxUd6d_3j{MDH#yYJP*wm232u)C583pSTaZ;{)n=vEv_%eLb{& z5%ck$jn>hElV2V|PF{AH9}Jx>U$KILn-kNUoQ6FKRfzoj@*-`+M%?aQ_44}DUB1Uy zzI%Uv##kL6s9FnXKz|B!s2u&$kh?qb(Q81!B-L8?j&u0KuO^zl^0^~y*+Q0 zUEOe22#lg}Hy<9o=y?U3xB8d)dNJpikGDHo$3~p|exzUC?-M8hcFOS!l`+73dU7l0 z^q)$^vdUeCJC=c~w@ar3N>)wXX67-Fq1>bytV8h^=i>j){~7v7|343c^M3$c52{_{ zkxT1AJsI;&Jmg*n^aht^U%Ny;j?0yQkE8#25@kOnX=MMgpmp zS(S4vD2Rnv!%d~dEkJtzhR#dfen4zYWA)h>?4A;PC17CW61>qGjZ5uw?g^{Fz6a@d zuX^1=S?23OXVE(F@^c-iO=|Dq2PTg{#Xf7q-$All9N!my06}=Kzg^am#=s6TjXT-C z{}jt#gCtyFu#O8SH>mvGLHg72uAx{hr15s=d!>TK`(xs)CpwUKx{K@fD#$x_U*m=4 zIq>n8p*fd49vg$RD^F46`Xhn*X1Q7Ow^NYclHlHxJ)^2vwl-WOHhB@0 zARv-NM2SjJDL`^oGKh)<0Z~v9PC20@u46=_=oc!8CxJw#R37}x`rp#F?K9JTFIWt(uej65C z{;GUnjEd_m+@eZU?(!`986+K*K9aB1XG~Q7nL(bQz`L=&G6ThXd3crz7T(Ku9+YxL z@E%=m4U_QRsqlMQD1x_oiUxz!Z!;iSlIJ6g%ph4jkIO8zB*GhtD?$RjJHanMqak0# zAY^Aquxx?@8*gs=Yue5Yd|*2{&WO&#acmA7?-ma3v&}1M4{vs|k5-)gILjk)ba(TB zu(gr(<3sq>dxz4s2f{*)@VD&nt7fYBpSPSEks2HtI<@HW_My_p`qbCfJ%3+sJx+o5 zt$_Rm6mNPXZ)GgJ_a9C=7mDD$uwb|DCW3cIj<3=;1n=$g4m+()%t67~k5k#B(Lf=z zcDJ%Q5f0UpT)yHAf;Ypx-N$)?z@8^R&Rav+cu#%eXJR?Y|Er!M=SCg#6vD>aoO4p~!D`yWTb%5}5+^^Uo$WnWh6!Nex_YSJ7(U*2>VoA~ zRNRDD+1ShLNaN#uq0c6B{e_@KKlcuLMxBqrgJbFkk-NA4egE%&y}QRxAj&zBo}vcb zV~ge_4Y3NmQ65je+R$OupxLAsF~_j-pr z`%Y=>8pOIZuQE7?_G*wW*#};JCG<8Cx7~RFaJ4?0RDfTDvew)kJkfgx_A{!g9X`>C zJH#q$ol&dLVq5e>Y%!HSD&(0B9fC*~q$Mt)z`N!B#6L4ggU3%bvG6uXhf_-tyuYyt zYBV5tKh7GFY(VgS`LW3J;3*SOlc0FH{8KdWP(3SX*bUO1XoUdJT-w8XIoStZe)PFIeoaXKFZ8zY z$KL+}Z>3YEErBkrxOk5`)~&E!H@E1ASQ97ee56jC*w`3Cnn5PgQQ+MS0~54C$`>rx zz`|QCq2Nacg0~gB?-df>YZQ3Xs}Q_{2IUPD8cf0Vg~=!E@1j8?-`CC!jzrk=`^=1c zK?hhp6xFeCAP6YNysgN5gpK!!eU_UZj3aoH<95ls*HFVsF$D58?AFGylZ2r4? z8%lw9lRu{vig(Q>S9L7BE5d%-jv#oico;$;ZBBd+lg=+f@V=tP5%*2U9Gr0dqQLVa z8hoxlSte;ugx9UYLruf_*rPfnmj&|%NS4_L@?9Krkz>-4ez z9A5jxcubbj9^Oo3A9(rAzrO^1zDxk8z0TgxxQ37S=+NHP@@jYB%&X9)6NC5-QrJMh z0OM`?MUQt_A9X%nho4&Ced|yEA3}lm-Hp?pDBgYL3Tjw*n+y#oUFD)SZ_&Xl7b1MOfUN20c6{sdqQ?_V}@6}zTXZVi2S@f$CI$Z;LqaU++1xM4N|3QZN3^)$E! zSw;4-4ktgg$qTPj-3Z{?K%|1}Ui=!g@N&}5K%yBA(k=N}-cH2~a!5v}VIgMG*C4vL zRQk}~6}Rfo3^I|K0`JbYG)EL~?=Rv^n0W87^W#TmkW()t*VQ9)M_Wu)^DDdtm82o4T_Wb@S1}wZ|)?`=yzPRt-XNK)EeIkVRcz)Gor)H>c6(EH@XIXZVD%&=B4FsrK_u*_9e z3+n^{bt%U>ixt>-Z#jHy3yUBh*hG$dbS{g}Zxc4&!wyjl@-&FI9@)nSocuzbpXEQX zod8Ou$^^cJ;p43=<`=9k+5{`Hy&^ix;^Q5ZTNay73|{nj*IuU12Xp=&jpW!r%Ug^T zc(R<#1v!D}wjjvf^i{vWCFng^$r7a}3BC zZZU3iCBmXmPIJUuJ7}`|?P9nt2qXmDeWt$#8}D5={5ACD`M^1H+^d^h;JX<%-u1Eq zhQ2g7IoV0}ftMenVO)+Y(*IwMjjfl9!N=QO5V|ue(geTi*czn#sReV=_RsWJHm|#K z_whxKH=PufKB`XLll?n6VW7af&E@?;6z_%)`Ae|yel~odYd?bb+@mM%q`kMfNGs?r zvb;6h@^GK*2O}`@Ypjo9DjH1eD%+5?lL%M$-dowXsss3eOS!65!C-dZcjn0d;j!V? zsS@Vz$my+LS~yvqHz|Np1F(ee*S|Ia~DgL+2y zO`|m^ahpB|Rt>T}HpIW2m5M}8gxo!rOb1rLGtaJK5e6J0DRvo5sb28K+~L2 zmU#dXzCXCnu;4@+;HjY7u^XvD>)t+AWe>uxDXPPDEjjVLK#3f8{^xzpdT#6?HY4Qo zWnFpNYmnBHec*(Dg5ygj%_m*=@<85j1^A-=X54`*g_g~`N_=^BETN7sT?eX#65}$SH z>r^wGqb}^-whaG*bP@Bk5<}_4MUVGsDt$zca82!w{d2s9jRNnk1Yvm;Z$GxmY?Y1M}{@0mS+y=?!?ZzGA{EPpB^fD@a2uoSYF1h%pdb3jC{m8L3 z0>!)MXf=d|_qg@FFV_*gPds&8LfV`FC!`v8Ab2M(WSzanV*rG-=R_K;V!+v6i%lB) zh_KPCyDH5*?SSKF&mLyOAn;A%Hk(upHr{JL^XDXV@`4$1T)))VyNB%&lW+ z0Q3Vbo+io1fK4}p-G+ULaNd|Hr;ctr5FO2|*^aERru{LN)V;xrKj0K`1XoLEvjfibI+bb`2`KG4-jElNZdAU@5$C|Hxk~1-66+45WM4mUB3%o(g9O1 zg1_(m6$8p!g(N0}iSP+84-LuUd!Smm(?g;%2rSK0w)(Le8}A?HmK(*Td4VuFPDRX8 zB6%w|-Whdz)xX4PZ-|{E`$)&hZ>S}-;QD3)AgbxwB#GnW{i04($qT_dByGD?X-_k5 zgG3iSGs)G#vG`|@)cTOPGpYD@2FXo<_tVJYEEMk%)mPkDcwbpNex3=LK~`>}gGqR= zn_YUX0m0ksgVtE~V_guuENA<*;TXVhQDH~W2_n33p=8t6*Y|)=lk?UBm0+Nu#`?3r z8XNDs)h5JDZC(J#aWl8}F|W9Yjko@D<;EQ}_=0*uD~+t)j>q5GJmaYcps;pXyGJpAQOLxN`xp_< zj>u9@;YT(nPLu^zi3WqsPZ_nPTCnj(W+t1TxbOlUa$LG(Jm1<A8%RTJf?nD^4p@v8?;d8 zW6P-98qKgjlM_w~yq`#}7eK4G{MqB2Sa{21uFup)@NQEbu$tvD00==*=VGgSJJ-k7`=nVkIl{r^8*Htqg^^#98!YS7?F;Z?K-y*a)? z5UU0~yz0xRhBQdqh^wrxA~ncPeV5NGEM!)0}uv{!>< z$v*DmLcYz^UjAt=$?6mY75p>%}71TlAMq?L6BGbf*JX^|^-tfhPCq=l8MkRvsRZv*F_f z%gJ#z&&CKA$FcE#CS-TvWGe09y`Jm?FTaiFmvwxz=K*}|$F!ck#mC#IQJCU3DuL{|Qp7Sn7P_>^hl!@!TK0`6=*z5ge z4j_2z?s!U9h2Z@%ruObp1n)bw6%ezVCNOxJ$NXD87E}OesOvNlj+9beS=!zT-b1(D zZkdMwt?C=~=iXxD9T2>lVM?AC=#%5vZO+(UzJQJQ*4!JrJ8AHNw4-DnxcU9CRD>__ zfUDa_54Miu<1M6|n|TVs`$BD}GV^8p28oU?-E~|raM3qNbn|J{`M6EUO!FbV|Ch)| zf%kx&@;MZ5MZrvdEWC~5uW6h`@GjLFaUkLCaNmkJiQw%Od~`~!QX6ng4ajPW!~zYS z6>@e_MEI+~E4If=?tz0=9hG#tAt2xQbn?vqaG#&>2&3T=3tmu0j?1@e(fL+`jrUpj zmqAn-?Nx74vJbrc{DIBh4NnNb!Pqfa@i#u+K51~F*v@-!Uv>5u^Vj&dw_ZvgtY)=X z{0&knl|H62TuvqYx!y97mjdtpWv=`v-t0U5`LOUF`#!@_j^O>1slJjD@9Z-g9{BvZ8T~1Mh-VJ!Wqcte7N=6K; z2AOgeEX~U<*RDwbl@-Vk`_b!i+}Au6?S@%GwY0A?oak;KAleWM2BR5-)U{_=UhDh#8o~#m3`M?H)bQy=>1Jg4ba{Y+fMdz z8z;ZXnAnER6$IcsUCVtx8-IxP&*c9V!O{V{J5=56{76L&vifCEbK}P1uR)g7`DjuP zj^zCF#BQQ61>SEsVaZ zz_OgW<4zT^;7woArTkIqcp7ydBgu8p4xt+1`_RIg~{9T#{oF&I) zMEL8}?7_zS7ROIEeKp#{`w-bjBTjy?q8}|yJ`q5P<;DQNQhdC@z^>~BVeRmfX$wY1 z4t%^{+;v~tW+}Dk8>G}b)cH8{&G3$A@}K@+hyw37fj@quc-zOcFUP{0!_6c06@vHo zL_zevamSm@ZOfmU8DcsYHZD06`byY~Bq_~f>L_3N1*$9n{W zxsS@LF8>d!vCG$Zw0mmtfCX~gvezlapMtRQe#GG|aGC~Bkgg#6=)%eGD|@)_a^&^a z@Fm-s?pEXDT@qLG${N9&>&DCSr8inIN40}4V@fJY} zyoa_ul0fkmhHpzu6vg`_#{$2N zcgBm)5#fY$awD9tTfn9-JC6(*2ZN}6_30Bq*wx!<={nz~&OG2WIWA5m_(xzeHs0=s z*SwXY!3)w{$UZ!9@_QWjX6VTf0US^53beY7kM~Wn2Mp5Sr=R+yq>2=TFj}rwb@O~|9p^oD1r|T_*g?HNV$;U!S|NlG1Zk~jg5Ce` zaJ6;1`kn_QkmHn0%{lyJvHu)S3X0yAxR6R$0jC!I+?%d~N*^3)f@}WW|Nm$3rs*G${$HG;27P)i zDT&sg*#oPjuxik^$&;c4WQgTT>5?f&YS89ahVkCW5<8)lsPe(l1h(f&Km5Hr7EGty zR13=|!o2Noh--(NK=PF#IRS}apqn&Sdx8yn$h<6{rKrJ20NUiZn|dM5R~=k2XG$w) zn6u@cO2V}EyUr&2ki^Lke)Uu3{9R;-bsa9{K89a|EUd0N8a(fSb={gBYDcN4LCw9l z?==c7`XQDMrqW00-65&JGsqPbc#ovm>_PEXn4gfq!h1zqdfZwB?~nAA2T6FJNx5&a z3BjB9w!(7FXd~G7tfL3pqgZg}t(_Wg9ub})(9gV(X$I^^i&dAE2ZIODzJA3s*m$S6 zd3P?8CxH9pxE;oap64fFGIT}1V;nZ#BU8NfM-2%7#2q~OVKh4z8*f7eElcHg+Qa)3*@rPseo8ab zX=0msz%F-{vF12@yq)T^1NR;2fPd)k-TO5P|Mr%9bzc@jRHSdx+UWM*<^$DG=c7`{ z{(@TKpX)6|DexXvD7cB@?UE2Jj)k{kS&5q$g7+={GEUOw#HYrc>q(CjZD<=)c=6DObdO(X?Fs+N{-7; z-g9nyEjHd`%~R=OZM28CEZN5dPJV>V@vGPQ6Tqc`c{`4C_;~Az?S7+z;Js;+$7e?> z_W$V;MPH`cuUYhXQ|n{*5oc&k$)D9*5emFN2$uSxc=xpUtiZzi*E5p`Q3&2zE8Dh{ z@P7KcbYdrh_gfaL3+}4guH8fqic|c(F&lQ_4 z;o~i)50(+24*1SDd&6o8{K-j^0k`pEv(!b8_Yjpn4kZu1UK?`Z-~Ippc6j{Xh)4Q= zX^I*|?3&g^Ymm#Bm>gCO61wBhcl>g>wn)(R`ck9@4bk7(ejfRPG=kUd;r9&|@LO?l zvz&LafZsYl*euvL}jcLNJDZyp~CSA$g;0HNQ#cyfl zTM_JdYoBy++by)W1{q5Bu?;7`0?ky%vfBh8L2qK9Xp3Ki1n$;$@8Z4>Cp@dw2~DG- z|9`bJ>D}x6#lHqQM5T{6BP>dP`+q44yeDI2-=KJBhrE}?!dp_G{$~n;w_T?HJPGf( zA?`po1n+9US1$`A%;DYwo_F1^W5LW)A^K&NM0mZA`M}4)yWmnuv5aLz2yl5bYHq2I zJ;WO19k7$^=LXK?xEgNfFR6Cecz?@0X2e5-cpH&@;N@3tG|QxYoB&J6Qna;CrIF`1^lR>U`*i*sq^0_%nl)q`-T^?IEK6zTUd| zbImF&yw3`){9T9OU3@CZunfVwBy~Dp2En^M=;GnJcr)1Z);agw7qMVNsi93(84-?n z{=L?AWfQQO4)pi34goJ$v5uwMVdHIddgRk7ZUT5gj$@PF79!(^jrZwE@KZ{U_Nuor z*#};Jps*t(ONR%nXxV&J%oiW;lZVOIn?-CQw%7yHa;;2$+x!VE?oq8}H$OJ+eg`2w;pH zSF|alcU>Gd-uufdQ*%sc5ATm;AAUIbrMJh9g`FUPzKbipG!Nk8tzsXP^-7=<-lHM< zGwc`s=`A|0ukq2mMT@?Ahw)J7V@Hii`o_Q4Tdt(QdvrX05Ut+D^hVNHcn@zA5&MeZ z-M;GdAPH}D@2#`D)%3v$V|aL0SLjhsEI4;lkA1R`2zw}cjpbiy0&Dhss;E{90nOaU zSNG*&<6V-?#xb*#0Pd3GhCei>X;xw5z1LIw!QeL9!@HF1V;@d_heo?NF5~Kzln>`vJf!skVUR$1H^1~D! zEJ`%J^(z(>I?``cZY08tcGIn}#vO2sar4%!vQQ8`W*gY|0lTK?-af+bKE(yX$#Fji z9xBw$@50>wm+Z4YaP0=|)gaV|I8J`@ZYRPrTL~aOdqszbE`ALX7L~90eft4S7x7Ed zNC&?LvBFVv2>iD3n7B_fEj$>r@Td6CI9q)0th-KnB?ct63aKp(@tD(BomYD}g z&#aBRZGew=NY!fLGYH=6zIIIK^WvW%rAwOA&rMjm=<%jYq|(Rl!`H#z1s_TfG}r<0Shnje4vpDyo*^>WX} ze?XcphdLj9#`lc3_WY^dt0?gP%Gb9Q#d~#wk31IM>LpJkwGh0S<(1ZwR&N{A+Bt6^ z%Uh7#jr~_U%;6B@^0_r5vEUk8`BCwDB7DBBHo=$YE{OCneIhCs27*G*CFy*`#yju+ zx|I0$+#rw~mn*-F!7>&b?-f(^V;U{Ahj%X7hX_u70u54x(CQcv`V>d08=fsY$egFAEml5sZjryp@$&XP~2~s#o z_^c+*t>VwS^N<-NeZKguDKBHV|J=zCPSZH>Br77esGSJ!FFgEX zM|dO9yJDoT{y79(^0v*++OZ3>pTGafvX8Hf1Dq$vg&gc0V42v78J~1;KzOGn?bRUE z$61{GatdvJ8V?|Ekg^xVDhc8bu}!tp;~zIXf}M}-nDu#uzd;&Sq$4DxBDv@rB&`DK zd?ZyD_N+SnXNX-#f%ng-Q{gDyY<4eIvG6`RxGnS`g7-Dcc7GDyOt)stA0T*J8s7We z!C?a5b2zIYvN;Z{@;g@Ndyfd0aLxMs6uu24Z^*7n%LxJdcZl>Adtu|f5MeZRX@&#r zA;%rqnBFwOjvX&Je(6gX4dRXZSc;S1_UnGePgx0IvR*y=vj{%kkHcbCMk08h>kQX? zABn%bMHiIyxUf@x(c?`QNSzN=OV*Nwnm-NFS_-^>7_8<-@pjmlrGkaGdpv9FSp@Gp zAuVMjye9@!sumEuhd>>Q6?p=@DKKvPE*N^>NthPyu9&erR)cLqnUDbL&@ekhe6nM|d zi@Zbe{;&|HjD@#XRn=4(g7?;%_D>|dA5Pm7wji4m;bR_!Lqeu-Dq~*VHsLsM-Pdh@ z|6L+%nwQ#n$OHynMVA=md_usjA2}S}HQ2Z|?v@l>eUTH?k>gCYzufdS!j8A#*uxs6 zMSFOoK1^})6L@#ZQ!$nRzW=grNtMILJDa}YusMP^u>lgXb*yS zzn{Poq0Odnt_-YqjV=x(bSU;^g->W?QByypBfDU`_iq@#P;tdh=i_h| zr!Rtweg=8`DRn-&`HuK|U-~nHRH49|Ztnw4bOveiqg4|NZ<~BbcL>4z@EUh}65g{h z4$TS(-cEsWJjWc3;2Sd6SR@g=i=LRQa_%9*Pa{69@F3g-m$ox1?!FfSGQ^|43=U%B z`fKfo_nL$3Ab}j`obg>d|1oyFUQ_rvO+(tl`zP6l4o-f{`lI-}Ja~ZZs%h!!CHQ!6 zFqG&XkLZFUP8IDd6`FXE&@)n&Vl|KB%Pm^bm%KyRJVL|ucXB6)@lNU9x z@a9!%3;m7Y%|@qshJ^P^$(Jom2;N!ajAofRMsT8z$Co*~II!hTy zR|<^|!p2+cW5V$bH2C#aKG}yRPJWa2i9$C$dB87*w=Cz_@$p{PpAg<3^9c6IOJAj{ zkB|56A3SgS8rc^82hvx6QRkx|`AMQv$RE5FDe#_q@u3H;-qFSiYFK#FYo@$XBlZ6? zW^*LGgH_A~A`rayT?!7Tzkf4h6d| zobmSAiH)}!!{!6ad^vyGb;t~onNDj>AyR{))F=0>FILgk?O%x9*QyK0 zi^bNym`1+;FaN@sJV=B?^+H9Ql&=AKOOGjULMZ4dc|PyJ0!W zay54^{2ipG!Y54(-xq)XFJ45Qk0F@@tLAe446*7IcrynHDxr8^d91{Qg?FcGS(+Jw z_h6Ze6A5qTQ*-0|2;P>uf{#8;Zh_h408bed2X1bg7RY`n198kg`|plv4XY(En5GW8;zcq$hTf>a9kBHxqD) zMDbpEjL3k6_p0?1>OKhGrEbZwB)s27MOKa>{lDQ)zsK4_`tX{zrdwCU;y_39^_c8_ zW@5^U1 zTQl?x;QE{N)tA-dz?fu-ddhPmd_#O!ezM$kkaG2PY=l)Pm{@!I1{VQ)HP-L*b$hWG zHt?1lH*Pb&ykRYN{Lu^PK0=PPhxb0RkHa|mC0ZwNI?3|@#fsTN(;0lciC3?=@({Y= zd9L;4ne6y@zdS!MWOiZk_y3F+sq^v1>;t6#_x}I&6nN8j23w$b&o7T%f`zxH^-1r1 z1aG;9fk_hHo`HnOy$Ie+9YeFp2Mu8j!KGUtA^m??N19K}Qz9(fX;8N1(RCnoSx5%9 z4+V$P;tj@=uyK|DV$B@+jt%S~$C*ER$F3KM9Y3}4RpM6%+QWMd*~eF${I;F2eSYQu z4`?3CR$KoQAMd5BDq2UlyWy6AyM@uzyxw9HSRU5(f1v-jqtb`&u3x0PxBl(_@wzw~ z_~*zBQj4MnaYk=#L~9UqNuL9&1}T4QdYzI{u015a!J+`EL5yYw{)I?`vG6Y7_$^kC z;C(dy`B4(y6$Y!fUPAC**R(y+_MrxxKXV}!(u@V3;gQT7ABeD!`nFu&;9Bs)M!O2m z4+Tr<%%8fjI%DF^(6*~=uOx(&$iH!}L2sY=9LC05Y_2-whAZviy>RcZj}E>zKQRjs5ss-KE~=6 zptk7orkkYF2PgO{@ppM^BL&{9zamee)qDT>1_%r9tJ$yNuL$1s_m6gw@OF~_@X`;# zTaHgU)Z!z68_pQ=s^-Q5{}rpPJl_!Ej!Z&Y%0L}pSaPeYZB-bEnkFtUiNVIzyumP7 z|1AVU$Z^|si%Si8v6r{(W6jg7y=bp`8`WYCz=&e7sAuwzds^ z>V~_#3{hbX7#+2ju;~;a|^#UK8Ou^Aau2n0nB0 z%vnKWbr`6sQs2nTkB#e1K86@E6IM_{jx*k{XRqvb?D#gFq-{$6w1;;C*~dMc{0?|H z`?0no$6F%IW~%;+y|=o|l)Z1Lc)evf<;I5Erz;md-rA|u`M8|8ho3e6-~0b*pu5LU z0qOs@P}Cs4kkxz98q`pz$%|EkI6Ga9=hMrziG5Vj*v3LR8Uxp5zVi0yOj+cJH(2fmiZ z$ypk87xVY{4*&^z(%gHuFaG|&iAo<10fMT3XOOxSc=PUGZHVGswNi!$3vaK0-fj_O z2Kg(=x0;0a=Fz*1VF=zqvf09XnThy`tVv6aNHhSh09s58>sa$2;s5bv}YOZTYG8=}-T! zLxDGs)KL=@Z~x;1+*o**3T^J(h~Vx0AmTX*@BYlWUGWIssujO;wso$C&vSlT5ic48 z?2R`_!ed1ERoa48e|;6;y+8=;i3$bp+($cGeq!TozHuz*TRt;*NsfCoTdvT292@V} z;0YB?JKC$>Mr0rNaPs?n`1zFEO9J@hKYX&H3m@7VKG_ zy7-s3=nhcnqd<#U@o)7;P8cp>j*~JK$m4V*EKysI;{7nYk_!v(9i>}@oDjT+A`O3& z@cxwfB`pKN`*Xf`X{Ws++#7p6cXdz9aUi1ypUJ2@aD83Ya8)_UyI=uxb@aDR0 z;e+D6P<)&d3-1w;D;JL;c(0V3kS6v2-Q@U@d>O>51R$#jy zJVJyy>9<$~F0TQ4QfuSJh)$Og@>9F_Swu>H;PYYlHY2-M2-z|f`=dkgXOgC^? z>rQ)kJCJ=y- zCv?>M_^s$E`S1S!Kdl!{|A5pWBZ?X%6yfZI)*uZRO+l<0R36o?ya(z3_nGwnzJk;s z+f|yKD@s(f)myUNTu(}Xm;2&-pZ-1ts{Fi{1xzDvkgyEsPFfd(f`+;yebJ$yO38Y& zUyCi~5Ie`bZKZn*BPb%rJ^bD3P~e4Kvs7FC6mDP{C}#@b=x-Ecl+qvdBtaGD(VMe_RYk44ycZ?aptzN3Nm z@U9{IP{+w{oeH<4qX_aK+`+85xi);fMKpth-8VmmnUm&;bFcAdkaYY`FX}a4EPA}d zxT*7T{lG7Y+Pi=He*+4<1$aKvp?Ld$d$<$}??+xb>+=x2Q_a3BlkonfbsxHg;4QAh zIvjV10jMUh{~B*U4YaIS2ETkI!kbusKTj|y0}+z%Zt~3_-~aRQED_+xUcD`F{6@U4OFbtIQIu{eG0snz8ct$;(Y;1;m5-Jh}~ZE zy9nOnQr9j2EN|)c?ca~!Jycj8k>L9M_HPX-V+ONm;IL_?B;^Yc?mGPbD0^c$;A6kj zumlPNXQyknuc*hyo99byN=+vdI7N>8e02YQ=T+DZl0BCh@&PsN;mt|*VS|(3vD%*9 zHigLQt;^nLQdHm_I+rBCg5XV`kWiAkqX}~q{AXeumz0|y)!y)rUaUVfQ0c?Mu!j6N zu^t89{8uHDP`vYJ{Q0o(cDpQj`Za?0nRJ_dlz4}wx(_Nya>C}XL$jw$qd~r!T(ib! zU0%KYS1Oq?K#)M4pQy z_5aTv-f$wF|IeUPxM7*03U2P*wts*p3V^SB?kD_2z94N=4ca%H1DbA@TITqj1ZoCH z4vkvaU=9t>?6f4>BI$twIWF36cl(cE>?L{5$?-PJBHF7#kI6pRaPr$?>$c5xlpjRN z$ZayYhF^nfa$K!F(;vfCb9n~)S-LTQk0^vDX4_QXu!e;PgKO)*Gw2hlPuYM_?s~R@m3UVy%#h>VbCpqr!i35Scx!8DD zx-nPJXVD(sa%3N6IQjKU=`6j4TyJqKxi%p1zrcI$y5(cKZ}<vyl%KhIm3Qs6Brc&He~`)qH=axA>}k00H{iOeAN=F{s*cpv+jlFNy#-WE)6 zj6BSv1imWP@x{D}0>^J_3g4I|!rCu93@rw)0OL*X(xD|`pn3C^4Bj2scylh?cmHn3 z0B(@uPI3>vjCzEPclGb#13WeKG`avz6&k@qdALWYVf5SDxT6 zZ}|pVTsFC(vFP#Ef~oUys7dAv{ok**OepYP{z4i?@gDt}CX9*q(&v0@5WLMk>pddj zo%)V*jSGTzclZ6)vP0{D*KJ>kj6J8oi)y8=n(xT-7BPti{SF0S@=I``8B-WIe%bw; z^lxmu9fqf;SGO~O1LU~y<+%lwY}gHw@TE&?pRdv$-qvIv0yz17yC{0mdoKZ~^QFF= zYQUeIjHSI=WsOWu!b>ch&wAi5Z_z#W(u}U}T>SliH@)s_jT$zAQM#-#8y$ehOS=9=Mn>Lxd9> zyOV^U7XscjR;{sv$YvG?AJzVZ*5uVMtR$Z?Oxj5f%qVdL$5to2Sa4dR_g z_Thk&-)Yx!j~a0TV41b^tGR)Xw`j`m@JqW>IF5Vp+xlG5=&9XMV-p&D_LX%Ur;m${foa#Jrz*7xOk|J?0I}vdqHF z98B{}pPAk=^)lUKYG5j1%3w-h3S&CR|^X?yv10- zn9Z2P7|D2q(TmZE(Tq`xQIS!Ck)M&7VU}T(;U&W(hC3W#90xhvIqW!$I5aurIm9>! z9Q5o{?8EGR?49hl*elqx*^}5K*^jV$u{*Jwv1_p_vP-b@voo{JvW>F6WP8MRhfABG zn&ApVGD9@OaRy(89Sl|sx(uoeG7N$YZ1i*Vlk`LMkLg?J>*q}uRq=rXFp z__owSS*Qx>y`~3cqAECpcO#U6s-PfGUnm__Cp2|!p)^z-XRHf>E}<&$*#;gc6;(&G zf9gRgs5%mO_$ic(s>3>GN1%(S3gCGv238AAurKwe$JxV<-YuJ2H8% zK;fuzIlpQvbP`qDRX=h)t2ZB8PHx-=|TquARkm|50z*^-lziUJ{gb~s9jH={moSE0P^FZ6Y69AhDndwlVb_HNsFKs$X$;w+YBizO46;Sls^&FOkPWJ2F81<5)~J$pgC(JDsFG6pZ3%5fl_bYR zEo6nNm9N@$Axl(=r@!0|S)huv-VT|ginKflnW2ibngf}liq!lE7 zBUF(NIYEY~BAp3=3{XYdLWlHGMcQ$M^iW0m_7B>ED$=J?kS?l7UzR{Rs3IN2hqO^e zI=75mWkMb;NH+*UTBzbcE?j{&ql$Dt1+)oOq|f=Gji@4h{S0ZMigXV#q=72ZwXKjk zsz|q7LTacYT?zN34&Bh-MZ%)1Mc&^1(LB*!K}^{7gBuf71)p(;&- zVJ%dPs!PlBgPOiMS4FK zT8k>ubCZxfsz|T%L2FPo-B26`$)RfMyreU<8dcxyyeA-8RDI>^+X}5h)#opBE|3hW zh+WgVkTj|$V`bk!QmC46d&mq)qH0{WV;Yh`)#!NqAhZ%ypPoxfLgJ_zNwL`jtw7aB zuck^!3{}Gl1vep4RDBRE^@BuE^=`o19a@g6wSb9V6SNdnFM?zBA%0X1*eRcb_)yiq%#|PFMb-03wKRx_tQ>E3 z*)Typ=s$aQdoBSYpz3L4aTdgls$R=$6%ZGyo=C12fH+arGrDgY;y_h*>xtD6JF2=8 zgykVNR6TNRjeuBD^-yWl27*xafJfB@VnJ1BTbd)pjH-@;K~9JXRqdyLRzQrXYIAvi z5Mn^pJ+^30h#plf?Z59N zS*B4{=bQsrrchNY^;L%D8>*^5cO|oY{rCPq+VAn`kPXsp6l;*ASq-`dSrjWOg|!B` zVWr!ajmQS6&HH2}(i&tkCws&=atCSO*~lkt=9>V!9HCmFEF83K7rZt9n+S^)&Y5)P zUI017cjDhX!+>VI&w!$)73RKmx2p~PMu-lqC&!%>J03;HiT%ZCvlC15Dr?$XVt+vP z(S(ym^q zSMK3^j41-FTKZix0KxkiDC?=LOaZTXt!}uhg#q#XWhR;B*m#dAU3hZIiw-O&$Ek@} zcZH~6<2_ofk?f>Pdw72&`@qYuEICAbbU82JC*GVKqXKXBFWFvC=%2tgJQ2Ii-r(OL z742b5@8Y?9(Z3*d%9A=D8Q*2rW+nXD|F@#Ro78urcrOvSwGs>O6$R6 zTKwvb;_bV$@{(LD{s!s25&y4_Hk^wd@7_<;`IyRKf9m@8{Xa_zyh#fwDBfmC=f$z` zo~IXnb`il_wIyXY3GeuYU0*d3yoVIL4@EVpfnJ?xIfaiAKxtp-d07N+9o+-Mr*38f z*MKauNNwc)|5F78Y5`j@Cnw_fmK)G*SOPwh9{*+(Hx zesX-Zu3E7?;HZRlh%ytRWJS76~?UFDEdgW#RG$2^dPw>n?g=|}|c+E;3HX&xKE5rvqW4R9oQ z;xo0|{TC4?>}oRp<&q7UpK`e$>J0R-kdOSPJ8Gu}^Q+ zd{_`?E~P!Z`N=-6;^bHK;BJ*f1>UDJW>xl#K8E`xL^3#;+cAHS|8#%H z)A<`~dl&uwKV3C-J{}i36wM;9xBT1x|3d)n{(v+{_7pXUv^Rp*pp}-qa#%IUkw`4b zyHu|Ioc$p?sRns36ZU$E^#5L==MJ=o>H;B4XLnWSaG;Q)VV$%L-BSGdMS&AcTncOg}VseVS6gLDe<1n<0-7uTx}gn`QToCVQ$C&Aw1Z6+fxu<>@Qf8leaVL{7<9CzY#^1d}MuxF6x zHp_187N$MCoyb1$@;i3OA3m+a2l}2Tk4;c_y?rpKbE>R z*6&&LLoBsEX04^JFFW-IZ(9nyNxRo5-nRCwtFZ7c?#*=>Lh#P-;9p9K_h~zgw=Ct_ zfPOeR;v0f@5{Iz19D=tWQ=0p?8^~=griZTY+e-#_=)29y@lxHnyHId_H z^k0g}M`Pp7!svSLb2M_eo5ubZLiT}|A8#v{-)Aj8a9bx&wZ0y|dJn&fzsQW>T|z&w zG+PC~|EJq_`H|;9(4xniY9GXoF7o|LNVBuXMG1NAX;C+Yw=W~b%`8TBTC0|NCO*hK8x25-+t0wgLH@N124aD<}~HE^}N8Io}0&tiq+esK*_gm zj!)pbmn*i45~ElF0olDB!$BC^e@FtxvLh+Wfw2;QaJE>G` znJ8)X7B-in#M}7L!8E=0&7fxE_til=!h!Yt&GknRyh~0F)$G1_4y1U2Q%osgAbCPr zg!v*i-o>@bnm_Cov|`9{CT@`jghsLN3z%Rv-M@Js?ctq6_A!o=-wpF8^9;4Tz`Y=~ z!;1>M>y}5sJQ+`GZ!+%IvpUgkZKUj<+1B=zKVA0a~rvSTWvV;8CQWN zcQ9P3)h%keKm<{fCBq*wPJv5RkP9FxmB;;&Fbs~WKNrjYh z$P5$j-3@t)uZ(|d*^=Y*9a1hA`eWn0e#xHZZKbq_w-eciDo%c{a@H;vf6oV|zr~Nt z7vba0b+%hX!53NHV)U&;TG&*;{ulECL8@EA-WEHOIueCWg;k`M|su3pwuOjOQ||3T(X3M_M-tchDZ* zrDPxHaPm7G-7mYnn;*DFRox?&;o~iR+~CI-_g>h^$b6ISx(ArQM|8*@5lJwAD3!D5 z@y-{e&WCOk@Sw(X!i7T(rrS`vE@ysw*QLX-`Xvtx8{z;-=& zq}cezM#pftyKP3J7{OZ^oIZU1hCS$~vzEJ15&^uH9+~f6f_=P2vbsX7X<$KX7dZ}U z*0O@)YrXG!_kP#;{&V`CbFI#G>2t38zMlIT)@*Y; zZ9(&g6Lb{T(O}v>`Zas$>a8gmZ{kx*B;IEZXm3X2-Dn=|8Uyn_AMLw}oHzS)${>gP zPT<+}*;3m)3jAQnkS>C+-u~wA+A#3Z5}1E3V^rXY23#`qhGUHAy!BqCg(bfDqsffK z;q(WK`(n{~YZues*bS(Uw+>Q=7Dj$!mG3U99pM3uVkV)VC^-L5$k*xbh0or^R=*bn zi`cx?3A_?wo&7Y=`v!$|(EoYpTnN9M=-=~y()vxse}$J=JF*@`d`^?pgQ5pkY)9)s zJa;ai2+kGe#h+4@)J-wi=hAbZvqI4^k7-( zlLbcF#8#^nM}q?r-KxyDbWnFb8^a-CR;gJ{O(d?RHT`?|AM{J?oB7!w0{2FU+J4f) zNFA~m`8kSg&$1Zj1E>4awrCb$FR^hwI%QJAcxcP(Nmbt<3I?RG*^dF&*VF#|PiY-4 z@%@ILOY^@i8E@i)$0Xj#i9JeaypLVsbG-=j4qY9xfykRPEn)vQnD@q(@I@gj01b-y zf15oU1nsEPh)!A{fUj3#UfoyD0HYrFn&TUyL7{d+<(_C=RNkv3Mb@+B3sj&I`dP^HJ-oz*ANxbiuUQ$Hk{YlK$t_tQo z{+yGK$a^Bg`J^Iz_12W}$Hi}qTF}++D`wnJgg{5XTwf4eB!KHJvfV~g@Z$z=-a%Dr z(ZFr?{>7%u-Kc*o)wfl)s#g5ev_RtCU3(YocmSPub2{Ca#zyMnU4himf{|bK$99**FdtSi@qmR}viF$9M|pE#}dWx~A6BRbD?SEYb; zf2Py>a-zVef|)G`rqOwOK00CktM8{~FA^ubN&no*@93KoWqy$d@fWCXKstuhp@NZL ziPw%+2Ul*eX7B2j5ej&#R!x1n0(Wo6PaItp1r*$zn2;>f@Od@OcW=5x%IXL%rB^?E zVQK!iBI8Yb*9nRDn>KBEG~O=`#$1_%c^`Tk#7yKZy}MsD5boY?*Pn=toB&Y8E4z(r zuZBXL)6=&WVcr8W7v#LYoddd&ca_60MFA~oV^{Uay{O%Ld$!kpzNvXlMI^4uLr!iz zAA0xJKXgdDD}(xYZ$awVkCES#yKXI;?{b5~e%!eX6r8=qyIifl0iV4&9PfYg^(OYs ziFDRehT}}(G|$_E!a6SP!1FR$NB=wjlXj=n{8xDXcP8sW#J4>WdyqU=jMLaj8#=Te zq%>6?J8-c?Yw>!L2eAi@e0wRN3O|D+D&rqM!mkaz&D}j^;Oh;|ge7(Q&k+F6l{5RZ z-xq+cHfiY+&nR#*W6f`da7EM}R2~;v9e(herZW;Z?N$|`$d10m+UVn4p4_9p9#n+X zft6nfm)V^$UtZ9TGhZoJf;}LetGWKO@}ntMhi!d=H|u4t1I_j>>y?L6Y35&`C`{B<{oO zE4l2#=)9G5OXVDHP#gPE`B_-~cD8@S3qG7a*?GSho3}#T=|_eJcxc9RTFGV{ zdx;HdNqiA!cZ246zipF`^ji+$Z|?1?diCyooQEB=Np7 zW2=J3yE*c_uLjJ!Kz~e|$lG|rGr0}Ez2)XiwO>x0CKTQztCZL14+UlatakcE04-r= zw`6}@1?~-wZk*TQ*Iq1N9!q~#6P0&V)p%WF?X>2XWq;%R3kEE3kI{LD>@{q#QlP%e zTOmjtp&0pXaadhepv?!iw|h6L-@xwPnJNlQ@1^lj*j2+A`Y!CtTXc#}j9j=|G=F)E zPJyyIR-}kOGlp-FhWFm~WW0%QOeOKoKB%gU#yhnv+1&!>-S^_F5|Q`nu|KoNVBX~% ziEsFBYC;8-()TJ_10a3Al6^|>+1o21lMz~W864lpbIIyjG+0@lZMYhhq6@W)R;z}2xk9QE&$xF@5rA-2&8^U|TVR>=p$6fKNKjKd&>rk8 zg8Ii2y`6Q(j=3StbW$9*`Tj!#=)ChD9WL0ug8F#-BXwZqw+3hLV5Y|hiXPrQF?k7_ zcSFAP6#WN06yj&Q*T)EZK*9;fZWQ`dLHoQnP*#UYKH##lL@xa@Ht#Dzv6mBX;vpWAL*j&u z${h4&(Rm;C=rA_=M18#bkvg#Q%Qh*u$^Xs=M6)wK8c}dSx}qRM{}jxd?!@~5Wq{3_ z?rl%L{PHr|pa1(QtfMJ4^U~j!6CWevP5kZ(iT7{Z1$s2z4_E?5n_%7+Dhc64-hcXk zOMAh*r=JjJIV!Xv{O-y%-ut~EOL}{T{j&rhDEZdP{M2=@+oPh@=~NVGjrpYzy+;m} zH>6`sUw(K(vjT}z%Prd~&4@n#Uyl2%bg7m4c$Xt}VCA=h{&D|xc|K5gG$v~_K2nD(Mt;j481asx67Vq0_d|ySt3SgChj6ZmmgQutf!s)H@yhT{jY(=U;y} z>Gc{^-hDo20^>D%HJ>AK&AY#~vG$|$_BDhW&qz@p?}tboJ{b8mm1#%2p5z5rKDfVm zdIpfowQ6ezG7FO<_Hq!A9^sq^&L9zYk$nA9d=M3 z?;xa(T#WoUFER%WP4j}LlE6|Z37dD@tYq%;N<6e+uzpeh3ijk=1j5qOPmn7c8t(8n@y!%h%4OhbhlFzO+Ohn!vE^<4G!@PfZ&AMq! z?1n^rrWHGWIzmnwrmiO@2tX=(H{oY>IfxLqS1AjL1Rld|ho!UoHUC*W|G!`K=Ey2} zM}5#V{qi?1DWLmU&j)ng92&cLd=06OcLP!fR(@Jt>MM8o@d4J}nJu4Fuz3$}v|P0s z<}LVRB|e`Y`|2&-JbRtM+C19doXk;JhrJXN@_I`TGTy|mw~~10U5s0a#ydX7LSF{v z?Y&8DoH+mAVqJfO2j;!0_jk9C)^4c&UF5f9;0zt2OC?BtBY+|{dbWohW#H7k4pA$o zNHBl!o789?E9#!{`crY97U7SY-bfq-EN!;;q4U;$IJ7El8};$dMC!oGPtPp=MY<9n zs6ShAelG=QZ^IJ2cQ(OiZ}<Rgm zNqUfx%cR+EO#_JT!-^|d=2R1xbF-ZVlS~fA=_7p zZg}W%{V`55^b zvC_2%JYNG$R5c#jSzz-PtiEvY6wLeQ`J?L&y}@2$=??v@3t9X>aC^%E3hUthqc&*2 z^m+?FGT!>{Q!`1tg>&Dsqw!WVz+JY4dD|y%gowO<*Kav&2lK{FDsJMA+y_}Ux~YBV zG=@4&+7h}y5`fbQ?lQ*NbswE)ydPb3aGrFYP888dY-Gfs^M>(oZG^0 z+yC(N)(G2{j;Ma><1LBQ@f9P#?1G!`tDdX@4XfDJ3;AI4)|u^+%P_`6nuoH?-7>LH zkmwTaR+JZ)(0uo%J4aa^r*0&yCkQTeZ(lOr`!8IwBk_)WcY8G&Z;RWBizi^-#oZ5c zh`dKr&OK*?dHb^78zZ#sg<9H$n$O|Qpd(6NI^%=z?JbHW`#jt3fZ>Bm!9yn_fz0^p zRO268PMmN2-o2UmHyV0V;oVy*NF7WV`MJJvuVldUg2l}* z&yR;=^F9@Dx9E>49unHi5x|ku2C#O%9fN`NbN32qe*UlcL|Gl5-`F2BXbF=6R3* zrmT(yXv;-S_~FEV-~Wfz_^9BY!}EU#Sr0n8^LIR{2RSw=twrlWW33ip85c^l-ek~s z6X$>9TlN<9rHWb(zZ6#8{bd0CSfsDb#<4)s)iD_gT?F9y=K2OMqgt?+nZ2WN4-UkH zds)fK>7XvLd+8$9uiX8%As&fiw~x`_6+~ZR^%l==TN5CO`uqKF{iMy1I`(1Y7q6mm z{^}cU@TN&dgn1426028`b}R?JLHbNHVFkksb`R1$S+j3WhW6k8#}iIj9aaWHW{;DX zc96kjyp6tsKoW0FA4Wbj-c4%aGk0L#xG2v8BJUH7wt_)0?YJdkQSWR8KyAGRoRK;nbD==@S?}-(KmnfM3yTwyC z2T0NWfYd`_9fyoe760De5=6$^uzCYMiMQ^?-Zf~vU4E(ibiur5o_L24dGFYvvPBr? zEzdMDC!lx;$~pb|teMDmsNom=z?~NaFn-8R=wfj-$T*uH=_ZB)ZE0M;?PoMldAE1R zyKGj*H#|q;HjJ(1N&OFxw>-Ijq(wE4`gp%X>S)EtPtnV2`#KRG5L>tCq$!EbJEHMe z&Co|Ylr+VY=69qSx z@u2Z;%P?Fu0rP$y`^kXFyZxw8&#e+gt-8Vsmw!1OfaE{kzXAVk$oV4stD~<8;LMnr zqwmZ6Al~UXU%Mm@e8&0I|Kiwz$~#0{%jXH(^M-LGZuw2A%s=hu-MdljRa`YheZ0>h zbv(ex&t%ftXKNA8XjrV00pI@q|yniJP9i?+>ZV*P| z8=y+;MEYAYsE-_=`@TdN@Ddx>Wd~h{d(c!Tr(e)*MJ6p z0=WF%ogvx-0%|=gFGa7zf$Y;;fB|72Y7g?LGP*Q8`lTTUiQB}qU70=%y$7k~zc!mb zMtxt9_C@MY#mLX8(YWa8O)e0jA#|%~aD^7upJ9CV?(ynuJY>*%;`AX_>~E0bYz5N7 z=+tO`iM6M!j>e$u#^2YLc97v@yv>=@FOzuZ2h9tj@ou%r?~sIf+tzPBN927Wbxqh7 zn75I!dG|g>3uvRIt^P6Vy&&yj-NEgT2_XNJy18j~15nbbuS}ke05|H-2lH;_mFQ9qeSLZ3Kqx5^FQU2e{TPMkQn---ly+N8dAf4a( zWE~oBhcOZPoiOhwA`a$6-eQi%gzj>f_aWYV^=)PlG&Je~&FlojkL?SMS_zz#e46@r*C2H~ z$H%(l^v@R-d_H6#4s?8r8G>|wZg;M#+ zdGz^TU%PHo$Ytu|&4<*nA0t2C?40|}irm2SqUk+VI_v>Su))hcd=w8Azhv!Alf~}d zYM!5FCUPWc{`D5iyeO+;-`3Tg1EavQ&F?lfB_No79CjrD(7O2om)Pc8Obv=I+M1W#r z@k^XhJ5hOesCwgA51NUrJ%&3Ee_~fFptlI_L2L0f3T$u>Dw?=eG$ZB&^;f)e zzFBJlwA^>z;kiu!Pm*3G+veq5H))CW@t6`tz`T!%9y{MD>j){@E!&cE*9@4N5BXiYLjb#W)2pQ(ZUlS^ zR%3^qF1?kKu-`}Nq-m59BgHhM{$7nS1 z4$>3`GTzoXT=^v4PH*c((0CiHG)uV$^B%}6xy+>8-9Wm=1ot=+bT`!Fp0N+>N#OF-X6(C+k0T%9``p$6L}A( zweA#z=l`NzLPJ;T?V$G=)@_8gBOrGy*(tD=02=*G`IuuKfWCRRPD`T*(7-Rl$g+Pw zD(~Gp--v>y(S~{?ZXzdNH@^U#cfMLnb-Wz)@jigmk%y6AyamIJxBgsU*&XxO1s&MD z4-$F~+;ql6&u^bjdFh3Hc}qZDKAdSC?a%)@6xJ~!!@N@d{1R_EGTxR-U;cUamNC$L z0~&Ang$KhEFmLmWp(*0!txoAvqGd2|tN4n6y)w4YiifYw-qjukht7MvZ)qTa2={M> z1fd6D`gfZ6TB`_9C=w9o^cv!8BS@?0__ph;S=aY<3m)J*} zs!iCw&os;-aSt|}+%r~Y4$z8rOBWEz)1>l)N za<`Z1A|BfRef^#zr?GdCxFKMkme5V}_aISP$A=e&E3=pGAWdN+en|iM?DTZQpX$GHIR*iFPPfr{i}R;)BZSHf zDm$7uAgv_h?Ra(ZAKp*3YNgP4<5}+J%EG*pjvYxN^0wLVa+Cw+tvK~cg5TH$s+K%_ zM(VpgP(8u@w5fmqEG-fgtG_jY`hBYREP`-gZ}e%l_Gv@Z?!8IC%K6>gRKqSLZZ2Oz zXOkZ~@5DUy{3#3S<1LHSk${n3`=cK*k&Haxl8!!IRt7fj*#{!B%aicXvcBc%Rdd+9 zV;27ycpEg+JnujX>)>2q$Xj5&K;*rGjJJbV*)LM}ZvPV_iN?E^r_FyK%=_7uSOX&O znB^DD*kRstdY@DaJ~%^NdQb!F&euE=6dMz50DqfoZmy_|f-^xBi;yrg~ zuLK(J*E5z^9AVysAsQf%IIGqJU7@Y$Qk-fb#>_G0r^YS~=%>fAb-=k3-;SsmLf54QY* z-`@J~`9IpUN=1JkUSe01^&pR5D_)X%P*XOu99j<=yIQl~8=n7Legs$-!#!x<^KHV{ z;3r5EM{0aR(!C%}gQ+j~B0NFA*fo8ZI09Hc+jnfZZXCFz>*HHkZ-Ux` zKI}`sZ_qH`a2|={XPRD|*0DsL|JCRkzl49HzVrWnqz{xFmFhXUNWQG6Y8GXl^v{p9PIwd!T$Ul0caAcGm6H*!#H(;OGjZh3iB~4295WH1?SmDn0K#o zQ4*0ip?JrJ5tw(Btelp2rw4R?*{X_tf^OjZo$K6=7YN|DlSjah)JGs&`IF5C5t#Ro z>1r7vblzVNZ*x5OdA8v`5*L~1%ITts&Rb&0yzaFC_3<7>>cGlxV1!-LMx6`T$4jdoz>qc9B^$B6aW2 z!}~U)@y>W(zyBS~+bX&10Fk%7n?Mio>@EDB=q`>xcc`P=$KjZW3kZFDAmIEZ0>FQ% z_@cM@5onlM?me!61FURT*NlRXpmy)(unjvlkN;?3LgJ33f8G3b5&iO(%*VLXbxPF7 zyA7#B79+o{4DmX}NnD_)M<<%!d((ZT ztPY7SPjJ%r{+<7+Xv#-V1)l%8$$F3WA~sbra9}$y?E$8A77$*5cUr8yhh#8uzVYuUt%*UtV7xQ+C~Dy(g_k58E;=M z*PA5X-FhofdB+9tKVXEH*aFLnL?Z71#uvZ)VBYEqmFI$keW3m>`hpF6e87o}rb&RaI@%-)tn z>f>F6)Pa?sY@FK`^UIvT_gaeOT?%+77~#Zt_rb5&8S&q@q89u9e;l4yd+3@E&GV+T zj&stprv#(U5)Vi@$#{F8AuJ>D<~x+Dh}OM7|M=d!0p^`&<*rWT?Y#1P(i52X*7C@S z7(pK>_@dpr)qUQ8&;I?>>JS1rHz`wj`d2fMx~Ak4d@BN++85fG_sSHNH%qPOo6e|( zhHxbALSm-z#kc5JZqy*W&+a&^&KzTgvKKGa9tQHhpP8;vnPgWpL^YiFZJ%p8^_hzXr}Y zHJJCQ-6`LQS8v7N?<%i=d0)KQWiEKr8}gVw;BwyD8x;E5Bv?fd0O5<8CI5wHpu=$T z=wNLGxN}Zj=cyDr@Agg*dE?UWhB72hzaZ%H>$B**xz?O4%)3v0ygQIOI5F~jE1y4c zP!GQU|LZpvP6uq>264~7B*VPdze=C>oul9Z>AXhqa(_db=S`PSVI7W>j+>TVZ;`@I z#@lnf$5RsT{H;J9jrWQ1XWNg$yeFj03yHjIkNX&>!MtCy%P9;Ac|(i0-CEdkyg=n! zu7iYV0&rCtyluaw890?(DA2IOf#ls9S4*nUc^{J!TxU}CtKlpXSKLwEx4G~?@D?|G z_VzXP@peJ#;KayJq|8tC+6FH0RBgHBeh+NkIqQPBVlU#M52Iszt}n6o-gIyEXSTcz zqW$^*J!N%#pIJ7&sGcKY803 zp8t*0@0=)wd(c|pD_gqZ7o=qgl`LBB_k$Q*Jk33?`+{asalzxJ1W;?~lxo}X1e|M+ z%(P&}fyP@GrQDWTqwXM^Z|bXXh%i9aNZiN+(G9$}ZBXa`6~zoWZ4uPhgB~MwVCBcS z_^Rym8BVbG$np!~ZrD9&IBnojizOba3fh=>RQsr1^ctI?I0=9k#~HA$w$Wf#MOCS(h{55)ue{TyP%|>GZN;#YPXdrk@qf~x6cNc_uV1&V%AAtNL>4= zOVSBnVCBC5%q1%VkneIx`(XM6c)e*zQ(?jZ7pa86G*v59-g__BlnfNpL$*lV&QP|e zOuNu|=e`W*DNUn3-g}Tbu=0DKwdP1;Hzx?*_C#RF37fanmuTA?Fz=d@{Fc+-DcC_8 z{1DK8Dn#?V>5foXM^fD)@fAC8_vR(z9T*hQOX9uv#syV0-ur(Zvde;bPk6oUEP;6| zLr&k7;3r7^ZXORzkM@PwPG?88>G%S^+a(G4_5>g#@5Oy|x)ngKuSNE;;(+1PED>Cg zB`WU>-JNTe?VyMBkhrGQn1o&Ltx>!8srxo(MoXxVH>nP+{Oacf0^Bm-?j5wcezOfW z@2{)4|3r!6p$8mU;wsCrySL|Iad-DRMtjK>HOHAvi=Z>!$uf796VyC-GZ(n90^g`(JL2+JRV1Lrdi&+DH2Z3ia{cj@0oBBfr`~o-2KloFFIb;8(6xY~Bx-8|{1p^FF$k z<86Nr1+Un7+|povV-wBurh7zT9oOT6{(k>2WgQvsurOy267Q$W#~9IgYb+M9tc7=w zef;dcxOysvVV5_KCCMXsG z2u3#CEHUW3SDLt#yeC^ zXX*QY#O{51posyEck6D8T?#O7xvj}!MBZbWc3XGBy!p1Tu~U5H50wfw*G1&|g2vyu z+RqLU!1b`NPYdJQfGF?N{58rEK>z$6w#B#ThZ9P1O45TB4A5>QZr8-@pOq`oc?SmS z=ht;nA8$FN4y^oUTrO7dDZ{t7v>Au9QgHu&iSE<3^QZ6-i(-j|zb^LWEfWP6w{QV2 zntwrBn>=N8s|qJ|Z*%cvdNkhB)q;llFz*#|C7r~>iP6#T z1nUY#ty3oQaoOp9(D&!j-4;E*fM;NBo|F**Ge<=vNjDt<_0yQ#8(zf7xFV0N|L1NO-$k|{Y(2$uw7`&MP4AjgE z0;f7awm_9SOHer2ASaNaSeLA1)aB7@rbzm0qWy@0jUEk zzug}N?%x#S0&+h;Tzy-O&HD`t1H8Y64@k=+>OSRQ4@h(y6->Sl-lTcn6xShJNl15F zy1ius8ShBtA$t<G`ME!PC zn+xk@y2oQyhGwW+jMRv8t3|iRpH%|P|Sq6*y=)B8P9<~geq(0t0NFAjZ`R#opn&Owk0VZ8H z70nc2ckhgaF0>x>ZQ|>nH_0Vh*Pk9#z619lh|4V77rukka|OSm!-4qS3U!eH{MGol%E8-f--?dzwA+$*hCTj5a$O>&^08k zJpw7YcgNR+V3p7yl2u|6i7}I@DO-89Nm&&Hs{QyyMR>o0E78=QDGn@xEX!vik?j zTTOQGNhQpCL88318s_aiWb*3KY#7A*!F@fazc(22gT2JkzbS~((!fK6iGuQQCT!lCZQOGT0qQhAAjP#%R!4tj^2W5-CEgNbyyK3v z|MT?LI;Pj`XuPFAM8%KsP@lFsZuxL2neCU*8$-Xmm34pm#Ya)<<9!3EBL^ctPlY3u32^r|iVDxl{*29=S4)6b+6oU{ z?k}8R%X^HvX(R1z!*_VqWIw)5^SpCZDXYVCPi1g$?o#&_BjX)2V-`W;%^?%QhQ?d+ z#`$f#VBT8~cbz5jW-)mzAPXN(#P@AEW%x1#+Wtjp$cEbo3~L@qGv|lDy;akDBVW7| zZ0vooEo=THcyZ`Mkzo}&Z+h>=+ut6pfbd9M6V#R}UX9K>JHq|&Lq+Q2{mbib9hWik z`xL8m!|Nj_P+$Gy$LqJ)yd88Fr8QyRK@w4SQurz8-jWI)p29b1e*UMEqOcCF=h-s< zp8u1&8+HE`p8sXYdQftSS1PFo#kFi(i`Ii4Jn+*ofd{00DYrxJ!ae9cVXaaT{D|H0 zT0<`*UL3SxOO}O{pBLD{klbb3KLMa!TQAE#eGb~H%IsGQhk?5R=2qTG4yg0LK3Lo6 zUc?O5AaOlmQblSB4ya2BhjM%ugP|zu@Atp;hp-E&gA*e^v7Zudp{ATb_ua>=en;&2 z|2bYvJAOI*25G6b4OwFp^dJF#v$4*tG{3~st);Mz!DC;y{@p=tCgYtHa%~@pw?g6{ zUNqjOoP#fYVBU-=rVK>h1hz%p7clR&vEdbu-bFy=uEJ;7qrAX=vk}7V&;-!?z!jm9 z{Tu{6Q7E&7!a(VfM@McAq4S;`GgTdxVTLM@xF*L8>3zBAy#4ty<||F8kM{^tM*v2C zFPB-G%yV%9x-%l?)(5e9KVUDpV|=Rz68m=Q7JC&1kJxeNG!zmZ&^~W2%IdJyek++? zw6ueiCgYu`Y4n4{dsAEM8Z_Q65pVs@!Mtl!%g$E8yhpa_A0U1p&EEgsMxn?EXuGtt zXHvEo$Ow8Z={G(BtP2_wAGkjUAI;*X)NY3XSslyUdqUB9cf9Yf*<8K~+KR-*ZYBIF z)I5@htj}xpo!gqJ85;pHC`huoQcY7eWoxJOHA}RQK z%K=_H{@ZFae}i@nVl0z#+(@z z{V(v=)4j|WVvjxl%Uq4g)p;pH^Ss@zP*#WOa@o4Tq^0h?k&O4*`Iki`-j3%2xY2ko zOPZ5tgn8E`jTI2j-W)zIcHf108*E;w5Re=WnQskE4_WjA^D|HCRpuwa;zNu4B3&;RmdJt+O1#&J>)@}Jza9<2wBYm0UCCY5M?xyJwQKHP(Nc>f$TyQ!#U z7}42|FULXiMh(~5&wGL^Z!hH#>L$SbBd<;Do^*lr%#RLUJ`f55>UJ6B1v;Y6>%9j; z<+z4fAyV9!diq!Ka!1tpU;E`S0~0g#^`K`+9RMT08){u#nkzZMY+Awli*eXJNVz+H zc`s8hME}-|=X(YP^S{`+8$KD0w0{j!gu*%kcvVII&i`^`yf1|I{PX<(fk{RoG~SZJ z)u{xScN;I>hRC~%sYUn|%)5A@{qf;!9OP@Dwdce&PoSXmxcBg*36Qg|M~)@E3mkfB zw*Q-aD0t2C<3-ya^Z{wNDBGu6Usk9OiQ`FieBZGjoj2W$tKbC}_3_q1>iARipY!AI z;bedFfCJQy#{AZez~+6gQ|j)89z4_(QI%!xguR2b-o?1%Vu~is&;OToD62!{_vn#h zUQ0X3tz^8<@9zIZ>fTD}?d#BZkM-5mo{|o^{F?=uMB)n5 zR`f~DqtE}<1mlTJA?oA(5UJxnMt*x9HBU`4asqi5!%E$g*u2HQj2y9nc|*lzVe!u? z*g3gM{&XuKmLFYAfHym?ADxe<8} z$pr0Jzon=pyY7C0rZWyYBX(?~;Ac;e_}lsLt?mg>_5J-vXSpu$#b!2E`)Mf1#kbih z{X*x>#v}BdIe`VrL*jbW^&5Ja(YyD|``(Bq8S3M`5~*VvBfo3QbDq0Aw&h3TEp)#0hz87CBYXEG@o-}J)dF6-L{aNS`?>)K9UP=HG=GUj*b96YzxnaX z>j|L3F)`Yj5Kn2?f(SqlBx~=)5)OrEXqX#{$hFasIl8tYROdcW+TH*J>S2 z>f^19)Pa?s@326zG%F|ABH?Lo=Yq|9x65$XJ^1X6&$v3laU(YGQY`@`vEOnuKmU6I z%IfG3)=zyB_3!=v|Fk!1{slb$ZztTk51nv2IltQAL`*}FVJ@mJsUf%FNmPOv)vR%rdol zt45#yKR#{j7?fj&NOA6mU(t`oI-xEl!gSGY%uhs6uP6L({SmxD>JY-nujEsun@JM~ zU?0zIpRB>|L6whAkG!~zhmQGg@RKmYp8rSuC$6^m%hLQ3yDWgRIvT>W3gS|hme_4% zyt5oD&Xbnd`RQ>{G~Vl@HN}s^ye-!L8LokO7X|*>l>+m2OufHTCj|!`(o)zKRqY9+ zw`ql4xI6&_uQ3)WrFVnvJ1#m%FAD*L3EL;PZP0ngnFct-Rjh_4khtU00lPh9(Rn|5 z`ub^dC-w1;MCxe7$nQm1gViBAPGI;$K3}^6o44ZeQTj!g_w7uf=e*mRQ2(?4=RfPR z!asMLRcM|!T{(qy{P7Es|2rTlk@3z{Wt1iH4%qQP1dX@vOu5u)n0K&qgd>r+g~PK3 z#v=IcE%D;7^%*#*AYGPkbD<}=_HAvtcHsm_=k(z+bLa-CUa|`Z*+M|QM?j()H#+b8 zuFX)F`f8{aiF;(g-<$jveLzx>8_Zkvn)-O(M(Ws#kzZNorruxG9N_2Gme0EjuzCO3 z)+RUn8xL7)T4%jUX~g9HAkX`h?`#Fl^LELntd5Lf5gyTtOWj+MjQ6E=1z{xKnNtbE zXuM_4b?D^6ykF;^?XQM;D{gEMzX0>raL#iIzKVmm+=ecQWq5)tV{QCU$pna)j&$LW z>jn%2+(Pr|5TMy`ced{!I`6^XN2gyjvq9=eoKKyBUegD3-iy~abg+J=KHl$;I(}i~ zC+n2*Q+I&_wFj1;)^IQ?)?_cr%Y$8m4)%>l>m>pcNFa>b<;>v{kf z>wDxW9}GBK`AX{oolxiXI~#Y2Zm;2h*pRp~Td!NcTAfkeU> z{6-y9fBcB$02>BYJ04|X(!v5GWxG#vTW1gSzE5G{aTj(Ey4f3HsC!F{=9gHRmz34f zx;A!YV9wGGQjLsvuGxhE(h|$jIJgmw_sx%XGovtXm0qzc^)PQby7(#&nD^>sJk}vW z@DB31@Cw^fZ;%+KCb=zW0!ZeTNpha+0h(Q6^End1AX)#+fhZ1i-hLJbyH160KRPAC2(4*FrqSzqVs4WQZS$j=cIAjP!GX27Bch;CvqIaL%4&aj{8 z%5_5Ly(fNjq)CedI*r6hzZ<++<&DnUyw<2IE`$1b>mqfSVdVFn_Z0@`dQ$h6 z!$nA<@jg}0n6&}s-PFr`st)Ge7p16YAc3+v`;Iq$=v;{RF8)5hFjQTT#q+LpeaGne36XZP>gMm=c`)VBR5T zb6N(P9;5zT{@KHy`ItHxtU&X;ac3#31Ml!h{BYL4^Z!48{?z;nc>dQS>p?{q9slV; zjw^WN(0b5U*?lfY;Q?t)LEXwmxCa51M7o!759)rz-N1C(L_9)86j^%$qy6 zLnRI7eJ+bTD2W*!29lSe;v0(9Q@ zwjB`6nB|20k+?Rs<3&;-=)4_0-v*4;P#^C~qz*fb{EUaIQ|F#?0MA`K+P_t?c{A;J zndSoXF1qOzNXLWyfHYm7)Lfg^Et=;|X&p?q`sRxx(ZnxEX_E0SRFrik@ebQuE{n!{ zP%r0oEX@1n)w+)m%v*KdUP1%r{X28US?W0sI{T`=maxwk{Nz&|aW|a++#d3hgadeB z9bhfC)guI)$Kh2gr;nj_Z<|^B=P3{;l!U|unyszj=0)eN-P|*0)JA>0Es#1iG4h*e zdB<9Ki4&ZU?@DUhgv~puJeR$V9uH|H%x&TJ!tUO3x(*%X7PS9@bc0=#)lo3@dcF1V zQuo#%H#nbnh{zlFSYUexe0ggw;F?5c9u8U~vCK~3 zjt`LPeCM5II{|Lw1+lWU1%uDdKEYeAJEQWhJj8tRYYZpUkHnR1Ns{pS zc?@+CzVP`zH}4zj<6Vx_k%o~UKBMaLKr;tejo&A__+Q|Cms3%?T(BAS=R(??Tn#Y6 z@r|(3{D5@i1Z8#P9N5r$I&SImmO2^lye|^RNWAUEbT*^$cIj8rt%iBm)xU(u&)$Me zQ~M5j;2=DQ^0kzeK7davdRcABP^Z7P9@1JTHd8Y`}$9o%6$1FyE?wc8Ig>Y~Jmj1B^MD|7n_?LT{KNMRjm>nxSv+gtuU|0gv#D*h|HgWN^dgGwWEnMplp zQjl>wS`P}SigkaTP@>g&UU=mrc!{00-(|2Jz6Yt9u%+N9OBCc}_iXvxT7TfM>jmzK z&;;$RKP&@CFg=f*&0}_6u`0VTK zi!?tVX;N6nt`g4A{eeq6NL@1CB|&4pB;JLFFO<-Dvs7COeusJAV90TQ2=i`NXrC#A z?;xFA?wK9Y5ebDio8!xW`++Pr-FI%16X09j^txEDUhs2pIjg+SAEaJ~5;i&5km2N;Auk+9wso41;M zz1^ZQ9x^TCbxR{)pCHjODBWf&zD)DHDXpVpmu&0#zfX|vB;$Qc@No%=_l+G{ifFup zT&!4G;2k6@q5OFh%$w0vI`t3yc*|7fyypR2BqY!?8mcwm2O{ZKj5BSW0NW-%TzIG1 z3*HSbuA8zA0jRxa(-ascQDg?BsY~s(8MduyZ{$_ZbiyL}?#N8d!n+Uk) zhTgq1BIQKbMNwCS|E=wzKT^jmMt%u_Z$nE9;byNEcx9`U0 zUAr$RrcDA53GB0RG?c>Ld(#aWBy8iCp#9Cs7s~2LUG|`p<@Uel|Npc%YW@X0|Lc+U zpgWz>g~T4D$Q9$n>*7R*)`O%uHl4792c+I_hvi$~9^`Lj!m$^A#ZD4`NcWB>(GVBM zUbe`OK0wgt`|sq*aS+gQ$7wq01z?TnbS|3;0^ed-oMd;P&;Ku*;^%KB^FX6WoagUM zWBskiQJ0eSp9P1$t5RPN!XtI?V&oU6A9MCi5eEof?=O*-i`|2EH5r6^+4VrpwdN5E zK~GVCE+l$yZE6MeAMc|19VD+EWpx}BDYfV>&mavRMB|H#oaod1oJ*oTKxVo%=@^O(3B_4JLy9E$Nd`7(7;%`#Fb88 zu#o>#tAP=|y@mJwkBluZfXSG9p;KKDI4;j(ds+*92g#Rdi4&*ifn1O{`WM$v^fRDe zz3r2TTQFCrKHfY?9e9lVczY5)ZcF0;9n!eNo|mwBAH8(TFOJXyjXMo{@7#lZKq_}2 z@r=4Q?cd&#c#yI>(vI4O{rR?ZK)Q#F_wCg;)k)pkRd!Oh1<9W|{KEL}P*4?_huZwTjUe{i0?-L0A@K(C;{z@zS_SR<8LIyAz z0euLO7v}Ns0rj!|yMmZzftG54rtI%`VAHLkWuM+aVA~-ZYRiPoTUKL7@N@$wWQm)X zVVJgFDj)gw)}b+wY;%1%=p0~cAiaHW+OFMnG-}K^2?Te1XlT@|RfdSztY!%dFY<4hW3)-03|K3`DK1 z?j8t3UYx{uQ~9NRQqRcW*IUCNdvy6(N7#YQ*KS+(O+tUjJ|ZkMF%m`YXJG zJV;Q39!51?#P|Pu)2wKbYS4in=TpZL;TNRs*&h4~u0eHO8*i(@E6AgM92Z|$L_tr_ zX!;)a@C4ZveT;ja&j2&Ym8l%pPH;hc|E-jw5Rjpp$leg?0U`ZtZYphx`c}mY;pfR= z9+)h6dLcFf^Mbbver1y0E%p*z9#bgsO>wQyY%1Ue->hzKvu;PPK{S$`m{g57(2;`~ z=bD(B5PvTCpD%}d?P1y*r^vnr(G!`+6{q~+v+-*?NCpJFA6VSkh3BnxMwteQHy?A! ztzR&2>l~r>moV?)yMq>)@a?VdgU(SNGm#J*%S~IEVJ}eg#N9Hzbq1UXRA&P_JHhQ$ zyK?v85a8H;ujY{pGH(gVs=f+yUg$V(UcRSLmMlQ#edyPxVT$vl$6E}ShdxSt&Vm(h zzIJng!NHY}zn`P?PEB#VO|AI`>TjZY6j6bGi4D`-=NHVzN%p+M)QHQ2e()ZHVbxlL zbbx^O{a>xe@VsCC9;ZU$?K~Cb!VRw=DRR$A5%PYJJ)SVX7zuIRzZy*6-~~7@AKHrT zngJ)fTep;RcY^D!+UkkwA>jEXgSqa*?ugYpCUEk`sbC)HDQ;e8-ZJmQ5>Lb`6@K90 zp0^^T$2%IAM-WPUfu;ugc{;fOx8N^cl?Uj&gI`rVpDK9+h4k*#mh?v7L6SE$=sbTZ zmh5@c8WNX>!raG>3t?-#_Y?50>X>+g=grdgkP?aa7e!Y#1(>%HHa_?TLG|XT*w>u6 z5((MsQ$5;N8)ZS^H|EPDfOlKbN5!CfcL$N4o!I8uNW3NLz76hz zdAFZE-u`Fr4Zk>1-)ObGjERD3$7#1S#(RN#Rb49!lQZB;ZGM;k>xRfXe{=TtXMJ2yJZ_#&(sAldv>u4nyCnHzjkP-I_5W9Jc@&_;S3A(qV(Z8a zL~5JP8vZx--dc8V8GESTj`(xIuf16f)D((k_LBYPMEXJE@~9PD7dPu)@bCG5JOEPu z3fCYLf*Mp;b!P1aX@BF&dq$PJPnUul^p3BEx(9G8bKN_?i;)-?M)xIu~4mBSbctQHy>hg}%##+i2L zEd4W=100R0H3)N@>BsLpd$M0aVjdBhN2+z@`oFi>jR|-|Tctbjm)O>`V(@#oFqo5e zo)`xB>oGf@<2G*2?ym6nmsHbT<6+(@ihJ4q@OB9{lTyxC(GqevHLZI#2CAubKajk` z0q`D=oD(gY0S|T=)atT#f&DK>o_TBw2Dh>0A-vC#`~TXG&r=~DQ zh`+|2k$e1HJ4o*mTZ7AEJ4$>PjSnv?$#a8`T-GwZ^XMx`-4n}E+g944@*H*1X>Rle z2_y2Rz54zf`SX55TpoI!m!yJn)*7Tk1iWjRAMeBS{uMrpMdF>G9&_yq%=<1^o_jOQ zTd-wd@z3im*|Kk5&Mc3Hlmlg~JI0-WSszvR(efD}$4USB(qtz%Ga;=xBNPITOTBgq z+3pD;RVnI>-w&Qe@Im-_A^W8J3gP22Nb{-2q$XdfkzW5#iOb{HhyNU((6x@5(i_~s zV{5`d(MNRNpz)P1EzcXMR&>C;QEz} zm;QQONqW3RaCvB;#CLgRAd%mUA2{Br45ArD=k3ZOBF_)=?#-mL5lA4Sdb@375BZ5D z|LW~TWFECY_8xZU{=?glfcK+I!cXzMQ+9^aA@LTrnW}Grd21vcl>Eb6Q&R4;8hpH^ zciX*SlgcP)XnaU<;*2}sZCiObUONM#3Ysi_XLf={iuci{!a_lHd!IsI9Ww82%g@26 zJRfu)H*a_EWK&8IGVh~}+a2BVNsqS%E)O%5_)aV-zF*Gf2b>bv8%F<)y*JJSIz?{W zZHQMj{MD{It~<(ab2{1cen(^;6eiB??;0=v+yCPMkn&f!23Zi)plAA)!T1_fvTGX$ zQVn8AxN(FMu0h8Q3S`>h8boRMb?n#`6|GAaJ=^c@ii1i_8-8FyY(YwsSmGw184z=$ zB2SjK8||+rM0Ni}cL606F--G;OTC>e*mLI~;tNng6RO>u)|8MWn)seZK^cti^ zTpl(k@wwOW)ysr(gLU?*wO4h}`+tfe#jBa2?a-)#n1`P_`Uj+O`L{9%vmGJ(8uU4m zxIC1?6Z3B-tgRr;33xY(X0_pYZ_Q_5N8(-6-DJxT^G@47@RGs7^;zZe_ncY!E-0+@qUTRV+tj{T3HIgj4o~f?8F|$siO0qbPx5bfO#`U zPfOVvp!3E^oZYoG+llOXW0Z)@W7o!Qxh`ufNHYT7PnSy9J|OMS-CIuGAyy>b3g5q8 zQ-XPqsGWG!3iEE2OZ46Y^A_#)VW*gih1l3`40b2m0=HYLHd;|LfWqT$hWWiNpv!dF zTtg@j9QG;B)tEu%eL`CKIp2PM$QU>Q)~UKctGAC$ktZ-B*Lm zyV%m*u-}gKc&p;_C`5_R)PjfiMKl*UU3Oc!o&}w^-KgE-6wEv7`I5Z|6A{n<|ETDt z_n9So-WbMPMCIYU^7Fh;-rC~iFahuS{Eeb`-qs=^%t*Y2G@Ki(VcyT&TJ2uLytkk2 zes2QvW=W1PKPnRo9U8Zd$eFhTQgLJ5l9@9gBm1MbibEIRZs>b1rxOIipymUQUm@?k zwJ<#8Wzpw{PUGgaCz@o+Q6cyLuak`I?~all?zM9|0m_P|DV|4{{JXJ z4QkejUVH!lpB3aQnN561HK_K=zF#Q`Wm*cf(=Xq`HOP~(#r+n%f*iG;EpM)jhpO}* ze4AN13IeFdqpSDK0PhC}7azXv2ER@#HZs2O1COe)#dTj?5qFR#5;P3g9TbG{^E{k6 z>IG(zFR}Z79G>(3CWiR;{gdzi@Hb<)Jocc(#}ysOM4Qb8>KP7a&BUSCAhX`g3gxr# z{y)XK`JO9{s5R)=m&)j!-4kU04$^XW;_~Q{cRLi8x^{`RCg9z~9XE=<#OhuB&4a{S z``Jg2>oD)j4G)f%*T_$Z$^=M+q&2;tJ4ZX_<4J--nV>Ehs^uZ47N>*lJqXIHn==;P~vN& zH~rD}g$r!v@DJ-hgU&md{dA8E%scA(m!c2>BAy_P?5i;Tv_ST}F;qn65i6sn^!Ip+ z6#?&;L!SfjyfaU>a3k?9{(frZG0dAae(F#M%=;zfNqsK(?(O~~f!-?e@sRfJ(#D`n z8_?Y9T71}I2JCj7<1;(m4d(WhC9n(mgVQF|PpSU{@1;2IJ?sqv5PqJK!7JYN7m;~a zWIW9rV<$b{i?}>)pv33T;uIPBh6_YGyWFq$Lg)Qx=IW$TKs)qnjJbJp4mxk9GpzG^ zQ_f_+f?O?RAu10p+V**a?6vBBgn;)8=$9v+H&5twE+pPU&-1h1!n}R1+&cdT=53HK zclapG`+$fUR<9!t@)2iO=H{^l?9PQFG{xt!*=dlQg(ZwqfUZIdKD-rI0_sH4O;2yVpAYH)*_nm<3-IivFy z332?i7v|0UBKlWC77=%EmD68*4ESGg_f{;8xIA_j(8&C)-j)QspGU}b;(0%obK^wf z-E~jnU zACS&Hn&mHiBLOme7$oVo=?K`Rr8gZXI0H^-RaI-H_W+aOBNfIceF4WwiO$PT$PH3; z&U@#l%YqO)Zr(QWX1@hD}-h1+wE>yuvpkI%ytCBAsm=r`s$oWL}B;1Wv{dJXy& zH5NlP*9I-W>bYEh9eoE0Grd(OUt5dpSCE(~;_~p^z*=|*{tQx>_b~$A?F_nhc;2TE zeicIEZRs-fQ3d9GNHKh%6Xvbryv!v9^X8VdIHd2I0B!c3EQ#|y0xIP#*>t34z=Y1M z&Z1in@O-(aVN0Mdh<)wVwQ~b9?=!p17AI~BLil;CZWpcFrIC53{BnKWXFz(q@p&Ym z#Aop)j6>xl7s%l;?l6Ch&O21`%kJ;G?NHf@9;crt`U%qRRQKCSS8B+fw^bT(c?7S& zG}V>3_Ie9D0^Y5?LiTvxZi>$Zk$C6Yf2!4kdCRhM@crT4`Sw%SgFF>2n)^-FK@tg2 z@T;LW3Y|xQl9kk)y21>&A(#8wW_J&WV}D9>UD_AC5e>0DBaZwADNY9wC!XVi&|BO* zpr7m#0l%3-CJGe z!xOi%?vOq2GeqVgqV0Zc%isRrmVo!`;)6qY-s5pu0!X|wTev>h!MtxK>KeU=dB+dN zK2nBx*G0=QV_VKbFMiYNx;t8df>n81VYL~+_I`bQi*OGJaQ`~-%g7ga$I*`3OCs|Y zyqD);D=G;2;pTnaHorCX05b0kBX)_8Hl)X!AD72Dl=y^F51A>`a)EKH3uEzj(5ttv z*_jajJ?)Tc@y_1|3ZA0!#-!a7j{I6p_PmMCW6y&I*}wh24FT_#FlHG%?`m&nek9&s z8?BE7!MtZ)iJyH3^LAamEf@~>|1!f?%cmXBLZ9sIw*OGF1|Kv}8dHE7kkI{h;QN1klxAceSnt8(l&^T_Mhi~N8--*b)4{_>?& zjQY-xpk7WO-Vyy%JqMjP79jk{zSw9pjj z?(h+anQMh&BWx)I+|XB$JiERHc#86q{UugvH*tAfRHqEwUbxo(I}-5jq*~y{^FDp> zvjh_FF1k}iPhsAgb4TCz!n}D3g}a(y-dD4)_9(R{LUB8pi_3N!10H>;tHsOH!0TmS zDKpcs;_Ktb+9+)?y!6Mxs-lx6!9XG=bQl{2uq50`VNGtNWvSZv~ zFyCBz0#M9=Z+@KH*=c$~S^B{d(G9+!ybJv7@c#C(JCw_)`3+?pS)&uk2Rkx|+ zG0fZOn^;qYP$Fde6?_RbGzWBLa=|0m8PI&n+GF<~^Vj zP*TPt3{l|bmD5TxPCZ2Cy(&I^xb7n9@$Sdvv5XSmR+SqY-K#jk>aOvm=y~)83F`By zSITaK{4-SSMdZ+V7hTNix7x-;_6?H!CF1fplQPb>FKdmr0|D<2?-&2{|8mThqDZ_M zbeDPQ;Qn9d3%hqW%p1S=MoX;}*m^wy@(pEN7-&2K0#*tvb2w(eWzIYKdmr|IFz#Bq zoMd0HaZizee+n{h4No%+#f%W7h?|!e$J<$(hs=AEj-T17d!)yED=v=>DDl~Of8;$b z3g6!HmU`VchR%C$B!%Zun78elixLSF4d}PGm|e!{gRhbQ{y!6uc`%ky$-|2iX1Ix= zp}2-&7H80=v!{-Nzy0?=r1lel`~Q;!HE2Le;357J%NNNZhg5?~QoX!)!k5^D+jjSc z;2Naxky7_Uwu+WZS?-dJMG_QNAJ=o~mJA5}yzy>z!!)>JwG_%g)dxBSdQNgH`T!4! z8=a9^$Tetu<9czLa1rPvZXWfQC>?VaU&McFd2`--zI+pfNbScviOVA!CBA@xtlq>0 z4zP^*pfkN6eFb?@#UMVSq!oHiqo8NUir)WYc-(&O{4GfSD@bDVpc-7S{I@}JBjDYS zVGhFc9=bUpgTxyv?Ym?O^WK+kIXnpSe*D7caYv4dR?3{Sh=O?%ly~S!`<5zIP?CA* z!ReN1z`LA0I5N-+?)3)mdZp$ACP%ZH&X^(dmR+lD#Zu-*rex7e%; z=OPp7U1H^Mc?hD!cQoynd=bO}ZtkV{GQJ6&cY5ukua!J)(9%nGy|9hwD@YOTubjJO zvdEry;x6LyD7LLr();@asVf2R-scvMc;38Cx7Q=_&Po+H<_7aFnzUg1!@F$Pi|2M1 zRJ87l=VhvxB|)}SC2yxfwSa3M#YKbn(_pJtYp&VDUf_Q?NJaCY4{)$QVXUly%saN} zeb7+}5y%cVZ{<;H{HIuC-tN0iBTtBu9&dae&M5IUhB~$$<>dtFf~pxlis-y0sEr!3 zVcu6SW!v4EB4P!3*@$gI?h@Ja#^e#1$7YpV(toSB3jyz*)D7qGyce#7OC#}?s7)9T zhk0kV*JusEyk*QIzqsbAXcgp&mPD8)K`+c+44kvr1NuIld%H3)4c>=`nXb#~1zQ&y zmZad%1r(DMYsbnW^XBBqF=hHG42j_8x!swLPBcO0UC(4xRj)>Ryg6`rJVJ@jcjwnq z> z|D6eVciVGI;dzhI9$bgSn|8r6CL89xvY_wX5A%NX?lY%4ygAV*#}K3p^VZ5gpx57Y z5GZ6Vwj@kU1Dk&AMmg_Za5E!c^-h5g5D(GStky#2t=x3?a>#pONEA1(^R`^WPjzJ8 zA{#mG(;Jc=Z+sqnDDl0FU49UAfD;5~rd97FV()Dydx%gL%sYgAxY}O(J!&ZE*I`iro4uH!(HZ;_MxBue{ycrZMc6c*{>k4CKH#3tBa`Rk(9Lq z(q06-M?R(h^YNBvmfkBO@#Yn{eR&$@y+ucYwqj@o`4aoWTG4&)W>F{$H}64*{@x=~ z$hWsdEHMM?tx1n}GcFGq20K0o z1|ON+tVMgS=(Qp9{1(Phe}D0 z_Y^J=!owdVBT>rk0lJlyrk| zOVKFg`+gLecL*iV6zdS_@s7jg;e!(2_veo{1{ZJuUyR$aQEPPG65T@8+u^;p=j$lv zwjMyQ-rxMaj-}|akv;E>0OImU@{7+ftp4}>|Np(=Cb9n(?*9V_YS1U~*Z;i#k1?M@ z4XFnG(2pE(Ur;Xj-1BG;f(9}eF>Aua}S;pS;RYF#+=47vYbR`+wTjuaue z{r@mr9!n_kRoW@F>$q|N>I3z>R|Ofh(3I?LD8Cf>;T6OZ9Q`C-2)+Lwkg$n+5l;U7 zzkwKWd6YjMbNCpu*8lqx@SYsMUx>fNI=^e%jKo{fe|TdA%-d<+(|Ho+ZRc?>rVr+A zbHK5#TC`5~!#}MGyL%kE3x50bwtJBX(k9P(xkG&}Ijj~K0 z-28}T@Ae92SH;3J7f}qX4^UO==4bsmRC$7XCaItN71kP z15m7(qQtBCX}~`ALZJI|ABgzPp_H!d4b=RmTxI{m<1N zcovHbq7W5so_Bm5bABo^?;;hIw+RxY*Z<4l^0Ic zn}t7Xh7NVK7hV4R0&!3BpEdj~6-hd_TJqojze8LeIl1?O_29d=|DONIKBZQ6dKn9e zsoZ(c(`5tAzyI=5asM>XzwduPW3V6i{IJw$Df0wDK00mXrpOOSOSkFPm5GT#0l0a} z>G@CQs*!6@^?^Jw)o(&1*Z<4n@~A?IuktaQ<6gKyQoO0>t)7V9An`YBTGU$C1m&|> zM4Jns_y0P}A7!pCsFD38R`MHhc??JouV_ZC_5UFRyk`fKRq&Tsqw*&jNW6o--JRxv zd1rTz&QHU<1-5v4N5Z`CJKGqXT#bc3H_EYrk)u%Uc{wvqlW7p_B(j=Z-w$M$ek8KAO;QN<{bHas5lPK}E`)*EH z8DRrh4)5H=Gw8f`eN?JC4fFo4o|GopiQfNXu4l~GD3E{uk0~N9kA6S*N5B4_{|_eM zJySZgi04helCl+vcYc`wwLHvwUVf484{zP``zd2!-k(gIedaXdptjMsHeai)p}b!f z)l)~NL9%nvvDCtTU~y1`M(eRBNbTKeo4V+X$Z=f$lt9BrQ78pB@4k=Tqjm{o-VD46 z=NeT>kM}e#4|&(4s>lV=a|AMI^&v&L} zWM92UJ`tBkt8_suSNdB2A4I@=I{3#wFDI(hJ-!8rcf_^q%{yV9Z-0IU5&eG-XG5aM|n?J$4A@DUO3FfW;K6@&#I}XatxYoGgyd`uv@b&o!*J;oq`$9X^u^;f4 zpUQIC8#SK~dj%yp^En;uB%=RMmn%t~P$m1vTQEfCF+#t=CH%s_ z{Xgk8{RELkA4#Jis6k(;W)I-|{|0{(TBI7}z|qNkA+Agd`o1}F0j@#sTHl>gfKQN0 zKiKhP5X3^ICjF&~KaWFP3^y)YNKb>jmqAzeog9FlkUYLg(#sQ6abz3MT|urv&xWEl zDa?vNcX0Du><#Bd$zBy#~vMlaa{0-3y+vroR(|cH!o+T`+IzID^bv^hSqQgbeBN_QvHQ zgc6@jgSyeVKz7g+5YiU=0iE~M^nS<4fEQ48aj-~B2oWnt{}%IROL?;AjqxEe4+r0M z!#3Q1KHlOC0q?~tj%$y%{JDE;Cp1Te#QViJD$}Ph@4`DFrJrHmwTsgNn_=Egw5?j5 zfw9nq;neMl&h}7H#Idbio2P+B_?CDF^#QPHi!lA}VNc*dnYnf45c2+ikwNw9x_U9_ z7;c`^C*|OjkI1|m+1q{H_LCm(o47olpv32NPRJnLh#goJhO=FGhR)kYMsMs?@=K@@ zgf3g_px?d4oXGnb(O*UWyotl3I$mKfAhfhCZonLwx2I~?lj2KakN|F8IIrLK_GDz< z4zIlhX5n{r68c(t18Wm28rnZ zqx-H=w%j5A{r@Q9^2qCvt&4d4Z~sp!{|^3R9B_j~OHhM;GM@CtUt+yV^qG)q&;}Fz zi)wHU8r&D8`wgx^;rml4YTtVLsgd5uaIkyxqPy(fSd$$9yc#{)9EF1w?M>8$uyg(lHM5U)gVh;9+N2X znOe@ZZvDjuL=4Zl3~pu8`j5Xe_z&C5Px$mCG(xlXnir|*h4;pp(Sq zkxK1z>i)I0{-1_`_ezV#+DGjExx~hdi7+DZHdDN|R}bd>a^cS5uQ2Z^lQVUn;1y&o zze61TcnmaDZn;COz!}Oaod535I1L80dohA-1E8X$hU;{PC+MH&I5*UZ%v*hAuI{ja z1oR#^uSG@Gs&+RrZ?7K%4BI(K?*!>qTplM;;#=3`(7UY54h9mw76mAw^R60h3{pGS z2)+B6es^Fi`u=~I_a!O&Y!0$-kitBP%R{4S(1g2ejW;y`@9*i7*YMTb-hK#+#5;K- z9qUn;cXLYa@h>p%by{}oW8k~D{5xXjyA@-huXjdYTbG`IhWeF1cd$=`rPDsyPpbz& zk;1ew{2A;ZYc61$7A5itQX}1Cw>=pppj6yEQyv*FMipely|45MF z;jiI;?%q-n@Lo=?$;0zzfBT9ai8oeoo24hr`}e(+h$RBvVdh*iTFK&20&db4+(VM81G8^ zP<4K?=Z$eEGLPK->$4sH+`UbsB;fr`RqLO#w^Jvh>5zCEoo|ndhIv1v6*;{~!29{9 zxLdbmW1-axw+3Y}j?nCd3geri(}1c@Smayu0FW9g9#wYr1e9sdfoL6DX=u9Rqbms2zC$D1}#7K0JKf+D>Bl^m)L`QXzWL^6438gf9IVl?tz2{ zkXMkgH`N|k8k1fPGQ{N(g%aOw?E0QsJ2qhaO!OW{GJEMdDSuah9f>zpRQ>2U%vD1=G9>%{U!2H1qA#&jJ0|^kyd@3$U%V}TXBa=n z^R9K6U`66BxhE3y1Ll3&<*e8W%)4^e4#nJaDq88~?HpI?qoE(`ICTtEyrEl7=`CIh zQ(&Mm*2hb35Om3;wq2ux&;S3zepcZ{=A9W+4|U9mL-DwICL!}>OMb|_S5BKy+`d72 zyt8n5d_{>bT~;cG-Wh%(D6uwr(jJ|6B!_QwAIw|p*7PYaZS=dh7_W4?`Kt%Wo;Svu zxIFBlnQZOy*KTjo6YyR=+FOk0%}a5E1&O!MjZLN}XhiidL4{ z?~bbnVj%nG18-8NJfNG0tnTevo&tI_rYFyE4}uA+>a%CEJ%P6FpcNAa`S#Y)6CoKE zh7yn_Zr*oUVT|NFGVh0lZHJk1Nw5F6#pO|j5})fjslDRg*}yBq+xu#b(RmyDaet>; z-v}M>zkV}28@)k#p!(bFx0edpFHSBh6PE{8=7R72oHgEb1iXLA4j#kvey!!tjKupx z;v7a2=6zFEZObyuyM5!%lrETej)6hnY(Nb3^yZnUOET_|>sF(Rg4HP?Y7@;8zd8UW zv;2=W7kYxC9UE+#hmfnc_pu*U5gHOu9&Vnd0qt)3Qe@t5e(dx8^@#L%`{MF=jS`=A z-h;#6wy}fxep&ao`_Os2sO~%wqXbI z;r?IBy=wEjlYph_$MmC1$h@K4dfu2f;t(BfUUkmkZhlK--cfc2<^?OH$GaYvMZ{d=R{5wdTPILe93Lu*}+ zW6$6IpM`)oO|-Zwp7#lcHf|)|ylF-8SupQ!G2?W<;T2@=mm%jVnD@Sk?CKb76yz;v z87<};06}x*8S3w+K=X2Z`pmgOAhD@!PXFUcz|VR?t0^3rH&3~peOIG6#DSZ)A|~c! z#E;B7@cM1rA7X+eSH1agdHAEm_d1~LQ14|{@GzwEs#*&=@BHV@nhneK(4+3+n+v@} zRPX*wQ}GNtvgeKIB`y!9YX6XLg=-BGGXZaE{|#z*-eHJ;cz1vc>VbFhUD0*8)$>DTz&!34LM z&7mY@-eGj}<0l@%Z@I(G`=LYCw&NS}2C3Fo5fG|Rdb}fWdF()mPk(QU7b6cFn8}lu zxcvZ~chg<-D-Ik_q5ig~cS4qlXpnphL{3LSWY4?Glej$mSkweDp=-RE2zXN|ROjP) zv+eWaMB;re>SlC zFb`g>pmiPuhYwk>s>*l(>Ikh`{VN9K#9-mj!KwDAsf(Fpt~@B1D*G2pGB=3Fz*ZFYM+*hh&bL-)TQPTr$_#4 z@2f=Sv3ljnzx_WEy*DXLf%|`Mf*Qo!l`4m?K@*9xB1km|!^-iT39dn=Vy*17aDx=t z_cl;58b1F&I=ud#Uj(H2UU#(pa3I8Z=8@yx+fyKs-9ZCOKLl=L)K(Sv-9V)OXK(6L zPKY%_lma?uOe+DM!Odf@T<2nFgIt3ox_DGx_wytEegD6H)Ka)S#8Kkob$nZ+@5=@# zH}x~=>}A$Mi?{z~+(pa@c$e+cI=#b1M64k75}yPmb&!1x3L`R)iUUsVoj2Alv0Mba znFDDRr@^xq50-t zO;@U>K(a%4VCt_yAoJ;Mf&!l#5Se)2k$w=FcbqOne3C6h67Xh>j92_{fRz>E$k@hxK z-E(mW;O6x&76XHB`5+fW&)Ikn6-A znD?)DKdGo--cLR`EF6x3Urx-;X8d(L0$Ms;JYZQ82weyd;n`O|1!CCM&ii)3n-fLR zESL&6aO&RC*og^b-c7PKN$%z1P!Mk3@_ELxCSBy}Exi5OfhJ1QyL;P;%L6UGvwnsT zQ}WmVo&BM-F>Z9;`O-k{i;T!PohL*bZ_y0(4-a`u_PoQ0%tPvap{!}iTJ>fp z;Em-|a=`P(%Aepz;vGG|i}MJ~o1Rgaf)eI^N6EeJ3(ULD>zGB1U?kL6=efkz6bL!T zxAZ4Hn*xUKIHqZy4T5dP3YQw+xdFA}JSEyWWZw2lkB{|dibI=l^D5e~bmt_Id8eCo zd>7*HJEJka9vJ%9Swr6D%(J@sd}2@N`L`?I!c*6`ljrwB?0aVvD*R`(@0c2y~p z{rmr35Sd5eLZOcme0%HP^Z#gF90~k6-2V#@)F94hTj%jLC{>473aJL&x$tnTGzLCF znyjPB2-hH|;hc;0a1ELcEx*=*iGU2-`_hw&{2^?wC(nlLDNuJ}BxQ8-5SU;$jw^C; z10`ENYTrDAe2ZP%dv#&kkOXucH}C8xkpn%LV1V=!+cuJsoy<*oHAn}S2U>j5{t6vw zob2Gx$nE^0^XN55x>`ZIqPPwc@%3b0c>D_S=Ys!vUA>qQF!^zo?E8NMBJ;4!7<_CW zy>>vFpMW<|g^w1VdFv{~NsT>UY@b=ArlhpWi9l{A?d3 zd)^I1=0W{@+N^u+1?g#g1iaZ@W%cm9hacC7Bk@-DQCi;t^X`2;DvgDC$DRHVstEHw zmgF0kt{efm<))TQng>8kqZ9RZ`BQ)^PfycLatQ2>o2Z*-aRZenv2DUp$h_Abd{v-Y zApzaS&2zjWH(A|@yn@`u7FuhqL3+GpaCxA`*VI%NZxg}>eqWU{ZB0P0-cNTrh<}8u zH~dk#k9P?W(f>OfJ+RrGO^)nh|pKuK#&(Yq=@u@&16zqYfp$Z`5Dh zf>hbS-XC|eIi1jXAJ2XNoRO~{TDU=%)K-PwAYnFzmX7T{N%s9ev3XcA=}I#EeK`>i z0dH1Xc4vI`?wvCdMdJNpm>;tO^Zpd=#!CnD#_zrH-^w^iSMONZJlfY8(5l%S~W06=Y7&?!>@+p_0U7p(_Y>BMDX6ITzW*omh7u{ z7?F8Ij?Ne9z#mTZZ~u?)zDW2h-2aOb)FA%;q+R$L#5^r7hg5^sB~;ws57!{!ErkJW za1FZfH8O1sUP01UPy2oj4Tq@DNuLfs=Lc=C_?ddJ5~Kt#K!TTywwiyO$*wPeGS4W6PZWD%xLei zwe$ZX1ibmuH1^~ak=4CAvj*4wU zzQi6pS3ec>lk|8S;_@&=iH~NV)$7SfR&Z@r&fj?$optdf?z4e0z6lNMdoD!qUWDnz(`T@&F6K|NJPad==@rf4EVq$dJz{7QWocmkQc~>f~>w8xA7|I!4-L-y&h}&Bu{3buI*pfYO z%n*@zur6Q19d8jN;LXkYOc2joyuxT55^t>4Ez$EZZ+SH~Ehd1V?hO8(G-rlIwVGGn?nO4Z+^LlQ$2CWadZQKbz|9@j+&OR5xaHzxh$i~kp{*dEQrO9RY zDImAus9ize5J=xUBKSzk1!(h@r9MtazQnTb{>{uHEeUPM&C7erwtcl0xdx@*%5B{c zM|uqsJ1&n5l=x(4C5?in*g&LO+lEv%7A-U|`Yqbm%Ff=0qOfY;xpmR+LFSpB*>xOR zNA@*nvpI2jJl#G?Hy*dvAW0JN7O6b&&ntG?kFP2s@orZ>rHp|uv0g#ix4B^69(z)x zFT=d0l&zT_%7jA;@#V9ZPx?bFT&oXbyr;mPS04iJc@KfCKvnxYLM~uWPt{TT6Ue;T zW7T3ysU#sC+&qCTNlTA>k$H>lWN!KyOM1LHaCu0e#HThEk;*K^4o=nQsr_D$&O1w5Rep0|Jnae3Uhpx9^> zvvzt*oPf8G4E=pP?~9%x@<_bzYt&gu!@Rp?$J01q-tp|?uD@d8x3^ePOiSp8L+Zcz zjgN8oL+WikZg+yFz`}`ppYNX-0@VBH&?elx=kL-z zUVcID|1~}v#VnSR9&dkK9-1iewN+!;^Zz%9%p*GWg@6?NaN@uHKUx<@0)Gzo z|FQ%%Xx)9z&G<`fVhNoZQVp8ZdwBUA-2bm+XetQ8HAwb*>rPkr4N_$j>%N4234_jO z`%ZcX2SPPXhcC5RPXVKcR1{2^L!j!@en}4j7qGWZSD~*IxdzF3l~RBIDG6!g<}s}_ z8ES?hpZ~uuswy4ZLV7i511=A=_-qs}IAyuAf!FTS>Nm2`YtYT$q`soQdyqi9{FMXn z=SZVTV%fgs30HU%*>8|;Ng^%}<+x)D+R1DEzYGCysjzdlc;3uM-)=_Ytz6-LDIexN z5Xi(M0Q2s7ZQ*MS^ESK%e9M1^K~b)^_umo>g!c6>h)deRZ;*x(-lQZCfsxBzvUf#X zfM4mhY~O5T-p1VL9#4!(LY}yJy0OXp-TKJ9&#|WHeds1V-iL8{B%#FDgR#GoT>?KK zeN3g?D+--=E=x{D8_c_a^3@=d9uYf8-%x_ zFa<7_)ReKD9RgSLRCg<%a{)7!`{^Wfk#~^zcUYc!|5g(Eh@02BOMld%1(|pCTxzNC zEa~wU#N}}xCB8!H>bNQg`02P1WZ7d3$TU z^i?|-ws2_g=Zl{-WCEa>bH^-RJ5GVx-mHbQT1xRd9+)?N?=AlFQ6D;yaA>LS5Hm%*Kh&U6byeDR3VgKr&A57c2;@kO?2m^} zZyi5mAa@}QnfJ-YxZ&GXl8_y49)-l48=Vi4d0(BXnp-bHdb~Ywd7#CYeB9$;lOH?S zR_4ngun(R0L9G>6Bl+YoDd-t) zp5rzX5fi%*#6I^&>HMpjLeg77j^Oe@i?62jQtk;eb`W)IMr*1My#_gMbg(E^xeJM@ zKH5}Thkl6-Gn!k^+eQ8lNMquN%OipR(XYkZYyH0h0dG0)zVG-;tU^J91`=;ql}TY8 zm^YNUO|fI z8@7DDOnSWWd7#Bdccv_}=oLG-`8YGbr~#dK1m=o=EX@1Nwe5;ccZk>^WlL%;9yB3) z-WWY1^T-*s%Km%2Wdi|k8MdTkJnv13wp$Q+XW6}Tf_bZ6D?K6%^LC~<$m;?hZ#h0+ zdTs7w7_>L1i^aw+2-@QEiT9Y<6nJX)RA}h<$`1V$AYVzaExiIKXVOhUWb09Ry&pVr8IR#vgv+c9FFa#1d zKay3HZ~;NTMbnkvAy;qBXO>&#xuqa)+`JJjdh?`4WZprL|52I-(&N1imj_yW!W&KG zjw!*s@72esUqk1;o1s#VTjL(2J=&u^a1XtDhecmyi?aM*@ce%zae18E6-sp(e*XW@ zNufciIt=Rq>j&2NtS?v}vX-)5W=&y@VD)7^!D`N`$GVMGkyVV9gO!@)E6XHH4@)yk zEz2#I0+tMx7?wa57ZxiP0~Tc#DHa|Udgc}8Y32duHs&YHmCQxVIm~C7Lz&%~ZJ7@- z?_ySCmSGlPW@1`p`ph)K^p@!vQ#I2Krd+0T40jl=GGsBtF$6QXF&t$uWYA{V%plFc z$H0L7iJip`Vc%dIuvOS%>;-Hh_B7TLdkkxW)x~bX%3+1DELaTv0{sX2_w+C5AJUi7 zU#3r?kD&LZKS6I!uSdU)UXfmmo`as6?kn9ST@PI|T`k=$x&pckx){1ZIu|-CIs-Z_ zI%PU3IvzTD+7;Sq+5y@&+9$M?v_-Tzv}b8UY29gUX%ErvqE(}np%tKIqFJT+Ofy3B zmgX5vHO&p0T$*z?iGn5k$fc?+2>^ZY)(z^33wSN0@UVw3Ts%bVZ1V9()4xpSJH*d+YuV#|UCHW5F% zknuYbn}8pk*FU=+dlo;+sZeFX#^Xm>(+6s>arjZ@!^;?KEPj-6;gTgb20u#ATxdt@hx2w}PvA!&lC6SabZyDrrUmYla^kG3ijp zn&L;6lEdGyhw&rxg&h-E6a2_*^u!|87(X&inX|?o!jBF+{tU+&;YTKx>s7FZ_>nRF zVh#2neq{82*t_#^D!2Y&;JZXN86!hv-o}zysN0l8q$CQNZDW}$b2N%%PDmQ0A}JM8 zE1Hyuj--+ZQIayH6z|&3zR$Ja_j>Q=-oL+|y?@s^|2)2@b)D9?KF{}F>t5?#t2c2o z(Hf0x%7=~-tpMwXwDTg3HfWO3PyKr~0A^&!XZ z5!a!S`BvL0q8S>kd)4P5H-zA1yLN0D4+8a#n6cI^)qoP z8d1(6CW@jF<=9rD2pUmNxg-js5#>-oq7WKU&QK#RK_kj-Mnpk0qFnw$6hI@&T^Yp1 zXhgYMfXI(Vl#|$rd}#EzV_1n;fkuxqZd(wqqR~U2fTP56Gu7ABrUqgzYceiP54(TzbF4&oU!s=TXvgII({*E7AFh^Nu$nk&a0 zVj&t;IK+J>ox#B4Mw_I-GUn1x2?wchR^W}?wK?s;Lv3^Y3P_M{6j9gT|4 zzLq7Xp%LYVYa%ZiQ7!}~@}Lpr{!}728d0vBByyn<<#s;eA~c#e?V>>BL?c4O(`!Ty zYP4-O)Aliuh(4=qCz;(RokWcg}EoQFo^@4KCe1T-2eBuM#H7uW9+}s=u6~uKKoBJ8uB^Y&OU`kpQV~**ngnW;Ky5M*(cFx zpr+yp`ve+&%<-;dA4j8pC(lIoF*NF1<2=ni3dhL*%pM5;Wc1;4Mjrcjv}MoT9&`3@ zXw-dZa)NyXjoyb;*sy;^qb^y|8uno{dPm^e%l-w8-ag(&W*+S z1Nalf{uYfMCn&vQe}hJkEVoCpzeb~n64@>69cXlayfm8q6&lqKUG-ycN29tTRSEW& zXmsypTsV6h8i7@$zu5o!cmF>V%<|y+zXr`aNXn>&@(z-+{;$Eli4E%=gDk$Ec+BLiH|BYLt97^)T6W6t3fM&~wCYB68qya3a(1L5d$- zLsuU8hTRP&MRV)_>NLD5!*rDQ5)K(wEZ!}p=9PVrca!>2q8#MC@|%-!#y$apkEld}Yy6EeJ4}a=9YHrh_1$j7EPY=mPn8cMeEpHV$sTOpeFGJD^IT-X zVrsim_TPxQKQ`|rv*Bt3ZyAsG2WlQdIQ`4ZStQz(&Woh>*iEhA#pfOSo}l%d$hBsy2iSm|9{KA68TjQg-*AK{B zshjhg4CKB0$I~X81P#Lu)O{Yv+ zwGT2Dm84ol#^(L>mer+A=CWXz+HS?T;|_lWoA>ye(nm8N7?1Z8Y913f{o8jy`E9cU zA98B9WiN>XpSNlF=`VqD6~N7l827D)j?Y^@MdW*aGiUk*Qo?6C^N{afNj)HKB@J)N zixiaiCdUW!v3LhZ>56l}1ya$krmv(S@3&VUlZ_HJ3~!$GUeI404@RvVG(rTUfRK6a zL9g{g$g3>X@%=ZuktaU7$mcsgNYj-a1+3e!dAFSOH(jF+Hz!it%@{^4N)o{4{rU0G zI?iFnFR!n?Qfg}dypbt7Rns*Z1d>4PX{^{ILKWAo1Ltp4CC zE(>I+?f4Ym1sr6@=6xCrUDW)=c)Za(@cMUzthf%@&W8*eX&!$tj?epfd5y%Aj0$kF zs)htc{>G$nCcIBCHye zZXO>J21k%d$%Kc>umjfeq*c+q|vqnqCE@iwuNYAKw z9Kq?|q^0^~4*bMU<0CI=I0%0Pxj#iGR7dtQnA)D!6v0l%H%I|(hjx`bW&R1$%wP27 zv39qS*54mU>(KC~EcT(iXQl->v3SdQ>q{SkynO<*&nrRR9oHQzNbvO*@2W}jk%w{M zaLS%t=8}=1wZJg{vF;G^FsXMYx3wGj^xh(~(#99Dw9wu>b`X1uon`s^+;{SFU@h9N zdB?@mtkIaCw=8;88}FdVc)ZtB^WetmU)j>YYI|>9q~9!}MsFKF?`!TajvWyz1t(K& zWj%i3?;s^?U2VUo-jV4?kc3JDy7G`!Ws?c5oEt%E)9|LOUZcD}7xojec-yTy^(Yte z&JcWkND=bB=dQ)O9r6yjBC>yoGakr*!6m=_BSG}!<&?8}L&$X2lld9V-N>u=idA8D zzR1JiD}e^l*u2#`74-c@<-k2^J6W=t*1`AK)mt~Iy|Mu3^ziRp_qhB&T?-339@^G@B;duOMZiBQI z4R6YJ43szN$aYNL76yGMFGJpE-wfwUKXJGK@^-cR;j_{p9$0jgS4%&P1RY3V zQk}sN5>@@&UZSxZNlh``Ss&z!kX_m~?>UamJE8iomnR@^H)^{xX4)r;JF$7^SFYDg zwr4!v@zgv{;q-5#r|*Y-M|qKk$49sBS&h&8lCGtDA>_Tj)Aua77N0la^VtJY-5;5r zH(}-sU3o}OW~MpbOrl(Gp-ID=vcCxBJrx(Z5UYA?>sYq~$U9|eg^4`mjjp{#w_P!9 z4vz;bt)2?~P>ljN8`TrHB0~tb{sphWN8N~fRd#(>m@l%$Z1nJgBiOuG-CHWKh$siF zsqMTnw!HJchRu6H?Zfv1evHRkmzoC~PXAQxHwJKd@gd@J4{fbh;PW;+RU;GgryOvM zHSa08fj>Ag9UL62Toc6fWABw@`tlfzJKimnnECJde~dB1|IfXEHE1VVoFB0`=5(ix&A-Et!hOoFILfFVTE^ zhVg39Pih_`IQ`qYTTeT~krx?|w%y2b9=`_J^gmcOnO_V9&HwC@PsINQi7*^_>DYW5 zrmsPSuk_`S_*^1c^Y0U+3}|>$whW`ZgAQu)Ve!7{J1wjXc^8q()~$rRgLI_HJ#YjW zt>|eN*%1qL7nkcEk=YCOmG}7bsSY8IwJ+~&>FGx7Qw257zxG9>E|LlhUSso~Uia=* zYzPU6Q`@->uwPv`jLlnivO>*aDdQcn^NX5?JWl_D*Ho~2oaaT7D`%xRa`1VJJU_W` zo6H5!?td`HHVFUqmZwWz??c-%rsuuKjlMj752u7Hz)$R8_1351P1ysF^5zTg;KAY@ z5c0WoHRK)nI8j~|^4{2~dhQ*3d#gGB%^DSpIB?ll_1BsL_<{5rveL^-s*KKd91~ z$7CogWd#ZH)}!G~`KSZs9pZO}8;kernw_sVLf&V(<^h4?|?CLGU)~G{zF9(9C?KYURyq~>* z&HHktfkSi&;|)&GJj!tTCnMF)Ar!!iH2rxOQ5BER`!Xl#1z+ez;3aWq(_Jq7-CG2W zKe}$A9`wR~{F3nRRafbJcql4R6X8%mZ-LK- zYFjMizIeR+{56MA(I_TuwCMe_Q2 zQ|2<@y7z_GS`UBh&DIjfd9LUV)ANqrORetBU_1lV%mCbx(D z5c1(>VBxdjZe+A_q@44B5Avc_V>-MLy9V8>-kEs3SPnE(+m&f^53eU-KVns?S#0$a z8E+5LU1}b9{S*DNz*y%ZAJXAreCkdIehpe;nI(LB-x&}eUnbLY3;!Kt~-l z!_&kwK%BdQgsj zb!PSG^H3jzyd`AyD{t)Tox9(2n{2Ec@S?UmDmMR*TRk@Kl97+8SC23r?`&!wmvH*m zV9W#FiSQxOomSaWcky|Lwl;24J9!RVUKd){Z-LKy#%IH0ujnGC=e^gDzC5B5xOXhb zo0}jZG`uNCL!i6^&t4F~;_avDUNs7Nv#x49uK{_F^~v0M0Y7h9l^lF9|6mMYuW0Zc zdb1lu*Zww|r#ys|Ph@=mI?#>W|MpH@pTif4_r4`*!h${j*H)GOQ!^|FVyNw!Z^W7L zZ^a&*^!ls`9Fu3f36dr?kA9r~4V6AxXIH?7^wcR!8&u)*KJ>kEcOT^KHn{%YH+pVw zy=SN0y}Xd=c@ygC%wuBXg51B4w_HQRn{w6(%6pAj*kUZ+`TpBVSmFF%^-^JyI^^9s z)3!|&@>Ym64Be?13wT4Ho;2~^10Li~>awW}Aql4fJ54^q>n)}w#VAwjMX7_>i-!dn=N! z;PW=$7Wu#ruDw~e@hY$B#=pHqxQh7tP7(9J-s-BRFOS`RoJuo?{$2lPmihlWni@no z?Fp?xx|~YOFl&&9w6rsP#BLGzbl(8hpd0GMyK3+oB)5Y8C5wilz?RSPs`8-`fW2^Q zS-A8NvMqoexiQg=G|gMnYNG3dC_4w~5LRH1AfHOz{XNW10!q|&l>v7)e-^}k#9qrd z*r~OL@kWr3sd-$->EFzc0psi_KEywpTuOXhDhH`Rnmj>WsJ&1+~E%E07b`Z4yoC4vjn00tyS@OQ zcfW$`Bd0_8fP4Cq;-x%?d`a)k3@VS|JZlEt%X&FnX9-nGLDg}dMaX$H0325rmdKmNlCQk0q4d|n2u-qqAR z@cKvWOc;?E;6->`$|GFn;q!K}R?yN@IStN;eTV9Jobo=lUbJ zEw&iDde0|EyB>>Xyz0G{ng?G0>fA;}gXH-T0r5-ME=}W4kfuhT-dwo+G*~nkrn2}p z9Un+1tz0F!Esg1U6OPcChm`yh)xWp5n9%U1oS2I8o~|T|VDVP8xSw4Dc{ki%rJxIW zH;W(aEr-1M1Axj()@ZQhXSww{eS!6NM6 zj6L?Q>%UqNTqg&LsqGZ`E6ue0u*cq2H##+f4l^EaK+OZMf3a8G_e}NkBIR~@H>C#f zc`KEixFmI}2uQuzWbCDbKlUb^N=R7Obe-wf{|Tq*%R~5&bkqHl|E~XI4gMMG-^2C) z4Ky`~a%MDIgCv8cWwB}y-|HvQvk7H}t;P;%#;^v(zCRc97`}t7`}F>0R9h5iy$)2YsP@F1Aej!{-I(P^0=#Iuj_<>I zU$D<0IafMy(S`vhNJi8=&g1kifUHrp`7$5kv_@uQunhhPa&NV<#*5P_K%eEriNurm zk66vb3#R#O!c6~&-F%q7Ja)b1pNjtb{69+?-jqYoQQpxFQ_@(xC-*E@;)jpeLml;G zBgh*$Rma5wAF;7+roaBYiUM0}b}m4YBfx3LXLV~N;Q?uU?`sjrd)kaQq-`e|+3V+< zXLcEzx3Yby$)GI>L{QsB`90KoFjdwOCWEq z&&B!KQ{BkP3%aN6i^+&ngZjKtA?yhf@>pe)gDDAYqqZy7_1ss#9D9Ov;XrBrwQ$Dc zZ9vTfuYcwPx&?iee2DA2Mm<>(eBK&&QlF#qQl8-kG-_R{o_$0xr~c zYB8_Ro2X;+=F*Nb8;oK+-f7f4xN-WIG=9kbJb@qK0y*050{Fal5t1exv~$24X*Dhb zb^Pib-yoM>EKa=rPc>)KAG)5>mxuo88LJh^bG*%IcvJ3OL3y8dcap&3eYSA@S_{a# zep%F))sXim>mGh1`1ZDvJ#<)j0It1V5-XJRivYr6iEo}k-V<-!Pu!pEMg-rzsbFRI zK_31*oyq>d zs3=RgSo7lZ&aa8nRnyG@$3=g?mo>%bO?dQnZ2W5$^Uwe3&Er>6NIu-&!Ug|t%sTHp zflG?Rc%jFF{qVxe_`RV0A6v-R_sw<-<01`V=LTVCJAcs1x8H4nW08I}aKM>+E$qrS^O{iTIp zgVJv<8EpEV0Cq?k-j0c+;~gabC1tTm5#}F3^3a#ZwYZ(r*Z-dX+tBc)T&0Hc?qwNN zz~cQ&+-_whI8Z72pJjNyl+x>7<>L7k$p7h(^(Qg+jae{a4~Si=KV3C;e>=AE;O%S_!#m|Yph*t26>;pOX9f*d6yxsf;lBo;5QKA zFmZ|iDtwEJ-63yVjljYp$osq9BNNxXWJG0mL-s%;HgAC|7j&0rkpS9m!uVd%R%LA7 zT!@0@Ie*6E%}31xuYX-CCIyq`_PVqoO2T-YZ~5^%Pvvg(b|VeSiIE|Wr|)y-pM;9znDVa3q6k~bHT-l zzVXu7g}0-C6Jq!L^_~bIzskQO8S;+iPnLIvy!UbGo|26tBM}a@3tqNj^R}|Se6lc! z1j4E9IE{2e+hwqMO9{Hj?F?Z&-WJq6q;dMU{P6eOrz`o9-~KODO_t;H{v#&#=kuZi zVBXRnoOcTFc}JF&ceUJR{`tQqoq4EU`TE0;Zi}xG3qUT>A zZ?O)`+a{2A+|or?b0F_O@=x|}Y=yjSA~&wgivVrTW-qQn-o3S_yrd!T@~|^&wGWYz zrpe;fobRxCD;h4`ZInO)jnsCg-oj^;B(Zs4z5B7ciUGH`kf?c7;Ph`QV^CVimk-f6 zVJ*B|5uf+L6jO^wf(L+!HSem+WB7*?5nOklcRN$c{PTZr`tsOS^eIK>)W7Thj5gK( z|MmyY|F_cAAjfM@u>_}oc_LSYzJ2FKYMYd1SU2I9Sv{Fh3qKrOZ(rhz~UXrvz65j^8WQk zNX`oK78ww_P2s&Uz*s~L9<4k6<;M3-Y2kqHPt=EG$h&{*1^VzMk0~3TqiY6G z-cEX@%dvO|9XKKC19@+Allx%_dGGJx$fxkG*AH#Du{H`k*gfxtZB;l(jmVi-4tXbC zz3li1@@^mmd^_bvMp8s%>VosId9VKtY+_nTAc@*8Z^(4|v<^0JCoP^vDJRC`ZBESt zuYaUs{*QbI`H+Hoj}hW}eBQdpo2&~UZ}&68N7dNq7(p6lc{N%~GXMM^p)(KnfkySe zH%Qyk@V4*u9z%KW7LHWG;;rTP%svY8ws}r`Yyo*+=vos>;k`ukU96L96gc-}+vN6- z;b5(6-lZnU`+QtYQwHSCQFGAaL=734`u=t0NgM3NiH}6l_D#=8V3OJ{-JB~5F1%vy zQd+!fbC7`#_$aWfdVxoVI6QlcFR5r0@-|(a-?0_)4saJFiPn*k&7!K$fde*g&ZsuY zZIJgSYP-BEK3nysCnS^uY2P9$vQ=T#CA_`r=~7G@9N^-sO{ep zz~dNME5A?pixaUEWtL+^Zl>pb<~x0P98$W>awFm2@Bjb5^KC}^mvH{?NK=E{cAWZW z1Sv{hsEt*FVlJDV?%7vns2JE|yam=E{Zoxj9hU;de!0f5c&? zuR(-q`tr~|7tedAVD1sSorbroq`4OQi0x2#sfopV+|I3i9P;j1dug#PM^Yw0myw|xcCgwoiZ`r~E`QAqY|I)nY(r3az;)Q5G1oGarZsops z$eSzak7wJq#APqacILdqK+Oqw_X09&c`H9xOQh zt9|S6^6d(Kgu`UXQHAaJyn{Xe`dR)p0jPKOf3zNJ#N|ymxLtbQHx8!fO>Z6n+s$Lz z&&^eD2O8eam3aXuZ_h{{bu8W%cUSIT3VENrpnuH<^1fWgHdzaKZQSQeQr}IPoC9-HCmB zGcND%NpI7PQWKe;cR!tZOv_|>7uTJlTyJ4d!`mrkcsa`ZccOtB7Vo=?&t9y6ye$@7 zN!SQ^8)fScQ0D*AOBV>3a7F>6Kl_$~&EY`Cyti@<<{b;B8^Uwdm*pf8UL!{aMM{=NV2|9xsOW(;ePD@_d| zTR8SpYLGVn0k1owZUn3vly9+{KLJjVv<*~Mw!<2vZ5q)|*&r>uy6y_=)krWi=4+tQ z8v;58&rD8>4>~8q}KOZO$@CMjSIF*Gwg1*PsPq+Iuf1%7bmxcJE(0vsI>H zpFv_x{JyW50S`!@Pt9WkPXBVJd>)Cm@FDA;L=aXu;6GwZSBQU}cQFAR^*<=Ma4-G} zQu8arPAeTE)6f4qUecFG1IJaRTPNm5kS;X5z4=U6ppRJ9yeE2Cydypu2xURu^IqG{ zI6&St`gWzwU?9`e?_^iW_Ljv(7P??^1Jhy?K=V~IVsp}=lK-yvzpyJ^$? zz8jFY=l2afjsiZ&&7j!lkA|^%=aeQ8j_r^K*Qo7SOcH;mjbQT@)4O{Y31d9oS=2m4 zaQgRnc8&P$zxWUx$?W(rI^N#4yqw*=(L5IH_St@Fr3xLpx7v#jNay}9I3WEceR*gP zEU4I=GFQEwX?Y8za-+O0m-*;o@vg9YVsIPs{;Q(5Xe;E+^}a1e%vj0V3RxurM6Qmbb8tS z9-Ft>v71Xn81VEKerg^jIQb?7{?~x zB)sa#eAmeQ8>9*C^yR@OexYX7-nmDtCk^ia?yc68M=XW6nXfb}7ViNLuLs(Ycgv~1 zS34l@C!hKE4a51r-r9tadXXrQG~(tcc`5{yII}Fc4|$v9D1Wnty!$0`WSigwsb46o z?#^>;-lgN}NoS79gI;R8l5o#^IaAn=Sk5(vc!e175qp`M2N9=#jgtq1o8T6^CB=_k zOxxkV-m*60Tw%R99;AvpKRzFXzrE#neL|HDJM(}4FL{r?Jgy!2E5^QHZvEebhPU7A zNIR5wJK-w}7VmGH#*VCqyuY@jlsQA*Q9tV*ynwv55v>Zj-;uyr=V@}|xe(AB5O}B+ z@|Iq-%}W>ZCe>cGs+{M8j9Hq4H>KFT#n$BX*FxUksqOO5J<@Dx#^zmJygg=`0e6s! zQuDZl)4$(!QV#O|d`PGjhn|}~K5sWA&yySi@u2EnQ0|f{{12oF3&bpwCQmZ`1c~r_ zDP4KYm(gB!uwt%yyVLOYt$ZSi^1iNEJ0FX;|LRxkoFH$L!A1L>An)a8V#~`RZ?sS?j6df8hOqcYc9*nmjl` zZ6^{@Jh7(%oA;E1=-#>n#v7c}Q}dX>>7PCSgvw@9eq`Cxq(6tZ;qzwqVl_Szy$>WC z2*yg#aY5R%V*~HpFERi3{}Bi1%cDI(rpYXRu6n!C@b(E&n>%}(GB|0OO`3AI`rQvk#cfaNBJ;g8zDp@Xea{!HWXspZ^cjm&cvALK)xS=Pm!v z|NpO~f<}OI5)SwK+Y7tfq`tqqZ@^O5bVN-H#ofoV@E)vEv3*r2q zy?va#uR997NC`MocrO$fw*=mLLm5G?2$@(0YtZ8<70Uy`WTe+Lw{ZJs>@P^Uf0X#> zOpyTE&X3cp(S;Mc207}N^T$;z!Q8U<-}=MnqUPa%(?5F~Su^fqyh#1WKqD6u{6}p5 zrqJutKX!qNs4|7pBXo=)ZGX-#@ET?Q8e~sj9#u;ZPP*~WjUat#cn8l0{)LVpt&+t# zv3MV=C@6jndAFR|bjlO*4orG^j2-f}_@pn~`7{dnuT{@<$O;AI@6BdUA@Atvl}Gd- z@4aWQXPG*XkvOm|iLDl!cS)oFu*4V%#8cZnT)pDA`77)#b~)!)=r%AQ?+esCGI9F% zD@v<(z9t_cdi9;Mni)QCr^4iWo<6%l*NJJ76)*95i_Pmk!nZYq=_g1vEOh1(q5hz} zA)T^=)Q5(5&~x3n1JWqfdog!E5sUY0wQ8F$koWbp*$@xNTVO@OCJxAZU&0BwClyiP zvhqCJD;}ZXn4&u&AShImN+s(0voCALfZou zW}d?4-E#X;qpfD32PEB!WIy$3QU)hJ#jAZ}A@5tPWB8t8|UgsRW(zWCWg|{~i@16UEI#Ay4 zt8*7(@!oi>N1YGO|IZu7$htw^!Tde@cpz^l9i_hIAyGg@ZeMtIe+Ur&(>U)7es*Q96X#zWFhD77#n=vQgzl2isO;sbB?uvT{j)Kw``Q-Jy`s|;Cf4X^N97G;s1C2 z|Gzcm{Ga{4um{bo$U5#B<7sAFBqDqZ4%e;UhLlf75Y)Sc7bMTPIh-8gxn2 z#{K%CXwb7Tw61Vp7^tXkogIfYXqkDs@GxZu>5Mqv{s@wY6C}d#z7`e1Z_Gdcr!$YvnXBbL&d$yMchd0QJ^Fhba)kr?%7em-!HGg3bF>nf43rI>zIT=5Z3Ie`a5~3q}v| zA@*-I2FCU9c}I0i=?ja6fZ?sTv-)`Px3|3UUu%a5c{BY8GA@9=JaqhP{drU7R*(W| zct<>VJ9qv+W&WQO`<@4jcfir0^y84XqEs&83wifESnMMLdB50Gp|V#x8f<>8C-R;% z49t?IADw`_RkwVXH~@Kjmn!xESGYjxoFcvI9yae4ns=f*g zZFQP0jK>?z;}}l=^e=68i+aS1OzH(?f7Zw6UCX}D$O`h-waBOwxlhOZ|JdMQ|0_?X z=S@hZFAuG)hDGj$bJaV5hIjZup4Djec4#=ujm4W#G-Y)b@-Cl!y2JD?-~T~f0Yp*T znO(MjWbz-X_dV`>tIQ9K$6Jk>$6cKMxipE4d=cbBbop7;wyehIy_BVcpuRB#NGzMU zv!V@ugLDmBsZ{%ZQ>GuB{KY|E9=?aQ&n-PP$J?KVcUY^-MwIv6{3tFg-b6(XuN#oJ z)`pc|ylHsf?2C=M1$hrF9@=ONd0!M>tXT?q_Zr5l`$FDIzpOG?9>MD^^xYj3xv+WH zReSRy8S(&aw_bHuVaX=!wKv6%LyKRpV?5sXsCmfa^v@uuS;KxYA5z=uz%{)FpZ5k4 zv8@wUA>fzRO-oV$9rJ(fT~+xk+nAm=L7&b%ScSs7-2dJG|390E|Cd_B`F|Kq4T@W8 zEr8Y_Rec>{tQs_BB%QL2F#)&->DWYY>OF}VQ1~jl)yFg(6!*I7 zIKVqd?&n5{UV(Rz+)~W253ut=q;3ZW*q_3#K{Aiz5*GiE2a?ow8*kjn;8=z|f^11N zOv~KQcr{3xn#VJo{+;bf{+&*DqsArrepqpb2mHt z>qO?SLFeep<9LVm)9rts{})QbJ7)9{8RZ?-PZYx9eV%yxs}$r-_+Gv=2=Y#jzIcst zyhX~ptLGv)Vt}RK^A#+laIk89eaj2@iCs(9xh?zQ5xWcbdGYhvO~A z0*^lz{UZ;WsqMxZpRN2rz~=p@CnWV(3ght}rRMPyr+?EU{8cfcd`PoG?WH%O_>WjK zJ|6D!r}|(|SJqyEA$;B)Z#^qNtop_Dyu0qwm&fER>!?>-24w{)gobzYRqMIiTPX8? zjhrSyEZ*5qk!VfG`}m#N@tu(Ou#164E#!T?%tdkJTQnHV-F52e{BRI*Bhx({^3M4A zJo5|W9r((lZi}H0^7zX-(&|v`>b)b~c;h#s0(eAir+41x-I}l1BS_&Sqt%Y57>~Cz zH4g!t{%zP%b^fOhFCz0P?+@EDeBMJBMfA4sn%IR-Y-{{G&sV=3AOTd;Z?Rih|rr${p&KYc_SATv;&tZ06}WI z-x+@H$~@TBd#rp)HtQzi@m@pCV+5yv>05a~#0_5LF$Hv>P{?K;==I^ub zkS+0fugQ3J{7rY{fHkIi9T#Df&xK{UK0-Bv6?c@LKbFUH~x3eBH7K;E3o zM=Ap#@7k9hgjJBYyNHWIQF%0YoLsV6{c0Ex99McyIlX0hoH+3e{={HIJV-{kvD~Fzr9ZiyXPX z#feh^pZ7Z5bJ>A3`S%|4S44|KV>7 zYtUYr8gxKJ{+};MGjA#`!>U2k_4d)%(P?h$!=sq<<5d@N@PS~Ci?L^1MEFW%OjJQGqiqv-8 zZKA+)H})Q+T{eClFVz`u50V%)j{uzhRfT0-BTMoi&J$q3wSmVF?{9HUww6P6-5x~C zlKX}3H2x!&aOnKQs)eb{UxSX*mq+Byk>9z0uORKA;hos8>4iRG(+p?Duy~(dbminj z$Xglldln9PkFke&rb6B?1l$(OU5o)W{D(?7@4-iG;>}GSkT=p$Ht6%C8*wmH*DvKH zBO*7wYVzh`^S-(8gs^%U383xLgW_k!S7Gzs`!wj>0S(6ET}jO&0;hlFf{n*4Px2rO zi=Q=Dzr^S5Y`luC{LWrvs_OF;rxHHz2fdfpi{51Z`M=~>`ttaqrk$yGGVe1dI3Q z`K?cWL*CxQH{3!XZ*4V6HywEX-^XBqq^%obK=^DttICRSFkb&KYznTunLd!REBo1v z6yK^ec;HG#COLC;k~FXfCpNF{iz!&hgK=uR!#x?u+QZn@`~5|$cAj>|7zC~J5OwXI3NoO9nhHlCJ zJO9UX<&!x7{> z{@tHEvSWa7PwYyKbs->=v@R}DW(djju$Si^??#B4e}r~PkdY6I>6a^zW(+EE92FmN@^a4IQ@%!Qt@@Rj2kg^$yA98z<Y)bY3>mlL&N*Xi_EJi@4V|H(pbFR z_1nw*A#YByfln0VeQQaqR3hZfo&C(9<75nYV6g1%&zumTZ^aU@4)Q)b>hU4~@|Kr< ze6xW-M%+FvQy%+_J%apm<@@hS$lI0LZqc5~*8`H+ye(VL*m*5vJl?;ld6?t$PjK-W zkM*)V$aA^Yck^QLdG`u?yM1x+Ms9oVdB8i4KZ3lbcr|?YlX0f!-6l<69*(!ym+d<` z$2*#a_u;Y|Cs5u6iBF`kcnd_BpNN6HcR6mdh=jarwuVPWL*7=ILTb{dV?ehX$2GAZ zA%HXS^3R{rL&&+k$^paWZ(5`1NHZ?d4Cmc|IwC20%*I*=49O~6W9}^ zZx62XKI33K-ow;9hH?7W!fC1CcA5wAiQoQN@hCp;MZ2$!7w_;!?i3%IXLOQ|5hRP% zC9NC+^N%3s)0xMXV0ZPu=l@YOybtBv??QQ-e9Mu<;$62vBOn#>*65sAz8CVoreD+$ z3VG`Zs?LNK#{d!kdtlHf6g;W?z5Wd3ZDtZE9z4;Flo|SQTB?ze*_h>z*le%|CmnB| zjY?*a0NRdY(NSlsBiPm3Q9`@KLxAykzoO>hfYZOgZ#ysWi|`=(y(51smg4gkux0TV zs|Z5=h$yeI8N}bcMOgHxCh*x&=I6~uUmiONQS0n3&sFb88r}yt+K>-P%?OIn`cm_mb^X3hRK2MNjJl?|8Jh*WBx9tu|TFH(V z$uqxna}~hn9XZPV@%p_z$ZHel_^OroA15xzGM&6~;}_HOUXV;*9-Qj?B`?Qj{(Jr( zW6bdXb1x1!X0XuIpfvGi(P$02WhAbIRfDYEqJ!tb8l>`|ha&;jpzkK^%?R8zLV)ENQ4$T^Wb~Owrp+$nK7S+cj{lP#wc&n@lOg^yg$~S zndXPQGsxp(@sRf+4@1@$@D;o0>#=Xv%VL47vV2^JbueJ>V|7i1yoC+Sj=7C?BPZWo z)aUFbBO_aEM1U^#7CW)C-#_;g<-uoaJLg4F#L53~y`}i(N72Un7?1ZdY932*`ZuO- zGyh>3FH$HWqP|WMpZ8QyM`A^@C!(iPeqN#eG3LtJKef&1wM+TnALi#RMPDBIpD$e_ zB~eC@8S`j(A4~ss66M`KR4$LjJ5sr~To&>UaYl7r^y12Jk)( zNBYx)!P=?%Btyts=J{gq9`b&+0Gu&zB_o$*x+pH6 z?0z%70WR|RN!t2$*5fZu5V&(Y6!$YfZ^Ew=^yLvXqL$|;NZJ1%N5eaLdFMrx_sCld zIV|4NWWz1ykoN~Y!E-T?H@f!L$A3`A7OuU0-t$n~8m_$!HaJeFL*74nvz#X&@6Mux zBO#FYoy+g)b}qo?-M?3V;V*u9P)lvM`J|^wnHzTX_R3{hubRSm)w_?HhZ|1+N^1Vp z*}x+Y!qvJLm$>5dzGd2Z%VT6K^84b28wQ~NU#$K)LCRr*xDu-d{ZMOrbuqTg@P2Sa#35LN^u8A<7xxQBy&nhR>>Nqx=x^WkE>v*l;&uvHQBjF8GOEo^|n5pOQD`4$`QN zuF{P{@*s=aZgi5D?Oh!9Cw8Z78-EuhGhPjfq2__tKcO`ruXVNXB1La@r?S^@8{(1K z9aWWi_COr+AuQE3SPcJyG=fyU!}!$!rmsPSwe;oTZSitf;oSOv#zGq2Sv9Br*&u!4 zMf(aY-jA=d8Qq4wKfd_jeh~70VgJ>s8}fehF!UCoD;8`|G>gz04+6@zM6r6(5K=gu z-tg*cH*#^>Bh*CS2U&eyGTY-9_9OOC9#^;=uRPGEwp+7s$*LP0v3YN+E?T2_fbn=A zrsm;*)4$r+yC3}3y{%t6nR5PL1{)3U%##J%(GjFu%=zV5yax&fYo9^hETtOO2Ow|BYVPJ{$U8jj zUV&b9EI7MS_t(*pAmF+~(9i<%zA(C-FL$IHF%*;b?v(XGyhPos4>V%)4$Wzw=;f9N z&eV2W`6lO=NMZA4AGcK%VZgVyVbna>aQZj6a8~1f9WU~9Y$j6d9X@Z;F6EfypuLEl zSk`ls4*U@$p;SMQ|3(1QuOJcX>B~cuP?z$fXm0+`O2a!NOFjhU-DeP_g2lT&nnk4x z@{SG((%TPt|8=P0`Yp=fgq3A+R!S^55+8Cw=5r8O6@ELcQEmuXb@}rtuW#MR!*4(C zH%a&)w{6Z`=(>Z=Tjl!er`xPP?hIJHms9h&htt1?_~hk- zl+#;fuf9|o$LGCBVg8*2uLvYGbHjC40O;`oK*33JtZ z0S)hTl@I^S|GD3qDP!>#+!+3B1oD2Tb5+KB! z%^P0N*g@VgR`UX7;M$vgaHqnxdt^j$O&!O7w?<*8xi9P?< zk6K$b&4BZNG!I>z{;gDr?mAM-i|l+Mvh?`>fOl=^`=a0H@HZ!Jamq2Vxa7w4WAD<< z^yN`qv?;wCew@e!Co!z^&J(z#IE)v1EZ7f!{P!P5`xAg8NG_Thls}>$gg#=wu9~Nf zRfG1DmR+}nHE6Tp#oA<8gSG^3AN>Jq5dTi%QsKHdkW%E0uL7@L>(k&xte(4DO036!#HuwX9=&PfkCdd1t4IXn*C5GJ>q}yX>X^O; zC48nYk2JQ3{;hd)BgjQGyz`ny^-$h2?r$`)cz?TD``Hunb_n}WdKB^&-diOy1$pa# z>^nT~VjR$Y*1X;QKrmRnda1n`S z<*rMu_i^X{1cH>Z--{Ne=S}z}NnalN+ixrVy}gB#hWE+L*+i7LAa|h#7H__5Y=j8N zyLGEyVG`us`zF+a!aJ8^qc<4| z|H#TS*oMvf{F8K^08bJKpthU$*62^-6gKZoA+8F&?--9ang?G0qANvv)wOw%ZKX9c z&SChxo5p#k*pBT%u3UO`)Q<;${Xf2CeyQz%8`Dpa2#xgR(dOPL@a*DT_2!`AooksS zkMjO029EG|)q;2AemD_k~x_P7*jyZ5OiXU>9XtXP}+~ryWMj~%9-lj$kX>{c>LGmum7hn5{`|HY-D=g=UC~> z<4t5@@<7%cZz2uv6XjamC~p~CV>K+^N2JFRPC(w00?XqLL*9h#$*(EAyF4tuoG^<6 zGlvtlnaKx(d3J}>X5iY}ubxdF9gz2j{ijRiA@6Oi-3lMBWAo%E0&V!``ub%KCf^wWr-!t%ek1Ah1a`Vn^q%wuKWt`nMA{3+%5bEfA_7^E|gDWZ(jzu*7=x2Bx`v)>oa|M_WZ(3!U zRfD{?e^Z)?fmiHi^Uq6%HOSw-uht9Jpx#Bv7ZX0jgJXY6vb3f{K$U6AmU^Wjgwy`V z^oGH1#P<+i=R`RCK)N?Q?(-t-SL{FLuS>lt0k7Dlw#)T4{nES?`yFIk`|Q=4LdL5> zqtra``d1^oqsOS32TA!UwLpD_%MkA`F|UT_!6F$eBwFZWx7d3+KCyeYN$#+0*($vM zF2n!&T^qXc2mzuW@0ZR!V)$6;mC!!JMrL6rM=0Mh7fR6@l)e*$UDl;`(7dB&6~D<-;Ql$#MS3xjdoKJ%E0T#J!1@lswyF)H8xB0v5kwqf$4 zzeKV*qTH!^rCSnzfpqoe3;u%NrSuq{FHQ$-1&Zm)W6#I4s~!Jd|L3LQeLDP81InB8 zN!ltb-W57>>m?!Y+dJz%rb6CL_g*?3g}l=|`88gr$AhYMQ*w`vg#gWvUz=SZZ)1A zTx{MuPizSGtYkdiR@6KKar(FJ(T8&#a=gf`1F@2PEAV;eYu~bXXY7V}SH^YT`GG${ z8q7Ideyq9agPcw$REuy@i zra<1BcKi_ykhekJp58)IJP@1TJzO#!3|NHp)B54!L}#f+1c1C#yG@OC^~lImTQx$$ zf8c#TCyCT#N&@$(?S^dvS40Q#ZF!%LAa1FSr?!8 z%RE{3rRHu(>W$eI&-3W`_V&`d=ocV|>3I{f>CA&wMN#?R`9IE3k3oJJ&i{pIYEVfl zF`rU{DD(fjE}Ph}YLM48uiKa4{QpdBvR)3XK@W*DkELJ@YHm1E$5XWrta)W|L1Q8m zD3U(Q>{lK_a=spQU>WE}jxF#hW@{rOO6r|q4|ZYC{{xD`4>$zCGf1fIB)`e>`K4gb z|BHuSx4DckUJdf1=7HBg(-l^PHILyDJKr7kgp%;*|6QZ1&n6ql$P(2Hn{zwqnE$K# z^t}1z%KYOmOWeN4tehwJNL&OZn68mI9BC{F*fg$ zOC-&@!${x@wOxy5*()^?Y94s~tGI2{WPFhqDFF6Ud`0-Y<$rm^ zIX`eg+#JNFIhWzj|9yTog}1kMFg@>V@n*X6kh#Cqb>#2)zaS0oV&8{nP~OSoUs$ks z-#xW^@iWM~Ch(D57UUg%-!M}T^4_R+Mena2`+%;z*UJORp@8@EdPgb9TTx2x#YM>b zceN6yQw15(as9#BAdbyDwA}ghOd<(rP}{ktjCh$CVe|GKNY_kTz<8gx1W@z9>)&L_ z)^pr<;Pn2+6T61$`BkZ zLc!^q^Cc(Y{Qp|>UEy)a+n{%!Mfr6ylEAS=D@PQYx6GbEj_ynnh^4mM^XARhO~%-~ zPqnT$kzl~{|HP?z6yo&np0z>|mn<)0aycg5(KF2*T4CQSdnLH1RcWA6h!7$`qtSrx+0ePcq zZ+Y`Yc16Lpw=*Ujl}|%y7297^nkYdrTg&it<%Q68`ZFRe_pz} z)}#cEy{YY9t>*Y_w*#B^|6%VwgQD2Fg#iyiRDzO&ft<6FgEXRmBozTAiR7dp83aUv zVgeJOq9g?c5m2In%2q*8BpS#HCbEc1FaUlV?0N6}>C-c~WAz)tzvur`$b65N2Au!bko2IUCp3$%*e%Tefz_Ltv3gKnOCYy3 z>_Jz{j#;L`9z>yUkTU419q>9G3sO!UuB|%~1oD_RncS5fMf~2G-=_W4kK~tK zH;|O`K(sc$lx(|)eT#kcZTx!vt71S6jT`$TVk?)8eGihi&&PeO0_6=z185!GIQebA z-06SjH!E^vVud3ATKpcgPo>c$Y;qeyPiMGy4v?{eObZ=XAM>LA9@I!?9o%&SDT_z! zB&{alU6^vKop_1O*u}ww#d~j5`EgIkoB!nLZI>bM&NQ8Ek&w6P38nOl!LdMRTYMHn zXb_;&xN+zlZ!#0w%EMa zO&_^ZBTsp}521A^;N<5U>Dy^0&5Ddmmo6Dn!{>c*Kh2+O0xpR3(W<&9-1zhVc`N?6P1CaMlHyWc$khjye z&O<4Xw>rXDT>+vpi%Hw?&tphK=mgwWZ^eR^%$|kk>KlJcs^=ZO)R(L}EWVz11&NCT5+4cgo66_yh`g`p6feW# z&Ctbv`8eeLtabgSRLEPi&g@`0{H-xC9~Xx!{nU~&TsHgB;L-`lzMDUY`YS_fW!v|bLC zA2e1X>^DZ*EiLeQYajP+ytKjxsR)}YVwuLD|2x0+DBa6&p!)g0dtEPCb!^Nz-{n}e z$eWjhcRtIdz)E&@|EuZ{CewFgI7C7+>zF8+NsC+uz7DP+0*c+K@2paasC|EfujGw z`-;F0$NU|X$6Fh%11~@EC$V*d4_6{zfgop#Gd}Ndp07;3Og>2L!*-uNXULfUEkT|8 zH5;nuO*l_x9R}4pg8%OS<4xX_@jIOVg-Ci(S+#mOu?Ov<*}#s~gEstrU`G#okn$dh zkSnkUxvZ+|9F0`cWgdUt(e@%1Ofcz`Zn_f)PS`%6dkZhIgiRmUJ^9#=WNJSg+rsLB zu*@#yx^W%52k{5oX-iEO1B_^#js4!kKmOqxBrXmFPG(8U>p^^I9Zop;wIg$7c|xp6 zhjhD_Yz4C}9**;VsvLrs4}#r0e{MNaM#c(~W!rb}^k%AGK@!x-t7GXKM@{|g#Y?Op z3GdQm_a-9m+v#jH;g`wn8)@>oq>_oE^)L zww?SSHwds(tg4A4nxG!NF)$=B(l352w4{zGv<1P3}co$nA8X@xDzw7l1EZz*> z{i{_V?}Q&(2QnaUA({q{0QiBlk1MuvwB3#cZ*}*WB?tt8)jPiNazWlPxp7N;AaA;q z!DEN?JdnBJB`26ZWAhG*T$MYOEe3v~amm&vIrUnwd2`dW*%c^J9&bOi4o;l>W-ewv zVGUtLR4>;&shPs(eSYim;2*ziK$?nySLF2{of|}KT$t#5%TJop4>7R^6|vN z>8)!?c;A{m_>Rc?(9>WREZ$z-yUYwB@5wVkcIl9}Q z-+dY4?d_s^-j_lr$f`p)Vnvg{nSam!!<*qK;&<4C#7TNkRk1Zcu?MXSRpG_zK~_~~ z5=tWrb$#ds!mq;~bf3Y_@IG8Y+BfgibDoI>`>mI>uk8u|JP!;%pN97!RmSMs``|su z>P@Mk?Qc8~>y-@*uV=BJL5jL}qf+db7_dR(^p^Go7rn=R2B}aYegD}rl-Gm8&^q#Q z@@vm7$m`K#Lvk#QoQkaQFR|J7ne6davB2Hi%D90M|A2HInbRsB9m7;V|1U$xtK-C( zb|0amiyNe3B)lt+AL1nPUOT>w2aES|l2t}?1B3^_-6yamxZ?%?F-xwEH(-k%luJ-9p|#vPxxp*C$|nPn`X4Z7wvU4XxW zB$VWPhs}SddftS4^(=KRt?1hmH6Z$TGc>c|7u)(HC#b%`E$+p58NPKGhp(dtK0**;vmjl zd>OlYBgf~BTxi4rF-~cc>6ceLHt*co3WwSh%Hyqp){%pgpTa6vwOz_=h?DBEp}A;$ z-Xqsa51y!r1|!W?F1mjB2c+BU_D{uzc~kugQg|R z$%hP1EZ$e+Iq5z^-fll`Mr1?YX5hN!|%5v-^PN@t|Qwo_yvMrJ#k-mK;D-3Mv=_ozy*z~d&NF-YCksb`3(aVae#5uRnTVfUaVZ{N0e!bj|K(74**iLl4-vF|~?=}t10+eLXR$hkLv>*&SF zZ_9_PQQhzsyO=A3w8#S{UA%ubt}8osY%Goga&~2BUbd2PK)Uj7oq(2IRNsRLqGZ<5 z%}p!!cLzzDgf|Fdog(tCJpOA97VjOZ;c~%{cfpxJt9;12euI9cA>>VSw3F9NA`S@e zj~-Ck7XXUuA13aDykFeBe7*#}VyCFumA5Lv1KDsrEQa+6Ht%;by?RPd#egmvm#7ly zJZ6i1iG9t)sd3kt@_2Wnb-cvMFZGDB-E#POi((PQRNFy(-W9KBIz1Q;gR&Vzr%WdN zTkM2OE%smLKT$pJ==0>&aeVc~4cGG)SCCR9ysNhtXb^cP*FRZ}#XCPWv*P zGK<6N3NrR<&%XxPY-K)elJV66DqKI{()3zT=C$B}sTc5b$#$ z@)k}?U4_Lv(n(J{8S<`tp6QhbdCzlA1T2HR^)`tJyl066PIm3qy%z$&$6F`#nc>}A zhu*UJ68QfAjh%}5YR5c~L_xitI2UZ*?;kxE7#|P=r_s1-yO!xy*Wz7tmRQh2M&i%mlCo}%jTZEg1Un2{QsGc|B z8kuz<^IzrvE>0v!c;6dhqa*VEzS@Hii+9RO+oWvB`}lVG&|Jv-DEnKp4tRU(e^zTV34;s$eRGUf4>MeCr$$5rFy-P z>7PG9^_SQgMe^!6#U&h)8J)B6h@Aon?0ApS@6@P@L8!*26AVqn+z0o?XaPp(Mpk=eSloQd9jaJt9Z}5() zQ4hN}--OFs3`Vv2?=gstrygE`|nRhfj%~;?qPr|!ahko%3(hH}zNSjp)VewY+ z*&wS1dGkIkmo9?5z3(1-+6xDyk8)Bxm#yP~z5EjmJ7ai2diTvlKggSfzT9i!>#Y`= zHy!ux@<3iKS+$zc40}MbeOM#$1M()u>APFGf8xX*kVfSz-xg9JZ*#PcVVwNR>VCIW zRKW+Nul`=Q^}oUU`raQ0lsoZvkSZ${9@)6sfNuPv@s^V$P@!yXk4BBKu!)VHt*lxv>Yq6DX)81 zpmqGj$!}jLS7!dlm59s}7LVaG_=^+HeIegzH%EcNOV9XXkKo_linj5+>lNTg^}M53 zkyl54w#eM~JBzosWJ!2GmT>$J@1K3v0$9AgzFCFtguHVbDzpnAZ&gOQ3SY>Zp>b8G zsAe1p7z~WL2tRM(7kM}3Ipm!idSy=;lbHTm0C^Ibq z4j=s6TN4l0eLc!(O7-)<=oRwnP<+EVVFOQZVS&TP5}IoS79mExr7rY`;s5^oAEo^b zz)P$ONe^ngBqv9_#6HX9kjCmk#y`HVZHj;^$e^FM%U}=s)OXkG3>=V-_1tmFI2H#U zOT4i*nhyZ_?gp(X@DscAJ-3#p!!Jnl8-IxWXzPK{O&Kwqyn)?=ZhJd4`3{SLC1{-6 zD>GUvN9;?i&dbX>dyZ0G54w)lp^cN@WTgf(uR15v__KxON-?7@9uvVW-nIMLgTPEy zZX_MR??DMB7aF&C=urJ7R+EdoI%)=ccelGOUSgF=ct783GDhSrz&I+2#e28riIE=2 zyOZGkv=s7wc;DP42J-gHSK457Bo63&_L`LJ2>=>zn+&c&-W783>_;H)5yF?j=Vl(r znd)P<{c+g5_loVBoqjC_&Y^J=3Yl{{+St7NnEY$_f+&x-Gg`+Roctuck|*AWaw2X+ z{QLc$;q!i{<>%AN5d=;Y`krC7A>##U!#?fR_FJf)H$jxlI{E@uX#CwlQX=8qpgj^v zcoHy8dv&ov()X^*t|E6TzHg5fp>53 zp>-fQ`5`o?esw5wBKP)tvxpP$SCGtAC(`=wg#g{st3o0O{`^m9a@J`HentJfpOaTd z?Z<6Vd(SR*@AV|SpDmdSB=Y9k94C&&+w!hR^3R3t-9$H240&tZTQ*_|c~?8$=;(`# z1LA)sf31uS0M>*sI{^kW>4AKC>f6Y&5}WtHl%vbpN-^*ijk{sQ zAHTB&n|IQ@&E@A5_;6wmTE|(O{65iZmgmxNA$+-=$ziMUd7D+gS(DFv5a<#f3vtWf z^PZqHK2r5%lNR2hhthwqC6HIgq1)9wk*61LZ>=NYUEldxn#lW9nUxq8Z#ozG@MUoR zpDDh=vcOxI9{8+>yboGz=l2Ya1C#IS;xe`b0Egd8F7-j)rTXnt(vY{G2eWlKmnS0e z*1le80-N{J2elVXO2mL98n^jPYkJEa?9GWT`TJA5w^QEYWcL2wIy!LjYsWLRKA5TjbY&&;NJ+r}TEU zm>-<~HA#BVi}+%DVh@UQSgwfGgHDb=w~d3B*s1jJ?Uk?xUGNy&Jr3_d2H18!HaZjs z(th}*YL*9r<2NtPPf3g-9p08>m&W>$?;VqJl|`P2|BjiV$m<@M`~SyNO&DoiB|tD5 zw?y+uLV8LR=0>2@x5gCp-<0F)DoSQURj`Wnl<>;4va zgt178uUs`54@h^Ye)(}vnd(=N(XHgwu~x?IyzJle|1?N=w^@rlC-UCj&?}F{`@3um z(>chy?a*5HyO4L>o~9l(c!@o)H=sCrI1a48uWp>MKM<@eeD`}byu=d3t=k+R?<3on zG`_v%iG&xpHu0uo^N!Qy`2F5g0z{#4EZn^Us;97dPkYiT#eSqb-eG7RQ#kp3QJnKn z@8Ci@l-r^4m`dYp;?!xCimh#SK3cbHykWwe% z-73Fp8Z`0Y$oo>nGlttI<3L5xr*ghEfk3vj zfkqSZwoppHssMTG3#sS|J@7>2F2tYjzk$tLJ8b=*0W}Grh{l}{oIXFBj?MeP;rBl} zTPTmWB3efnPJYSL8YfNpxRGzKUWXL9;Pdv4bZ?Sw_6IvA&O61G<8P1>rsvd6vJ|L( z2Z?Z>%sO;ME?)lo^%gY}-px~MI*7dYKMj<{;?4fd;LI(^JI6xfL#H}6h<-~vY|Eb^(0G$63k{;A~VYr6a zgEkynqKegnST4S<)`C4~JL~-?4`2^U%WIu%f$t!B=op-Ax)2BG)0)NFCxgK~j(1hx z#YYkGASq|r@qWYvVP89D;(>U7v`Xw=f_;g7_4=ynh?Y1AK;yi0-b9RD$L>MrO!WDm zcTiprYC!8ai<93N&%LF6)|`lcOvTIY*yXx-a;`>({M>Ok6olK0yry}Ce~X<^Rwbm* zP(<}Th;Y4U7E$$%cknrxXYV9QQ?hNfv#^MdincIyZ?;jGS@9#t2YqKO+ z`XO&$bph?#({UiWYWBkJykJ1X9it)xZ*RGOx>qg9mcTc30L|H})kq zII(BqroK2xLE}CLJlQ;O5Sur<)Qg?j?>v63uLK&{@=ntULBWC+#lvSySRefK*GD-)#xmd_l53K zB`n_Jxu5y0A#W}1>Dhab_nEwGry0n*)ymhT3O?R)F+aid*_L2n=HwOS2YEZ6ETi#) zycPGa)~i$UK-g!5Us+UO^VW+svf;532YhH;YV+woMRwS{ua&QhnVXUl@sBCn3_mruLS z-d^n9+9bSRFRd&g^0w3sU5~|^_tcsr?vVHIZ?Sv}yn{GDpIWHtbDjhrCxtx9d*A<1J4+`B?NJ*o%`NPnYrk?h^;eXxvv_*ZS{E zu;>5m(_Rmv4p83wKaSRM1t-6y$ZF;dN?ge2OPR}7_u=!7llY|PWEc!=ug^8`XW~Dc zsP1s*)3u|QsGj#SZSv~ixmHip7{AC{i-h;f=M}4oy!XxOt;6DN8&~ot2=YFA|Ex+C z)&zOqHGZVj1Ml8SZtWa!boNBDK8G`! zabn-Seg3#OpW&bcxQ51ocRzNm`Gd`Shu+NFY7QREy*#|N?Elv9kI*{Iaq_!TMV}G) zjtc>QcIBk~!sp$%M(fiXgJ2M}wqEJhS~4C^96a)erZSiM*WQg}))5obB?});{CEEU z-;(`5_~*j;e=|uBdK(*mc%cWW!#7AL{9OrHJt)Ck1I#{WVud?HfDwa4%L%bj(F`pP2ukY(wj(lzcDjbAzotF zoo~>@;(a1aMUNg{V$U%z(|ZJY%id95p9Oh)@<>qLhOpkoU)t z?C;HA`Vpn1f=N#Y59CAkGn&hO*el5Aqec%0zlnh%G|tiYg!5Mh>`QFe&KdD5rzmeg zdW6;yjFVs0nSrmvJse08?FWJ^0sj)~|Mf_C_cD9EB=UZsd`1I{_e+s0^K6het*yMZ*VLOIe!aEC z_Vn6iWpSYW!{H$J^C7@4Xo)4BvU&`;7`>Y;uB5KFY3U7+z^RB%5-adFL z0)$+yGnHI||MixJ8KH|Gjz>{FZ)tyFvg-KrB72VY(Bkc_jU>Fg`}dg>dEY8Q zSXH%(6S=_Z*srt^pLY=-pQ_0B2$1;VwJv=Q{{BCqc6iOTn0-_~{}T*`$f~3E$mt}R z^NaJpE-7zqM^++lc~=EBEZ#QywAt6 zdDEU$qWRH6dAxsk{;h)sC%>>yIl^*`T!@B>$Tyn3_`J*Z^;;f~4Fww_M6#HC@E0d} zsV(0Ig43yf{;#;*OjaGCTzk)C!S4O<{ExTVqk!Mx{BK0kgFgDOSuOOSh50{Ta~lIz z4>~CGQm7Qp|7tA8R&}rkaobLJUO%9un@{8R>0ojk$QKl!Se6z7CIyeJY!n$qs%E|Y z)xN_WBpKRE?;pA&7k&$QFU!K7|Mzze+pP5$1L%B85zp*Mq## zIuM-vwwt96mY1?4>V>~7O2qN!fA1iJLz`k^faUu#&GBgb9i-^fr;abVVo3G#e{>mn zb%aaDyG&hOyu@xH;r(H=ZW@vIn^iJPuy~ufFFpMb^0qh>5%mP}u9WZc?SZ_xt+Njq z!AtB8@MWufK?o4pciVX|R&f|SR*7_DO+PJTNlSIVzv=0MiI=(!N7kIx&duwFU-D;5xH z+fO%;am3CNi&@s&oW)en+dY!JI$T}{6Wss4AZwaLr`$_7^@hB4 z%)75kxMK6(8ggczLAn^&jKXgTO3tGn%PJStFa!+=6aUk<_ zG9q=h_`JW?`rWDj9Sb%zeQ^jP=j$zoLiaa3Eu(tggllBh;m_6}{rB#z0SWK^9=#$W zZ{Og1v{<~^M8aZvAny;$=UZwZZ+%OF!BEIsp2Ox?;hi{e>1Gj6(d!V9`>OP473959 z@_kMD*M3Cn-HNlj89k8XElEN5fBge*y+Xlp`2K$?8uwQ7)Q*)$uoov|dpYm$TTvcw z1GJ7|ocvgXhU*y&I1sfIw^f8Q_`F~0RGeOubr=|gx~kSL$A5c^&=sS5u3CxeZ*LLY zW67#xrA46bx{Srei9QMMzTEUjMBb{xr)jWwTP2SP4MX0|r!Pz|?7bbXWGMd*d2?$e z)t-DB2fm9|{hpi%0WHAJn-y+O{0ObrOC^8IAhvE+u6QY>7Y{5$_szp5Jm+SjQm-oY1&z?fpd>cd;+A41vaa z$u~JE?ir+dw2nUk|D4|e$B}XkQBLI4`{?D!)up<4|7^#(8V21;4uCz|4MGFT@o%yJ z@HZcy4sN3Q9z-v;ovb=mMeJc;8NaxLWJbb!SaIWHB5y~39wsc_G0U?G4np2)g_b}`+t+`a~Q0;f`OBcTPqE`y>-!zlkO$gr=LH z&5H?}w~S);=#-!sphx3)`WcgCqOf@v_f4GmSV?)jCDA%=;^gPZpwrHN&pVz__m8F4(<57*Ap~aKGq%t1M#O%b!@@s9q>9SyVOOC>IbB7)pKOk zvH6Qr#q{5|w@gTQ4?MS9e7$91b3#F_bQu=!HNQ?+T!g%zt%xTq@SbItu^NZGWtGQ` zgy7d(jDN^pDKrQHW8=^NSVG=U)0de3hMN<`s|vn$HoGI1j(K}bKVkEx^RG=#(-Q+W zXx#5l@qFSA*u1T^mdYjcQXcPlzrS@@;NJ`CMzy_*coFuPUM^+u5&aaD+J^b(f zKi&*S5x>Lv--4tEP3*jGO6)=3eKpy!deFwf-%k}_57OcnifM*D=oG_D(ck37|#C(*;e&%P4y!g7Ow9FQ``}iO(X9=a$pZgE1EtW++HdQ zRM9wkb{39Z0oa$=-IpI$r5I6O4`N2^u*Au4YqQCjS1cSzd`4RzhvLFa3qlT}AQi{`6N*n=SN9VEQJsG9#G@^-w+!-mB> z_xIBvZOFUPaI~Tc@^&-uV~{`UzO3!Z{%^`amKjazkhX=b_(HgCz;H7&1pQy%Z7XdQw$`OPup zvCNyXBL(BuTUF`sSC9$0A76iqa08pTMzr?l;txoKI~Fm;Eu&P=o4^-FRvk@w#`$fU zM;3USlkoohop6N6JL_T3N-W-Wx6a+TEi2@xo?pGd5r|UmF zy*1^bDRsb)@_64x>lnw$uT#Z0zc`&8*>Xyc;fVx3?-(xiflc2eGi|7Jx zF2V45TgZE_^BtGT*Reo{&*8&e*I;nfXN2b&b!6xD5RL`5RiOf36XJya1aV_xPM#6hEO`ey?`+DaA z7A)SzMQKJZkav=Bhskru`?Bccp{H=~?GhWWh!cEhPWaSr*QdvWfyo-3-cHDSd5GMW zCdfOcbeqSIX?Mh?>1Fu*5$v`1wFhcJtC_@rJsQViC^IxUh0R+#+gtF}Rm$Ui6|F-V zC%^bg0!#6B4n(|d*g`)BpZCLu&hJcm_Je@@o$AAy_-k*1XzI5|f#%e|I0?B(RvlL* z%MU&&`gi}IBIbL%Bw!D+Ch0-bX7)>nJxE_cg%_&_sjs@k@a;gM?p4=K&M#mOl3H!q z?F64ea@R=}9t(&CJN?5R_7Z}@Nx=59Ux4R>4C+{0yoWj1u zUbDVx7H1#|TG2Sk(eCEY|1coM>OVfUriX*#_W!fdIu79E*E+>%JwD2g)G2o-uUBHg zo&VQ;1S>yF1p@X^KeN@>@Gr5|>vA>}j>J%X5AqvIC#w#IvjuFY+!r@UcaiX(lHFTQ zImdLaZ;pFDKHio*Yu2P&;)}ujZ(ZJkoOX) z9E(uM+k7<#^3~8C(N&fGnb?fY+fv=^+-+M?fS_@PN$=J#U5$N-bt`Jf$oN8eymz2= z*yH3^D3tQLOP2!~lR37w#t@(PSi;Y3U&SDAK4(6S^<*5e(?0Ow&BGnyP!+TLNZx8kgQbRFXr8Gbk5aYt5%>6!> zV)MTI_A~pZrIfdVR7dMb!pU!FqvJ^$4i1FF>UvyS3_frAbLBy=r`*Ahf!REhJ~D1^ zHSah1B2WFtTSV`3A*+r9^S_>26)tvfD-zz{{v`ZoapKL9&WXi4Yj4(hZpeFek1W>$ z@9F);kzMfaZBA>A8B|LS3-a!~^eR>f@)moy;kI3-JJMNsZK=RN z9B<)wA?q$fq9`E7rIj357gT`Fdy;jOF+!N~c<)E+7{$r2Fot82%Z~%8J$|aWBM+bV z?qtoaM-<&a=rK^pbqt@kL=K;gqig`x&;PM3jAYeu(Q0h$(ckm`EJ=8Oz1Vh)*u9&) zgE+8wYtPv&5rMqlmeQHEK;ASALv|-1@1vS2d0CKmOYEujsCk2v9ZU4}{?=-gT`Ex@QY((QyR`7ChJiz8{5k&j01fe|M zA_^X&aRS~=hxayO_aN_cB8>juDQ`gfGy1mtYAmFL{uL4MlHde|M&Zg z9(nOA1l$%ZC^DGDpZ^Izwmpx18A<&ElIV7_>QJ1w&hBblTtV8C@cyl(n@Qwtd7ox2 z7H?sV0ItW7w_rz^$Lobl?8MKe+wlB9{Q}wt!B^o9QU?5nrFk&e3nCSRAa93w8}5~m zcfs&(E59LkB#B}8Zo3fn5xbvmslJK~5e4VaIKjsiZXDs*=l^LtKlkFIzyaw4T89!& zeq-mpui15i0~wA~^mVSq=WRyQeIi#V zkX`Zj@fJH0-oI!SQ;EFqHTSH>;%(JiJ>CR)TZ^vGe+79zaIZF2fV^`=a{F2mV!_rV zSN^rK!Qgq+^wrCdx67V-l^4_f$hUUKhc?6T?rp5fVId}L-l=yDc)CuD0%F{U?N95h zJg|9B<#{<)3sT++@&a1NC{BJZ2OOizTG)}hUG;~ey775`X`pRp_6`N>yE5C7>+zo; zC2Wp~9?+bmdfo&+^6DtCyXBcxvDm$BNqGOreJ4TW{f7C>DlFd3{h+Z6@}B8W9D50Q z`&|@xc@W;-$}6cxX5i*T`Ik!M#GfG0abh6uF66D7XmtHL?p>_xaaO*X{gish;K&deD*`nFR-7532WFUDO3Hv1>-TAIQKJ zd`g@QXnRV1PPfPvXAax?)O~aICOXS_S_p2}# zZ}Xl`n&Xgn>6YM`PRRRu$jdc-#Kzjr>pdR$BI02#a^k!{y$|khjI13S@!zZ6k(X#S6E$td`6ha>fBc z+FFs>-|!1ZeES+dLEf&ky1|3+_Eyx`k(%RyZpamTJ%#my*t`P`O>cFd6#>LJlUMh5 zEL)1r`xHC#<3SP1F6MV?5V|-+G-QVuLhlKb1{hd3A-Meq+ML{gyzsDmpGa+xLA={H3 zkhj9UWyM@@b3$&7#COB#STL;I8rl9b7-$RVZ(xD*|9-QWZ8sNqgX-F*hi*vsg{B|u zKG=(skqgPY2XBdhE;KG=Y<2FY6l~r}3aL_jdX&d|5Ut}RPJYGLbDe@s*^!v|Hf=_A z{Q2Lh@fI9=NdXNugh=l`HRvU*JYl*c;* ztz$1vegk5a_dkSkAg4Yn8y#}M=Y5Ka-{cb9dz-RS&>ugEKmUVuJ!;>c`%!)OP9?LB zBG#++hX20*k9$$4hyd7wJpQW(*)3DZ`p*%&Nj$vLSUqTIqtGrx*n@-$4A;JaJxD2t zf3GHd28lLS@lnFrIFL3V)y5ef0!)1AzUK&xB2M4CYI=Y6BLeR}iurDELqyF?nl%Km zFR{a)47Y6P7X~6|+{bXwKMF$Fm)H)QOVJ~KlsEr>MC)k5$#3^;YNzxEHiWlfV({fW z9q#wYcx*`*sw@$~}IO$`Q$J-sPLj@9`;D2w0^NUdMIBw77J!Q3hhp7b949VCL)bxVfK&D6hwv>>mJ&4ssK z2&ONtAl*oKFM0bkmdM*C_KpM=@B1kXXYCWH{v>)$_JZC$Ekj9S)n7jxC ziO+kMp<(~WrV!v&`$Mz67k@w^j9M-UXRM@p-h@H&>iFY+@?Bi&V)u3-;Z2uevxmsr zZ@Ik~7VpQhQ8odP_q*^1uHBF~U+58!S;*U@Af!QKXB;qKUbTMOA_P2jGkp;bd0!l- zr%Qmm`Jx=zD^9}2$^O;0;ttrn4;I&mgqn$fIyA0WZ=+;?AU1D9;XO;L-cla#aI_8t zCqFf$v1E{g9hu0Rk=DPA&-+V)X1EXBdn@PqetKdKe{*7MZCUpL8Z)Y2d+XgGuZ|~M z9b}eW_;>%GBIbL%B;fqNkE92!kgSR%_Mmnh7DcQcR1%=($PRnZM+QF6e%OOD2~FCO z@Q58j;4LW#KajT9JSzRskr2>1-2%AbfW&cy=UMfye#EA^$VzJ56ej{~;+iZ|yEhXD1Tdkn-N zZyD{iS-FsRBCXtO`BqoN?d8Nv``_3bq&=b^6hF}m17aLMxWE0>%W%w%K)-XLtsxgE zk9Rv-hbK;c$Cs%oj8C#6N?SRSQ;*>DPCRj8%gQ@GVEr-e^ICKGE6C_a(mK`$2dVxN z8~vWVI%e6wg>wAeLGmWy&Gh8cIU?_@y6bXSyt}2?Z6zRY-e>Q57kJx-D@~?D-ogpY zUN(^T-Mc*mZpeG(t0AlPkoPH*+?I2YcX_X+x$i?)1QB|%V`D8gZ)0zcZDD-EfEcHv zu&-`?CN}So-rOer0?Om9kJjOflb;t$rb(qH8{#{zl@eHt&%5aI{wHOGaKPgEeaEO2 zK5yM?u_Y}N=2Sl*=~k0h$FJ%={J%~w4oF@kycrXwjuUz3Fa^tE@uus{=UxwaN7#D% zyoJ0!&Jr${L*55%mHe90;0Mw}In?yy;0Myr#i-gt-q)RW{@4b2yQuA&9j+r95A@TR|7Eco1%e~C$h`bMc zFp|OIEyhvuLL2gC4-B&#=?LYw;XXis_Kf(n_VW*ZTt=8@lHqUV8qGK zarnXQD@JU{hWI~ctUuxNw!NC#HPaam80lJE%s=DL|FbI|_o~v?Q9W-p8S?6odBI!P z9P{t||Gza;{*V5-aQ^ov=|P;LJWRwMRJ?&s6{`m+J!GnV8wS7sH@ETX2iSwa%(1G= z@C?%RJZ$Yt_Q!#9`)Ut8h4a7Urp|3O{G-S-CcgcKzx$CXV`Mbrj2q&8cSXrpfc*^8 zv0vjM$t#4xUNp{#W0hTRI`%V2OI}vkRi#m04?2w2LBPq6PB@>pOPw8IPrT5UUrnov z_ivn9=j=^?*b5YVVzLRbC*u*j82G)T*%#D5AVrZ^$3TgPXZPO^r1_EXW}o)ILgX!E z(yWZd`&+N$w;{-T-IN7kf%o-9^)~?WHu5z7C=EAAb@N|;Erh)9?d3oJ6!NxdO|{d3 zyob(Nct=OOA-#-UUqg;!^RBKhc#ykB7`#E__K)22+w6(W+bW3Zo77Fp<6VW;u?;7` z?Y9%II>8On4;@)?9DVq_ZwIq^@*edAd_3)L`Va62q*o3vdQDesp!!SffE{^t?3Q_Dp4j$oqXtjuIB{VEI_J?~r#&71!?fkoTLz2k(D|ym<@fe$>atfp_bw zYqKEl(C1xl?U48G9HA2ukau&PX~aaB8zM3oFdz62CrEw2!|-gUEPQ$kjgyEwd$98# z4oLrW-C14v9_8_#Km_{+BJXq^zx7zWt2J0nsu;2gR zps5f75Mgiujq|ln3!jq1e*gc)(hpe!&6LMm1FfSGCqGSx5Sg}kc4U>0`uYbO@CT#} zZQlF#vVP!N_wQ`^FV8XWYX4`E^Fk|K$d394Btk2Bb+m^DN^55=-rn*d)htlAZ*o)%lrSgy|>;sri3ST8UMcj|DXOw!T$s2{}7TMv}$?X;xkAZ z@Dsb)dNu^C9%N##mskidvCpbbRt~@(MELIJ#se?0(d+!y9F&X$<2kjrxP3!_@hFRr zHta!L+W2>f&h{hqrP7kuP2G^^e~c2m3b6;Ia4lmR^&%nAh{j1ornRR2!}tIC_E-sR z)uOx}6o%IE7AHR${?$z$@cDn`k)t%O?D#9l)ffANwuA)&_04ZICf?u=NYO$Oipm_+ z|AKThBYAb?5Q4k)t}R|-gGqSvb~|zqFR}HPYBjNVKhPR6xdVAC@tLhz;Js|n_}M%h zkgh+_dUj4Z4%{Exo%;+v|3A9V?tvrZ-JCM)G7MLc8vb58hjiVLAZ^*0#|N=_pLsdd zo(6>){6s;Zl%?#VIg4E#D{=*$a~^K4_g7`9ngvl z4(hle9WuxWs}nZwwr%~F?!FKL#JH5I?HkU@Ve>A{QJmIxq&(g&XdSn4@=IUY*X`@e zj>Nsvj;7s$&wFw=_wgI{K|qCmdG@kgGB!vHYYOTA=utgy!Xq;4XbNuO`aAyzlJMq^ z3bi2eR@~#Jj>TJ=#k{fs@?MQdfA|P_hsRl*uYkOl?KF_lvVhP3S5-3{hzbEEat$~DKP^*&dTI}8dB)qwtjy4f_4+iR~Ve#IwGveqg$UCE3M}L90W7g03D9GEmPrr)O zBMvxrj?Q<%`QLUfd-HwB+uO1cv4Fhkjcd2xy5)xOpYu%|fV7FuCIjGL95 z4&nNS%{%&GhS170l*fA+T1O;Ke&bii-Y#FpflQ{ly!xGo&wJaR%Z0L$UZA|L*y(f} zKJTk;30H~(1T!V{$8XN~mU ze2WFlNiuvhkoQ*Kgf=0_yO#b;{tn2S^K0=^=I^e^AAbLo?bg`5*~F5fUKj}hg23On zHq+@3Zy2z7ADWoE-qcQcyjP%g;N|zt`}x7#M{LMpRn0$-;_!I~g2S|9YEx)#SduyS4>oUyKVex)8$xeF~ z^6uYp{qPXvz4b!omn6tLjayo4Xg(HnRaM5U^9ljK1;ecPAn#AByLaz_ygA0EORA<^ z5xvbeuP<%J<{f0_>aXo01oY9k_Ne5c@)_*6x8#4NuTq+zJl+9l9eDXId$3IF;0ku+ zvfq<_qcnWpe)jxdm(*DROB%a38K=pZ{~ODsR>V>N+gpTH<>b|2Jsvsly!e6iFcRKt zVlsw^-8-W02`v`y;MgZdmlg&j^V?qrA#X`z*G3P>JLiVsZZ?)UFdQ%AlmL0Zp827< zzXD>G-DW;J1)E{i#w3azr2=b8VHQG-cdV& z;Lra9sZo8BBh)|tzjh_B4)YHKKF90+o&WJ>IEwiFh+Q&)qz8%po_j{@LAI_2%ve20 z({_8)cG!b5PxqW3gFT4jt-Ovm>_OjV8TNdC77H5sSRy9jQ*sQgvjxhq2i-Y4eO4Xz zpjg6th?pyQk8Weu4L;wJVsSAn&aP^B1_AV?pz$ssskD z5b%*9iGCyGZ9lcqcH!}s56asgp1k6UoX(MW-7164JFVF4{pr%j~}4^Hx})dfo7XDTqm`Z;|+dKmR))DBb#l zuaWBK{}2)K>Sz?WxufgU;tDc~gty3riVZ~GB3lNQWAT>m`O)SKd0(j)_8Wz~QyNSa zFF@Y%o;+K}Uc>?!+RG-d3`2m2N^qkA<2@ zG6iS-PHww#mW=s7%f`X}J@vo6MQ|pwj*Yh&6#sVbgCx9#ouzLQc`MTvFT>(pXI@#n z7xJ!K&D1vndGmh_m%j^nXKgK)&*_W>388oDUhWJ5meRqBn;~!8rC(>)Lf*R+rZp?) zU6GoU>05*izbvFE7ZL|LGl6`kz@*|NMVzH(7OfGg>~h%UktDo@ z3{$d*yqQ-XU5dqfq$2fk5ahkzsM&adcWCFwJ)a-^yq$U-qKn&S`s%X zk9Q|8Gon_mio2r256l z@-p)3a9c05_GRS1^FKw*_jpOb`F{yX50YhhAWrN-PABx)v3gMd%ALicum^<+$T)w2 zJ&1WocEwZJg9@ewHI(27(%YogbMrq52F!V^9ot|JVoI&xWrsazK^&hSsJVe6oi7|Mi>h zN9p1ZNcK`IPsx5=2l@^6HLSBHV+9%B&qMz{o9cTIA(+fM;tOW&oECPFlIcl!OFxym zNaWq+v4RbY_j2uT;c}2S!iY=DG4bHtb8RmT~t@TQfn>fyT8veEi;U9GkayzDIn<9m?ZP ztYaTee)mo1<@E*Fkfg5(aS9IjyyMIY+sp>dK|Eh+p~4S*-rW_yH8S^zQ2h!rrI@@r zw(YF0Iq4d+z?+VgH|xPvE3ROGAK0&;4@?n-kaMcrI!}-jm;7Pa$w~;-t&+KCV;P zyvtrit6zx|1jo?0UH)uyUpcV{q?#3Mv+-<{Hz1Xxb>QW9D>L8Onwbr`<5JVzcNL#^ zt7YAA*1c80-ifP!#R~kxiK17sH%UwEpnBfq)?sXMum9`7!u+31L&96a()j|B_lcrN z7A)Q)H-}ysLf$uevZNMxf4XRd*h1c>-(_|<*2MxpCJVmJ;vrz)XP?D~6R#u-3+!50 zoO~+D)c~#tmzjC}?F-nvi^4*!II;u*2O75|qD|RU6r1<^x&ynb}^zuZ{=IX%~Zek77Zn@4v9~aT2KEy z{~vGiri|ZV4`L+gLF-1H|MQ65nTyK2SUo87vFh}X&_dm#oj=!pgFWboy6(Q8@C#DY zpROOclNbwbI18V%%?$>|J&|s|;3c;DTVWL)dP4N^ND@eYsLaAw8s_#LBj!yFGNV{kJ_XMfr5bGw}RB z_U=5arZs#V{@%Mit+l60nu(HgUb%h~H({j<*6zw7Bc=UyWf@4Z=C2bge(eY}NR z&;-0Mt#>Ni54`O@9M{Hk#aOF z>tN5hWc=s)e*v!pZ_{xD?vcC)m9A2u;=OJAxPIM$x9-w?v7dmq+u2p_x1d4dPSmW? zEQ-fh&e(GF?!iU)LGF|((}B0f4Tl{q!25(<)w8wmaH6*0x$RXS>IbARC=Ky;T+|EK zl#SCEXx3-*BWm7j*A6|qf!X;Qq>HjT*3rz*%X*9Q4J{?CS!cTbyl(Uj(ho)HeB^;H z7QD$eGP;7kL1N@Bibyxm>GG>LW3GI4ddo!I+hnEyC3)9=o7;_w_tH~6 zK4}5((M_K}64%~H-oo4ASG9n*?)cFLw}5xn%bd!oz`If9xZ`i&y>MrC&f2Iz?D^7~ zkKO*`el`!3& zKKn9F=y@;k*~WWx%>w`aG~lz(S^CY%*sm5>&!^^fdEWgW%U4H_*!B-I|GxjfbM*Ig zvw;3z(qRp6QmKVjeAn9L0*+V_g;biKj7uM-Cto1Du3N#um`?Ds=e_*Qj9bn zf20?6;PAdhxYqS9F((;Ggr^`{bvU$?!epn5dS-Qh#eN#qD{s7 z?u?Y>w}JPP8eI)F zvD;@jd%Mn-w>lDdhYv7$JOp@aIVRa`-57|KEwCKjYXCLxLE0k3n5>R5H1jjqJ!Zl-6}UlK_wMEApXqsDST=QJSd2ARaCJmLiX7kn zi%6KEGBUTg%k$ovC|?~jo@UKb&;P?)*n#)JiK@{g?{CxdHK};ddeoHp3V1Ktp=d$y z9{Dz8#B|{OxnxD7U2;6Gj3i!LxM>mIw65a1JMf;Vlejq=cyBx9e6#U*Aa-)BS;mtI z)V%Y}#1UVA>)n$s_3MGEZz3}a_aiP`&)_sbm=54c}-^D%- zosV~wtPVSx`9-Z>ke8#TgdLjIw{_rHdfvOY)Qu<^H5U72dhu)C2m1d1eeR}!_9Uw= zzxSTtBVQd?mkc|x3EsWMVKA61R0RLmGTkIClJAlx$vep_$ur4A$sNgc$z{oT$r%YQ zsgxX&?3L`4lt?y7iX^Kfd6G;?ibN_|CW(^FmxM`zB)*c#k_i%5$tcM%$smc9#7xpp zq9^GgQIjZ11QL$8UHnu0Mf_g;O8iuOUwl)1MSNa-T3jVQBHkz7Dc&Y77OxTKi!;T^ z;yCeA@gi}!I7A#Eo+h3ob{CHoj}&8KJMjRqiP%8gTdXDSE|!Q9v4W^g)GTTeHHuz} z9*gdZu8S^-YDCqdW1>T%J)#|=Eu!_JRia!`x+qb!LbO=4P&7vrESe#jBJvcC6O9oK z7Yz~Fh%7|?MfxHgk%p+7NF?Hkn8Fs}H{nO&8{u=|L*Z@VRbid*tPmGg2oDH%3rmHY zgzJQb!fauxP%2y|j1tZlh6#g&zQW1E2|`!lDB&>SAfc7eOxRDTC+s0q6DkP>LXMza z@Kf+b@Lupr@KkVLa8qzaa9(g)P$f7b*eBR2*d{0ztP$i3G6l(kIKfiEB0;zyL=YgD zCYU5}7mO8*6kq~7!2p4Yz(CMjpe5)okO&Zg0@{W)qfKZd`VxJN-bJsYm(Uut8a;*{ zLieCM&@JeCbQPM5rlX1I3Uo2L5S@btqchMcs3$rO9fJ->hoCm71==6gM|DsQv>Pfy zc_wXAvB!Kn@_gky2z6vJNRkvXN9oiY!B-koia$5`_37 zlaUFCD>4chh73Zi5HqA7qKEWA)DR^^fN=Qj{Ga?U{P+A<{HOf;{G0qM{PXVnHPdWEFH#t{0=Q*c2Rh%Q7eVm<~ZJc7x8cseZ zlatJe<1FPY;)HWTI02k#oJkya&REV!4#u(L4B(h>3^=_xTAc122?yaQu-n+p>?U?2 z`z8A^`!4%B`x3i`UClnmKE&R`-of6&Ue8{|&Sj^w6WJ@+i`fg=bJ)S`8SE)+Pxd(W z81``X5Vj55g5963&(>jUu)E0)-ke{Z{wV%;f`5Mke}4jhe*%Ah0{>Tk0!-I56t;pc zX~e#8Y#RK#na-(8A&yCngg82NKEzR}vmrXA216W~>JM>5>NJSMQ@tTNrcQu3EY%Gn zmO2LF(9{tShor&@bLQYwdx(QltsvT`nnScp?GMp5wJ$`Q)ZP%SQ?(&lrK&+3n5qnM zKq~A|nU<-1h!&{|5Y1DTLo`cS4AC?t0-{MuI7H)=P>B6gf*=~D_(ANKG6kYxiWfwK z6nBVyQ(PeGr;LKwC&dw>Udj-Nx+%60d#4P5*ek^pqE1Rbh&@yKKBrSpXD`^qLpGor|{zwXg*qk&I;`gK(5Wgi& zh4?jT62vb_9uPk#xk7A88V&JN(r}0$lZHb4kYoq(ebPXP?~=?QHYOQCe4C^X@l8@M zh_92hAihdch1ig!1o35(5aRPB9>ix!EQn7NmqC1z7!C1p;zEdz66ZpEm>2@_L1G}p z`-#2~?iQ40PU z#ZvIk*dPV}jP+9R&nS|Df5ti~_-Cw@f`7&uDfnlsmV$rADk=D9tdxR(Mxhk^GYX{O zpOGIA{uz1k;GdBj5B?cB@!+449S{B)S@8i7GvmQOBO@OCGt%S1KO-$3{4-MH!9OD< zek8=?cn63{@!+447!Up#3Gv{cA&m$BjQDs1h;i}YpAj1m{uwLc!9QbpJmG&?JmG&y zJmG(FJmEh&j_@B9NBED7Bm6IlBm76i5&jp(5&jp%5&q}L5&q}J5&pyD2>)~A2>)~9 z2>-L=hC>XCBm9TP5&lEs2>-L<2>-!xg#Vdw`VfQSdO-|~Bm4)%5&r$-2>&zU2>*U@ zgn!>S!vA!F|1?7XR097L!oCkde=;H8n}9!waPLL1_axL$B+ySF%zF%j;7*7iPkQ{v;|!{WW-GVxaN2Jvcfo;X9C zB#sp?5l4vUif4)a#Z$#z;_+f<@d)uyv8~urY%K08?j_a~tBA#7zL+Iy6@3?d61^3@ z5Iqvz5nU5q6rB^D6jh22ipoXXMVm!MqLrc?QJN@0v|JP|S|FM&nkn)V`G_Wp+(e^A zj-tULYmvFgNYqEvQ=~3Z770aM5kvS(_*M8p_*(c(_&|6|STDRFJR>|IJSyBT+$Ag# zZWOK+76`M1DZ+SRj4)C-PZ%l;6iyd<3q6D`LMNev&|WxDXeu-m>I$`mszOB}Dr5_O z3w{Vb3*HGD1WyF_1UCei1+{`xg5!e2g1v$=!B)Wr!D>OCAVZKOh!rdmL}QbLr0^I=wQ?uHAjumK4?!=9aTn! zC>LcQzmTuU2jn&K40(XuLh6wV$Qk4WaunH*>_SSAjmTQ00Lem9ka#2piA3fhp-3Py z9q~py5EsM=aX{>mfru$$i0C5Ph$^Cppa`4)oBxCVng5R8@CO+<`}^zfPvGxQ;O|f1 z?@!?GPvHNLp8zYl5H^0Sq(a#Eu@VbmK9D1?n4 zYk47T{8-BhVdKY&DTIw5YiS{D{8&p0VdKYITnHOKR&*h3{8&+iu<>I>7Q)7lwWts_ zeyoT>*!Zy)7WRU;pb$2Gtoeno@ng*^gpD67ybv~itht4-@ng*?gpD6-b^+}CSYZXQ z^<#w=z}}A)QUIGj)~o{9{jq`zVEf0KSpfS#R!{+K09k;qZT3ScA1npyxmLDrN4*b1_I3SckDnp^;zL6&y`>;_qr z3Sc|Pnot1yL6%1WYzSHI1+XDxjW2+|7}mJ_r4ZfnBO$ux&xh!eKO5rM{9uUA`Th{c zrR85QpVkL3GGBhlu6(hd4C9FT^4F zy&(?H*M>MKUk##tzA{9+d=W(3d_F{*dIdFfRh)fV^;smU*ENE%JgO zn&m?TZjgE10d?>nL_N7*AJpz zULT0Mc{&h#=V?OhmDe4jPM#vfo_PX@J@U8^wey$|wQ^%1YUV~k)W}@`Q9XAKM77*m z5LI&nAa>844pAj{GQ@7V6Co<+j)SO_>kLsbcO*nft^-7I?jVSwTx*EJTnmVTTw{o6 zt^q_OR~I5bw+BRCt~x|+Za0XWTros;E&@>@mkp7XL-=Rr5dIlC;Gfx^1OA!6bHG2d zEeHHFTXVoavn2=oGk@iPf9B5|@Xu_{0sqYJIpCl9EeHHFzvh5{=9e7s&-|P-5Momf z_-B5~0sqX8IpCl9A*UC__c`F7`7Q_iGaGZ1Aim83|I9Zz;Gg+A2mCW%WrKfaLpJzl zzRX?-@kKWHXFksc|IBCE;Gg+48~ih$WP^X^<81KHe3T9TnGdtUKl4F0_-EeF2LH@^ z+2EgfHyivj?_`62=Iw0o&%Bil{+Tzk!9VjxHuz^=&j$a@YuPFguV#aPW_>pJXI{w$ z|IEwT42YMqz(4b17Wik@WzC0pJ`4OaYqP*VvnC7tGtXs#f9BaN@XtJxH38!3Ebz}f zl?DEp)mh-5c`^(9Gx03&&peR@{+U%-;GcOs3;Z*WWr2TYWfu5nR%C&H=Fu$h&peU^ z{+Wlfz(4a)7Wii#%mV++1DW8Txjz&9GxueJf9BrIaEN;{!9TM+6Z|uGXM%s`u1xUH z+?fgfnPr*o5O-vPf9Cc~@XsvG1pmyEOz_X#mI?luTQdhh+>&VuadRg4XKu;_|ICe< z;GbEX3I3TIGQmG{eJ1#4uFC}f%(a=|pSdOz{4-Z)fPdzy4DiofnF0Qpg&E+VS&#w# znfV#upP82d{+YQM;Gdb30sfiU8RH;kWq^NXW(N3YW@LbWW_kwrXQpL4g8K>4g6!>4g8q>4g92bi#jBI^jPuo$$XXo$w!#PWWG#PWWGtPWYdnPWYdfPWTT` zH-k7Qo$x<9o$w!)PWTT^C;W$`6aHtV6aItK3I8+G3I9Rqg#W-a!hb*-;om=v@INDM zE=0dH!oP1C;eUD>;eT2h;eTox;eSdR;om2X@IN_?@b8^Q_@9(U`1eX9{ClPm{wJmp z{wJgn{yowN|L$po|M6*r|8Z$5D0-5CE1YCVK1*Ie&tD5y`gch-NOGXZkC4oS-riX< z7<&3%5@qP+zl&c(4}Vd70($q&;sWT|qs5`ntGkIEphxc`Ru%I_zeMk#C$ATsf?m8t zv>JNw7|~qly*)%DpyxIeX^Mox-@;GOW8V;-gWkGKSR~9s_oG{(V@*MqK&Lt#9S@%aK5?FLZg9?Vj&jO4 zMVu^7EN1~HkmJP}&9Ubgb9!9b_4qk`vUtoyPUm|oySgKN3v(Jeb_GSp=@)u zE?b4oRrsOsR^frdWrdUf?|yp1Sm6RV6X7Ks4QC*Xg+1ZS155A~&N$o=T!1qT<${fH zh9N-^31=331TJt!!CasVXA-#R4>*JH0KE(Z{{6+=|L-6F{-F!}1Vjp4mf9B4lwG&W zKcVxGIA+wT``5(~P|7OTs6Euv>w)+1N zqoHKB#s1M;G=$7H{is-o&LXpo^;bWl!DLpvu16_4lgu{E)v8B>$ZWmUJX17~%!*X+ zTcH7Dw)RSX8|qJHYwo_fiOwLi)$`f}s2`cFvOlpF^(C{FT(@L&I++#Rw)%ojBeVQd zr+v|>WR{n)=OQ|V%yOq1l%YOkmSZI`MJJP4*5ls`QExKK++8*to%CwXm-LuN7EUaUb!li89o z=TdYOnJo@)JcK%tS+t#I7CMs5qBv*E(Gg@8$#Drrhm%>v&c%tSBbhBMxY>#hBeMk_ zX+2N}GMlgDw+zL|Y#u}15*v`T*v>%yyR#cxs4asccVy~5`0hvu0-eW4-m&`nLYpB$HYh$)8C51TdzU?ts1ljksrV?MieyGS zZ-+|AjCec=6_Xk9GzTgoGvelVR7hsTy~3z~%!s%4peUIUFF8RGG9%szf%3_Wc!VD1 zks0yCG0G(~;@!U}hs=mqrK0SAGkCKksz7GMi}+9$nGx?TLz!eod_f3hkQwp86{MZa zi0@M%zsZbvoj=k>X2jdikybJzzC(<(kQwpWR^%6%5ns7Pev%pSQ9$GenGxSmLz>A< z6FKLLd?z#Ydw$)JZ)B!+pn5s-mCRI^M@>M!kQwnMcH}ecVlQ`r!}Q-N%JmZ<|87{qRQEfc(lFZoac0Wg6keR}U z$-c;QGGjU9>LJg_j43GcL7vJopY{haddL$p`+eNY19|*!W*#^Yc|>Ndb9X;Q9+Fwh zActb)0h#?`nXf_ali82brv}J9GHXue9YF4q*>~5e9OMp}eKQU_gxn^xFYh0jBDcuw zb9)8{xk+YCtFNXYH^}UhSBVR9oyzgg7HK1e;8H5QqwBUi}m z?R54-GJ7#c$rCwGX3s}B6d|=_ z_Kb6H5K=>CPwqRGBj?EMaq0SM+S7-YP!1Mnq9iBlVb~WT9cB_P@ec&V)W6q3u3>1F% zpRq8=cXr5JIJL$2IAD=hDLjK@FIjEY49_6#G)=aSg=dh=Cy&m%vNawrXuo{O^~WMy z>40?UGk69G-L>mvCOrS|WIL5x|2hC;+|`WJ5gOv*MBdkH$s#9izC@_kefCls6aG0&k_k zF;QRZ1F+1(_YKn~QuE%tv1Y>1`#ta!**Na5#ddp_QuCf?aqVZ0f~eE+-YKgil4gFE zJI+jXa#6&dPCnXp^fW#1hSA#P84f=9@7|-c-EJvjfA90Pl^5IK~8TRi&BZ*8%U>%R&Q9;QfCo6A#}j zdbkMB8MWEzGVtD~&n(;nyfclk+6FoOJ0I^?vO0ok<~Q~!XW(v$5_aWszuya*>3QcMn6-|BKmM@kE@#&>dfu-a z%6_fO58J@k8S(h7sU`bwTwH{EjzZfm0PhLj?w1b%Z}$7KJ64_wz{a)Th?sy< zuimaYx~W$O^u))?#))_LkKSib&0Dh0)78SK^YQkQ)zOV+ekb!cLJoNL>F3+10DqkHh(<}4l{rUc1fno>V#F;^o zx8Eus9V*^-KQHa60p5Xq7Mc*e*9R|uRRz2w3$L|rj*rL1%}XxNJ+ufv;quyGC-9zp zZQQLlzEgVgA-1`*dr$Tet7h?)`A8WeJM`NmjSgCt)r ztoaFR(52nReRjYawDBq?^8Fl-zy7&!|IheHT<^?K<>|c|u>lwA_$PnB`~MmTc!W9! zU>{~49oF_Uh_az6n=z%R#Y!80CmRLwt} z`Sqz?G4HCDBKAX5_0h|Nt(0|=b!@owD(k}r8*D;R{g zDjqj~nLB>gyh!}o>fvi$f%p6g1ETH&?_h(#FGO z<8FQk*kQ4cn)h&iSm3_Y&c}O{td7w%^LzE<#plRLirB9i8+*iFr{{gV`i-_QXB}&<7+C)E1}U`;yosyVByZ()XAG!#|9IG3mJPhq z-RGD50N!iDW1bNG|1XtQ*$NNh@meHvgYlF|e8$2-v5vr7@NDLi55W85EnA&WX#rTu z*|?>PJgFO`#Xbhyr~1E5lb__(7T88SEwsu zSL_zG?$)92|L+9O*!5d+3~qRCNkhgc`m?u;s*I;sJ`V5t4N|szb@U2R+j9SCB5`_4 zwF7VBb_|lYb-uJO74MAT%+;%aca)b-UxN344+SS2Bk^Cw zYqgz$cSGLEn&-fqUo|Gza%li|X?MM%S#N6I;Yf>QSgAICUN&xu)&>1k18UySy;&1i z-0pn5qh)oxp_$*?XqL@{M~c|YFpc6_F7&)L)m8Og_4CG3-d*|Gq)8Zd;6NhfE z71VEQ5#6fDjaou}o^=;_R6xm0y|-VALy>sUK}uG_l5{Xf~Ob?V>Y5ZklE8bsV- zNv=VNmy$Wv8dO$oW9b8HP{dm!ZY!)oJqu5rm;r0h#>aCdE@CNOw1u%;@;wp{&bT+` zCagjC^hRp5H9x`fH*I+Fq$L1DjSM!wpF;hL-ETIZ&bC%-<9yjTi-~WaCr+h42RZ6$ zP((~q=R3r<$?9;SnV*wK|9J&%ikOds-@*JREwpP&Q;gB&%2lq|{?s<**oX92kQ@t7 z>$Y9%`rja7*~wQ&WB=`Gmy`b-VtaJpP24g}@^;_!(v*sKt9`etGl(6e!@i6b;9VE- zs_#PJ{h?I)ES4+9RkLFYpWTEnNI$t3ybpNyW?AgDfgPmx+v0sK?*p)x=ii>3YDCRj z*I~+4)3@3d2@=oe*ZsMzB&y0g`sOJ|D4{^?!cS42cF~|_i%>^ z74NfNYet6v?*`{9-3i_$zUkjmfp^NrRnZ=8@pz`fij%5)BXI@AH+~tw`=KT}J_2|b zA1HX6JAsl{Q}f=_Sf%hbG+4sCmJ2J3;7C%t*Q;XvsdyJFx}1sz-bIgxYIWqTU0An$BJei< z{jOXac&B_Su9^e9U&kA@l>qOcUMX#NE(BmI+!+r~J)l0lwY{%rxa62N-c2@cSQB3% z`zdw*AF%i1$qjEi-`;zVtd0b{?x9Q6Ns9o8V?IZbj6`s~ZLrdorJ zEVI351#8f+)Sjb%!yz_6fAYN@@QK~L6Jd5-3n|?BSzL5$X%s$w*NXj?y&JKkrmpk- zq5n^M_;Eu0u>ef#;GKe&2r!GY;2b3I*6qNXc<`9yZ9o6gKq}satkBJL5%9jSQ#ocH@IGmNL+G(H02|VtKV~OJ&D-PV%OuP7 zTDYBT-0f|rrmfMU=Dq9H)ep08c0S%dvO4zA%x~1$v<74l4SbE;Ccexbp*yx1EP8M8Sdqj>MWSW0Pw^<*%{0@@QBS5Y?Opkq; z_G!*-o&dRNZt<)FSn%PUDnK=Jr;OJ9hH6{E>3uynclD$c*ph{HR4%sDc%|r z(p)+`3ZI#`!c+{rkECqVDhA%09hs?fHUwbP&rTn6u$8(&3ZMIZ__iln_!QYVLHPXP zhyJ5MGTwn&Y*X!g4N|nM4s)9MIZtgfP@bfOg$1%jf@So)y-we_8x%JZ@A<>>dGTm^ z-bbglerb-I)#XobHAKo+NA9qb>}A=1cY>UDmtzdg{%I^Y;LA*PES>_gPsT<7nomtG_RPNV)wxU0uK-fQ9)WaFwm zZf3{pQm;Ydo1R8o>)-iykgc*hCeqCB!ewdqr>RPq@btkqUv~VY?f)ICQt}ndXJY5> znU7e|O^zF+m)Q#22M}-8?c%>;t%a^}w!1qPr?}vHJi3i@%XR!f~fp==3(2X(o0GfsDg7eh84Z~7aD~;@Yym!dzFs7N`%%w#i$74#^ z{ohaa3RLM&Z!w;jo7Bx3kF|W;f3H|wjvJ(X9vSDdd)Rkz-0&gI-iPxJdEAla5-(mqg)f z9M;$S1MkOY`CFA?2brA6zE*K909(KQ@|29n)T?(&H(hnUo)*4JHtyD($4#+i)Vwv+ zYK|uPc0S(OvO0Ru%F2G((*7j-WOMip3OIZ1Y zCe7R~&wFm5e0Ah$Ty+ah6yKEd0rJ$VyD;sy>K&y1x@uidp?a{Hfju*vtKHfiMb&RE%Ury?V<#WxIFdvoE_Nvq9dH;~{ zc3}QO+!6W)Y4n7-)BLY5?DD)PkCm^E5%$=zYgvC*?>-%P6K_l(rsy?N=`93yzQ20fcwHBgE_zcAD6SZWj=U~tG}81Q~MrTwTg@ZM;!uC5^} z0P}PlFx}-pPH!RJuKN2zwD9q=aR>G|enT%(^RD`Saqx*PosYMYtd5g3^Sd}a_xaHI zN?65EQ`XOPdfwyLj_Hwf3dODu;F|TSI79ir{lA+L;kh=$r=Q?E2wnWw*z@w$v9(XT z0qnj1KL6hZ{=T9AH|ekj5$}v9)*zz)XBAH1QmsLQ9uFG#C33fe^8VpVSkNG4{22F; z3#Ztz8%riETqDH;V_dO!!f5>KeDU{1x{cVgGrKE1zCFS8*0kO11JD0!R!99f>qfnU zbeeQOL(x(bSCx%>dS#E9*C*;V=qsNY6%mC{HeCNxe-mS6bu`n=FQxhCwuxhvu;hka zQzmEspj}hOE9s4i>*tGoh^ZduQzXY4G-TMBqYVSPe*a%8XB`(ECz}7${~LGUO}qr1 znHI_|()s07HW2>b=yY=FOV7x#^OZCeD_P^K9!mAoL_P?~@X7#O1Y}k2had z$7!1RRoJXB_{vto`i{E(cxgR7@AZO;RST4YFuO%H_U3cwPj3x53d8>F{fM?@3#%W4%Y2?Gnh@yTcL8qlj3EX_+Ht# z;Fz94Ys;y5yH+qRo1N@@yb)O)<7wuXGV++9+h`?hs_o&{?CSrUZ4s?0m3?n(~=o@`Z?Vr`#r~_}}GZiH7-m{LesCYlle&@*r-l-ww zBMIK9&Z9xZ&57zhAJ?pokm63=`yKjqFA6VvJoyI$c+WR!DN%y6x1(M+1uRJq!1VTp z#Cor#=55zE-k@}cCf-vvPSR^)@>ngA ziSMqEyro&$Oe)^ILjl!7;BDra^^mwYk$);Pi|GGnmLeXx0aEOT_lWt81-f_+j-yGKkU`H})r%x@R<{i~+A$oUP6W=czH&=7wXlFla-YUDlZ5*rC z`TGADSsm&$^Ly5RWR(I0g3EVP>68y)N*6z|PFbJ1NB#H#e1a z8ybzfj_9#>9q`7M8O>1!-q%^!W1q+Vn1AV)Z)P86z~1HtA^K3bJuwNt-U+8b;0A==qsfpXYQw-Y;c!n9MP$n#6<}^cxFk7#)@saAvj@s^7&n!}DhAJOF-q#&Mrb@VbhA+C%0vwE9#;7xq& zlH~0$Zy%qE_wj=|!dJlC_GaIq1n-@j{2Z47@0FO2SitzHJ(f=QWNRu?u(` zKi_Kb6L^>MGNUil_+tYNZ>DTtL(O~1B^QM&P8ztSY@GJ}4`&^9sCgG=Ec~%Kzw_~4 zE~{fL&HUmHCN%oRDPkVsb$8Ah((_iBpxGCx_rTTWMd_ctPv0Oh0-N$z_jK;^ykkw} ztK;?O-|DY6{#m_EJMbpH-b(VGy)~Cd#e2@7Gh^NZZ{vmwcZrJ=4L=8DNR@4nBY!B zT-HzeixcIA7j)`omvnjFU)|)ZL$rRh=dAUA`~Ux=KKy@bFzg_0I;=s&_p8Y@Xw7X` zWvVqOxc)`NAy|VZnN0TL!WyK4EKlG@4RBa?>GRI`cT&9jiq9oW+@kT);x$ieVGU9! z^+`GhhgieQdR1Qj{+Q|lZbSVv>NO~9aGcPguR7jMHg4VhS&<1xmr(Y_cMX$viI?*_ zUH_jgtK%Wf{A`0x-LBc9h_zk`A9HE^cgi|RCi{2j+<7*|53{SC-n76|wu@?7SMw=y@C6P}dme z>x%EXGNIVFU5*`OiPz(yhNrteZ&&&1m}M4!uGgVIJ4mYzyn_sWnvlHxkKK__@m3fZ zP*e@Pvzyxs2;S>Q+?+lNc$d929Gv|`iXZP^vI89(jjuoG*i;0(hptno6TuGBYW|qo z_Zj|}@g8>6lN@T^D~c`8=g(5d`^m=X*m=Ev_?>$7Hn~((_n@lt@s5?%VM#N;Cb*D1 ztWXi#ypO+R_Y->F+2W;GjgmcXJA==(GNk7n-)y08|IE0{?;!ma%2&q&$zsObls~)& zcHkX|Y;`1gpMAVrOvQVdQ&d9@@HXx9&Ya-A`2N245x{$dTibKZyHY&CW@qEK(b2eX zaLesv;63DBslGYz4!eRUk4*E&1{qhVlt)wZE_zUXXHtebZYLY(shGUR_Bl20u*J4h zMm_0#yw}U>2&b8!^zgzjN;ed-^8t^)&E(LZy`8mH(e`JAJ-%qeyqRa;$Z>Px)FrIs zE0$fJH$zX(I^tr3_5azN4Cuf+pvbe92OS%?I}a z??A1wlb!0NxY-b&%yOq_{Pvg|6>-43J*#DtJ@9TbJkx7$qd(^HHI}#EB$#rqY&Poj z-Qfq-@$s^8(oL6^_1#Q;dMh&Ect9n$^Y#DcvO1Q~%ugruTaI$BBDO7-p(~zA&s$nQ zXqO8s4EI&Nby0H<{n=Z_n8ky!QwO^~ZzuWc*f89q_eQwA9!MQzun-VmlORh zc4sDBE1zAoy~{U9vl_3;Rfp!OCHk+E|LhKaFW;vhaJtsh@M#Y<%px?Y6cxMcn zQO^V3CaM+13BWsHOUAl6EmGWj`=M5IxV`1^Gjnw(;N7i<71jp4tqwn${NScPrc$k8 zY8Xb%yKb5P0u?oNTuC-Ab9A-($y3yaSf|HhVy@5Ye7wmz#?s8M{)FiFd!{m`Sif{s zXaPO%B+JRxIZvFh1xJjfYQ^*o62oihy>O%d1vf~0$XUmr`y-0r6+5tc+jrm{X71-k z@-~UP*`12Fef+i~TY&dG`|t>Ycl8eM!CQfM3~SHbq0LhKu+Y(=_o!%m$FLa(jexgT zXm8JcaC+-VaqX?@^Zr;+k6kSSrjeaicJJC)Z_m_O&1~?xwdJO&l+|!@$ZwB7e&JFkbc-J4}r$4iG zv8UdgoUzzHP>`#Rvt{E7r}Qw|wvn3mo?egGRt=qx_gPsT2WjTFc*{$FzY;}kZ^iyF zrYZf|+f6zN*oawv*!NbO@BSh5*Z+@ZjQ`=|pws2|-nx47)zJgd-&y*%|L??2e}}2T z4suwBHE3bM%~o;^dgeT^C)FAh`{ZqN46H$uNJSjdf2AkClxJ zEt!|NEr$9Tqk&t0RJDetkL9liY48VJ@!SEH2u8rS1Q7{EoEM1^MAA zaZ&pvV){cY`hKnFsP7xP{2HWQDPJ9ttJolDE@EW)CXfX+=*w z=L!q!MmMfBh_p1dS_5|<2gUW-Z0`Ig3D%dbV0`8_D?D@+e8gEv5_#_N? zZ_gZRcM^D4c$xJ#o)>^gFT5E0wuYKF$Ea4nm%ch4CmUB%sh>Qs=Q7Gw?cL#C=ljHV zKHe-@9Up1txAgS0w)h)LnAH&eQqcu^-p_v3zCP~fh#z@><5}@QIj$ge%kyws-M8yE zNQiuO>_6FS?25EMtM||jyyr30ElJ+K<8m~qcqcZbKga;yJ#GA-q{n{0q`&X%XXGAnzN_10) zx4--|Zu^yWJ06=*^XAVCaQa%>`FN+w>JZY*@9?qVoMpwz*g2$c!Zn1x|9|0~!@v68 z71wUxVn3pip7$AT#>?8(hFyO3&M9brAx|9+79~{&{&_fYNC)0?Yuay+yvq*-X;ASV z*k@5e9`JrpGB>Fs@2NYl^e_S5rbaz8X8`XkyRu+n?|tyjo)2e%w^4c6($~NIF~4=K zBctyJQ|`S7?|Zq>_qiHAT{iB-dSQNLf9lQ2v~d|lGqBFb+g?`344U~(+dC=jLzWU2 z-;%m1&77Y15G&VdN=IDrcoxHkb(sFz8{@}2$E9EG)}0a;w1?%AGP<$F2If zIZE%QleqVQ!!J8k9xZ(pakrWL@O z{n;vQ#3_Hw#UeSjdkgg;Hhti{m+E&_adOo6XU=Hw}@p1h<6nHP>Yc;=s1}XaVN5?T{3AlUj zsCeZgQTTI{o$-;t+w*-YXAkhM$+)9&tkNHQSK81g=`J;Its(E0cmJe{ljBwvZ_Yo# zq2|5dTkMXNo}G`kx~z^Un)&suHfSF6QyCl5WFhU5N6-67oW;n+hXe4&J=ZU#6TH4-1wmB=|g(n z-q&plej8856@S?2Kj=x{|Fgb)9MEH4S(jhEecs7e$0e)T!we(-+}`5Yfp^5t#s9v0 z+gX2_4i)c+D@PAU0dGCahc*Onld|Dk0)e+vzz6$hJri(Moeftee~ZFDw)f8s2Hrb& z%&$8KyjQa?8dvKEU^c%lpJ|&xz4xwkwm5d-h#EdnHcri_yFIgndiAdK+xSgEt@HK& zM`U%JpqXEj=6)`7jS{9=U(`ETf&T36x;>5F4+c)g`<)fg_fmDbQnJm*0Cc zl;o>pQ0rP_JnwJ+Pxfk^`giF6$97nQR)h`y_Z7Rg6)HwlYf$Z(@7iNw4f5Z%L_q{= zkaE(fFYd4grCX#fvm26tzb&|aB|bO`KQ$q=v=6L7)(4KAu!MV%xbvA_+b#VuWgXw5 zOaJlxzd?)>u2*uqN%tKK5nAz|6iQe2>txU2M=7f)!ns*{ti-x-WTU+?f(T2NcWeoj=V1k!l%3cTtRZ~ zzQefj1*=Lm0eb zx9{o=`oKGGT3c@m;H^G_7o@B0kEN)5EmY}Cy@L!GadWfwzV3L2Y}|;otS2K3sChf9 z7!0+zcZ=3) zS5I~5@;k^$8uHa~=LJIJn>~kb6XI>N@vb05cDDZAP;Q0mt-pcQc(?a<0f;6Kv&W*;Il&kGT z;oW@)Z*<3PW#c?X%?Nh*ME!vDlOsK+?;qazc)QE$cu6zAbw1nAvVSRI50@O$|22u8 zcWX6j>uMf?tC+X6n3l@1gH(F(uMMmLL!{mNm!28!n}7;|exQPBHIM^KN(*HoA9k=i_}(R!1Yv z{G!?}mzH75*y_>Q*F#s)^H%;C!WmW*iihdoMT@r3-yq#8L{`LC?dkHo>+R&L!)nm> zh+&0)c#rD9dr6sdDam`lPA`2b-q){thD`_FwZAvl5*H`7)Q&&V47`88_N&Smlz?lW zpS1XAOcd_Q!^1+^R z+??pO&F%idU0t3x!$rISK4xXJ5RL)nx&(*LQy z34K`|Uuotyq+(doL_=llcvzMf_Irq>x;#}Thru4 z-Esc}oPqfJpZAW!`?amHP=G`1pv2Kvh$l$hZ*3Y?=HQP>j;#z7)KT-kp`)=Xs!;_e z$89?MqTH~8n)f^7O&SjVosai5Ssfo~=4XFE`)h845|%etZ%^qpdfrpC=J+M`n1ye+ zqS^Z*m;Un>4FAxAqEB7F|7T2*ua4ip-nWe_`Lly`>%cp{O;b$rE_2ysLd9Es$nNAJ zz&k>6^d52ccJQNb(F=jMPQL$uB~udc@6SUAmQIPnm!z0)5diPR+;KJDz}tqob-Fj4 zy|pi2F!$DfyuGE&+UC?6#qKyc?wS7Z8?Kquy!p1Z1|~_JkN0+29VpHGwr>5Xg6&hr z5?kFp`smT0y~RK39*jy0#i!Qgt@J|cXjl6?`D_--KGx-TkV{hKt7B@@@+<4o{+!-& z?Z7+ko%sWj_n>Rh##Fq;IX$_Kzjj0|6s}cM<=f;IO_w7UN(4`e``z>fILNk-5^YJHAXdu18D7^+*44aU!i) zsrSv@osV~mtd2~Y`F$=o)Oyyage~;88B*j;&wJILupwKdp?ItHpn$+q`s@D;`*HnB zTC2M}Z-%9Ob+BF?$Qo1nXZ3dJz&m!8xjD%@k~ykB74H>8(^ohFZ{NDLE(Gu7OD#oy zz}s*|)ECj11bpRQK`T2T3LkUsqPsEht`u18)d${(*XHE=_4CIHH$R#%_&=__CFb8+ z5gpJSUo9IqbyvAh>2&JV+k02o{0X-@A8)Cwj;S>BOVAy%zT0tS?C6Hp_WE7)yj7Ho zuO5HpgGW4%>KPwKzd5;L>h}5kJ@Y~TQ$5K4t^e+!zVg+v@A}mn$nt`}{r~^1AN>E9 z{~qZ7Jv*#H>F&Jg>gH&q=_i z_h6LX;Y8ur#Y0xcLjQlnquRs@-a-2AxzX&{?*7<a-3`R zN;9SZc!N|4+o)UM4TVnE|69uH*iJJ)zV5q~F-b~T{n_^(5jF2=cZ4&VN+g#u7vNFK znhT8L>8~Kg9{;xD$fc28zyEiaua4jU4|{hWPSw9Qj(?LvhRide$(SNSSSUj!C5;-k zDM~VAR%9koNfeo)G^tdQl)Z#RQWViZGDW7$MEu^1wa<4y=l877+Meq?*R}U^b^bY@ zI`?ticfCIM`+cwX8nis6eKKa2*c}wSBPBc-$h@=nzgvUF`|#5AN6P?jc1NyV2=8v4 zc|vCa@33&oExr*U@U9IN1)ls~u%!flehT2-6c@8J* z;5%3)VSF$-uK2-~?Je%uOYG-sMPdRBw70~vqIG=5$!}eUn4{nuZYU|#vr5#s7nisC zGLe#_UM_Id^DI#xXZ*`s3oq>cy}cou?s?a4p{|bQ4^t(oQfGLZQ}8~`aaotlTS4`@ z3Knl=7gaA=z*~bOL*j>zrAe98u!cZ=30;z}jjB6IP|>(mij2ER}WeiCBow zUcKE;!8`otJ0mjh9VRZySiIltJN!oh@P6=Spc%P(dzN!eW+>pT*tl2um`4a4P#L6> zqvZvwoA<^eA17M=A^1%Z;Jv5n*O>M`Ybc?8Ir}F8>>H%xR&uxmcksc9Xq=JOsXbl{ z*f&TwK6B3RCDI=6i)bB9IQc~fmE{22B^HnGV8wrW zDgq5J-&r3TJJY?*D0qjRIn_nxO%zaDjm6u2Uis@)fcLTR#!Sky zx04Px<}U|lZ*~^4?tMGG;L5e-A+><_mB&~8?g8F^ZkS#=aMT+59d>GO@ltHw=`Ppv zjm7w3a-6gFzTKeM( zID1R2y%Scx0e|n^WVbB*1Drtj-Md?rx;i-S7`LZ^&s+XI|Nq|{-2X#A8_fR}6g?}4kjhxnr;{rYC^|yxWTwsZHYYlrv@=(#0y)b>YCnW^lRHOT6 zN1P`-W!(FWAM_yT&lci$Fd&VoR+XEqvxb_Jel0)Yh~0zQkJn4T^5%t`(7076sy6Yc zV)r039R)u4HzWKX`cwIj{TOl`+i~(+Un1GTWXcO=MxK^+hJWHNu@6}Tm@BJ}z%@$q zOHVz`6kkj(lgRMp`$Soy0UY~}=MF9q-Os*6^Vm)K;N22Cv9+eFPi z@dDny6Sb}gZ}qdXqfLPKtCm=nt;r#9N856ffSaB$+ZsP#8Nhq2K3B9D@E&X`5$jlP z4M|wDoqMl@&AWzZv&=7p7beFokyK8ECa?#jO*z+!jhE8iuTJt|| zp*`N@I*M@e+m~dS)K|s>buChX4zBOUJ%?DR@WUy}h2yo2iqij>Y@xk%P}f0Ph9m;!FtdO?5fj3;^%e z{%ySL5<=iHzbTH#T)fceo;``lIrzLS7j3B>tvw2V z)q9$JBn5v!B5adNy6j2+ya_^7*1@>V?egsFEx^aK85W#bx>+!TV_!63zUL#j;okv18#RA@Upvyn5#D~D2eqAzLH|7cF$wpqb0=)084mxWG zc$YtYv-qNtHDpj#P<)vMoA=!(9!x#*eDDS|F6#BVohSaGdyi$Ek!-k0d%W+Vb^ON3 zPgwtytLs)C=ycsPxm;)bvp4tpB8|~=$Ki(1Q-0N7@E=Z0i+-78^;3iH_ugeKB~;ZB z(4h9K>(t-#|Nqz!`M>#t!2D07=s}k>Nr^}gLgs({HCq>8^&kbi;xtCkg9e?AL%2Z? z^8OrE84U&``7i2S?qG@CuYK@nd6x&g>9+;zZK*Cuk(hWoW~2$a9+$MqXv_*~kr0>s zqmSK#x;fV^GK}GY$#J(8)tV!Ru$R~$*LXNBg=ug8??LOp%g=*VvE?@_FSIu1){dYR zKX7-D->0Ha@vc7%ulUf*ePB8M{Ga!5NHA{Ub-M3CQ4+&c)nOX*v~IRC{=*X6|FyX449o+Q<17@mKRNImo3{nGX8CbL+T%Td z)`6E_B-c9|b!{Ff;9gT##~FOy0_-hf?+gyZy-oTzySwmrkO9NNt|GbgfBqk^HiW7= zw#C}byOTRJARVCKeX&k;kj$Hdp?e+{Z_$9wk}QCCacYB+pJjH{2K6n!>4;= zyiLR+&fMV;r2F~5-if+8ey&U4TLQiy1vV%9DR{>g6%)z4zixZUh{gL(Q1$3S!21Wg z{4_HETPIFzzXEt4Wbb^W1P&*RYu_m-?C^wjhE$3h0B^ZC$8B1GcWdcYv#;$|5J%FY zg@ zw?DrCp8tQT*!AE^TPJS!?%mq+L)O^^Hu^;@zp9SE_a?}^O!l_WqWir!L9K+UI?|<_ zOv1stxBs61|8EZN|Dm4^mRMVg9+a%=GIKzR%>UjyH?m{(ps`Ia9*lV0)m5?Bt-%9& z(8G-5qzcf3-jozrs>X)EE{Tpl{p(SgI+l1%0;_@Clz0yDCf-~%X=ZtpmVk&l!Z;t6a zJeWcEya_iQsjEXW)E#}jg*655#CNfO$h@1gzq4ZT*3r~cm;k)fG{lFI`Tt4C36W=j zw=yXx<;g|xg0!7lTR0p&;Kd&n5VHaA4Tb63A^~qJxxOIPvsRFE)?42;5;pH(MU^kl zBe-ElG)~z;)|I#yyL(Swt

uWT3h39g5cR2PePSQ)2@XEj*BPy~npAbn04c*WG0TxnJ)xqHPR?!yRK?*h}RusGwKK-aA^L`?d z%Ywywn{`zBAHe&jpTj$Z_ceyb!}kI2$Mf#{+=~M*Nc*Hu%!u%SSBJb&%>%qOxrj^r z0PkMeAC-)!tsvO|<&_p!v3bjw*(CNqB3&J+i9&b6cjtZRo z4r)6`pIyZZZ6CBaU-bo_H{s%mO9L$SaFi>z@01Nb?=gwRm-CON&^>R@RpM0D5p4hD zio@*Y#FB#dWtTr}WZp^oq0Csk+5JB262SZ~m8^0D;XUtt{Gv3#+gE+F;zw})pOfCb zN$a);oJ@F{^c3)BU68-T7w}Fd42d~|F9WXeVIl3kgw0!M^7GXBU)-u(S`jQ z*t{PwOFnyhlJRCF>yk<{3ZZ|&Acy5HqY7fihw&u3J!oPY; zX#afspz2k+=S|@JLS-GccM`$vEq~|#|JWG$zxRW{5_^QA2W4nBI+1%&CPU9d;NsxDzPktA;nu+yU#&q8D)0IgGk>%R z+T0u5*yd#g?dZ}uX~u_r4f4bhm6mvMF4!E6)9sR!agN3AK`BjTH-0%xlm7Sqp#En+ z*&nSV9VfqbW`zhIPaf!+(ep{Ui%qyasH0%7>A0s0Y`^_(>3k~g|0f)ff0JSw@brIH z1r7bb*2_>;$A*nh-!844*+Cwr;C*%M>C6q%$mOl$H#xYmc)vasFWU=vi>pXIM|f|~ zS8jd>cqiTObNZee0;~L9P`Z1{9ai`8o(e$*Bo14xcVLOFV-Tp5va*79Ya1u4eZXE~ zzYtifbxgV7ooHN38`JWl9oW2E(zdmKEvG%+jc6S|aPqtOP5a;v9bPEZw6gKpf$zAy z?SdxOFVnMvP2U#R+;YNy#ZKP&UDn2GLv+u(Qp%jFI@;64Dk6er9&fRy;GI@g-AC@; z4B`!ouy_l{JyQJzcxNqqm4xu#6eBx76Y$n&<$XPIKLmE{Yv9RP=mB5qxilRLcvpJ- z_*n^fZy`;KTrshNcv<)Hp8SW`TQsape0n*M3+6`SmJ=>7N)o~5Z8vUzgGrF~E^jrV zbsWaYuj=?Me=Q##$Z^MTTYMcp@58+%{JRaT;1;3j4(%8CcaRdicO|XU>Y;ny1nK=$ z)$v|zkDJi!1JZUByi>1;&%7WV>E4q4S)5qBk1Wa69ssn~(>bR5>po0PvRYc3`Umyicia?k)mXZ$$$_IX?Jccki(8r!PKx%moXf zaYh~AFW53*^XBC(oBwSi?eUI4>)^x5FY!R)>O3P}$eGjGDLu9sw|oD*cQjDW>wZHk zNL3QU}{Na&vNEi>K z#ALu3H;T`@t+03G`fl)Xq5^~4dKpyA|2bFJP4W5BJ#RuHb#+vv>>V~p{(JsULsJuW zDq#M1qUb@ll$h3%dr*9!rVv&S3S7zeqZRa^Ov&S$c|i|)7ZK^Q2Yeu1@I3e1wf!OR z(B5JF$F1%#)AZXN!;;_y>9J)K*E>nZ9i)1LdY7dQC!B!BLCd%QshWq)n>A1!j!B_C-a2RGCr=dFcx-?XC3dXao@4w@I^FXwb2v;@9T&Re|EPVQ zxxD2_!8@}swwKIXq5nNU7Vp|iSq(n`ZzT&;afJ8L4=PjIfVbGLIOh4^L*UGpIlH%a zy2E!mxbqhS-q-t^ESv!E%BO=$VGFIGlCeMPkB?&WJ|++>CsfM`7olu54CM{kfmO39nmNs-L^`s*Yree z9`GLgt{F1;F$9iC%oAVM?G6Vm{cNBLc&8Uhq?!QUD@Pj|>+P+e&Djd94MNz56Q<`r zJQv=$2;PLo{r>d27CwjFy&b|=+xA7$LZRBm2pK?+oE?03O zzdE5S&Tyq+n7;fx{HwQwmImFbg=_M$cd2ypzr6oSRUHy?W;fMmzuw|N!TXx^7$=#x zANMg{EZ$pH25$TWyxDdy9+RL|a>0vWIW*2Q-d#ld3^wmu;pW|S{j|qB1g+yf zPJTvuTjS#7d797Z=WPpKyVNZoD?kX2Sn^OXhOze!+eQ>5c8?)d9CBXl@7j4z1$@PJU+&i8Jxs=Z88U4L?`% zsl{DlcQAY&_$1^6f6`gCM$NGjH$L83Hs$LJZo2P5>sC=$$A@<%ft|uh$ozktg7-a! z{%A69nfF5CSiBEN99`N3czc%IibHstJ>B@^I^b&F_ z@jj2%u?{D{;{|W)Pn_g|xHuD%bGClO<+^LjWR{?a6P#8vnfP=Re~As~xc9y*U7GHB z2P9HgN6yPSX4yrt2ya&k-dT0`evx@cbhe0M@fIN-W&I9#KP@qeKzJ`$#?o^E@P0Ry zq>;)V3Ue6o-62)C0U%O{Ly`@xTi52zmcliWQr;WZUkxXT}_` z3mUhT@X_DK4V!mkgyn>PB<=BDhSt%BlVA9r!aMaYgI_37)@9PPB*vevZZ|^{(?Oi^Cp}9=kf+7$DHz)!Ub79nWy`ORZb>wsk2F zWM9vB`c546ygO2Ed1Z*>A5QRXEJ`Zg5=HmCHCMi%s*Zu+q4fv$pFwy#Q}DjMe+~H6 z?7O$3lN^MxcyExKxZeVJ$NW4-M0k_W-bzN95@ z`oa9qw`Z-F3gGSj`SH@tqS(B7$F3iP)Hz`nG_J{8FM~fEoA>9Yt`#Qkw8vWnt)mGi zKf#Pg+)N%kQ0gl8ZQOqKxZPW8nsYSqo-_R3VRuo+n_}E}!r|x3UcE`p!(V^1wF`{q6a+|-tSB9K^8o+OR;)TU&V(PUqBDKxh(WE(u0E6 z=KqNROKia51CAoALgC3fuHp=fJYazrnym9c58C_C`O?bqCMfV^!#3k?aD(*M$%kt7 z*gMEi)-{|*E!ki*G|ugL@9~vtewhER`Sc!qee&*anj4TB&^iKf^7EZqzwZ;cL3-#% zWPEV}{ybl1%K7pSc*Jg4=MjBmwyTT6{tNb!$SWjNL^Icp(en&X7&|3UKG3^ zHRSy3{{J+)U(#5-S57$1{|b0-SQGXU;eENM-6jq2&UUNNJEIT^`!DrQt;{N1u9e-wYM<8G!-UtH|vf&VF>SLql<45-V*GO zju!&nw`6aB+#(YSJAAmNCN|*?>qjojl>)rCq@F)F1qP%oOalh2`>mn8E`uY!m$7;8 zTr0znX2A|WK;zg|dOB{*^T+&aKlXab<)>F^kGBO{hX+o6mSd>{leN4MvFA*p>f>t6 zI>}wYY}a&o;0^~^Yy+ohQ7As|%UiV7ssj4yeg|2(jJi6q%j*J9&c40XgM#;ibDQeO zyjzH8B(ZpZ``miA0r398dAWd+x1n17)3tzim2|kh2jE@Kz2l?-;4Qv1#QG)R{q|=Y zoBww!X!?oZ9otmw&57d@I}SEkc6bbpTPqga@RAX`d-sRz$_RF)J>ITp9pgCp4e~*T z@ufTvhn?k$Q+wXy^4|W?SHxty1DyZsTHXU^{P~}-Iy(79D-+#!?*Ins>e#!HpS@!C z)~yXH)X7>6Ocn0=(l-zxI0zcwbo=wDt(# zeZ`r-rO zI(2n$P7dCBQ6Btv{wFW@wEW*-{`aHkLC+R<%8+|dql=InRu8gX7Ih!lLB8Vp`V#3u zAH-j!PJ(BUc71Q3A|UfW_kz~k{T{IAk|6e$#a)nUM4z%H7?Av5O!kzfTS5X$1zIy6 zVc$X8_Pkayyp zqp}W7pPdP_UywRM!8@;TyIvAUG@YCU}s!|qM0F7(^ zbSnN~F*fftCo+wfFCC+~?j45Kp@oxQ?#1R)w|??K0x^nD2~zkEJil6^(ls$?4L^#X z2s|W>KmS{l38deQSD^a?(p`_Kt7Ge!)Sc+?nFpkODR@7*RQ#{=|C-0q%dvPXsWapv zya#x^J|Vp8RF*bv2D}}j>m37CLgD3uRtXXc9`K#~fnO7#dym>J7uEp01u`$1#~ibQ z1|3{wNbJ}HlKb774DCu*xCf0hKdh`>y9fLBmZ+5+of1pOX^yuyT1OmCe&@d)m%DL@ z2jc!ck2Uf=K3DIp2in!gtYJpmwY!&p!+&~<@bJso1FS3Po;Sgjx;og7EFSB)GP61H zq2QgnIf9woz4^cFUWUc{?ecg7g!jcea?J?u3a4=yFTlGg@9}#nz?+H1bmY2#2V7`Z z!Z84NU%D8uXCvTkSd~=H*J}mYcN5vrQfWpSNk>VT;lW zjC8*_*`j}hsyb{2hd)FI|9$?SmdE~oOt=onO;M# zK^E>0Nkw`P%XP@I1H6M&F5HWKiBKrKdd;12*I4k1-R8<-BG^F&ZoPLS0bGN;?Q?Wx zg0&@NVzO+jPAK;Lf0bz&k3{f%*bt4o9k}VsnJ|Jm>N22=CHz)_q*y^43UZP=KmfC~QY+ zTsa--0Z)AAe`pAJb8aWbz5u*6HgTpn@3n+i_ED_-c(auL$&fg8BI3EzY&+BP&4bl*-tuO~vq z?Jb;V7^2_P|K%+LH??-4Ic{urT40i9@F2xHieE2!@@w0ol zyc2X%&TbXkPkLr1btw5FK5woDOHZ8|F1jC(Hh-h8j!!;j90oJp`{F4I-US|q?~-}< zA33Ff#oHuNFcaaOuAKP@;caSIGd~LOPKr3NdTMzn{5bK2$31rsSW@#=2shx(bYfIa z01QZ?4y#u#wy}h=&wW2=W{%C9Ur^sQZ+HQG2aS_73y&B&fz6xKJpSO;gCjK8y#>%Z z_;K>vzhL+<`%zv<_?G^)T@ep)c@wmkWT$dClGHZ6`K)}AimSIFEXjAZIOv`?;VhMP z+#A-Bn7ujCpMv*uUCX6p-oKx2lE>oxdIgaI;e9#&Sf~$!`M)4}NPIououqYX`{%osP^L}Ifu~=vdEeD+Z&~2Z45y)SQPtz3 z18mq=Z}WxE#>af3J>K`xI$q%9x1@x~r=!9P9j$3QqP5}~F7JTF1z?J~A+W+?j@7F^dB6pBKaP!pCDz${Y{gCR z4AQbR3DW%Y;QU`KXFOIJ`vfUvdBV9v>*m3HXx!mXeZD`|WA`8raq&0y&jx62iM@)} z;fa%-Y(o|HtIV>j3Y=%T_-e_p^j9DDSz-Hif;!R=&Fl>)f6PpF`s+ zNM6q_aAWiK-D>6pv_w6UE45a9O2Wj!?7FBiZY!LC3i9`-a-AsT1Q9NKrJ1$#i+FXeA#bBXqNFGuSj;^bGzaWr%C z0}u4>=d~D;#YJ4+1nYepqpRLMpBH{F>2o3e{Q?B*o*s$q%jups;TUywnW*)#Ot32&XCSJSU|omJTVHm2 z^@oMDcQ|nbt-}x}zm_*EVEI&DsIX)#`N-NtT;87=bo?3uO$$on3!je-;PbArbs8S; zjHP?t@{ZKi@$|aQCi$7Kx5Uk(;9cYz?MUW*>EMagSiH6JH}@ll6F~alsBJ?1yhAc*#O-$(1Xh?8Gb-MppCzw$s@edZ*uo2j_G1N6fc z*IOSfXiVkJN=?B(|0fuv_qLiZrTh6mU;%Y?@R*jA#$Eb5|I_l=|F7J@63b4}gWmM? z%=92F@QIzECL#f=2OZb?G>E)G3La+OiS(dK`|ArlKo9E4x6)E-41p8tSS${zdBOyP zkunLRV}6?;FgPhb91TA}oJ8tjH27f5_i(ycU~x@~`=299|6YD>TmL z<_XoOU$J>F39i_&hOwXKc&DLtNa5rc9nsi1kUMwYiw`xba;V_%AOkMme0%H>{m=h| zHtOn#Nr>$>%9xjn5&*tp8u-o(b=G?uDgaz9B*s0*HA3m1@MfjpU2gL%jm+DAg^fBEZ`)tGGq1Ni@xuS`%zzaBD=z@>cBv8D zFx?XZCs{B{H~sN|85VA-Qv$qStzwll1-u1MyZar_wuBy^8kE=+i_P2EkbyUH4)^QOhzl|*-e9v~zo%j1kE&Im2V8kBa}yun9oX8s#24`Xyt9323g8{g$;d*H&@&{u`ne@O9A_rpH=zd7-3C3STiud(*HbpG%A|Nq?$P5v6p|J)Qk=zZhY zl}Hal=6|k@<_oZTkR;2l1IR0OGh#)Jksid6knkh~^q_)oNs|mQA@IqgoVI)up77-T z5rzTKgDkHsJuVCeq<|I6cC3493H4_lXtU+Teg>)CEn9lE))Z*~jnib>-?WMu`w=_8 z$FjH0U3zG4KuHx{nMKmV_}UVY=~1NwjeKTj)lb=)~s zILjxODZ@P5C#=v^S-Efl%*i*#xTyiM)* z>GyS>u!`ckoG*a4{-OsJT7Y-8*XnJ2sg{uU&*yIns<4+>hAMWWlA$S*4;p8;-(=qE zQtTy`&nEf#rlq|!$D0+cV6yQybCST z%vp;=V6KGpe#qYw7R!ErBn$AaIAw7m9Pl2E*C5@Av4n&rIA7gL#O~f<(wr%KbO^8r z8fWpvdjIu*c>lk(Th{ke>3uZUy(7^&_Tc2l^=JjOpkeO3-*oYBd-H~h!-=B;KhE6@ zq z^SAlu5V$`pWY@9{p0MlP@8+?9_rhaqMDGLM8VPFlDRGuiTN`n&TpTuU=inpD+%gF; zIc_uO@72+<*xlQwlU=YvjrPvo+|W8aaPn)|Za5%zbMCwi8hZA;EX9BJcGZ&mYMTo~ z>Hh3(&28%H;NDi4dG_+(^M9J0_y0X9F#iis^q~4WV-mRsrPmm+WA&iYigirLH%Nx| zRj4C9=+WYmuVSDF*$Ngd|FAFwcC|B)d^PC>pSzp&cAsa|I_zHtsG)53qUHEs||C-Zw$YLE}2~8|K@sP+0 za`(Pl{hbwycVblQbA&gaCohEXUK-DlxE}C68CNA-q74p68>fewlD*(Nz9m*FfcN2O zle9;Gx0|1g?Y*Ox(Cw|EZpjJQysIY9FD~bpB$4B`nO5y=IfdQ5M?~k3k8bUvIo|bX z9o;zjX)f~@o#2~$_qNfJU-kAo{tnW?zc({!4gFue&j@1>5Htph{;mu3IyVizn z<^}0U_g=ZShy{yxSt?&F!h7C^bbW;P!5tl(mdJo)ze$PjUtD4)R8OLyrW09tQ9SrBu$}li79NS9))7_wj$mn#Lw@h zIo@$-9lLSzD@d_!xqfW!yg${+9@un;iupfV=6W_85B<;oIaJmWpOfJ_JOA@g@UD?G z|3vQIPvwJ|v3O^`>$X97>rF=)BE0hp4sjvp|H8(B%L+q6;PapF72Of`f|n_{`!WOG zg&MakM*(kH<*&mdHQ?UcvgP6Yd$G^nxZn2}W=H-ZnW1r(-+DE6Z^k}*>tkSXGAyP& z-oj`d?Kt_>J6 zVuT3nCD!QB$c>%9+i7lz{esq^hm+q8d`<$UOb?F zR{`+;Iv_VP2?xVBS8qEqeAyfR@UAK565uVta(bR1*g>vzGWu@1))LzI_zL%f!`Qs# z@(fQnmX49gaV7NxqO>+PZ!z|2m{+2M=6EZib@1clS7_*Zf*3q^-aDol=kMyppa1O= zMYmd4Y`dR{jB_EsSZ-d_|;`pDf|JpMK(7VlD>8cl@v1zSrMg!jb> zNJ$d#E{Q6Uds!b0cUC*F%Gh|r+r1{Q1Owj1mxcDL0p6bLY;RuGvV{8XSQZ=o1MkEH z+pvN|<0Nw2qpa%8NeG*F{p;(hMo(#vcPd&(HBNrH*OjY2)XtqZeDI68!g(s@{|$bw zRZulrlZyg@Mg_e->?ht_LIL*;RtR{T*X&vb$$i*{LjPaAw0tN zo1}!s-TG)BmHZF)-e#KW99X-L_Rijf&^l6Z@=LPt>Q%Wpciu5;R$Ni6r(*v1Iq1Hu zSCamDn^0FryxEzXtoeWEf0~^4|2-)%|4UNzpw^0=+sHjACSP3$s|U?{*?FrC^q_mc zHZmYR=sb7gIzM+6-H3bk-Z%FL!y&i09Z#P2fdl;CM9D4bf^4^SSu278sqId^O5hbD zG?b+@7tb@6RM-zk`IgsMPgQcMHw!Aitw^EW*i;l}IqP z)17+{64%u5Ac*46|2KU<5J)?GHU9mtpWc3bA?ZC;by)UhKm8UlGygB9;N21~w42P^ zV*RuL7Vqmk>$W1iSF)^UL3mr8d^!~icn9Q!c{;c*~J1|62M&k-MS1wz&6PtJJB!6g}O)Jgu-h|e1 z7AHTq$h|zryt(Im{{Os^d5n#k`Jb@tYpX*r-SZ}xEv2dsLk&$~vGkewUxI>n^Fg6f zGVjH5ANjF(&v$>`)e3mW6jUujcn=k4tix>C)tgC>{+uJIDU+o+1@qU8V z;f9l6SKOjUqww5$OP|nAK1Id+UnQuqD9o{g?s+TkRi~;BZO__k(Cq#H;uO5UuTah+ z^PX6d&WFXDqaE@`cqhg#5JGtW*#R%C0laVUpR)RMJQ%jiIyDty;scXPx(bHDfYfA` zP!I@s>vj&_{jiz{X@->sD_UUl*4-vwXg)klQbpqizh$5LB8bh~IM>v#me@vf-P-`I zV?9oO89(;iKVE8Co($n!(K5+Pkgy+qGcho5k z-Za3Q=sdh#`4bUZyg1is%LF#>lxu98TKz{zqG;Ti(1%4E3bA>A>|XbysEzh`UqkDt z#>ua9^chLAX71g)hhfCg_X8F4fA&gwrMnw7>20t5|I2r3HC1&a@@U+%iugPK|Ns8{ zXz@3|{J)H%2mO3du1fAfA|?tFSUqTm)b5MOfW#e8FwFyc(7|w>Rw1y&il3>qb2JKu zcdRAFZmjl!eGIHgR$vD?4lVsuGuQ;_D-)t_F?Jm~m$-!gJnixBN9#C;lV5n=0_Ig+bLVaU$ylkhlZq20l?8>K zS>ANdn@~HSx;no449d*zAeT_^?l5JtB=fGgP$7!Nd(*43RD`$jsM`$h_b_XSHsD?O zw*1?+ZQ%A69ia;vk9^=y>|Yg)0Ph_K6y2u*@8-7+2VL|np=RC8sZ$-;ydekYMyrrP z(ib$&cH?-+P#SjkzV`Lh{g`Rm<86S}k%p6>;_<-4Z1?8QyF5$Ayeu34>Mh}XeN9p- zBmM6nv#6`%WQfBa$F!O5Elt7uhxDe~WZuCa6GgCi-!@>mj_@A8`FVzSZ*`~L9>6<> z&HmG`ox!ksGV{hYX+CgYXtcBj;9b9}Wr80JNJk2?R^&q91?dkgBNu+c=3V9B8JjvW zNZNwNc^U7#z4#xV-qMy9F}UPLdxsNsXdN0j`8AbP8AkZceg2ne9cH}khyV4K!wVc# zEK`orJ@0M<>grgd@NVsB=*;1S6b0|L&IdhY-Wy7Y!kE0DkIkID`A-`Em$SF^_h--E z%x=t{y+!)Xp1t*(&7Qrvwr&x$*RzDG4o25TzQ^WWFJjH{#%qZ58jWLJ?P(Hm9=m%B zE9X5uOoL}{-_Sbvaq<&5I(_w9!Q8v|#~+n@pMRoa{!huvNQoX+r^WGaPC0cxp{kDU zZ#X;7fv>l4fFC}e;W~jsYN0-}4O0mC$G`ufwLbwcAjwhmpkFsn{OkRH0ShIUV)dZU zq%#`rV2M>J*)@pF|52UWc#6RiE4kN1wm>=_%iGsK^g^A3l(FRT4`2uG~a(ymQey z(s1$<%&_0Jym9Wl*X`YLteXvg2kF54$)x5758dw|3lCCPhy5SRQ;!NSAeXmfD0ufK z3eSAr0=fVH@Sl7sEZ&hnET@nG>F(KcqX_Sg!0j#ZPeN?x`NE>Y zPNtE7w`+xW{6)Y!%am~GfHM&aY~Q|LXg)UYNv7XF1)2Iu-e_F2m!5k@Cidkmc?PCK zIp=AQH^cndI^=NjQ!cY+3e=lB@3i;!nFrFT*g;yatlR%kg6??}f~cz_>{WkDvwR@J zdj%!$FwYa@0jVwht|S)kE&~r*VY$B2mv*#{qA~%impzD#0+rk9C2s#(dz- zTkZu00^VP}Q+(3_?>>HRDv49hY(PlapMbf1YRV^FQ+kV;gn_{O-*&aL-;c?JC{#F6*VP4%z2&4fEXN z5#Gxwcz69g_=?PX{(I}iSiCJF-JT%4ht@|=BD@ueOuLK#?qbs2l28Tnc(n zT{rW3Mc!bT#LXyRCgTgQc7Ao|5$HjBdAm28gC11ydwlXnpe0m&dFRulci7J$L0rK* z7?1Rl%Fwv>Z&vrpoUq?PLX>XS_;#g%=6cX(w2p%~`L*8E%{=r zmwDFuxabgQ&oWQxt(Z>W4vppEIDwO&-8Emm4Tf{yLGF3HvGl7V{^hNq z)#+QW?H;3h-t79+)p15v$n56nnG+;M3f@DTvJzaJ#Rt@b#=f8;$h2sGw1&b6ubx5zSJi3zE^x=ITr8Z7F%WxC%lR+{>$M6 z>%Q5;iHo0S4<}-pW)CNBN6#KkESU;~WI^|i<_H-Nx`NGn%$zVB1`a1e(733^KEXge zY~E0Q`$$?g?Hx``p>=5EgrGs zws^ZWa)!4&1@HdhW&UK|q5*rCVex*cwSI>8(j)u+3-4PNv%K$pndQy-eU^7~)GTks zgQ?}pOqNiISDOG&4))dC3)0m`69MmMXq=Nt?(~rz*k^C4msgjU(jf24XdTHo`Tgn4 zaqxOEciwL+_i)O+qvGa7yVxGX{wccWO^~=qT^(OoR29I@iGR=k|J#Y1wtf@L|7$3E z&}4$=VR8@Z+{(QQs|TeW_;wE2K|Y_B#qdl`(`AAubtSLuaMuQ-EY3*uSQZ%tp= z^ISgh8`wb}ir%2e0d|mUlIz)3K@W_qH&j+rR%MtuzQf! zpT;T2-cK|)AdR7Q=;GuTd_|_B^WxkGBtBk&$fzRxC6@4JG{EX%2>tIMv#6}&QsCXh z*-z}MQ1G7cIP{Lpd-Lj!l~}yx*)FCcysO7dW_a)EIB%Q_c*{p#$TtSO#Ugy$`89mu zlGY1>^?P!8 z%vqa&&osyT2wKNNocx?ODogDvo%<3i4pp;e3ggfJWu=WjiIS{ze~DfFCUtc^^9z>%-kFu(cfZUbLUoU#!({&91?erSP-tU56XpVO;T1Ny}f!EZ%2_OJ5+oNgJeQcynmhm&1Vf%66**On`UO(7A70 z*Z9Kjda2XpfVXF+dbSeatv7Zx)$=hC60>eGb&tjF-Xm{PZX9#(Ch?(hr5=Wvs!OnW z^VJhmH6PO+Z^lZr4xIc-9F$nr=*+!)|FAK0iyFj#y`@WHLYQ8%Bi-|Uex15H;Ae}@ zti3QZ|F5FpJzCRLOy;fEVLf=dq@-WX5*3`n~pr} zz~(Kx_C&DW=vSKS-j!$_GC29Yda0n^S3Gy#52lZV>s_K^{y%T9*raig{^$P$D(ev5 z7$^I8{->=uA1fO$|7-le9<-k^GVxz8NI&qLK@F=18J$*7L3+?r;;}Yl2YGwcOYSD< zLAj?7uXg|glA+n#ME+gAu-j4XN6bsRAY)>}Sj9jS#1@=#(c?K0;;z~)-V8_j+{jC;^|NN)Uhi$# zj`03M%JIJic*{&kzPtcw8wi0t-~89zgS0x-e!@xU*6Jn%o3H$ zz~4dsQtMjqZplTu=j|FrT^+0^_0@%AXLzrr;7w3+U?KCiU4Byqi+8<2O$@@@ItqB#wSClT2fVHINAq(ch|uK7&1;O8 zuz5=)$fzdtbdW~TxP1#axrKzVc}wfnuFo^7r@8JegVwPeCqK*DshG2S=g!;Od{f~^ z2`YAwjwA9*;6%FTO-Q1$j<@UXA}2_od#n9F-utG->|T(0=L|S1WAWw-<&Q*o7fY|4 z8IZP|;IJ-+uKSA&0p4B9*;>s6ETL=%moJTK z*aH&j_50JKCpt-4Xk0t@ql&d8Y~IZU`QLco(;n|Kw2pS1{A%>~Kxg^q&ij6g*91e+ zEBwo1TSV_Z?G&f``Jb?hx;pwF?zAwT{d$Wk1@AxQ9+70;*)ck+v3Or|8VNvnCvIHd ziEK{l>`k4Kx3}uDWW7`c^Z&^6ewV9SzVK+GIiVf!7T%HJ&j{v!osb5V2NGcZ-&54u z3t{u_kzpLJSoD)Ly?ZupZ|M)V!E$Wg?o+!fbF66Z>}?dS!y6|*-`s$~>OFJk?X#8r z+|Yh}-ig(b#GFT7bl<&?&p$&|9T(T|E&3Do_x^vZk(;J|A1tvt|E~w_XF0>6j`SdH zpr@vPtN~-a#hX=JgIuwUTpbq47%?@iYutA!!-KH)ull* z2c+5*yqPyy^N^R=)I%kjSiJo+$4n94yb`()9*RJ68nk7_R?!S2)5iEXIew_ zg}coZmTeoK$os=+tr-o0z<91DwzsCd1_n7sMJq}6oKoA8IaIvivQ z=PBNqxq7Qf!JBEFxC5E@fvaoRV)4Ew)?b6n|FG)ECWQA^$@jHRfcFi-bzRxa!Ei); z+d{$pzVMe#&}%`!dxT>&{2}1Yx?5fK850pIUiqB!pb|Fk;2)wtNDb|z0yJ)|o7Hgk zHEiBr$IZ4}H~dI*-8&ksqZubZt%?)YnvQet-fxS93+E5v^S)^J%Fxs=jqZ7S9Hp*~ z;Aek68-tq@|K9&kQ3xWLB#Q#Y3qR?IAC$!P>+ExEWCPG-A2%ZKCtbww*@_jt4AvQl`#=At?jD4 zk&WGhl74^77FgLrGC||=wWq>d1hEIC{2%s8>mIzPxgK;4tpmo%k8_P{L&VtJm)OET zmM7XOi*e_F!j7AlQUn?4e?W4fvW|kO@FlY+Nct4KIZOw?k$G#MlADjk`|~Ym6xl)U zfAIb_!uxV|9D^|6t?*XpE8k!ce9`RnS21uv`b=|hy#e5TB&6!>QNX)XhcFfd6QKuI z9~=gyu`jVFK78~n^GXZpJ{qTb>ExTJv)H_o3rlUvML*CS?{u_|be#NLB=2`?=gysX z<+UU0pR(d#Vkf{Y>N^NA^v}DEx;o?<`HlBx%haL+s}-T^Is zZxP-)uCFQ)-Uo%mT(|*mbL}A07QowSuVTP5aC?i)ygPxqfOn@T@9*P)_w?%5^}Fv7 zA;;XrE(T_7-g}sDWw>#)l8&Hp>3_J51l+NCXWZEn>=H?PyoqQXw{Y^iI(@b-=l9%s zyLfE4#Q@>oy%qA2OZTMH2;KAE#>7ok9c!}6UR8z6@Ybc^z3}_>9CG(gsCmJN#hW8K z_A0`AOp~D+;oWI}DTo>H=K1)hr*lhy$VpJm$Ic&QNQ4%|9Ri>MbFgi%qXx zg6_LFL5#XOjM?r^YhV3){{P<(+%)#PVE#9z=s|ooGBfueAv?%bzl_+idJwze+B#&3 zUCw-^99d$0iGj?!z!EESW$cB`&mfpku}z#&$rmQ}eA{*$EU}Y?x3iamCD#1f1yTig zK|1qkD-DU&*geR(`c%xc!gtaFG>+5p6?^(We1qg*x?RnBQWeb&NbYDIRyg@Z?^~;< zl{fbtq^`nRm3k_^|9948i+?PaFWvVb&Mp(G>ZpLmln%^(LE4CdH?Q7i9r6-e-z~w0 z#rttaOfSOQ&EJ1_tyj7W>)n7ilY(T3Dd4SC zmI=h`u5Y~Bg3@qX}k+T*|n%};_@qs=clMT#*3pEM z-|Y;!Z{`1ky|;(N{Pcul_?NewI-IzD2=xE`zt9Hi>L_E9I%xyGz5Vz6pT=hW|1KRc z|8Jq_K_V{VFUdW~$#ydjRu9^8#(pC*AT5+|dxP{KLZ^{RIk^A-&;IDo?;8HU_Rc&S zt1sUFPmDf84o zippGu-#$9$uIJu$&-Xm;TKBH!`K|ir`+c`Q>-+t@pY>Xwy+3>Jv$r3j*A!h<0&b8l zQ`s*N32IPlvav|#k2d(U{)5Ky7!$arcIK7nWfyCqkc&UvXjj{@<~PJ|E{| zubfM~IW>dSp}~8Bocz=SY3TA+L@_TvA>LvBrYPRuK8sD^U2^ugWCOsPJ!$1;r&d2? z@1~Ch{YyL$`EB=FuL8V7lYKkB0=(}#7aw@#WCFkFtoM2=OpJGlxo)m2(n8J0;_8I< zm=4$y)VdDQYW#vvdzaT z!Ul=)wzn+y(~5h=aMgP)=EIpJKd9Dl7njWR@%9`M*O%=hKS4?nw!Ut;=l_HLUx7X! zWx{TKGFemATbl;&c`rkj;dq}nc)&}9cPw>72#U8#k=Yd9j}?UrIYEQOGcpMIb^0MW zrtAhL%RCTGw+FdF0B@t;-+X6)2C3((li2Vl6IdWMvPiSZWkEf(sU-A2XZHVPMg ztF9-;`*6WTVV7YQ!{IH4`LH3$Pb1{)Xi5L{@$TkO8hNNhzPu${b$eXaERgB@f7w3z ze0&*}ErbK6`hP7NyyxC!*@@$=^l=q{!EWI zWet5k3eFtTZv%I4{q6t%yM~*={top21~fHjsqV@Ds6o+%^7Dym&@RiNPV^h3ZH9Ya zp)<($k`f z)wxIi@`4m!a&pAXutw@NEH3Hb@Mo@e;x))X$NejF+RGSjh!w(oTp-EsaF~Q#uFCY6 z*q=qrh`W(Pen8si^{=z7w#@(jpN}zpK2Gt?`O@Y+HG|Zr!CPeMnQVNBg$}U_5#fC& zrr>NEf&&a(_!VQA4n}O{r@lq%(=}E{H$g6zN*daCl$Ae3X#n_a;*| zLfmWmcv}b-Jm@zk$9tqv{y{FwH>U6Z!?fx1u_HW1uPZ#^2k7mx8i!0~nys-8=P zH|qiaIp_>>?VU4IcrOyOP3Qr5r<$0Y%msLBq$B&c3xVq`R=imj2k`DNk+iASmtn3M9r`jpgCez*NS=+aL3xNs`}pt6}@d zf$29$UpCz9A6-J;|8uM`&svakl<6BJX-WEga4eE=@BFj>uS+4_h0Oq)c4BH9Bk`^UiOf z4q$NxaDP?Mzr4M5HF#&d8UyaV>0mx0N%9jDH8|J)Kj{BeUb$QTcu!uveV&F+?v|Uu z{MEadJ|Es<*Ber9{O$i4tkeJR(*gbeKAIXNX}RYaUW1-Z$}b_RK}Tcn>Y@!&M9pv= z+W!kwZF&uZHOQ9Onyq~~eu&@6)IIaT6FX)nSzcv3vJCU#PLkiUl0)(l9Mhjc zJ`e3F&7|jwowHVEI{QvDe+>$t&xd5ElZ|A`RD-ma25$+$*Mm6T(ei_fi15DExa0_m zw{fWS+o|I%ryOshCrF3x>^R+)?}rqJ|4?!UPwdpY@UTAvc<&b}dG!?F9hTIZb=ANW z)_SZz;<=s}Z{7eOfsAeSRDCQ?$2|CS&?#cPcdAuK3dA!W-a?oUJ(B!7M#V-Q%BPPv zd%{MEt3Sv$NNu)kK0$dk!t{9a(&?k%yv6Vf|EV3MJv4ZW54TKRkcJ*_*~L@0kO=SG zagiVt@4dfP)uMQ>9pvqj0eCMu>yckt>W5ssIVt;G!UNHMTq2bL@Sagxvp5IfZJXom zZMfPL=2?Am_htcNytQ_0dRtvvPo0Csv5QGPmD^8@_sT%~yUq%w3|GDNF&_#f`TgQq za^UI2^c$o_vFRpHqUe}G<~}~;qCsK$28lwak4~lQKGARw1*h)LNCD{4utXW-i7%nCCN`w z&dID(ZTi(ak#d(yKZ5*lqS5kuUe=|?OpkZI6n#E6C(mndFrJ#67}DS^8pXFCpPZzu zI=+Ai@3OMFl_=gtY>88QZ^8mYL2Ll;)U{&w?}NR!hZif0> z(El6J)F4?^b1u9F?J8cnjHm`3kbdC%5!9er9KBO_kUsd8@?a5IVrTU<-t^wW56ODt z-#o|11JNm~mnZ`@==f@zb+eQioG5Zy zVp%Kk8Kl{f`x=rrzht}_B<6#kB)`?Way<4toc;__Mtk7N_Icz(EX6-J`ffP$zd=Gt zqtl0yi07L_Q!hvzq``ZId!8tc_mCYdPK3AdGB^gsTkz`5R_qn~r)&qK`uvMzCm!=W%5c@&-+wV!`I_fbj zE_-cSdg*oIA@=)cSu@VZjEDC(%m-P1g68JewtG$=Zx2|yZqk_ic?-&Am$7CWKBk{R zQr4cJ%g4m-j3Fh#0Q7;h12lNcu=04|c!zwf5hcQVh(kFa#an57b_!^}g+?gMzpJf~*#{2wE(ZOEHB8IEpNtlldB>4^NuGNnD9~^J7i|txpoKZn~d#ho| zjHOqNFEKsd!R_?9hp$-)9JH3yZP`vjY zQ`vnR;4LtGNz5(84_SUG7O4Xlq(4>U;wk`mYmB!>KLmIyr>)t}r)dgTJv8Q8vXvO` zSZ9U3mD2C1byys0J3@6jLyY&GjqLu{A{YlKjMZ8xvb|reD3+*i=yOHC2-0 zO=;-X@HigF^mtR6=<}g5lk4b#?8_+L`)Tl&Iuq@S;~igbDnf*J=?*V0wEtIAel+!Z zi`ASl$xi_9K(`GM+wS-w4c&I1x^z5{uqDS;UjV#Ii~K%ajFeb@wi^QXTuh9QN|9?+X zwB{K3^%jYI2@-6A{Y;PdZeIF)tjx}FeR}@y{r?Qr=MyCZYS1B?8njwrLc+@8Hax(U>vSXq@H zXFv_Q*sfk+t7ZmwT=aT;>Cq8{D6Q%jj=MEY-%z`-xIpo_=OjN9U$GPG-Z=9~djZ4M zpm&%LvizP0tXp%;X!VR_6+tzoOWpWynO0`IK^cf z)d9SNK3y-n0PueNRZ)E?)f6sNUi?9_ns^48C@Pe_t@aJI0*m8MZ`Cn@i1D_T`?2z| zK_SE8{RH!2Lz16Q$_jDE@afMWt!CH#wof8o-l~{cP?Vl=i0Sc;-cFy7?JGHT%1-;E zGe}b!yye#{pMm3@|Di~V2=AO69zzswS)<4f6mQNjb309dch-dsU+?PqA#Ft$*)5~N z>g`;Aqt^g$wZjKHuL8WiFB|by0=%zo>Yru^r6 zOA{KrZ}s*b=EIdFzoq55 zZv~R4k9YRRH&x#Q$iLpAc#A*PVgJtj8>F}B^I;q*+njQ0YW3Eb2Je+eSN%uzb{p1` zAi`T=Q}h(x12_Kj-di1pwJ;Bw;e>fDLqfBE)Sldp4x9pKGc z^C!-b<)vb0CGql>mE2gvC0&-?Nb+00Sykfaqv_+F-le?r>2~tdTRZB?#H}`% zGkx`*_(h)&lW;r5j_|+d|A~5AhWdLjgS4WlLCP|h-0&fm^EM<;RD<;5mzQ*c8Dy6A zKZEEDvLyF8wFAr`GY@*o4D|XUyt6(>hZ}ezn=8ejJ}`qc>gF%A0yD_>l`H*gx0%An z&P9mszd$^LT-mmShuT?9b;jZvZ}TGWpApxfHLcgLUvN0khY+~Td6eD498n5 z=HW^ryiK@AR->!8V!FzGDBiAAN(y>=>z9)c)5j@($dY$=&iO6(L>@JBuj&DKAG#D! zX%Fz;d!}ho6ptw!-|4?I_FpzgyK?WIe4bE4eT>Da=_zcAb0)?+*ksk$qwDh-u6lpP ze4Hc6&-mtyA4Z#}U%g$8lO+zzk_&xdUAa+mlkQwOBYY4BcC z=w^ZAt>oz=ON93cSvv<5@0{HkJt*EWFC~SZ0=&a>H|{yf?S~w{pPX&X=ZSQCDam&O zydPaJ?{oloe|g{Pac!O{tn)eAPhN|-dT(P7*%LLlmTG{-B~{H)Z+0if+dU^b?Q#s` z;jM%DAj?nXLEq8Jfa&8cKhNPnAU&_Qy#6{T3+iHeyeX}8`na)xRp!s~)?pgF6f@xLw0(bDRHY&?D9MLWRz zydd{Ko&fKYS;ya$8JfZOwG3l_y(3=Uij=+lD6X%TnuNtc9#=)i1-%Ie?~@)93Ii^T zxA%4z^Ffwh|9w#&o{;I|-My;JI2Xqv!ohvF-T?h&6s%9I=*O>=xr^}ym* zoozSST}XWXU+K#HG;f|43^#+!#(b4CSQkF7GbT$A<~hS==fSD#CE zv6;XIc3X3cOo;J@wv6W%Sih$3!QxW0(pbB^i1C&VfAshqE92qKhxw2p$?y5hxpu!V z&4!P3&bhQdg#r4ACckTydOdlAL>Vf!EPn6B^mtPimC)s*aNu(T+n?tx zY-#Y`Sgw(P<9+>7j3N=<0Y0;R+X3E55=R!GcrX5BcLTj3O>q7b_YXzB$Ut)(bzh<< z;aq6j6^w`XV$6p$Nq$fE%zo`(F&l=ujxTJ}iY3LnXiJdfDjjn~?CybT{t@!yEf&p^ z*ORY&VtTw)#_03mliz0V5>p>PK)j(3!o<7y(j+spZNI{@A+!4cdj-uw1F zVQ&X`Z%l{QvA_0377u-B9=z^}ymb1#pcCNzP0MAq2f+L6rI39yYK`Gf32#n#h!Ep_ zvwp3)Zux6!7Zz7v<#ka2CdRwT&r)NLCF9|J8}rdZlHZ$n_NAVj{IJXJq7tVM*Gcgf zFyo0`tZt4xoArBQ6FslD1nc`N7xywf-jp;teQaEzD*31Xx2C~+z2(+=9B+z*x&jg2 zG5dEcL^mhY^9m-X`u}kq-;V(Ay{qyrZ~u??Y7G5P(EmHq)F2JP zp-pHFQUy0ieO5E35Y?dHMhBegKn)5Ad0vDLvArG!9zx&_60a+-a=RjYk>JiNi=Fws zkXzl4vbTd86m>S_=W*}`Nl@jxiQY^TIBhZ`@x@BwCH9X)YW<;7wbTqO?)d?+B=LWF zgY=1p^uUe`##>_V!F`bA=YCOVi5qwz{lFUz_8iMsq(iJ~RM@`uOfw|Ef^A!44EYR_ zt=mgrW!he*A7UdS>GN^EWYRV0%+w6hfd+5&Z_*Teh%I(4-#~L0ID z9K?A0$3OY!r%??R!Q$pRRNKK4#5+jhoJJ>P`xtNkKN#~NL6RS9&(YS$YXo3*x54Bu zo)x5c%bS($x%AWw;jXwTDy|M`CkuLFHP+)TpID|SHjK1PH0=ES)> zaJ;#q!`2hwZOwoEp9X+;rnONpinq}Fll~Ndw;A`7)idtF#866UM_k z4)ftglHc0|_o(1reptL(YV4~Q`Eivws@!=6T!)dU>%sFL=aI)#1V$AW_%Q$T78C{g zd~n1^w+!Ezs@_Lw@K*B|%Ej?+X|_-%!kfi$NTdni-B~H*fZ{!LP$><4-qIyy;f|fj zzKGyCwxih{p2%ALj}E8M>V0OEx)9(!dieu2N758#^^>$e8b*xw7HY`yas6s42Nt)+ zaP`9WG-A9z@BH=UYd7OHNZT+U-6Z*i^PBj{$qT?UyB5yeYD-5o_M>##JhMQM%@Ni= zjLGp1J}{CV|9uD3H%LAn^!Zrh%WJeWWD0M48oXhHMN}N`jx1Ud&PlZp8Zz-PuA1m(=Zx?R^Zv`)vH-+~u?-kwvUU%Lj zyhgmbylT9wd6)6d+}?V?1U&20R)(Yk8!3gn78R zC%C_JcW}SqF5-U1{fIk~JA~VZ+lkwPdoTBP?hV|s+)KD;bF**_aDC!>&sD~i!n4c7rK9WGTac`h-oIb3Ye2=oPNf?h!{pfo5Bx&{S79*{j`0_j2O&>Bb* znh!yoW1PL5ZJafng`An34>@mgUf?{%>BxDQb2q0Zr!uDu=ORvCP723Qjt?Al93>oC z9Elv!9AO-O94;JI9Q!%6IaE00IF^E+=10&?K&Q=LcCq6Sy)=KHC6| zEA)^P^aWSwnGmQOSLhZx)P*Z_#}WFBEA-nx=o7Bc zPoc<2hZ^)ASLka-&^uhAkH0{5xI*8`fZpN? zeOdr|gDdnVcBmFt=$pt;4X)59WT9$Yp)YPiuW^MwPzY7w3VqKFdW9=t$Hgz9N?a|F zlQ)Mda3wT883vW(YTnC`Wl$Ne&{yH1Qe4e3mkx$Xa3#2ThbmNzD*+A}cc=(gv#YxE zp_jPgyQ^sk72=Bbxa%FL09QP^{jE?wuDAtal%PCZLGAa_p%=K~O!qwtA-Li=&!Y@c zamB8ESOCh!6`R1_Pf!l7X3Y$nfU!DzfV|JK~He?YuzacC=FMm`xnlJQgJo>rmX-< z!PU^s@<`}0t_JOuC!u6q4QQ)Spd?)NuY0)(O2pNVL5WjP02+qmj5nO_7&7(_~4O}&@EbN0KaMi#od=0vetM~7=Q=x0PdUxBI7rKh8I!j?G=nAgh znsaT2!g2LxsbM{I8CNweO>)pBTvaDauZ6;J_1blYG!%-fDxE{(PzbJGEht+7UBp$z zw{P~)1zeRQndZ=WT$TB69)*H&Rcf9c1D(TFiHC3;6ojjyNy>UC5LYj=E%;ym0mG#gGl;iL0mA3${ZZxXRoS#15UrRmK7%56B%?Pny%6 zAvav5#ng#IuDD7K)qV$^z*WkXE1Mw~Ts?LeFoc}{-v7@8Q#r7Mbb@9L5}nncYmn&v zzt5;H8_^o1ugb`_3a|#bu|L>$4p@VXvg=Zk221R@A~#hYU-d=04l2tgJ9r^&TUcd= z#e3k{hxK>=1WW9K>ggqS{7m4NQtDgZ&m&%g{MgNRGxGR5Y8e)1et_j??F!;G$XnM| z-G2Cq@vhkI!F)uM|CGz8 z3>qSt|NcKpI(;M*5~#0B;M`YAqD+c1qwA z4S+XKf&Hivz&rT8hU!~$FXZ5${02_2#6CHqp7R#qt(9CbFsf|=>jm6C^6@?K5jz#f zUGqFG>!^FMIF8;M^&bCn#4fbJJ~6G0@otb($9!BO$xk+Muj!z^0NiG=+H>{J8dAJ% zg!lVM3LQe&P4;ohIg(#*$!))a(%aU<^v7FdBIxt+_|BUB*5Ha=P`#aL@J9Pi9Pd(_ z!I?yOKNYuH@fzU0$~{sB#d}4G=zulAyF&0p@Aws8q`EL+meO7?MBZ>$=n{Z;xw6W@ z6M%R7xAP@jbHV2=(ruc_k;Hg^eBzTIV*8f54~t8Gw#eXn3h@b2P4BWF{$CjH{=Xi~ z$99tZl9!H|$N2EWW4SjJwmzvQ#oJ)d%_MfgLr7}N*xunhI!=%_AG;JfFv#?HQ|3C* z-#&D3L z+9?%#V!VGu2xVnO)>6-7ak2Y^vtxaU@wPg!H-b-^@xK2b#(db27cC}KU@{w z=M*hYj`tVYs67?O3=qrxF{>}e(y{;F)bZ}HjUChDP5D8e59;Au)!K)D&;K()_fMgK z8KehI4MO)u@EX+Bt;J1LgT|4Nb@`wMxwENo&jmF|Oxo=s`u)EI$5!_j;QYU%?AzwO zfnLbdc#dPoLI0ncx#muBe;ceLn;v+z-UN=_p*?fU8RGsw!(UxW?qoCdAr|K=Hmhgr zzdVq3>2+mvb7=*`egB_}`M6AypIV~z2;$EVJAFHUMA@^Bbco%(sqmy+=3!*9!QihU zPVysml#?fPHYp4;{~4r9E_C@ga)o2ti+fWu$dfd9qnmv=-pyA8xrp%Q%^clb2=I>M z5cz`6Ah(9{Xy*XDwM7nc$O63Moo(-C`FSDHW)32O0B;E|6TW)@?|tj+{N2(`V2;|6 zN~?dl|1Wo9A+>E=6O|W>8}7|h-C|F?ycOHHZ%^y(a)!hECFUcJBtJFY8TxPuKU~uI zievW2x1@L*DD-^(48EV3(XlnvQk8s&En6m)XP?CU7o=aG-S!FURi9u6%yVKx} z?q1_~bNYYeB*I&L-3;p@fVbieY6*(><(Jm#5diNQH6iMr*L@LAEw=eK-d;%Lt<&1~ z(CYnZ_D>gpcia80P~N*H@P^e5ZSiWv)qC>=m;4~1MyeVX=fjr1xMepn-V(ZJ^AK0Y zdqG+Y^C3x+-;q{x8obft7&zYhA7*e6;q9b)GqwcaJyLN$4#nHno%^>9zdKl zRle%FJidtd{{NiTu%LSDQiiME?U)ZLNq%P}qP1A~@(@XuAVZRkp z`rb^bn1y`xmZE!E@X-tAU%jPth0^6?X~CUm%Pvn6*@^JpvND=l z2Jki;%k)F>#`oUV^GSEU0GktfB+%!hki|&xaPZ&v|Cpu! zKTT7E&=Zz;4Vp0z79grY)hwYhnV<$u>YS)T`+p(v{!TvE+&HRvAZLxm*2#0fW{8-e_A`i>A?<0TEGL+nvAZrc&q99itMnSI`O zIzGwsw>tD9R+;H*5ak4&K6)Vsr9U4?pQ6DVJu-~red8CzPlR`JCiLVPz?-^M^FE3< z=gJAaCjjrEgovM+mwl0Zi6SFvqZguIDj32FhFGZe(QFrhx2v*(6RgZ zds4iw_Qi}0>scYHHWG@zpV4u=S)nhL8J4(}tF z53>BiHBwG^vkAbNo{P&OC*P6cEgBl(;%j&W5jh@^WO+4c_QS9XQ^-F86tf@aE>pkje#k7b^D|qj>AK)##wlTkQC!_l^Z< zkZ#}6QC7?HLLMqSblM2;HZ33hvIyYqYhl-I>1GV;%%T?Wk|Lg*?6BRM+ojV=)x+Xg z-Q*3n$P-Ua8uw?ouf6<=;qcbOd^C~dr~Zm}&A6d5usdx6r?+k?iC6EvK#q5o z&lmQWwF+SFjh_E!Wj#yb5rx#*&B4F? z{qy%1`1=d|{RRFHe*yo4*JjcTvFL}#_z*kGfFeXR#GZ@FzMKGtSjnCguX$jI4cFz3 z+5v{x*M&!GzFhQ0hVu3txuxQb9CWVecmS5Sgcm)X$2Qmouk4xkCP>5t-coil>{UPU z4Dy%$0%7efAE+8wT%6W+4%ucN zJ_X<%Aig+y1T;vwqV3lAMvUQvN{4m6#l(1LQ3q?TpYNn5VsSsDhVSotO^i3U(S3h= z@SxiN&TslZ|F7m?J|L3(t~fp%6))q5pE$0Ra9Ghqinm)}Se%dQf!5sTl585K0$tZi*l*xSP+6RJ>HakHgx$IExT#6@*28&dyPVaH+t6z zjYE*7yf9`dSh5Wf6MtYm;e9( diff --git a/planning/autoware_static_centerline_generator/test/data/lanelet2_map.osm b/planning/autoware_static_centerline_generator/test/data/lanelet2_map.osm deleted file mode 100644 index 406cd85c151ea..0000000000000 --- a/planning/autoware_static_centerline_generator/test/data/lanelet2_map.osm +++ /dev/null @@ -1,146 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py b/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py deleted file mode 100644 index ca2621212ef83..0000000000000 --- a/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py +++ /dev/null @@ -1,112 +0,0 @@ -#!/usr/bin/env python3 - -# Copyright 2022 TIER IV, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -import os -import unittest - -from ament_index_python import get_package_share_directory -import launch -from launch import LaunchDescription -from launch_ros.actions import Node -import launch_testing -import pytest - - -@pytest.mark.launch_test -def generate_test_description(): - lanelet2_map_path = os.path.join( - get_package_share_directory("autoware_static_centerline_generator"), - "test/data/lanelet2_map.osm", - ) - - static_centerline_generator_node = Node( - package="autoware_static_centerline_generator", - executable="main", - output="screen", - parameters=[ - {"lanelet2_map_path": lanelet2_map_path}, - {"mode": "AUTO"}, - {"rviz": False}, - {"centerline_source": "optimization_trajectory_base"}, - {"lanelet2_input_file_path": lanelet2_map_path}, - {"lanelet2_output_file_path": "/tmp/lanelet2_map.osm"}, - {"start_lanelet_id": 215}, - {"end_lanelet_id": 216}, - os.path.join( - get_package_share_directory("autoware_mission_planner"), - "config", - "mission_planner.param.yaml", - ), - os.path.join( - get_package_share_directory("autoware_static_centerline_generator"), - "config/static_centerline_generator.param.yaml", - ), - os.path.join( - get_package_share_directory("autoware_behavior_path_planner"), - "config/behavior_path_planner.param.yaml", - ), - os.path.join( - get_package_share_directory("autoware_behavior_velocity_planner"), - "config/behavior_velocity_planner.param.yaml", - ), - os.path.join( - get_package_share_directory("autoware_path_smoother"), - "config/elastic_band_smoother.param.yaml", - ), - os.path.join( - get_package_share_directory("autoware_path_optimizer"), - "config/path_optimizer.param.yaml", - ), - os.path.join( - get_package_share_directory("autoware_map_loader"), - "config/lanelet2_map_loader.param.yaml", - ), - os.path.join( - get_package_share_directory("autoware_static_centerline_generator"), - "config/common.param.yaml", - ), - os.path.join( - get_package_share_directory("autoware_static_centerline_generator"), - "config/nearest_search.param.yaml", - ), - os.path.join( - get_package_share_directory("autoware_static_centerline_generator"), - "config/vehicle_info.param.yaml", - ), - ], - ) - - context = {} - - return ( - LaunchDescription( - [ - static_centerline_generator_node, - # Start test after 1s - gives time for the autoware_static_centerline_generator to finish initialization - launch.actions.TimerAction( - period=1.0, actions=[launch_testing.actions.ReadyToTest()] - ), - ] - ), - context, - ) - - -@launch_testing.post_shutdown_test() -class TestProcessOutput(unittest.TestCase): - def test_exit_code(self, proc_info): - # Check that process exits with code 0: no error - launch_testing.asserts.assertExitCodes(proc_info) From 7ac40b7d5e29bee9a1eeed604e9340fdbd58e762 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Thu, 9 Jan 2025 15:30:58 +0900 Subject: [PATCH 165/334] feat: tier4_debug_msgs changed to autoware-internal_debug_msgs in files localization/autoware_ndt_scan_matcher (#9861) Signed-off-by: vish0012 Co-authored-by: SakodaShintaro --- .../autoware_ndt_scan_matcher/README.md | 40 +++++++++---------- .../ndt_scan_matcher_core.hpp | 23 ++++++----- .../autoware_ndt_scan_matcher/package.xml | 2 +- .../src/ndt_scan_matcher_core.cpp | 33 ++++++++------- 4 files changed, 51 insertions(+), 47 deletions(-) diff --git a/localization/autoware_ndt_scan_matcher/README.md b/localization/autoware_ndt_scan_matcher/README.md index 22e56930a0048..ee177608bdefe 100644 --- a/localization/autoware_ndt_scan_matcher/README.md +++ b/localization/autoware_ndt_scan_matcher/README.md @@ -25,26 +25,26 @@ One optional function is regularization. Please see the regularization chapter i ### Output -| Name | Type | Description | -| --------------------------------- | ----------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------- | -| `ndt_pose` | `geometry_msgs::msg::PoseStamped` | estimated pose | -| `ndt_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | estimated pose with covariance | -| `/diagnostics` | `diagnostic_msgs::msg::DiagnosticArray` | diagnostics | -| `points_aligned` | `sensor_msgs::msg::PointCloud2` | [debug topic] pointcloud aligned by scan matching | -| `points_aligned_no_ground` | `sensor_msgs::msg::PointCloud2` | [debug topic] no ground pointcloud aligned by scan matching | -| `initial_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | [debug topic] initial pose used in scan matching | -| `multi_ndt_pose` | `geometry_msgs::msg::PoseArray` | [debug topic] estimated poses from multiple initial poses in real-time covariance estimation | -| `multi_initial_pose` | `geometry_msgs::msg::PoseArray` | [debug topic] initial poses for real-time covariance estimation | -| `exe_time_ms` | `tier4_debug_msgs::msg::Float32Stamped` | [debug topic] execution time for scan matching [ms] | -| `transform_probability` | `tier4_debug_msgs::msg::Float32Stamped` | [debug topic] score of scan matching | -| `no_ground_transform_probability` | `tier4_debug_msgs::msg::Float32Stamped` | [debug topic] score of scan matching based on no ground LiDAR scan | -| `iteration_num` | `tier4_debug_msgs::msg::Int32Stamped` | [debug topic] number of scan matching iterations | -| `initial_to_result_relative_pose` | `geometry_msgs::msg::PoseStamped` | [debug topic] relative pose between the initial point and the convergence point | -| `initial_to_result_distance` | `tier4_debug_msgs::msg::Float32Stamped` | [debug topic] distance difference between the initial point and the convergence point [m] | -| `initial_to_result_distance_old` | `tier4_debug_msgs::msg::Float32Stamped` | [debug topic] distance difference between the older of the two initial points used in linear interpolation and the convergence point [m] | -| `initial_to_result_distance_new` | `tier4_debug_msgs::msg::Float32Stamped` | [debug topic] distance difference between the newer of the two initial points used in linear interpolation and the convergence point [m] | -| `ndt_marker` | `visualization_msgs::msg::MarkerArray` | [debug topic] markers for debugging | -| `monte_carlo_initial_pose_marker` | `visualization_msgs::msg::MarkerArray` | [debug topic] particles used in initial position estimation | +| Name | Type | Description | +| --------------------------------- | --------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------- | +| `ndt_pose` | `geometry_msgs::msg::PoseStamped` | estimated pose | +| `ndt_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | estimated pose with covariance | +| `/diagnostics` | `diagnostic_msgs::msg::DiagnosticArray` | diagnostics | +| `points_aligned` | `sensor_msgs::msg::PointCloud2` | [debug topic] pointcloud aligned by scan matching | +| `points_aligned_no_ground` | `sensor_msgs::msg::PointCloud2` | [debug topic] no ground pointcloud aligned by scan matching | +| `initial_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | [debug topic] initial pose used in scan matching | +| `multi_ndt_pose` | `geometry_msgs::msg::PoseArray` | [debug topic] estimated poses from multiple initial poses in real-time covariance estimation | +| `multi_initial_pose` | `geometry_msgs::msg::PoseArray` | [debug topic] initial poses for real-time covariance estimation | +| `exe_time_ms` | `autoware_internal_debug_msgs::msg::Float32Stamped` | [debug topic] execution time for scan matching [ms] | +| `transform_probability` | `autoware_internal_debug_msgs::msg::Float32Stamped` | [debug topic] score of scan matching | +| `no_ground_transform_probability` | `autoware_internal_debug_msgs::msg::Float32Stamped` | [debug topic] score of scan matching based on no ground LiDAR scan | +| `iteration_num` | `autoware_internal_debug_msgs::msg::Int32Stamped` | [debug topic] number of scan matching iterations | +| `initial_to_result_relative_pose` | `geometry_msgs::msg::PoseStamped` | [debug topic] relative pose between the initial point and the convergence point | +| `initial_to_result_distance` | `autoware_internal_debug_msgs::msg::Float32Stamped` | [debug topic] distance difference between the initial point and the convergence point [m] | +| `initial_to_result_distance_old` | `autoware_internal_debug_msgs::msg::Float32Stamped` | [debug topic] distance difference between the older of the two initial points used in linear interpolation and the convergence point [m] | +| `initial_to_result_distance_new` | `autoware_internal_debug_msgs::msg::Float32Stamped` | [debug topic] distance difference between the newer of the two initial points used in linear interpolation and the convergence point [m] | +| `ndt_marker` | `visualization_msgs::msg::MarkerArray` | [debug topic] markers for debugging | +| `monte_carlo_initial_pose_marker` | `visualization_msgs::msg::MarkerArray` | [debug topic] particles used in initial position estimation | ### Service diff --git a/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_scan_matcher_core.hpp b/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_scan_matcher_core.hpp index e083e6751c3db..d6e629ee2f1c3 100644 --- a/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_scan_matcher_core.hpp +++ b/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_scan_matcher_core.hpp @@ -26,6 +26,8 @@ #include #include +#include +#include #include #include #include @@ -33,8 +35,6 @@ #include #include #include -#include -#include #include #include @@ -166,23 +166,24 @@ class NDTScanMatcher : public rclcpp::Node initial_pose_with_covariance_pub_; rclcpp::Publisher::SharedPtr multi_ndt_pose_pub_; rclcpp::Publisher::SharedPtr multi_initial_pose_pub_; - rclcpp::Publisher::SharedPtr exe_time_pub_; - rclcpp::Publisher::SharedPtr transform_probability_pub_; - rclcpp::Publisher::SharedPtr + rclcpp::Publisher::SharedPtr exe_time_pub_; + rclcpp::Publisher::SharedPtr + transform_probability_pub_; + rclcpp::Publisher::SharedPtr nearest_voxel_transformation_likelihood_pub_; rclcpp::Publisher::SharedPtr voxel_score_points_pub_; - rclcpp::Publisher::SharedPtr + rclcpp::Publisher::SharedPtr no_ground_transform_probability_pub_; - rclcpp::Publisher::SharedPtr + rclcpp::Publisher::SharedPtr no_ground_nearest_voxel_transformation_likelihood_pub_; - rclcpp::Publisher::SharedPtr iteration_num_pub_; + rclcpp::Publisher::SharedPtr iteration_num_pub_; rclcpp::Publisher::SharedPtr initial_to_result_relative_pose_pub_; - rclcpp::Publisher::SharedPtr + rclcpp::Publisher::SharedPtr initial_to_result_distance_pub_; - rclcpp::Publisher::SharedPtr + rclcpp::Publisher::SharedPtr initial_to_result_distance_old_pub_; - rclcpp::Publisher::SharedPtr + rclcpp::Publisher::SharedPtr initial_to_result_distance_new_pub_; rclcpp::Publisher::SharedPtr ndt_marker_pub_; rclcpp::Publisher::SharedPtr diff --git a/localization/autoware_ndt_scan_matcher/package.xml b/localization/autoware_ndt_scan_matcher/package.xml index f2047418310aa..ebd1ebda2d573 100644 --- a/localization/autoware_ndt_scan_matcher/package.xml +++ b/localization/autoware_ndt_scan_matcher/package.xml @@ -17,6 +17,7 @@ ament_cmake_auto autoware_cmake + autoware_internal_debug_msgs autoware_localization_util autoware_map_msgs autoware_universe_utils @@ -35,7 +36,6 @@ tf2_geometry_msgs tf2_ros tf2_sensor_msgs - tier4_debug_msgs tier4_localization_msgs visualization_msgs diff --git a/localization/autoware_ndt_scan_matcher/src/ndt_scan_matcher_core.cpp b/localization/autoware_ndt_scan_matcher/src/ndt_scan_matcher_core.cpp index d3e1fa5982867..3d06dfffa16ed 100644 --- a/localization/autoware_ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/autoware_ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -53,18 +53,18 @@ using autoware::localization_util::SmartPoseBuffer; using autoware::localization_util::TreeStructuredParzenEstimator; using autoware::universe_utils::DiagnosticsInterface; -tier4_debug_msgs::msg::Float32Stamped make_float32_stamped( +autoware_internal_debug_msgs::msg::Float32Stamped make_float32_stamped( const builtin_interfaces::msg::Time & stamp, const float data) { - using T = tier4_debug_msgs::msg::Float32Stamped; - return tier4_debug_msgs::build().stamp(stamp).data(data); + using T = autoware_internal_debug_msgs::msg::Float32Stamped; + return autoware_internal_debug_msgs::build().stamp(stamp).data(data); } -tier4_debug_msgs::msg::Int32Stamped make_int32_stamped( +autoware_internal_debug_msgs::msg::Int32Stamped make_int32_stamped( const builtin_interfaces::msg::Time & stamp, const int32_t data) { - using T = tier4_debug_msgs::msg::Int32Stamped; - return tier4_debug_msgs::build().stamp(stamp).data(data); + using T = autoware_internal_debug_msgs::msg::Int32Stamped; + return autoware_internal_debug_msgs::build().stamp(stamp).data(data); } std::array rotate_covariance( @@ -158,31 +158,34 @@ NDTScanMatcher::NDTScanMatcher(const rclcpp::NodeOptions & options) multi_ndt_pose_pub_ = this->create_publisher("multi_ndt_pose", 10); multi_initial_pose_pub_ = this->create_publisher("multi_initial_pose", 10); - exe_time_pub_ = this->create_publisher("exe_time_ms", 10); + exe_time_pub_ = + this->create_publisher("exe_time_ms", 10); transform_probability_pub_ = - this->create_publisher("transform_probability", 10); + this->create_publisher( + "transform_probability", 10); nearest_voxel_transformation_likelihood_pub_ = - this->create_publisher( + this->create_publisher( "nearest_voxel_transformation_likelihood", 10); voxel_score_points_pub_ = this->create_publisher("voxel_score_points", 10); no_ground_transform_probability_pub_ = - this->create_publisher( + this->create_publisher( "no_ground_transform_probability", 10); no_ground_nearest_voxel_transformation_likelihood_pub_ = - this->create_publisher( + this->create_publisher( "no_ground_nearest_voxel_transformation_likelihood", 10); iteration_num_pub_ = - this->create_publisher("iteration_num", 10); + this->create_publisher("iteration_num", 10); initial_to_result_relative_pose_pub_ = this->create_publisher("initial_to_result_relative_pose", 10); initial_to_result_distance_pub_ = - this->create_publisher("initial_to_result_distance", 10); + this->create_publisher( + "initial_to_result_distance", 10); initial_to_result_distance_old_pub_ = - this->create_publisher( + this->create_publisher( "initial_to_result_distance_old", 10); initial_to_result_distance_new_pub_ = - this->create_publisher( + this->create_publisher( "initial_to_result_distance_new", 10); ndt_marker_pub_ = this->create_publisher("ndt_marker", 10); ndt_monte_carlo_initial_pose_marker_pub_ = From 22ca70398f7785af65446ee6a363b476c0fe72bd Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Thu, 9 Jan 2025 15:57:04 +0900 Subject: [PATCH 166/334] feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in fies localization/autoware_ekf_localizer (#9860) Signed-off-by: vish0012 Co-authored-by: SakodaShintaro --- localization/autoware_ekf_localizer/README.md | 22 +++++++++---------- .../autoware/ekf_localizer/ekf_localizer.hpp | 9 ++++---- .../autoware_ekf_localizer/package.xml | 2 +- .../src/ekf_localizer.cpp | 16 ++++++++------ 4 files changed, 26 insertions(+), 23 deletions(-) diff --git a/localization/autoware_ekf_localizer/README.md b/localization/autoware_ekf_localizer/README.md index 802bf7dbb16c3..a46ea7181315f 100644 --- a/localization/autoware_ekf_localizer/README.md +++ b/localization/autoware_ekf_localizer/README.md @@ -44,17 +44,17 @@ This package includes the following features: ### Published Topics -| Name | Type | Description | -| --------------------------------- | ------------------------------------------------ | ----------------------------------------------------- | -| `ekf_odom` | `nav_msgs::msg::Odometry` | Estimated odometry. | -| `ekf_pose` | `geometry_msgs::msg::PoseStamped` | Estimated pose. | -| `ekf_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Estimated pose with covariance. | -| `ekf_biased_pose` | `geometry_msgs::msg::PoseStamped` | Estimated pose including the yaw bias | -| `ekf_biased_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Estimated pose with covariance including the yaw bias | -| `ekf_twist` | `geometry_msgs::msg::TwistStamped` | Estimated twist. | -| `ekf_twist_with_covariance` | `geometry_msgs::msg::TwistWithCovarianceStamped` | The estimated twist with covariance. | -| `diagnostics` | `diagnostics_msgs::msg::DiagnosticArray` | The diagnostic information. | -| `debug/processing_time_ms` | `tier4_debug_msgs::msg::Float64Stamped` | The processing time [ms]. | +| Name | Type | Description | +| --------------------------------- | --------------------------------------------------- | ----------------------------------------------------- | +| `ekf_odom` | `nav_msgs::msg::Odometry` | Estimated odometry. | +| `ekf_pose` | `geometry_msgs::msg::PoseStamped` | Estimated pose. | +| `ekf_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Estimated pose with covariance. | +| `ekf_biased_pose` | `geometry_msgs::msg::PoseStamped` | Estimated pose including the yaw bias | +| `ekf_biased_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Estimated pose with covariance including the yaw bias | +| `ekf_twist` | `geometry_msgs::msg::TwistStamped` | Estimated twist. | +| `ekf_twist_with_covariance` | `geometry_msgs::msg::TwistWithCovarianceStamped` | The estimated twist with covariance. | +| `diagnostics` | `diagnostics_msgs::msg::DiagnosticArray` | The diagnostic information. | +| `debug/processing_time_ms` | `autoware_internal_debug_msgs::msg::Float64Stamped` | The processing time [ms]. | ### Published TF diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_localizer.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_localizer.hpp index 0561e250298ac..84018c043cc14 100644 --- a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_localizer.hpp +++ b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_localizer.hpp @@ -25,6 +25,8 @@ #include #include +#include +#include #include #include #include @@ -34,8 +36,6 @@ #include #include #include -#include -#include #include #include @@ -78,7 +78,7 @@ class EKFLocalizer : public rclcpp::Node //!< @brief ekf estimated twist with covariance publisher rclcpp::Publisher::SharedPtr pub_twist_cov_; //!< @brief ekf estimated yaw bias publisher - rclcpp::Publisher::SharedPtr pub_yaw_bias_; + rclcpp::Publisher::SharedPtr pub_yaw_bias_; //!< @brief ekf estimated yaw bias publisher rclcpp::Publisher::SharedPtr pub_biased_pose_; //!< @brief ekf estimated yaw bias publisher @@ -86,7 +86,8 @@ class EKFLocalizer : public rclcpp::Node //!< @brief diagnostics publisher rclcpp::Publisher::SharedPtr pub_diag_; //!< @brief processing_time publisher - rclcpp::Publisher::SharedPtr pub_processing_time_; + rclcpp::Publisher::SharedPtr + pub_processing_time_; //!< @brief initial pose subscriber rclcpp::Subscription::SharedPtr sub_initialpose_; //!< @brief measurement pose with covariance subscriber diff --git a/localization/autoware_ekf_localizer/package.xml b/localization/autoware_ekf_localizer/package.xml index 8dc3cc9844c50..e0e37f59d1acb 100644 --- a/localization/autoware_ekf_localizer/package.xml +++ b/localization/autoware_ekf_localizer/package.xml @@ -22,6 +22,7 @@ eigen + autoware_internal_debug_msgs autoware_kalman_filter autoware_localization_util autoware_universe_utils @@ -34,7 +35,6 @@ std_srvs tf2 tf2_ros - tier4_debug_msgs ament_cmake_ros ament_lint_auto diff --git a/localization/autoware_ekf_localizer/src/ekf_localizer.cpp b/localization/autoware_ekf_localizer/src/ekf_localizer.cpp index 11d7788adfade..5638a5416e6ab 100644 --- a/localization/autoware_ekf_localizer/src/ekf_localizer.cpp +++ b/localization/autoware_ekf_localizer/src/ekf_localizer.cpp @@ -70,13 +70,14 @@ EKFLocalizer::EKFLocalizer(const rclcpp::NodeOptions & node_options) pub_twist_ = create_publisher("ekf_twist", 1); pub_twist_cov_ = create_publisher( "ekf_twist_with_covariance", 1); - pub_yaw_bias_ = create_publisher("estimated_yaw_bias", 1); + pub_yaw_bias_ = + create_publisher("estimated_yaw_bias", 1); pub_biased_pose_ = create_publisher("ekf_biased_pose", 1); pub_biased_pose_cov_ = create_publisher( "ekf_biased_pose_with_covariance", 1); pub_diag_ = this->create_publisher("/diagnostics", 10); - pub_processing_time_ = - create_publisher("debug/processing_time_ms", 1); + pub_processing_time_ = create_publisher( + "debug/processing_time_ms", 1); sub_initialpose_ = create_subscription( "initialpose", 1, std::bind(&EKFLocalizer::callback_initial_pose, this, _1)); sub_pose_with_cov_ = create_subscription( @@ -235,9 +236,10 @@ void EKFLocalizer::timer_callback() /* publish processing time */ const double elapsed_time = stop_watch_timer_cb_.toc(); - pub_processing_time_->publish(tier4_debug_msgs::build() - .stamp(current_time) - .data(elapsed_time)); + pub_processing_time_->publish( + autoware_internal_debug_msgs::build() + .stamp(current_time) + .data(elapsed_time)); } /* @@ -343,7 +345,7 @@ void EKFLocalizer::publish_estimate_result( pub_twist_cov_->publish(twist_cov); /* publish yaw bias */ - tier4_debug_msgs::msg::Float64Stamped yawb; + autoware_internal_debug_msgs::msg::Float64Stamped yawb; yawb.stamp = current_ekf_twist.header.stamp; yawb.data = ekf_module_->get_yaw_bias(); pub_yaw_bias_->publish(yawb); From bb66275f29f829dd02a729de0df7fda8deb0884b Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Thu, 9 Jan 2025 16:27:44 +0900 Subject: [PATCH 167/334] ci(cppcheck): ignore benchmarks directories for cppcheck (#9842) Signed-off-by: veqcc --- .cppcheck_suppressions | 1 + 1 file changed, 1 insertion(+) diff --git a/.cppcheck_suppressions b/.cppcheck_suppressions index ab267ec3ac007..4119e69ed72e1 100644 --- a/.cppcheck_suppressions +++ b/.cppcheck_suppressions @@ -1,5 +1,6 @@ *:*/test/* *:*/examples/* +*:*/benchmarks/* checkersReport missingInclude From c8ee48bd6828ba0b7352250541425e66aa96f2b3 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Thu, 9 Jan 2025 20:38:17 +0900 Subject: [PATCH 168/334] =?UTF-8?q?feat:=20tier4=5Fdebug=5Fmsgs=20changed?= =?UTF-8?q?=20to=20autoware=5Finternal=5Fdebug=5Fmsgs=20in=20fil=E2=80=A6?= =?UTF-8?q?=20(#9880)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files perception/autoware_detection_by_tracker Signed-off-by: vish0012 Co-authored-by: Taekjin LEE --- .../autoware_detection_by_tracker/src/debugger/debugger.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/autoware_detection_by_tracker/src/debugger/debugger.hpp b/perception/autoware_detection_by_tracker/src/debugger/debugger.hpp index 39dd3db10cfa9..8bd1deba35ccb 100644 --- a/perception/autoware_detection_by_tracker/src/debugger/debugger.hpp +++ b/perception/autoware_detection_by_tracker/src/debugger/debugger.hpp @@ -89,9 +89,9 @@ class Debugger void startMeasureProcessingTime() { stop_watch_ptr_->tic("processing_time"); } void publishProcessingTime() { - processing_time_publisher_->publish( + processing_time_publisher_->publish( "debug/cyclic_time_ms", stop_watch_ptr_->toc("cyclic_time", true)); - processing_time_publisher_->publish( + processing_time_publisher_->publish( "debug/processing_time_ms", stop_watch_ptr_->toc("processing_time", true)); } From 56ff9b8de27e050787f9b2fe610f5df1348c4a03 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Fri, 10 Jan 2025 01:49:20 +0900 Subject: [PATCH 169/334] =?UTF-8?q?feat:=20tier4=5Fdebug=5Fmsgs=20changed?= =?UTF-8?q?=20to=20autoware=5Finternal=5Fdebug=5Fmsgs=20in=20fil=E2=80=A6?= =?UTF-8?q?=20(#9858)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files evaluator/autoware_control_evaluator Signed-off-by: vish0012 --- .../autoware/control_evaluator/control_evaluator_node.hpp | 5 +++-- .../src/control_evaluator_node.cpp | 6 +++--- 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp b/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp index c510b2ea46779..9606dea577bd0 100644 --- a/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp +++ b/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp @@ -25,9 +25,9 @@ #include #include "geometry_msgs/msg/accel_with_covariance_stamped.hpp" +#include #include #include -#include #include #include @@ -85,7 +85,8 @@ class ControlEvaluatorNode : public rclcpp::Node LaneletMapBin, autoware::universe_utils::polling_policy::Newest> vector_map_subscriber_{this, "~/input/vector_map", rclcpp::QoS{1}.transient_local()}; - rclcpp::Publisher::SharedPtr processing_time_pub_; + rclcpp::Publisher::SharedPtr + processing_time_pub_; rclcpp::Publisher::SharedPtr metrics_pub_; // update Route Handler diff --git a/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp b/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp index b0db41b0fdc73..79e89423af6dd 100644 --- a/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp +++ b/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp @@ -34,8 +34,8 @@ ControlEvaluatorNode::ControlEvaluatorNode(const rclcpp::NodeOptions & node_opti using std::placeholders::_1; // Publisher - processing_time_pub_ = - this->create_publisher("~/debug/processing_time_ms", 1); + processing_time_pub_ = this->create_publisher( + "~/debug/processing_time_ms", 1); metrics_pub_ = create_publisher("~/metrics", 1); // Parameters @@ -288,7 +288,7 @@ void ControlEvaluatorNode::onTimer() metrics_msg_ = MetricArrayMsg{}; // Publish processing time - tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg; processing_time_msg.stamp = get_clock()->now(); processing_time_msg.data = stop_watch.toc(); processing_time_pub_->publish(processing_time_msg); From 6fe89228f731af6f97541de0f3b163752a5baefc Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Fri, 10 Jan 2025 01:49:37 +0900 Subject: [PATCH 170/334] =?UTF-8?q?feat:=20tier4=5Fdebug=5Fmsgs=20changed?= =?UTF-8?q?=20to=20autoware=5Finternal=5Fdebug=5Fmsgs=20in=20fil=E2=80=A6?= =?UTF-8?q?=20(#9857)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files control/control_performance_analysis Signed-off-by: vish0012 --- control/control_performance_analysis/package.xml | 2 +- .../scripts/control_performance_plot.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/control/control_performance_analysis/package.xml b/control/control_performance_analysis/package.xml index 9c2ef69e0137b..f2630a7d47f62 100644 --- a/control/control_performance_analysis/package.xml +++ b/control/control_performance_analysis/package.xml @@ -25,6 +25,7 @@ builtin_interfaces autoware_control_msgs + autoware_internal_debug_msgs autoware_motion_utils autoware_planning_msgs autoware_signal_processing @@ -41,7 +42,6 @@ tf2 tf2_eigen tf2_ros - tier4_debug_msgs autoware_global_parameter_loader builtin_interfaces rosidl_default_runtime diff --git a/control/control_performance_analysis/scripts/control_performance_plot.py b/control/control_performance_analysis/scripts/control_performance_plot.py index c5e5cabd5b059..d4a6038465e12 100644 --- a/control/control_performance_analysis/scripts/control_performance_plot.py +++ b/control/control_performance_analysis/scripts/control_performance_plot.py @@ -17,13 +17,13 @@ import argparse import math +from autoware_internal_debug_msgs.msg import BoolStamped from control_performance_analysis.msg import DrivingMonitorStamped from control_performance_analysis.msg import ErrorStamped import matplotlib.pyplot as plt from nav_msgs.msg import Odometry import rclpy from rclpy.node import Node -from tier4_debug_msgs.msg import BoolStamped parser = argparse.ArgumentParser() parser.add_argument("-i", "--interval", help="interval distance to plot") From 4d0a86f10df9462696a1955511f882042914db5d Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Fri, 10 Jan 2025 01:50:28 +0900 Subject: [PATCH 171/334] =?UTF-8?q?feat:=20tier4=5Fdebug=5Fmsgs=20changed?= =?UTF-8?q?=20to=20autoware=5Finternal=5Fmsgs=20in=20files=20con=E2=80=A6?= =?UTF-8?q?=20(#9852)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs changed to autoware_internal_msgs in files control/autoware_trajectory_follower_base Signed-off-by: vish0012 --- control/autoware_trajectory_follower_base/package.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/control/autoware_trajectory_follower_base/package.xml b/control/autoware_trajectory_follower_base/package.xml index e7b00e4b19cdc..195c077835910 100644 --- a/control/autoware_trajectory_follower_base/package.xml +++ b/control/autoware_trajectory_follower_base/package.xml @@ -21,6 +21,7 @@ autoware_adapi_v1_msgs autoware_control_msgs + autoware_internal_debug_msgs autoware_interpolation autoware_motion_utils autoware_osqp_interface @@ -37,7 +38,6 @@ std_msgs tf2 tf2_ros - tier4_debug_msgs ament_cmake_ros ament_lint_auto From 926ad7f3d6d1e0a6c689ce6e2a1a104d850913e3 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Fri, 10 Jan 2025 01:52:15 +0900 Subject: [PATCH 172/334] =?UTF-8?q?feat:=20tier4=5Fdebug=5Fmsgs=20changed?= =?UTF-8?q?=20to=20autoware=5Finternal=5Fdebug=5Fmsgs=20in=20fil=E2=80=A6?= =?UTF-8?q?=20(#9848)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files control/autoware_pid_longitudinal_controller Signed-off-by: vish0012 --- .../pid_longitudinal_controller.hpp | 8 +++++--- control/autoware_pid_longitudinal_controller/package.xml | 2 +- .../src/pid_longitudinal_controller.cpp | 8 ++++---- 3 files changed, 10 insertions(+), 8 deletions(-) diff --git a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp index 1d03d1b339af6..db5fa09b5eeee 100644 --- a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp +++ b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp @@ -34,11 +34,11 @@ #include "autoware_adapi_v1_msgs/msg/operation_mode_state.hpp" #include "autoware_control_msgs/msg/longitudinal.hpp" +#include "autoware_internal_debug_msgs/msg/float32_multi_array_stamped.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "nav_msgs/msg/odometry.hpp" #include "tf2_msgs/msg/tf_message.hpp" -#include "tier4_debug_msgs/msg/float32_multi_array_stamped.hpp" #include "visualization_msgs/msg/marker.hpp" #include @@ -98,8 +98,10 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro rclcpp::Clock::SharedPtr clock_; rclcpp::Logger logger_; // ros variables - rclcpp::Publisher::SharedPtr m_pub_slope; - rclcpp::Publisher::SharedPtr m_pub_debug; + rclcpp::Publisher::SharedPtr + m_pub_slope; + rclcpp::Publisher::SharedPtr + m_pub_debug; rclcpp::Publisher::SharedPtr m_pub_virtual_wall_marker; rclcpp::Node::OnSetParametersCallbackHandle::SharedPtr m_set_param_res; diff --git a/control/autoware_pid_longitudinal_controller/package.xml b/control/autoware_pid_longitudinal_controller/package.xml index 67e95a9d4c0ac..127ce8e76d69d 100644 --- a/control/autoware_pid_longitudinal_controller/package.xml +++ b/control/autoware_pid_longitudinal_controller/package.xml @@ -21,6 +21,7 @@ autoware_adapi_v1_msgs autoware_control_msgs + autoware_internal_debug_msgs autoware_interpolation autoware_motion_utils autoware_planning_msgs @@ -37,7 +38,6 @@ std_msgs tf2 tf2_ros - tier4_debug_msgs ament_cmake_ros ament_lint_auto diff --git a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp index ec95ce656fa6f..c87e936de3e40 100644 --- a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp +++ b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp @@ -214,9 +214,9 @@ PidLongitudinalController::PidLongitudinalController( : node.declare_parameter("ego_nearest_yaw_threshold"); // [rad] // subscriber, publisher - m_pub_slope = node.create_publisher( + m_pub_slope = node.create_publisher( "~/output/slope_angle", rclcpp::QoS{1}); - m_pub_debug = node.create_publisher( + m_pub_debug = node.create_publisher( "~/output/longitudinal_diagnostic", rclcpp::QoS{1}); m_pub_virtual_wall_marker = node.create_publisher("~/virtual_wall", 1); @@ -931,7 +931,7 @@ void PidLongitudinalController::publishDebugData( m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_PUBLISHED, ctrl_cmd.acc); // publish debug values - tier4_debug_msgs::msg::Float32MultiArrayStamped debug_msg{}; + autoware_internal_debug_msgs::msg::Float32MultiArrayStamped debug_msg{}; debug_msg.stamp = clock_->now(); for (const auto & v : m_debug_values.getValues()) { debug_msg.data.push_back(static_cast(v)); @@ -939,7 +939,7 @@ void PidLongitudinalController::publishDebugData( m_pub_debug->publish(debug_msg); // slope angle - tier4_debug_msgs::msg::Float32MultiArrayStamped slope_msg{}; + autoware_internal_debug_msgs::msg::Float32MultiArrayStamped slope_msg{}; slope_msg.stamp = clock_->now(); slope_msg.data.push_back( static_cast(control_data.slope_angle)); From 0b73c13206e4185b0182a8ec11710e7c17959006 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Fri, 10 Jan 2025 01:52:55 +0900 Subject: [PATCH 173/334] =?UTF-8?q?feat:=20tier4=5Fdebug=5Fmsgs=20changed?= =?UTF-8?q?=20to=20autoware=5Finternal=5Fdebug=5Fmsgs=20in=20fil=E2=80=A6?= =?UTF-8?q?=20(#9846)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files ontrol/autoware_mpc_lateral_controller Signed-off-by: vish0012 * style(pre-commit): autofix --------- Signed-off-by: vish0012 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../lane_departure_checker_node.hpp | 5 +++-- control/autoware_lane_departure_checker/package.xml | 2 +- .../lane_departure_checker_node.cpp | 12 +++++++----- .../include/autoware/mpc_lateral_controller/mpc.hpp | 4 ++-- .../mpc_lateral_controller.hpp | 8 ++++---- control/autoware_mpc_lateral_controller/package.xml | 2 +- .../test/test_mpc.cpp | 4 ++-- 7 files changed, 20 insertions(+), 17 deletions(-) diff --git a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker_node.hpp b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker_node.hpp index 7e2229d7b5754..4d99b1a134b3a 100644 --- a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker_node.hpp +++ b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker_node.hpp @@ -24,6 +24,7 @@ #include #include +#include #include #include #include @@ -31,7 +32,6 @@ #include #include #include -#include #include #include @@ -115,7 +115,8 @@ class LaneDepartureCheckerNode : public rclcpp::Node autoware::universe_utils::DebugPublisher debug_publisher_{this, "~/debug"}; autoware::universe_utils::ProcessingTimePublisher processing_diag_publisher_{ this, "~/debug/processing_time_ms_diag"}; - rclcpp::Publisher::SharedPtr processing_time_publisher_; + rclcpp::Publisher::SharedPtr + processing_time_publisher_; // Timer rclcpp::TimerBase::SharedPtr timer_; diff --git a/control/autoware_lane_departure_checker/package.xml b/control/autoware_lane_departure_checker/package.xml index 2689b4a4dbcb7..97ad5eaf82e00 100644 --- a/control/autoware_lane_departure_checker/package.xml +++ b/control/autoware_lane_departure_checker/package.xml @@ -14,6 +14,7 @@ autoware_cmake autoware_adapi_v1_msgs + autoware_internal_debug_msgs autoware_lanelet2_extension autoware_map_msgs autoware_motion_utils @@ -32,7 +33,6 @@ tf2_eigen tf2_geometry_msgs tf2_ros - tier4_debug_msgs ament_cmake_ros ament_lint_auto diff --git a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp index 366b84a1f6131..d9775415d3ed3 100644 --- a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp +++ b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp @@ -171,7 +171,8 @@ LaneDepartureCheckerNode::LaneDepartureCheckerNode(const rclcpp::NodeOptions & o // Publisher processing_time_publisher_ = - this->create_publisher("~/debug/processing_time_ms", 1); + this->create_publisher( + "~/debug/processing_time_ms", 1); // Nothing // Diagnostic Updater @@ -342,10 +343,11 @@ void LaneDepartureCheckerNode::onTimer() { const auto & deviation = output_.trajectory_deviation; - debug_publisher_.publish( + debug_publisher_.publish( "deviation/lateral", deviation.lateral); - debug_publisher_.publish("deviation/yaw", deviation.yaw); - debug_publisher_.publish( + debug_publisher_.publish( + "deviation/yaw", deviation.yaw); + debug_publisher_.publish( "deviation/yaw_deg", rad2deg(deviation.yaw)); } processing_time_map["Node: publishTrajectoryDeviation"] = stop_watch.toc(true); @@ -361,7 +363,7 @@ void LaneDepartureCheckerNode::onTimer() processing_time_map["Total"] = stop_watch.toc("Total"); processing_diag_publisher_.publish(processing_time_map); - tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg; processing_time_msg.stamp = get_clock()->now(); processing_time_msg.data = processing_time_map["Total"]; processing_time_publisher_->publish(processing_time_msg); diff --git a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc.hpp b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc.hpp index 4c8d5df2c22a7..166dfa1814562 100644 --- a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc.hpp +++ b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc.hpp @@ -24,11 +24,11 @@ #include "rclcpp/rclcpp.hpp" #include "autoware_control_msgs/msg/lateral.hpp" +#include "autoware_internal_debug_msgs/msg/float32_multi_array_stamped.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" #include "autoware_vehicle_msgs/msg/steering_report.hpp" #include "geometry_msgs/msg/pose.hpp" #include "nav_msgs/msg/odometry.hpp" -#include "tier4_debug_msgs/msg/float32_multi_array_stamped.hpp" #include #include @@ -41,11 +41,11 @@ namespace autoware::motion::control::mpc_lateral_controller using autoware::motion::control::trajectory_follower::LateralHorizon; using autoware_control_msgs::msg::Lateral; +using autoware_internal_debug_msgs::msg::Float32MultiArrayStamped; using autoware_planning_msgs::msg::Trajectory; using autoware_vehicle_msgs::msg::SteeringReport; using geometry_msgs::msg::Pose; using nav_msgs::msg::Odometry; -using tier4_debug_msgs::msg::Float32MultiArrayStamped; using Eigen::MatrixXd; using Eigen::VectorXd; diff --git a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp index d7442f64b028a..0f3004775e5bd 100644 --- a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp +++ b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp @@ -26,13 +26,13 @@ #include #include "autoware_control_msgs/msg/lateral.hpp" +#include "autoware_internal_debug_msgs/msg/float32_multi_array_stamped.hpp" +#include "autoware_internal_debug_msgs/msg/float32_stamped.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" #include "autoware_vehicle_msgs/msg/steering_report.hpp" #include "geometry_msgs/msg/pose.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "nav_msgs/msg/odometry.hpp" -#include "tier4_debug_msgs/msg/float32_multi_array_stamped.hpp" -#include "tier4_debug_msgs/msg/float32_stamped.hpp" #include #include @@ -45,11 +45,11 @@ namespace autoware::motion::control::mpc_lateral_controller namespace trajectory_follower = ::autoware::motion::control::trajectory_follower; using autoware_control_msgs::msg::Lateral; +using autoware_internal_debug_msgs::msg::Float32MultiArrayStamped; +using autoware_internal_debug_msgs::msg::Float32Stamped; using autoware_planning_msgs::msg::Trajectory; using autoware_vehicle_msgs::msg::SteeringReport; using nav_msgs::msg::Odometry; -using tier4_debug_msgs::msg::Float32MultiArrayStamped; -using tier4_debug_msgs::msg::Float32Stamped; using trajectory_follower::LateralHorizon; class MpcLateralController : public trajectory_follower::LateralControllerBase diff --git a/control/autoware_mpc_lateral_controller/package.xml b/control/autoware_mpc_lateral_controller/package.xml index b450af05ea0e1..719d11ef7948b 100644 --- a/control/autoware_mpc_lateral_controller/package.xml +++ b/control/autoware_mpc_lateral_controller/package.xml @@ -19,6 +19,7 @@ autoware_cmake autoware_control_msgs + autoware_internal_debug_msgs autoware_interpolation autoware_motion_utils autoware_osqp_interface @@ -36,7 +37,6 @@ std_msgs tf2 tf2_ros - tier4_debug_msgs ament_cmake_ros ament_lint_auto diff --git a/control/autoware_mpc_lateral_controller/test/test_mpc.cpp b/control/autoware_mpc_lateral_controller/test/test_mpc.cpp index 9c30369305f6e..0a34302f8f60c 100644 --- a/control/autoware_mpc_lateral_controller/test/test_mpc.cpp +++ b/control/autoware_mpc_lateral_controller/test/test_mpc.cpp @@ -24,11 +24,11 @@ #include #include "autoware_control_msgs/msg/lateral.hpp" +#include "autoware_internal_debug_msgs/msg/float32_multi_array_stamped.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" #include "autoware_planning_msgs/msg/trajectory_point.hpp" #include "autoware_vehicle_msgs/msg/steering_report.hpp" #include "geometry_msgs/msg/pose.hpp" -#include "tier4_debug_msgs/msg/float32_multi_array_stamped.hpp" #ifdef ROS_DISTRO_GALACTIC #include "tf2_geometry_msgs/tf2_geometry_msgs.h" @@ -45,12 +45,12 @@ namespace autoware::motion::control::mpc_lateral_controller using autoware::motion::control::trajectory_follower::LateralHorizon; using autoware_control_msgs::msg::Lateral; +using autoware_internal_debug_msgs::msg::Float32MultiArrayStamped; using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; using autoware_vehicle_msgs::msg::SteeringReport; using geometry_msgs::msg::Pose; using geometry_msgs::msg::PoseStamped; -using tier4_debug_msgs::msg::Float32MultiArrayStamped; TrajectoryPoint makePoint(const double x, const double y, const float vx) { From 4dc720114dab3d07989b365bdd64be84bf5f4b60 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Fri, 10 Jan 2025 10:20:00 +0900 Subject: [PATCH 174/334] refactor(lane_change): refactor transit failure function (#9835) * refactor(lane_change): refactor transit failure function Signed-off-by: Zulfaqar Azmi * fixed failed scenario Signed-off-by: Zulfaqar Azmi * remove is abort from debug Signed-off-by: Zulfaqar Azmi * set is abort state Signed-off-by: Zulfaqar Azmi * add comments for clarity Signed-off-by: Zulfaqar Azmi * include what you use. Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Zulfaqar Azmi --- .../interface.hpp | 5 + .../structs/data.hpp | 1 + .../structs/debug.hpp | 8 +- .../utils/markers.hpp | 8 +- .../src/interface.cpp | 154 ++++++++---------- .../src/scene.cpp | 19 +-- .../src/utils/markers.cpp | 41 +++-- 7 files changed, 111 insertions(+), 125 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp index a69ae0d92647a..4b97fb0d069a0 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp @@ -35,6 +35,7 @@ #include #include #include +#include namespace autoware::behavior_path_planner { @@ -120,6 +121,8 @@ class LaneChangeInterface : public SceneModuleInterface } } + std::pair check_transit_failure(); + void updateDebugMarker() const; void updateSteeringFactorPtr(const BehaviorModuleOutput & output); @@ -134,6 +137,8 @@ class LaneChangeInterface : public SceneModuleInterface bool is_abort_path_approved_{false}; bool is_abort_approval_requested_{false}; + + lane_change::InterfaceDebug interface_debug_; }; } // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp index d5bbfe25fe1e9..9e6b9d229d2f2 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp @@ -48,6 +48,7 @@ enum class States { Cancel, Abort, Stop, + Warning, }; struct PhaseInfo diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp index 90b13f86976b2..1541846841f20 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp @@ -58,7 +58,6 @@ struct Debug double distance_to_abort_finished{std::numeric_limits::max()}; bool is_able_to_return_to_current_lane{true}; bool is_stuck{false}; - bool is_abort{false}; void reset() { @@ -83,9 +82,14 @@ struct Debug distance_to_abort_finished = std::numeric_limits::max(); is_able_to_return_to_current_lane = true; is_stuck = false; - is_abort = false; } }; + +struct InterfaceDebug +{ + std::string_view failing_reason; + LaneChangeStates lc_state; +}; } // namespace autoware::behavior_path_planner::lane_change #endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__STRUCTS__DEBUG_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/markers.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/markers.hpp index 059db8e38300f..a9ea35cb9b83e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/markers.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/markers.hpp @@ -32,6 +32,7 @@ namespace marker_utils::lane_change_markers using autoware::behavior_path_planner::FilteredLanesObjects; using autoware::behavior_path_planner::LaneChangePath; using autoware::behavior_path_planner::lane_change::Debug; +using autoware::behavior_path_planner::lane_change::InterfaceDebug; using autoware::behavior_path_planner::utils::path_safety_checker::ExtendedPredictedObjects; using visualization_msgs::msg::MarkerArray; MarkerArray showAllValidLaneChangePath( @@ -42,9 +43,12 @@ MarkerArray createLaneChangingVirtualWallMarker( MarkerArray showFilteredObjects( const FilteredLanesObjects & filtered_objects, const std::string & ns); MarkerArray createExecutionArea(const geometry_msgs::msg::Polygon & execution_area); -MarkerArray showExecutionInfo(const Debug & debug_data, const geometry_msgs::msg::Pose & ego_pose); +MarkerArray showExecutionInfo( + const InterfaceDebug & interface_debug_data, const Debug & scene_debug_data, + const geometry_msgs::msg::Pose & ego_pose); MarkerArray createDebugMarkerArray( - const Debug & debug_data, const geometry_msgs::msg::Pose & ego_pose); + const InterfaceDebug & interface_debug_data, const Debug & scene_debug_data, + const geometry_msgs::msg::Pose & ego_pose); } // namespace marker_utils::lane_change_markers #endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__MARKERS_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp index 9f3c6c9ef48bf..ebcd4eb4809fc 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp @@ -139,9 +139,8 @@ BehaviorModuleOutput LaneChangeInterface::plan() const auto force_activated = std::any_of( rtc_interface_ptr_map_.begin(), rtc_interface_ptr_map_.end(), [&](const auto & rtc) { return rtc.second->isForceActivated(uuid_map_.at(rtc.first)); }); - const bool safe = force_activated ? false : true; updateRTCStatus( - path.start_distance_to_path_change, path.finish_distance_to_path_change, safe, + path.start_distance_to_path_change, path.finish_distance_to_path_change, !force_activated, State::RUNNING); } } @@ -220,9 +219,7 @@ bool LaneChangeInterface::canTransitSuccessState() if (module_type_->specialExpiredCheck() && isWaitingApproval()) { log_debug_throttled("Run specialExpiredCheck."); - if (isWaitingApproval()) { - return true; - } + return true; } if (module_type_->hasFinishedLaneChange()) { @@ -237,13 +234,6 @@ bool LaneChangeInterface::canTransitSuccessState() bool LaneChangeInterface::canTransitFailureState() { - auto log_debug_throttled = [&](std::string_view message) -> void { - RCLCPP_DEBUG(getLogger(), "%s", message.data()); - }; - - updateDebugMarker(); - log_debug_throttled(__func__); - const auto force_activated = std::any_of( rtc_interface_ptr_map_.begin(), rtc_interface_ptr_map_.end(), [&](const auto & rtc) { return rtc.second->isForceActivated(uuid_map_.at(rtc.first)); }); @@ -253,121 +243,106 @@ bool LaneChangeInterface::canTransitFailureState() return false; } - if (module_type_->isAbortState() && !module_type_->hasFinishedAbort()) { - log_debug_throttled("Abort process has on going."); - return false; - } + const auto [state, reason] = check_transit_failure(); - if (isWaitingApproval()) { - if (module_type_->is_near_regulatory_element()) { - log_debug_throttled("Ego is close to regulatory element. Cancel lane change"); - updateRTCStatus( - std::numeric_limits::lowest(), std::numeric_limits::lowest(), true, - State::FAILED); - return true; - } - log_debug_throttled("Can't transit to failure state. Module is WAITING_FOR_APPROVAL"); - return false; - } + interface_debug_.failing_reason = reason; + interface_debug_.lc_state = state; - if (!module_type_->isValidPath()) { - log_debug_throttled("Transit to failure state due not to find valid path"); + updateDebugMarker(); + + if (state == LaneChangeStates::Cancel) { updateRTCStatus( std::numeric_limits::lowest(), std::numeric_limits::lowest(), true, State::FAILED); + module_type_->toCancelState(); return true; } - if (module_type_->isAbortState() && module_type_->hasFinishedAbort()) { - log_debug_throttled("Abort process has completed."); - updateRTCStatus( - std::numeric_limits::lowest(), std::numeric_limits::lowest(), true, - State::FAILED); - return true; + if (state == LaneChangeStates::Abort) { + module_type_->toAbortState(); + return false; } - if (module_type_->is_near_terminal()) { - log_debug_throttled("Unsafe, but ego is approaching terminal. Continue lane change"); + // Note: Ideally, if it is unsafe, but for some reason, we can't abort or cancel, then we should + // stop. Note: This feature is not working properly for now. + const auto [is_safe, unsafe_trailing_obj] = post_process_safety_status_; + if (!is_safe && module_type_->isRequiredStop(unsafe_trailing_obj)) { + module_type_->toStopState(); + return false; + } + + module_type_->toNormalState(); + return false; +} - if (module_type_->isRequiredStop(post_process_safety_status_.is_trailing_object)) { - log_debug_throttled("Module require stopping"); +std::pair LaneChangeInterface::check_transit_failure() +{ + if (module_type_->isAbortState()) { + if (module_type_->hasFinishedAbort()) { + return {LaneChangeStates::Cancel, "Aborted"}; } - return false; + return {LaneChangeStates::Abort, "Aborting"}; } - if (module_type_->isCancelEnabled() && module_type_->isEgoOnPreparePhase()) { - if (module_type_->isStoppedAtRedTrafficLight()) { - log_debug_throttled("Stopping at traffic light while in prepare phase. Cancel lane change"); - module_type_->toCancelState(); - updateRTCStatus( - std::numeric_limits::lowest(), std::numeric_limits::lowest(), true, - State::FAILED); - return true; + if (isWaitingApproval()) { + if (module_type_->is_near_regulatory_element()) { + return {LaneChangeStates::Cancel, "CloseToRegElement"}; } + return {LaneChangeStates::Normal, "WaitingForApproval"}; + } + if (!module_type_->isValidPath()) { + return {LaneChangeStates::Cancel, "InvalidPath"}; + } + + const auto is_preparing = module_type_->isEgoOnPreparePhase(); + const auto can_return_to_current = module_type_->isAbleToReturnCurrentLane(); + + // regardless of safe and unsafe, we want to cancel lane change. + if (is_preparing) { const auto force_deactivated = std::any_of( rtc_interface_ptr_map_.begin(), rtc_interface_ptr_map_.end(), [&](const auto & rtc) { return rtc.second->isForceDeactivated(uuid_map_.at(rtc.first)); }); - if (force_deactivated && module_type_->isAbleToReturnCurrentLane()) { - log_debug_throttled("Cancel lane change due to force deactivation"); - module_type_->toCancelState(); - updateRTCStatus( - std::numeric_limits::lowest(), std::numeric_limits::lowest(), true, - State::FAILED); - return true; - } - - if (post_process_safety_status_.is_safe) { - log_debug_throttled("Can't transit to failure state. Ego is on prepare, and it's safe."); - return false; - } - - if (module_type_->isAbleToReturnCurrentLane()) { - log_debug_throttled("It's possible to return to current lane. Cancel lane change."); - updateRTCStatus( - std::numeric_limits::lowest(), std::numeric_limits::lowest(), true, - State::FAILED); - return true; + if (force_deactivated && can_return_to_current) { + return {LaneChangeStates::Cancel, "ForceDeactivation"}; } } if (post_process_safety_status_.is_safe) { - log_debug_throttled("Can't transit to failure state. Ego is lane changing, and it's safe."); - return false; + return {LaneChangeStates::Normal, "SafeToLaneChange"}; } - if (module_type_->isRequiredStop(post_process_safety_status_.is_trailing_object)) { - log_debug_throttled("Module require stopping"); + if (!module_type_->isCancelEnabled()) { + return {LaneChangeStates::Warning, "CancelDisabled"}; } - if (!module_type_->isCancelEnabled()) { - log_debug_throttled( - "Lane change path is unsafe but cancel was not enabled. Continue lane change."); - return false; + // We also check if the ego can return to the current lane, as prepare segment might be out of the + // lane, for example, during an evasive maneuver around a static object. + if (is_preparing && can_return_to_current) { + return {LaneChangeStates::Cancel, "SafeToCancel"}; + } + + if (module_type_->is_near_terminal()) { + return {LaneChangeStates::Warning, "TooNearTerminal"}; } if (!module_type_->isAbortEnabled()) { - log_debug_throttled( - "Lane change path is unsafe but abort was not enabled. Continue lane change."); - return false; + return {LaneChangeStates::Warning, "AbortDisabled"}; } - if (!module_type_->isAbleToReturnCurrentLane()) { - log_debug_throttled("It's is not possible to return to original lane. Continue lane change."); - return false; + // To prevent the lane module from having to check rear objects in the current lane, we limit the + // abort maneuver to cases where the ego vehicle is still in the current lane. + if (!can_return_to_current) { + return {LaneChangeStates::Warning, "TooLateToAbort"}; } const auto found_abort_path = module_type_->calcAbortPath(); if (!found_abort_path) { - log_debug_throttled( - "Lane change path is unsafe but abort path not found. Continue lane change."); - return false; + return {LaneChangeStates::Warning, "AbortPathNotFound"}; } - log_debug_throttled("Lane change path is unsafe. Abort lane change."); - module_type_->toAbortState(); - return false; + return {LaneChangeStates::Abort, "SafeToAbort"}; } void LaneChangeInterface::updateDebugMarker() const @@ -377,7 +352,8 @@ void LaneChangeInterface::updateDebugMarker() const return; } using marker_utils::lane_change_markers::createDebugMarkerArray; - debug_marker_ = createDebugMarkerArray(module_type_->getDebugData(), module_type_->getEgoPose()); + debug_marker_ = createDebugMarkerArray( + interface_debug_, module_type_->getDebugData(), module_type_->getEgoPose()); } MarkerArray LaneChangeInterface::getModuleVirtualWall() diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index 2719239baaed8..09a4216bf5857 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -892,7 +892,6 @@ bool NormalLaneChange::isAbleToStopSafely() const bool NormalLaneChange::hasFinishedAbort() const { if (!abort_path_) { - lane_change_debug_.is_abort = true; return true; } @@ -901,7 +900,6 @@ bool NormalLaneChange::hasFinishedAbort() const lane_change_debug_.distance_to_abort_finished = distance_to_finish; const auto has_finished_abort = distance_to_finish < 0.0; - lane_change_debug_.is_abort = has_finished_abort; return has_finished_abort; } @@ -916,12 +914,7 @@ bool NormalLaneChange::isAbortState() const return false; } - if (!abort_path_) { - return false; - } - - lane_change_debug_.is_abort = true; - return true; + return abort_path_ != nullptr; } int NormalLaneChange::getNumToPreferredLane(const lanelet::ConstLanelet & lane) const @@ -1491,14 +1484,8 @@ bool NormalLaneChange::isValidPath(const PathWithLaneId & path) const bool NormalLaneChange::isRequiredStop(const bool is_trailing_object) { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); - if ( - common_data_ptr_->transient_data.is_ego_near_current_terminal_start && isAbleToStopSafely() && - is_trailing_object) { - current_lane_change_state_ = LaneChangeStates::Stop; - return true; - } - current_lane_change_state_ = LaneChangeStates::Normal; - return false; + return common_data_ptr_->transient_data.is_ego_near_current_terminal_start && + isAbleToStopSafely() && is_trailing_object; } bool NormalLaneChange::calcAbortPath() diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp index da9ee52b038c6..eb120e006a229 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp @@ -19,6 +19,7 @@ #include #include #include +#include #include #include @@ -164,7 +165,9 @@ MarkerArray showFilteredObjects( return marker_array; } -MarkerArray showExecutionInfo(const Debug & debug_data, const geometry_msgs::msg::Pose & ego_pose) +MarkerArray showExecutionInfo( + const InterfaceDebug & interface_debug_data, const Debug & scene_debug_data, + const geometry_msgs::msg::Pose & ego_pose) { auto default_text_marker = [&]() { return createDefaultMarker( @@ -177,11 +180,15 @@ MarkerArray showExecutionInfo(const Debug & debug_data, const geometry_msgs::msg auto safety_check_info_text = default_text_marker(); safety_check_info_text.pose = ego_pose; safety_check_info_text.pose.position.z += 4.0; + const auto lc_state = interface_debug_data.lc_state; + const auto & failing_reason = interface_debug_data.failing_reason; safety_check_info_text.text = fmt::format( - "{stuck} | {return_lane} | {abort}", fmt::arg("stuck", debug_data.is_stuck ? "is stuck" : ""), - fmt::arg("return_lane", debug_data.is_able_to_return_to_current_lane ? "" : "can't return"), - fmt::arg("abort", debug_data.is_abort ? "aborting" : "")); + "{stuck} | {return_lane} | {state} : {reason}", + fmt::arg("stuck", scene_debug_data.is_stuck ? "is stuck" : ""), + fmt::arg( + "return_lane", scene_debug_data.is_able_to_return_to_current_lane ? "" : "can't return"), + fmt::arg("state", magic_enum::enum_name(lc_state)), fmt::arg("reason", failing_reason)); marker_array.markers.push_back(safety_check_info_text); return marker_array; } @@ -227,7 +234,8 @@ MarkerArray ShowLaneChangeMetricsInfo( } MarkerArray createDebugMarkerArray( - const Debug & debug_data, const geometry_msgs::msg::Pose & ego_pose) + const InterfaceDebug & interface_debug_data, const Debug & scene_debug_data, + const geometry_msgs::msg::Pose & ego_pose) { using lanelet::visualization::laneletsAsTriangleMarkerArray; using marker_utils::showPolygon; @@ -236,31 +244,32 @@ MarkerArray createDebugMarkerArray( using marker_utils::lane_change_markers::showAllValidLaneChangePath; using marker_utils::lane_change_markers::showFilteredObjects; - const auto & debug_collision_check_object = debug_data.collision_check_objects; + const auto & debug_collision_check_object = scene_debug_data.collision_check_objects; const auto & debug_collision_check_object_after_approval = - debug_data.collision_check_objects_after_approval; - const auto & debug_valid_paths = debug_data.valid_paths; - const auto & debug_filtered_objects = debug_data.filtered_objects; + scene_debug_data.collision_check_objects_after_approval; + const auto & debug_valid_paths = scene_debug_data.valid_paths; + const auto & debug_filtered_objects = scene_debug_data.filtered_objects; MarkerArray debug_marker; const auto add = [&debug_marker](const MarkerArray & added) { autoware::universe_utils::appendMarkerArray(added, &debug_marker); }; - if (!debug_data.execution_area.points.empty()) { + if (!scene_debug_data.execution_area.points.empty()) { add(createPolygonMarkerArray( - debug_data.execution_area, "execution_area", 0, 0.16, 1.0, 0.69, 0.1)); + scene_debug_data.execution_area, "execution_area", 0, 0.16, 1.0, 0.69, 0.1)); } - add(showExecutionInfo(debug_data, ego_pose)); - add(ShowLaneChangeMetricsInfo(debug_data, ego_pose)); + add(showExecutionInfo(interface_debug_data, scene_debug_data, ego_pose)); + add(ShowLaneChangeMetricsInfo(scene_debug_data, ego_pose)); // lanes add(laneletsAsTriangleMarkerArray( - "current_lanes", debug_data.current_lanes, colors::light_yellow(0.2))); - add(laneletsAsTriangleMarkerArray("target_lanes", debug_data.target_lanes, colors::aqua(0.2))); + "current_lanes", scene_debug_data.current_lanes, colors::light_yellow(0.2))); add(laneletsAsTriangleMarkerArray( - "target_backward_lanes", debug_data.target_backward_lanes, colors::blue(0.2))); + "target_lanes", scene_debug_data.target_lanes, colors::aqua(0.2))); + add(laneletsAsTriangleMarkerArray( + "target_backward_lanes", scene_debug_data.target_backward_lanes, colors::blue(0.2))); add(showAllValidLaneChangePath(debug_valid_paths, "lane_change_valid_paths")); add(showFilteredObjects(debug_filtered_objects, "object_filtered")); From 485ccc660cfacc0e939e3019b5cc13c0f25fd9ae Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> Date: Fri, 10 Jan 2025 16:05:23 +0900 Subject: [PATCH 175/334] refactor(lane_departure_checker): improve LaneDepartureChecker initialization and parameter handling (#9791) * refactor(lane_departure_checker): improve LaneDepartureChecker initialization and parameter handling Signed-off-by: kyoichi-sugahara --------- Signed-off-by: Kyoichi Sugahara --- .../CMakeLists.txt | 1 + .../lane_departure_checker.hpp | 73 ++------- .../lane_departure_checker_node.hpp | 16 +- .../lane_departure_checker/parameters.hpp | 101 +++++++++++++ .../lane_departure_checker_node.cpp | 35 +---- .../parameters.cpp | 59 ++++++++ .../examples/plot_map_case1.cpp | 7 +- .../examples/plot_map_case2.cpp | 5 +- .../src/goal_planner_module.cpp | 4 +- .../src/start_planner_module.cpp | 6 +- .../test/test_geometric_pull_out.cpp | 138 ++++++------------ .../test/test_shift_pull_out.cpp | 8 +- 12 files changed, 230 insertions(+), 223 deletions(-) create mode 100644 control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/parameters.hpp create mode 100644 control/autoware_lane_departure_checker/src/lane_departure_checker_node/parameters.cpp diff --git a/control/autoware_lane_departure_checker/CMakeLists.txt b/control/autoware_lane_departure_checker/CMakeLists.txt index 199195fc88b08..19046a09922f0 100644 --- a/control/autoware_lane_departure_checker/CMakeLists.txt +++ b/control/autoware_lane_departure_checker/CMakeLists.txt @@ -14,6 +14,7 @@ ament_auto_add_library(autoware_lane_departure_checker SHARED src/lane_departure_checker_node/lane_departure_checker.cpp src/lane_departure_checker_node/lane_departure_checker_node.cpp src/lane_departure_checker_node/utils.cpp + src/lane_departure_checker_node/parameters.cpp ) rclcpp_components_register_node(${PROJECT_NAME} diff --git a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker.hpp b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker.hpp index 1ac984394a25e..101338551cbf3 100644 --- a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker.hpp +++ b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker.hpp @@ -15,15 +15,12 @@ #ifndef AUTOWARE__LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_HPP_ #define AUTOWARE__LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_HPP_ -#include -#include +#include "autoware/lane_departure_checker/parameters.hpp" + #include #include #include -#include -#include -#include #include #include #include @@ -48,81 +45,33 @@ namespace autoware::lane_departure_checker { -using autoware::universe_utils::LinearRing2d; -using autoware::universe_utils::PoseDeviation; using autoware::universe_utils::Segment2d; -using autoware_planning_msgs::msg::LaneletRoute; -using autoware_planning_msgs::msg::Trajectory; -using autoware_planning_msgs::msg::TrajectoryPoint; using tier4_planning_msgs::msg::PathWithLaneId; -using TrajectoryPoints = std::vector; typedef boost::geometry::index::rtree> SegmentRtree; -struct Param -{ - double footprint_margin_scale{0.0}; - double footprint_extra_margin{0.0}; - double resample_interval{0.0}; - double max_deceleration{0.0}; - double delay_time{0.0}; - double max_lateral_deviation{0.0}; - double max_longitudinal_deviation{0.0}; - double max_yaw_deviation_deg{0.0}; - double min_braking_distance{0.0}; - // nearest search to ego - double ego_nearest_dist_threshold{0.0}; - double ego_nearest_yaw_threshold{0.0}; -}; - -struct Input -{ - nav_msgs::msg::Odometry::ConstSharedPtr current_odom{}; - lanelet::LaneletMapPtr lanelet_map{}; - LaneletRoute::ConstSharedPtr route{}; - lanelet::ConstLanelets route_lanelets{}; - lanelet::ConstLanelets shoulder_lanelets{}; - Trajectory::ConstSharedPtr reference_trajectory{}; - Trajectory::ConstSharedPtr predicted_trajectory{}; - std::vector boundary_types_to_detect{}; -}; - -struct Output -{ - std::map processing_time_map{}; - bool will_leave_lane{}; - bool is_out_of_lane{}; - bool will_cross_boundary{}; - PoseDeviation trajectory_deviation{}; - lanelet::ConstLanelets candidate_lanelets{}; - TrajectoryPoints resampled_trajectory{}; - std::vector vehicle_footprints{}; - std::vector vehicle_passing_areas{}; -}; - class LaneDepartureChecker { public: - LaneDepartureChecker( + explicit LaneDepartureChecker( std::shared_ptr time_keeper = std::make_shared()) : time_keeper_(time_keeper) { } - Output update(const Input & input); - void setParam(const Param & param, const autoware::vehicle_info_utils::VehicleInfo vehicle_info) + LaneDepartureChecker( + const Param & param, const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, + std::shared_ptr time_keeper = + std::make_shared()) + : param_(param), + vehicle_info_ptr_(std::make_shared(vehicle_info)), + time_keeper_(time_keeper) { - param_ = param; - vehicle_info_ptr_ = std::make_shared(vehicle_info); } + Output update(const Input & input); void setParam(const Param & param) { param_ = param; } - void setVehicleInfo(const autoware::vehicle_info_utils::VehicleInfo vehicle_info) - { - vehicle_info_ptr_ = std::make_shared(vehicle_info); - } - bool checkPathWillLeaveLane( const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path) const; diff --git a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker_node.hpp b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker_node.hpp index 4d99b1a134b3a..7aaf4816708bd 100644 --- a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker_node.hpp +++ b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker_node.hpp @@ -16,6 +16,7 @@ #define AUTOWARE__LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_NODE_HPP_ #include "autoware/lane_departure_checker/lane_departure_checker.hpp" +#include "autoware/lane_departure_checker/parameters.hpp" #include "autoware/universe_utils/ros/polling_subscriber.hpp" #include @@ -47,21 +48,6 @@ namespace autoware::lane_departure_checker { using autoware_map_msgs::msg::LaneletMapBin; -struct NodeParam -{ - bool will_out_of_lane_checker; - bool out_of_lane_checker; - bool boundary_departure_checker; - - double update_rate; - bool visualize_lanelet; - bool include_right_lanes; - bool include_left_lanes; - bool include_opposite_lanes; - bool include_conflicting_lanes; - std::vector boundary_types_to_detect; -}; - class LaneDepartureCheckerNode : public rclcpp::Node { public: diff --git a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/parameters.hpp b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/parameters.hpp new file mode 100644 index 0000000000000..425b032af425f --- /dev/null +++ b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/parameters.hpp @@ -0,0 +1,101 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__LANE_DEPARTURE_CHECKER__PARAMETERS_HPP_ +#define AUTOWARE__LANE_DEPARTURE_CHECKER__PARAMETERS_HPP_ + +#include +#include +#include + +#include +#include +#include +#include + +#include + +#include +#include +#include + +namespace autoware::lane_departure_checker +{ +using autoware::universe_utils::PoseDeviation; +using autoware_planning_msgs::msg::LaneletRoute; +using autoware_planning_msgs::msg::Trajectory; +using autoware_planning_msgs::msg::TrajectoryPoint; +using TrajectoryPoints = std::vector; +using autoware::universe_utils::LinearRing2d; + +struct Param +{ + static Param init(rclcpp::Node & node); + double footprint_margin_scale{}; + double footprint_extra_margin{}; + double resample_interval{}; + double max_deceleration{}; + double delay_time{}; + double max_lateral_deviation{}; + double max_longitudinal_deviation{}; + double max_yaw_deviation_deg{}; + double min_braking_distance{}; + // nearest search to ego + double ego_nearest_dist_threshold{}; + double ego_nearest_yaw_threshold{}; +}; + +struct NodeParam +{ + static NodeParam init(rclcpp::Node & node); + bool will_out_of_lane_checker{}; + bool out_of_lane_checker{}; + bool boundary_departure_checker{}; + + double update_rate{}; + bool visualize_lanelet{}; + bool include_right_lanes{}; + bool include_left_lanes{}; + bool include_opposite_lanes{}; + bool include_conflicting_lanes{}; + std::vector boundary_types_to_detect{}; +}; + +struct Input +{ + nav_msgs::msg::Odometry::ConstSharedPtr current_odom{}; + lanelet::LaneletMapPtr lanelet_map{}; + LaneletRoute::ConstSharedPtr route{}; + lanelet::ConstLanelets route_lanelets{}; + lanelet::ConstLanelets shoulder_lanelets{}; + Trajectory::ConstSharedPtr reference_trajectory{}; + Trajectory::ConstSharedPtr predicted_trajectory{}; + std::vector boundary_types_to_detect{}; +}; + +struct Output +{ + std::map processing_time_map{}; + bool will_leave_lane{}; + bool is_out_of_lane{}; + bool will_cross_boundary{}; + PoseDeviation trajectory_deviation{}; + lanelet::ConstLanelets candidate_lanelets{}; + TrajectoryPoints resampled_trajectory{}; + std::vector vehicle_footprints{}; + std::vector vehicle_passing_areas{}; +}; +} // namespace autoware::lane_departure_checker + +#endif // AUTOWARE__LANE_DEPARTURE_CHECKER__PARAMETERS_HPP_ diff --git a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp index d9775415d3ed3..32384b7e6c7dd 100644 --- a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp +++ b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp @@ -126,48 +126,19 @@ LaneDepartureCheckerNode::LaneDepartureCheckerNode(const rclcpp::NodeOptions & o : Node("lane_departure_checker_node", options) { using std::placeholders::_1; - - // Enable feature - node_param_.will_out_of_lane_checker = declare_parameter("will_out_of_lane_checker"); - node_param_.out_of_lane_checker = declare_parameter("out_of_lane_checker"); - node_param_.boundary_departure_checker = declare_parameter("boundary_departure_checker"); - - // Node Parameter - node_param_.update_rate = declare_parameter("update_rate"); - node_param_.visualize_lanelet = declare_parameter("visualize_lanelet"); - node_param_.include_right_lanes = declare_parameter("include_right_lanes"); - node_param_.include_left_lanes = declare_parameter("include_left_lanes"); - node_param_.include_opposite_lanes = declare_parameter("include_opposite_lanes"); - node_param_.include_conflicting_lanes = declare_parameter("include_conflicting_lanes"); - - // Boundary_departure_checker - node_param_.boundary_types_to_detect = - declare_parameter>("boundary_types_to_detect"); + node_param_ = NodeParam::init(*this); + param_ = Param::init(*this); // Vehicle Info const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo(); vehicle_length_m_ = vehicle_info.vehicle_length_m; - // Core Parameter - param_.footprint_margin_scale = declare_parameter("footprint_margin_scale"); - param_.footprint_extra_margin = declare_parameter("footprint_extra_margin"); - param_.resample_interval = declare_parameter("resample_interval"); - param_.max_deceleration = declare_parameter("max_deceleration"); - param_.delay_time = declare_parameter("delay_time"); - param_.max_lateral_deviation = declare_parameter("max_lateral_deviation"); - param_.max_longitudinal_deviation = declare_parameter("max_longitudinal_deviation"); - param_.max_yaw_deviation_deg = declare_parameter("max_yaw_deviation_deg"); - param_.ego_nearest_dist_threshold = declare_parameter("ego_nearest_dist_threshold"); - param_.ego_nearest_yaw_threshold = declare_parameter("ego_nearest_yaw_threshold"); - param_.min_braking_distance = declare_parameter("min_braking_distance"); - // Parameter Callback set_param_res_ = add_on_set_parameters_callback(std::bind(&LaneDepartureCheckerNode::onParameter, this, _1)); // Core - lane_departure_checker_ = std::make_unique(); - lane_departure_checker_->setParam(param_, vehicle_info); + lane_departure_checker_ = std::make_unique(param_, vehicle_info); // Publisher processing_time_publisher_ = diff --git a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/parameters.cpp b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/parameters.cpp new file mode 100644 index 0000000000000..f3aa23275e35c --- /dev/null +++ b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/parameters.cpp @@ -0,0 +1,59 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/lane_departure_checker/parameters.hpp" + +#include +#include + +#include + +namespace autoware::lane_departure_checker +{ +using autoware::universe_utils::getOrDeclareParameter; + +Param Param::init(rclcpp::Node & node) +{ + Param p; + p.footprint_margin_scale = getOrDeclareParameter(node, "footprint_margin_scale"); + p.footprint_extra_margin = getOrDeclareParameter(node, "footprint_extra_margin"); + p.resample_interval = getOrDeclareParameter(node, "resample_interval"); + p.max_deceleration = getOrDeclareParameter(node, "max_deceleration"); + p.delay_time = getOrDeclareParameter(node, "delay_time"); + p.max_lateral_deviation = getOrDeclareParameter(node, "max_lateral_deviation"); + p.max_longitudinal_deviation = getOrDeclareParameter(node, "max_longitudinal_deviation"); + p.max_yaw_deviation_deg = getOrDeclareParameter(node, "max_yaw_deviation_deg"); + p.min_braking_distance = getOrDeclareParameter(node, "min_braking_distance"); + p.ego_nearest_dist_threshold = getOrDeclareParameter(node, "ego_nearest_dist_threshold"); + p.ego_nearest_yaw_threshold = getOrDeclareParameter(node, "ego_nearest_yaw_threshold"); + return p; +} + +NodeParam NodeParam::init(rclcpp::Node & node) +{ + NodeParam p; + p.will_out_of_lane_checker = getOrDeclareParameter(node, "will_out_of_lane_checker"); + p.out_of_lane_checker = getOrDeclareParameter(node, "out_of_lane_checker"); + p.boundary_departure_checker = getOrDeclareParameter(node, "boundary_departure_checker"); + p.update_rate = getOrDeclareParameter(node, "update_rate"); + p.visualize_lanelet = getOrDeclareParameter(node, "visualize_lanelet"); + p.include_right_lanes = getOrDeclareParameter(node, "include_right_lanes"); + p.include_left_lanes = getOrDeclareParameter(node, "include_left_lanes"); + p.include_opposite_lanes = getOrDeclareParameter(node, "include_opposite_lanes"); + p.include_conflicting_lanes = getOrDeclareParameter(node, "include_conflicting_lanes"); + p.boundary_types_to_detect = + getOrDeclareParameter>(node, "boundary_types_to_detect"); + return p; +} +} // namespace autoware::lane_departure_checker diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case1.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case1.cpp index 46d3b97b71e58..6172fb75978cd 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case1.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case1.cpp @@ -564,13 +564,12 @@ int main(int argc, char ** argv) node.get(), "goal_planner."); goal_planner_parameter.bus_stop_area.use_bus_stop_area = true; goal_planner_parameter.lane_departure_check_expansion_margin = 0.2; - const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(*node).getVehicleInfo(); - autoware::lane_departure_checker::LaneDepartureChecker lane_departure_checker{}; - lane_departure_checker.setVehicleInfo(vehicle_info); autoware::lane_departure_checker::Param lane_departure_checker_params; lane_departure_checker_params.footprint_extra_margin = goal_planner_parameter.lane_departure_check_expansion_margin; - lane_departure_checker.setParam(lane_departure_checker_params); + autoware::lane_departure_checker::LaneDepartureChecker lane_departure_checker( + lane_departure_checker_params, vehicle_info); + const auto footprint = vehicle_info.createFootprint(); autoware::behavior_path_planner::GoalSearcher goal_searcher(goal_planner_parameter, footprint); auto goal_candidates = goal_searcher.search(planner_data); diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case2.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case2.cpp index 3518b5041be53..f7fefa8ba9dc0 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case2.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map_case2.cpp @@ -573,12 +573,11 @@ int main(int argc, char ** argv) autoware::behavior_path_planner::GoalPlannerModuleManager::initGoalPlannerParameters( node.get(), "goal_planner."); const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(*node).getVehicleInfo(); - autoware::lane_departure_checker::LaneDepartureChecker lane_departure_checker{}; - lane_departure_checker.setVehicleInfo(vehicle_info); autoware::lane_departure_checker::Param lane_departure_checker_params; lane_departure_checker_params.footprint_extra_margin = goal_planner_parameter.lane_departure_check_expansion_margin; - lane_departure_checker.setParam(lane_departure_checker_params); + autoware::lane_departure_checker::LaneDepartureChecker lane_departure_checker( + lane_departure_checker_params, vehicle_info); const auto footprint = vehicle_info.createFootprint(); autoware::behavior_path_planner::GoalSearcher goal_searcher(goal_planner_parameter, footprint); auto goal_candidates = goal_searcher.search(planner_data); diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 8272ddde0189e..96aeb5f5e4da8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -290,12 +290,10 @@ LaneParkingPlanner::LaneParkingPlanner( logger_(logger) { const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo(); - LaneDepartureChecker lane_departure_checker{}; - lane_departure_checker.setVehicleInfo(vehicle_info); lane_departure_checker::Param lane_departure_checker_params; lane_departure_checker_params.footprint_extra_margin = parameters.lane_departure_check_expansion_margin; - lane_departure_checker.setParam(lane_departure_checker_params); + LaneDepartureChecker lane_departure_checker(lane_departure_checker_params, vehicle_info); for (const std::string & planner_type : parameters.efficient_path_order) { if (planner_type == "SHIFT" && parameters.enable_shift_parking) { diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp index f45924b9542dc..83c1d55c7d022 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp @@ -68,13 +68,11 @@ StartPlannerModule::StartPlannerModule( vehicle_info_{autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()}, is_freespace_planner_cb_running_{false} { - lane_departure_checker_ = std::make_shared(time_keeper_); - lane_departure_checker_->setVehicleInfo(vehicle_info_); autoware::lane_departure_checker::Param lane_departure_checker_params{}; lane_departure_checker_params.footprint_extra_margin = parameters->lane_departure_check_expansion_margin; - - lane_departure_checker_->setParam(lane_departure_checker_params); + lane_departure_checker_ = std::make_shared( + lane_departure_checker_params, vehicle_info_, time_keeper_); // set enabled planner if (parameters_->enable_shift_pull_out) { diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_geometric_pull_out.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_geometric_pull_out.cpp index dd8bb02c97dea..726c9ccc4c5d7 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_geometric_pull_out.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_geometric_pull_out.cpp @@ -24,9 +24,7 @@ #include -#include #include -#include #include #include @@ -44,7 +42,7 @@ namespace autoware::behavior_path_planner class TestGeometricPullOut : public ::testing::Test { public: - std::optional plan( + std::optional call_plan( const Pose & start_pose, const Pose & goal_pose, PlannerDebugData & planner_debug_data) { return geometric_pull_out_->plan(start_pose, goal_pose, planner_debug_data); @@ -54,27 +52,51 @@ class TestGeometricPullOut : public ::testing::Test void SetUp() override { rclcpp::init(0, nullptr); - node_ = rclcpp::Node::make_shared("geometric_pull_out", get_node_options()); + node_ = rclcpp::Node::make_shared("geometric_pull_out", make_node_options()); - load_parameters(); - initialize_vehicle_info(); initialize_lane_departure_checker(); - initialize_routeHandler(); initialize_geometric_pull_out_planner(); - initialize_planner_data(); } void TearDown() override { rclcpp::shutdown(); } + + PlannerData make_planner_data( + const Pose & start_pose, const int route_start_lane_id, const int route_goal_lane_id) + { + PlannerData planner_data; + planner_data.init_parameters(*node_); + + // Load a sample lanelet map and create a route handler + const auto shoulder_map_path = autoware::test_utils::get_absolute_path_to_lanelet_map( + "autoware_test_utils", "road_shoulder/lanelet2_map.osm"); + const auto map_bin_msg = autoware::test_utils::make_map_bin_msg(shoulder_map_path, 0.5); + auto route_handler = std::make_shared(map_bin_msg); + + // Set up current odometry at start pose + auto odometry = std::make_shared(); + odometry->pose.pose = start_pose; + odometry->header.frame_id = "map"; + planner_data.self_odometry = odometry; + + // Setup route + const auto route = makeBehaviorRouteFromLaneId( + route_start_lane_id, route_goal_lane_id, "autoware_test_utils", + "road_shoulder/lanelet2_map.osm"); + route_handler->setRoute(route); + + // Update planner data with the route handler + planner_data.route_handler = route_handler; + + return planner_data; + } + // Member variables std::shared_ptr node_; - std::shared_ptr route_handler_; - autoware::vehicle_info_utils::VehicleInfo vehicle_info_; std::shared_ptr geometric_pull_out_; std::shared_ptr lane_departure_checker_; - PlannerData planner_data_; private: - rclcpp::NodeOptions get_node_options() const + rclcpp::NodeOptions make_node_options() const { // Load common configuration files auto node_options = rclcpp::NodeOptions{}; @@ -102,84 +124,22 @@ class TestGeometricPullOut : public ::testing::Test return node_options; } - void load_parameters() - { - const auto dp_double = [&](const std::string & s) { - return node_->declare_parameter(s); - }; - const auto dp_bool = [&](const std::string & s) { return node_->declare_parameter(s); }; - // Load parameters required for planning - const std::string ns = "start_planner."; - lane_departure_check_expansion_margin_ = - dp_double(ns + "lane_departure_check_expansion_margin"); - pull_out_max_steer_angle_ = dp_double(ns + "pull_out_max_steer_angle"); - pull_out_arc_path_interval_ = dp_double(ns + "arc_path_interval"); - center_line_path_interval_ = dp_double(ns + "center_line_path_interval"); - th_moving_object_velocity_ = dp_double(ns + "th_moving_object_velocity"); - divide_pull_out_path_ = dp_bool(ns + "divide_pull_out_path"); - backward_path_length_ = dp_double("backward_path_length"); - forward_path_length_ = dp_double("forward_path_length"); - } - - void initialize_vehicle_info() - { - vehicle_info_ = autoware::vehicle_info_utils::VehicleInfoUtils(*node_).getVehicleInfo(); - } - void initialize_lane_departure_checker() { - lane_departure_checker_ = std::make_shared(); - lane_departure_checker_->setVehicleInfo(vehicle_info_); - autoware::lane_departure_checker::Param lane_departure_checker_params{}; - lane_departure_checker_params.footprint_extra_margin = lane_departure_check_expansion_margin_; - lane_departure_checker_->setParam(lane_departure_checker_params); - } - - void initialize_routeHandler() - { - // Load a sample lanelet map and create a route handler - const auto shoulder_map_path = autoware::test_utils::get_absolute_path_to_lanelet_map( - "autoware_test_utils", "road_shoulder/lanelet2_map.osm"); - const auto map_bin_msg = autoware::test_utils::make_map_bin_msg(shoulder_map_path, 0.5); - - route_handler_ = std::make_shared(map_bin_msg); + const auto vehicle_info = + autoware::vehicle_info_utils::VehicleInfoUtils(*node_).getVehicleInfo(); + lane_departure_checker_ = + std::make_shared(lane_departure_checker_params, vehicle_info); } void initialize_geometric_pull_out_planner() { - auto parameters = std::make_shared(); - parameters->parallel_parking_parameters.pull_out_max_steer_angle = pull_out_max_steer_angle_; - parameters->parallel_parking_parameters.pull_out_arc_path_interval = - pull_out_arc_path_interval_; - parameters->parallel_parking_parameters.center_line_path_interval = center_line_path_interval_; - parameters->th_moving_object_velocity = th_moving_object_velocity_; - parameters->divide_pull_out_path = divide_pull_out_path_; + auto parameters = StartPlannerParameters::init(*node_); geometric_pull_out_ = - std::make_shared(*node_, *parameters, lane_departure_checker_); - } - - void initialize_planner_data() - { - planner_data_.parameters.backward_path_length = backward_path_length_; - planner_data_.parameters.forward_path_length = forward_path_length_; - planner_data_.parameters.wheel_base = vehicle_info_.wheel_base_m; - planner_data_.parameters.wheel_tread = vehicle_info_.wheel_tread_m; - planner_data_.parameters.front_overhang = vehicle_info_.front_overhang_m; - planner_data_.parameters.left_over_hang = vehicle_info_.left_overhang_m; - planner_data_.parameters.right_over_hang = vehicle_info_.right_overhang_m; + std::make_shared(*node_, parameters, lane_departure_checker_); } - - // Parameter variables - double lane_departure_check_expansion_margin_{0.0}; - double pull_out_max_steer_angle_{0.0}; - double pull_out_arc_path_interval_{0.0}; - double center_line_path_interval_{0.0}; - double th_moving_object_velocity_{0.0}; - double backward_path_length_{0.0}; - double forward_path_length_{0.0}; - bool divide_pull_out_path_{false}; }; TEST_F(TestGeometricPullOut, GenerateValidGeometricPullOutPath) @@ -197,25 +157,13 @@ TEST_F(TestGeometricPullOut, GenerateValidGeometricPullOutPath) .orientation( geometry_msgs::build().x(0.0).y(0.0).z(0.705897).w( 0.708314)); + const auto planner_data = make_planner_data(start_pose, 4619, 4635); - // Set up current odometry at start pose - auto odometry = std::make_shared(); - odometry->pose.pose = start_pose; - odometry->header.frame_id = "map"; - planner_data_.self_odometry = odometry; - - // Setup route - const auto route = makeBehaviorRouteFromLaneId( - 4619, 4635, "autoware_test_utils", "road_shoulder/lanelet2_map.osm"); - route_handler_->setRoute(route); - - // Update planner data with the route handler - planner_data_.route_handler = route_handler_; - geometric_pull_out_->setPlannerData(std::make_shared(planner_data_)); + geometric_pull_out_->setPlannerData(std::make_shared(planner_data)); // Plan the pull out path PlannerDebugData debug_data; - auto result = plan(start_pose, goal_pose, debug_data); + auto result = call_plan(start_pose, goal_pose, debug_data); // Assert that a valid geometric geometric pull out path is generated ASSERT_TRUE(result.has_value()) << "Geometric pull out path generation failed."; diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_shift_pull_out.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_shift_pull_out.cpp index 474da055b4de7..05a9201dad41d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_shift_pull_out.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_shift_pull_out.cpp @@ -126,13 +126,11 @@ class TestShiftPullOut : public ::testing::Test void initialize_lane_departure_checker() { + autoware::lane_departure_checker::Param lane_departure_checker_params{}; const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(*node_).getVehicleInfo(); - lane_departure_checker_ = std::make_shared(); - lane_departure_checker_->setVehicleInfo(vehicle_info); - - autoware::lane_departure_checker::Param lane_departure_checker_params{}; - lane_departure_checker_->setParam(lane_departure_checker_params); + lane_departure_checker_ = + std::make_shared(lane_departure_checker_params, vehicle_info); } void initialize_shift_pull_out_planner() From 23a77640da41966fc9fc28355905dc4db6df6fe0 Mon Sep 17 00:00:00 2001 From: Atto Armoo <168620037+AA-T4@users.noreply.github.com> Date: Fri, 10 Jan 2025 16:53:18 +0900 Subject: [PATCH 176/334] fix(planning): text revisions (#9886) * fix(planning): text revisions Signed-off-by: Atto Armoo <168620037+AA-T4@users.noreply.github.com> * style(pre-commit): autofix --------- Signed-off-by: Atto Armoo <168620037+AA-T4@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../autoware_behavior_path_planner/README.md | 126 +++++++++--------- 1 file changed, 62 insertions(+), 64 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/README.md b/planning/behavior_path_planner/autoware_behavior_path_planner/README.md index ab8d02dc83f92..81cb945802595 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/README.md @@ -4,11 +4,11 @@ The Behavior Path Planner's main objective is to significantly enhance the safet The module begins by thoroughly analyzing the ego vehicle's current situation, including its position, speed, and surrounding environment. This analysis leads to essential driving decisions about lane changes or stopping and subsequently generates a path that is both safe and efficient. It considers road geometry, traffic rules, and dynamic conditions while also incorporating obstacle avoidance to respond to static and dynamic obstacles such as other vehicles, pedestrians, or unexpected roadblocks, ensuring safe navigation. -Moreover, the planner actively interacts with other traffic participants, predicting their actions and accordingly adjusting the vehicle's path. This ensures not only the safety of the autonomous vehicle but also contributes to smooth traffic flow. Its adherence to traffic laws, including speed limits and traffic signals, further guarantees lawful and predictable driving behavior. The planner is also designed to minimize sudden or abrupt maneuvers, aiming for a comfortable and natural driving experience. +Moreover, the planner responds to the behavior of other traffic participants, predicting their actions and accordingly adjusting the vehicle's path. This ensures not only the safety of the autonomous vehicle but also contributes to smooth traffic flow. Its adherence to traffic laws, including speed limits and compliance with traffic signals, further guarantees lawful and predictable driving behavior. The planner is also designed to minimize sudden or abrupt maneuvers, aiming for a comfortable and natural driving experience. !!! note - The [Planning Component Design](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/planning/) Document outlines the foundational philosophy guiding the design and future development of the Behavior Path Planner module. We strongly encourage readers to consult this document to understand the rationale behind its current configuration and the direction of its ongoing development. + The [Planning Component Design](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/planning/) documentation outlines the foundational philosophy guiding the design and future development of the Behavior Path Planner module. We strongly encourage readers to consult this document to understand the rationale behind its current configuration and the direction of its ongoing development. ## Purpose / Use Cases @@ -22,23 +22,23 @@ Essentially, the module has three primary responsibilities: ### Supported Scene Modules -Behavior Path Planner has following scene modules +Behavior Path Planner has the following scene modules -| Name | Description | Details | -| :------------------------- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :---------------------------------------------------------------------------- | -| Lane Following | this module generates reference path from lanelet centerline. | LINK | -| Static Obstacle Avoidance | this module generates avoidance path when there is objects that should be avoid. | [LINK](../autoware_behavior_path_static_obstacle_avoidance_module/README.md) | -| Dynamic Obstacle Avoidance | WIP | [LINK](../autoware_behavior_path_dynamic_obstacle_avoidance_module/README.md) | -| Avoidance By Lane Change | this module generates lane change path when there is objects that should be avoid. | [LINK](../behavior_path_avoidance_by_lane_change_module/README.md) | -| Lane Change | this module is performed when it is necessary and a collision check with other vehicles is cleared. | [LINK](../autoware_behavior_path_lane_change_module/README.md) | -| External Lane Change | WIP | LINK | -| Goal Planner | this module is performed when ego-vehicle is in the road lane and goal is in the shoulder lane. ego-vehicle will stop at the goal. | [LINK](../autoware_behavior_path_goal_planner_module/README.md) | -| Start Planner | this module is performed when ego-vehicle is stationary and footprint of ego-vehicle is included in shoulder lane. This module ends when ego-vehicle merges into the road. | [LINK](../autoware_behavior_path_start_planner_module/README.md) | -| Side Shift | (for remote control) shift the path to left or right according to an external instruction. | [LINK](../autoware_behavior_path_side_shift_module/README.md) | +| Name | Description | Details | +| :------------------------- | :--------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :---------------------------------------------------------------------------- | +| Lane Following | This module generates a reference path from lanelet centerline. | LINK | +| Static Obstacle Avoidance | This module generates an avoidance path when there are objects that should be avoided. | [LINK](../autoware_behavior_path_static_obstacle_avoidance_module/README.md) | +| Dynamic Obstacle Avoidance | WIP | [LINK](../autoware_behavior_path_dynamic_obstacle_avoidance_module/README.md) | +| Avoidance By Lane Change | This module generates a lane change path when there are objects that should be avoided. | [LINK](../behavior_path_avoidance_by_lane_change_module/README.md) | +| Lane Change | This module is performed when it is necessary and a collision check with other vehicles is cleared. | [LINK](../autoware_behavior_path_lane_change_module/README.md) | +| External Lane Change | WIP | LINK | +| Goal Planner | This module is performed when the ego vehicle is in a driving lane and the goal is in the shoulder lane. The ego vehicle will stop at the goal. | [LINK](../autoware_behavior_path_goal_planner_module/README.md) | +| Start Planner | This module is performed when the ego vehicle is stationary and the footprint of the ego vehicle is included in the shoulder lane. This module ends when the ego vehicle merges into the road. | [LINK](../autoware_behavior_path_start_planner_module/README.md) | +| Side Shift | This module shifts the path to the left or right based on external instructions, intended for remote control applications. | [LINK](../autoware_behavior_path_side_shift_module/README.md) | !!! Note - click on the following images to view the video of their execution + Click on the following images to view videos of their execution

@@ -59,13 +59,13 @@ Behavior Path Planner has following scene modules Users can refer to [Planning component design](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/planning/#supported-functions) for some additional behavior. -#### How to add or implement new module? +#### How to add or implement new module -All scene modules are implemented by inheriting base class `scene_module_interface.hpp`. +All scene modules are implemented by inheriting the base class `scene_module_interface.hpp`. !!! Warning - The remainder of this subsection is work in progress (WIP). + The remainder of this subsection is a work in progress (WIP). ### Planner Manager @@ -77,65 +77,65 @@ The Planner Manager's responsibilities include: !!! note - To check the scene module's transition, i.e.: registered, approved and candidate modules, set `verbose: true` in the [behavior path planner configuration file](https://github.com/autowarefoundation/autoware_launch/blob/0cd5d891a36ac34a32a417205905c109f2bafe7b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml#L3). + To check the scene module's transition – i.e., registered, approved and candidate modules – set `verbose: true` in the [Behavior Path Planner configuration file](https://github.com/autowarefoundation/autoware_launch/blob/0cd5d891a36ac34a32a417205905c109f2bafe7b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/behavior_path_planner.param.yaml#L3). ![Scene module's transition table](./image/checking_module_transition.png) !!! note - For more in-depth information, refer to [Manager design](./docs/behavior_path_planner_manager_design.md) document. + For more in-depth information, refer to the [Manager design](./docs/behavior_path_planner_manager_design.md) document. ## Inputs / Outputs / API ### Input -| Name | Required? | Type | Description | -| :---------------------------- | :-------: | :------------------------------------------------------ | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| ~/input/odometry | ○ | `nav_msgs::msg::Odometry` | for ego velocity. | -| ~/input/accel | ○ | `geometry_msgs::msg::AccelWithCovarianceStamped` | for ego acceleration. | -| ~/input/objects | ○ | `autoware_perception_msgs::msg::PredictedObjects` | dynamic objects from perception module. | -| ~/input/occupancy_grid_map | ○ | `nav_msgs::msg::OccupancyGrid` | occupancy grid map from perception module. This is used for only Goal Planner module. | -| ~/input/traffic_signals | ○ | `autoware_perception_msgs::msg::TrafficLightGroupArray` | traffic signals information from the perception module | -| ~/input/vector_map | ○ | `autoware_map_msgs::msg::LaneletMapBin` | vector map information. | -| ~/input/route | ○ | `autoware_planning_msgs::msg::LaneletRoute` | current route from start to goal. | -| ~/input/scenario | ○ | `tier4_planning_msgs::msg::Scenario` | Launches behavior path planner if current scenario == `Scenario:LaneDriving`. | -| ~/input/lateral_offset | △ | `tier4_planning_msgs::msg::LateralOffset` | lateral offset to trigger side shift | -| ~/system/operation_mode/state | ○ | `autoware_adapi_v1_msgs::msg::OperationModeState` | Allows planning module to know if vehicle is in autonomous mode or can be controlled[ref](https://github.com/autowarefoundation/autoware.universe/blob/main/system/autoware_default_adapi/document/operation-mode.md) | - -- ○ Mandatory: Planning Module would not work if anyone of this is not present. -- △ Optional: Some module would not work, but Planning Module can still be operated. +| Name | Required? | Type | Description | +| :---------------------------- | :-------: | :------------------------------------------------------ | :----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| ~/input/odometry | ○ | `nav_msgs::msg::Odometry` | For ego velocity | +| ~/input/accel | ○ | `geometry_msgs::msg::AccelWithCovarianceStamped` | For ego acceleration | +| ~/input/objects | ○ | `autoware_perception_msgs::msg::PredictedObjects` | Dynamic objects from the perception module | +| ~/input/occupancy_grid_map | ○ | `nav_msgs::msg::OccupancyGrid` | Occupancy grid map from the perception module. This is used for only the Goal Planner module | +| ~/input/traffic_signals | ○ | `autoware_perception_msgs::msg::TrafficLightGroupArray` | Traffic signal information from the perception module | +| ~/input/vector_map | ○ | `autoware_map_msgs::msg::LaneletMapBin` | Vector map information | +| ~/input/route | ○ | `autoware_planning_msgs::msg::LaneletRoute` | Current route from start to goal | +| ~/input/scenario | ○ | `tier4_planning_msgs::msg::Scenario` | Launches Behavior Path Planner if current scenario == `Scenario:LaneDriving` | +| ~/input/lateral_offset | △ | `tier4_planning_msgs::msg::LateralOffset` | Lateral offset to trigger side shift | +| ~/system/operation_mode/state | ○ | `autoware_adapi_v1_msgs::msg::OperationModeState` | Allows the planning module to know if vehicle is in autonomous mode or if it can be controlled[ref](https://github.com/autowarefoundation/autoware.universe/blob/main/system/autoware_default_adapi/document/operation-mode.md) | + +- ○ Mandatory: The planning module would not work if anyone of these were not present. +- △ Optional: Some modules would not work, but the planning module can still be operated. ### Output -| Name | Type | Description | QoS Durability | -| :---------------------------- | :-------------------------------------------------- | :--------------------------------------------------------------------------------------------- | ----------------- | -| ~/output/path | `tier4_planning_msgs::msg::PathWithLaneId` | the path generated by modules. | `volatile` | -| ~/output/turn_indicators_cmd | `autoware_vehicle_msgs::msg::TurnIndicatorsCommand` | turn indicators command. | `volatile` | -| ~/output/hazard_lights_cmd | `autoware_vehicle_msgs::msg::HazardLightsCommand` | hazard lights command. | `volatile` | -| ~/output/modified_goal | `autoware_planning_msgs::msg::PoseWithUuidStamped` | output modified goal commands. | `transient_local` | -| ~/output/reroute_availability | `tier4_planning_msgs::msg::RerouteAvailability` | the path the module is about to take. to be executed as soon as external approval is obtained. | `volatile` | +| Name | Type | Description | QoS Durability | +| :---------------------------- | :-------------------------------------------------- | :-------------------------------------------------------------------------------------------- | ----------------- | +| ~/output/path | `tier4_planning_msgs::msg::PathWithLaneId` | The path generated by modules | `volatile` | +| ~/output/turn_indicators_cmd | `autoware_vehicle_msgs::msg::TurnIndicatorsCommand` | Turn indicators command | `volatile` | +| ~/output/hazard_lights_cmd | `autoware_vehicle_msgs::msg::HazardLightsCommand` | Hazard lights command | `volatile` | +| ~/output/modified_goal | `autoware_planning_msgs::msg::PoseWithUuidStamped` | Output modified goal commands | `transient_local` | +| ~/output/reroute_availability | `tier4_planning_msgs::msg::RerouteAvailability` | The path the module is about to take. To be executed as soon as external approval is obtained | `volatile` | ### Debug -| Name | Type | Description | QoS Durability | -| :-------------------------------------- | :-------------------------------------------------- | :---------------------------------------------------------------------------------------- | -------------- | -| ~/debug/avoidance_debug_message_array | `tier4_planning_msgs::msg::AvoidanceDebugMsgArray` | debug message for avoidance. notify users reasons for avoidance path cannot be generated. | `volatile` | -| ~/debug/lane_change_debug_message_array | `tier4_planning_msgs::msg::LaneChangeDebugMsgArray` | debug message for lane change. notify users unsafe reason during lane changing process | `volatile` | -| ~/debug/maximum_drivable_area | `visualization_msgs::msg::MarkerArray` | shows maximum static drivable area. | `volatile` | -| ~/debug/turn_signal_info | `visualization_msgs::msg::MarkerArray` | TBA | `volatile` | -| ~/debug/bound | `visualization_msgs::msg::MarkerArray` | debug for static drivable area | `volatile` | -| ~/planning/path_candidate/\* | `autoware_planning_msgs::msg::Path` | the path before approval. | `volatile` | -| ~/planning/path_reference/\* | `autoware_planning_msgs::msg::Path` | reference path generated by each modules. | `volatile` | +| Name | Type | Description | QoS Durability | +| :-------------------------------------- | :-------------------------------------------------- | :---------------------------------------------------------------------------------------------- | -------------- | +| ~/debug/avoidance_debug_message_array | `tier4_planning_msgs::msg::AvoidanceDebugMsgArray` | Debug message for avoidance. Notifies users of reasons avoidance path cannot be generated | `volatile` | +| ~/debug/lane_change_debug_message_array | `tier4_planning_msgs::msg::LaneChangeDebugMsgArray` | Debug message for lane change. Notifies users of unsafe conditions during lane-changing process | `volatile` | +| ~/debug/maximum_drivable_area | `visualization_msgs::msg::MarkerArray` | Shows maximum static drivable area | `volatile` | +| ~/debug/turn_signal_info | `visualization_msgs::msg::MarkerArray` | TBA | `volatile` | +| ~/debug/bound | `visualization_msgs::msg::MarkerArray` | Debug for static drivable area | `volatile` | +| ~/planning/path_candidate/\* | `autoware_planning_msgs::msg::Path` | The path before approval | `volatile` | +| ~/planning/path_reference/\* | `autoware_planning_msgs::msg::Path` | Reference path generated by each module | `volatile` | !!! note - For specific information of which topics are being subscribed and published, refer to [behavior_path_planner.xml](https://github.com/autowarefoundation/autoware.universe/blob/9000f430c937764c14e43109539302f1f878ed70/planning/behavior_path_planner/launch/behavior_path_planner.launch.xml#L36-L49). + For specific information about which topics are being subscribed to and published, refer to [behavior_path_planner.xml](https://github.com/autowarefoundation/autoware.universe/blob/9000f430c937764c14e43109539302f1f878ed70/planning/behavior_path_planner/launch/behavior_path_planner.launch.xml#L36-L49). -## How to enable or disable the modules +## How to Enable or Disable Modules -Enabling and disabling the modules in the behavior path planner is primarily managed through two key files: `default_preset.yaml` and `behavior_path_planner.launch.xml`. +Enabling and disabling the modules in the Behavior Path Planner is primarily managed through two key files: `default_preset.yaml` and `behavior_path_planner.launch.xml`. -The `default_preset.yaml` file acts as a configuration file for enabling or disabling specific modules within the planner. It contains a series of arguments which represent the behavior path planner's modules or features. For example: +The `default_preset.yaml` file acts as a configuration file for enabling or disabling specific modules within the planner. It contains a series of arguments which represent the Behavior Path Planner's modules or features. For example: - `launch_static_obstacle_avoidance_module`: Set to `true` to enable the avoidance module, or `false` to disable it. @@ -143,14 +143,12 @@ The `default_preset.yaml` file acts as a configuration file for enabling or disa Click [here](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/planning/preset/default_preset.yaml) to view the `default_preset.yaml`. -The `behavior_path_planner.launch.xml` file references the settings defined in `default_preset.yaml` to apply the configurations when the behavior path planner's node is running. For instance, the parameter `static_obstacle_avoidance.enable_module` in +The `behavior_path_planner.launch.xml` file references the settings defined in `default_preset.yaml` to apply the configurations when the Behavior Path Planner's node is running. For instance, the parameter `static_obstacle_avoidance.enable_module` in the following segment corresponds to launch_static_obstacle_avoidance_module from `default_preset.yaml`: ```xml ``` -corresponds to launch_static_obstacle_avoidance_module from `default_preset.yaml`. - Therefore, to enable or disable a module, simply set the corresponding module in `default_preset.yaml` to `true` or `false`. These changes will be applied upon the next launch of Autoware. ## Generating Path @@ -163,13 +161,13 @@ The `ShiftLine` struct (as seen [here](https://github.com/autowarefoundation/aut Furthermore, the design and its implementation incorporate various equations and mathematical models to calculate essential parameters for the path shift. These include the total distance of the lateral shift, the maximum allowable lateral acceleration and jerk, and the total time required for the shift. Practical considerations are also noted, such as simplifying assumptions in the absence of a specific time interval for most lane change and avoidance cases. -The shifted path generation logic enables the behavior path planner to dynamically generate safe and efficient paths, precisely controlling the vehicle’s lateral movements to ensure the smooth execution of lane changes and avoidance maneuvers. This careful planning and execution adhere to the vehicle's dynamic capabilities and safety constraints, maximizing efficiency and safety in autonomous vehicle navigation. +The shifted path generation logic enables the Behavior Path Planner to dynamically generate safe and efficient paths, precisely controlling the vehicle’s lateral movements to ensure the smooth execution of lane changes and avoidance maneuvers. This careful planning and execution adhere to the vehicle's dynamic capabilities and safety constraints, maximizing efficiency and safety in autonomous vehicle navigation. !!! note If you're a math lover, refer to [Path Generation Design](../autoware_behavior_path_planner_common/docs/behavior_path_planner_path_generation_design.md) for the nitty-gritty. -## Collision Assessment / Safety check +## Collision Assessment / Safety Check The purpose of the collision assessment function in the Behavior Path Planner is to evaluate the potential for collisions with target objects across all modules. It is utilized in two scenarios: @@ -207,7 +205,7 @@ Static drivable area expansion operates under assumptions about the correct arra !!! note - Further details can is provided in [Drivable Area Design](../autoware_behavior_path_planner_common/docs/behavior_path_planner_drivable_area_design.md). + Further details can be found in [Drivable Area Design](../autoware_behavior_path_planner_common/docs/behavior_path_planner_drivable_area_design.md). ### Dynamic Drivable Area Logic @@ -233,7 +231,7 @@ The `TurnIndicatorsCommand` message structure has a command field that can take !!! warning - Rerouting is a feature that was still under progress. Further information will be included on a later date. + The rerouting feature is under development. Further information will be included at a later date. ## Parameters and Configuration @@ -278,5 +276,5 @@ preset ## Limitations & Future Work -1. Goal Planner module cannot be simultaneously executed together with other modules. -2. Module is not designed as plugin. Integrating custom module is not straightforward and user have to modify some part of the behavior path planner main code. +1. The Goal Planner module cannot be simultaneously executed together with other modules. +2. The module is not designed as a plugin. Integrating a custom module is not straightforward. Users have to modify part of the Behavior Path Planner's main code. From 00892a10702536fbcd071f9decc8953addddfd24 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 10 Jan 2025 16:55:14 +0900 Subject: [PATCH 177/334] feat(goal_planner): cut stop path to goal (#9829) Signed-off-by: kosuke55 --- .../src/goal_planner_module.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 96aeb5f5e4da8..87a6e28ff0007 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -1671,7 +1671,10 @@ PathWithLaneId GoalPlannerModule::generateStopPath( const auto reference_path = std::invoke([&]() -> PathWithLaneId { const auto s_current = lanelet::utils::getArcCoordinates(current_lanes, current_pose).length; const double s_start = std::max(0.0, s_current - common_parameters.backward_path_length); - const double s_end = s_current + common_parameters.forward_path_length; + const double s_end = std::clamp( + lanelet::utils::getArcCoordinates(current_lanes, route_handler->getGoalPose()).length, + s_current + std::numeric_limits::epsilon(), + s_current + common_parameters.forward_path_length); return route_handler->getCenterLinePath(current_lanes, s_start, s_end, true); }); From 594c099daf4413d6807f5dbe2f0d5d88a914afe9 Mon Sep 17 00:00:00 2001 From: Kazunori-Nakajima <169115284+Kazunori-Nakajima@users.noreply.github.com> Date: Fri, 10 Jan 2025 16:55:44 +0900 Subject: [PATCH 178/334] feat(goal_planner): update lateral_deviation_thresh from `0.3` to `0.1` (#9850) * fix(goal_planner): Update lateral_deviation_thresh from 0.3 to 0.1 Signed-off-by: Kasunori-Nakajima * unified hasDeviatedFrom{Last|Current}PreviousModulePath Signed-off-by: Kasunori-Nakajima * style(pre-commit): autofix * hasDeviatedFromPath argument modification Signed-off-by: Kasunori-Nakajima * style(pre-commit): autofix --------- Signed-off-by: Kasunori-Nakajima Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../goal_planner_module.hpp | 6 ++--- .../src/goal_planner_module.cpp | 26 +++++++------------ 2 files changed, 11 insertions(+), 21 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp index 0765147cbeb80..cabbeb3435087 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -135,10 +135,8 @@ bool isOnModifiedGoal( bool hasPreviousModulePathShapeChanged( const BehaviorModuleOutput & upstream_module_output, const BehaviorModuleOutput & last_upstream_module_output); -bool hasDeviatedFromLastPreviousModulePath( - const PlannerData & planner_data, const BehaviorModuleOutput & last_upstream_module_output); -bool hasDeviatedFromCurrentPreviousModulePath( - const PlannerData & planner_data, const BehaviorModuleOutput & upstream_module_output); +bool hasDeviatedFromPath( + const Point & ego_position, const BehaviorModuleOutput & upstream_module_output); bool needPathUpdate( const Pose & current_pose, const double path_update_duration, const rclcpp::Time & now, diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 87a6e28ff0007..d4f3953c557b4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -155,7 +155,7 @@ bool hasPreviousModulePathShapeChanged( { // Calculate the lateral distance between each point of the current path and the nearest point of // the last path - constexpr double LATERAL_DEVIATION_THRESH = 0.3; + constexpr double LATERAL_DEVIATION_THRESH = 0.1; for (const auto & p : upstream_module_output.path.points) { const size_t nearest_seg_idx = autoware::motion_utils::findNearestSegmentIndex( last_upstream_module_output.path.points, p.point.pose.position); @@ -184,21 +184,12 @@ bool hasPreviousModulePathShapeChanged( return false; } -bool hasDeviatedFromLastPreviousModulePath( - const PlannerData & planner_data, const BehaviorModuleOutput & last_upstream_module_output) +bool hasDeviatedFromPath( + const Point & ego_position, const BehaviorModuleOutput & upstream_module_output) { + constexpr double LATERAL_DEVIATION_THRESH = 0.1; return std::abs(autoware::motion_utils::calcLateralOffset( - last_upstream_module_output.path.points, - planner_data.self_odometry->pose.pose.position)) > 0.3; -} - -bool hasDeviatedFromCurrentPreviousModulePath( - const PlannerData & planner_data, const BehaviorModuleOutput & upstream_module_output) -{ - constexpr double LATERAL_DEVIATION_THRESH = 0.3; - return std::abs(autoware::motion_utils::calcLateralOffset( - upstream_module_output.path.points, planner_data.self_odometry->pose.pose.position)) > - LATERAL_DEVIATION_THRESH; + upstream_module_output.path.points, ego_position)) > LATERAL_DEVIATION_THRESH; } bool needPathUpdate( @@ -371,7 +362,8 @@ void LaneParkingPlanner::onTimer() local_planner_data->self_odometry->pose.pose, modified_goal_opt, parameters_)) { return false; } - if (hasDeviatedFromCurrentPreviousModulePath(*local_planner_data, upstream_module_output)) { + if (hasDeviatedFromPath( + local_planner_data->self_odometry->pose.pose.position, upstream_module_output)) { RCLCPP_DEBUG(getLogger(), "has deviated from current previous module path"); return false; } @@ -381,8 +373,8 @@ void LaneParkingPlanner::onTimer() return true; } if ( - hasDeviatedFromLastPreviousModulePath( - *local_planner_data, original_upstream_module_output_) && + hasDeviatedFromPath( + local_planner_data->self_odometry->pose.pose.position, original_upstream_module_output_) && current_state != PathDecisionState::DecisionKind::DECIDED) { RCLCPP_DEBUG(getLogger(), "has deviated from last previous module path"); return true; From 2a94090ec5a5c658dd4108bf8c07862b4bbe59bd Mon Sep 17 00:00:00 2001 From: Amadeusz Szymko Date: Fri, 10 Jan 2025 17:12:56 +0900 Subject: [PATCH 179/334] refactor(autoware_tensorrt_common): multi-TensorRT compatibility & tensorrt_common as unified lib for all perception components (#9762) * refactor(autoware_tensorrt_common): multi-TensorRT compatibility & tensorrt_common as unified lib for all perception components Signed-off-by: Amadeusz Szymko * style(pre-commit): autofix * style(autoware_tensorrt_common): linting Signed-off-by: Amadeusz Szymko * style(autoware_lidar_centerpoint): typo Co-authored-by: Kenzo Lobos Tsunekawa * docs(autoware_tensorrt_common): grammar Co-authored-by: Kenzo Lobos Tsunekawa * fix(autoware_lidar_transfusion): reuse cast variable Signed-off-by: Amadeusz Szymko * fix(autoware_tensorrt_common): remove deprecated inference API Signed-off-by: Amadeusz Szymko * style(autoware_tensorrt_common): grammar Co-authored-by: Kenzo Lobos Tsunekawa * style(autoware_tensorrt_common): grammar Co-authored-by: Kenzo Lobos Tsunekawa * fix(autoware_tensorrt_common): const pointer Signed-off-by: Amadeusz Szymko * fix(autoware_tensorrt_common): remove unused method declaration Signed-off-by: Amadeusz Szymko * style(pre-commit): autofix * refactor(autoware_tensorrt_common): readability Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> * fix(autoware_tensorrt_common): return if layer not registered Signed-off-by: Amadeusz Szymko * refactor(autoware_tensorrt_common): readability Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> * fix(autoware_tensorrt_common): rename struct Signed-off-by: Amadeusz Szymko * style(pre-commit): autofix --------- Signed-off-by: Amadeusz Szymko Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Kenzo Lobos Tsunekawa Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> --- .../pointpainting_trt.hpp | 5 +- .../src/pointpainting_fusion/node.cpp | 8 +- .../pointpainting_trt.cpp | 4 +- .../src/detector.cpp | 23 +- .../autoware_lidar_centerpoint/CMakeLists.txt | 2 - .../lidar_centerpoint/centerpoint_trt.hpp | 31 +- .../lidar_centerpoint/network/network_trt.hpp | 53 - .../network/tensorrt_wrapper.hpp | 67 -- .../lib/centerpoint_trt.cpp | 100 +- .../lib/network/network_trt.cpp | 85 -- .../lib/network/tensorrt_wrapper.cpp | 169 --- .../autoware_lidar_centerpoint/src/node.cpp | 4 +- .../autoware_lidar_transfusion/CMakeLists.txt | 1 - .../lidar_transfusion/network/network_trt.hpp | 87 -- .../lidar_transfusion/transfusion_config.hpp | 78 +- .../lidar_transfusion/transfusion_trt.hpp | 31 +- .../lib/network/network_trt.cpp | 357 ------- .../lib/transfusion_trt.cpp | 104 +- .../src/lidar_transfusion_node.cpp | 6 +- .../autoware_shape_estimation/CMakeLists.txt | 3 + .../tensorrt_shape_estimator.hpp | 6 +- .../lib/tensorrt_shape_estimator.cpp | 49 +- .../src/shape_estimation_node.cpp | 3 +- .../CMakeLists.txt | 3 + .../tensorrt_classifier.hpp | 21 +- .../src/tensorrt_classifier.cpp | 95 +- .../autoware_tensorrt_common/CMakeLists.txt | 9 +- perception/autoware_tensorrt_common/README.md | 70 +- .../tensorrt_common/conv_profiler.hpp | 108 ++ .../autoware/tensorrt_common/logger.hpp | 40 +- .../autoware/tensorrt_common/profiler.hpp | 96 ++ .../tensorrt_common/simple_profiler.hpp | 73 -- .../tensorrt_common/tensorrt_common.hpp | 449 +++++--- .../tensorrt_common/tensorrt_conv_calib.hpp | 241 +++++ .../autoware/tensorrt_common/utils.hpp | 408 +++++++ .../autoware_tensorrt_common/src/profiler.cpp | 113 ++ .../src/simple_profiler.cpp | 138 --- .../src/tensorrt_common.cpp | 992 +++++++++--------- .../autoware_tensorrt_yolox/CMakeLists.txt | 3 + .../tensorrt_yolox/tensorrt_yolox.hpp | 46 +- .../src/tensorrt_yolox.cpp | 184 ++-- .../src/tensorrt_yolox_node.cpp | 15 +- .../src/yolox_single_image_inference_node.cpp | 4 +- .../CMakeLists.txt | 1 - .../src/classifier/cnn_classifier.cpp | 7 +- .../CMakeLists.txt | 1 - .../src/traffic_light_fine_detector_node.cpp | 15 +- 47 files changed, 2345 insertions(+), 2063 deletions(-) delete mode 100644 perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/network/network_trt.hpp delete mode 100644 perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/network/tensorrt_wrapper.hpp delete mode 100644 perception/autoware_lidar_centerpoint/lib/network/network_trt.cpp delete mode 100644 perception/autoware_lidar_centerpoint/lib/network/tensorrt_wrapper.cpp delete mode 100644 perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/network/network_trt.hpp delete mode 100644 perception/autoware_lidar_transfusion/lib/network/network_trt.cpp create mode 100644 perception/autoware_tensorrt_common/include/autoware/tensorrt_common/conv_profiler.hpp create mode 100644 perception/autoware_tensorrt_common/include/autoware/tensorrt_common/profiler.hpp delete mode 100644 perception/autoware_tensorrt_common/include/autoware/tensorrt_common/simple_profiler.hpp create mode 100644 perception/autoware_tensorrt_common/include/autoware/tensorrt_common/tensorrt_conv_calib.hpp create mode 100644 perception/autoware_tensorrt_common/include/autoware/tensorrt_common/utils.hpp create mode 100644 perception/autoware_tensorrt_common/src/profiler.cpp delete mode 100644 perception/autoware_tensorrt_common/src/simple_profiler.cpp diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/pointpainting_trt.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/pointpainting_trt.hpp index a89ee3d02cd8b..a1d12bcb56384 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/pointpainting_trt.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/pointpainting_trt.hpp @@ -17,6 +17,7 @@ #include #include +#include #include #include @@ -29,8 +30,8 @@ class PointPaintingTRT : public autoware::lidar_centerpoint::CenterPointTRT using autoware::lidar_centerpoint::CenterPointTRT::CenterPointTRT; explicit PointPaintingTRT( - const autoware::lidar_centerpoint::NetworkParam & encoder_param, - const autoware::lidar_centerpoint::NetworkParam & head_param, + const autoware::tensorrt_common::TrtCommonConfig & encoder_param, + const autoware::tensorrt_common::TrtCommonConfig & head_param, const autoware::lidar_centerpoint::DensificationParam & densification_param, const autoware::lidar_centerpoint::CenterPointConfig & config); diff --git a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp index bcd62383319c1..ef03cf6c3a7cf 100644 --- a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp @@ -176,10 +176,10 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt iou_bev_nms_.setParameters(p); } - autoware::lidar_centerpoint::NetworkParam encoder_param( - encoder_onnx_path, encoder_engine_path, trt_precision); - autoware::lidar_centerpoint::NetworkParam head_param( - head_onnx_path, head_engine_path, trt_precision); + autoware::tensorrt_common::TrtCommonConfig encoder_param( + encoder_onnx_path, trt_precision, encoder_engine_path); + autoware::tensorrt_common::TrtCommonConfig head_param( + head_onnx_path, trt_precision, head_engine_path); autoware::lidar_centerpoint::DensificationParam densification_param( densification_world_frame_id, densification_num_past_frames); autoware::lidar_centerpoint::CenterPointConfig config( diff --git a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/pointpainting_trt.cpp b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/pointpainting_trt.cpp index cc3eb17cc32ab..1fe860e68a967 100644 --- a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/pointpainting_trt.cpp +++ b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/pointpainting_trt.cpp @@ -27,8 +27,8 @@ namespace autoware::image_projection_based_fusion { PointPaintingTRT::PointPaintingTRT( - const autoware::lidar_centerpoint::NetworkParam & encoder_param, - const autoware::lidar_centerpoint::NetworkParam & head_param, + const autoware::tensorrt_common::TrtCommonConfig & encoder_param, + const autoware::tensorrt_common::TrtCommonConfig & head_param, const autoware::lidar_centerpoint::DensificationParam & densification_param, const autoware::lidar_centerpoint::CenterPointConfig & config) : autoware::lidar_centerpoint::CenterPointTRT( diff --git a/perception/autoware_lidar_apollo_instance_segmentation/src/detector.cpp b/perception/autoware_lidar_apollo_instance_segmentation/src/detector.cpp index 60aa09c8e16d7..2e3a7a2243399 100644 --- a/perception/autoware_lidar_apollo_instance_segmentation/src/detector.cpp +++ b/perception/autoware_lidar_apollo_instance_segmentation/src/detector.cpp @@ -18,7 +18,6 @@ #include -#include #include #include @@ -51,12 +50,9 @@ LidarApolloInstanceSegmentation::LidarApolloInstanceSegmentation(rclcpp::Node * const auto precision = node_->declare_parameter("precision", "fp32"); trt_common_ = std::make_unique( - onnx_file, precision, nullptr, autoware::tensorrt_common::BatchConfig{1, 1, 1}, 1 << 30); - trt_common_->setup(); - - if (!trt_common_->isInitialized()) { - RCLCPP_ERROR_STREAM(node_->get_logger(), "failed to create tensorrt engine file."); - return; + tensorrt_common::TrtCommonConfig(onnx_file, precision)); + if (!trt_common_->setup()) { + throw std::runtime_error("Failed to setup TensorRT"); } if (node_->declare_parameter("build_only", false)) { @@ -65,11 +61,11 @@ LidarApolloInstanceSegmentation::LidarApolloInstanceSegmentation(rclcpp::Node * } // GPU memory allocation - const auto input_dims = trt_common_->getBindingDimensions(0); + const auto input_dims = trt_common_->getTensorShape(0); const auto input_size = std::accumulate(input_dims.d + 1, input_dims.d + input_dims.nbDims, 1, std::multiplies()); input_d_ = autoware::cuda_utils::make_unique(input_size); - const auto output_dims = trt_common_->getBindingDimensions(1); + const auto output_dims = trt_common_->getTensorShape(1); output_size_ = std::accumulate( output_dims.d + 1, output_dims.d + output_dims.nbDims, 1, std::multiplies()); output_d_ = autoware::cuda_utils::make_unique(output_size_); @@ -127,10 +123,6 @@ bool LidarApolloInstanceSegmentation::detectDynamicObjects( const sensor_msgs::msg::PointCloud2 & input, tier4_perception_msgs::msg::DetectedObjectsWithFeature & output) { - if (!trt_common_->isInitialized()) { - return false; - } - // move up pointcloud z_offset in z axis sensor_msgs::msg::PointCloud2 transformed_cloud; transformCloud(input, transformed_cloud, z_offset_); @@ -169,7 +161,10 @@ bool LidarApolloInstanceSegmentation::detectDynamicObjects( std::vector buffers = {input_d_.get(), output_d_.get()}; - trt_common_->enqueueV2(buffers.data(), *stream_, nullptr); + if (!trt_common_->setTensorsAddresses(buffers)) { + return false; + } + trt_common_->enqueueV3(*stream_); CHECK_CUDA_ERROR(cudaMemcpyAsync( output_h_.get(), output_d_.get(), sizeof(float) * output_size_, cudaMemcpyDeviceToHost, diff --git a/perception/autoware_lidar_centerpoint/CMakeLists.txt b/perception/autoware_lidar_centerpoint/CMakeLists.txt index 88244b3153349..322907c67c6ae 100644 --- a/perception/autoware_lidar_centerpoint/CMakeLists.txt +++ b/perception/autoware_lidar_centerpoint/CMakeLists.txt @@ -84,8 +84,6 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL) lib/detection_class_remapper.cpp lib/utils.cpp lib/ros_utils.cpp - lib/network/network_trt.cpp - lib/network/tensorrt_wrapper.cpp lib/postprocess/non_maximum_suppression.cpp lib/preprocess/pointcloud_densification.cpp lib/preprocess/voxel_generator.cpp diff --git a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/centerpoint_trt.hpp b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/centerpoint_trt.hpp index 671ff54f8ce0d..4b531e34877d6 100644 --- a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/centerpoint_trt.hpp +++ b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/centerpoint_trt.hpp @@ -16,12 +16,13 @@ #define AUTOWARE__LIDAR_CENTERPOINT__CENTERPOINT_TRT_HPP_ #include "autoware/lidar_centerpoint/cuda_utils.hpp" -#include "autoware/lidar_centerpoint/network/network_trt.hpp" #include "autoware/lidar_centerpoint/postprocess/postprocess_kernel.hpp" #include "autoware/lidar_centerpoint/preprocess/voxel_generator.hpp" #include "pcl/point_cloud.h" #include "pcl/point_types.h" +#include + #include "sensor_msgs/msg/point_cloud2.hpp" #include @@ -31,31 +32,14 @@ namespace autoware::lidar_centerpoint { -class NetworkParam -{ -public: - NetworkParam(std::string onnx_path, std::string engine_path, std::string trt_precision) - : onnx_path_(std::move(onnx_path)), - engine_path_(std::move(engine_path)), - trt_precision_(std::move(trt_precision)) - { - } - - std::string onnx_path() const { return onnx_path_; } - std::string engine_path() const { return engine_path_; } - std::string trt_precision() const { return trt_precision_; } - -private: - std::string onnx_path_; - std::string engine_path_; - std::string trt_precision_; -}; +using autoware::tensorrt_common::ProfileDims; +using autoware::tensorrt_common::TrtCommonConfig; class CenterPointTRT { public: explicit CenterPointTRT( - const NetworkParam & encoder_param, const NetworkParam & head_param, + const TrtCommonConfig & encoder_param, const TrtCommonConfig & head_param, const DensificationParam & densification_param, const CenterPointConfig & config); virtual ~CenterPointTRT(); @@ -66,6 +50,7 @@ class CenterPointTRT protected: void initPtr(); + void initTrt(const TrtCommonConfig & encoder_param, const TrtCommonConfig & head_param); virtual bool preprocess( const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer); @@ -75,8 +60,8 @@ class CenterPointTRT void postProcess(std::vector & det_boxes3d); std::unique_ptr vg_ptr_{nullptr}; - std::unique_ptr encoder_trt_ptr_{nullptr}; - std::unique_ptr head_trt_ptr_{nullptr}; + std::unique_ptr encoder_trt_ptr_{nullptr}; + std::unique_ptr head_trt_ptr_{nullptr}; std::unique_ptr post_proc_ptr_{nullptr}; cudaStream_t stream_{nullptr}; diff --git a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/network/network_trt.hpp b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/network/network_trt.hpp deleted file mode 100644 index 17778d77ed798..0000000000000 --- a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/network/network_trt.hpp +++ /dev/null @@ -1,53 +0,0 @@ -// Copyright 2021 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__LIDAR_CENTERPOINT__NETWORK__NETWORK_TRT_HPP_ -#define AUTOWARE__LIDAR_CENTERPOINT__NETWORK__NETWORK_TRT_HPP_ - -#include "autoware/lidar_centerpoint/centerpoint_config.hpp" -#include "autoware/lidar_centerpoint/network/tensorrt_wrapper.hpp" - -#include - -namespace autoware::lidar_centerpoint -{ -class VoxelEncoderTRT : public TensorRTWrapper -{ -public: - using TensorRTWrapper::TensorRTWrapper; - -protected: - bool setProfile( - nvinfer1::IBuilder & builder, nvinfer1::INetworkDefinition & network, - nvinfer1::IBuilderConfig & config) override; -}; - -class HeadTRT : public TensorRTWrapper -{ -public: - using TensorRTWrapper::TensorRTWrapper; - - HeadTRT(const std::vector & out_channel_sizes, const CenterPointConfig & config); - -protected: - bool setProfile( - nvinfer1::IBuilder & builder, nvinfer1::INetworkDefinition & network, - nvinfer1::IBuilderConfig & config) override; - - std::vector out_channel_sizes_; -}; - -} // namespace autoware::lidar_centerpoint - -#endif // AUTOWARE__LIDAR_CENTERPOINT__NETWORK__NETWORK_TRT_HPP_ diff --git a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/network/tensorrt_wrapper.hpp b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/network/tensorrt_wrapper.hpp deleted file mode 100644 index d56ccc699add3..0000000000000 --- a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/network/tensorrt_wrapper.hpp +++ /dev/null @@ -1,67 +0,0 @@ -// Copyright 2021 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__LIDAR_CENTERPOINT__NETWORK__TENSORRT_WRAPPER_HPP_ -#define AUTOWARE__LIDAR_CENTERPOINT__NETWORK__TENSORRT_WRAPPER_HPP_ - -#include "NvInfer.h" -#include "autoware/lidar_centerpoint/centerpoint_config.hpp" -#include "autoware/tensorrt_common/tensorrt_common.hpp" - -#include -#include -#include - -namespace autoware::lidar_centerpoint -{ - -class TensorRTWrapper -{ -public: - explicit TensorRTWrapper(const CenterPointConfig & config); - - virtual ~TensorRTWrapper(); - - bool init( - const std::string & onnx_path, const std::string & engine_path, const std::string & precision); - - autoware::tensorrt_common::TrtUniquePtr context_{nullptr}; - -protected: - virtual bool setProfile( - nvinfer1::IBuilder & builder, nvinfer1::INetworkDefinition & network, - nvinfer1::IBuilderConfig & config) = 0; - - CenterPointConfig config_; - autoware::tensorrt_common::Logger logger_; - -private: - bool parseONNX( - const std::string & onnx_path, const std::string & engine_path, const std::string & precision, - std::size_t workspace_size = (1ULL << 30)); - - bool saveEngine(const std::string & engine_path); - - bool loadEngine(const std::string & engine_path); - - bool createContext(); - - autoware::tensorrt_common::TrtUniquePtr runtime_{nullptr}; - autoware::tensorrt_common::TrtUniquePtr plan_{nullptr}; - autoware::tensorrt_common::TrtUniquePtr engine_{nullptr}; -}; - -} // namespace autoware::lidar_centerpoint - -#endif // AUTOWARE__LIDAR_CENTERPOINT__NETWORK__TENSORRT_WRAPPER_HPP_ diff --git a/perception/autoware_lidar_centerpoint/lib/centerpoint_trt.cpp b/perception/autoware_lidar_centerpoint/lib/centerpoint_trt.cpp index 530f59179d25b..c586eeb961716 100644 --- a/perception/autoware_lidar_centerpoint/lib/centerpoint_trt.cpp +++ b/perception/autoware_lidar_centerpoint/lib/centerpoint_trt.cpp @@ -28,39 +28,22 @@ #include #include #include +#include +#include #include namespace autoware::lidar_centerpoint { CenterPointTRT::CenterPointTRT( - const NetworkParam & encoder_param, const NetworkParam & head_param, + const TrtCommonConfig & encoder_param, const TrtCommonConfig & head_param, const DensificationParam & densification_param, const CenterPointConfig & config) : config_(config) { vg_ptr_ = std::make_unique(densification_param, config_); post_proc_ptr_ = std::make_unique(config_); - // encoder - encoder_trt_ptr_ = std::make_unique(config_); - encoder_trt_ptr_->init( - encoder_param.onnx_path(), encoder_param.engine_path(), encoder_param.trt_precision()); - encoder_trt_ptr_->context_->setBindingDimensions( - 0, - nvinfer1::Dims3( - config_.max_voxel_size_, config_.max_point_in_voxel_size_, config_.encoder_in_feature_size_)); - - // head - std::vector out_channel_sizes = { - config_.class_size_, config_.head_out_offset_size_, config_.head_out_z_size_, - config_.head_out_dim_size_, config_.head_out_rot_size_, config_.head_out_vel_size_}; - head_trt_ptr_ = std::make_unique(out_channel_sizes, config_); - head_trt_ptr_->init(head_param.onnx_path(), head_param.engine_path(), head_param.trt_precision()); - head_trt_ptr_->context_->setBindingDimensions( - 0, nvinfer1::Dims4( - config_.batch_size_, config_.encoder_out_feature_size_, config_.grid_size_y_, - config_.grid_size_x_)); - initPtr(); + initTrt(encoder_param, head_param); cudaStreamCreate(&stream_); } @@ -126,6 +109,66 @@ void CenterPointTRT::initPtr() cudaMemcpyHostToDevice, stream_)); } +void CenterPointTRT::initTrt( + const TrtCommonConfig & encoder_param, const TrtCommonConfig & head_param) +{ + // encoder input profile + auto enc_in_dims = nvinfer1::Dims{ + 3, + {static_cast(config_.max_voxel_size_), + static_cast(config_.max_point_in_voxel_size_), + static_cast(config_.encoder_in_feature_size_)}}; + std::vector encoder_profile_dims{ + tensorrt_common::ProfileDims(0, enc_in_dims, enc_in_dims, enc_in_dims)}; + auto encoder_profile_dims_ptr = + std::make_unique>(encoder_profile_dims); + + // head input profile + auto head_in_dims = nvinfer1::Dims{ + 4, + {static_cast(config_.batch_size_), + static_cast(config_.encoder_out_feature_size_), + static_cast(config_.grid_size_y_), static_cast(config_.grid_size_x_)}}; + std::vector head_profile_dims{ + tensorrt_common::ProfileDims(0, head_in_dims, head_in_dims, head_in_dims)}; + std::unordered_map out_channel_map = { + {1, static_cast(config_.class_size_)}, + {2, static_cast(config_.head_out_offset_size_)}, + {3, static_cast(config_.head_out_z_size_)}, + {4, static_cast(config_.head_out_dim_size_)}, + {5, static_cast(config_.head_out_rot_size_)}, + {6, static_cast(config_.head_out_vel_size_)}}; + for (const auto & [tensor_name, channel_size] : out_channel_map) { + auto dims = nvinfer1::Dims{ + 4, + {static_cast(config_.batch_size_), channel_size, + static_cast(config_.down_grid_size_y_), + static_cast(config_.down_grid_size_x_)}}; + head_profile_dims.emplace_back(tensor_name, dims, dims, dims); + } + auto head_profile_dims_ptr = + std::make_unique>(head_profile_dims); + + // initialize trt wrappers + encoder_trt_ptr_ = std::make_unique(encoder_param); + + head_trt_ptr_ = std::make_unique(head_param); + + // setup trt engines + if ( + !encoder_trt_ptr_->setup(std::move(encoder_profile_dims_ptr)) || + !head_trt_ptr_->setup(std::move(head_profile_dims_ptr))) { + throw std::runtime_error("Failed to setup TRT engine."); + } + + // set input shapes + if ( + !encoder_trt_ptr_->setInputShape(0, enc_in_dims) || + !head_trt_ptr_->setInputShape(0, head_in_dims)) { + throw std::runtime_error("Failed to set input shape."); + } +} + bool CenterPointTRT::detect( const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer, std::vector & det_boxes3d, bool & is_num_pillars_within_range) @@ -210,13 +253,10 @@ bool CenterPointTRT::preprocess( void CenterPointTRT::inference() { - if (!encoder_trt_ptr_->context_ || !head_trt_ptr_->context_) { - throw std::runtime_error("Failed to create tensorrt context."); - } - // pillar encoder network - std::vector encoder_buffers{encoder_in_features_d_.get(), pillar_features_d_.get()}; - encoder_trt_ptr_->context_->enqueueV2(encoder_buffers.data(), stream_, nullptr); + std::vector encoder_tensors = {encoder_in_features_d_.get(), pillar_features_d_.get()}; + encoder_trt_ptr_->setTensorsAddresses(encoder_tensors); + encoder_trt_ptr_->enqueueV3(stream_); // scatter CHECK_CUDA_ERROR(scatterFeatures_launch( @@ -225,11 +265,13 @@ void CenterPointTRT::inference() spatial_features_d_.get(), stream_)); // head network - std::vector head_buffers = {spatial_features_d_.get(), head_out_heatmap_d_.get(), + std::vector head_tensors = {spatial_features_d_.get(), head_out_heatmap_d_.get(), head_out_offset_d_.get(), head_out_z_d_.get(), head_out_dim_d_.get(), head_out_rot_d_.get(), head_out_vel_d_.get()}; - head_trt_ptr_->context_->enqueueV2(head_buffers.data(), stream_, nullptr); + head_trt_ptr_->setTensorsAddresses(head_tensors); + + head_trt_ptr_->enqueueV3(stream_); } void CenterPointTRT::postProcess(std::vector & det_boxes3d) diff --git a/perception/autoware_lidar_centerpoint/lib/network/network_trt.cpp b/perception/autoware_lidar_centerpoint/lib/network/network_trt.cpp deleted file mode 100644 index 7767c0b5cbb02..0000000000000 --- a/perception/autoware_lidar_centerpoint/lib/network/network_trt.cpp +++ /dev/null @@ -1,85 +0,0 @@ -// Copyright 2021 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/lidar_centerpoint/network/network_trt.hpp" - -#include -#include - -namespace autoware::lidar_centerpoint -{ -bool VoxelEncoderTRT::setProfile( - nvinfer1::IBuilder & builder, nvinfer1::INetworkDefinition & network, - nvinfer1::IBuilderConfig & config) -{ - auto profile = builder.createOptimizationProfile(); - auto in_name = network.getInput(0)->getName(); - auto in_dims = nvinfer1::Dims3( - config_.max_voxel_size_, config_.max_point_in_voxel_size_, config_.encoder_in_feature_size_); - profile->setDimensions(in_name, nvinfer1::OptProfileSelector::kMIN, in_dims); - profile->setDimensions(in_name, nvinfer1::OptProfileSelector::kOPT, in_dims); - profile->setDimensions(in_name, nvinfer1::OptProfileSelector::kMAX, in_dims); - - auto out_name = network.getOutput(0)->getName(); - auto out_dims = nvinfer1::Dims2(config_.max_voxel_size_, config_.encoder_out_feature_size_); - profile->setDimensions(out_name, nvinfer1::OptProfileSelector::kMIN, out_dims); - profile->setDimensions(out_name, nvinfer1::OptProfileSelector::kOPT, out_dims); - profile->setDimensions(out_name, nvinfer1::OptProfileSelector::kMAX, out_dims); - config.addOptimizationProfile(profile); - - return true; -} - -HeadTRT::HeadTRT( - const std::vector & out_channel_sizes, const CenterPointConfig & config) -: TensorRTWrapper(config), out_channel_sizes_(out_channel_sizes) -{ -} - -bool HeadTRT::setProfile( - nvinfer1::IBuilder & builder, nvinfer1::INetworkDefinition & network, - nvinfer1::IBuilderConfig & config) -{ - auto profile = builder.createOptimizationProfile(); - auto in_name = network.getInput(0)->getName(); - auto in_dims = nvinfer1::Dims4( - config_.batch_size_, config_.encoder_out_feature_size_, config_.grid_size_y_, - config_.grid_size_x_); - profile->setDimensions(in_name, nvinfer1::OptProfileSelector::kMIN, in_dims); - profile->setDimensions(in_name, nvinfer1::OptProfileSelector::kOPT, in_dims); - profile->setDimensions(in_name, nvinfer1::OptProfileSelector::kMAX, in_dims); - - for (std::size_t ci = 0; ci < out_channel_sizes_.size(); ci++) { - auto out_name = network.getOutput(ci)->getName(); - - if ( - out_name == std::string("heatmap") && - network.getOutput(ci)->getDimensions().d[1] != static_cast(out_channel_sizes_[ci])) { - autoware::tensorrt_common::LOG_ERROR(logger_) - << "Expected and actual number of classes do not match" << std::endl; - return false; - } - auto out_dims = nvinfer1::Dims4( - config_.batch_size_, out_channel_sizes_[ci], config_.down_grid_size_y_, - config_.down_grid_size_x_); - profile->setDimensions(out_name, nvinfer1::OptProfileSelector::kMIN, out_dims); - profile->setDimensions(out_name, nvinfer1::OptProfileSelector::kOPT, out_dims); - profile->setDimensions(out_name, nvinfer1::OptProfileSelector::kMAX, out_dims); - } - config.addOptimizationProfile(profile); - - return true; -} - -} // namespace autoware::lidar_centerpoint diff --git a/perception/autoware_lidar_centerpoint/lib/network/tensorrt_wrapper.cpp b/perception/autoware_lidar_centerpoint/lib/network/tensorrt_wrapper.cpp deleted file mode 100644 index 6d4c2e053b34f..0000000000000 --- a/perception/autoware_lidar_centerpoint/lib/network/tensorrt_wrapper.cpp +++ /dev/null @@ -1,169 +0,0 @@ -// Copyright 2021 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/lidar_centerpoint/network/tensorrt_wrapper.hpp" - -#include "NvOnnxParser.h" - -#include -#include -#include - -namespace autoware::lidar_centerpoint -{ -TensorRTWrapper::TensorRTWrapper(const CenterPointConfig & config) : config_(config) -{ -} - -TensorRTWrapper::~TensorRTWrapper() -{ - context_.reset(); - runtime_.reset(); - plan_.reset(); - engine_.reset(); -} - -bool TensorRTWrapper::init( - const std::string & onnx_path, const std::string & engine_path, const std::string & precision) -{ - runtime_ = autoware::tensorrt_common::TrtUniquePtr( - nvinfer1::createInferRuntime(logger_)); - if (!runtime_) { - autoware::tensorrt_common::LOG_ERROR(logger_) << "Failed to create runtime" << std::endl; - return false; - } - - bool success; - std::ifstream engine_file(engine_path); - if (engine_file.is_open()) { - success = loadEngine(engine_path); - } else { - auto log_thread = logger_.log_throttle( - nvinfer1::ILogger::Severity::kINFO, - "Applying optimizations and building TRT CUDA engine. Please wait a minutes...", 5); - success = parseONNX(onnx_path, engine_path, precision); - logger_.stop_throttle(log_thread); - } - success &= createContext(); - - return success; -} - -bool TensorRTWrapper::createContext() -{ - if (!engine_) { - autoware::tensorrt_common::LOG_ERROR(logger_) - << "Failed to create context: Engine was not created" << std::endl; - return false; - } - - context_ = autoware::tensorrt_common::TrtUniquePtr( - engine_->createExecutionContext()); - if (!context_) { - autoware::tensorrt_common::LOG_ERROR(logger_) << "Failed to create context" << std::endl; - return false; - } - - return true; -} - -bool TensorRTWrapper::parseONNX( - const std::string & onnx_path, const std::string & engine_path, const std::string & precision, - const std::size_t workspace_size) -{ - auto builder = autoware::tensorrt_common::TrtUniquePtr( - nvinfer1::createInferBuilder(logger_)); - if (!builder) { - autoware::tensorrt_common::LOG_ERROR(logger_) << "Failed to create builder" << std::endl; - return false; - } - - auto config = autoware::tensorrt_common::TrtUniquePtr( - builder->createBuilderConfig()); - if (!config) { - autoware::tensorrt_common::LOG_ERROR(logger_) << "Failed to create config" << std::endl; - return false; - } -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8400 - config->setMemoryPoolLimit(nvinfer1::MemoryPoolType::kWORKSPACE, workspace_size); -#else - config->setMaxWorkspaceSize(workspace_size); -#endif - if (precision == "fp16") { - if (builder->platformHasFastFp16()) { - autoware::tensorrt_common::LOG_INFO(logger_) << "Using TensorRT FP16 Inference" << std::endl; - config->setFlag(nvinfer1::BuilderFlag::kFP16); - } else { - autoware::tensorrt_common::LOG_INFO(logger_) - << "TensorRT FP16 Inference isn't supported in this environment" << std::endl; - } - } - - const auto flag = - 1U << static_cast(nvinfer1::NetworkDefinitionCreationFlag::kEXPLICIT_BATCH); - auto network = autoware::tensorrt_common::TrtUniquePtr( - builder->createNetworkV2(flag)); - if (!network) { - autoware::tensorrt_common::LOG_ERROR(logger_) << "Failed to create network" << std::endl; - return false; - } - - auto parser = autoware::tensorrt_common::TrtUniquePtr( - nvonnxparser::createParser(*network, logger_)); - parser->parseFromFile(onnx_path.c_str(), static_cast(nvinfer1::ILogger::Severity::kERROR)); - - if (!setProfile(*builder, *network, *config)) { - autoware::tensorrt_common::LOG_ERROR(logger_) << "Failed to set profile" << std::endl; - return false; - } - - plan_ = autoware::tensorrt_common::TrtUniquePtr( - builder->buildSerializedNetwork(*network, *config)); - if (!plan_) { - autoware::tensorrt_common::LOG_ERROR(logger_) - << "Failed to create serialized network" << std::endl; - return false; - } - engine_ = autoware::tensorrt_common::TrtUniquePtr( - runtime_->deserializeCudaEngine(plan_->data(), plan_->size())); - if (!engine_) { - autoware::tensorrt_common::LOG_ERROR(logger_) << "Failed to create engine" << std::endl; - return false; - } - - return saveEngine(engine_path); -} - -bool TensorRTWrapper::saveEngine(const std::string & engine_path) -{ - autoware::tensorrt_common::LOG_INFO(logger_) << "Writing to " << engine_path << std::endl; - std::ofstream file(engine_path, std::ios::out | std::ios::binary); - file.write(reinterpret_cast(plan_->data()), plan_->size()); - return true; -} - -bool TensorRTWrapper::loadEngine(const std::string & engine_path) -{ - std::ifstream engine_file(engine_path); - std::stringstream engine_buffer; - engine_buffer << engine_file.rdbuf(); - std::string engine_str = engine_buffer.str(); - engine_ = - autoware::tensorrt_common::TrtUniquePtr(runtime_->deserializeCudaEngine( - reinterpret_cast(engine_str.data()), engine_str.size())); - autoware::tensorrt_common::LOG_INFO(logger_) << "Loaded engine from " << engine_path << std::endl; - return true; -} - -} // namespace autoware::lidar_centerpoint diff --git a/perception/autoware_lidar_centerpoint/src/node.cpp b/perception/autoware_lidar_centerpoint/src/node.cpp index 825fc40234120..19d1475db9051 100644 --- a/perception/autoware_lidar_centerpoint/src/node.cpp +++ b/perception/autoware_lidar_centerpoint/src/node.cpp @@ -86,8 +86,8 @@ LidarCenterPointNode::LidarCenterPointNode(const rclcpp::NodeOptions & node_opti iou_bev_nms_.setParameters(p); } - NetworkParam encoder_param(encoder_onnx_path, encoder_engine_path, trt_precision); - NetworkParam head_param(head_onnx_path, head_engine_path, trt_precision); + TrtCommonConfig encoder_param(encoder_onnx_path, trt_precision, encoder_engine_path); + TrtCommonConfig head_param(head_onnx_path, trt_precision, head_engine_path); DensificationParam densification_param( densification_world_frame_id, densification_num_past_frames); diff --git a/perception/autoware_lidar_transfusion/CMakeLists.txt b/perception/autoware_lidar_transfusion/CMakeLists.txt index c3a56f883fbe5..fdb978c64946f 100644 --- a/perception/autoware_lidar_transfusion/CMakeLists.txt +++ b/perception/autoware_lidar_transfusion/CMakeLists.txt @@ -84,7 +84,6 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL) ament_auto_add_library(${PROJECT_NAME}_lib SHARED lib/detection_class_remapper.cpp - lib/network/network_trt.cpp lib/postprocess/non_maximum_suppression.cpp lib/preprocess/voxel_generator.cpp lib/preprocess/pointcloud_densification.cpp diff --git a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/network/network_trt.hpp b/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/network/network_trt.hpp deleted file mode 100644 index 71cd08acdb8c8..0000000000000 --- a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/network/network_trt.hpp +++ /dev/null @@ -1,87 +0,0 @@ -// Copyright 2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__LIDAR_TRANSFUSION__NETWORK__NETWORK_TRT_HPP_ -#define AUTOWARE__LIDAR_TRANSFUSION__NETWORK__NETWORK_TRT_HPP_ - -#include "autoware/lidar_transfusion/transfusion_config.hpp" -#include "autoware/lidar_transfusion/utils.hpp" - -#include - -#include - -#include -#include -#include -#include -#include -#include - -namespace autoware::lidar_transfusion -{ - -struct ProfileDimension -{ - nvinfer1::Dims min; - nvinfer1::Dims opt; - nvinfer1::Dims max; - - bool operator!=(const ProfileDimension & rhs) const - { - return min.nbDims != rhs.min.nbDims || opt.nbDims != rhs.opt.nbDims || - max.nbDims != rhs.max.nbDims || !std::equal(min.d, min.d + min.nbDims, rhs.min.d) || - !std::equal(opt.d, opt.d + opt.nbDims, rhs.opt.d) || - !std::equal(max.d, max.d + max.nbDims, rhs.max.d); - } -}; - -class NetworkTRT -{ -public: - explicit NetworkTRT(const TransfusionConfig & config); - ~NetworkTRT(); - - bool init( - const std::string & onnx_path, const std::string & engine_path, const std::string & precision); - const char * getTensorName(NetworkIO name); - - autoware::tensorrt_common::TrtUniquePtr engine{nullptr}; - autoware::tensorrt_common::TrtUniquePtr context{nullptr}; - -private: - bool parseONNX( - const std::string & onnx_path, const std::string & engine_path, const std::string & precision, - std::size_t workspace_size = (1ULL << 30)); - bool saveEngine(const std::string & engine_path); - bool loadEngine(const std::string & engine_path); - bool createContext(); - bool setProfile( - nvinfer1::IBuilder & builder, nvinfer1::INetworkDefinition & network, - nvinfer1::IBuilderConfig & config); - bool validateNetworkIO(); - nvinfer1::Dims validateTensorShape(NetworkIO name, const std::vector shape); - - autoware::tensorrt_common::TrtUniquePtr runtime_{nullptr}; - autoware::tensorrt_common::TrtUniquePtr plan_{nullptr}; - autoware::tensorrt_common::Logger logger_; - TransfusionConfig config_; - std::vector tensors_names_; - - std::array in_profile_dims_; -}; - -} // namespace autoware::lidar_transfusion - -#endif // AUTOWARE__LIDAR_TRANSFUSION__NETWORK__NETWORK_TRT_HPP_ diff --git a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/transfusion_config.hpp b/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/transfusion_config.hpp index 363ee17a0d6e0..e60ee04150b5c 100644 --- a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/transfusion_config.hpp +++ b/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/transfusion_config.hpp @@ -35,21 +35,21 @@ class TransfusionConfig if (voxels_num.size() == 3) { max_voxels_ = voxels_num[2]; - voxels_num_[0] = voxels_num[0]; - voxels_num_[1] = voxels_num[1]; - voxels_num_[2] = voxels_num[2]; + voxels_num_[0] = static_cast(voxels_num[0]); + voxels_num_[1] = static_cast(voxels_num[1]); + voxels_num_[2] = static_cast(voxels_num[2]); - min_voxel_size_ = voxels_num[0]; - opt_voxel_size_ = voxels_num[1]; - max_voxel_size_ = voxels_num[2]; + min_voxel_size_ = static_cast(voxels_num[0]); + opt_voxel_size_ = static_cast(voxels_num[1]); + max_voxel_size_ = static_cast(voxels_num[2]); - min_points_size_ = voxels_num[0]; - opt_points_size_ = voxels_num[1]; - max_points_size_ = voxels_num[2]; + min_points_size_ = static_cast(voxels_num[0]); + opt_points_size_ = static_cast(voxels_num[1]); + max_points_size_ = static_cast(voxels_num[2]); - min_coors_size_ = voxels_num[0]; - opt_coors_size_ = voxels_num[1]; - max_coors_size_ = voxels_num[2]; + min_coors_size_ = static_cast(voxels_num[0]); + opt_coors_size_ = static_cast(voxels_num[1]); + max_coors_size_ = static_cast(voxels_num[2]); } if (point_cloud_range.size() == 6) { min_x_range_ = static_cast(point_cloud_range[0]); @@ -91,7 +91,7 @@ class TransfusionConfig std::size_t cloud_capacity_{}; ///// KERNEL PARAMETERS ///// const std::size_t threads_for_voxel_{256}; // threads number for a block - const std::size_t points_per_voxel_{20}; + const int32_t points_per_voxel_{20}; const std::size_t warp_size_{32}; // one warp(32 threads) for one pillar const std::size_t pillars_per_block_{64}; // one thread deals with one pillar // and a block has pillars_per_block threads @@ -99,9 +99,9 @@ class TransfusionConfig std::size_t max_voxels_{60000}; ///// NETWORK PARAMETERS ///// - const std::size_t batch_size_{1}; - const std::size_t num_classes_{5}; - const std::size_t num_point_feature_size_{5}; // x, y, z, intensity, lag + const int32_t batch_size_{1}; + const int32_t num_classes_{5}; + const int32_t num_point_feature_size_{5}; // x, y, z, intensity, lag // the dimension of the input cloud float min_x_range_{-76.8}; float max_x_range_{76.8}; @@ -114,9 +114,9 @@ class TransfusionConfig float voxel_y_size_{0.3}; float voxel_z_size_{8.0}; const std::size_t out_size_factor_{4}; - const std::size_t max_num_points_per_pillar_{points_per_voxel_}; - const std::size_t num_point_values_{4}; - std::size_t num_proposals_{200}; + const int32_t max_num_points_per_pillar_{points_per_voxel_}; + const int32_t num_point_values_{4}; + int32_t num_proposals_{200}; // the number of feature maps for pillar scatter const std::size_t num_feature_scatter_{pillar_feature_size_}; // the score threshold for classification @@ -126,7 +126,7 @@ class TransfusionConfig std::size_t max_num_pillars_{max_voxels_}; const std::size_t pillar_points_bev_{max_num_points_per_pillar_ * max_num_pillars_}; // the detected boxes result decode by (x, y, z, w, l, h, yaw) - const std::size_t num_box_values_{8}; + const int32_t num_box_values_{8}; // the input size of the 2D backbone network std::size_t grid_x_size_{512}; std::size_t grid_y_size_{512}; @@ -136,33 +136,33 @@ class TransfusionConfig std::size_t feature_y_size_{grid_y_size_ / out_size_factor_}; ///// RUNTIME DIMENSIONS ///// - std::vector voxels_num_{5000, 30000, 60000}; + std::vector voxels_num_{5000, 30000, 60000}; // voxels - std::size_t min_voxel_size_{voxels_num_[0]}; - std::size_t opt_voxel_size_{voxels_num_[1]}; - std::size_t max_voxel_size_{voxels_num_[2]}; + int32_t min_voxel_size_{voxels_num_[0]}; + int32_t opt_voxel_size_{voxels_num_[1]}; + int32_t max_voxel_size_{voxels_num_[2]}; - std::size_t min_point_in_voxel_size_{points_per_voxel_}; - std::size_t opt_point_in_voxel_size_{points_per_voxel_}; - std::size_t max_point_in_voxel_size_{points_per_voxel_}; + int32_t min_point_in_voxel_size_{points_per_voxel_}; + int32_t opt_point_in_voxel_size_{points_per_voxel_}; + int32_t max_point_in_voxel_size_{points_per_voxel_}; - std::size_t min_network_feature_size_{num_point_feature_size_}; - std::size_t opt_network_feature_size_{num_point_feature_size_}; - std::size_t max_network_feature_size_{num_point_feature_size_}; + int32_t min_network_feature_size_{num_point_feature_size_}; + int32_t opt_network_feature_size_{num_point_feature_size_}; + int32_t max_network_feature_size_{num_point_feature_size_}; // num_points - std::size_t min_points_size_{voxels_num_[0]}; - std::size_t opt_points_size_{voxels_num_[1]}; - std::size_t max_points_size_{voxels_num_[2]}; + int32_t min_points_size_{voxels_num_[0]}; + int32_t opt_points_size_{voxels_num_[1]}; + int32_t max_points_size_{voxels_num_[2]}; // coors - std::size_t min_coors_size_{voxels_num_[0]}; - std::size_t opt_coors_size_{voxels_num_[1]}; - std::size_t max_coors_size_{voxels_num_[2]}; + int32_t min_coors_size_{voxels_num_[0]}; + int32_t opt_coors_size_{voxels_num_[1]}; + int32_t max_coors_size_{voxels_num_[2]}; - std::size_t min_coors_dim_size_{num_point_values_}; - std::size_t opt_coors_dim_size_{num_point_values_}; - std::size_t max_coors_dim_size_{num_point_values_}; + int32_t min_coors_dim_size_{num_point_values_}; + int32_t opt_coors_dim_size_{num_point_values_}; + int32_t max_coors_dim_size_{num_point_values_}; }; } // namespace autoware::lidar_transfusion diff --git a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/transfusion_trt.hpp b/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/transfusion_trt.hpp index 06dd65b4b805f..00bb5e726706c 100644 --- a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/transfusion_trt.hpp +++ b/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/transfusion_trt.hpp @@ -16,7 +16,6 @@ #define AUTOWARE__LIDAR_TRANSFUSION__TRANSFUSION_TRT_HPP_ #include "autoware/lidar_transfusion/cuda_utils.hpp" -#include "autoware/lidar_transfusion/network/network_trt.hpp" #include "autoware/lidar_transfusion/postprocess/postprocess_kernel.hpp" #include "autoware/lidar_transfusion/preprocess/pointcloud_densification.hpp" #include "autoware/lidar_transfusion/preprocess/preprocess_kernel.hpp" @@ -24,6 +23,7 @@ #include "autoware/lidar_transfusion/utils.hpp" #include "autoware/lidar_transfusion/visibility_control.hpp" +#include #include #include @@ -34,38 +34,17 @@ #include #include #include -#include #include namespace autoware::lidar_transfusion { -class NetworkParam -{ -public: - NetworkParam(std::string onnx_path, std::string engine_path, std::string trt_precision) - : onnx_path_(std::move(onnx_path)), - engine_path_(std::move(engine_path)), - trt_precision_(std::move(trt_precision)) - { - } - - std::string onnx_path() const { return onnx_path_; } - std::string engine_path() const { return engine_path_; } - std::string trt_precision() const { return trt_precision_; } - -private: - std::string onnx_path_; - std::string engine_path_; - std::string trt_precision_; -}; - class LIDAR_TRANSFUSION_PUBLIC TransfusionTRT { public: explicit TransfusionTRT( - const NetworkParam & network_param, const DensificationParam & densification_param, - const TransfusionConfig & config); + const tensorrt_common::TrtCommonConfig & trt_config, + const DensificationParam & densification_param, const TransfusionConfig config); virtual ~TransfusionTRT(); bool detect( @@ -73,6 +52,8 @@ class LIDAR_TRANSFUSION_PUBLIC TransfusionTRT std::vector & det_boxes3d, std::unordered_map & proc_timing); protected: + void initTrt(const tensorrt_common::TrtCommonConfig & trt_config); + void initPtr(); bool preprocess(const sensor_msgs::msg::PointCloud2 & msg, const tf2_ros::Buffer & tf_buffer); @@ -81,7 +62,7 @@ class LIDAR_TRANSFUSION_PUBLIC TransfusionTRT bool postprocess(std::vector & det_boxes3d); - std::unique_ptr network_trt_ptr_{nullptr}; + std::unique_ptr network_trt_ptr_{nullptr}; std::unique_ptr vg_ptr_{nullptr}; std::unique_ptr> stop_watch_ptr_{ nullptr}; diff --git a/perception/autoware_lidar_transfusion/lib/network/network_trt.cpp b/perception/autoware_lidar_transfusion/lib/network/network_trt.cpp deleted file mode 100644 index 8e3cb8a55ec7e..0000000000000 --- a/perception/autoware_lidar_transfusion/lib/network/network_trt.cpp +++ /dev/null @@ -1,357 +0,0 @@ -// Copyright 2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/lidar_transfusion/network/network_trt.hpp" - -#include - -#include -#include -#include -#include -#include - -namespace autoware::lidar_transfusion -{ - -inline NetworkIO nameToNetworkIO(const char * name) -{ - static const std::unordered_map name_to_enum = { - {"voxels", NetworkIO::voxels}, {"num_points", NetworkIO::num_points}, - {"coors", NetworkIO::coors}, {"cls_score0", NetworkIO::cls_score}, - {"bbox_pred0", NetworkIO::bbox_pred}, {"dir_cls_pred0", NetworkIO::dir_pred}}; - - auto it = name_to_enum.find(name); - if (it != name_to_enum.end()) { - return it->second; - } - throw std::runtime_error("Invalid input name: " + std::string(name)); -} - -std::ostream & operator<<(std::ostream & os, const ProfileDimension & profile) -{ - std::string delim = ""; - os << "min->["; - for (int i = 0; i < profile.min.nbDims; ++i) { - os << delim << profile.min.d[i]; - delim = ", "; - } - os << "], opt->["; - delim = ""; - for (int i = 0; i < profile.opt.nbDims; ++i) { - os << delim << profile.opt.d[i]; - delim = ", "; - } - os << "], max->["; - delim = ""; - for (int i = 0; i < profile.max.nbDims; ++i) { - os << delim << profile.max.d[i]; - delim = ", "; - } - os << "]"; - return os; -} - -NetworkTRT::NetworkTRT(const TransfusionConfig & config) : config_(config) -{ - ProfileDimension voxels_dims = { - nvinfer1::Dims3( - config_.min_voxel_size_, config_.min_point_in_voxel_size_, config_.min_network_feature_size_), - nvinfer1::Dims3( - config_.opt_voxel_size_, config_.opt_point_in_voxel_size_, config_.opt_network_feature_size_), - nvinfer1::Dims3( - config_.max_voxel_size_, config_.max_point_in_voxel_size_, - config_.max_network_feature_size_)}; - ProfileDimension num_points_dims = { - nvinfer1::Dims{1, {static_cast(config_.min_points_size_)}}, - nvinfer1::Dims{1, {static_cast(config_.opt_points_size_)}}, - nvinfer1::Dims{1, {static_cast(config_.max_points_size_)}}}; - ProfileDimension coors_dims = { - nvinfer1::Dims2(config_.min_coors_size_, config_.min_coors_dim_size_), - nvinfer1::Dims2(config_.opt_coors_size_, config_.opt_coors_dim_size_), - nvinfer1::Dims2(config_.max_coors_size_, config_.max_coors_dim_size_)}; - in_profile_dims_ = {voxels_dims, num_points_dims, coors_dims}; -} - -NetworkTRT::~NetworkTRT() -{ - context.reset(); - runtime_.reset(); - plan_.reset(); - engine.reset(); -} - -bool NetworkTRT::init( - const std::string & onnx_path, const std::string & engine_path, const std::string & precision) -{ - runtime_ = autoware::tensorrt_common::TrtUniquePtr( - nvinfer1::createInferRuntime(logger_)); - if (!runtime_) { - autoware::tensorrt_common::LOG_ERROR(logger_) << "Failed to create runtime" << std::endl; - return false; - } - - bool success; - std::ifstream engine_file(engine_path); - if (engine_file.is_open()) { - success = loadEngine(engine_path); - } else { - auto log_thread = logger_.log_throttle( - nvinfer1::ILogger::Severity::kINFO, - "Applying optimizations and building TRT CUDA engine. Please wait a minutes...", 5); - success = parseONNX(onnx_path, engine_path, precision); - logger_.stop_throttle(log_thread); - } - success &= createContext(); - - return success; -} - -bool NetworkTRT::setProfile( - nvinfer1::IBuilder & builder, nvinfer1::INetworkDefinition & network, - nvinfer1::IBuilderConfig & config) -{ - auto profile = builder.createOptimizationProfile(); - - auto voxels_name = network.getInput(NetworkIO::voxels)->getName(); - auto num_points_name = network.getInput(NetworkIO::num_points)->getName(); - auto coors_name = network.getInput(NetworkIO::coors)->getName(); - - profile->setDimensions( - voxels_name, nvinfer1::OptProfileSelector::kMIN, in_profile_dims_[NetworkIO::voxels].min); - profile->setDimensions( - voxels_name, nvinfer1::OptProfileSelector::kOPT, in_profile_dims_[NetworkIO::voxels].opt); - profile->setDimensions( - voxels_name, nvinfer1::OptProfileSelector::kMAX, in_profile_dims_[NetworkIO::voxels].max); - - profile->setDimensions( - num_points_name, nvinfer1::OptProfileSelector::kMIN, - in_profile_dims_[NetworkIO::num_points].min); - profile->setDimensions( - num_points_name, nvinfer1::OptProfileSelector::kOPT, - in_profile_dims_[NetworkIO::num_points].opt); - profile->setDimensions( - num_points_name, nvinfer1::OptProfileSelector::kMAX, - in_profile_dims_[NetworkIO::num_points].max); - - profile->setDimensions( - coors_name, nvinfer1::OptProfileSelector::kMIN, in_profile_dims_[NetworkIO::coors].min); - profile->setDimensions( - coors_name, nvinfer1::OptProfileSelector::kOPT, in_profile_dims_[NetworkIO::coors].opt); - profile->setDimensions( - coors_name, nvinfer1::OptProfileSelector::kMAX, in_profile_dims_[NetworkIO::coors].max); - - config.addOptimizationProfile(profile); - return true; -} - -bool NetworkTRT::createContext() -{ - if (!engine) { - autoware::tensorrt_common::LOG_ERROR(logger_) - << "Failed to create context: Engine was not created" << std::endl; - return false; - } - - context = autoware::tensorrt_common::TrtUniquePtr( - engine->createExecutionContext()); - if (!context) { - autoware::tensorrt_common::LOG_ERROR(logger_) << "Failed to create context" << std::endl; - return false; - } - - return true; -} - -bool NetworkTRT::parseONNX( - const std::string & onnx_path, const std::string & engine_path, const std::string & precision, - const size_t workspace_size) -{ - auto builder = autoware::tensorrt_common::TrtUniquePtr( - nvinfer1::createInferBuilder(logger_)); - if (!builder) { - autoware::tensorrt_common::LOG_ERROR(logger_) << "Failed to create builder" << std::endl; - return false; - } - - auto config = autoware::tensorrt_common::TrtUniquePtr( - builder->createBuilderConfig()); - if (!config) { - autoware::tensorrt_common::LOG_ERROR(logger_) << "Failed to create config" << std::endl; - return false; - } -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8400 - config->setMemoryPoolLimit(nvinfer1::MemoryPoolType::kWORKSPACE, workspace_size); -#else - config->setMaxWorkspaceSize(workspace_size); -#endif - if (precision == "fp16") { - if (builder->platformHasFastFp16()) { - autoware::tensorrt_common::LOG_INFO(logger_) << "Using TensorRT FP16 Inference" << std::endl; - config->setFlag(nvinfer1::BuilderFlag::kFP16); - } else { - autoware::tensorrt_common::LOG_INFO(logger_) - << "TensorRT FP16 Inference isn't supported in this environment" << std::endl; - } - } - - const auto flag = - 1U << static_cast(nvinfer1::NetworkDefinitionCreationFlag::kEXPLICIT_BATCH); - auto network = autoware::tensorrt_common::TrtUniquePtr( - builder->createNetworkV2(flag)); - if (!network) { - autoware::tensorrt_common::LOG_ERROR(logger_) << "Failed to create network" << std::endl; - return false; - } - - auto parser = autoware::tensorrt_common::TrtUniquePtr( - nvonnxparser::createParser(*network, logger_)); - parser->parseFromFile(onnx_path.c_str(), static_cast(nvinfer1::ILogger::Severity::kERROR)); - - if (!setProfile(*builder, *network, *config)) { - autoware::tensorrt_common::LOG_ERROR(logger_) << "Failed to set profile" << std::endl; - return false; - } - - plan_ = autoware::tensorrt_common::TrtUniquePtr( - builder->buildSerializedNetwork(*network, *config)); - if (!plan_) { - autoware::tensorrt_common::LOG_ERROR(logger_) - << "Failed to create serialized network" << std::endl; - return false; - } - engine = autoware::tensorrt_common::TrtUniquePtr( - runtime_->deserializeCudaEngine(plan_->data(), plan_->size())); - if (!engine) { - autoware::tensorrt_common::LOG_ERROR(logger_) << "Failed to create engine" << std::endl; - return false; - } - - return saveEngine(engine_path); -} - -bool NetworkTRT::saveEngine(const std::string & engine_path) -{ - autoware::tensorrt_common::LOG_INFO(logger_) << "Writing to " << engine_path << std::endl; - std::ofstream file(engine_path, std::ios::out | std::ios::binary); - file.write(reinterpret_cast(plan_->data()), plan_->size()); - return validateNetworkIO(); -} - -bool NetworkTRT::loadEngine(const std::string & engine_path) -{ - std::ifstream engine_file(engine_path); - std::stringstream engine_buffer; - engine_buffer << engine_file.rdbuf(); - std::string engine_str = engine_buffer.str(); - engine = - autoware::tensorrt_common::TrtUniquePtr(runtime_->deserializeCudaEngine( - reinterpret_cast(engine_str.data()), engine_str.size())); - autoware::tensorrt_common::LOG_INFO(logger_) << "Loaded engine from " << engine_path << std::endl; - return validateNetworkIO(); -} - -bool NetworkTRT::validateNetworkIO() -{ - // Whether the number of IO match the expected size - if (engine->getNbIOTensors() != NetworkIO::ENUM_SIZE) { - autoware::tensorrt_common::LOG_ERROR(logger_) - << "Invalid network IO. Expected size: " << NetworkIO::ENUM_SIZE - << ". Actual size: " << engine->getNbIOTensors() << "." << std::endl; - throw std::runtime_error("Failed to initialize TRT network."); - } - - // Initialize tensors_names_ with null values - tensors_names_.resize(NetworkIO::ENUM_SIZE, nullptr); - - // Loop over the tensor names and place them in the correct positions - for (int i = 0; i < NetworkIO::ENUM_SIZE; ++i) { - const char * name = engine->getIOTensorName(i); - tensors_names_[nameToNetworkIO(name)] = name; - } - - // Log the network IO - std::string tensors = std::accumulate( - tensors_names_.begin(), tensors_names_.end(), std::string(), - [](const std::string & a, const std::string & b) -> std::string { return a + b + " "; }); - autoware::tensorrt_common::LOG_INFO(logger_) << "Network IO: " << tensors << std::endl; - - // Whether the current engine input profile match the config input profile - for (int i = 0; i <= NetworkIO::coors; ++i) { - ProfileDimension engine_dims{ - engine->getProfileShape(tensors_names_[i], 0, nvinfer1::OptProfileSelector::kMIN), - engine->getProfileShape(tensors_names_[i], 0, nvinfer1::OptProfileSelector::kOPT), - engine->getProfileShape(tensors_names_[i], 0, nvinfer1::OptProfileSelector::kMAX)}; - - autoware::tensorrt_common::LOG_INFO(logger_) - << "Profile for " << tensors_names_[i] << ": " << engine_dims << std::endl; - - if (engine_dims != in_profile_dims_[i]) { - autoware::tensorrt_common::LOG_ERROR(logger_) - << "Invalid network input dimension. Config: " << in_profile_dims_[i] - << ". Please change the input profile or delete the engine file and build engine again." - << std::endl; - throw std::runtime_error("Failed to initialize TRT network."); - } - } - - // Whether the IO tensor shapes match the network config, -1 for dynamic size - validateTensorShape( - NetworkIO::voxels, {-1, static_cast(config_.points_per_voxel_), - static_cast(config_.num_point_feature_size_)}); - validateTensorShape(NetworkIO::num_points, {-1}); - validateTensorShape(NetworkIO::coors, {-1, static_cast(config_.num_point_values_)}); - auto cls_score = validateTensorShape( - NetworkIO::cls_score, - {static_cast(config_.batch_size_), static_cast(config_.num_classes_), - static_cast(config_.num_proposals_)}); - autoware::tensorrt_common::LOG_INFO(logger_) - << "Network num classes: " << cls_score.d[1] << std::endl; - validateTensorShape( - NetworkIO::dir_pred, - {static_cast(config_.batch_size_), 2, static_cast(config_.num_proposals_)}); // x, y - validateTensorShape( - NetworkIO::bbox_pred, - {static_cast(config_.batch_size_), static_cast(config_.num_box_values_), - static_cast(config_.num_proposals_)}); - - return true; -} - -const char * NetworkTRT::getTensorName(NetworkIO name) -{ - return tensors_names_.at(name); -} - -nvinfer1::Dims NetworkTRT::validateTensorShape(NetworkIO name, const std::vector shape) -{ - auto tensor_shape = engine->getTensorShape(tensors_names_[name]); - if (tensor_shape.nbDims != static_cast(shape.size())) { - autoware::tensorrt_common::LOG_ERROR(logger_) - << "Invalid tensor shape for " << tensors_names_[name] << ". Expected size: " << shape.size() - << ". Actual size: " << tensor_shape.nbDims << "." << std::endl; - throw std::runtime_error("Failed to initialize TRT network."); - } - for (int i = 0; i < tensor_shape.nbDims; ++i) { - if (tensor_shape.d[i] != static_cast(shape[i])) { - autoware::tensorrt_common::LOG_ERROR(logger_) - << "Invalid tensor shape for " << tensors_names_[name] << ". Expected: " << shape[i] - << ". Actual: " << tensor_shape.d[i] << "." << std::endl; - throw std::runtime_error("Failed to initialize TRT network."); - } - } - return tensor_shape; -} - -} // namespace autoware::lidar_transfusion diff --git a/perception/autoware_lidar_transfusion/lib/transfusion_trt.cpp b/perception/autoware_lidar_transfusion/lib/transfusion_trt.cpp index 4e100f2e794d5..dd075a45cb29c 100644 --- a/perception/autoware_lidar_transfusion/lib/transfusion_trt.cpp +++ b/perception/autoware_lidar_transfusion/lib/transfusion_trt.cpp @@ -17,6 +17,7 @@ #include "autoware/lidar_transfusion/preprocess/preprocess_kernel.hpp" #include "autoware/lidar_transfusion/transfusion_config.hpp" +#include #include #include @@ -27,25 +28,23 @@ #include #include #include +#include #include namespace autoware::lidar_transfusion { TransfusionTRT::TransfusionTRT( - const NetworkParam & network_param, const DensificationParam & densification_param, - const TransfusionConfig & config) -: config_(config) + const tensorrt_common::TrtCommonConfig & trt_config, + const DensificationParam & densification_param, TransfusionConfig config) +: config_(std::move(config)) { - network_trt_ptr_ = std::make_unique(config_); - - network_trt_ptr_->init( - network_param.onnx_path(), network_param.engine_path(), network_param.trt_precision()); vg_ptr_ = std::make_unique(densification_param, config_, stream_); stop_watch_ptr_ = std::make_unique>(); stop_watch_ptr_->tic("processing/inner"); initPtr(); + initTrt(trt_config); CHECK_CUDA_ERROR(cudaStreamCreate(&stream_)); } @@ -99,6 +98,51 @@ void TransfusionTRT::initPtr() post_ptr_ = std::make_unique(config_, stream_); } +void TransfusionTRT::initTrt(const tensorrt_common::TrtCommonConfig & trt_config) +{ + std::vector network_io{ + autoware::tensorrt_common::NetworkIO( + "voxels", {3, {-1, config_.points_per_voxel_, config_.num_point_feature_size_}}), + autoware::tensorrt_common::NetworkIO("num_points", {1, {-1}}), + autoware::tensorrt_common::NetworkIO("coors", {2, {-1, config_.num_point_values_}}), + autoware::tensorrt_common::NetworkIO( + "cls_score0", {3, {config_.batch_size_, config_.num_classes_, config_.num_proposals_}}), + autoware::tensorrt_common::NetworkIO( + "bbox_pred0", {3, {config_.batch_size_, config_.num_box_values_, config_.num_proposals_}}), + autoware::tensorrt_common::NetworkIO( + "dir_cls_pred0", {3, {config_.batch_size_, 2, config_.num_proposals_}})}; + + std::vector profile_dims{ + autoware::tensorrt_common::ProfileDims( + "voxels", + {3, + {config_.min_voxel_size_, config_.min_point_in_voxel_size_, + config_.min_network_feature_size_}}, + {3, + {config_.opt_voxel_size_, config_.opt_point_in_voxel_size_, + config_.opt_network_feature_size_}}, + {3, + {config_.max_voxel_size_, config_.max_point_in_voxel_size_, + config_.max_network_feature_size_}}), + autoware::tensorrt_common::ProfileDims( + "num_points", {1, {static_cast(config_.min_points_size_)}}, + {1, {static_cast(config_.opt_points_size_)}}, + {1, {static_cast(config_.max_points_size_)}}), + autoware::tensorrt_common::ProfileDims( + "coors", {2, {config_.min_coors_size_, config_.min_coors_dim_size_}}, + {2, {config_.opt_coors_size_, config_.opt_coors_dim_size_}}, + {2, {config_.max_coors_size_, config_.max_coors_dim_size_}})}; + + auto network_io_ptr = + std::make_unique>(network_io); + auto profile_dims_ptr = + std::make_unique>(profile_dims); + + network_trt_ptr_ = std::make_unique(trt_config); + if (!network_trt_ptr_->setup(std::move(profile_dims_ptr), std::move(network_io_ptr))) + throw std::runtime_error("Failed to setup TRT engine."); +} + bool TransfusionTRT::detect( const sensor_msgs::msg::PointCloud2 & msg, const tf2_ros::Buffer & tf_buffer, std::vector & det_boxes3d, std::unordered_map & proc_timing) @@ -166,8 +210,9 @@ bool TransfusionTRT::preprocess( CHECK_CUDA_ERROR(cudaMemcpyAsync( ¶ms_input, params_input_d_.get(), sizeof(unsigned int), cudaMemcpyDeviceToHost, stream_)); CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); + auto params_input_i32 = static_cast(params_input); - if (params_input < config_.min_voxel_size_) { + if (params_input_i32 < config_.min_voxel_size_) { RCLCPP_WARN_STREAM( rclcpp::get_logger("lidar_transfusion"), "Too few voxels (" << params_input << ") for actual optimization profile (" @@ -185,39 +230,34 @@ bool TransfusionTRT::preprocess( params_input = config_.max_voxels_; } + RCLCPP_DEBUG_STREAM( rclcpp::get_logger("lidar_transfusion"), "Generated input voxels: " << params_input); - network_trt_ptr_->context->setTensorAddress( - network_trt_ptr_->getTensorName(NetworkIO::voxels), voxel_features_d_.get()); - network_trt_ptr_->context->setInputShape( - network_trt_ptr_->getTensorName(NetworkIO::voxels), + bool success = true; + + // Inputs + success &= network_trt_ptr_->setTensor( + "voxels", voxel_features_d_.get(), nvinfer1::Dims3{ - static_cast(params_input), static_cast(config_.max_num_points_per_pillar_), + params_input_i32, config_.max_num_points_per_pillar_, static_cast(config_.num_point_feature_size_)}); - network_trt_ptr_->context->setTensorAddress( - network_trt_ptr_->getTensorName(NetworkIO::num_points), voxel_num_d_.get()); - network_trt_ptr_->context->setInputShape( - network_trt_ptr_->getTensorName(NetworkIO::num_points), - nvinfer1::Dims{1, {static_cast(params_input)}}); - network_trt_ptr_->context->setTensorAddress( - network_trt_ptr_->getTensorName(NetworkIO::coors), voxel_idxs_d_.get()); - network_trt_ptr_->context->setInputShape( - network_trt_ptr_->getTensorName(NetworkIO::coors), - nvinfer1::Dims2{ - static_cast(params_input), static_cast(config_.num_point_values_)}); - network_trt_ptr_->context->setTensorAddress( - network_trt_ptr_->getTensorName(NetworkIO::cls_score), cls_output_d_.get()); - network_trt_ptr_->context->setTensorAddress( - network_trt_ptr_->getTensorName(NetworkIO::bbox_pred), box_output_d_.get()); - network_trt_ptr_->context->setTensorAddress( - network_trt_ptr_->getTensorName(NetworkIO::dir_pred), dir_cls_output_d_.get()); - return true; + success &= network_trt_ptr_->setTensor( + "num_points", voxel_num_d_.get(), nvinfer1::Dims{1, {params_input_i32}}); + success &= network_trt_ptr_->setTensor( + "coors", voxel_idxs_d_.get(), nvinfer1::Dims2{params_input_i32, config_.num_point_values_}); + + // Outputs + success &= network_trt_ptr_->setTensor("cls_score0", cls_output_d_.get()); + success &= network_trt_ptr_->setTensor("bbox_pred0", box_output_d_.get()); + success &= network_trt_ptr_->setTensor("dir_cls_pred0", dir_cls_output_d_.get()); + + return success; } bool TransfusionTRT::inference() { - auto status = network_trt_ptr_->context->enqueueV3(stream_); + auto status = network_trt_ptr_->enqueueV3(stream_); CHECK_CUDA_ERROR(cudaStreamSynchronize(stream_)); if (!status) { diff --git a/perception/autoware_lidar_transfusion/src/lidar_transfusion_node.cpp b/perception/autoware_lidar_transfusion/src/lidar_transfusion_node.cpp index 8bb70a821621f..563abd97698e0 100644 --- a/perception/autoware_lidar_transfusion/src/lidar_transfusion_node.cpp +++ b/perception/autoware_lidar_transfusion/src/lidar_transfusion_node.cpp @@ -75,7 +75,6 @@ LidarTransfusionNode::LidarTransfusionNode(const rclcpp::NodeOptions & options) const float score_threshold = static_cast(this->declare_parameter("score_threshold", descriptor)); - NetworkParam network_param(onnx_path, engine_path, trt_precision); DensificationParam densification_param( densification_world_frame_id, densification_num_past_frames); TransfusionConfig config( @@ -91,7 +90,9 @@ LidarTransfusionNode::LidarTransfusionNode(const rclcpp::NodeOptions & options) detection_class_remapper_.setParameters( allow_remapping_by_area_matrix, min_area_matrix, max_area_matrix); - detector_ptr_ = std::make_unique(network_param, densification_param, config); + auto trt_config = tensorrt_common::TrtCommonConfig(onnx_path, trt_precision, engine_path); + + detector_ptr_ = std::make_unique(trt_config, densification_param, config); cloud_sub_ = this->create_subscription( "~/input/pointcloud", rclcpp::SensorDataQoS{}.keep_last(1), @@ -155,7 +156,6 @@ void LidarTransfusionNode::cloudCallback(const sensor_msgs::msg::PointCloud2::Co objects_pub_->publish(output_msg); published_time_pub_->publish_if_subscribed(objects_pub_, output_msg.header.stamp); } - // add processing time for debug if (debug_publisher_ptr_ && stop_watch_ptr_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic", true); diff --git a/perception/autoware_shape_estimation/CMakeLists.txt b/perception/autoware_shape_estimation/CMakeLists.txt index d0eb2aa5535a8..d7313111e6ade 100644 --- a/perception/autoware_shape_estimation/CMakeLists.txt +++ b/perception/autoware_shape_estimation/CMakeLists.txt @@ -4,6 +4,9 @@ project(autoware_shape_estimation) find_package(autoware_cmake REQUIRED) autoware_package() +# TODO(amadeuszsz): Remove -Wno-deprecated-declarations once removing implicit quantization +add_compile_options(-Wno-deprecated-declarations) + find_package(PCL REQUIRED COMPONENTS common) find_package(pcl_conversions REQUIRED) diff --git a/perception/autoware_shape_estimation/include/autoware/shape_estimation/tensorrt_shape_estimator.hpp b/perception/autoware_shape_estimation/include/autoware/shape_estimation/tensorrt_shape_estimator.hpp index d39dce65d224d..4328246ff395f 100644 --- a/perception/autoware_shape_estimation/include/autoware/shape_estimation/tensorrt_shape_estimator.hpp +++ b/perception/autoware_shape_estimation/include/autoware/shape_estimation/tensorrt_shape_estimator.hpp @@ -48,11 +48,7 @@ class TrtShapeEstimator { public: TrtShapeEstimator( - const std::string & model_path, const std::string & precision, - const autoware::tensorrt_common::BatchConfig & batch_config, - const size_t max_workspace_size = (1 << 30), - const autoware::tensorrt_common::BuildConfig build_config = - autoware::tensorrt_common::BuildConfig("MinMax", -1, false, false, false, 0.0)); + const std::string & model_path, const std::string & precision, const int batch_size); ~TrtShapeEstimator() = default; diff --git a/perception/autoware_shape_estimation/lib/tensorrt_shape_estimator.cpp b/perception/autoware_shape_estimation/lib/tensorrt_shape_estimator.cpp index b4b1f18832da7..fa3c3cb09bad3 100644 --- a/perception/autoware_shape_estimation/lib/tensorrt_shape_estimator.cpp +++ b/perception/autoware_shape_estimation/lib/tensorrt_shape_estimator.cpp @@ -29,47 +29,41 @@ namespace autoware::shape_estimation { TrtShapeEstimator::TrtShapeEstimator( - const std::string & model_path, const std::string & precision, - const autoware::tensorrt_common::BatchConfig & batch_config, const size_t max_workspace_size, - const autoware::tensorrt_common::BuildConfig build_config) + const std::string & model_path, const std::string & precision, const int batch_size) { trt_common_ = std::make_unique( - model_path, precision, nullptr, batch_config, max_workspace_size, build_config); + tensorrt_common::TrtCommonConfig(model_path, precision)); + batch_size_ = batch_size; - trt_common_->setup(); - - if (!trt_common_->isInitialized()) { - std::cerr << "Failed to initialize TensorRT" << std::endl; - return; + if (!trt_common_->setup()) { + throw std::runtime_error("Failed to setup TensorRT"); } - const auto pc_input_dims = trt_common_->getBindingDimensions(0); + const auto pc_input_dims = trt_common_->getTensorShape(0); const auto pc_input_size = std::accumulate( pc_input_dims.d + 1, pc_input_dims.d + pc_input_dims.nbDims, 1, std::multiplies()); - input_pc_d_ = autoware::cuda_utils::make_unique(pc_input_size * batch_config[2]); - batch_size_ = batch_config[2]; - const auto one_hot_input_dims = trt_common_->getBindingDimensions(1); + input_pc_d_ = autoware::cuda_utils::make_unique(pc_input_size * batch_size_); + const auto one_hot_input_dims = trt_common_->getTensorShape(1); const auto one_hot_input_size = std::accumulate( one_hot_input_dims.d + 1, one_hot_input_dims.d + one_hot_input_dims.nbDims, 1, std::multiplies()); - input_one_hot_d_ = - autoware::cuda_utils::make_unique(one_hot_input_size * batch_config[2]); + input_one_hot_d_ = autoware::cuda_utils::make_unique(one_hot_input_size * batch_size_); - const auto stage1_center_out_dims = trt_common_->getBindingDimensions(2); + const auto stage1_center_out_dims = trt_common_->getTensorShape(2); out_s1center_elem_num_ = std::accumulate( stage1_center_out_dims.d + 1, stage1_center_out_dims.d + stage1_center_out_dims.nbDims, 1, std::multiplies()); - out_s1center_elem_num_ = out_s1center_elem_num_ * batch_config[2]; - out_s1center_elem_num_per_batch_ = static_cast(out_s1center_elem_num_ / batch_config[2]); + out_s1center_elem_num_ = out_s1center_elem_num_ * batch_size_; + out_s1center_elem_num_per_batch_ = static_cast(out_s1center_elem_num_ / batch_size_); out_s1center_prob_d_ = autoware::cuda_utils::make_unique(out_s1center_elem_num_); out_s1center_prob_h_ = autoware::cuda_utils::make_unique_host(out_s1center_elem_num_, cudaHostAllocPortable); - const auto pred_out_dims = trt_common_->getBindingDimensions(3); + const auto pred_out_dims = trt_common_->getTensorShape(3); out_pred_elem_num_ = std::accumulate( pred_out_dims.d + 1, pred_out_dims.d + pred_out_dims.nbDims, 1, std::multiplies()); - out_pred_elem_num_ = out_pred_elem_num_ * batch_config[2]; - out_pred_elem_num_per_batch_ = static_cast(out_pred_elem_num_ / batch_config[2]); + out_pred_elem_num_ = out_pred_elem_num_ * batch_size_; + out_pred_elem_num_per_batch_ = static_cast(out_pred_elem_num_ / batch_size_); out_pred_prob_d_ = autoware::cuda_utils::make_unique(out_pred_elem_num_); out_pred_prob_h_ = autoware::cuda_utils::make_unique_host(out_pred_elem_num_, cudaHostAllocPortable); @@ -83,10 +77,6 @@ TrtShapeEstimator::TrtShapeEstimator( bool TrtShapeEstimator::inference( const DetectedObjectsWithFeature & input, DetectedObjectsWithFeature & output) { - if (!trt_common_->isInitialized()) { - return false; - } - bool result = false; for (size_t i = 0; i < input.feature_objects.size(); i += batch_size_) { @@ -111,13 +101,13 @@ bool TrtShapeEstimator::inference( void TrtShapeEstimator::preprocess(const DetectedObjectsWithFeature & input) { - auto input_dims_pc = trt_common_->getBindingDimensions(0); + auto input_dims_pc = trt_common_->getTensorShape(0); int batch_size = static_cast(input.feature_objects.size()); const auto input_chan = static_cast(input_dims_pc.d[1]); const auto input_pc_size = static_cast(input_dims_pc.d[2]); - auto input_dims_one_hot = trt_common_->getBindingDimensions(1); + auto input_dims_one_hot = trt_common_->getTensorShape(1); const auto input_one_hot_size = static_cast(input_dims_one_hot.d[1]); int volume_pc = batch_size * input_chan * input_pc_size; @@ -229,7 +219,10 @@ bool TrtShapeEstimator::feed_forward_and_decode( int batch_size = static_cast(input.feature_objects.size()); std::vector buffers = { input_pc_d_.get(), input_one_hot_d_.get(), out_s1center_prob_d_.get(), out_pred_prob_d_.get()}; - trt_common_->enqueueV2(buffers.data(), *stream_, nullptr); + if (!trt_common_->setTensorsAddresses(buffers)) { + return false; + } + trt_common_->enqueueV3(*stream_); CHECK_CUDA_ERROR(cudaMemcpyAsync( out_s1center_prob_h_.get(), out_s1center_prob_d_.get(), out_s1center_elem_num_ * sizeof(float), diff --git a/perception/autoware_shape_estimation/src/shape_estimation_node.cpp b/perception/autoware_shape_estimation/src/shape_estimation_node.cpp index 67402f68d63ef..c5450dc14adb0 100644 --- a/perception/autoware_shape_estimation/src/shape_estimation_node.cpp +++ b/perception/autoware_shape_estimation/src/shape_estimation_node.cpp @@ -63,9 +63,8 @@ ShapeEstimationNode::ShapeEstimationNode(const rclcpp::NodeOptions & node_option min_points_ = declare_parameter("model_params.minimum_points"); std::string precision = declare_parameter("model_params.precision"); int batch_size = declare_parameter("model_params.batch_size"); - autoware::tensorrt_common::BatchConfig batch_config{batch_size, batch_size, batch_size}; tensorrt_shape_estimator_ = - std::make_unique(model_path, precision, batch_config); + std::make_unique(model_path, precision, batch_size); if (this->declare_parameter("model_params.build_only", false)) { RCLCPP_INFO(this->get_logger(), "TensorRT engine is built and shutdown node."); rclcpp::shutdown(); diff --git a/perception/autoware_tensorrt_classifier/CMakeLists.txt b/perception/autoware_tensorrt_classifier/CMakeLists.txt index 88747a1e9240c..59ce7b18afcc3 100644 --- a/perception/autoware_tensorrt_classifier/CMakeLists.txt +++ b/perception/autoware_tensorrt_classifier/CMakeLists.txt @@ -6,6 +6,9 @@ set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++17 -O3 -Wno-write-strings -fopen find_package(autoware_cmake REQUIRED) autoware_package() +# TODO(amadeuszsz): Remove -Wno-deprecated-declarations once removing implicit quantization +add_compile_options(-Wno-deprecated-declarations) + find_package(CUDA) find_package(CUDNN) find_package(TENSORRT) diff --git a/perception/autoware_tensorrt_classifier/include/autoware/tensorrt_classifier/tensorrt_classifier.hpp b/perception/autoware_tensorrt_classifier/include/autoware/tensorrt_classifier/tensorrt_classifier.hpp index ee16343b956d1..4f7a5865c72ae 100644 --- a/perception/autoware_tensorrt_classifier/include/autoware/tensorrt_classifier/tensorrt_classifier.hpp +++ b/perception/autoware_tensorrt_classifier/include/autoware/tensorrt_classifier/tensorrt_classifier.hpp @@ -19,6 +19,7 @@ #include #include #include +#include #include #include @@ -44,22 +45,18 @@ class TrtClassifier * @param[in] mode_path ONNX model_path * @param[in] precision precision for inference * @param[in] calibration_images path for calibration files (only require for quantization) - * @param[in] batch_config configuration for batched execution - * @param[in] max_workspace_size maximum workspace for building TensorRT engine * @param[in] mean mean for preprocess * @param[in] std std for preprocess - * @param[in] buildConfig configuration including precision, calibration method, dla, remaining - * fp16 for first layer, remaining fp16 for last layer and profiler for builder + * @param[in] calib_config calibration configuration * @param[in] cuda whether use cuda gpu for preprocessing */ TrtClassifier( const std::string & model_path, const std::string & precision, - const autoware::tensorrt_common::BatchConfig & batch_config = {1, 1, 1}, const std::vector & mean = {123.675, 116.28, 103.53}, const std::vector & std = {58.395, 57.12, 57.375}, - const size_t max_workspace_size = (1 << 30), const std::string & calibration_images = "", - const autoware::tensorrt_common::BuildConfig build_config = - autoware::tensorrt_common::BuildConfig("MinMax", -1, false, false, false, 0.0), + const std::string & calibration_images = "", + const tensorrt_common::CalibrationConfig & calibration_config = + tensorrt_common::CalibrationConfig("MinMax", false, false, 0.0), const bool cuda = false); /** * @brief Deconstruct TrtClassifier @@ -84,6 +81,12 @@ class TrtClassifier */ void initPreprocessBuffer(int width, int height); + /** + * @brief get batch size + * @return batch size + */ + [[nodiscard]] int getBatchSize() const; + private: /** * @brief run preprocess including resizing, letterbox, BGR2RGB, NHWC2NCHW and toFloat on CPU @@ -102,7 +105,7 @@ class TrtClassifier const std::vector & images, std::vector & results, std::vector & probabilities); - std::unique_ptr trt_common_; + std::unique_ptr trt_common_; std::vector input_h_; CudaUniquePtr input_d_; diff --git a/perception/autoware_tensorrt_classifier/src/tensorrt_classifier.cpp b/perception/autoware_tensorrt_classifier/src/tensorrt_classifier.cpp index 4aa008e42c966..7666ae4f9d068 100644 --- a/perception/autoware_tensorrt_classifier/src/tensorrt_classifier.cpp +++ b/perception/autoware_tensorrt_classifier/src/tensorrt_classifier.cpp @@ -100,11 +100,9 @@ std::vector loadImageList(const std::string & filename, const std:: namespace autoware::tensorrt_classifier { TrtClassifier::TrtClassifier( - const std::string & model_path, const std::string & precision, - const autoware::tensorrt_common::BatchConfig & batch_config, const std::vector & mean, - const std::vector & std, const size_t max_workspace_size, - const std::string & calibration_image_list_path, - autoware::tensorrt_common::BuildConfig build_config, const bool cuda) + const std::string & model_path, const std::string & precision, const std::vector & mean, + const std::vector & std, const std::string & calibration_image_list_path, + const tensorrt_common::CalibrationConfig & calib_config, const bool cuda) { src_width_ = -1; src_height_ = -1; @@ -114,22 +112,36 @@ TrtClassifier::TrtClassifier( for (size_t i = 0; i < inv_std_.size(); i++) { inv_std_[i] = 1.0 / inv_std_[i]; } - batch_size_ = batch_config[2]; + trt_common_ = std::make_unique( + tensorrt_common::TrtCommonConfig(model_path, precision)); + + const auto network_input_dims = trt_common_->getTensorShape(0); + batch_size_ = network_input_dims.d[0]; + const auto input_channel = network_input_dims.d[1]; + const auto input_height = network_input_dims.d[2]; + const auto input_width = network_input_dims.d[3]; + + std::vector profile_dims{ + autoware::tensorrt_common::ProfileDims( + 0, {4, {batch_size_, input_channel, input_height, input_width}}, + {4, {batch_size_, input_channel, input_height, input_width}}, + {4, {batch_size_, input_channel, input_height, input_width}})}; + auto profile_dims_ptr = + std::make_unique>(profile_dims); + if (precision == "int8") { - int max_batch_size = batch_config[2]; - nvinfer1::Dims input_dims = autoware::tensorrt_common::get_input_dims(model_path); std::vector calibration_images; if (calibration_image_list_path != "") { calibration_images = loadImageList(calibration_image_list_path, ""); } autoware::tensorrt_classifier::ImageStream stream( - max_batch_size, input_dims, calibration_images); + batch_size_, network_input_dims, calibration_images); fs::path calibration_table{model_path}; std::string ext = ""; - if (build_config.calib_type_str == "Entropy") { + if (calib_config.calib_type_str == "Entropy") { ext = "EntropyV2-"; } else if ( - build_config.calib_type_str == "Legacy" || build_config.calib_type_str == "Percentile") { + calib_config.calib_type_str == "Legacy" || calib_config.calib_type_str == "Percentile") { ext = "Legacy-"; } else { ext = "MinMax-"; @@ -141,11 +153,11 @@ TrtClassifier::TrtClassifier( histogram_table.replace_extension(ext); std::unique_ptr calibrator; - if (build_config.calib_type_str == "Entropy") { + if (calib_config.calib_type_str == "Entropy") { calibrator.reset(new autoware::tensorrt_classifier::Int8EntropyCalibrator( stream, calibration_table, mean_, std_)); } else if ( - build_config.calib_type_str == "Legacy" || build_config.calib_type_str == "Percentile") { + calib_config.calib_type_str == "Legacy" || calib_config.calib_type_str == "Percentile") { double quantile = 0.999999; double cutoff = 0.999999; calibrator.reset(new autoware::tensorrt_classifier::Int8LegacyCalibrator( @@ -154,29 +166,27 @@ TrtClassifier::TrtClassifier( calibrator.reset(new autoware::tensorrt_classifier::Int8MinMaxCalibrator( stream, calibration_table, mean_, std_)); } - trt_common_ = std::make_unique( - model_path, precision, std::move(calibrator), batch_config, max_workspace_size, build_config); + if (!trt_common_->setupWithCalibrator( + std::move(calibrator), calib_config, std::move((profile_dims_ptr)))) { + throw std::runtime_error("Failed to setup TensorRT engine with calibrator"); + } } else { - trt_common_ = std::make_unique( - model_path, precision, nullptr, batch_config, max_workspace_size, build_config); - } - trt_common_->setup(); - - if (!trt_common_->isInitialized()) { - return; + if (!trt_common_->setup(std::move(profile_dims_ptr))) { + throw std::runtime_error("Failed to setup TensorRT engine"); + } } // GPU memory allocation - const auto input_dims = trt_common_->getBindingDimensions(0); + const auto input_dims = trt_common_->getTensorShape(0); const auto input_size = std::accumulate(input_dims.d + 1, input_dims.d + input_dims.nbDims, 1, std::multiplies()); - const auto output_dims = trt_common_->getBindingDimensions(1); - input_d_ = autoware::cuda_utils::make_unique(batch_config[2] * input_size); + const auto output_dims = trt_common_->getTensorShape(1); + input_d_ = autoware::cuda_utils::make_unique(batch_size_ * input_size); out_elem_num_ = std::accumulate( output_dims.d + 1, output_dims.d + output_dims.nbDims, 1, std::multiplies()); - out_elem_num_ = out_elem_num_ * batch_config[2]; - out_elem_num_per_batch_ = static_cast(out_elem_num_ / batch_config[2]); + out_elem_num_ = out_elem_num_ * batch_size_; + out_elem_num_per_batch_ = static_cast(out_elem_num_ / batch_size_); out_prob_d_ = autoware::cuda_utils::make_unique(out_elem_num_); out_prob_h_ = autoware::cuda_utils::make_unique_host(out_elem_num_, cudaHostAllocPortable); @@ -224,7 +234,7 @@ void TrtClassifier::initPreprocessBuffer(int width, int height) src_width_ = width; src_height_ = height; if (m_cuda) { - auto input_dims = trt_common_->getBindingDimensions(0); + auto input_dims = trt_common_->getTensorShape(0); bool const hasRuntimeDim = std::any_of( input_dims.d, input_dims.d + input_dims.nbDims, [](int32_t input_dim) { return input_dim == -1; }); @@ -232,7 +242,9 @@ void TrtClassifier::initPreprocessBuffer(int width, int height) input_dims.d[0] = batch_size_; } if (!h_img_) { - trt_common_->setBindingDimensions(0, input_dims); + if (!trt_common_->setInputShape(0, input_dims)) { + return; + } } if (!h_img_) { CHECK_CUDA_ERROR(cudaMallocHost( @@ -245,10 +257,15 @@ void TrtClassifier::initPreprocessBuffer(int width, int height) } } +int TrtClassifier::getBatchSize() const +{ + return batch_size_; +} + void TrtClassifier::preprocessGpu(const std::vector & images) { const auto batch_size = images.size(); - auto input_dims = trt_common_->getBindingDimensions(0); + auto input_dims = trt_common_->getTensorShape(0); input_dims.d[0] = batch_size; for (const auto & image : images) { @@ -272,7 +289,9 @@ void TrtClassifier::preprocessGpu(const std::vector & images) src_height_ = height; } if (!h_img_) { - trt_common_->setBindingDimensions(0, input_dims); + if (!trt_common_->setInputShape(0, input_dims)) { + return; + } } const float input_height = static_cast(input_dims.d[2]); const float input_width = static_cast(input_dims.d[3]); @@ -305,9 +324,11 @@ void TrtClassifier::preprocessGpu(const std::vector & images) void TrtClassifier::preprocess_opt(const std::vector & images) { int batch_size = static_cast(images.size()); - auto input_dims = trt_common_->getBindingDimensions(0); + auto input_dims = trt_common_->getTensorShape(0); input_dims.d[0] = batch_size; - trt_common_->setBindingDimensions(0, input_dims); + if (!trt_common_->setInputShape(0, input_dims)) { + return; + } const float input_chan = static_cast(input_dims.d[1]); const float input_height = static_cast(input_dims.d[2]); const float input_width = static_cast(input_dims.d[3]); @@ -354,9 +375,6 @@ bool TrtClassifier::doInference( const std::vector & images, std::vector & results, std::vector & probabilities) { - if (!trt_common_->isInitialized()) { - return false; - } preprocess_opt(images); return feedforwardAndDecode(images, results, probabilities); @@ -369,7 +387,10 @@ bool TrtClassifier::feedforwardAndDecode( results.clear(); probabilities.clear(); std::vector buffers = {input_d_.get(), out_prob_d_.get()}; - trt_common_->enqueueV2(buffers.data(), *stream_, nullptr); + if (!trt_common_->setTensorsAddresses(buffers)) { + return false; + } + trt_common_->enqueueV3(*stream_); int batch_size = static_cast(images.size()); diff --git a/perception/autoware_tensorrt_common/CMakeLists.txt b/perception/autoware_tensorrt_common/CMakeLists.txt index 3105523a509e3..d7d8026866124 100644 --- a/perception/autoware_tensorrt_common/CMakeLists.txt +++ b/perception/autoware_tensorrt_common/CMakeLists.txt @@ -16,9 +16,14 @@ if(NOT (CUDAToolkit_FOUND AND CUDNN_FOUND AND TENSORRT_FOUND)) return() endif() +if(TENSORRT_VERSION VERSION_LESS 8.5) + message(WARNING "Unsupported version TensorRT ${TENSORRT_VERSION} detected. This package requires TensorRT 8.5 or later.") + return() +endif() + add_library(${PROJECT_NAME} SHARED src/tensorrt_common.cpp - src/simple_profiler.cpp + src/profiler.cpp ) target_link_libraries(${PROJECT_NAME} @@ -42,7 +47,7 @@ set_target_properties(${PROJECT_NAME} CXX_EXTENSIONS NO ) -# TODO(autoware_tensorrt_common): Remove -Wno-deprecated-declarations once upgrading to TensorRT 8.5 is complete +# TODO(amadeuszsz): Remove -Wno-deprecated-declarations once removing implicit quantization target_compile_options(${PROJECT_NAME} PRIVATE -Wall -Wextra -Wpedantic -Werror -Wno-deprecated-declarations ) diff --git a/perception/autoware_tensorrt_common/README.md b/perception/autoware_tensorrt_common/README.md index c828be58c1c1c..54bfccdfcb561 100644 --- a/perception/autoware_tensorrt_common/README.md +++ b/perception/autoware_tensorrt_common/README.md @@ -1,6 +1,70 @@ # autoware_tensorrt_common -## Purpose +This package provides a high-level API to work with TensorRT. This library simplifies the process of loading, building, and executing TensorRT inference engines using ONNX models. It also includes utilities for profiling and managing TensorRT execution contexts, making it easier to integrate TensorRT-based packages in Autoware. -This package contains a library of common functions related to TensorRT. -This package may include functions for handling TensorRT engine and calibration algorithm used for quantization +## Usage + +Here is an example usage of the library. For the full API documentation, please refer to the doxygen documentation (see header [file](include/autoware/tensorrt_common/tensorrt_common.hpp)). + +```c++ +#include + +#include +#include +#include + +using autoware::tensorrt_common::TrtCommon; +using autoware::tensorrt_common::TrtCommonConfig; +using autoware::tensorrt_common::TensorInfo; +using autoware::tensorrt_common::NetworkIO; +using autoware::tensorrt_common::ProfileDims; + +std::unique_ptr trt_common_; +``` + +### Create a tensorrt common instance and setup engine + +- With minimal configuration. + +```c++ +trt_common_ = std::make_unique(TrtCommonConfig("/path/to/onnx/model.onnx")); +trt_common_->setup(); +``` + +- With full configuration. + +```c++ +trt_common_ = std::make_unique(TrtCommonConfig("/path/to/onnx/model.onnx", "fp16", "/path/to/engine/model.engine", (1ULL << 30U), -1, false)); + +std::vector network_io{ + NetworkIO("sample_input", {3, {-1, 64, 512}}), NetworkIO("sample_output", {1, {50}})}; +std::vector profile_dims{ + ProfileDims("sample_input", {3, {1, 64, 512}}, {3, {3, 64, 512}}, {3, {9, 64, 512}})}; + +auto network_io_ptr = std::make_unique>(network_io); +auto profile_dims_ptr = std::make_unique>(profile_dims); + +trt_common_->setup(std::move(profile_dims_ptr), std::move(network_io_ptr)); +``` + +By defining network IO names and dimensions, an extra shapes validation will be performed after building / loading engine. This is useful to ensure the model is compatible with current code for preprocessing as it might consists of operations dependent on tensor shapes. + +Profile dimension is used to specify the min, opt, and max dimensions for dynamic shapes. + +Network IO or / and profile dimensions can be omitted if not needed. + +### Setting input and output tensors + +```c++ +bool success = true; +success &= trt_common_->setTensor("sample_input", sample_input_d_.get(), nvinfer1::Dims{3, {var_size, 64, 512}}); +success &= trt_common_->setTensor("sample_output", sample_output_d_.get()); +return success; +``` + +### Execute inference + +```c++ +auto success = trt_common_->enqueueV3(stream_); +return success; +``` diff --git a/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/conv_profiler.hpp b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/conv_profiler.hpp new file mode 100644 index 0000000000000..0b58a797d8b9b --- /dev/null +++ b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/conv_profiler.hpp @@ -0,0 +1,108 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__TENSORRT_COMMON__CONV_PROFILER_HPP_ +#define AUTOWARE__TENSORRT_COMMON__CONV_PROFILER_HPP_ + +#include + +#include + +#include +#include +#include + +namespace autoware +{ +namespace tensorrt_common +{ +/** + * @struct ConvLayerInfo + * @brief Information of a layer. + */ +struct ConvLayerInfo +{ + //! @brief Input channel. + int in_c; + //! @brief Output channel. + int out_c; + //! @brief Width. + int w; + //! @brief Height. + int h; + //! @brief Kernel size. + int k; + //! @brief Stride. + int stride; + //! @brief Number of groups. + int groups; + //! @brief Layer type. + nvinfer1::LayerType type; +}; + +/** + * @class ConvProfiler + * @brief Collect per-layer profile information, assuming times are reported in the same order. + */ +class ConvProfiler : public tensorrt_common::Profiler +{ +public: + /** + * @brief Construct Profiler for convolutional layers. + * + * @param[in] src_profilers Source profilers to merge. + */ + explicit ConvProfiler( + const std::vector & src_profilers = std::vector()) + : Profiler(src_profilers) + { + } + + /** + * @brief Set per-layer profile information for model. + * + * @param[in] layer Layer to set profile information. + */ + void setProfDict(nvinfer1::ILayer * const layer) noexcept final + { + if (const auto type = layer->getType(); type == nvinfer1::LayerType::kCONVOLUTION) { + const auto name = layer->getName(); + auto conv = dynamic_cast(layer); + + nvinfer1::ITensor * in = layer->getInput(0); + nvinfer1::Dims in_dim = in->getDimensions(); + + nvinfer1::ITensor * out = layer->getOutput(0); + nvinfer1::Dims out_dim = out->getDimensions(); + + nvinfer1::Dims k_dims = conv->getKernelSizeNd(); + nvinfer1::Dims s_dims = conv->getStrideNd(); + + int32_t kernel = k_dims.d[0]; + int32_t stride = s_dims.d[0]; + int32_t groups = conv->getNbGroups(); + + layer_dict_.insert_or_assign( + name, ConvLayerInfo{ + in_dim.d[1], out_dim.d[1], in_dim.d[3], in_dim.d[2], kernel, stride, groups, type}); + } + } + +private: + //! @brief Per-layer information. + std::map layer_dict_; +}; +} // namespace tensorrt_common +} // namespace autoware +#endif // AUTOWARE__TENSORRT_COMMON__CONV_PROFILER_HPP_ diff --git a/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/logger.hpp b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/logger.hpp index 5aa897983af72..b9b9048cd8204 100644 --- a/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/logger.hpp +++ b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/logger.hpp @@ -17,18 +17,19 @@ #ifndef AUTOWARE__TENSORRT_COMMON__LOGGER_HPP_ #define AUTOWARE__TENSORRT_COMMON__LOGGER_HPP_ -#include "NvInferRuntimeCommon.h" +#include #include #include +#include #include #include -#include #include #include #include #include #include +#include namespace autoware { @@ -46,7 +47,7 @@ class LogStreamConsumerBuffer : public std::stringbuf LogStreamConsumerBuffer(LogStreamConsumerBuffer && other) : mOutput(other.mOutput) {} - ~LogStreamConsumerBuffer() + ~LogStreamConsumerBuffer() override { // std::streambuf::pbase() gives a pointer to the beginning of the buffered part of the output // sequence std::streambuf::pptr() gives a pointer to the current position of the output @@ -60,7 +61,7 @@ class LogStreamConsumerBuffer : public std::stringbuf // synchronizes the stream buffer and returns 0 on success // synchronizing the stream buffer consists of inserting the buffer contents into the stream, // resetting the buffer and flushing the stream - virtual int sync() + int sync() override { putOutput(); return 0; @@ -252,6 +253,37 @@ class Logger : public nvinfer1::ILogger // NOLINT } } + void log(Severity severity, const char * msg, ...) const noexcept + { + if (mVerbose) { + va_list args; + va_start(args, msg); + + // Buffer size + va_list args_copy; + va_copy(args_copy, args); + int required_size = std::vsnprintf(nullptr, 0, msg, args_copy); + va_end(args_copy); + + // Formatting error + if (required_size < 0) { + log(Severity::kINTERNAL_ERROR, "Error formatting log message"); + va_end(args); + return; + } + + // Format msg + std::vector buffer(required_size + 1); + std::vsnprintf(buffer.data(), buffer.size(), msg, args); + + va_end(args); // End variadic argument processing + + // Send the formatted message to LogStreamConsumer + LogStreamConsumer(mReportableSeverity, severity) + << "[TRT] " << std::string(buffer.data()) << std::endl; + } + } + /** * @brief Logging with throttle. * diff --git a/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/profiler.hpp b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/profiler.hpp new file mode 100644 index 0000000000000..d45351f97fd01 --- /dev/null +++ b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/profiler.hpp @@ -0,0 +1,96 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__TENSORRT_COMMON__PROFILER_HPP_ +#define AUTOWARE__TENSORRT_COMMON__PROFILER_HPP_ + +#include + +#include +#include +#include +#include + +namespace autoware +{ +namespace tensorrt_common +{ + +/** + * @class Profiler + * @brief Collect per-layer profile information, assuming times are reported in the same order. + */ +class Profiler : public nvinfer1::IProfiler +{ +public: + /** + * @struct Record + * @brief Record of layer profile information. + */ + struct Record + { + float time{0}; + int count{0}; + float min_time{-1.0}; + int index; + }; + + /** + * @brief Construct Profiler. + * + * @param[in] src_profilers Source profilers to merge. + */ + explicit Profiler(const std::vector & src_profilers = std::vector()); + + /** + * @brief Report layer time. + * + * @param[in] layerName Layer name. + * @param[in] ms Time in milliseconds. + */ + void reportLayerTime(const char * layerName, float ms) noexcept final; + + /** + * @brief Get printable representation of Profiler. + * + * @return String representation for current state of Profiler. + */ + [[nodiscard]] std::string toString() const; + + /** + * @brief Set per-layer profile information for model. + * + * @param[in] layer Layer to set profile information. + */ + virtual void setProfDict([[maybe_unused]] nvinfer1::ILayer * layer) noexcept {}; + + /** + * @brief Output Profiler to ostream. + * + * @param[out] out Output stream. + * @param[in] value Profiler to output. + * @return Output stream. + */ + friend std::ostream & operator<<(std::ostream & out, const Profiler & value); + +private: + //!< @brief Profile information for layers. + std::map profile_; + + //!< @brief Index for layer. + int index_; +}; +} // namespace tensorrt_common +} // namespace autoware +#endif // AUTOWARE__TENSORRT_COMMON__PROFILER_HPP_ diff --git a/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/simple_profiler.hpp b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/simple_profiler.hpp deleted file mode 100644 index a8d504fb2861a..0000000000000 --- a/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/simple_profiler.hpp +++ /dev/null @@ -1,73 +0,0 @@ -// Copyright 2023 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__TENSORRT_COMMON__SIMPLE_PROFILER_HPP_ -#define AUTOWARE__TENSORRT_COMMON__SIMPLE_PROFILER_HPP_ - -#include - -#include -#include -#include -#include - -namespace autoware -{ -namespace tensorrt_common -{ -struct LayerInfo -{ - int in_c; - int out_c; - int w; - int h; - int k; - int stride; - int groups; - nvinfer1::LayerType type; -}; - -/** - * @class Profiler - * @brief Collect per-layer profile information, assuming times are reported in the same order - */ -class SimpleProfiler : public nvinfer1::IProfiler -{ -public: - struct Record - { - float time{0}; - int count{0}; - float min_time{-1.0}; - int index; - }; - SimpleProfiler( - std::string name, - const std::vector & src_profilers = std::vector()); - - void reportLayerTime(const char * layerName, float ms) noexcept override; - - void setProfDict(nvinfer1::ILayer * layer) noexcept; - - friend std::ostream & operator<<(std::ostream & out, const SimpleProfiler & value); - -private: - std::string m_name; - std::map m_profile; - int m_index; - std::map m_layer_dict; -}; -} // namespace tensorrt_common -} // namespace autoware -#endif // AUTOWARE__TENSORRT_COMMON__SIMPLE_PROFILER_HPP_ diff --git a/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/tensorrt_common.hpp b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/tensorrt_common.hpp index 2b3b3f02f315f..9355732962e23 100644 --- a/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/tensorrt_common.hpp +++ b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/tensorrt_common.hpp @@ -15,226 +15,367 @@ #ifndef AUTOWARE__TENSORRT_COMMON__TENSORRT_COMMON_HPP_ #define AUTOWARE__TENSORRT_COMMON__TENSORRT_COMMON_HPP_ -#ifndef YOLOX_STANDALONE -#include - -#include -#endif +#include "autoware/tensorrt_common/logger.hpp" +#include "autoware/tensorrt_common/profiler.hpp" +#include "autoware/tensorrt_common/utils.hpp" #include #include -#if (defined(_MSC_VER) or (defined(__GNUC__) and (7 <= __GNUC_MAJOR__))) -#include -namespace fs = ::std::filesystem; -#else -#include -namespace fs = ::std::experimental::filesystem; -#endif - -#include -#include - #include -#include #include +#include +#include #include namespace autoware { namespace tensorrt_common { -/** - * @struct BuildConfig - * @brief Configuration to provide fine control regarding TensorRT builder - */ -struct BuildConfig -{ - // type for calibration - std::string calib_type_str; - - // DLA core ID that the process uses - int dla_core_id; - - // flag for partial quantization in first layer - bool quantize_first_layer; // For partial quantization - - // flag for partial quantization in last layer - bool quantize_last_layer; // For partial quantization - - // flag for per-layer profiler using IProfiler - bool profile_per_layer; - - // clip value for implicit quantization - double clip_value; // For implicit quantization - - // Supported calibration type - const std::array valid_calib_type = {"Entropy", "Legacy", "Percentile", "MinMax"}; - - BuildConfig() - : calib_type_str("MinMax"), - dla_core_id(-1), - quantize_first_layer(false), - quantize_last_layer(false), - profile_per_layer(false), - clip_value(0.0) - { - } - - explicit BuildConfig( - const std::string & calib_type_str, const int dla_core_id = -1, - const bool quantize_first_layer = false, const bool quantize_last_layer = false, - const bool profile_per_layer = false, const double clip_value = 0.0) - : calib_type_str(calib_type_str), - dla_core_id(dla_core_id), - quantize_first_layer(quantize_first_layer), - quantize_last_layer(quantize_last_layer), - profile_per_layer(profile_per_layer), - clip_value(clip_value) - { -#ifndef YOLOX_STANDALONE - if ( - std::find(valid_calib_type.begin(), valid_calib_type.end(), calib_type_str) == - valid_calib_type.end()) { - std::stringstream message; - message << "Invalid calibration type was specified: " << calib_type_str << std::endl - << "Valid value is one of: [Entropy, (Legacy | Percentile), MinMax]" << std::endl - << "Default calibration type will be used: MinMax" << std::endl; - std::cerr << message.str(); - } -#endif - } -}; - -nvinfer1::Dims get_input_dims(const std::string & onnx_file_path); - -const std::array valid_precisions = {"fp32", "fp16", "int8"}; -bool is_valid_precision_string(const std::string & precision); - template struct InferDeleter // NOLINT { - void operator()(T * obj) const - { - if (obj) { -#if TENSORRT_VERSION_MAJOR >= 8 - delete obj; -#else - obj->destroy(); -#endif - } - } + void operator()(T * obj) const { delete obj; } }; template using TrtUniquePtr = std::unique_ptr>; -using BatchConfig = std::array; +using NetworkIOPtr = std::unique_ptr>; +using ProfileDimsPtr = std::unique_ptr>; +using TensorsVec = std::vector>; +using TensorsMap = std::unordered_map>; /** * @class TrtCommon - * @brief TensorRT common library + * @brief TensorRT common library. */ class TrtCommon // NOLINT { public: /** * @brief Construct TrtCommon. - * @param[in] mode_path ONNX model_path - * @param[in] precision precision for inference - * @param[in] calibrator pointer for any type of INT8 calibrator - * @param[in] batch_config configuration for batched execution - * @param[in] max_workspace_size maximum workspace for building TensorRT engine - * @param[in] buildConfig configuration including precision, calibration method, dla, remaining - * fp16 for first layer, remaining fp16 for last layer and profiler for builder - * @param[in] plugin_paths path for custom plugin + * + * @param[in] trt_config Base configuration with ONNX model path as minimum required. + * parameter. + * @param[in] profiler Per-layer profiler. + * @param[in] plugin_paths Paths for TensorRT plugins. */ TrtCommon( - const std::string & model_path, const std::string & precision, - std::unique_ptr calibrator = nullptr, - const BatchConfig & batch_config = {1, 1, 1}, const size_t max_workspace_size = (16 << 20), - const BuildConfig & buildConfig = BuildConfig(), + const TrtCommonConfig & trt_config, + const std::shared_ptr & profiler = std::make_shared(), const std::vector & plugin_paths = {}); - /** * @brief Deconstruct TrtCommon */ ~TrtCommon(); /** - * @brief Load TensorRT engine - * @param[in] engine_file_path path for a engine file - * @return flag for whether loading are succeeded or failed + * @brief Setup for TensorRT execution including building and loading engine. + * + * @param[in] profile_dims Optimization profile of tensors for dynamic shapes. + * @param[in] network_io Network input/output tensors information. + * @return Whether setup is successful. + */ + [[nodiscard]] virtual bool setup( + ProfileDimsPtr profile_dims = nullptr, NetworkIOPtr network_io = nullptr); + + /** + * @brief Get TensorRT engine precision. + * + * @return string representation of TensorRT engine precision. + */ + [[nodiscard]] std::string getPrecision() const; + + /** + * @brief Get tensor name by index from TensorRT engine with fallback from TensorRT network. + * + * @param[in] index Tensor index. + * @return Tensor name. + */ + [[nodiscard]] const char * getIOTensorName(const int32_t index) const; + + /** + * @brief Get number of IO tensors from TensorRT engine with fallback from TensorRT network. + * + * @return Number of IO tensors. + */ + [[nodiscard]] int32_t getNbIOTensors() const; + + /** + * @brief Get tensor shape by index from TensorRT engine with fallback from TensorRT network. + * + * @param[in] index Tensor index. + * @return Tensor shape. + */ + [[nodiscard]] nvinfer1::Dims getTensorShape(const int32_t index) const; + + /** + * @brief Get tensor shape by name from TensorRT engine. + * + * @param[in] tensor_name Tensor name. + * @return Tensor shape. + */ + [[nodiscard]] nvinfer1::Dims getTensorShape(const char * tensor_name) const; + + /** + * @brief Get input tensor shape by index from TensorRT network. + * + * @param[in] index Tensor index. + * @return Tensor shape. + */ + [[nodiscard]] nvinfer1::Dims getInputDims(const int32_t index) const; + + /** + * @brief Get output tensor shape by index from TensorRT network. + * + * @param[in] index Tensor index. + * @return Tensor shape. + */ + [[nodiscard]] nvinfer1::Dims getOutputDims(const int32_t index) const; + + /** + * @brief Set tensor address by index via TensorRT context. + * + * @param[in] index Tensor index. + * @param[in] data Tensor pointer. + * @return Whether setting tensor address is successful. + */ + bool setTensorAddress(const int32_t index, void * data); + + /** + * @brief Set tensor address by name via TensorRT context. + * + * @param[in] tensor_name Tensor name. + * @param[in] data Tensor pointer. + * @return Whether setting tensor address is successful. + */ + bool setTensorAddress(const char * tensor_name, void * data); + + /** + * @brief Set tensors addresses by indices via TensorRT context. + * + * @param[in] tensors Tensors pointers. + * @return Whether setting tensors addresses is successful. + */ + bool setTensorsAddresses(std::vector & tensors); + + /** + * @brief Set tensors addresses by names via TensorRT context. + * + * @param[in] tensors Tensors pointers. + * @return Whether setting tensors addresses is successful. + */ + bool setTensorsAddresses(std::unordered_map & tensors); + + /** + * @brief Set input shape by index via TensorRT context. + * + * @param[in] index Tensor index. + * @param[in] dimensions Tensor dimensions. + * @return Whether setting input shape is successful. + */ + bool setInputShape(const int32_t index, const nvinfer1::Dims & dimensions); + + /** + * @brief Set input shape by name via TensorRT context. + * + * @param[in] tensor_name Tensor name. + * @param[in] dimensions Tensor dimensions. + * @return Whether setting input shape is successful. + */ + bool setInputShape(const char * tensor_name, const nvinfer1::Dims & dimensions); + + /** + * @brief Set inputs shapes by indices via TensorRT context. + * + * @param[in] dimensions Vector of tensor dimensions with corresponding indices. + * @return Whether setting input shapes is successful. + */ + bool setInputsShapes(const std::vector & dimensions); + + /** + * @brief Set inputs shapes by names via TensorRT context. + * + * @param[in] dimensions Map of tensor dimensions with corresponding names as keys. + * @return Whether setting input shapes is successful. + */ + bool setInputsShapes(const std::unordered_map & dimensions); + + /** + * @brief Set tensor (address and shape) by index via TensorRT context. + * + * @param[in] index Tensor index. + * @param[in] data Tensor pointer. + * @param[in] dimensions Tensor dimensions. + * @return Whether setting tensor is successful. + */ + bool setTensor(const int32_t index, void * data, nvinfer1::Dims dimensions = {}); + + /** + * @brief Set tensor (address and shape) by name via TensorRT context. + * + * @param[in] tensor_name Tensor name. + * @param[in] data Tensor pointer. + * @param[in] dimensions Tensor dimensions. + * @return Whether setting tensor is successful. + */ + bool setTensor(const char * tensor_name, void * data, nvinfer1::Dims dimensions = {}); + + /** + * @brief Set tensors (addresses and shapes) by indices via TensorRT context. + * + * @param[in] tensors Vector of tensor pointers and dimensions with corresponding indices. + * @return Whether setting tensors is successful. */ - bool loadEngine(const std::string & engine_file_path); + bool setTensors(TensorsVec & tensors); /** - * @brief Output layer information including GFLOPs and parameters - * @param[in] onnx_file_path path for a onnx file - * @warning This function is based on darknet log. + * @brief Set tensors (addresses and shapes) by names via TensorRT context. + * + * @param[in] tensors Map of tensor pointers and dimensions with corresponding names as keys. + * @return Whether setting tensors is successful. */ - void printNetworkInfo(const std::string & onnx_file_path); + bool setTensors(TensorsMap & tensors); /** - * @brief build TensorRT engine from ONNX - * @param[in] onnx_file_path path for a onnx file - * @param[in] output_engine_file_path path for a engine file + * @brief Get per-layer profiler for model. + * + * @return Per-layer profiler. */ - bool buildEngineFromOnnx( - const std::string & onnx_file_path, const std::string & output_engine_file_path); + [[nodiscard]] std::shared_ptr getModelProfiler(); /** - * @brief setup for TensorRT execution including building and loading engine + * @brief Get per-layer profiler for host. + * + * @return Per-layer profiler. */ - void setup(); + [[nodiscard]] std::shared_ptr getHostProfiler(); -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8500 - void setupBindings(std::vector & bindings); -#endif + /** + * @brief Get TensorRT common configuration. + * + * @return TensorRT common configuration. + */ + [[nodiscard]] std::shared_ptr getTrtCommonConfig(); - bool isInitialized(); + /** + * @brief Get TensorRT builder configuration. + * + * @return TensorRT builder configuration. + */ + [[nodiscard]] std::shared_ptr getBuilderConfig(); + + /** + * @brief Get TensorRT network definition. + * + * @return TensorRT network definition. + */ + [[nodiscard]] std::shared_ptr getNetwork(); - nvinfer1::Dims getBindingDimensions(const int32_t index) const; - int32_t getNbBindings(); - bool setBindingDimensions(const int32_t index, const nvinfer1::Dims & dimensions) const; -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8500 + /** + * @brief Get TensorRT logger. + * + * @return TensorRT logger. + */ + [[nodiscard]] std::shared_ptr getLogger(); + + /** + * @brief Execute inference via TensorRT context. + * + * @param[in] stream CUDA stream. + * @return Whether inference is successful. + */ bool enqueueV3(cudaStream_t stream); -#endif -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH < 10000 - bool enqueueV2(void ** bindings, cudaStream_t stream, cudaEvent_t * input_consumed); -#endif /** - * @brief output per-layer information + * @brief Print per-layer information. + */ + void printProfiling() const; + +private: + /** + * @brief Initialize TensorRT common. + * + * @return Whether initialization is successful. */ - void printProfiling(void); + [[nodiscard]] bool initialize(); -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8200 /** - * @brief get per-layer information for trt-engine-profiler + * @brief Get per-layer information for trt-engine-profiler. + * + * @param[in] format Format for layer information. + * @return Layer information. */ std::string getLayerInformation(nvinfer1::LayerInformationFormat format); -#endif -private: - Logger logger_; - fs::path model_file_path_; + /** + + * @brief Build TensorRT engine from ONNX. + * + * @return Whether building engine is successful. + */ + bool buildEngineFromOnnx(); + + /** + * @brief Load TensorRT engine. + * + * @return Whether loading engine is successful. + */ + bool loadEngine(); + + /** + * @brief Validate network input/output names and dimensions. + * + * @return Whether network input/output is valid. + */ + bool validateNetworkIO(); + + /** + * @brief Validate optimization profile. + * + * @return Whether optimization profile is valid. + */ + bool validateProfileDims(); + + //! @brief TensorRT runtime. TrtUniquePtr runtime_; + + //! @brief TensorRT engine. TrtUniquePtr engine_; + + //! @brief TensorRT execution context. TrtUniquePtr context_; - std::unique_ptr calibrator_; - std::string precision_; - BatchConfig batch_config_; - size_t max_workspace_size_; - bool is_initialized_{false}; + //! @brief TensorRT builder. + TrtUniquePtr builder_; + + //! @brief TensorRT engine parser. + TrtUniquePtr parser_; + + //! @brief TensorRT builder configuration. + std::shared_ptr builder_config_; + + //! @brief TensorRT network definition. + std::shared_ptr network_; + + //! @brief TrtCommon library base configuration. + std::shared_ptr trt_config_; + + //! @brief TensorRT logger. + std::shared_ptr logger_; + + //! @brief Per-layer profiler for host. + std::shared_ptr host_profiler_; + + //! @brief Per-layer profiler for model. + std::shared_ptr model_profiler_; - // profiler for per-layer - SimpleProfiler model_profiler_; - // profiler for whole model - SimpleProfiler host_profiler_; + //! @brief Model optimization profile. + ProfileDimsPtr profile_dims_; - std::unique_ptr build_config_; + //! @brief Model network input/output tensors information. + NetworkIOPtr network_io_; }; } // namespace tensorrt_common diff --git a/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/tensorrt_conv_calib.hpp b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/tensorrt_conv_calib.hpp new file mode 100644 index 0000000000000..44a944031086e --- /dev/null +++ b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/tensorrt_conv_calib.hpp @@ -0,0 +1,241 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__TENSORRT_COMMON__TENSORRT_CONV_CALIB_HPP_ +#define AUTOWARE__TENSORRT_COMMON__TENSORRT_CONV_CALIB_HPP_ + +#include +#include +#include + +#include + +#include +#include +#include +#include + +namespace autoware +{ +namespace tensorrt_common +{ +template +bool contain(const std::string & s, const T & v) +{ + return s.find(v) != std::string::npos; +} + +using autoware::tensorrt_common::CalibrationConfig; +using autoware::tensorrt_common::NetworkIOPtr; +using autoware::tensorrt_common::ProfileDimsPtr; +using autoware::tensorrt_common::Profiler; +using autoware::tensorrt_common::TrtCommonConfig; + +/** + * @class TrtConvCalib + * @brief TensorRT common library with calibration. + */ +class TrtConvCalib : public tensorrt_common::TrtCommon +{ +public: + /** + * @brief Construct TrtCommonCalib. + * + * @param[in] trt_config base trt common configuration, ONNX model path is mandatory + * @param[in] profiler per-layer profiler + * @param[in] plugin_paths paths for TensorRT plugins + */ + explicit TrtConvCalib( + const TrtCommonConfig & trt_config, + const std::shared_ptr & profiler = std::make_shared(), + const std::vector & plugin_paths = {}) + : TrtCommon(trt_config, profiler, plugin_paths) + { + } + + /** + * @brief Setup for TensorRT execution including calibration, building and loading engine. + * + * @param[in] calibrator Pointer for any type of INT8 calibrator. + * @param[in] calib_config Calibration configuration. + * @param[in] profile_dims Optimization profile of input tensors for dynamic shapes. + * @param[in] network_io Network input/output tensors information. + * @return Whether setup is successful. + */ + [[nodiscard]] bool setupWithCalibrator( + std::unique_ptr calibrator, const CalibrationConfig & calib_config, + ProfileDimsPtr profile_dims = nullptr, NetworkIOPtr network_io = nullptr) + { + calibrator_ = std::move(calibrator); + calib_config_ = std::make_unique(calib_config); + + auto builder_config = getBuilderConfig(); + builder_config->setFlag(nvinfer1::BuilderFlag::kPREFER_PRECISION_CONSTRAINTS); + builder_config->setInt8Calibrator(calibrator_.get()); + + // Model specific quantization + auto logger = getLogger(); + auto quantization_log = quantization(); + logger->log(nvinfer1::ILogger::Severity::kINFO, quantization_log.c_str()); + + return setup(std::move(profile_dims), std::move(network_io)); + } + +private: + /** + * @brief Implicit quantization for TensorRT. + * + * @return Output log for TensorRT logger. + */ + std::string quantization() + { + auto network = getNetwork(); + auto trt_config = getTrtCommonConfig(); + auto model_profiler = getModelProfiler(); + + const int num = network->getNbLayers(); + bool first = calib_config_->quantize_first_layer; + bool last = calib_config_->quantize_last_layer; + std::stringstream ss; + + // Partial Quantization + if (getPrecision() == "int8") { + auto builder_config = getBuilderConfig(); + builder_config->setFlag(nvinfer1::BuilderFlag::kFP16); + network->getInput(0)->setDynamicRange(0, 255.0); + for (int i = 0; i < num; i++) { + nvinfer1::ILayer * layer = network->getLayer(i); + auto layer_type = layer->getType(); + std::string name = layer->getName(); + nvinfer1::ITensor * out = layer->getOutput(0); + if (calib_config_->clip_value > 0.0) { + ss << "Set max value for outputs: " << calib_config_->clip_value << " " << name + << std::endl; + out->setDynamicRange(0.0, calib_config_->clip_value); + } + + if (layer_type == nvinfer1::LayerType::kCONVOLUTION) { + if (first) { + layer->setPrecision(nvinfer1::DataType::kHALF); + ss << "Set kHALF in " << name << std::endl; + first = false; + } + if (last) { + // cspell: ignore preds + if ( + contain(name, "reg_preds") || contain(name, "cls_preds") || + contain(name, "obj_preds")) { + layer->setPrecision(nvinfer1::DataType::kHALF); + ss << "Set kHALF in " << name << std::endl; + } + for (int j = num - 1; j >= 0; j--) { + nvinfer1::ILayer * inner_layer = network->getLayer(j); + auto inner_layer_type = inner_layer->getType(); + std::string inner_name = inner_layer->getName(); + if (inner_layer_type == nvinfer1::LayerType::kCONVOLUTION) { + inner_layer->setPrecision(nvinfer1::DataType::kHALF); + ss << "Set kHALF in " << inner_name << std::endl; + break; + } + if (inner_layer_type == nvinfer1::LayerType::kMATRIX_MULTIPLY) { + inner_layer->setPrecision(nvinfer1::DataType::kHALF); + ss << "Set kHALF in " << inner_name << std::endl; + break; + } + } + } + } + } + builder_config->setFlag(nvinfer1::BuilderFlag::kINT8); + } + + // Print layer information + float total_gflops = 0.0; + int total_params = 0; + + for (int i = 0; i < num; i++) { + nvinfer1::ILayer * layer = network->getLayer(i); + auto layer_type = layer->getType(); + if (trt_config->profile_per_layer) { + model_profiler->setProfDict(layer); + } + if (layer_type == nvinfer1::LayerType::kCONSTANT) { + continue; + } + nvinfer1::ITensor * in = layer->getInput(0); + nvinfer1::Dims dim_in = in->getDimensions(); + nvinfer1::ITensor * out = layer->getOutput(0); + nvinfer1::Dims dim_out = out->getDimensions(); + + if (layer_type == nvinfer1::LayerType::kCONVOLUTION) { + auto conv = dynamic_cast(layer); + nvinfer1::Dims k_dims = conv->getKernelSizeNd(); + nvinfer1::Dims s_dims = conv->getStrideNd(); + int groups = conv->getNbGroups(); + int stride = s_dims.d[0]; + int num_weights = (dim_in.d[1] / groups) * dim_out.d[1] * k_dims.d[0] * k_dims.d[1]; + float gflops = (2.0 * num_weights) * (static_cast(dim_in.d[3]) / stride * + static_cast(dim_in.d[2]) / stride / 1e9); + total_gflops += gflops; + total_params += num_weights; + ss << "L" << i << " [conv " << k_dims.d[0] << "x" << k_dims.d[1] << " (" << groups << ") " + << ") " << "/" << s_dims.d[0] << "] " << dim_in.d[3] << "x" << dim_in.d[2] << "x" + << " -> " << dim_out.d[3] << "x" << dim_out.d[2] << "x" << dim_out.d[1]; + ss << " weights:" << num_weights; + ss << " GFLOPs:" << gflops; + ss << std::endl; + } else if (layer_type == nvinfer1::LayerType::kPOOLING) { + auto pool = dynamic_cast(layer); + auto p_type = pool->getPoolingType(); + nvinfer1::Dims dim_stride = pool->getStrideNd(); + nvinfer1::Dims dim_window = pool->getWindowSizeNd(); + + ss << "L" << i << " ["; + if (p_type == nvinfer1::PoolingType::kMAX) { + ss << "max "; + } else if (p_type == nvinfer1::PoolingType::kAVERAGE) { + ss << "avg "; + } else if (p_type == nvinfer1::PoolingType::kMAX_AVERAGE_BLEND) { + ss << "max avg blend "; + } + float gflops = static_cast(dim_in.d[1]) * + (static_cast(dim_window.d[0]) / static_cast(dim_stride.d[0])) * + (static_cast(dim_window.d[1]) / static_cast(dim_stride.d[1])) * + static_cast(dim_in.d[2]) * static_cast(dim_in.d[3]) / 1e9; + total_gflops += gflops; + ss << "pool " << dim_window.d[0] << "x" << dim_window.d[1] << "]"; + ss << " GFLOPs:" << gflops; + ss << std::endl; + } else if (layer_type == nvinfer1::LayerType::kRESIZE) { + ss << "L" << i << " [resize]" << std::endl; + } + } + ss << "Total " << total_gflops << " GFLOPs" << std::endl; + ss << "Total " << total_params / 1000.0 / 1000.0 << " M params" << std::endl; + + return ss.str(); + }; + +private: + //!< Calibration configuration + std::unique_ptr calib_config_; + + //!< Calibrator used for implicit quantization + std::unique_ptr calibrator_; +}; + +} // namespace tensorrt_common +} // namespace autoware + +#endif // AUTOWARE__TENSORRT_COMMON__TENSORRT_CONV_CALIB_HPP_ diff --git a/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/utils.hpp b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/utils.hpp new file mode 100644 index 0000000000000..be640f52147d9 --- /dev/null +++ b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/utils.hpp @@ -0,0 +1,408 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__TENSORRT_COMMON__UTILS_HPP_ +#define AUTOWARE__TENSORRT_COMMON__UTILS_HPP_ + +#include +#include + +#if (defined(_MSC_VER) or (defined(__GNUC__) and (7 <= __GNUC_MAJOR__))) +#include +namespace fs = ::std::filesystem; +#else +#include +namespace fs = ::std::experimental::filesystem; +#endif + +#include +#include +#include +#include +#include +#include +#include + +namespace autoware +{ +namespace tensorrt_common +{ +constexpr std::array valid_precisions = {"fp32", "fp16", "int8"}; + +/** + * @struct TrtCommonConfig + * @brief Configuration to provide fine control regarding TensorRT builder + */ +struct TrtCommonConfig +{ + /** @brief Construct TrtCommonConfig, ONNX model path is mandatory. + * + * @param[in] onnx_path ONNX model path + * @param[in] precision precision for inference + * @param[in] engine_path TensorRT engine path + * @param[in] max_workspace_size maximum workspace size for TensorRT + * @param[in] dla_core_id DLA core ID + * @param[in] profile_per_layer flag for per-layer profiler using IProfiler + */ + explicit TrtCommonConfig( + const std::string onnx_path, const std::string precision = "fp16", + const std::string engine_path = "", const size_t max_workspace_size = (1ULL << 30U), + const int32_t dla_core_id = -1, const bool profile_per_layer = false) + : onnx_path(onnx_path), + precision(precision), + engine_path(engine_path), + max_workspace_size(max_workspace_size), + dla_core_id(dla_core_id), + profile_per_layer(profile_per_layer) + { + validatePrecision(); + + if (engine_path.empty()) { + this->engine_path = onnx_path; + this->engine_path.replace_extension(".engine"); + } + } + + /** + * @brief Validate configured TensorRT engine precision. + */ + void validatePrecision() const + { + if ( + std::find(valid_precisions.begin(), valid_precisions.end(), precision) == + valid_precisions.end()) { + std::stringstream message; + message << "Invalid precision was specified: " << precision << std::endl + << "Valid string is one of: [" << valid_precisions[0]; + for (size_t i = 1; i < valid_precisions.size(); ++i) { + message << ", " << valid_precisions[i]; + } + message << "] (case sensitive)" << std::endl; + + throw std::runtime_error(message.str()); + } + } + + //!< @brief ONNX model path. + const fs::path onnx_path; + + //!< @brief Precision for inference. + const std::string precision; + + //!< @brief TensorRT engine path. + fs::path engine_path; + + //!< @brief TensorRT max workspace size. + const size_t max_workspace_size; + + //!< @brief DLA core ID that the process uses. + const int32_t dla_core_id; + + //!< @brief Flag for per-layer profiler using IProfiler. + const bool profile_per_layer; +}; + +/** + * @brief Represents a tensor with its name or index. + */ +struct TensorInfo +{ + /** + * @brief Construct TensorInfo with tensor name. + * + * @param[in] name Tensor name. + */ + explicit TensorInfo(std::string name) : tensor_name(std::move(name)), tensor_index(-1) {} + + /** + * @brief Construct TensorInfo with tensor index. + * + * @param[in] index Tensor index. + */ + explicit TensorInfo(int32_t index) : tensor_index(index) {} + + /** + * @brief Check if dimensions are equal. + * + * @param lhs Left-hand side tensor dimensions. + * @param rhs Right-hand side tensor dimensions. + * @return Whether dimensions are equal. + */ + static bool dimsEqual(const nvinfer1::Dims & lhs, const nvinfer1::Dims & rhs) + { + if (lhs.nbDims != rhs.nbDims) return false; + return std::equal(lhs.d, lhs.d + lhs.nbDims, rhs.d); // NOLINT + } + + /** + * @brief Get printable representation of tensor dimensions. + * + * @param[in] dims Tensor dimensions. + * @return String representation of tensor dimensions. + */ + static std::string dimsRepr(const nvinfer1::Dims & dims) + { + if (dims.nbDims == 0) return "[]"; + std::string repr = "[" + std::to_string(dims.d[0]); + for (int i = 1; i < dims.nbDims; ++i) { + repr += ", " + std::to_string(dims.d[i]); + } + repr += "]"; + return repr; + } + + //!< @brief Tensor name. + std::string tensor_name; + + //!< @brief Tensor index. + int32_t tensor_index; +}; + +/** + * @brief Represents a network input/output tensor with its dimensions. + * + * Example usage: + * @code + * nvinfer1::Dims tensor_dims = {3, {1, 2, 3}}; + * NetworkIO input("input_tensor", tensor_dims); + * NetworkIO output("output_tensor", tensor_dims); + * bool is_equal = input == output; // false + * @endcode + */ +struct NetworkIO : public TensorInfo +{ + /** + * @brief Construct NetworkIO with tensor name and dimensions. + * + * @param[in] name Tensor name. + * @param[in] tensor_dims Tensor dimensions. + */ + NetworkIO(std::string name, const nvinfer1::Dims & tensor_dims) + : TensorInfo(std::move(name)), dims(tensor_dims) + { + } + + /** + * @brief Construct NetworkIO with tensor index and dimensions. + * + * @param[in] index Tensor index. + * @param[in] tensor_dims Tensor dimensions. + */ + NetworkIO(int32_t index, const nvinfer1::Dims & tensor_dims) + : TensorInfo(index), dims(tensor_dims) + { + } + + /** + * @brief Get printable representation of NetworkIO. + * + * @return String representation of NetworkIO. + */ + [[nodiscard]] std::string toString() const + { + std::stringstream ss; + ss << tensor_name << " {" << TensorInfo::dimsRepr(dims) << "}"; + return ss.str(); + } + + /** + * @brief Check if NetworkIO is equal to another NetworkIO. + * + * @param rhs Right-hand side NetworkIO. + * @return Whether NetworkIO is equal to another NetworkIO. + */ + bool operator==(const NetworkIO & rhs) const + { + if (tensor_name != rhs.tensor_name) return false; + return dimsEqual(dims, rhs.dims); + } + + /** + * @brief Check if NetworkIO is not equal to another NetworkIO. + * + * @param rhs Right-hand side NetworkIO. + * @return Whether NetworkIO is not equal to another NetworkIO. + */ + bool operator!=(const NetworkIO & rhs) const { return !(*this == rhs); } + + /** + * @brief Output NetworkIO to ostream. + * + * @param os Output stream. + * @param io NetworkIO. + * @return Output stream. + */ + friend std::ostream & operator<<(std::ostream & os, const NetworkIO & io) + { + os << io.toString(); + return os; + } + + //!< @brief Tensor dimensions. + nvinfer1::Dims dims; +}; + +/** + * @brief Represents a tensor optimization profile with minimum, optimal, and maximum dimensions. + * + * Example usage: + * @code + * nvinfer1::Dims min = {3, {1, 2, 3}}; + * nvinfer1::Dims opt = {3, {1, 3, 4}}; + * nvinfer1::Dims max = {3, {1, 4, 5}}; + * ProfileDims entry_1("tensor_name", min, opt, max); + * ProfileDims entry_2("tensor_name", {3, {1, 2, 3}}, {3, {1, 3, 4}}, {3, {1, 4, 5}}); + * bool is_equal = entry_1 == entry_2; // true + * @endcode + */ +struct ProfileDims : public TensorInfo +{ + /** + * @brief Construct ProfileDims with tensor name and dimensions. + * + * @param[in] name Tensor name. + * @param[in] min Minimum dimensions for optimization profile. + * @param[in] opt Optimal dimensions for optimization profile. + * @param[in] max Maximum dimensions for optimization profile. + */ + ProfileDims( + std::string name, const nvinfer1::Dims & min, const nvinfer1::Dims & opt, + const nvinfer1::Dims & max) + : TensorInfo(std::move(name)), min_dims(min), opt_dims(opt), max_dims(max) + { + } + + /** + * @brief Construct ProfileDims with tensor index and dimensions. + * + * @param[in] index Tensor index. + * @param[in] min Minimum dimensions for optimization profile. + * @param[in] opt Optimal dimensions for optimization profile. + * @param[in] max Maximum dimensions for optimization profile. + */ + ProfileDims( + int32_t index, const nvinfer1::Dims & min, const nvinfer1::Dims & opt, + const nvinfer1::Dims & max) + : TensorInfo(index), min_dims(min), opt_dims(opt), max_dims(max) + { + } + + /** + * @brief Get printable representation of ProfileDims. + * + * @return String representation of ProfileDims. + */ + [[nodiscard]] std::string toString() const + { + std::ostringstream oss; + oss << tensor_name << " {min " << TensorInfo::dimsRepr(min_dims) << ", opt " + << TensorInfo::dimsRepr(opt_dims) << ", max " << TensorInfo::dimsRepr(max_dims) << "}"; + return oss.str(); + } + + /** + * @brief Check if ProfileDims is equal to another ProfileDims. + * + * @param rhs Right-hand side ProfileDims. + * @return Whether ProfileDims is equal to another ProfileDims. + */ + bool operator==(const ProfileDims & rhs) const + { + if (tensor_name != rhs.tensor_name) return false; + return dimsEqual(min_dims, rhs.min_dims) && dimsEqual(opt_dims, rhs.opt_dims) && + dimsEqual(max_dims, rhs.max_dims); + } + + /** + * @brief Check if ProfileDims is not equal to another ProfileDims. + * + * @param rhs Right-hand side ProfileDims. + * @return Whether ProfileDims is not equal to another ProfileDims. + */ + bool operator!=(const ProfileDims & rhs) const { return !(*this == rhs); } + + /** + * @brief Output ProfileDims to ostream. + * + * @param os Output stream. + * @param profile ProfileDims. + * @return Output stream. + */ + friend std::ostream & operator<<(std::ostream & os, const ProfileDims & profile) + { + os << profile.toString(); + return os; + } + + //!< @brief Minimum dimensions for optimization profile. + nvinfer1::Dims min_dims; + + //!< @brief Optimal dimensions for optimization profile. + nvinfer1::Dims opt_dims; + + //!< @brief Maximum dimensions for optimization profile. + nvinfer1::Dims max_dims; +}; + +//!< @brief Valid calibration types for TensorRT. +constexpr std::array valid_calib_type = { + "Entropy", "Legacy", "Percentile", "MinMax"}; + +/** + * @brief Configuration for implicit calibration. + */ +struct CalibrationConfig +{ + /** + * @brief Construct CalibrationConfig with its parameters. + * + * @param[in] calib_type_str Calibration type. + * @param[in] quantize_first_layer Flag for partial quantization in first layer. + * @param[in] quantize_last_layer Flag for partial quantization in last layer. + * @param[in] clip_value Clip value for implicit quantization. + */ + explicit CalibrationConfig( + const std::string & calib_type_str = "MinMax", const bool quantize_first_layer = false, + const bool quantize_last_layer = false, const double clip_value = 0.0) + : calib_type_str(calib_type_str), + quantize_first_layer(quantize_first_layer), + quantize_last_layer(quantize_last_layer), + clip_value(clip_value) + { + if ( + std::find(valid_calib_type.begin(), valid_calib_type.end(), calib_type_str) == + valid_calib_type.end()) { + throw std::runtime_error( + "Invalid calibration type was specified: " + std::string(calib_type_str) + + "\nValid value is one of: [Entropy, (Legacy | Percentile), MinMax]"); + } + } + + //!< @brief type of calibration + const std::string calib_type_str; + + //!< @brief flag for partial quantization in first layer + const bool quantize_first_layer; + + //!< @brief flag for partial quantization in last layer + const bool quantize_last_layer; + + //!< @brief clip value for implicit quantization + const double clip_value; +}; + +} // namespace tensorrt_common +} // namespace autoware + +#endif // AUTOWARE__TENSORRT_COMMON__UTILS_HPP_ diff --git a/perception/autoware_tensorrt_common/src/profiler.cpp b/perception/autoware_tensorrt_common/src/profiler.cpp new file mode 100644 index 0000000000000..433cca51f2b4f --- /dev/null +++ b/perception/autoware_tensorrt_common/src/profiler.cpp @@ -0,0 +1,113 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include +#include +#include +#include + +namespace autoware +{ +namespace tensorrt_common +{ + +Profiler::Profiler(const std::vector & src_profilers) +{ + index_ = 0; + for (const auto & src_profiler : src_profilers) { + for (const auto & [name, record] : src_profiler.profile_) { + auto it = profile_.find(name); + if (it == profile_.end()) { + profile_.emplace(name, record); + } else { + it->second.time += record.time; + it->second.count += record.count; + } + } + } +} + +void Profiler::reportLayerTime(const char * layerName, float ms) noexcept +{ + if (profile_.find(layerName) == profile_.end()) { + return; + } + profile_[layerName].count++; + profile_[layerName].time += ms; + if (profile_[layerName].min_time == -1.0) { + profile_[layerName].min_time = ms; + profile_[layerName].index = index_; + index_++; + } else if (profile_[layerName].min_time > ms) { + profile_[layerName].min_time = ms; + } +} + +std::string Profiler::toString() const +{ + std::ostringstream out; + float total_time = 0.0; + std::string layer_name = "Operation"; + + int max_layer_name_length = static_cast(layer_name.size()); + for (const auto & elem : profile_) { + total_time += elem.second.time; + max_layer_name_length = std::max(max_layer_name_length, static_cast(elem.first.size())); + } + + auto old_settings = out.flags(); + auto old_precision = out.precision(); + // Output header + { + out << "index, " << std::setw(12); + out << std::setw(max_layer_name_length) << layer_name << " "; + out << std::setw(12) << "Runtime" << "%," << " "; + out << std::setw(12) << "Invocations" << " , "; + out << std::setw(12) << "Runtime[ms]" << " , "; + out << std::setw(12) << "Avg Runtime[ms]" << " ,"; + out << std::setw(12) << "Min Runtime[ms]" << std::endl; + } + int index = index_; + for (int i = 0; i < index; i++) { + for (const auto & elem : profile_) { + if (elem.second.index == i) { + out << i << ", "; + out << std::setw(max_layer_name_length) << elem.first << ","; + out << std::setw(12) << std::fixed << std::setprecision(1) + << (elem.second.time * 100.0F / total_time) << "%" << ","; + out << std::setw(12) << elem.second.count << ","; + out << std::setw(12) << std::fixed << std::setprecision(2) << elem.second.time << ", "; + out << std::setw(12) << std::fixed << std::setprecision(2) + << elem.second.time / elem.second.count << ", "; + out << std::setw(12) << std::fixed << std::setprecision(2) << elem.second.min_time + << std::endl; + } + } + } + out.flags(old_settings); + out.precision(old_precision); + out << "========== total runtime = " << total_time << " ms ==========" << std::endl; + + return out.str(); +} + +std::ostream & operator<<(std::ostream & out, const Profiler & value) +{ + out << value.toString(); + return out; +} +} // namespace tensorrt_common +} // namespace autoware diff --git a/perception/autoware_tensorrt_common/src/simple_profiler.cpp b/perception/autoware_tensorrt_common/src/simple_profiler.cpp deleted file mode 100644 index 2bcc1c4f9da06..0000000000000 --- a/perception/autoware_tensorrt_common/src/simple_profiler.cpp +++ /dev/null @@ -1,138 +0,0 @@ -// Copyright 2023 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include - -#include -#include -#include -#include - -namespace autoware -{ -namespace tensorrt_common -{ - -SimpleProfiler::SimpleProfiler(std::string name, const std::vector & src_profilers) -: m_name(name) -{ - m_index = 0; - for (const auto & src_profiler : src_profilers) { - for (const auto & rec : src_profiler.m_profile) { - auto it = m_profile.find(rec.first); - if (it == m_profile.end()) { - m_profile.insert(rec); - } else { - it->second.time += rec.second.time; - it->second.count += rec.second.count; - } - } - } -} - -void SimpleProfiler::reportLayerTime(const char * layerName, float ms) noexcept -{ - m_profile[layerName].count++; - m_profile[layerName].time += ms; - if (m_profile[layerName].min_time == -1.0) { - m_profile[layerName].min_time = ms; - m_profile[layerName].index = m_index; - m_index++; - } else if (m_profile[layerName].min_time > ms) { - m_profile[layerName].min_time = ms; - } -} - -void SimpleProfiler::setProfDict(nvinfer1::ILayer * layer) noexcept -{ - std::string name = layer->getName(); - m_layer_dict[name]; - m_layer_dict[name].type = layer->getType(); - if (layer->getType() == nvinfer1::LayerType::kCONVOLUTION) { - nvinfer1::IConvolutionLayer * conv = (nvinfer1::IConvolutionLayer *)layer; - nvinfer1::ITensor * in = layer->getInput(0); - nvinfer1::Dims dim_in = in->getDimensions(); - nvinfer1::ITensor * out = layer->getOutput(0); - nvinfer1::Dims dim_out = out->getDimensions(); - nvinfer1::Dims k_dims = conv->getKernelSizeNd(); - nvinfer1::Dims s_dims = conv->getStrideNd(); - int groups = conv->getNbGroups(); - int stride = s_dims.d[0]; - int kernel = k_dims.d[0]; - m_layer_dict[name].in_c = dim_in.d[1]; - m_layer_dict[name].out_c = dim_out.d[1]; - m_layer_dict[name].w = dim_in.d[3]; - m_layer_dict[name].h = dim_in.d[2]; - m_layer_dict[name].k = kernel; - ; - m_layer_dict[name].stride = stride; - m_layer_dict[name].groups = groups; - } -} - -std::ostream & operator<<(std::ostream & out, const SimpleProfiler & value) -{ - out << "========== " << value.m_name << " profile ==========" << std::endl; - float totalTime = 0; - std::string layerNameStr = "Operation"; - - int maxLayerNameLength = static_cast(layerNameStr.size()); - for (const auto & elem : value.m_profile) { - totalTime += elem.second.time; - maxLayerNameLength = std::max(maxLayerNameLength, static_cast(elem.first.size())); - } - - auto old_settings = out.flags(); - auto old_precision = out.precision(); - // Output header - { - out << "index, " << std::setw(12); - out << std::setw(maxLayerNameLength) << layerNameStr << " "; - out << std::setw(12) << "Runtime" - << "%," - << " "; - out << std::setw(12) << "Invocations" - << " , "; - out << std::setw(12) << "Runtime[ms]" - << " , "; - out << std::setw(12) << "Avg Runtime[ms]" - << " ,"; - out << std::setw(12) << "Min Runtime[ms]" << std::endl; - } - int index = value.m_index; - for (int i = 0; i < index; i++) { - for (const auto & elem : value.m_profile) { - if (elem.second.index == i) { - out << i << ", "; - out << std::setw(maxLayerNameLength) << elem.first << ","; - out << std::setw(12) << std::fixed << std::setprecision(1) - << (elem.second.time * 100.0F / totalTime) << "%" - << ","; - out << std::setw(12) << elem.second.count << ","; - out << std::setw(12) << std::fixed << std::setprecision(2) << elem.second.time << ", "; - out << std::setw(12) << std::fixed << std::setprecision(2) - << elem.second.time / elem.second.count << ", "; - out << std::setw(12) << std::fixed << std::setprecision(2) << elem.second.min_time - << std::endl; - } - } - } - out.flags(old_settings); - out.precision(old_precision); - out << "========== " << value.m_name << " total runtime = " << totalTime - << " ms ==========" << std::endl; - return out; -} -} // namespace tensorrt_common -} // namespace autoware diff --git a/perception/autoware_tensorrt_common/src/tensorrt_common.cpp b/perception/autoware_tensorrt_common/src/tensorrt_common.cpp index 990433ee277a0..ba422277416ab 100644 --- a/perception/autoware_tensorrt_common/src/tensorrt_common.cpp +++ b/perception/autoware_tensorrt_common/src/tensorrt_common.cpp @@ -12,102 +12,38 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include "autoware/tensorrt_common/tensorrt_common.hpp" +#include "autoware/tensorrt_common/logger.hpp" +#include "autoware/tensorrt_common/utils.hpp" + +#include #include +#include #include +#include #include -#include #include #include #include +#include #include #include -namespace -{ -template -bool contain(const std::string & s, const T & v) -{ - return s.find(v) != std::string::npos; -} -} // anonymous namespace - namespace autoware { namespace tensorrt_common { -nvinfer1::Dims get_input_dims(const std::string & onnx_file_path) -{ - Logger logger_; - auto builder = TrtUniquePtr(nvinfer1::createInferBuilder(logger_)); - if (!builder) { - logger_.log(nvinfer1::ILogger::Severity::kERROR, "Fail to create builder"); - } - - const auto explicitBatch = - 1U << static_cast(nvinfer1::NetworkDefinitionCreationFlag::kEXPLICIT_BATCH); - - auto network = - TrtUniquePtr(builder->createNetworkV2(explicitBatch)); - if (!network) { - logger_.log(nvinfer1::ILogger::Severity::kERROR, "Fail to create network"); - } - - auto config = TrtUniquePtr(builder->createBuilderConfig()); - if (!config) { - logger_.log(nvinfer1::ILogger::Severity::kERROR, "Fail to create builder config"); - } - - auto parser = TrtUniquePtr(nvonnxparser::createParser(*network, logger_)); - if (!parser->parseFromFile( - onnx_file_path.c_str(), static_cast(nvinfer1::ILogger::Severity::kERROR))) { - logger_.log(nvinfer1::ILogger::Severity::kERROR, "Failed to parse onnx file"); - } - - const auto input = network->getInput(0); - return input->getDimensions(); -} - -bool is_valid_precision_string(const std::string & precision) -{ - if ( - std::find(valid_precisions.begin(), valid_precisions.end(), precision) == - valid_precisions.end()) { - std::stringstream message; - message << "Invalid precision was specified: " << precision << std::endl - << "Valid string is one of: ["; - for (const auto & s : valid_precisions) { - message << s << ", "; - } - message << "] (case sensitive)" << std::endl; - std::cerr << message.str(); - return false; - } else { - return true; - } -} TrtCommon::TrtCommon( - const std::string & model_path, const std::string & precision, - std::unique_ptr calibrator, const BatchConfig & batch_config, - const size_t max_workspace_size, const BuildConfig & build_config, + const TrtCommonConfig & trt_config, const std::shared_ptr & profiler, const std::vector & plugin_paths) -: model_file_path_(model_path), - calibrator_(std::move(calibrator)), - precision_(precision), - batch_config_(batch_config), - max_workspace_size_(max_workspace_size), - model_profiler_("Model"), - host_profiler_("Host") +: trt_config_(std::make_shared(trt_config)), + host_profiler_(profiler), + model_profiler_(profiler) { - // Check given precision is valid one - if (!is_valid_precision_string(precision)) { - return; - } - build_config_ = std::make_unique(build_config); - + logger_ = std::make_shared(); for (const auto & plugin_path : plugin_paths) { int32_t flags{RTLD_LAZY}; // cspell: ignore asan @@ -120,523 +56,595 @@ TrtCommon::TrtCommon( #endif // ENABLE_ASAN void * handle = dlopen(plugin_path.c_str(), flags); if (!handle) { - logger_.log(nvinfer1::ILogger::Severity::kERROR, "Could not load plugin library"); + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Could not load plugin library"); + } else { + logger_->log( + nvinfer1::ILogger::Severity::kINFO, "Loaded plugin library: %s", plugin_path.c_str()); } } - runtime_ = TrtUniquePtr(nvinfer1::createInferRuntime(logger_)); - if (build_config_->dla_core_id != -1) { - runtime_->setDLACore(build_config_->dla_core_id); + runtime_ = TrtUniquePtr(nvinfer1::createInferRuntime(*logger_)); + if (trt_config_->dla_core_id != -1) { + runtime_->setDLACore(trt_config_->dla_core_id); } - initLibNvInferPlugins(&logger_, ""); -} + initLibNvInferPlugins(&*logger_, ""); -TrtCommon::~TrtCommon() -{ + if (!initialize()) { + throw std::runtime_error("Failed to initialize TensorRT"); + } } -void TrtCommon::setup() +TrtCommon::~TrtCommon() = default; + +bool TrtCommon::setup(ProfileDimsPtr profile_dims, NetworkIOPtr network_io) { - if (!fs::exists(model_file_path_)) { - is_initialized_ = false; - return; - } - // cppcheck-suppress unreadVariable - std::string engine_path = model_file_path_; - if (model_file_path_.extension() == ".engine") { - std::cout << "Load ... " << model_file_path_ << std::endl; - loadEngine(model_file_path_); - } else if (model_file_path_.extension() == ".onnx") { - fs::path cache_engine_path{model_file_path_}; - std::string ext; - std::string calib_name = ""; - if (precision_ == "int8") { - if (build_config_->calib_type_str == "Entropy") { - calib_name = "EntropyV2-"; - } else if ( - build_config_->calib_type_str == "Legacy" || - build_config_->calib_type_str == "Percentile") { - calib_name = "Legacy-"; - } else { - calib_name = "MinMax-"; + profile_dims_ = std::move(profile_dims); + network_io_ = std::move(network_io); + + // Set input profile + if (profile_dims_ && !profile_dims_->empty()) { + auto profile = builder_->createOptimizationProfile(); + for (auto & profile_dim : *profile_dims_) { + if (profile_dim.tensor_name.empty()) { + profile_dim.tensor_name = getIOTensorName(profile_dim.tensor_index); } + logger_->log( + nvinfer1::ILogger::Severity::kINFO, "Setting optimization profile for tensor: %s", + profile_dim.toString().c_str()); + profile->setDimensions( + profile_dim.tensor_name.c_str(), nvinfer1::OptProfileSelector::kMIN, profile_dim.min_dims); + profile->setDimensions( + profile_dim.tensor_name.c_str(), nvinfer1::OptProfileSelector::kOPT, profile_dim.opt_dims); + profile->setDimensions( + profile_dim.tensor_name.c_str(), nvinfer1::OptProfileSelector::kMAX, profile_dim.max_dims); } - if (build_config_->dla_core_id != -1) { - ext = "DLA" + std::to_string(build_config_->dla_core_id) + "-" + calib_name + precision_; - if (build_config_->quantize_first_layer) { - ext += "-firstFP16"; - } - if (build_config_->quantize_last_layer) { - ext += "-lastFP16"; - } - ext += "-batch" + std::to_string(batch_config_[0]) + ".engine"; - } else { - ext = calib_name + precision_; - if (build_config_->quantize_first_layer) { - ext += "-firstFP16"; - } - if (build_config_->quantize_last_layer) { - ext += "-lastFP16"; - } - ext += "-batch" + std::to_string(batch_config_[0]) + ".engine"; + builder_config_->addOptimizationProfile(profile); + } + + auto build_engine_with_log = [this]() -> bool { + logger_->log(nvinfer1::ILogger::Severity::kINFO, "Starting to build engine"); + auto log_thread = logger_->log_throttle( + nvinfer1::ILogger::Severity::kINFO, + "Applying optimizations and building TensorRT CUDA engine. Please wait for a few minutes...", + 5); + auto success = buildEngineFromOnnx(); + logger_->stop_throttle(log_thread); + logger_->log(nvinfer1::ILogger::Severity::kINFO, "Engine build completed"); + return success; + }; + + // Load engine file if it exists + if (fs::exists(trt_config_->engine_path)) { + logger_->log(nvinfer1::ILogger::Severity::kINFO, "Loading engine"); + if (!loadEngine()) { + return false; } - cache_engine_path.replace_extension(ext); - - // Output Network Information - printNetworkInfo(model_file_path_); - - if (fs::exists(cache_engine_path)) { - std::cout << "Loading... " << cache_engine_path << std::endl; - loadEngine(cache_engine_path); - } else { - std::cout << "Building... " << cache_engine_path << std::endl; - logger_.log(nvinfer1::ILogger::Severity::kINFO, "Start build engine"); - auto log_thread = logger_.log_throttle( - nvinfer1::ILogger::Severity::kINFO, - "Applying optimizations and building TRT CUDA engine. Please wait for a few minutes...", 5); - buildEngineFromOnnx(model_file_path_, cache_engine_path); - logger_.stop_throttle(log_thread); - logger_.log(nvinfer1::ILogger::Severity::kINFO, "End build engine"); + logger_->log(nvinfer1::ILogger::Severity::kINFO, "Network validation"); + // Validate engine tensor shapes and optimization profile + if (!validateNetworkIO() || !validateProfileDims()) { + logger_->log( + nvinfer1::ILogger::Severity::kWARNING, + "Network validation failed for loaded engine from file. Rebuilding engine"); + // Rebuild engine if the tensor shapes or optimization profile mismatch + if (!build_engine_with_log()) { + return false; + } } - // cppcheck-suppress unreadVariable - engine_path = cache_engine_path; } else { - is_initialized_ = false; - return; + // Build engine if engine has not been cached + if (!build_engine_with_log()) { + return false; + } } - context_ = TrtUniquePtr(engine_->createExecutionContext()); - if (!context_) { - logger_.log(nvinfer1::ILogger::Severity::kERROR, "Fail to create context"); - is_initialized_ = false; - return; + // Validate engine nevertheless is loaded or rebuilt + if (!validateNetworkIO() || !validateProfileDims()) { + logger_->log( + nvinfer1::ILogger::Severity::kERROR, + "Final network validation failed. Possibly the input / output of the currently " + "deployed model has changed. Check your configuration file with the current model."); + return false; } - if (build_config_->profile_per_layer) { - context_->setProfiler(&model_profiler_); + logger_->log(nvinfer1::ILogger::Severity::kINFO, "Engine setup completed"); + return true; +} + +std::string TrtCommon::getPrecision() const +{ + return trt_config_->precision; +} + +const char * TrtCommon::getIOTensorName(const int32_t index) const +{ + if (!engine_) { + logger_->log( + nvinfer1::ILogger::Severity::kWARNING, + "Engine is not initialized. Retrieving data from network"); + if (!network_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Network is not initialized"); + return nullptr; + } + auto num_inputs = network_->getNbInputs(); + auto num_outputs = network_->getNbOutputs(); + if (index < 0 || index >= num_inputs + num_outputs) { + logger_->log( + nvinfer1::ILogger::Severity::kERROR, + "Invalid index for I/O tensor: %d. Total I/O tensors: %d", index, num_inputs + num_outputs); + return nullptr; + } + if (index < num_inputs) { + return network_->getInput(index)->getName(); + } + return network_->getOutput(index - num_inputs)->getName(); } -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8200 - // Write profiles for trt-engine-explorer - // See: https://github.com/NVIDIA/TensorRT/tree/main/tools/experimental/trt-engine-explorer - std::string j_ext = ".json"; - fs::path json_path{engine_path}; - json_path.replace_extension(j_ext); - std::string ret = getLayerInformation(nvinfer1::LayerInformationFormat::kJSON); - std::ofstream os(json_path, std::ofstream::trunc); - os << ret << std::flush; -#endif - is_initialized_ = true; + return engine_->getIOTensorName(index); } -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8500 -void TrtCommon::setupBindings(std::vector & bindings) +int32_t TrtCommon::getNbIOTensors() const { - for (int32_t i = 0, e = engine_->getNbIOTensors(); i < e; i++) { - auto const name = engine_->getIOTensorName(i); - context_->setTensorAddress(name, bindings.at(i)); + if (!engine_) { + logger_->log( + nvinfer1::ILogger::Severity::kWARNING, + "Engine is not initialized. Retrieving data from network"); + if (!network_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Network is not initialized"); + return 0; + } + return network_->getNbInputs() + network_->getNbOutputs(); } + return engine_->getNbIOTensors(); } -#endif -bool TrtCommon::loadEngine(const std::string & engine_file_path) +nvinfer1::Dims TrtCommon::getTensorShape(const int32_t index) const { - std::ifstream engine_file(engine_file_path); - std::stringstream engine_buffer; - engine_buffer << engine_file.rdbuf(); - std::string engine_str = engine_buffer.str(); - engine_ = TrtUniquePtr(runtime_->deserializeCudaEngine( - reinterpret_cast(engine_str.data()), engine_str.size())); - return true; + if (!engine_) { + logger_->log( + nvinfer1::ILogger::Severity::kWARNING, + "Engine is not initialized. Retrieving data from network"); + if (!network_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Network is not initialized"); + return nvinfer1::Dims{}; + } + auto num_inputs = network_->getNbInputs(); + auto num_outputs = network_->getNbOutputs(); + if (index < 0 || index >= num_inputs + num_outputs) { + logger_->log( + nvinfer1::ILogger::Severity::kERROR, + "Invalid index for I/O tensor: %d. Total I/O tensors: %d", index, num_inputs + num_outputs); + return nvinfer1::Dims{}; + } + if (index < num_inputs) { + return network_->getInput(index)->getDimensions(); + } + return network_->getOutput(index - num_inputs)->getDimensions(); + } + auto const & name = getIOTensorName(index); + return getTensorShape(name); } -void TrtCommon::printNetworkInfo(const std::string & onnx_file_path) +nvinfer1::Dims TrtCommon::getTensorShape(const char * tensor_name) const { - auto builder = TrtUniquePtr(nvinfer1::createInferBuilder(logger_)); - if (!builder) { - logger_.log(nvinfer1::ILogger::Severity::kERROR, "Fail to create builder"); - return; + if (!engine_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Engine is not initialized"); + return nvinfer1::Dims{}; } + return engine_->getTensorShape(tensor_name); +} - const auto explicitBatch = - 1U << static_cast(nvinfer1::NetworkDefinitionCreationFlag::kEXPLICIT_BATCH); +nvinfer1::Dims TrtCommon::getInputDims(const int32_t index) const +{ + if (!network_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Network is not initialized"); + return {}; + } + const auto input = network_->getInput(index); + return input->getDimensions(); +} - auto network = - TrtUniquePtr(builder->createNetworkV2(explicitBatch)); - if (!network) { - logger_.log(nvinfer1::ILogger::Severity::kERROR, "Fail to create network"); - return; +nvinfer1::Dims TrtCommon::getOutputDims(const int32_t index) const +{ + if (!network_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Network is not initialized"); + return {}; } + const auto output = network_->getOutput(index); + return output->getDimensions(); +} + +bool TrtCommon::setTensorAddress(const int32_t index, void * data) +{ + auto const & name = getIOTensorName(index); + return setTensorAddress(name, data); +} - auto config = TrtUniquePtr(builder->createBuilderConfig()); - if (!config) { - logger_.log(nvinfer1::ILogger::Severity::kERROR, "Fail to create builder config"); - return; +bool TrtCommon::setTensorAddress(const char * tensor_name, void * data) +{ + if (!context_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Context is not initialized"); + return false; + } + auto success = context_->setTensorAddress(tensor_name, data); + if (!success) { + logger_->log( + nvinfer1::ILogger::Severity::kERROR, + "Failed to set tensor address for tensor: ", tensor_name); } + return success; +} - if (precision_ == "fp16" || precision_ == "int8") { - config->setFlag(nvinfer1::BuilderFlag::kFP16); +bool TrtCommon::setTensorsAddresses(std::vector & tensors) +{ + bool success = true; + for (std::size_t i = 0, e = tensors.size(); i < e; i++) { + auto const name = getIOTensorName(i); + success &= setTensorAddress(name, tensors.at(i)); } -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8400 - config->setMemoryPoolLimit(nvinfer1::MemoryPoolType::kWORKSPACE, max_workspace_size_); -#else - config->setMaxWorkspaceSize(max_workspace_size_); -#endif + return success; +} - auto parser = TrtUniquePtr(nvonnxparser::createParser(*network, logger_)); - if (!parser->parseFromFile( - onnx_file_path.c_str(), static_cast(nvinfer1::ILogger::Severity::kERROR))) { - return; - } - int num = network->getNbLayers(); - float total_gflops = 0.0; - int total_params = 0; - for (int i = 0; i < num; i++) { - nvinfer1::ILayer * layer = network->getLayer(i); - auto layer_type = layer->getType(); - if (build_config_->profile_per_layer) { - model_profiler_.setProfDict(layer); - } - if (layer_type == nvinfer1::LayerType::kCONSTANT) { - continue; - } - nvinfer1::ITensor * in = layer->getInput(0); - nvinfer1::Dims dim_in = in->getDimensions(); - nvinfer1::ITensor * out = layer->getOutput(0); - nvinfer1::Dims dim_out = out->getDimensions(); - - if (layer_type == nvinfer1::LayerType::kCONVOLUTION) { - nvinfer1::IConvolutionLayer * conv = (nvinfer1::IConvolutionLayer *)layer; - nvinfer1::Dims k_dims = conv->getKernelSizeNd(); - nvinfer1::Dims s_dims = conv->getStrideNd(); - int groups = conv->getNbGroups(); - int stride = s_dims.d[0]; - int num_weights = (dim_in.d[1] / groups) * dim_out.d[1] * k_dims.d[0] * k_dims.d[1]; - float gflops = (2.0 * num_weights) * (static_cast(dim_in.d[3]) / stride * - static_cast(dim_in.d[2]) / stride / 1e9); - total_gflops += gflops; - total_params += num_weights; - std::cout << "L" << i << " [conv " << k_dims.d[0] << "x" << k_dims.d[1] << " (" << groups - << ") " - << "/" << s_dims.d[0] << "] " << dim_in.d[3] << "x" << dim_in.d[2] << "x" - << dim_in.d[1] << " -> " << dim_out.d[3] << "x" << dim_out.d[2] << "x" - << dim_out.d[1]; - std::cout << " weights:" << num_weights; - std::cout << " GFLOPs:" << gflops; - std::cout << std::endl; - } else if (layer_type == nvinfer1::LayerType::kPOOLING) { - nvinfer1::IPoolingLayer * pool = (nvinfer1::IPoolingLayer *)layer; - auto p_type = pool->getPoolingType(); - nvinfer1::Dims dim_stride = pool->getStrideNd(); - nvinfer1::Dims dim_window = pool->getWindowSizeNd(); - - std::cout << "L" << i << " ["; - if (p_type == nvinfer1::PoolingType::kMAX) { - std::cout << "max "; - } else if (p_type == nvinfer1::PoolingType::kAVERAGE) { - std::cout << "avg "; - } else if (p_type == nvinfer1::PoolingType::kMAX_AVERAGE_BLEND) { - std::cout << "max avg blend "; - } - float gflops = static_cast(dim_in.d[1]) * - (static_cast(dim_window.d[0]) / static_cast(dim_stride.d[0])) * - (static_cast(dim_window.d[1]) / static_cast(dim_stride.d[1])) * - static_cast(dim_in.d[2]) * static_cast(dim_in.d[3]) / 1e9; - total_gflops += gflops; - std::cout << "pool " << dim_window.d[0] << "x" << dim_window.d[1] << "]"; - std::cout << " GFLOPs:" << gflops; - std::cout << std::endl; - } else if (layer_type == nvinfer1::LayerType::kRESIZE) { - std::cout << "L" << i << " [resize]" << std::endl; - } +bool TrtCommon::setTensorsAddresses(std::unordered_map & tensors) +{ + bool success = true; + for (auto const & tensor : tensors) { + success &= setTensorAddress(tensor.first, tensor.second); } - std::cout << "Total " << total_gflops << " GFLOPs" << std::endl; - std::cout << "Total " << total_params / 1000.0 / 1000.0 << " M params" << std::endl; - return; + return success; +} + +bool TrtCommon::setInputShape(const int32_t index, const nvinfer1::Dims & dimensions) +{ + auto const & name = getIOTensorName(index); + return setInputShape(name, dimensions); } -bool TrtCommon::buildEngineFromOnnx( - const std::string & onnx_file_path, const std::string & output_engine_file_path) +bool TrtCommon::setInputShape(const char * tensor_name, const nvinfer1::Dims & dimensions) { - auto builder = TrtUniquePtr(nvinfer1::createInferBuilder(logger_)); - if (!builder) { - logger_.log(nvinfer1::ILogger::Severity::kERROR, "Fail to create builder"); + if (!context_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Context is not initialized"); return false; } + auto success = context_->setInputShape(tensor_name, dimensions); + if (!success) { + logger_->log( + nvinfer1::ILogger::Severity::kERROR, "Failed to set input shape for tensor: ", tensor_name); + } + return success; +} - const auto explicitBatch = - 1U << static_cast(nvinfer1::NetworkDefinitionCreationFlag::kEXPLICIT_BATCH); +bool TrtCommon::setInputsShapes(const std::vector & dimensions) +{ + bool success = true; + for (std::size_t i = 0, e = dimensions.size(); i < e; i++) { + success &= setInputShape(i, dimensions.at(i)); + } + return success; +} - auto network = - TrtUniquePtr(builder->createNetworkV2(explicitBatch)); - if (!network) { - logger_.log(nvinfer1::ILogger::Severity::kERROR, "Fail to create network"); - return false; +bool TrtCommon::setInputsShapes(const std::unordered_map & dimensions) +{ + bool success = true; + for (auto const & dim : dimensions) { + success &= setInputShape(dim.first, dim.second); } + return success; +} - auto config = TrtUniquePtr(builder->createBuilderConfig()); - if (!config) { - logger_.log(nvinfer1::ILogger::Severity::kERROR, "Fail to create builder config"); - return false; +bool TrtCommon::setTensor(const int32_t index, void * data, nvinfer1::Dims dimensions) +{ + auto success = setTensorAddress(index, data); + if (dimensions.nbDims > 0) { + success &= setInputShape(index, dimensions); } + return success; +} - int num_available_dla = builder->getNbDLACores(); - if (build_config_->dla_core_id != -1) { - if (num_available_dla > 0) { - std::cout << "###" << num_available_dla << " DLAs are supported! ###" << std::endl; - } else { - std::cout << "###Warning : " - << "No DLA is supported! ###" << std::endl; - } - config->setDefaultDeviceType(nvinfer1::DeviceType::kDLA); - config->setDLACore(build_config_->dla_core_id); -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8200 - config->setFlag(nvinfer1::BuilderFlag::kPREFER_PRECISION_CONSTRAINTS); -#else - config->setFlag(nvinfer1::BuilderFlag::kSTRICT_TYPES); -#endif - config->setFlag(nvinfer1::BuilderFlag::kGPU_FALLBACK); +bool TrtCommon::setTensor(const char * tensor_name, void * data, nvinfer1::Dims dimensions) +{ + auto success = setTensorAddress(tensor_name, data); + if (dimensions.nbDims > 0) { + success &= setInputShape(tensor_name, dimensions); } - if (precision_ == "fp16" || precision_ == "int8") { - config->setFlag(nvinfer1::BuilderFlag::kFP16); + return success; +} + +bool TrtCommon::setTensors(TensorsVec & tensors) +{ + bool success = true; + for (std::size_t i = 0, e = tensors.size(); i < e; i++) { + success &= setTensor(i, tensors.at(i).first, tensors.at(i).second); } -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8400 - config->setMemoryPoolLimit(nvinfer1::MemoryPoolType::kWORKSPACE, max_workspace_size_); -#else - config->setMaxWorkspaceSize(max_workspace_size_); -#endif + return success; +} - auto parser = TrtUniquePtr(nvonnxparser::createParser(*network, logger_)); - if (!parser->parseFromFile( - onnx_file_path.c_str(), static_cast(nvinfer1::ILogger::Severity::kERROR))) { - std::cout << "Failed to parse onnx file" << std::endl; - return false; +bool TrtCommon::setTensors(TensorsMap & tensors) +{ + bool success = true; + for (auto const & tensor : tensors) { + success &= setTensor(tensor.first, tensor.second.first, tensor.second.second); } + return success; +} - const int num = network->getNbLayers(); - bool first = build_config_->quantize_first_layer; - bool last = build_config_->quantize_last_layer; - // Partial Quantization - if (precision_ == "int8") { - network->getInput(0)->setDynamicRange(0, 255.0); - for (int i = 0; i < num; i++) { - nvinfer1::ILayer * layer = network->getLayer(i); - auto layer_type = layer->getType(); - std::string name = layer->getName(); - nvinfer1::ITensor * out = layer->getOutput(0); - if (build_config_->clip_value > 0.0) { - std::cout << "Set max value for outputs : " << build_config_->clip_value << " " << name - << std::endl; - out->setDynamicRange(0.0, build_config_->clip_value); - } +std::shared_ptr TrtCommon::getModelProfiler() +{ + return model_profiler_; +} - if (layer_type == nvinfer1::LayerType::kCONVOLUTION) { - if (first) { - layer->setPrecision(nvinfer1::DataType::kHALF); - std::cout << "Set kHALF in " << name << std::endl; - first = false; - } - if (last) { - // cspell: ignore preds - if ( - contain(name, "reg_preds") || contain(name, "cls_preds") || - contain(name, "obj_preds")) { - layer->setPrecision(nvinfer1::DataType::kHALF); - std::cout << "Set kHALF in " << name << std::endl; - } - for (int j = num - 1; j >= 0; j--) { - nvinfer1::ILayer * inner_layer = network->getLayer(j); - auto inner_layer_type = inner_layer->getType(); - std::string inner_name = inner_layer->getName(); - if (inner_layer_type == nvinfer1::LayerType::kCONVOLUTION) { - inner_layer->setPrecision(nvinfer1::DataType::kHALF); - std::cout << "Set kHALF in " << inner_name << std::endl; - break; - } - if (inner_layer_type == nvinfer1::LayerType::kMATRIX_MULTIPLY) { - inner_layer->setPrecision(nvinfer1::DataType::kHALF); - std::cout << "Set kHALF in " << inner_name << std::endl; - break; - } - } - } - } - } +std::shared_ptr TrtCommon::getHostProfiler() +{ + return host_profiler_; +} + +std::shared_ptr TrtCommon::getTrtCommonConfig() +{ + return trt_config_; +} + +std::shared_ptr TrtCommon::getBuilderConfig() +{ + return builder_config_; +} + +std::shared_ptr TrtCommon::getNetwork() +{ + return network_; +} + +std::shared_ptr TrtCommon::getLogger() +{ + return logger_; +} + +bool TrtCommon::enqueueV3(cudaStream_t stream) +{ + if (!context_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Context is not initialized"); + return false; + } + if (trt_config_->profile_per_layer) { + auto inference_start = std::chrono::high_resolution_clock::now(); + auto success = context_->enqueueV3(stream); + auto inference_end = std::chrono::high_resolution_clock::now(); + host_profiler_->reportLayerTime( + "inference_host", + std::chrono::duration(inference_end - inference_start).count()); + return success; } + return context_->enqueueV3(stream); +} - const auto input = network->getInput(0); - const auto input_dims = input->getDimensions(); - const auto input_channel = input_dims.d[1]; - const auto input_height = input_dims.d[2]; - const auto input_width = input_dims.d[3]; - const auto input_batch = input_dims.d[0]; +void TrtCommon::printProfiling() const +{ + logger_->log( + nvinfer1::ILogger::Severity::kINFO, "Host Profiling\n", host_profiler_->toString().c_str()); + logger_->log( + nvinfer1::ILogger::Severity::kINFO, "Model Profiling\n", model_profiler_->toString().c_str()); +} + +std::string TrtCommon::getLayerInformation(nvinfer1::LayerInformationFormat format) +{ + if (!context_ || !engine_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Context or engine are not initialized"); + return {}; + } + auto inspector = std::unique_ptr(engine_->createEngineInspector()); + inspector->setExecutionContext(&(*context_)); + std::string result = inspector->getEngineInformation(format); + return result; +} - if (input_batch > 1) { - batch_config_[0] = input_batch; +bool TrtCommon::initialize() +{ + if (!fs::exists(trt_config_->onnx_path) || trt_config_->onnx_path.extension() != ".onnx") { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Invalid ONNX file path or extension"); + return false; } - if (batch_config_.at(0) > 1 && (batch_config_.at(0) == batch_config_.at(2))) { - // Attention : below API is deprecated in TRT8.4 - builder->setMaxBatchSize(batch_config_.at(2)); - } else { - if (build_config_->profile_per_layer) { - auto profile = builder->createOptimizationProfile(); - profile->setDimensions( - network->getInput(0)->getName(), nvinfer1::OptProfileSelector::kMIN, - nvinfer1::Dims4{batch_config_.at(0), input_channel, input_height, input_width}); - profile->setDimensions( - network->getInput(0)->getName(), nvinfer1::OptProfileSelector::kOPT, - nvinfer1::Dims4{batch_config_.at(1), input_channel, input_height, input_width}); - profile->setDimensions( - network->getInput(0)->getName(), nvinfer1::OptProfileSelector::kMAX, - nvinfer1::Dims4{batch_config_.at(2), input_channel, input_height, input_width}); - config->addOptimizationProfile(profile); - } + builder_ = TrtUniquePtr(nvinfer1::createInferBuilder(*logger_)); + if (!builder_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Fail to create builder"); + return false; } - if (precision_ == "int8" && calibrator_) { - config->setFlag(nvinfer1::BuilderFlag::kINT8); -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8200 - config->setFlag(nvinfer1::BuilderFlag::kPREFER_PRECISION_CONSTRAINTS); + +#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH < 10000 + const auto explicit_batch = + 1U << static_cast(nvinfer1::NetworkDefinitionCreationFlag::kEXPLICIT_BATCH); + network_ = TrtUniquePtr(builder_->createNetworkV2(explicit_batch)); #else - config->setFlag(nvinfer1::BuilderFlag::kSTRICT_TYPES); + network_ = TrtUniquePtr(builder_->createNetworkV2(0)); #endif - // QAT requires no calibrator. - // assert((calibrator != nullptr) && "Invalid calibrator for INT8 precision"); - config->setInt8Calibrator(calibrator_.get()); + + if (!network_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Fail to create network"); + return false; } - if (build_config_->profile_per_layer) { -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8200 - config->setProfilingVerbosity(nvinfer1::ProfilingVerbosity::kDETAILED); -#else - config->setProfilingVerbosity(nvinfer1::ProfilingVerbosity::kVERBOSE); -#endif + + builder_config_ = TrtUniquePtr(builder_->createBuilderConfig()); + if (!builder_config_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Fail to create builder config"); + return false; + } + + auto num_available_dla = builder_->getNbDLACores(); + if (trt_config_->dla_core_id != -1) { + logger_->log( + nvinfer1::ILogger::Severity::kINFO, "Number of DLAs supported: %d", num_available_dla); + builder_config_->setDefaultDeviceType(nvinfer1::DeviceType::kDLA); + builder_config_->setDLACore(trt_config_->dla_core_id); + builder_config_->setFlag(nvinfer1::BuilderFlag::kPREFER_PRECISION_CONSTRAINTS); + builder_config_->setFlag(nvinfer1::BuilderFlag::kGPU_FALLBACK); } + if (trt_config_->precision == "fp16") { + builder_config_->setFlag(nvinfer1::BuilderFlag::kFP16); + } else if (trt_config_->precision == "int8") { + builder_config_->setFlag(nvinfer1::BuilderFlag::kINT8); + } + builder_config_->setMemoryPoolLimit( + nvinfer1::MemoryPoolType::kWORKSPACE, trt_config_->max_workspace_size); + + parser_ = TrtUniquePtr(nvonnxparser::createParser(*network_, *logger_)); + if (!parser_->parseFromFile( + trt_config_->onnx_path.c_str(), + static_cast(nvinfer1::ILogger::Severity::kERROR))) { + return false; + } + + if (trt_config_->profile_per_layer) { + builder_config_->setProfilingVerbosity(nvinfer1::ProfilingVerbosity::kDETAILED); + } + + return true; +} -#if TENSORRT_VERSION_MAJOR >= 8 - auto plan = - TrtUniquePtr(builder->buildSerializedNetwork(*network, *config)); +bool TrtCommon::buildEngineFromOnnx() +{ + // Build engine + auto plan = TrtUniquePtr( + builder_->buildSerializedNetwork(*network_, *builder_config_)); if (!plan) { - logger_.log(nvinfer1::ILogger::Severity::kERROR, "Fail to create host memory"); + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Fail to create host memory"); return false; } engine_ = TrtUniquePtr( runtime_->deserializeCudaEngine(plan->data(), plan->size())); -#else - engine_ = TrtUniquePtr(builder->buildEngineWithConfig(*network, *config)); -#endif if (!engine_) { - logger_.log(nvinfer1::ILogger::Severity::kERROR, "Fail to create engine"); + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Fail to create engine"); return false; } - // save engine -#if TENSORRT_VERSION_MAJOR < 8 - auto data = TrtUniquePtr(engine_->serialize()); -#endif + // Save engine std::ofstream file; - file.open(output_engine_file_path, std::ios::binary | std::ios::out); + file.open(trt_config_->engine_path, std::ios::binary | std::ios::out); if (!file.is_open()) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Fail to open engine file"); return false; } -#if TENSORRT_VERSION_MAJOR < 8 - file.write(reinterpret_cast(data->data()), data->size()); -#else - file.write(reinterpret_cast(plan->data()), plan->size()); -#endif - + file.write(reinterpret_cast(plan->data()), plan->size()); // NOLINT file.close(); - return true; -} - -bool TrtCommon::isInitialized() -{ - return is_initialized_; -} - -nvinfer1::Dims TrtCommon::getBindingDimensions(const int32_t index) const -{ -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + (NV_TENSOR_PATCH * 10) >= 8500 - auto const & name = engine_->getIOTensorName(index); - auto dims = context_->getTensorShape(name); - bool const has_runtime_dim = - std::any_of(dims.d, dims.d + dims.nbDims, [](int32_t dim) { return dim == -1; }); + context_ = TrtUniquePtr(engine_->createExecutionContext()); + if (!context_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Fail to create context"); + return false; + } - if (has_runtime_dim) { - return dims; - } else { - return context_->getBindingDimensions(index); + if (trt_config_->profile_per_layer) { + context_->setProfiler(&*model_profiler_); } -#else - return context_->getBindingDimensions(index); -#endif -} -int32_t TrtCommon::getNbBindings() -{ - return engine_->getNbBindings(); -} + fs::path json_path = trt_config_->engine_path.replace_extension(".json"); + auto ret = getLayerInformation(nvinfer1::LayerInformationFormat::kJSON); + std::ofstream os(json_path, std::ofstream::trunc); + os << ret << std::flush; + os.close(); -bool TrtCommon::setBindingDimensions(const int32_t index, const nvinfer1::Dims & dimensions) const -{ - return context_->setBindingDimensions(index, dimensions); + return true; } -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8500 -bool TrtCommon::enqueueV3(cudaStream_t stream) +bool TrtCommon::loadEngine() { - if (build_config_->profile_per_layer) { - auto inference_start = std::chrono::high_resolution_clock::now(); - - bool ret = context_->enqueueV3(stream); + std::ifstream engine_file(trt_config_->engine_path); + std::stringstream engine_buffer; + engine_buffer << engine_file.rdbuf(); + std::string engine_str = engine_buffer.str(); - auto inference_end = std::chrono::high_resolution_clock::now(); - host_profiler_.reportLayerTime( - "inference", - std::chrono::duration(inference_end - inference_start).count()); - return ret; + engine_ = TrtUniquePtr(runtime_->deserializeCudaEngine( + reinterpret_cast( // NOLINT + engine_str.data()), + engine_str.size())); + if (!engine_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Fail to create engine"); + return false; } - return context_->enqueueV3(stream); -} -#endif -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH < 10000 -bool TrtCommon::enqueueV2(void ** bindings, cudaStream_t stream, cudaEvent_t * input_consumed) -{ - if (build_config_->profile_per_layer) { - auto inference_start = std::chrono::high_resolution_clock::now(); - bool ret = context_->enqueueV2(bindings, stream, input_consumed); + context_ = TrtUniquePtr(engine_->createExecutionContext()); + if (!context_) { + logger_->log(nvinfer1::ILogger::Severity::kERROR, "Fail to create context"); + return false; + } - auto inference_end = std::chrono::high_resolution_clock::now(); - host_profiler_.reportLayerTime( - "inference", - std::chrono::duration(inference_end - inference_start).count()); - return ret; - } else { - return context_->enqueueV2(bindings, stream, input_consumed); + if (trt_config_->profile_per_layer) { + context_->setProfiler(&*model_profiler_); } + + return true; } -#endif -void TrtCommon::printProfiling() +bool TrtCommon::validateProfileDims() { - std::cout << host_profiler_; - std::cout << std::endl; - std::cout << model_profiler_; + auto success = true; + if (!profile_dims_ || profile_dims_->empty()) { + logger_->log( + nvinfer1::ILogger::Severity::kWARNING, + "Input profile is empty, skipping validation. If network has dynamic shapes, it might lead " + "to undefined behavior."); + return success; + } + if (engine_->getNbOptimizationProfiles() != 1) { + logger_->log( + nvinfer1::ILogger::Severity::kWARNING, + "Number of optimization profiles in the engine (%d) is not equal to 1. Selecting the first " + "cached profile.", + engine_->getNbOptimizationProfiles()); + } + + for (const auto & profile_dim : *profile_dims_) { + nvinfer1::Dims min_dims = engine_->getProfileShape( + profile_dim.tensor_name.c_str(), 0, nvinfer1::OptProfileSelector::kMIN); + nvinfer1::Dims opt_dims = engine_->getProfileShape( + profile_dim.tensor_name.c_str(), 0, nvinfer1::OptProfileSelector::kOPT); + nvinfer1::Dims max_dims = engine_->getProfileShape( + profile_dim.tensor_name.c_str(), 0, nvinfer1::OptProfileSelector::kMAX); + ProfileDims profile_from_engine{profile_dim.tensor_name, min_dims, opt_dims, max_dims}; + if (profile_dim != profile_from_engine) { + logger_->log( + nvinfer1::ILogger::Severity::kWARNING, + "Invalid profile. Current configuration: %s. Cached engine: %s", + profile_dim.toString().c_str(), profile_from_engine.toString().c_str()); + success = false; + } + } + return success; } -#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8200 -std::string TrtCommon::getLayerInformation(nvinfer1::LayerInformationFormat format) +bool TrtCommon::validateNetworkIO() { - auto runtime = std::unique_ptr(nvinfer1::createInferRuntime(logger_)); - auto inspector = std::unique_ptr(engine_->createEngineInspector()); - if (context_ != nullptr) { - inspector->setExecutionContext(&(*context_)); + auto success = true; + if (!network_io_ || network_io_->empty()) { + logger_->log( + nvinfer1::ILogger::Severity::kWARNING, + "Network IO is empty, skipping validation. It might lead to undefined behavior"); + return success; + } + + if (network_io_->size() != static_cast(getNbIOTensors())) { + std::string tensor_names = "[" + std::string(getIOTensorName(0)); + for (int32_t i = 1; i < getNbIOTensors(); ++i) { + tensor_names += ", " + std::string(getIOTensorName(i)); + } + tensor_names += "]"; + logger_->log( + nvinfer1::ILogger::Severity::kWARNING, + "Number of tensors in the engine (%d) does not match number of tensors in the config (%d). " + "Tensors in the built engine: %s", + getNbIOTensors(), network_io_->size(), tensor_names.c_str()); + success = false; + } + for (const auto & io : *network_io_) { + NetworkIO tensor_from_engine{io.tensor_name, getTensorShape(io.tensor_name.c_str())}; + if (io != tensor_from_engine) { + logger_->log( + nvinfer1::ILogger::Severity::kERROR, + "Invalid tensor. Current configuration: %s. Cached engine: %s", io.toString().c_str(), + tensor_from_engine.toString().c_str()); + success = false; + } } - std::string result = inspector->getEngineInformation(format); - return result; + + return success; } -#endif } // namespace tensorrt_common } // namespace autoware diff --git a/perception/autoware_tensorrt_yolox/CMakeLists.txt b/perception/autoware_tensorrt_yolox/CMakeLists.txt index 17b31fc7e8df1..cc0d793151781 100644 --- a/perception/autoware_tensorrt_yolox/CMakeLists.txt +++ b/perception/autoware_tensorrt_yolox/CMakeLists.txt @@ -10,6 +10,9 @@ endif() find_package(autoware_cmake REQUIRED) autoware_package() +# TODO(amadeuszsz): Remove -Wno-deprecated-declarations once removing implicit quantization +add_compile_options(-Wno-deprecated-declarations) + find_package(OpenCV REQUIRED) option(CUDA_VERBOSE "Verbose output of CUDA modules" OFF) diff --git a/perception/autoware_tensorrt_yolox/include/autoware/tensorrt_yolox/tensorrt_yolox.hpp b/perception/autoware_tensorrt_yolox/include/autoware/tensorrt_yolox/tensorrt_yolox.hpp index 483adfbdf2757..7d49df145b72e 100644 --- a/perception/autoware_tensorrt_yolox/include/autoware/tensorrt_yolox/tensorrt_yolox.hpp +++ b/perception/autoware_tensorrt_yolox/include/autoware/tensorrt_yolox/tensorrt_yolox.hpp @@ -18,6 +18,8 @@ #include #include #include +#include +#include #include #include @@ -44,6 +46,13 @@ struct Object using ObjectArray = std::vector; using ObjectArrays = std::vector; +using autoware::tensorrt_common::CalibrationConfig; +using autoware::tensorrt_common::NetworkIOPtr; +using autoware::tensorrt_common::ProfileDimsPtr; +using autoware::tensorrt_common::Profiler; +using autoware::tensorrt_common::TrtCommon; +using autoware::tensorrt_common::TrtCommonConfig; +using autoware::tensorrt_common::TrtConvCalib; struct GridAndStride { @@ -70,31 +79,26 @@ class TrtYoloX public: /** * @brief Construct TrtYoloX. - * @param[in] mode_path ONNX model_path - * @param[in] precision precision for inference + * @param[in] trt_config base trt common configuration * @param[in] num_class classifier-ed num * @param[in] score_threshold threshold for detection * @param[in] nms_threshold threshold for NMS - * @param[in] build_config configuration including precision, calibration method, DLA, remaining - * fp16 for first layer, remaining fp16 for last layer and profiler for builder * @param[in] use_gpu_preprocess whether use cuda gpu for preprocessing - * @param[in] calibration_image_list_file path for calibration files (only require for + * @param[in] gpu_id GPU id for inference + * @param[in] calibration_image_list_path path for calibration files (only require for * quantization) * @param[in] norm_factor scaling factor for preprocess * @param[in] cache_dir unused variable - * @param[in] batch_config configuration for batched execution - * @param[in] max_workspace_size maximum workspace for building TensorRT engine + * @param[in] color_map_path path for colormap for masks + * @param[in] calib_config calibration configuration */ TrtYoloX( - const std::string & model_path, const std::string & precision, const int num_class = 8, - const float score_threshold = 0.3, const float nms_threshold = 0.7, - const autoware::tensorrt_common::BuildConfig build_config = - autoware::tensorrt_common::BuildConfig(), - const bool use_gpu_preprocess = false, const uint8_t gpu_id = 0, - std::string calibration_image_list_file = std::string(), const double norm_factor = 1.0, - [[maybe_unused]] const std::string & cache_dir = "", - const autoware::tensorrt_common::BatchConfig & batch_config = {1, 1, 1}, - const size_t max_workspace_size = (1 << 30), const std::string & color_map_path = ""); + TrtCommonConfig & trt_config, const int num_class = 8, const float score_threshold = 0.3, + const float nms_threshold = 0.7, const bool use_gpu_preprocess = false, + const uint8_t gpu_id = 0, std::string calibration_image_list_path = std::string(), + const double norm_factor = 1.0, [[maybe_unused]] const std::string & cache_dir = "", + const std::string & color_map_path = "", + const CalibrationConfig & calib_config = CalibrationConfig()); /** * @brief Deconstruct TrtYoloX */ @@ -168,6 +172,12 @@ class TrtYoloX cv::Mat & colorized_mask); inline std::vector getColorMap() { return sematic_color_map_; } + /** + * @brief get batch size + * @return batch size + */ + [[nodiscard]] int getBatchSize() const; + private: /** * @brief run preprocess including resizing, letterbox, NHWC2NCHW and toFloat on CPU @@ -266,7 +276,7 @@ class TrtYoloX */ cv::Mat getMaskImageGpu(float * d_prob, nvinfer1::Dims dims, int out_w, int out_h, int b); - std::unique_ptr trt_common_; + std::unique_ptr trt_common_; std::vector input_h_; CudaUniquePtr input_d_; @@ -288,7 +298,7 @@ class TrtYoloX int num_class_; float score_threshold_; float nms_threshold_; - int batch_size_; + int32_t batch_size_; CudaUniquePtrHost out_prob_h_; // flag whether preprocess are performed on GPU diff --git a/perception/autoware_tensorrt_yolox/src/tensorrt_yolox.cpp b/perception/autoware_tensorrt_yolox/src/tensorrt_yolox.cpp index 7e2e327bf6f5e..74d8d73ecaed4 100644 --- a/perception/autoware_tensorrt_yolox/src/tensorrt_yolox.cpp +++ b/perception/autoware_tensorrt_yolox/src/tensorrt_yolox.cpp @@ -155,13 +155,11 @@ std::vector get_seg_colormap(const std::stri namespace autoware::tensorrt_yolox { TrtYoloX::TrtYoloX( - const std::string & model_path, const std::string & precision, const int num_class, - const float score_threshold, const float nms_threshold, - autoware::tensorrt_common::BuildConfig build_config, const bool use_gpu_preprocess, - const uint8_t gpu_id, std::string calibration_image_list_path, const double norm_factor, - [[maybe_unused]] const std::string & cache_dir, - const autoware::tensorrt_common::BatchConfig & batch_config, const size_t max_workspace_size, - const std::string & color_map_path) + TrtCommonConfig & trt_config, const int num_class, const float score_threshold, + const float nms_threshold, const bool use_gpu_preprocess, const uint8_t gpu_id, + std::string calibration_image_list_path, const double norm_factor, + [[maybe_unused]] const std::string & cache_dir, const std::string & color_map_path, + const CalibrationConfig & calib_config) : gpu_id_(gpu_id), is_gpu_initialized_(false) { if (!setCudaDeviceId(gpu_id_)) { @@ -172,13 +170,29 @@ TrtYoloX::TrtYoloX( src_width_ = -1; src_height_ = -1; norm_factor_ = norm_factor; - batch_size_ = batch_config[2]; multitask_ = 0; sematic_color_map_ = get_seg_colormap(color_map_path); stream_ = makeCudaStream(); - if (precision == "int8") { - if (build_config.clip_value <= 0.0) { + trt_common_ = std::make_unique(trt_config); + + const auto network_input_dims = trt_common_->getTensorShape(0); + batch_size_ = network_input_dims.d[0]; + const auto input_channel = network_input_dims.d[1]; + const auto input_height = network_input_dims.d[2]; + const auto input_width = network_input_dims.d[3]; + + auto profile_dims_ptr = std::make_unique>(); + + std::vector profile_dims{ + autoware::tensorrt_common::ProfileDims( + 0, {4, {batch_size_, input_channel, input_height, input_width}}, + {4, {batch_size_, input_channel, input_height, input_width}}, + {4, {batch_size_, input_channel, input_height, input_width}})}; + *profile_dims_ptr = profile_dims; + + if (trt_config.precision == "int8") { + if (calib_config.clip_value <= 0.0) { if (calibration_image_list_path.empty()) { throw std::runtime_error( "calibration_image_list_path should be passed to generate int8 engine " @@ -189,19 +203,17 @@ TrtYoloX::TrtYoloX( calibration_image_list_path = ""; } - int max_batch_size = batch_size_; - nvinfer1::Dims input_dims = autoware::tensorrt_common::get_input_dims(model_path); std::vector calibration_images; if (calibration_image_list_path != "") { calibration_images = loadImageList(calibration_image_list_path, ""); } - tensorrt_yolox::ImageStream stream(max_batch_size, input_dims, calibration_images); - fs::path calibration_table{model_path}; + tensorrt_yolox::ImageStream stream(batch_size_, network_input_dims, calibration_images); + fs::path calibration_table{trt_config.onnx_path}; std::string ext = ""; - if (build_config.calib_type_str == "Entropy") { + if (calib_config.calib_type_str == "Entropy") { ext = "EntropyV2-"; } else if ( - build_config.calib_type_str == "Legacy" || build_config.calib_type_str == "Percentile") { + calib_config.calib_type_str == "Legacy" || calib_config.calib_type_str == "Percentile") { ext = "Legacy-"; } else { ext = "MinMax-"; @@ -209,17 +221,17 @@ TrtYoloX::TrtYoloX( ext += "calibration.table"; calibration_table.replace_extension(ext); - fs::path histogram_table{model_path}; + fs::path histogram_table{trt_config.onnx_path}; ext = "histogram.table"; histogram_table.replace_extension(ext); std::unique_ptr calibrator; - if (build_config.calib_type_str == "Entropy") { + if (calib_config.calib_type_str == "Entropy") { calibrator.reset( new tensorrt_yolox::Int8EntropyCalibrator(stream, calibration_table, norm_factor_)); } else if ( - build_config.calib_type_str == "Legacy" || build_config.calib_type_str == "Percentile") { + calib_config.calib_type_str == "Legacy" || calib_config.calib_type_str == "Percentile") { const double quantile = 0.999999; const double cutoff = 0.999999; calibrator.reset(new tensorrt_yolox::Int8LegacyCalibrator( @@ -228,22 +240,20 @@ TrtYoloX::TrtYoloX( calibrator.reset( new tensorrt_yolox::Int8MinMaxCalibrator(stream, calibration_table, norm_factor_)); } - trt_common_ = std::make_unique( - model_path, precision, std::move(calibrator), batch_config, max_workspace_size, build_config); + if (!trt_common_->setupWithCalibrator( + std::move(calibrator), calib_config, std::move((profile_dims_ptr)))) { + throw std::runtime_error("Failed to setup TensorRT engine with calibrator"); + } } else { - trt_common_ = std::make_unique( - model_path, precision, nullptr, batch_config, max_workspace_size, build_config); - } - trt_common_->setup(); - - if (!trt_common_->isInitialized()) { - return; + if (!trt_common_->setup(std::move(profile_dims_ptr))) { + throw std::runtime_error("Failed to setup TensorRT engine"); + } } // Judge whether decoding output is required // Plain models require decoding, while models with EfficientNMS_TRT module don't. // If getNbBindings == 5, the model contains EfficientNMS_TRT - switch (trt_common_->getNbBindings()) { + switch (trt_common_->getNbIOTensors()) { case 2: // Specified model is plain one. // Bindings are: [input, output] @@ -273,16 +283,16 @@ TrtYoloX::TrtYoloX( */ } // GPU memory allocation - const auto input_dims = trt_common_->getBindingDimensions(0); + const auto input_dims = trt_common_->getTensorShape(0); const auto input_size = std::accumulate(input_dims.d + 1, input_dims.d + input_dims.nbDims, 1, std::multiplies()); if (needs_output_decode_) { - const auto output_dims = trt_common_->getBindingDimensions(1); - input_d_ = autoware::cuda_utils::make_unique(batch_config[2] * input_size); + const auto output_dims = trt_common_->getTensorShape(1); + input_d_ = autoware::cuda_utils::make_unique(batch_size_ * input_size); out_elem_num_ = std::accumulate( output_dims.d + 1, output_dims.d + output_dims.nbDims, 1, std::multiplies()); - out_elem_num_ = out_elem_num_ * batch_config[2]; - out_elem_num_per_batch_ = static_cast(out_elem_num_ / batch_config[2]); + out_elem_num_ = out_elem_num_ * batch_size_; + out_elem_num_per_batch_ = static_cast(out_elem_num_ / batch_size_); out_prob_d_ = autoware::cuda_utils::make_unique(out_elem_num_); out_prob_h_ = autoware::cuda_utils::make_unique_host(out_elem_num_, cudaHostAllocPortable); @@ -298,29 +308,27 @@ TrtYoloX::TrtYoloX( output_strides_ = {8, 16, 32, 4}; } } else { - const auto out_scores_dims = trt_common_->getBindingDimensions(3); + const auto out_scores_dims = trt_common_->getTensorShape(3); max_detections_ = out_scores_dims.d[1]; - input_d_ = autoware::cuda_utils::make_unique(batch_config[2] * input_size); - out_num_detections_d_ = autoware::cuda_utils::make_unique(batch_config[2]); - out_boxes_d_ = - autoware::cuda_utils::make_unique(batch_config[2] * max_detections_ * 4); - out_scores_d_ = autoware::cuda_utils::make_unique(batch_config[2] * max_detections_); - out_classes_d_ = - autoware::cuda_utils::make_unique(batch_config[2] * max_detections_); + input_d_ = autoware::cuda_utils::make_unique(batch_size_ * input_size); + out_num_detections_d_ = autoware::cuda_utils::make_unique(batch_size_); + out_boxes_d_ = autoware::cuda_utils::make_unique(batch_size_ * max_detections_ * 4); + out_scores_d_ = autoware::cuda_utils::make_unique(batch_size_ * max_detections_); + out_classes_d_ = autoware::cuda_utils::make_unique(batch_size_ * max_detections_); } if (multitask_) { // Allocate buffer for segmentation segmentation_out_elem_num_ = 0; for (int m = 0; m < multitask_; m++) { const auto output_dims = - trt_common_->getBindingDimensions(m + 2); // 0 : input, 1 : output for detections + trt_common_->getTensorShape(m + 2); // 0 : input, 1 : output for detections size_t out_elem_num = std::accumulate( output_dims.d + 1, output_dims.d + output_dims.nbDims, 1, std::multiplies()); - out_elem_num = out_elem_num * batch_config[2]; + out_elem_num = out_elem_num * batch_size_; segmentation_out_elem_num_ += out_elem_num; } segmentation_out_elem_num_per_batch_ = - static_cast(segmentation_out_elem_num_ / batch_config[2]); + static_cast(segmentation_out_elem_num_ / batch_size_); segmentation_out_prob_d_ = autoware::cuda_utils::make_unique(segmentation_out_elem_num_); segmentation_out_prob_h_ = autoware::cuda_utils::make_unique_host( @@ -387,7 +395,7 @@ void TrtYoloX::initPreprocessBuffer(int width, int height) src_width_ = width; src_height_ = height; if (use_gpu_preprocess_) { - auto input_dims = trt_common_->getBindingDimensions(0); + auto input_dims = trt_common_->getTensorShape(0); bool const hasRuntimeDim = std::any_of( input_dims.d, input_dims.d + input_dims.nbDims, [](int32_t input_dim) { return input_dim == -1; }); @@ -395,7 +403,9 @@ void TrtYoloX::initPreprocessBuffer(int width, int height) input_dims.d[0] = batch_size_; } if (!image_buf_h_) { - trt_common_->setBindingDimensions(0, input_dims); + if (!trt_common_->setInputShape(0, input_dims)) { + return; + } scales_.clear(); } const float input_height = static_cast(input_dims.d[2]); @@ -414,7 +424,7 @@ void TrtYoloX::initPreprocessBuffer(int width, int height) size_t argmax_out_elem_num = 0; for (int m = 0; m < multitask_; m++) { const auto output_dims = - trt_common_->getBindingDimensions(m + 2); // 0 : input, 1 : output for detections + trt_common_->getTensorShape(m + 2); // 0 : input, 1 : output for detections const float scale = std::min( output_dims.d[3] / static_cast(width), output_dims.d[2] / static_cast(height)); @@ -441,7 +451,7 @@ void TrtYoloX::printProfiling(void) void TrtYoloX::preprocessGpu(const std::vector & images) { const auto batch_size = images.size(); - auto input_dims = trt_common_->getBindingDimensions(0); + auto input_dims = trt_common_->getTensorShape(0); input_dims.d[0] = batch_size; for (const auto & image : images) { @@ -469,7 +479,9 @@ void TrtYoloX::preprocessGpu(const std::vector & images) src_height_ = height; } if (!image_buf_h_) { - trt_common_->setBindingDimensions(0, input_dims); + if (!trt_common_->setInputShape(0, input_dims)) { + return; + } scales_.clear(); } const float input_height = static_cast(input_dims.d[2]); @@ -495,7 +507,7 @@ void TrtYoloX::preprocessGpu(const std::vector & images) if (multitask_) { for (int m = 0; m < multitask_; m++) { const auto output_dims = - trt_common_->getBindingDimensions(m + 2); // 0: input, 1: output for detections + trt_common_->getTensorShape(m + 2); // 0: input, 1: output for detections const float scale = std::min( output_dims.d[3] / static_cast(image.cols), output_dims.d[2] / static_cast(image.rows)); @@ -530,9 +542,11 @@ void TrtYoloX::preprocessGpu(const std::vector & images) void TrtYoloX::preprocess(const std::vector & images) { const auto batch_size = images.size(); - auto input_dims = trt_common_->getBindingDimensions(0); + auto input_dims = trt_common_->getTensorShape(0); input_dims.d[0] = batch_size; - trt_common_->setBindingDimensions(0, input_dims); + if (!trt_common_->setInputShape(0, input_dims)) { + return; + } const float input_height = static_cast(input_dims.d[2]); const float input_width = static_cast(input_dims.d[3]); std::vector dst_images; @@ -567,9 +581,6 @@ bool TrtYoloX::doInference( if (!setCudaDeviceId(gpu_id_)) { return false; } - if (!trt_common_->isInitialized()) { - return false; - } if (use_gpu_preprocess_) { preprocessGpu(images); @@ -588,7 +599,7 @@ void TrtYoloX::preprocessWithRoiGpu( const std::vector & images, const std::vector & rois) { const auto batch_size = images.size(); - auto input_dims = trt_common_->getBindingDimensions(0); + auto input_dims = trt_common_->getTensorShape(0); input_dims.d[0] = batch_size; for (const auto & image : images) { @@ -610,7 +621,9 @@ void TrtYoloX::preprocessWithRoiGpu( src_height_ = height; } if (!image_buf_h_) { - trt_common_->setBindingDimensions(0, input_dims); + if (!trt_common_->setInputShape(0, input_dims)) { + return; + } } const float input_height = static_cast(input_dims.d[2]); const float input_width = static_cast(input_dims.d[3]); @@ -662,9 +675,11 @@ void TrtYoloX::preprocessWithRoi( const std::vector & images, const std::vector & rois) { const auto batch_size = images.size(); - auto input_dims = trt_common_->getBindingDimensions(0); + auto input_dims = trt_common_->getTensorShape(0); input_dims.d[0] = batch_size; - trt_common_->setBindingDimensions(0, input_dims); + if (!trt_common_->setInputShape(0, input_dims)) { + return; + } const float input_height = static_cast(input_dims.d[2]); const float input_width = static_cast(input_dims.d[3]); std::vector dst_images; @@ -700,7 +715,7 @@ void TrtYoloX::preprocessWithRoi( void TrtYoloX::multiScalePreprocessGpu(const cv::Mat & image, const std::vector & rois) { const auto batch_size = rois.size(); - auto input_dims = trt_common_->getBindingDimensions(0); + auto input_dims = trt_common_->getTensorShape(0); input_dims.d[0] = batch_size; @@ -722,7 +737,9 @@ void TrtYoloX::multiScalePreprocessGpu(const cv::Mat & image, const std::vector< src_height_ = height; if (!image_buf_h_) { - trt_common_->setBindingDimensions(0, input_dims); + if (!trt_common_->setInputShape(0, input_dims)) { + return; + } } const float input_height = static_cast(input_dims.d[2]); const float input_width = static_cast(input_dims.d[3]); @@ -770,9 +787,11 @@ void TrtYoloX::multiScalePreprocessGpu(const cv::Mat & image, const std::vector< void TrtYoloX::multiScalePreprocess(const cv::Mat & image, const std::vector & rois) { const auto batch_size = rois.size(); - auto input_dims = trt_common_->getBindingDimensions(0); + auto input_dims = trt_common_->getTensorShape(0); input_dims.d[0] = batch_size; - trt_common_->setBindingDimensions(0, input_dims); + if (!trt_common_->setInputShape(0, input_dims)) { + return; + } const float input_height = static_cast(input_dims.d[2]); const float input_width = static_cast(input_dims.d[3]); std::vector dst_images; @@ -806,9 +825,6 @@ void TrtYoloX::multiScalePreprocess(const cv::Mat & image, const std::vector & images, ObjectArrays & objects, const std::vector & rois) { - if (!trt_common_->isInitialized()) { - return false; - } if (use_gpu_preprocess_) { preprocessWithRoiGpu(images, rois); } else { @@ -827,9 +843,6 @@ bool TrtYoloX::doInferenceWithRoi( bool TrtYoloX::doMultiScaleInference( const cv::Mat & image, ObjectArrays & objects, const std::vector & rois) { - if (!trt_common_->isInitialized()) { - return false; - } if (use_gpu_preprocess_) { multiScalePreprocessGpu(image, rois); } else { @@ -849,8 +862,10 @@ bool TrtYoloX::feedforward(const std::vector & images, ObjectArrays & o std::vector buffers = { input_d_.get(), out_num_detections_d_.get(), out_boxes_d_.get(), out_scores_d_.get(), out_classes_d_.get()}; - - trt_common_->enqueueV2(buffers.data(), *stream_, nullptr); + if (!trt_common_->setTensorsAddresses(buffers)) { + return false; + } + trt_common_->enqueueV3(*stream_); const auto batch_size = images.size(); auto out_num_detections = std::make_unique(batch_size); @@ -903,7 +918,11 @@ bool TrtYoloX::feedforwardAndDecode( if (multitask_) { buffers = {input_d_.get(), out_prob_d_.get(), segmentation_out_prob_d_.get()}; } - trt_common_->enqueueV2(buffers.data(), *stream_, nullptr); + + if (!trt_common_->setTensorsAddresses(buffers)) { + return false; + } + trt_common_->enqueueV3(*stream_); const auto batch_size = images.size(); @@ -933,7 +952,7 @@ bool TrtYoloX::feedforwardAndDecode( static_cast(segmentation_out_elem_num_ / segmentation_out_elem_num_per_batch_); for (int m = 0; m < multitask_; m++) { const auto output_dims = - trt_common_->getBindingDimensions(m + 2); // 0 : input, 1 : output for detections + trt_common_->getTensorShape(m + 2); // 0 : input, 1 : output for detections size_t out_elem_num = std::accumulate( output_dims.d + 1, output_dims.d + output_dims.nbDims, 1, std::multiplies()); out_elem_num = out_elem_num * batch; @@ -972,7 +991,10 @@ bool TrtYoloX::multiScaleFeedforward(const cv::Mat & image, int batch_size, Obje input_d_.get(), out_num_detections_d_.get(), out_boxes_d_.get(), out_scores_d_.get(), out_classes_d_.get()}; - trt_common_->enqueueV2(buffers.data(), *stream_, nullptr); + if (!trt_common_->setTensorsAddresses(buffers)) { + return false; + } + trt_common_->enqueueV3(*stream_); auto out_num_detections = std::make_unique(batch_size); auto out_boxes = std::make_unique(4 * batch_size * max_detections_); @@ -1020,7 +1042,10 @@ bool TrtYoloX::multiScaleFeedforwardAndDecode( const cv::Mat & image, int batch_size, ObjectArrays & objects) { std::vector buffers = {input_d_.get(), out_prob_d_.get()}; - trt_common_->enqueueV2(buffers.data(), *stream_, nullptr); + if (!trt_common_->setTensorsAddresses(buffers)) { + return false; + } + trt_common_->enqueueV3(*stream_); CHECK_CUDA_ERROR(cudaMemcpyAsync( out_prob_h_.get(), out_prob_d_.get(), sizeof(float) * out_elem_num_, cudaMemcpyDeviceToHost, @@ -1042,7 +1067,7 @@ void TrtYoloX::decodeOutputs( float * prob, ObjectArray & objects, float scale, cv::Size & img_size) const { ObjectArray proposals; - auto input_dims = trt_common_->getBindingDimensions(0); + auto input_dims = trt_common_->getTensorShape(0); const float input_height = static_cast(input_dims.d[2]); const float input_width = static_cast(input_dims.d[3]); std::vector grid_strides; @@ -1298,4 +1323,9 @@ void TrtYoloX::getColorizedMask( } } +int TrtYoloX::getBatchSize() const +{ + return batch_size_; +} + } // namespace autoware::tensorrt_yolox diff --git a/perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp b/perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp index 94a3a37a4d08f..2048279dcf3f1 100644 --- a/perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp +++ b/perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp @@ -83,19 +83,18 @@ TrtYoloXNode::TrtYoloXNode(const rclcpp::NodeOptions & node_options) roi_overlay_segment_labels_.ANIMAL = declare_parameter("roi_overlay_segment_label.ANIMAL"); replaceLabelMap(); - autoware::tensorrt_common::BuildConfig build_config( - calibration_algorithm, dla_core_id, quantize_first_layer, quantize_last_layer, - profile_per_layer, clip_value); + TrtCommonConfig trt_config( + model_path, precision, "", (1ULL << 30U), dla_core_id, profile_per_layer); + + CalibrationConfig calib_config( + calibration_algorithm, quantize_first_layer, quantize_last_layer, clip_value); const double norm_factor = 1.0; const std::string cache_dir = ""; - const autoware::tensorrt_common::BatchConfig batch_config{1, 1, 1}; - const size_t max_workspace_size = (1 << 30); trt_yolox_ = std::make_unique( - model_path, precision, label_map_.size(), score_threshold, nms_threshold, build_config, - preprocess_on_gpu, gpu_id, calibration_image_list_path, norm_factor, cache_dir, batch_config, - max_workspace_size, color_map_path); + trt_config, label_map_.size(), score_threshold, nms_threshold, preprocess_on_gpu, gpu_id, + calibration_image_list_path, norm_factor, cache_dir, color_map_path, calib_config); if (!trt_yolox_->isGPUInitialized()) { RCLCPP_ERROR(this->get_logger(), "GPU %d does not exist or is not suitable.", gpu_id); diff --git a/perception/autoware_tensorrt_yolox/src/yolox_single_image_inference_node.cpp b/perception/autoware_tensorrt_yolox/src/yolox_single_image_inference_node.cpp index 243e82c65dab9..63c0ee0cd3e8a 100644 --- a/perception/autoware_tensorrt_yolox/src/yolox_single_image_inference_node.cpp +++ b/perception/autoware_tensorrt_yolox/src/yolox_single_image_inference_node.cpp @@ -46,7 +46,9 @@ class YoloXSingleImageInferenceNode : public rclcpp::Node const auto output_image_path = declare_parameter("output_image_path", p.string() + "_detect" + ext); - auto trt_yolox = std::make_unique(model_path, precision); + auto trt_config = tensorrt_common::TrtCommonConfig(model_path, precision); + + auto trt_yolox = std::make_unique(trt_config); auto image = cv::imread(image_path); tensorrt_yolox::ObjectArrays objects; std::vector masks; diff --git a/perception/autoware_traffic_light_classifier/CMakeLists.txt b/perception/autoware_traffic_light_classifier/CMakeLists.txt index d132577743ab0..181037caebfa5 100644 --- a/perception/autoware_traffic_light_classifier/CMakeLists.txt +++ b/perception/autoware_traffic_light_classifier/CMakeLists.txt @@ -34,7 +34,6 @@ if(NVINFER AND NVONNXPARSER AND NVINFER_PLUGIN) if(CUDA_VERBOSE) message(STATUS "TensorRT is available!") message(STATUS "NVINFER: ${NVINFER}") - message(STATUS "NVPARSERS: ${NVPARSERS}") message(STATUS "NVINFER_PLUGIN: ${NVINFER_PLUGIN}") message(STATUS "NVONNXPARSER: ${NVONNXPARSER}") endif() diff --git a/perception/autoware_traffic_light_classifier/src/classifier/cnn_classifier.cpp b/perception/autoware_traffic_light_classifier/src/classifier/cnn_classifier.cpp index f9bf2509aa2ae..d47cb1500fffd 100644 --- a/perception/autoware_traffic_light_classifier/src/classifier/cnn_classifier.cpp +++ b/perception/autoware_traffic_light_classifier/src/classifier/cnn_classifier.cpp @@ -51,13 +51,10 @@ CNNClassifier::CNNClassifier(rclcpp::Node * node_ptr) : node_ptr_(node_ptr) } readLabelfile(label_file_path, labels_); - nvinfer1::Dims input_dim = autoware::tensorrt_common::get_input_dims(model_file_path); - assert(input_dim.d[0] > 0); - batch_size_ = input_dim.d[0]; - autoware::tensorrt_common::BatchConfig batch_config{batch_size_, batch_size_, batch_size_}; classifier_ = std::make_unique( - model_file_path, precision, batch_config, mean_, std_); + model_file_path, precision, mean_, std_); + batch_size_ = classifier_->getBatchSize(); if (node_ptr_->declare_parameter("build_only", false)) { RCLCPP_INFO(node_ptr_->get_logger(), "TensorRT engine is built and shutdown node."); rclcpp::shutdown(); diff --git a/perception/autoware_traffic_light_fine_detector/CMakeLists.txt b/perception/autoware_traffic_light_fine_detector/CMakeLists.txt index 80d6e43c098ed..dffbab0e77681 100644 --- a/perception/autoware_traffic_light_fine_detector/CMakeLists.txt +++ b/perception/autoware_traffic_light_fine_detector/CMakeLists.txt @@ -39,7 +39,6 @@ if(NVINFER AND NVONNXPARSER AND NVINFER_PLUGIN) if(CUDA_VERBOSE) message(STATUS "TensorRT is available!") message(STATUS "NVINFER: ${NVINFER}") - message(STATUS "NVPARSERS: ${NVPARSERS}") message(STATUS "NVINFER_PLUGIN: ${NVINFER_PLUGIN}") message(STATUS "NVONNXPARSER: ${NVONNXPARSER}") endif() diff --git a/perception/autoware_traffic_light_fine_detector/src/traffic_light_fine_detector_node.cpp b/perception/autoware_traffic_light_fine_detector/src/traffic_light_fine_detector_node.cpp index 37ffca4a9526c..d9e0471a43d62 100644 --- a/perception/autoware_traffic_light_fine_detector/src/traffic_light_fine_detector_node.cpp +++ b/perception/autoware_traffic_light_fine_detector/src/traffic_light_fine_detector_node.cpp @@ -75,21 +75,18 @@ TrafficLightFineDetectorNode::TrafficLightFineDetectorNode(const rclcpp::NodeOpt RCLCPP_ERROR(this->get_logger(), "Could not find tlr id"); } - const autoware::tensorrt_common::BuildConfig build_config = - autoware::tensorrt_common::BuildConfig("MinMax", -1, false, false, false, 0.0); - const bool cuda_preprocess = true; const std::string calib_image_list = ""; const double scale = 1.0; const std::string cache_dir = ""; - nvinfer1::Dims input_dim = autoware::tensorrt_common::get_input_dims(model_path); - assert(input_dim.d[0] > 0); - batch_size_ = input_dim.d[0]; - const autoware::tensorrt_common::BatchConfig batch_config{batch_size_, batch_size_, batch_size_}; + + auto trt_config = autoware::tensorrt_common::TrtCommonConfig(model_path, precision); trt_yolox_ = std::make_unique( - model_path, precision, num_class, score_thresh_, nms_threshold, build_config, cuda_preprocess, - gpu_id, calib_image_list, scale, cache_dir, batch_config); + trt_config, num_class, score_thresh_, nms_threshold, cuda_preprocess, gpu_id, calib_image_list, + scale, cache_dir); + + batch_size_ = trt_yolox_->getBatchSize(); if (!trt_yolox_->isGPUInitialized()) { RCLCPP_ERROR(this->get_logger(), "GPU %d does not exist or is not suitable.", gpu_id); From 76aa83fcd1a716692789fdc50fed6369c154cb43 Mon Sep 17 00:00:00 2001 From: Kazunori-Nakajima <169115284+Kazunori-Nakajima@users.noreply.github.com> Date: Fri, 10 Jan 2025 17:35:41 +0900 Subject: [PATCH 180/334] fix(planning_evaluator): update lateral_trajectory_displacement to absolute value (#9696) * fix(planning_evaluator): update lateral_trajectory_displacement to absolute value Signed-off-by: Kasunori-Nakajima * style(pre-commit): autofix --------- Signed-off-by: Kasunori-Nakajima Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../src/metrics/deviation_metrics.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/evaluator/autoware_planning_evaluator/src/metrics/deviation_metrics.cpp b/evaluator/autoware_planning_evaluator/src/metrics/deviation_metrics.cpp index 82ba86c65d6af..9b5959948f8cb 100644 --- a/evaluator/autoware_planning_evaluator/src/metrics/deviation_metrics.cpp +++ b/evaluator/autoware_planning_evaluator/src/metrics/deviation_metrics.cpp @@ -58,7 +58,8 @@ Accumulator calcLocalLateralTrajectoryDisplacement( autoware::motion_utils::calcLateralOffset(prev.points, ego_pose.position); const auto traj_lateral_deviation = autoware::motion_utils::calcLateralOffset(traj.points, ego_pose.position); - const auto lateral_trajectory_displacement = traj_lateral_deviation - prev_lateral_deviation; + const auto lateral_trajectory_displacement = + std::abs(traj_lateral_deviation - prev_lateral_deviation); stat.add(lateral_trajectory_displacement); return stat; } From 7d63242e089ec25e0a976d4b6c3c8cda21def59a Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Fri, 10 Jan 2025 18:02:48 +0900 Subject: [PATCH 181/334] docs(lane_change): explaining cancel and abort process (#9845) * docs(lane_change): explaining cancel and abort process Signed-off-by: Zulfaqar Azmi * slight fix in formatting Signed-off-by: Zulfaqar Azmi * rephrase sentence Signed-off-by: Zulfaqar Azmi * rephrase and replace image for cancel Signed-off-by: Zulfaqar Azmi * Cancel explanations and limitations Signed-off-by: Zulfaqar Azmi * revise abort figure Signed-off-by: Zulfaqar Azmi * revise flow chart Signed-off-by: Zulfaqar Azmi * rephase sentence Signed-off-by: Zulfaqar Azmi * minor fix Signed-off-by: Zulfaqar Azmi * finish up Signed-off-by: Zulfaqar Azmi * offers change to reduces for negative connotation Signed-off-by: Zulfaqar Azmi * minor fix Signed-off-by: Zulfaqar Azmi * move limitation all the way down Signed-off-by: Zulfaqar Azmi * precommit Signed-off-by: Zulfaqar Azmi * equation mistake Signed-off-by: Zulfaqar Azmi * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> * rename subheading Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Zulfaqar Azmi Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> --- .../README.md | 277 ++++++++++++------ .../images/check_able_to_return.png | Bin 0 -> 26510 bytes .../images/lane_change-abort.png | Bin 222968 -> 22119 bytes .../images/lane_change-abort_computation.png | Bin 0 -> 19345 bytes .../images/lane_change-cancel.png | Bin 175745 -> 25706 bytes .../lane_change-cant_cancel_no_abort.png | Bin 138829 -> 16484 bytes 6 files changed, 193 insertions(+), 84 deletions(-) create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/check_able_to_return.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/lane_change-abort_computation.png diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md index 0508dc753a2e8..c5cdf0bb68bc2 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md @@ -722,47 +722,129 @@ If the ego vehicle gets stuck, to avoid stuck, it enables lane change in crosswa If the ego vehicle stops more than `stuck_detection.stop_time` seconds, it is regarded as a stuck. If the ego vehicle velocity is smaller than `stuck_detection.velocity`, it is regarded as stopping. -### Aborting lane change +## Lane change completion checks + +To determine if the ego vehicle has successfully changed lanes, one of two criteria must be met: either the longitudinal or the lateral criteria. + +For the longitudinal criteria, the ego vehicle must pass the lane-changing end pose and be within the `finish_judge_buffer` distance from it. The module then checks if the ego vehicle is in the target lane. If true, the module returns success. This check ensures that the planner manager updates the root lanelet correctly based on the ego vehicle's current pose. Without this check, if the ego vehicle is changing lanes while avoiding an obstacle and its current pose is in the original lane, the planner manager might set the root lanelet as the original lane. This would force the ego vehicle to perform the lane change again. With the target lane check, the ego vehicle is confirmed to be in the target lane, and the planner manager can correctly update the root lanelets. -The abort process may result in three different outcome; Cancel, Abort and Stop/Cruise. +If the longitudinal criteria are not met, the module evaluates the lateral criteria. For the lateral criteria, the ego vehicle must be within `finish_judge_lateral_threshold` distance from the target lane's centerline, and the angle deviation must be within `finish_judge_lateral_angle_deviation` degrees. The angle deviation check ensures there is no sudden steering. If the angle deviation is set too high, the ego vehicle's orientation could deviate significantly from the centerline, causing the trajectory follower to aggressively correct the steering to return to the centerline. Keeping the angle deviation value as small as possible avoids this issue. -The following depicts the flow of the abort lane change check. +The process of determining lane change completion is shown in the following diagram. ```plantuml @startuml -skinparam monochrome true skinparam defaultTextAlignment center +skinparam backgroundColor #WHITE + +title Lane change completion judge + +start + +:Calculate distance from current ego pose to lane change end pose; + +if (Is ego velocity < 1.0?) then (YES) + :Set finish_judge_buffer to 0.0; +else (NO) + :Set finish_judge_buffer to lane_change_finish_judge_buffer; +endif + +if (ego has passed the end_pose and ego is finish_judge_buffer meters away from end_pose?) then (YES) + if (Current ego pose is in target lanes' polygon?) then (YES) + :Lane change is completed; + stop + else (NO) +:Lane change is NOT completed; +stop + endif +else (NO) +endif + +if (ego's yaw deviation to centerline exceeds finish_judge_lateral_angle_deviation?) then (YES) + :Lane change is NOT completed; + stop +else (NO) + :Calculate distance to the target lanes' centerline; + if (abs(distance to the target lanes' centerline) is less than finish_judge_lateral_threshold?) then (YES) + :Lane change is completed; + stop + else (NO) + :Lane change is NOT completed; + stop + endif +endif + +@enduml +``` + +## Terminal Lane Change Path + +Depending on the space configuration around the Ego vehicle, it is possible that a valid LC path cannot be generated. If that happens, then Ego will get stuck at `terminal_start` and not be able to proceed. Therefore we introduced the terminal LC path feature; when ego gets near to the terminal point (dist to `terminal_start` is less than the maximum lane change length) a terminal lane changing path will be computed starting from the terminal start point on the current lane and connects to the target lane. The terminal path only needs to be computed once in each execution of LC module. If no valid candidate paths are found in the path generation process, then the terminal path will be used as a fallback candidate path, the safety of the terminal path is not ensured and therefore it can only be force approved. The following images illustrate the expected behavior without and with the terminal path feature respectively: + +![no terminal path](./images/lane_change-no_terminal_path.png) + +![terminal path](./images/lane_change-terminal_path.png) + +Additionally if terminal path feature is enabled and path is computed, stop point placement can be configured to be at the edge of the current lane instead of at the `terminal_start` position, as indicated by the dashed red line in the image above. + +## Aborting a Previously Approved Lane Change + +Once the lane change path is approved, there are several situations where we may need to abort the maneuver. The abort process is triggered when any of the following conditions is met + +1. The ego vehicle is near a traffic light, crosswalk, or intersection, and it is possible to complete the lane change after the ego vehicle passes these areas. +2. The target object list is updated, requiring us to [delay lane change](#delay-lane-change-check) +3. The lane change is forcefully canceled via [RTC](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-interfaces/ad-api/features/cooperation/). +4. The path has become unsafe. + +Furthermore, if the path has become unsafe, there are three possible outcomes for the maneuver: + +1. **CANCEL**: The approved lane change path is canceled, and the ego vehicle resumes its previous maneuver. +2. **ABORT**: The lane change module generates a return path to bring the ego vehicle back to its current lane. +3. **CRUISE** or **STOP**: If aborting is not feasible, the ego vehicle continues with the lane change. [Another module](https://autowarefoundation.github.io/autoware.universe/main/planning/autoware_obstacle_cruise_planner/) should decide whether the ego vehicle should cruise or stop in this scenario. + +**CANCEL** can be enabled by setting the `cancel.enable_on_prepare_phase` flag to `true`, and **ABORT** can be enabled by setting the `cancel.enable_on_lane_changing_phase` flag to true. + +!!! warning + + Enabling **CANCEL** is a prerequisite for enabling **ABORT**. + +!!! warning + + When **CANCEL** is disabled, all maneuvers will default to either **CRUISE** or **STOP**. + +The chart shows the high level flow of the lane change abort process. + +```plantuml +@startuml +skinparam defaultTextAlignment center +skinparam backgroundColor #WHITE -title Abort Lane Change +title High-Level Flow of Lane Change Abort Process while(Lane Following) if (Lane Change required) then (**YES**) - if (Safe to change lane) then (**SAFE**) - while(Lane Changing) - if (Lane Change Completed) then (**YES**) - break - else (**NO**) - if (Is Abort Condition Satisfied) then (**NO**) + if (Safe to change lane) then (SAFE) + :Approve safe path; + while(Lane change maneuver is completed?) is (**NO**) + if (Is cancel/abort Condition satisfied) then (**NO**) else (**YES**) if (Is Enough margin to retry lane change) then (**YES**) - if (Ego is on lane change prepare phase) then (**YES**) - :Cancel lane change; + if (Ego is preparing to change lane) then (**YES**) + #LightPink:CANCEL; break else (**NO**) - if (Will the overhang to target lane be less than threshold?) then (**YES**) - :Perform abort maneuver; + if (Overhang from current lanes is less than threshold?) then (**YES**) + #Cyan:ABORT; break else (NO) - :Stop or Cruise depending on the situation; endif endif else (**NO**) endif + #Yellow:CRUISE/STOP; endif - endif - :Stop and wait; - endwhile - else (**UNSAFE**) + endwhile (**YES**) + else (UNSAFE) endif else (**NO**) endif @@ -772,117 +854,137 @@ detach @enduml ``` -During a lane change, a safety check is made in consideration of the deceleration of the ego vehicle, and a safety check is made for `cancel.deceleration_sampling_num` deceleration patterns, and the lane change will be canceled if the abort condition is satisfied for all deceleration patterns. +### Preventing Oscillating Paths When Unsafe -To preventive measure for lane change path oscillations caused by alternating safe and unsafe conditions, an additional hysteresis count check is implemented before executing an abort or cancel maneuver. If unsafe, the `unsafe_hysteresis_count_` is incremented and compared against `unsafe_hysteresis_threshold`; exceeding it prompts an abort condition check, ensuring decisions are made with consideration to recent safety assessments as shown in flow chart above. This mechanism stabilizes decision-making, preventing abrupt changes due to transient unsafe conditions. +Lane change paths can oscillate when conditions switch between safe and unsafe. To address this, a hysteresis count check is added before executing an abort maneuver. When the path is unsafe, the `unsafe_hysteresis_count_` increases. If it exceeds the `unsafe_hysteresis_threshold`, an abort condition check is triggered. This logic stabilizes the path approval process and prevents abrupt changes caused by temporary unsafe conditions. ```plantuml @startuml skinparam defaultTextAlignment center skinparam backgroundColor #WHITE -title Abort Lane Change +title Hysteresis count flow for oscillation prevention +while (lane changing completed?) is (FALSE) if (Perform collision check?) then (SAFE) :Reset unsafe_hysteresis_count_; else (UNSAFE) :Increase unsafe_hysteresis_count_; - if (unsafe_hysteresis_count_ > unsafe_hysteresis_threshold?) then (FALSE) + if (unsafe_hysteresis_count_ is more than\n unsafe_hysteresis_threshold?) then (FALSE) else (TRUE) #LightPink:Check abort condition; - stop + -[hidden]-> + detach endif endif -:Continue lane changing; +endwhile (TRUE) +stop @enduml ``` -#### Cancel +### Evaluating Ego Vehicle's Position to Prevent Abrupt Maneuvers -Suppose the lane change trajectory is evaluated as unsafe. In that case, if the ego vehicle has not departed from the current lane yet, the trajectory will be reset, and the ego vehicle will resume the lane following the maneuver. +To avoid abrupt maneuvers during **CANCEL** or **ABORT**, the lane change module ensures the ego vehicle can safely return to the original lane. This is done through geometric checks that verify whether the ego vehicle remains within the lane boundaries. -The function can be enabled by setting `enable_on_prepare_phase` to `true`. +The edges of the ego vehicle’s footprint are compared against the boundary of the current lane to determine if they exceed the overhang tolerance, `cancel.overhang_tolerance`. If the distance from any edge of the footprint to the boundary exceeds this threshold, the vehicle is considered to be diverging. -The following image illustrates the cancel process. +The footprints checked against the lane boundary include: -![cancel](./images/lane_change-cancel.png) +1. Current Footprint: Based on the ego vehicle's current position. +2. Future Footprint: Based on the ego vehicle's estimated position after traveling a distance, calculated as $𝑑_{est}=𝑣_{ego} \cdot \Delta_{𝑡}$, where -#### Abort + - $v_{ego}$ is ego vehicle's current velocity + - $\Delta_{t}$ is parameterized time constant value, `cancel.delta_time`. -Assume the ego vehicle has already departed from the current lane. In that case, it is dangerous to cancel the path, and it will cause the ego vehicle to change the heading direction abruptly. In this case, planning a trajectory that allows the ego vehicle to return to the current path while minimizing the heading changes is necessary. In this case, the lane change module will generate an abort path. The following images show an example of the abort path. Do note that the function DOESN'T GUARANTEE a safe abort process, as it didn't check the presence of the surrounding objects and/or their reactions. The function can be enable manually by setting both `enable_on_prepare_phase` and `enable_on_lane_changing_phase` to `true`. The parameter `max_lateral_jerk` need to be set to a high value in order for it to work. + as depicted in the following diagram -![abort](./images/lane_change-abort.png) + ![can_return](./images/check_able_to_return.png) -#### Stop/Cruise +!!! note -The last behavior will also occur if the ego vehicle has departed from the current lane. If the abort function is disabled or the abort is no longer possible, the ego vehicle will attempt to stop or transition to the obstacle cruise mode. Do note that the module DOESN'T GUARANTEE safe maneuver due to the unexpected behavior that might've occurred during these critical scenarios. The following images illustrate the situation. + The ego vehicle is considered capable of safely returning to the current lane only if **BOTH** the current and future footprint checks are `true`. -![stop](./images/lane_change-cant_cancel_no_abort.png) +### Checking Approved Path Safety -## Lane change completion checks +The lane change module samples accelerations along the path and recalculates velocity to perform safety checks. The motivation for this feature is explained in the [Limitation](#limitation) section. -To determine if the ego vehicle has successfully changed lanes, one of two criteria must be met: either the longitudinal or the lateral criteria. +The computation of sampled accelerations is as follows: -For the longitudinal criteria, the ego vehicle must pass the lane-changing end pose and be within the `finish_judge_buffer` distance from it. The module then checks if the ego vehicle is in the target lane. If true, the module returns success. This check ensures that the planner manager updates the root lanelet correctly based on the ego vehicle's current pose. Without this check, if the ego vehicle is changing lanes while avoiding an obstacle and its current pose is in the original lane, the planner manager might set the root lanelet as the original lane. This would force the ego vehicle to perform the lane change again. With the target lane check, the ego vehicle is confirmed to be in the target lane, and the planner manager can correctly update the root lanelets. +Let -If the longitudinal criteria are not met, the module evaluates the lateral criteria. For the lateral criteria, the ego vehicle must be within `finish_judge_lateral_threshold` distance from the target lane's centerline, and the angle deviation must be within `finish_judge_lateral_angle_deviation` degrees. The angle deviation check ensures there is no sudden steering. If the angle deviation is set too high, the ego vehicle's orientation could deviate significantly from the centerline, causing the trajectory follower to aggressively correct the steering to return to the centerline. Keeping the angle deviation value as small as possible avoids this issue. +$$ +\text{resolution} = \frac{a_{\text{min}} - a_{\text{LC}}}{N} +$$ -The process of determining lane change completion is shown in the following diagram. +The sequence of sampled accelerations is then given as -```plantuml -@startuml -skinparam defaultTextAlignment center -skinparam backgroundColor #WHITE +$$ +\text{acc} = a_{\text{LC}} + k \cdot \text{resolution}, \quad k = [0, N] +$$ -title Lane change completion judge +where -start +- $a_{\text{min}}$, is the minimum of the parameterized [global acceleration constant](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/planning/scenario_planning/common/common.param.yaml) `normal.min_acc` or the [parameterized constant](#essential-lane-change-parameters) `trajectory.min_longitudinal_acceleration`. +- $a_{\text{LC}}$ is the acceleration used to generate the approved path. +- $N$ is the parameterized constant `cancel.deceleration_sampling` -:Calculate distance from current ego pose to lane change end pose; +If none of the sampled accelerations pass the safety check, the lane change path will be canceled, subject to the [hysteresis check](#preventing-oscillating-paths-when-unsafe). -if (Is ego velocity < 1.0?) then (YES) - :Set finish_judge_buffer to 0.0; -else (NO) - :Set finish_judge_buffer to lane_change_finish_judge_buffer; -endif +### Cancel -if (ego has passed the end_pose and ego is finish_judge_buffer meters away from end_pose?) then (YES) - if (Current ego pose is in target lanes' polygon?) then (YES) - :Lane change is completed; - stop - else (NO) -:Lane change is NOT completed; -stop - endif -else (NO) -endif +When lane change is canceled, the approved path is reset. After the reset, the ego vehicle will return to following the original reference path (the last approved path before the lane change started), as illustrated in the following image -if (ego's yaw deviation to centerline exceeds finish_judge_lateral_angle_deviation?) then (YES) - :Lane change is NOT completed; - stop -else (NO) - :Calculate distance to the target lanes' centerline; - if (abs(distance to the target lanes' centerline) is less than finish_judge_lateral_threshold?) then (YES) - :Lane change is completed; - stop - else (NO) - :Lane change is NOT completed; - stop - endif -endif +![cancel](./images/lane_change-cancel.png) -@enduml -``` +The following parameters can be configured to tune the behavior of the cancel process: -## Terminal Lane Change Path +1. [Safety constraints](#safety-constraints-to-cancel-lane-change-path) for cancel. +2. [Safety constraints](#safety-constraints-specifically-for-stopped-or-parked-vehicles) for parked vehicle. -Depending on the space configuration around the Ego vehicle, it is possible that a valid LC path cannot be generated. If that happens, then Ego will get stuck at `terminal_start` and will be not be able to proceed. Therefore we introduced the terminal LC path feature; when ego gets near to the terminal point (dist to `terminal_start` is less than the maximum lane change length) a terminal lane changing path will be computed starting from the terminal start point on the current lane and connects to the target lane. The terminal path only needs to be computed once in each execution of LC module. If no valid candidate paths are found in the path generation process, then the terminal path will be used as a fallback candidate path, the safety of the terminal path is not ensured and therefore it can only be force approved. The following images illustrate the expected behavior without and with the terminal path feature respectively: +!!! note -![no terminal path](./images/lane_change-no_terminal_path.png) + To ensure feasible behavior, all safety constraint values must be equal to or less than their corresponding parameters in the [execution](#safety-constraints-during-lane-change-path-is-computed) settings. -![terminal path](./images/lane_change-terminal_path.png) + - The closer the values, the more conservative the lane change behavior will be. This means it will be easier to cancel the lane change but harder for the ego vehicle to complete a lane change. + - The larger the difference, the more aggressive the lane change behavior will be. This makes it harder to cancel the lane change but easier for the ego vehicle to change lanes. -Additionally if terminal path feature is enabled and path is computed, stop point placement can be configured to be at the edge of the current lane instead of at the `terminal_start` position, as indicated by the dashed red line in the image above. +### Abort + +During the prepare phase, the ego vehicle follows the previously approved path. However, once the ego vehicle begins the lane change, its heading starts to diverge from this path. Resetting to the previously approved path in this situation would cause abrupt steering, as the controller would attempt to rapidly realign the vehicle with the reference trajectory. + +Instead, the lane change module generates an abort path. This return path is specifically designed to guide the ego vehicle back to the current lane, avoiding any sudden maneuvers. The following image provides an illustration of the abort process. + +![abort](./images/lane_change-abort.png) + +The abort path is generated by shifting the approved lane change path using the path shifter. This ensures the continuity in lateral velocity, and prevents abrupt changes in the vehicle’s movement. The abort start shift and abort end shift are computed as follows: + +1. Start Shift: $d_{start}^{abort} = v_{ego} \cdot \Delta_{t}$ +2. End Shift: $d_{end}^{abort} = v_{ego} \cdot ( \Delta_{t} + t_{end} )$ + +- $v_{ego}$ is ego vehicle's current velocity +- $\Delta_{t}$ is parameterized time constant value, `cancel.delta_time`. +- $t_{end}$ is the parameterized time constant value, `cancel.duration`. + +as depicted in the following diagram + +![abort_computation](./images/lane_change-abort_computation.png) + +!!! note + + When executing the abort process, comfort is not a primary concern. However, due to safety considerations, limited real-world testing has been conducted to tune or validate this parameter. Currently, the maximum lateral jerk is set to an arbitrary value. To avoid generating a path with excessive lateral jerk, this value can be configured using `cancel.max_lateral_jerk`. + +!!! note + + Lane change module returns `ModuleStatus::FAILURE` once abort is completed. + +### Stop/Cruise + +Once canceling or aborting the lane change is no longer an option, the ego vehicle will proceed with the lane change. This can happen in the following situations: + +- The ego vehicle is performing a lane change near a terminal or dead-end, making it impossible to return to the original lane. In such cases, completing the lane change is necessary. +- If safety parameters are tuned too aggressively, it becomes harder to cancel or abort the lane change. This reduces tolerance for unexpected behaviors from surrounding vehicles, such as a trailing vehicle in the target lane suddenly accelerating or a leading vehicle suddenly decelerating. Aggressive settings leave less room for error during the maneuver. + +![stop](./images/lane_change-cant_cancel_no_abort.png) ## Parameters @@ -1095,3 +1197,10 @@ Available information 3. Object is safe or not, shown by the color of the polygon (Green = Safe, Red = unsafe) 4. Valid candidate paths. 5. Position when lane changing start and end. + +## Limitation + +1. When a lane change is canceled, the lane change module returns `ModuleStatus::FAILURE`. As the module is removed from the approved module stack (see [Failure modules](https://autowarefoundation.github.io/autoware.universe/main/planning/behavior_path_planner/autoware_behavior_path_planner/docs/behavior_path_planner_manager_design/#failure-modules)), a new instance of the lane change module is initiated. Due to this, any information stored prior to the reset is lost. For example, the `lane_change_prepare_duration` in the `TransientData` is reset to its maximum value. +2. The lane change module has no knowledge of any velocity modifications introduced to the path after it is approved. This is because other modules may add deceleration points after subscribing to the behavior path planner output, and the final velocity is managed by the [velocity smoother](https://autowarefoundation.github.io/autoware.universe/pr-9845/planning/autoware_velocity_smoother/). Since this limitation affects **CANCEL**, the lane change module mitigates it by [sampling accelerations along the approved lane change path](#checking-approved-path-safety). These sampled accelerations are used during safety checks to estimate the velocity that might occur if the ego vehicle decelerates. +3. Ideally, the abort path should account for whether its execution would affect trailing vehicles in the current lane. However, the lane change module does not evaluate such interactions or assess whether the abort path is safe. As a result, **the abort path is not guaranteed to be safe**. To minimize the risk of unsafe situations, the abort maneuver is only permitted if the ego vehicle has not yet diverged from the current lane. +4. Due to limited resources, the abort path logic is not fully optimized. The generated path may overshoot, causing the return trajectory to slightly shift toward the opposite lane. This can be dangerous, especially if the opposite lane has traffic moving in the opposite direction. Furthermore, the logic does not account for different vehicle types, which can lead to varying effects. For instance, the behavior might differ significantly between a bus and a small passenger car. diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/check_able_to_return.png b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/check_able_to_return.png new file mode 100644 index 0000000000000000000000000000000000000000..1f01b6df5464ad77971fb0eea37c587b3434fc85 GIT binary patch literal 26510 zcmeFZWmuHm_cp8uN~oZKD2<4efJzAnLrF?AbP7m=bf+SUlp-N5&A<%O-3%FS7>@{L);tLlpT$7iRR=;oo z-yit<0^w!g=M$p~kAXifx~R)aUV!z}u3fmmctKuTLetY|V}>XpV(Gkdw}_>-OT9vx ziGtW-U{aFBpDiOpj!ALi=GWM~GWI2^O+D!>O=6IRd>jRnv^l$aMH$*SO@H8YfY$P5 zzX0z_vKMG<>G8|dC4ZxVFZuglwz2i4bRzB>3B^o-7w`xf|Lc!?$>IXRX>WXTrpf-t zXN+_Bg#MmP|LqCfKZ!WRcVf~>leZ}2gZ1Y`l4n$v|t9+Wc^LB|19v4knB`C zqqF$e|8(P*SoAKRi3Xhc=6LT;J}jD)g`eGepfe|(hn^1!`g=3X3xN%Hc)RceX3c0y zP$zf-SylyKp~1U!`RcdIS?}HoN5oc+k5{azCU$4?AIpEN95~0iSXg}%IQQruc(b4B z!5(=Fq1P^g1HIs9!_&G&H|*-j5L!h>_E-$6QkKDw z@9TDKlA?Z7<)o}n!DOyAJVz6orPN9PS2l4?0z&_cp6+ho?gbSxJ#<}Fohr4A@*xkH z^;*$w^v8bEa`4_PA1gHLjMTk!H>CD+F9}bbiE#k7d?a6^^YV4t1UnUIa1Pf;8WW5b z##0dFf9grYXBCZM zWR#eSdm|Awgjn&k_<)|U3X2J5IIP;Wci*J(&wH#uss6s=L>uFYk{waW5VhXA@@Lrv z31C_J)SG6~fbV!AJ_lC;mET~NsS4~A?Ar0;WhkiER|a7Z-Vt<0&`@cz#N_a@Ur2gv z5$3k~qnQA-IaOIHi139+NJQ!#8R=(S20@PGt$WfOcb1ShcP}mA|JBn4yo-RMJWYS8 z9iJtgBa(>xKE6Su$S4N$JV}5n&*!;)u1QW&x2*Ck1U##tMI7Oq>*EzyTvHRW(av|M40u6Uc~*uges-9+xqa@n}N<2tfv`V2Tv4P){*zE zKq*NeU*PyCm?woZ0m4vi^X#G42SvrSBIdvMiIte_bO-Xw>f|)U!L;kTaXiA`2^U#miOc|CvebYIf3ZWyh@dHdNHG>kF!`m-=zDUtu{LBO8Z01s@rM3 zJdIDYR9U{uQtg>KkM`)Vr205?6-4I8f8y{Qu4RMvk&u@gD_{fbT-r3|;z#}V-TqNo zCU72)^^%deSmeYur?jL#5*4tzfI!GL2MK^LoH)$#<-KSR(+we}RNr98Ty8A49dqwQ zMn&$&$!ceZLsaXEPK=pZ^q|sltSYJRe%2!|yWB+NJAJstB|LAmbZ2#6xUwjwrA!>P z`ekFbeu_VNv{7R(&Z0kAsC9je{CmAOW_5z?`=D!~N!o|tyG84rh}K$J$HaJ!D2J-~ zw^^19J>%n4f2@?Os|ODsqt0htAn>T_}F>mi1xHJru!;|T=Z6k zbigdxeT|J#4}dE~`z`T)bPV1N1Y^5MrDPRv|C3gu0IXY*h=;?FD|?7?<&1k$txSrr zo83UFs61ye0ZmtyTR>0)Y-Kj%*@yJB5B>A{hl>mx>te>9^8|wKqEe1MUyP*Iycp)E zMLPfSI>isfcgTBHLVu+KkM7PX>F;fyEO2RW9ir6C=0vvZcqhV?jS}Ydi855PEC*8M zdoz9DRdp|0g1l?m;I3(((e!KkV}>4vO_W7-v%(FrJm_h#wqY!VyVut!N4N!;m&>q* zkKJSsj};-)>2bLU1??QOdv|^$EPF&lPKcwBBo%A);ydi5T4~wA!c(8=kW2B zBHTW8LyngFW6{;oEgs(Lb$~EUyf4}awV?}KOJaa;^jV74-pGzOQXqDI>dEs&t%zo( zFo1-~vM~XNYKf#`U37IO54&bGrn!D-ws;bs z-mMRal>K{QhNJ)wCaNjKigS#Cc*NWk(rl}P%k}cwE|!kMk-;OVG=lCL z^~3QU0sEV%3={c_?*%EpC*Ax!x~@{(1`Avs)pvA*e=A!{)qJ$11m34B@Ceu|FsLpe za30cpLSSnY{gZB+CVbT_L?qBi0$f@+aSJb{Lwk*$65i$Dk!4i?@zSWUf;2O*c|6g z*A4fmNkIugGqNEZ;MrsCzBU)nh3%W+7KIJhZ&LwM{&GUmy1 zjLEul=O4L?0lDuW`$m50l{KBwawtn4Rv9&0Rj@AI98t;s!*ip!^Ak07n#ZgcYhAVW z6F#p!^Gbu`Yl72c@k}y$q(%}^TX2`5voog9!eL8!r4pX{19c5j7Q~!vC);fehWol# zgk|*>-(?pe{p)vfJ+@~BUd=V>P}7@9{I$6SNkAdo^yIH`Q4`2dsskMZ7@(Is-u}&A z04K$WyGB&MPphpeQ2W|Xk@h|hYRz!cwD}XFyif803r=V{Qu04aUQhv+JWIX9EQ4FJ z>jj>XTNH;6kjAZ`G2fGg;KNrFxz6w@ezI4=%VZG^%DWz{;kbB*i$VV-h?8~g;ps6! zb&6k9*iQ+FU^Yr)5-lvf5}x4i1T#3U;)^>SlihjzTb)k#05>E{`r+%{-+@j1lmxIM zeDU4$=hc^ful+(7*jHTIb+bPaD(DTl9Q!fT1%)cvzH7e=88ULf*x=Kd0)Hng=w+Bn=ZVdQU7=}so=Lz(Ide9 zEkSbzV*YrVpsSR?e!jM_N->a9{Z0h2>bX~#dw5Sl&56J_nM@ZZ~d0*9TTv#+upaY68t&Oo5qaUbD>SFyJ?~x@BYXH zq|oMXg~xsy9B|_~=NN!h%qQaU1S5Zcc3~u)QCsyU&e1egirqGE8>hZfY?JR2_*l7s=r^pfcFIuB}Qn=fb!2a|C|c$c;!5R zrCnK<|LF4H4~sA3_7y3j{mXm&bGpAC9x?=sYvz6R9~1b`uL4}T5YE3X_Je=h&%d7w zas^IR-s1)L-)!t(&zVO8>C68j&8 zn-Wd?ocp<}Eq1WeBZJezmIm$}6Mcw({jan7qspM~}n{^xIuIRsW)wD73V=HD0SzZ}jy3EAlz$Ig%c zb8+$Kz(;Kdi>9ysm(Pv?8c7A6hzt1W|3ox%(IC*-aqBG}BfB);(_*MW^-zWVj7`AV ziRI|)cP(_5y>WeE6znfXAmGxMTzWd0G7*K+?{DS|l>S?p;-i3%?4}<0QY+24OmKFF zal{-=Ic{#HJbUc71w_y-QhiT6Vy_a*0S6(Mee;MeGT2dwYuNX{OMfC_Z&Nt$S+{NVM-3%1{CCjVo{P!|2U;A3g{; zJLNXtC4KhTwknNB|K*smN6J!nOs7_nZj5d#A-V>=3xlu|*d__sm#`0j97(7iyy`R_ zt}326Z@Q#;h7awI{FgDdUV0nHW_jic^BRAs)U*hmnWeb5pzb%Uv91>n84t z9eyUs>$Fcy7CR$Kb+_vlA(@x2 zQ=5;uZ#^GKdvoltaQ|P&NC;FEt(=!G;y+fJLm>hxiK4`8cp48rE%n6@q$WL`uo=$# z_+Up(XLo6R1jxAgP?ZpE3Ve%>9OQbGBzXvEaMso6aG^VeHOj>b(NGUAQfm!Mb`D$W z`ohZ*AG7jqzIA4}#`k1@s&JwdYTo@xO-PXSpGX7jBWRo)h~M>=E$_&>9^(O-WqH9= zr66{uT9Jz8skxl`;rm39^8>hwfajbzX1$>3d4XTPkW)XcP^5PAY3<_?P{8>nwFEM1 z48vM~!H-7iN}~TV_%?gpAcJ=KPiXqmRQe>!MT`M?T5}~tF%d6!J#%lVXX27shYoNE zh5@Nogz6-mrQ^fA)#EY!_JL&}O0Ku)La#0SS?47C!P>Blojz1hT zKaL$UDjmvJtmWl6)oJvvpP6lJ^gG9*xW)6;%OOBX)7LMIe88z!m@uVsv71!HeSAZ= zbfcHwb|W5(F-%K8fDjIOMbQc^NPfa2Aih`Y{spn{qvq-1G_k=bGeeBwB zq&HRSQ<>u2!#?WRbisBEmQs+hD-c2zlj_wm>xp%PA7qzF#)embpZz%Dx7BMr!$M#7 zC3bhvf7hWnexO^@Mo$l#6>u1zyRNnaU#XZfAfxEcSS*dwD`Rv23@{kX=Zk$Tv z_54Qme&3n4Z@_iA3Zi}cRy>1bTJ*&m5{EK#%m<$OpB%cHo0$p>ToV3!-Kk_0`#Qmj-D5*`rlK`V%I_U_Z70wU>f zAbLWaukqQ*3hafvM)}@SpKaz=btiYj@r&LR5f8astz(y+ISHB{MQMJ!?Nr>!cV1yO zN0(}lcZqGxtNbwTwOP+dEYC(J%bBidFwGE(`~&L%5{Tyz0qF|0C>4;0^Bh-yQ>LRj zWji=|apGKCElWC9YT4HHaWqFMDXU4^Sldk{zCUHNmP>znWy)jKq~04O8pX?-@@6dOg$j?os9wd=#9%%1Ns&(?tiFXIr2v2&V7VXBdr!}P#xRA-HBj9@COUca z>fbTZi5;-P_^1d8=IGmaXU$Q;DYmeNNr6IRN5R8Y(|RA2`^e+Tvoj=*px=58x8d{N zCRE+ht+AbPBnicbyTo>UbekP8LwiJnpSuNe)E(9JQ65FnlRz0JD(aLWirOfJ-8r%? zYILyZ`AoD#(S5{nOq3LP=?0-!tQexCWW`Y#^b8H9a`BO{X1Kf z0|(B9QW4^r5}TLmn$mZh-b^s(x9fb@4eN{&98nBXt`~OOz=fN!9Hmm5kpkAklEIbB zvreIYd%K-5o8=HH$R` ze|$MVg9cFX7(Ly0a)63=448mo_+)75aS9Z6Y=LEewuhpUC9pF$+E z72>bkt8UN%2z)5jWn4NUu7yj)h*iG$Jf{K*pDrD#YyM@L-XC7}O%E6GXu(_^vsz{j zraZBijo?LberMI#y>BaohuDyX+k3B-Jz{)q{~cRzv)aN}Z_1C6N~w*ry~JbUyBRo>&(aOb6x zBND#wTGnHtOA%7P@`wdo>tu`m&ZS67oJ^_G_nHUR`E6TLm$MZZ4tv)8;Yt;jCK3qM#O;!`*Ps7?ASuJoy-ezV2KYP%y$91ag!_8X$g-v-006A zb|rD&>Pxe5LbWKGHQ|HaA4yj;;HtSGaUl7x<0d220CxPmDuA@Na88yp^cvmcHn9Ye zG3-&jN1B-XE=&CQLFH^ozD7<$j+N`y^u%RSI_eR2W88f)dLnE~e5`%L>l~(8_vX_3 z@^m@Vehn2d>jBVt9VNGB*H*xeM1gUme~F2#2B^Fw9xr30Kx?At%JnK61|>wHTISmn z!|D=BHdRL5XVKg6F^b|8(5Xq9-_aM6*A3`(PO8gmlR*`{15bJLoyr`y(}Bd+qK_&T zVMu-?#Ja}oh z=Q1$Cs{-2ecJe(Ql-&~C9h?NvMV4+aGC5twAH%#MQfOb9H`0lc-ezMk*vDE)3x4N; zc%C$xZ{A_~LRb-A%Sjr?y7?CR5Pq~!CPc~}BCNTpQD&tk0+lAxX40vbxh8^|b}>{< zQJ3<;8cfxC6p;YQt|G6bFnr{$?R zXFOmd+uZJaAlJpkOvWEn*1%x6qw&?(t90>v;G-S!dBhOLk#g&}PxK~&6C zvTN*tMoxI`%O^=&YAEXUQJ9|(jflSiu#RP(<(>YVu}CASuMXbOb$*(j3NNJD*Ny%L zf4ncZPHBZ+l-rCrE2V%^L5Rcs!2#j=i~5xgDQ;F{{R9#P4X2OW5mll44~hI+=6BD2 z{N)0uE#Af-Qkknv3n=OGrSXy3Z8*_X+Y2DAdl z8|r-w2~-Puc`9KuHPvaN#15L>i@}MnuWW|WiEIFUuCi>!xbZRLfK6)Y0;=eiYk(pS~- zA3A@HL~mZD6Zmd32HWKDr_iy2`>%s4>?R&-b3y6F(VG@Wb`u5!8In{Xpv0kU5LzfF z0Hb|*&2qAvHEo0AJ%?7|DkK;JF52RVQcvt~>)foIO7=kTLkUOAtTnWmvgjp=TQAuY zsEAGQi9V0Wis5+EFWd_?io21t1^NW0!*+IQ7KMA-7%;05WMHugdCJpNcz2khM^Vh8 z{*M>fUq!s307|`$;+I-GnSzR#qs>xW-4(|-M#JU^=E05{I>y}xyeLM=n@_vN6rycj zL=`E+7)LEQP$43fx6cT|j?AJE}np21Ju@d=QJVi}wZyx4J5>VZ5 zN6YMxBURq*{=!abLw?M8$W zZ{Iwe&j?h1V^h!GpnM7PyqearRxw0Bv z%m*C2&ab_uFhSO#GuO<5S{OrQA=B(yWqE%4eS%xQ%(4;Au?p0$b7Bc5>z0=IpFP)T z9}U=#C@|kk)WFbZy5JMPE^Dh3Jks$D#s?MeP~5)sD~<66u(zzrhbt;NxQI`04@7(_ zPHh>3^&&xzS%z)pIz*nVyCo|<6gkarmryV2SA$W)(3tWyp!$W)I~vB9kaW9u%?x*5SxI8I@wU8p+1cbe)fasXO>+0V_;jklq*zn{XnWcC?ly9oj@Iu;VwU2KH~N7j zum)MAa>Q$U2mz1QYV%Ni8ZI(MY|#r19d^sxhUEuS^AM`@NBQ4BD+y@K4|Cd_EQc{2 z#20ASBE8`qzO9S|PmMIJH#3p8`!M8`_@us(5lS<|ygTdRYO>3Kn`ty&ws;cWeWiTx z>zClmT<51Qn8Pt+4MQWNSn)GT$r>4N$NxV)NW0ddZ7}np429a;v!nZQ`qK(ecE4F~ zq`;~>{7-jf$D}f+A_U*^+bI#;abHP+1*dy`xOFtX7!~S9ADs4W;t5$$AfD*DK=By8 zU(0NY=#*ZWm8pty@+!pECMBRD$>wk?S;&DnzH-g>5*p=U`Yq>;sEAjI?J4aR1)JgG zIOu#FWJJEoENk#1qiH(n{?Sq*|IuQqsDnYn*ltcRC8yT+!)xk?gN}(D04nORLHtEs z&&bFOw36&%aLF3Vrd9Q7o-aOLo2<-y_l16$)yJg!ag%#{fcLOcX=gc}Pol=P3K%(Y z?TV1x@1i*$03gG>FbHt+7xT1pBYn*F0PfXR-U=`dzptF);*uukJ`+ls;%jZl#`Yd>)w|70nDh;Lo{-Rrp9Nxb^vBKBb*Gc zGRym2)jpA!+fsy;%#OLaVVz~B{VLtIhT1FqQ7Oo^%rrGlEvPdbR=1hthTK3Si#(LR z9M=1`$7<*3h>~+x2HZZt3}$j$saZr*tJ*5W#YJc*z*HwHEu%XMdl_=fcw>L!aqRoM3|AU0B|tb>0B@IYP+50nCWq%FFR-ryZ`QCcA_ zqXd9|?5X2WS^h|Y_CN&B5c>-NlW%Bwa{ZUKQgPVvn)Rd6gqygS;Dk@?e~`5N-;e-h z@75iZaljX?gld=~6^iBs_|$cKka;30ze|P!n|YYz9KtW?zPX+w%9c0idcDZhmQ8z@ zCM%a!*;S*yY+)RL0qETWrFY1~o?`As*ECrZkmy$S@IwKITx;{Cn!(p(sVBZt+sJ=n ztA2$Zg{`qW*)wPL0&02tg|_!F$>sWLml?#J;*(Gb>g}(uuNd-YXl)LyzaV}Cv`CjF z??ScQ)wibIy}vwm*FbGKC?t9lRqt5s1Gupq#&*rCGT>-Kp7Yb1S;&6ktZ@3?UN2SCgA?##jVr=c2-fK6LV>e z8Nk90*}sACf(ZIK!J{1KseL%44NI%;26&UhwUJ(+tFwX^MP=;GKGB>a>|O@u)Sk59 z(x1#Ezi)1{lrhHBg_$a7IdNZ9M0Iy&w6dt++a5HJ zc&S_gIM`d5U!X=?0ic*VF`HJ~{9C>ku@9OVzkwC^psyF}5$h*sZyWQGFlEP2P9 zbqIWqwdsk5sgicThC{G+b%T(X^GZcBYszPe3u}FEXS+PVendH?53DJxW4s@BdakH0 zg6nVSRXb;2V-WZbM(4H2#)?6?8=wCCCNnnb*m!u~8DQ1rO)GZ_mhPE(@pKX_XVq*>Y_qt+r^SNPi64#6Nd5Wf+pN?QXg`xrNb#*9jZ=xqY`@ zUy1aOv+fyrdyQrT=+4+pjY79pv=RPTgC7etv&m%i*ppnkC!Rm}6a60T5rqTe$f5u> z?H&)`c6koCE$O4%01idMUH1bkW55(~)_HbxhMjTj;pY-}45t>f{&a9(!ttT|=Jc9> zEeyeS4q&ZXbvlp6OvWr&$*3%mO=4l*{@s@urRPduAtd_fP?PmT=R0m{k<8GI) zww)!(K3O~$A_q$FX1MLld0E9Qd1w8n)&;Fh22{Q*VwEFWZb5q$1IZ%IQ>$n$!;-eLY0R5WdKc8^$ucgwT+A56 zY=32-(uq{`XMbk2Q9-idNRE=UUqsnmUBr|_X)LFf&exWZnc?bnew#N2qR)27zZV4h z{f0eoJ?Pmq#zk4iNP_>4rQeHPFPN}eu`MbWt@Ws7H^yGR`l_+-(9bMWP~{hj?z?zR z@LIFr>U)BlN+(YmUn*%wXqLY0i$;8AKhP~Pf1iY|aB98mp}1Z=2mt7Jy-Tz9SNq1N zt6l7I6(ey5fS^C4xc6+KetYMu+;x@RaX(qSG{JIY_Shr#6hT9W6vIs>&;!;l-0w24qLK-L{Fx9g#CrP@|l66{T}9fhrqKvkIHu#)n^KScEe} z^v~OZctnf<+mcq0PGRZ1sO~6H|Le0Pe;?@iSMBT%=%1^7im?zd6ezvjM|CZA2Vb;L z`=c2G4(kS!=()hBy=U01h$yi%`lS8>gi%3oo_G*mH}^a=ICCJLTcbm-+{Oav#<*!P zmtd!M_@J*8G}`=UD+j>W0guq9RiwAH#i9)}fPE|vW>BK};L5@q@>1`XQN748&+3|d zOpE`1EPelbf93xIYc3i|wC_=UOC4F)OX4hY1^K+}Ph8S!R%f90i(=nV+gYs5m#D=v z44G7n<0A3-hW6S68fXsXQqVWqX_V;9Km(8>!)@LUu3~!Vj;!eD@VCjNApyURt7EUZ z#{0mwTa!zY*m@AwyxeB2f;H9mu`b)Kjp{nArY`@|$;##~V8iEhU(SxEV8I-p(>~&Z zzCubtzjE`ZICOte!|XfZy?23$E=DsA^|nL#sW;H})hN&gL}4)LOY@~GHD_er@Q;dq zzGsHQCEO>Clq^-jAjN#cE3^~K1D__HcOgP>XPv48)HS&_=yF;+Q^ z_MUi7OBCohU7ud}qAHuCm3m3EWhITntDHpV!D5ZvyktSqO(Bm}yauL^j<*qj{-H0zl_A4Wa z#API_rjIo7Zz_p5LQ{5DGaV?4aGgt+7}i>Zs!tLg8Frw~zW_>n8w>47T>}rs#1)}v z-0I(}v#68_rf556IInas(h9q-nv4L2X(&_h=vaRuvq5Jo(cE9c-ZN zj}OGNCXksOt526ZS3dZ$x}dN!`8C#f>NV-pIqy$?XYEv5-GX_>h@;IJq*n2es|o_z zPe4_*mhW+mVN0u<*hBxDNzh@#p%#jF@$2p)R4r3xYY~TWUu#5iQ*F$;ApG1gf@WVh4*Jq}{ zGH>_xzs#{3ct!qVEWKj|${J5^y>QAPeDWVjfsThDWaaci&V|n!ZoQXCtG>0O`rcI5 zeBUyxeU1&_1Is6IyePBS*NyFE-ZOmPJEe_b@tav$6i*{{?e9wxoC2U6XGad8g^h$U ztO>?US;{H2>B*rM;q>%cTZ&ieL)I&O z4Qz1Owz46G5Qyf`c)5aU6<8kPp#I}g5$@fTm<1?)ZssQzGK+2=n4Wi3QXV z(V$gnBr0ej$)uQW4gNBJd{ScJj&&QW7St&iE9?$udgH3(DF4#&#O$y|r^+NqBs3?4 z&3xZpm}aPZ;!e<2vYl(;by4-IY_~W*yydH%ev8_&<&mz-J9SAn}nECHU=Pkex$=Vl=><;KKHYU$l)VO9Gagw}(FUpCK| zsE{+Yl{6Y<0t8w%J9R*_(H33-P12+6&siETLQYR$zXzDN;M-1S$&Z60(Ctl!hBf05 zaDhRzsBhalbE);w&0~;k{p|i;#eJxDnHi-#2l;AzYVq`5D7Rxj5qY_<9F|c zR@Tsicp6Vj>L0p6mikksavF{^kh~Oqn=O;&GZfPwGi7vhZHulUhtWa-8kG)!8EK78 zDFrFrOA^ds@|az_b#Z6rvzws3_tOLGp`UFR*i?5G3B-(wKT9&u_5LQ1ir3+MKQhK_ zn($sipucT_wJ~bOB?{oOkMf@lulQa{#;;wvT1{8KrrDJ}%U}~JYSMI}w#3br!|$srbZQ^)gUda{?vG}N8!g}A&A?97vt)fg%B zd*YZH%cU<+=we#~%kj=v$nA9-n@Ded-6|Y)T|FeG<6evZB^dv{vqp$e56Dr< z1G+2AY{b5dN%b40mVFqd0G}*_=!NveZqDeIs?)|ej;MUQlsn0)!~T03<((Vg<#Ylh z!%6>8C|{_H_rBvf+u*HyQ>7K7zEf)2dbzg3OjdAa9Z0VVjq1JSudRazJv#$09sy9a z4$uOb;V_w3M)h2crk|;;U0N7n-Kg%4X{8U2GbsWP6%qe#z&G}==f3fSrHXoww}g;D z+q_ovUc<)pvKLsU(=tv-sv3bAg%K4!s_aQtE~bWGG#D}-T)MfJbsNX|$MFo?!UNGW zu45%@03NnZ$FHNs!*y7shG5{=avcBmRlmGPUsR>Ox8Zn!q!wsJQe9?$i0gjC1Xaok zT!t?p_+$3Bi6nvCh1IcbZTqtS7e+-hJw%< zMFs?8KPQlfF{5+&NAimAe$NH9#Q+84Q&FxC+=v}+TaTE40DyIfC6Vj%>2w5R z8HdScBEKOE9G7(rO<0DCet$$NW~Gt)+(~0dj7Z=;(JOw$qm-%adddPl_V!2Y_>ZSR5oB|l|*`FLyr(Rj!l zUj0J3#Fa$R^~Y1yN9VbL1j2zfX?%AkF8<2p`f<73M$jXJKOEjJ--`qSda2km%$7^6 z2;B0!oF2c5MvZ{utew;q(h8sq&;^DMHzxa240%^H%7?Tn>|lfYKbWNK09ciKL+G#! zzHz$W?-CI?@MQ67<=yyxpCNhH>I-bVt&IFRsYjEx0^Y-HmFD$vFj5bAwWd(k+;dai zUM*;gXl%WhePTo%#(`6HL9<|{(nobgZ8dX;wcLJ)rgn4rdVZ*sgkgBf?*!r94dCkB z_9D9q@bP{ZnTq1`kBvUNCejd6K@XQ zGTS>!$sB%bsBHJ-%)$oF95D+)O^ zhHIEBL$%r=?lv?BUg`yCcDH_qTIXSd{cTc;gYJnNza$8{jcfTdhqgrj7Eqk=h#-<) zbUp5-wrA!Nyi@e_8^6sk+XMxd5;9TP4We&j5RnGHmIXA=8-}N=UVW8>O|r@!ZTw=) zWY3P&E(07z4@`cET+-R-0SEMQ&Rm{%1hxC}7fZeFPb`KOs#{OJhFGo+xq(sz2exR1 zha=2}R|nkz(DN;ik18|X$aFFMyp2yoTW_W?R5 z_ct~1tRh?f0zg+)^gw4G*)`v~g+wpX?BxZ^c5*&f7ta7#FVX#r4417Lz&F_m)fqMO z)ma3W3RMAdGuS@$Fh(Fd83J4jqWv(Nm0PC()_r^M<^egq-*BoI+FE-pGc4_u;1{c& z1V~o@+VE(YcEQb|d^|ALb41KKMUE+207|h8rH&hYfu`*V;ro~BOiCK&S6>4-wRyb_xY4h_roF2bYUW}Z;z*R=SNnAqh zhG4yQ8sK4}t}t;hh#ic{a(h7_@ofM6d}x>W_4uC~!-5Mo-qhiLXCM}o#U=WI*-|sJ z&Tyx%Z#i5jhVyQecpvatjsI95DX`4${Veaq|3C>lr1|X-;ky{jNFa#=GyHr|H4o*C zwHY%TDR(?gqp9%Of2e)Suq_Y<#00nu*$NsheDpkI>I3Px-1rf8kr(=WM9yW_Z_LPV ziBb^zd_<~}l-A0A>N4W;9h%2~xd5`A=S((FX#^e0`cs6fIZ{G9qAKIK^xt9&5nqJh zZ?DqZorF=9lb{i_qr_GXU{JFb2A|giVQp%}Nb%iizNicpnGt@c8)Qfu;&i~wlj@(pwA9& zsat1^kN`SCw3|pMSx!`W5zH`KffC1SCHZolLFfg-VS2R#211{=Uc7W!r*ye*#;bM4 zm4P&Z&epME_pN^UMmfNwR-6f~wQeu_!fUCw3$dIMGMo%?qeei|UKRKSSAPp2`@D^6 z3>FIaBYS6k@eFet$C|g02m*#9Yr^I}3s9YEJ^*k5$EcF@8vKR zh=C0episLbH8|oadckg@Zh~tKM%kqKp4k~)t_04;KFN?dJxctGUg z9p7JI`#|Sg(^k#Cvd2tn<@5_thX$bx7Xh0eO-fLaO!-Tk0rHE{X(=9om1VWS^vt9` z=7egh(W_t+QP&r_1v-25XU^v%;nTzKaQ8Kf_-y)9K5N$-%_{eLXn&z&xD4f#Gd=7U zSG&JVHShG}4YbaPBxF>L@MlYUUy|YNtfjt7_KHDRbVX#c z8m*d?Sr6sFB0fhOPAl5&QFv7LkiA`w0E(Se;q@z7^x`LbD>#f|0go+2CpXRCd&tIg zUd+JI7K1|Qr-}L50n9=@0Cn4(uuLm|(JqDTUi9%JkT35CAx3?%;HuUzMl7Si^wl@9+%V%lB>3dwWI-kMMMvyQZ;dz^$98i zxJc|T5;<@K0yPiWvRMYB&W@5cXDSD9%rhD<)Xdgri-9Mt04Hq@66KpDhcpXOSjS{u z?q5j@XwYYRetz9DvS8|RGJ+3YZJ zSE=$lv)}#v3f2C5{46UCNNdm&&M*Ju2;z+QE*>s8X|$eQ3#wDK8iN^L9LQ`CS%+tG z&jvd?dQR~-xmjlQo_sG&xxnzR(Zr(zkOa!%7wLsHBWAuK-^PcJ_9#Wh}2aFb_u65#)^vG1^uv0WWn8730~=x2N_4w#vOEBY_Bb}AEzq&FrG*kRfzi@t za5tNgLhE&7&FUFStqiS0t7L)s{&`#wqI&2UrqeQWPw)*cq>|yrgMMgk{2sak{--T1 zP>Xy&=lzK?m7=wm*CF0ekGT=~8o(N@YLH-88XVH(3jyiv0WY&Sg`uLvv|g{s<+`2N zaC%MxS+wEsx33u2KK{6MK8l zYcq88dV6Ib3((bC^xi_k3*vE{S%+!>z_dinOKp`YR@j$BfHvI&##^Y;IoNzfBBdGm zFA_Y|Kq)KnZ^*BC^5EMTd@FY2n&fA*B2eVn@M+H3N?JbxX(4q~JBu|I0Py49R_Rjz zpH%Zg&^!E3aq*~vtCJ}$dwVvkh1RAvjGJ-sj^jVTmruBP7}f*%+7)BvM12k(LaDV% z%;l2~fN=;QmrQ-dK_Fptp=`TrH)`Ua-85-4PK9-8@gDRq(crC_A^MU8ZsmP?Hy1j_ z+)P^ZCu0YGc~Ck*Brw&%@w&opHrcL5N1?a30HFd5KotT>B9J<{7B94a(4VdIg4gBb zcwm9%sKATkSNgcQ1hoSIWvuQP)XRPV?Gq$a2b1al#M2~r=FoMgBvo9YIjSYexf+X? zjHpbMOtx~s2MrE~54hYoZCi0M8~$C>0xaY2gr2>&?IsNSZ!z&iuXKwA@wkhc!&voj7`6L2m{hW=#&iP_WMTogwtUOBsH?NaVk8e#iOBKYMsij1Rf0 zemg6j?MIIF3kUgQy9qmh@^u6tXGuBUv240S-Uq9u+U3@ZTGu~x$ONQYvE}$)Z%IEm zT-w-W0ftoH+-#F(#wT9#-eu{vdQHiAOr#YCkm&vn4&J@>1K?nAyygpe9xI;MAImIz z-6I7+>-FI|N>JNM2M2JmNls{ph&XVN#*Ea@LJJbmPH!aE7JGEfj2S=8b)vR>rP9Sc zW~#)^ka~p$vF8xq5+3r?wlmv%^|Eq1F|#en4F8-dqdcR&t9SBC-N95xdgE+XH36Qh zdxm;qYFiN)@h0+jT07*0Rx-vs<4(oK%eX<1R8j3;1KGI!mLvn-!942eU~rl^^{mZ{ zv#+Y=&a@HY%S7g`WHEzdy-#&vw7A#Sd{f`}&wOFDDxOAeVg$XtKtO|T^-mIHmRDNg z?YR4D!yb%eVZ!XJ-x-6#ufKSV_P*2BWpNib1$`k(>OWJj3)<-blNPGqSL4o~^qA!o zvqSyNr#?tWSj@NgRpeC)La#KE6<^xd;$;Mnh2M3rBA-ot*negWxNvk%^6%;mCq82b zf#xP0I<+eS0Wc{@+OWgNu=MW%7s&`M&Uj7mJO4bqn{0-A^eF8H^Pf>;;Nf>Af!dpk zDFQ=~w6eD=H27Wxq1kR%ja3*f5=c&RQ1Z;5 zZG?Yy5afDe6`mUf^yD=J%)7{FcwauRF<`!>vTnS&81bmSz@ISq#qJ2%WP&>J+q!7B zveIG?ts7mdjQ2B(;=!qAPZ6vDE&~$n_-BMlnlYO4b(;8y7`>^CHkJ(k+0H`5pp;+k z$CI}b5bB|_#}$R_(Ss7t0Yk7A8#%7A4Ng1uHVVJ>*NomJifdi2H-&;j#8SyvTEVFDGiPCEqXE^wQ%0SJ;)uL%H{DiI#DSLP|%p+DAmTEa{Xj zyRl4Bq+<(Z%{G=&Dxqx0k|hkrzBdR-2-#)djy?O9VFu6lE;`TqywCf2{~I&rzUQ9% zw_M-rdtKMaP4a9X%3wjvSsMtAw-q&tJLBJr#6SWQ$#sv#kkiOl;Ncp2O zEO0L)<;=*PQT+DtIpS$U`Sgtgq}P+(zjv8_hjbr(5J;xkj@EvSyRsMQ2GC*iUY?NZ z2B>rQON2-+SWv_U&qLymmL(VlnfdgZ9OwFH8WLxqkj+~duI`!c$^|Q^Rj8D!qvTXt zZW@R)F9Q2qST^@HQJG~Y;3EgLMS5GC8&(k8Gdlo=t?MYQo8}1pisF7504mZ(Q8uM(_>I-Ft$cV;H4_7|E2$ukc9`jIhh=7{YRrn&5}`lb z))ot3_i@_bjB#sWBLj?-NJ7k?qBiahF{zWir{(?goCe%Gh!%X1)na?+{njRVrj$H; z;pHulr2It8%rF~!Dn`b)~3~TWZ{Vi?fDtuja;PVy5kI&e1<-`-G zu+7WYgS=HVe{;9@u_e~(6MIL~9(YxK&DYaiol}R_-+#)>X^@DcqqeB1&$^t*EDwGl>M^;l1S+BFlm9mxU% zTQ_*WTqxNXS$?WPAxlv&H9jge|0*i4sA#N5`Li?tfxjG9xHst$k{Em z+B@tW+g5NJVvvT16Jhd%<#}^h^|zhhNS`!Dz)C6g=E<(zNe;df-Y6Uoo5gKYb_+Aw zExyoi#Dmd!9noC2mO1YJ?Gi_tSH#6O0W<#leiitPda5JSY1d=w{g@BQ>s38W>s&`Q z-U$LqhSEKXtO=uG8r%zoreJ||`92+fZy6P!-TqdI9Yd2Mq!6Rk6t~1xuhAJdsL=BP z#OK|XnGVc?a8C-tZsEiy-B9|`xOH>Mjpf!p=}lfIXRY@LX#)2z+cd`gBKM$%Y@+1} zaobAFQG*Acn5(Zm23z)YZlfc!RMAtQ?9Lk40Lwqy&$Q{b(yr?`OB^rCoarm>pw(nu zI%XPWR2L>t2&}{zwpAD=-C0H-5u{N7g>gb7{fSGR;g}T7PujGjY^Ni^f!IwiLm8ai z>UW*XhuR@&oo8P`ceSKqiOxpCO1dmY9V_R?<~2cgoo9gGf|H-5E0}7Z6~|0THOsL( zQBQ1i95t|!TuPG}!qUiS30pofTHJKDz*8pF7?&Y4SeAYHX|Y`!hC5CQi&M#dxO z4%1_<-e&yy%G6Vf-fUakcltl{cQDsZlmIo6QL?DS!sXnWVjq=}k0=A|^KAw;ACobk zf(U_bSNH`;%?$(^O)%Nu0~LnC3C}kHXe9`wNSGrq1f0Z0lLn=cqHL-$%DklgiQU!3 z*WN-%+ltiRx0pvn0#&EPkfy;0x&$T)S0%SYo^1{zTRlZ>cjNsil9IgoGf$%(32=cVJ@5RUvQw2W1OeQSx>aT#@{CH zfMYtmrpvd6Gteqz3QjkC-`yay4~zpOXeB)(-y>ewrVnbUcBOw!ye*gNoFZr&tJ0d~INfPv^L|A~lRlQ^mRmD~lkF+A z4W;I=f*d1<4}l(;$3;YR;wNrj9AM69!DdKxW|H^FfSBK&*FR-7U{+V^Wt(vKjr{8& ziV;sjH0PIkY|75gO!cY74$7w{Oj06nj)Uc1o`q-`ar_YqFu$c<0Zu{#gVj^q>CjE2 z;!4%opjpD6{&_j)Uz{N=tSrgJ8aRv6nDEb=W+y1URr;jdIrCEB5&JH%gnp#^(K<*FXdj}U~YlxCHunh?)+GJYeURS)n`pU_OiSmJY55&7?Z!pzr0 zh$rz%=fy_dhI=t1;tyd`?O>T zZ)b|3L_;e6bbs7Q{^6-z7g^lu?8%G_WcQZ;lgQF;B(WK8YCOjQNXic_L-xC3nvG_pDW7mkwG|>IiTu7Bhzm?vw0wnxpJZ( z#3*KTEa*H0+-RvujXpVQJ>QysLo^clK1itLSYwP0M0z-klNYMl)Ae)zoV7{cygDCr zbl|R6XlTc{Hh1L{*-J?3%TlYdUp64tD!UQ%&Uej7i@zTJw|5u>W)fxPTHi1!Bqs&9 ztR-VdAs?gwfJyXurSx}@S#$=x{)KdQd2Pik_erxQ)_oEkR}_pi0WGCH7_OSF!zvlx z(h_N^55Lg2@}6JHn|*+A0(0_>!&iNzv)M{8{w9;ap*$2^kpuv|pJ>*#0@Zx6k&ouW zQlHZRQCbEoqS9K5CXO7IbXiV*4~Y%4n+~czhLB1``n%CnnY>r7C_&VUZ#TN}EQ7Be z6ivo*stj>Z`aJghC#^w2mRSJXtfUp2XI~u3mudLE$g(qy>J0RkcE#nD5zO*ZDnJJq zqjpH!=yfPYcRo)23=qB6sBr4PVC5~cI6i=U^fz1J5-EVoB9{AoTE zITM0zjftRxrwvDfSBevZm-=<7Q+t*&k$^3q`XkV0n&vED*{Q&G(Nr8(S385jm@9?j zLw$-4Q6BRgVJ9>0`&4aLs}z5R^jS$w^5R^`Am_yxy7*sN#5pCN_$){wt7s4#_Ddje z(O=an1yRR1zAA;aCUX46&eELlpgaJC7ej}Wh8m@#N1EE9KtSw3gc_ZFe9uQrP_OO_+Qu zVlCCVri}%lkbf$Icvw1frZ1OX4rE9^TAL%_6KE4P$Y~;U&^HHedhlg&wrw>6FgMFI z0I%;gURv_AJe-~d3%&Vh76RD@KRlX=vTN8+HvZuYx=rO3?0r(;3^o50%wdy0Q+8e_ z)pI1lAd*N zR=@k_icTSZ4Bvo9t@`D3tuC_Q=DNJB!#mn$lIkQ3z_b?VL?E{Hf1$Rh7#Dez${8*_~lcHTurt$}ovPn}DWqw->+ z%}K8bowlsDV7o#GS!*x?)veLL*ia4zURdq27tb8s`{RTz$eNdg9{)woF!<^NdHI*S z@Nd8UpgW$!ziU*EX#aDv|Cz-0ztWy2Pc=dKq$})((>sv5PDCu_7*K-L$N=<8;{f*t zbF|Rv4m&)FR!_%@AXPAej}P5?0ZTwdtSa!hza$q#xOGu7vQK`9_2Ih;7r0NFH{#V! z4n*n$SW33Uyie@9-Jxl$ue*gZ7Sjw3i4_mOjGnCFB=Dx6|G}g$m}@s=|?mo-$hhh*mhc_5hAC_6Y&8zYZha+DAg|!LI5dsyP+PpMq-qalm;E}>05$m2sn%SBj}rE zs6W9BqK!CTW_s-!Rf>{=y<tMT@6pM9&!cQ`Tjz01nYrsWo80it`q%M|}qTT0Ld)C@Ysj#jDKDX-Zi z>}!~sra{WkR%{09DX>j>nG?{ScXc z)k#%lj~)CJiRZ|oYx(SsUh@l-WEpvRf6IJ>a{Uzq;tY+qj(Vh?1=Naj%p5kZu8A-uZi zNiod#i6w%bCRc)>OC;d|BKK`rt7KHugP!Hm@ z2ocLr1Lx6@SxdxCPxp$+1>tr8nq63Ret8+A7I10N7b%l5=gjHGVO(fH@ZA47F0Su~ zs;~s04Aojs14AhqM;|p zdxZrDRE$CiVQo$dMz8R0K6d~A&D2EUtjjhWbrtO(g1m@Z-Kzk?$D1%@l1@AL^q{YN z-wgb5_!OPZNW8vzQ814g4g%>qEUQIH`e2iK1LHfT$ozR2kGpWl^&Wt$(-o&yPHBet z7dn3k!27<3l9w||>;2<%DiI?*&P+PyOI4Yrvfr)-e?8K$fp<{-sn&zE6hyZ2T3z~UCZiomawkKO=?CNp&Y!s+RU)2R%<#GQijmjo8fY=-Dr;PcMswt4HMgo z@~HK^sA+rAti=&xNlX+oiBO$6)H%{ZRVKc9WvWAM>0$+OKv=Ez;Lp9ua#Ba zIi*Xl86n8S&Sc<4YTOc{`&RqiCS^$$JeVfy5VzWEfh=Gs3yL|d3~<2tAOR`bQ}5-S z0-HfMAgAMi|I(wS2nsDqri5jU+==_MqFhXlKj9$93#6Try|-azTS_3iOj|ODa3%PV zk`k4=Bui#ACNtSX74Bk?fg7~#Gj0X23T56Z>xVQgesD^r7!&qcz{(8!#KhysCgCh3 zd0u6qMaihU1xikf(<>wm_EQ5YQeMI*RQ48+yjJeb6R=rwAw3pque;Hn3d^#!zVm>J zS3p(TLPLzqKm@=%e3g$&S+hsZcBjOPgft(vOl#P7kj*(dvqT;r5uojI!Fqn?g9Pu{NCaWnEu_q-t7Ej^a~_05-EmC z^0=2De1L{#>l{toymQF$4i%5M0wciu^7B0>&zX%3+JNLikoFp~CUj z=G+dL)Z_;__y;K{`3);3H(|4;a?tKsVEZh9LDR`LzN$N_3ENr1je|^-i5Dn)c>H(h zjZBERxe;xkoRvy#23hABa;DJfR7}MsViw{(lQa{R93f*(6o+A)yhNxWf+bKz3fHzJ zKjgR0JQ+|yxX*(V-uw(o^T~U*Ei1L5{8QA4bEV{l#nHNP!gJw0Hgqev;YpE?dO!D` z8ZH=-ey_(QeqIIg+YLZ(W=)O9d&;*K_T$J_EDdI@!UFv55PLaS9MJv|59|Q`gd~Ax z(S{HOmAxIeNz37HfL88@h_5Y;JB0|L?z*hbTKUkisM@MRf{8zN-Jq2aiZ=L0eeC5F z;-encqz$Cz>x<-Z&<>9;y*ji&TZj4wLzs4{O|CiS)V9njn=>PHGjBnoEnQW5y zT~t)EN5=+4PB=c$rrOWVPP31JL)MdO7d1TarS^~6$9Zl0uU}6;WVuf%5lCSF@jt(w f<&fn-{T5{(Bf;NJ@P{ARp;El6`bUP`ZSQ{p2!G@< literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/lane_change-abort.png b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/lane_change-abort.png index 0913912b6a332683a5d3a5a13bcdf1297c85a4bf..41e2bddbdafba1bc01a7aa07b7e9fa322e5bdb0d 100644 GIT binary patch literal 22119 zcmeGEbxAZ6L^gZVudCqe?L`F&&4jKy@1Ox<5R75}y1mu-AaDEN>8hEV~+%y9I zfZE9k^MRC);Ov2b5P*mZd{l7OJW7LdR}if4ZSy`P5#jUBlEp~yCZG(3BJcwjQWrwW z&hbV}un8j17E#d0ZYK!kef!bHyLy1v8Ip~hsDv0QI2$aqT~D;ez=wpIkYsz9!fr!S zq`-=`b?MvV^vSH_gvMZzSDd65dx2B{3OYKvUjVp>_kWM}18_d__Lh;vSD!(k{&RQ} z@q+e7@Pd*2_uwXa8kV>Kj6h%q z8TEEm^9oYPas3t8QVF;B5Fw{frceY{aCo@=oR-M`_Hd5}{^3y-=seO=ueH-{C@B>~@G?fEEGtvJ}B3L2_gbD~9p5(iKj}M9jNezag{l6Cgk#X`% zXS3ns8cApOORh7`Qmrv8RIb3| z=rfz<^1<0UmxwxR^V&mFhMGoD8XqjFfE4yqn9=ory~Dj z2^b^Jv}{AZWW3pXyt8Bu3KeDbc*`=xvrK|jW$KA#hR^OCp~ld z3=Q+ovkeRl2&ow5=cx$8kZhedBw35z3X~nLv|^vMJhFUyKIRC==D|z*;Lu5$pss6- zqeKL%^)?ga0>U8j<3H2IP4YP<JFGvboe4xZcL<&4KIoWSf zQ3IrvOA9Nt&QuISG6#kfe2Xu4kbLsMl^t0|QrUC-m2`BnT;osqj#N3-2o;N0CtR;i zhiXQ%%^EBVwc5A^a4eS^5k>X-igR(EaTs6ga=<_(27o{$sw(+9{<9L>1>drHJ#lht z)j?A!mA22&s42v^4~PvXGke{L?2X8Y?q)nWA*!r@XOP=`h~F;S|Ix++J(?lhCX6Qw zCeEq6-hq@wN+d>?OL?au5Sw~{6ivE91;x{{K0sw-*X-E%a6ULrz#w;3r_=S?TvXgI zoaQ^Lrt43GEfZvf`NiiePmd;7X2X%>fSFlMGkxe%elTuAUeImiAsqjImQ9PW_Gmg6 z#@*e)?OG6ithcG-&n;uud4s$xue%xrqOaj7XCDmo^<$wPsjgHEjGk#r85rZnCfy2h z)10RSR7A=6hTTYg0kc`CNqwHcTQHkQcp|J9<8j!Z`uK%R@^p72Y9n6F@?)Lp^b`h% z(_#DJd`*?-qic6>FOkU-+w@M0%LTpb6uCqSH?D@RUW7!FgGl?k7mM{x^805ly`3O~ zZ?U+|F+5l5V7&I0Fg@F;5XGgSq^2hUN75yCsQWBXCgoz22gT~51+FCE_uBX^VpckFXV-L13vCD|OF{nn zVwu`BhBW6-61?MCgal33BCMOSEPf0g%hdDW5Rm4L5stI11TEcmyV14bT$0PsunTzi zYcViOz!dFXVWs>_W=zQ7u_R6x25!|#keg*Mp7etsZ3?j%bG}%Z(AlYBZliuU&`Q_E| zu}4q&W=G@6{0J-#PEK_wT6Qfmi(1EhqrCzFb(51O-4e1|$LDjH6^|PY_XZ2>6)YaS z2FJbZuhDkeIYN=$fma7rj*qUWujljZjJ9Yd{gX>Js<@$?{eXqWT39XpkBdJA^=Y!( z)_zd4S_?qe>eh?m%5M=A5|@&K7mCElLQ=Hf9Rm%iXbt3f{y7@QLPt){I}k(aY3 z>OM*|YQ^G7ecyiOHw^1OlV}4mBvD79ROBBYv`uunP*Oqp@v<$$Gc=w?4U0vJ4?H11 zS6f{UNmo~w-t^LVtJPMi-h4hg#zUl0TTTwC++=!y&dFRfo*z-0s5_okEgvaLM77o! zF%S+nG^xfYN3SoE64%pww%pmcpCA`^X~*0(-sAaLiIsq|y2@Y&-55Cs1f~`>r}dwx zFTuI~~=Dk#MuS zvY|a!_M~M|j~kAaImvh@8Iw}9OVna8{VQitC#2WCwWe0D1o>g{!}9hU?cVeKNt9n$zpyVqj4_tOz@Cs70?8-vO9N{RXHLqh7(HX)GuXpACFc3LPiI})Kb&qv1vbY$x_P9q z>`s@Uui&tjhl4a{S*TGzY$C^%o#o8eoQ-Eo)0>Stc6q3k5kVw2DKY6^p=+T?r`&la z(bc=SxZK)rLG#Dw7Zm9A54LIf?v!>fdu4nj852q3v_X<%#l9EsX>91rF`3L4`r5#I_o;x-*lI7*JXL7IMRc&t-zTZF|APqj~1-67^U_4pqT%+wOT z^|nIS2`!b7EtbsBv$=0Vernj(oPKT_X@$OersPphdxp`T_EJvs&>9abGdO7Dn-K6|m(M zF1OQ;aLoNDdMMG@8uMgwyF4vKe_X33L5-HuxRix@#RLwoI!jzb_glghJRUs!p$Gg2 zDm|VNbkwGaR)hUe5H;o#WO2_1mc^Z7bF3zK-DBUM@HbIN+Fw@Ef-5U4C&W~fl2op? zO!-r!1Y+D}uqd9;w9A79y}V>0Nz@FEBB1G&8zUcgj1T9ka>7BxdGv)-4i>B{_Md|6 z0*Y9_O<7lfp&w2kn&&Pa?S};@-8St%^PpK*C{-#;>-%MtpnLkA_3RWgj>boyD9XJ% zIhA$iFd)Nod$55Om0((cmH*);9q>q_RRyLjEQo3OPLyUdHIC%bx?w1V108wAMOfpS z+R5R&D!rTQhZPJKST46K+dbMUvro0{ampG2s8q`F$#y$O4g8(RUJFgg8MJDF%C8Z6 z{X>wepbDZrwriUW-`I0lLD74bYu+}Qig<5rZlWCYDD$4sVp*AhH8nLEJjrP9eYdp* zmGpLF&P<>y4Byeb8nz9ai@Esp2~y`LeP>wJy1EqJH_U|aw(m`)PCuBJrq{h5#g})k zco>b=;m^vgJw(X4LgT0g?lbxjModX+zB8A7ZGOzQ*O#`bhA0 zWpBy|e^(}u)?jxen5b!s=bM+FRMg$9dhgZ(S!Q)cT3iB~S1NU0rMs>}wIs#n%8g^w zywY+8EqQu82}9Cmh)?|yqX(Xqm1UW6^0e27uNVWDG8{OM@1_1BAmKHf9Lv+`q%@oL zD#-EI4R}})k#;NA+V&B>pa`jHxhrzOX{MrRZ+}Ag#Q!_Mz10T4T=S=L^gOXUX!ynm zx8}fq)?=#IC*0kh;q`>cbOLwUhniw7++^2UozNyZp@f5YL<$UQtl>0 z()~t*bGEGwx+69wEiJ+;5(@&+2nLN-plqRz(5Ul{`|@q_3T9ZX-#w?LIDx$g;3XBa zK^SLU$FTmy{V&L;4XczaVc#BJ+(puU0TVpfvojd6Vw729Ypgj=A?k1XmP{;j(VF(q=>GVI$;S?3)V5qlMzV zAbfZ4y~+HwGp~nN(%e@l#fl~Q;3`4zxTn19;wtreDba+~%0WQb5dYt>;Yp^=f{?(7 z(~L&fS7pKTmAYNmsuk6NpZ`~QDph4P>MFcJz~>Hch>1B}cKWe)1cf|SuE7!I+Ob(} zHC;$a#I@8%(~TGFY1XxH!(A4i^o-M$N(2CXq2~RMzVMO9j3^!qpYh_V=sypn zkIoQy$WyX-KGs1uF@6d}zz#$mOxW1!@Eb3%(&8T$zzEqfnH$TZbXz;%4_g0vP*K4Y z9axJftEi$WYd%f6{U*Tg$fvwas{gFED6U-VsY7Kh>%(BhtsDw6sc2UW(VB zxeZEBgCV!(O_v(q+e)P?cnrGGpV>1TkAdU}0ohQXoKz~C&zV(gz;ubS-v0eb&a{Jt z_9&N$erS9NGV1)CtsV3xl&m+z`Tn@$pGCqC4n|WtHkK$@E**PCeh4%B#&oVI^3qHzhwGA^bkUni09}GX zr|o_-nV+>h%&NDGZAI?W%Lisizzb>^sF(@&C+Wd^r%g(yY+%jcbkr+tho%Qq9F$Wd zakh7tCY(1zjA8;nH3{W`=PHtxFcI^~*ds1|Fvgk>ijbO;ucOJ1&3^Z@n91`|!w=mb zE3E@1r0c@SN)v4;h+@f&69RFNlt+ZV#SbUCe!=;WE&>9D8Pg|-i2HS~Nk@T+q)V%I z-hs#C3E9WkVz*`ATGGHUqrD_1hLBD;nwDg&G8T;5}zaR66s^3 z*(~k!Y+{w3&BZV)_Fg1VAsf9^$breP{$M)J$=>l;+;6`asl$c^FE}8|7SL{*OUp{( z30--8bgA4trV@=@GmReWkW67&(+We=5&x8oB#E^DF3TU)rJ$C+9mp!<&xGO-72vS6 z&vQj@M`yLLN5;r^>Mwo8Jkfj#ffCf3Jvqazr2NU&4&y7iU_n9v}?kPymOnbCIYTZH1qnW^(JZ@CdAg(Gof zi6l7XK9OfazX}hQ`A#1m{@%75(xLaz50laQdI*!WoDxZa2qX;^F0>!p zm_{@lR;H(O<9TD%XKzdZ_)D@;H2#A^@lt?F+C%sy3?|Ll*3t;jlfq(TB1wsS`dL!( zZNZE~d`IdaF*fN)PFj5EPmo zzjIsW&+UysfrljwYE&sAex%9CB1!+uDE)|xWWDS#TcnRM!ue5780JX6bAMNME05CS zXzo2KSmKv28}?`WfV~OPoA?%c3J3&LBuHPc*@Gw%fWiRCK}|c6E%e_Pc)JVk+c8M$ zTf%=)G9~9=>=^f*XWJ3VFH`K&kAOn|5=Lo}Rh+KV^GF%%g!WsNnq?|)m9%T-8G;fOx z+X;1M#|(+i4vE6mND&@RU{HS2*{PO2D|z zfxxef*zQ`<5k+eljr2C7qv0*a1?GqmqcD*4h~cB!g;nu&lrB^Q_wRAR;C^)v!jK>X zKl8aZQGaz|rvZ8bFpx6ds@n3L_0R8zMv{*vBrbJJT_Si|)b2+gkGUpcn(AcDDB9Jt z2M1m(&DsXsSJqlkkR_1w#g0YV_W>)TuI#L8)*JN432j88OHhJG!QmCu2@xug0yT_9 zIe78S-Ur|U<_2l(0n3=e;`rq^NNhADsr1=W8l?5dmJa-@7*gUdEs1u1U^GtfiHzl4 zh(v!FZmcuofNf))&;#kRw$*SIgKK&3pLP!HEWm)%kh`N+CfS3gcGNuhN3iIv>PlKB zBXo&So7>x+mJP&otg~_$KmeL@@9gZ-z5CzQfIVW!~H-uUpl(7ZYlO!8rwa!DlC8Q6xmAt`!pUkA=ZiDjL~< z`k;}VgQA@lI)fdnnYcYw^*Dk%E#mvl%P<6EP{FH674h7;^kX~v-JTvQgmio?eBllv z1gB8BdHLBtx)4f2QbQtzEY)#F7R}j^k&$n|Ob%xzFPD3kq$P*;*D@(cihd+cf%9sE zBoqQQ^r2aYtJ;jXB-J<3?&SSlHsNpURAK<+dG;MSoeJq@|}Ze zMCK;W&4_B6$-cxQpIdmlil*ZoPdOY zEyI3ZZsYVyO2kNC&zf%j$j7@3I1n5cPt@XM%L2|ax|j_gs&k|}V? zJ>8jh_Dn<;EKKGL3S1mi#OoW1afq+|wF8$UH}>{KB*nYprxf(#<_I?Wa~wo>H`Q({m_UWzmOe3DCPbg;rC zrRau%C_^<}<3Q9;x|r-xNT--SmQ_`An8MIjYycH8O%u9xe=Eeb@wn>Ov1 zeN~tCIMy5Cb5<B5}K(t7^e^8%1B5S}#Lc+E$S5Bu$1 zq(&Viu+d=Dg-=c(m%2sb-LK{{5?(hMt7;`HTSaaoI=#x8eR{H%n>q4)-G47Sy^q8^ zEQ4+2aqfY1`r0SOFz&>4fX*r%a znm~THpJRJJPIHm~yJ-cQ@6v(e^27vseU{1|%;Nk8i%XlmDN2)1hgvCO5R3Dc9@j@b|7i~SAH;?dj|uYjEQ zPc!8^ngHLws(ojCWIww~~dtkT?5< zl8H`05~;4ly#|7CcRXa%7=V4%?&nvHwEzL9Ht{1j>SIq|OAu8*>#G83;9_qN!6XC{ zb1tlC-P&17wX`0V>rV!#?KCZEHSwpf_pAT%h(=4*@lOSa_PgN@q@F3t5P9RqESWeF##-D6|memaRv|{1>P^M_7MAyDqS*&4# zYpod_|2#FE5_Zo$*F5yBrdX`daqQui_V}E?BE8&#iEwoch;Z@hO=qDB*7>=1FeIbg zjKzZSEr30s~W0%P_29u?7RI*Mv< zNFI@$9PUe?sqB@?O`nX66sPXbgN9vT&@qZR94|43Qs3uHe0_lT_P&E(EjyvAE(m`b zPjzEv`&J?6tw`G*I)Wbm}N+bk-|J*G)HRZC}y?CXjLs%R%b9H?=-v$Mh$Q~<0 zB;Ku;kJ_YCx4Oj66dcY(D4L8i1h7qp8}59_+si{D1b4zjK(fnx{qesd`6ebs%kJ$^ zPL8Emc{Q6yD?%g=63h{hLnVInh9Gs8!U9lNU%#FDMhd`Dlu7{M)6b|q^r~Z3X@war z9UCGs06jt8P7HXTf=J2wi#H@S#V0a8Nqv*f!C}k!U)eoajCV8G;r^V8eJdp0RFD40 z%h)&OKs24n%XOxOdIO=t`@|#DYYbi4uEjsn?g7+n$2Bn9@j#{k@F(V}iH&M~lkj(> zz)0S@gD;_KD+9T~u$N6lBF8L^vEf^7TZB1Q$&__tIk^BkYjzl*F{0+yp%6jdE>VZW z)Y}K7mhP}ixm|JS3duWSTnS4Bc`lU_A0UziUjW^FGQcC5r6vXs%FCZ+`H6?8NiM*G zm3o;|Uw3!Qc(bdOYP)8DQ70;;*wIJ>H;LuON0-Soo{KJv+S)6_YgWo-1i1gV7{7y1 zn1|WyddpFiKKDpz1rS$5=TtZoV*P1tY(|Q;PQSGQ`7NFp=}xAk0i(1~$X z~@IlvByAv;X3e^C%o$VjIL9V^!5{n^=q1m7E-b<~L@u+4z-L z+u`pa5*hhGPq_i+4>gkHC6*5_y7rc!q>D^)f79w!3^*dHPg!9E@ma2wRc_=gS`6-A z&`)Brx4IhQayc#oGScTb?L#SL3%)vec^e>n6MvwEr{iD~Rvh1CJamkE;FD|L>F#OT zbfK!9A0uJMq_JRm0P>|WT;~c(KU$+U$NW4+$`8z-@%0W=;hIN+poaTpmP2f}xngx4vywXIzHZ;-^3*JP)JtU$`SIt%qScax| zS;VI>+ANI+ZHOR}-(3bE$*yDorGb^L1`QP+n9dHVOlHAecxGjOJiD~t(wPv$O@Uiu z!7c|f(Gb#BoyQ@i5EihlMxwjRM*k>;De9b!q8#I9+$nLp^5PNM=GM zRxVuTBga%aM4qR1DqnFtqDEV|ROV)kGt!G3kc&P_JBj~}A_JBTc~3|q301kI*}8Nd z2(fT^wbE?N%Bi*BPSFl#v1LN{uR8*2-X!nf%Dk8?dQynKLq~ghQ3n>0HO}bLG=gjdzl&#sMvRzQ14wbuKda{qZv zOb6EYUPAEezwP=j#0CUPC4g7N)6>&NNGMQoyURr-k@w?AP@s<%aC&MDGa4gb0|t7m zNL8w9J>&yKl$m+xnoZ5RPRiG#IHpsDKK=b7LCEl;%PmcfCw{GdL6Ambzgt(oZ%mVD zEK5&#D2ZpZ3WUS+!TAheo3t`up?0hhgCRv35a1>4N0oqoe z?LAGUGGBxaG`?LyDVqV`5eSF9PM5~P0U##8KTYhkzrDquTYOOyk~R{&mQM@VS;=|_TT&qQ~V4Lm6-mog*Uk<_R22>=zcmL}Zs6+-R&Y@zI{XaI&A{&zkHEz zxeKF{Fk*uv@;L_|N#_dVe}h0&EC|y{2r7@fs>ytHKE{R%taZyEUc&ZPEOIJAjsV`S zK)ADnku+SG%Jubi-E5-&UuAOx#oQ^kUgU4n{9~4(AP^X=VE=1g|MwTbDm$1h>uw10 zyQz)CB*sG35;UNn66kuhPe?-2ZTG6`9nvX1u-Xw`894os1vn{3z6IJ=p6Ckm^Zg?u zN<0Z(@i&(hgAl`VFW{Zo0?Kd-YoEn(bBx_bRgv~^U||n6Qr3q2GqKdXyvHYU zz7$jkU>_Z-!F(KmPC-EpTGe!=EHRVml*n=e3BsB4(P9IFNl_6wB_-dI$Bhmz9~d7$ zf7*2)G|8$NutvX;jhy}CMF1kTv5r@=Q*n!Oamy^_^WnUhky@TuoE%|ZNO3=sjv{3> z7PDMdK;%oWb0m!;sMYOeeHjY*g&%c!FpEG3kL3?EuV2$!BwGpsqbsQ^j{HkvSfsaW z*#TFIn{g8`lt+(%5(`>qixpvjHgoH_Qb+ zss0?7RCE~kSrCf7~KKJG+o}IbSLcY@?A>S-z6WN*OM3=d5e$^s>*Ciqj6PUL}Hj>9%K7d;;h!O4|i@&C3fVohQmOiZdHL-nqQnkCabbAXZaE z@v=FXoPCy*NW4WE$KZR}rKBXW-Mv=%^)jTWWJs#-0);LW0x~AqVs7yl zS_}Mcl6Mn4-Aa4Frh^a06S+`$9uGE4wu3ZZUEpj-g`uCrzMwn-yY7zVV#fJ0WOZerj5;t�zoI~=eIEP3^i|B;#g6)56| zFYly#-@%}*e!D;EvwOTx2t~@d{?1-3U?sQs2Wnj{0Xc+g;pM&9MlcA>_doj}^x zZ%iS2zxp0OAaS@{QEskxvqsn=FxchNqHOc@ad;vVv|OP~OiUaPKkkgAjdvT$ z6M7N_7HisuoPRLM@+G>9r_~5WD3Dez`e9`{3lC^cRxcti$SuC zokI(6QHI0U^$Sl`BTp|b%4(ZT2~zUITp;;n2)lLN!7dpJyr72yjH!w)N!U9e{Rz(F z`RE}=O8Az@lmpE$Qb6q|%bn}p%|JuNA=ejbx?#YvRD%4!Lq9eQFl0xfy&FglE-HLw z)Y)f@Ev%<7%##71Q|n+w8ta|d4NpoFY#sPbAFB2B4{ zXsypnVz@H9)(8ASe6>zlOVM}Ni{}xAMy;O7Jlr3WR#LR1F_)yfyIXr|cYMHYtJHkH zT9EYqvvo&qE{XbNah%riTnu#(QM*7ejYho$DPDB7@i-AI_6HP3qfw#0NLv^NODl_FG^!|Qof%Z$UYt_x|EuE=CS!1`22&q;hTP5>_ zsUnp|>nv!emW%S{)cW_jVH^&dL$imfHL>0g`r}0EUR`j-DFEiQmQ;|=H=$;gWi*=J zc)Va1C*p2nhgg~OXFYYxd&_Cm|wscJ#pwtf*-G3-*4|4eIz*!mU3(~eZMJ}$$P5tT9@1DjZ9R6&M^QrgEaH9A6JkkW{mUkW5X-W)G0)}(Pb5tSQB z!@BN~a$a3d-kJdo|LDF#%t?B;L7^NCwQ{@{DP#XDC6M_hK(d`zhOkl5t&-2F^8ww< zRR$kXZZ6Y0A&=Liz~n4hH%7TPp==Qu<+G^YW@DYXH2K-Ek1t5!uPGA2K(Ji zxv8)S54W4%ingav%)$8e$6+nZ<3&@{H_NVXkZlr;Wq+~4(G8#><^ z02!3?U6Rr1dgjNxqs=Adn?%}xClHfw^X$9bc~hI4uMMvt05#B8jWy>iqIVKv}v zpwN{dTD*42(x8ST4prHTr~%xj0NhYIp0fQjE&*lz0e;n`JpEACKVH8Txr$UUy)I+x zW@FJwd*|I?EWzF4vJ*DmC-6jdg@=pd<-kP|K}1%fOM%lSwQQ?zm{|@7y5A@A_D2}L z_mZa<^Y885t_g31Fz7#P{>X;|GROedz6dJfc1z<$G#H+r0tRLe#@FWVwY$he3pL9c zUtWE~eX#@je~8cst1T^@?q6*K2*oESC*N;w{h;fxQ(8Z6lh!~o&Xq`KgDOgic+ArU z5a{t*6M5q0^{f>S*y%8nA9$k(?j153@^h}roReeNpJ0yxWeVV zF!wk;Ggn8#j4Y0hGa}=x+Ig<@*amBfNeu48_gd;_k#Qh-eDM8w5nXQp)44y*xFi+x z>7hsz8TEYEa&Nlk-SzRjAA;eK%uSG}NOr2hq(BnYV<^F)^B~Rsx=v^`8tcTuZFXEZ*T^NQ?^#N`-(ti0rRtZh0*03AF5`G%^Uyoy9O z%X)u9Zk0eq`acBfCHsB1lcLJDEh?qe{X+7tBa)(k)S8%F{Ns2RyB*z5j+4T{^sRDQ zb{Iox=|1ePz$~K*P1#`EHmO5LpiIlJSQM@JFob!iT#^+|)l(}C5FM0y({ zmNlm8(NxFTLvPC+8qnTR#mtADV!~hLS}D2~Xlt|YymKJI>x+Fii(?`1#M##snR@wI zH>4J35qSY@raBSl)PxZoo=?=QtPMl>+GTb7+o=(dAvb{~jjRT|m|7BHk?)5z1 zC43z{@G>0frb+t%u)(u@7wawT*zIL`ybqfV2IF=1Vo2v64*>T0`zC=qAAoQP>;r^d zwB4Vg2%d|fU--Yqst&rJ0XlA@kuP5rx0EJh1q=8;q`Bh zHK*P3ORoa^zT!exj4^LJVN|Y8ytHCLzElBQ`23p#0|UQ$z@HW1dnt&r zn6qFTdOg_ep=e?;iOk=2N%O3=`@CvAh~%IrAOvk&9s}cu!e#lOC_e3$tMSg>*fTC~ z8>RnC76{Dd^yDJIA&HA)n&$k2;tM2>>uu}pqG3uQYplFgM{4LgBQmoQw@nlqt_SS(TDHhACbaBSgpgKGt8-3QCKLl?8S1n>~yC7{6q;Z zFXrgT^2Bb6B9Ka>()hN{bT%**>fnBi-`LfNdIJ9VqLIdDjPPZfMaX}mOc3}GS^K9$ zo*-H^KSs}t#VH){%dGIr_#{2aA?*ON#>*92t%W*|g+8{F=ztRqwgghXJiYtt{U>Uu zQN~Y(!>L6vpWNB>0>2_i#K7I=9R6s-uV}l*f(L+muRHr%^Le?Xs`~^jdj0;lTd3IF zy5K~_#ERR!94B94aPbeqnA?sogPJ_?zkm&$h|BbXK-1fm{n04J3mUdc1ZBL!5Lz7u zj>$XBT&2iO)54Q~x*;6)`Dzd^p$lwFsscz$-kY53J788vSKD;GZh3D{ZrQd0&-vU5 zLz_0wFwqwMAqHH3*Q`Qkqc`Fu874>2JX)wzoJ8Qc1(__6?Amy~eUt9KPoYqv1OUJA zxF1%1x)UnR`&fwiRm$Q29h!;S&Z_#&R~EZx7?YRbK8WG z5$u_!*3C~MfUAP_Io}y@zV5^lFA1TQCK){?iPi{9*qE!w*Fe**YFG*Vnw6D!zT##) zQ<_Bh1^)keLU-N(CGKp^yM=m-uv_IfdMowM7|BMNiW4mtTSqg;(uZS*lfZVjFRrO57NLq(P$QF!+SlliVpT(KGAtg1n!YEN;ZARS<35BqsAz3wm1wTK)sODL4%m1)t;jF$qzYp%G@2b1FI1asNna|;6_2~jiyv+}cdTZELzB_g;z)&;)|#sd3Vi~ZwsQxa+nF)=aGAt|AV6<(kR z0ASuft{A|ZCn*%_Qma=+(@h7#Bz~Vxf-pl$Y=X^l1AyXAd!%R+)XwIRY zJE6Gff!+hCnJ_d=AD)TT+WP1yGAN>75RRN-g~SYfW_5b6ZyzSF20jyt&0&a^+H4PD zmi{~!r&euIfnslxR}zTHjZe65%0>98!S_l~Wx81L0L+IpaGxJuFgQeVp{At(-Do1? zl5}U9sfx^~C7H>@ck!!}Fi;j!T!EmWplGjk2HXNW%xjx}8p3*Pz>$urh_u7Lz+aWn zK*a)R<_)Mvz1!uim>sqTHE2z|^;$WJj0D!O9a+vxedZ}ei7Jb`zFi(|5Ttak6$4(RURIk<@KV*9*I7C`joZm))*BJ5#Wfl_ zSy_}4GX8OBEGpwaso5vYw&DG~O4A4paifpVXlf7k~QQiR|ZQh{WKe2TLT zVIbq(m$yPk%%f3;$9Q#I@9rg@AhowQG10~4)HY6u2!3uUj~7j9O)V?O;B-wBW%;GB zSai0b(R9YwGLa^eOiA-WQJqVf=y)@m%}{SdP!bnnF|`A`6HhZL+E`MvWJfIaAmSdV z!DNwDl2>h+c+LVfJb!LAHVY$gp6}*RUPc25nh*d^nN#t({Spll%6P~6QY#(eRjUbl z1Loxl!=7lyF7eoC!rrLm_oX3g{Mnu|rL8gpnz{p6{iDl+cmMx*=)$pMyzDikgziMi zkvQzx0*TJKwKBY@uQ3p_VstPt^)`bM_rvGkFdD7`u&$W8B1xeD$OkGS>K-(gZ?&7M z_Zn_!%|zHtypN~WTQ+)xpo~C5!MIU8M)nKm0XU|+g2^jk`HvF%<;Y`hBbSMd7OLi zuw7D3v{G}mIIwgW5DN8v z!XtWo^Y{`q3G#miU~)0=AY`ap8*h6%bTT0yR5gNVm^E_ z&OlNUj-sSf+%xNoEPC6Xnu=5KtUOhsToJB40j~HM91N{RmvPv&2U5xlhW4_Z!$)uv z)K^2pM20J$X&a&V|$1{0PPwI%grLd@8>@LVVk;RHELaldLJ;3*^# zP!AG7K!&Ctt5=dytO zeY*Gs>7zjgBTuJ612p^m^4JLkr^vtBiokZbfp?%;4b<&uW5U~}c(lYJjPCkKFMTO` zOyF`~Xds9G(hVdIn5*pdun!lk7Hn$XMPgoZg1A@ypk7)HF)*q)U^_LN)wXhf$@WB) znMS2ojo?-0ebaX}?LvDp>Q4;7vbQfA;CTxFZbJKH67td|F~=`x?KG8sjH&_fs4-+9 zsrCGgc;h2yCJgnpFJnY%(z0e&K>-n)5RC9(rkn=vVV!_KPBjGlL3Gt!hwywfJs@|~ z0I*@?m&aC|UyKqm#TKOuw@4XQONzgJ!uBRY;rC3)Xw~qfqU6(gVpph;UtHu*`u6-5 zL=mLlj`>OpjS+Emr#MN;ubz$g?Q}N8Hm&+<<){7uRI1R76P|We9`}sjZHx9G@M5Kk z$YSQ=jhOvuS*}uAQ(=EM_sdRSuuY>3f#qH}t`#Q&dlma~5Toj98`={T=yNFu-|w~2 zfLj8AR9`8@{PwABqzYtkbd+wSzaP@OXslcNos5i(H{jxn#EF1j$uG)J%LgBe#qV}T zHUu~RuA8ZY%A?f1P*Wwc$g{#MA8RV__B)W+UikTJW`g2A!1GiH7#Jq1K&WQ4BBXTx zQUve{%FpX%QoAIcFMUhc_QovwLQQT{ina+vwK;`K#l?CB_{#RnGim<4O%jhVGlWqx z(Zu8|&+g|uw4i@HStU~ksczUWa~^sj5)GB`FaEV^MB2r{2iyjS_PI*>Q}RM+=(2Pg zUar2X_=3Ln9Au2#pda>qZK;0q{KD1*SQ|?WB6nY|ss9qOLzwp>_xsS5PQxlfi=G|+Ex8w)J zL#Et=G9F=>n@oR;^;e6w-3$o3ErBymxIDkv^4_lRXIgskSIQoDJa5wX0+tpE>j3)f zxPiex2sdDYg)a|BfN&H#Jf3493?eG;9?Xk-1@T5kRwaA92q=e1dtCpzgTG&8*ntHD zbNIFuroTLTYMQV6*FfQjgn<)O|BXTn7+|vQ@e0dPt6ibn9G`VN5w5cjlcq!M}|W=sb(G zTQ=y40c6bl+*@mfXSiu9TKHCA_rJYF_;YyWX+MfKnu@v;cw&u-TaL7m9zcryy}*#@ zv3)$x&Va{abh)I!vD?_NVdF+HqM?vY1KbXAY2h+}$&s5&&}|tsY}l1tXEt0<0&0Z- zq0&xAxcXmi`^%7!L;%fvKthC9iO+YD5#2_fgBdkp?#S}SrV0+mf@L}YQq%}c?hsB~ z^rPRVerRPFgw{tlXnH!{D~E)?h{Ln$Y3{o5zqW zAxv3ILJW#ZB9T2tmQb=~N#;F6me=+EH`lqY-!i{*?)%*5oX_`r@j{!b8ZTgtZ29Of z^~Vuz$FXWh0|1-5;QslFiw;P}If#c5g7o!ZQEK!jxQxl2DupA)o$d9KQuE(kMLoa) z10|DJlhvZhG^6^tRiHC}_X9tBblz>1rM(oibLv2FyuWNtRBYJ}p)1u$y=QpFt z%vEYyf^lf|7h@PX{F1IdGtggzw%6VZ(3Qqyn^Mfk6FcK_C=KhRc3o)$X?DC`qj1$L z>}J%DcD)phE5?Sp^jHUQNB`MP#yqjSQc{iA(@?|hZlkR}*%O1jJr|y1C0eg2+ntI) z#2$!}<^oEpY4UPP){|q6@yAvb|B~k2wt*rpL%JX~*K95G{1OmY6cs zP5=Z9@!7^>${}t$fm26@_A_gH0Hp#UDk}WFTT;`6ER6&@l732vukeHnyfavTv~)SZ z{*|0w%yjUUexzjKa$~kNzJkT4z4V1*(ICGM$p_yiGdWBIoS<0ah6H3IVGvJcTsq6% zk5CT@@{sOrY8+BM)_RA*AcRqlhw@}OV7jzVAaGqYKEeAElF@A7#{paK`}QqqU?ha6 zBYG!a#=MqcF*qOJ?MGzm9xOEz*C?B5s5yDY{aM4`s77I zR!OWPk%ULKPxTE_g!HkmYf#!VgWp;gx=&KYYqWhN3!2>frI96LN(B51aZpQzf!5Sp zo5~XEedYA(1ZdDDfv@f&HO@X$X7Sl7W!eXe1Fqd15!doY6a-*Gfx(8jG-A04)8b$4}X zaCT|63?;7F$fw*Y9Dli{?9F1dgDDA0z=*U)a$2WfuK@kdd(ZM%=BZCyAr;@Mj%tpL zj*%D7U*YD3YibJojl**n@O5bIlm7<4kuzWFG<%`DBc%2)$p!=P?$(0D7up!IxUN6l z>#ne;VasE;-?=%q*8la^SJTGt;9(}yZjtyikDul$_g|&_4qr7& zSL6Xp&K!SM{_YsMU#uDPk1CR>{uj^>j*H2U`U}_Wl@>B->n2<{mLzNGpud)qQ0w;h z)D|`I3IAA==*AvHM#kNGW(w=udzLzOi0N8~Kg2Zi?`z4=F$#i{15Kv~#`m+_I#Z(f zWt0RfK|LV$mAA*9hLv>ZbexO!%h#(1t{r>@Q&;S!{EBcw>Fcj!A-*rWsIW0-iE$H@mW;YLo12dl_IWbX0!B=yxS2CWbg4j}^C*4p@cWuKutum84?9YynB$&F z$(m!*z7!swq~LR-JaT!~@6M45Xj|64xQc8gYas19jXi_KTr)MtVp5A)SMwnAG)^qr zxdFxw?Po(-p3;@YNg-73O29?(LaSQ-z185`2hR9>rGIxF0!9UGzNqa8!Lfm1*lA+? z^3rB%&hR&iw$od?7ak1KbFPF$=n}T_$#of}EQl`yUR4Sl&G|Z9=Gc0l<3rTTEz0`5 zflg;VJvKw|J9`;@@gKfdVY%0Sg2vayLdpvqsznMdytIZh7%I^NLF`5!?n zfRu&XWVHmRAp8XNPw;CXmHHwO6J{hHNtb&o=2%rGZT3D{TuhTLprDPp!t%>7`$v9J zXKa6v|D;9pwlN?SBW;m{1i9nm*=fIq1h`|d8d^PE9L}S~lzhIT5L3%06yul5>|(E? zYk9dW)6$kOXH+S*h6WO+FAc0CMt*)dS@X|SkThd7k?Y?>X#CAU1ellirzEqwYi;(0Mj+x9QNqHv#pEneaggHcf+XXeWH6tZ6B(yeDzl zokM{6n~TA3cXFYdpCa0lJlj#K5v<|DlH~x4Oi#lnt!9Bw;${XEi)=s_v{id_zygG| z1pB_Br_l{exlzTvuC9@Hak>hr#te_|xw_`e7rK^Z1{p;kJZ1K!C(inVo|!%mr_!0j zLHwqs5o_z7w!Ebs9kcGQ0|Iq&!%iY=V&W6xlHg{se$REUKY+}0BPsrh z>h8)v@AnlQ2q-6IUv{jiq(l!l@63^~Ath@-)KGJcZ>_u#HKn@|zx6wuFUXo=h(y z*hG~#A#OnGf1U%=gM#|(cN)? z=4PiGoOMgyg-7QaOH~t9+Vbqxl`O*ekgiT;=dYU`Oz;Xg4-Pe}AxRFq`BiHimc9fy zh85@KjbI1vUUY0mO_*L-^iVD@?nxY)pm_8m-G=cZ_&$ zM$C7^x>Ohx{RS*TC(q(IzhA9S79ZMnDy2fYV%$AZtN_wog&d9e!Mz94738}kum_|D z%j*A&nAS4LF=f?SVMn&zA2zutC^I+{&aiPaN!(dNP(M!HXXv`n*`5PsBI!C9;2aA< M=$q(0K7k7TFKX##kpKVy literal 222968 zcmb?@cRbba`+rteB(q3pAVSJ0q9bHwCL#`%aztiEX2_0|MCKu*5{hH5NLFR<5u(h4 z?Cp2Giq`w{{eC}>_v80ZN$1?J`*q*fd|uD%@>5fhqoQD@*tTsOm4dvC#Qko9v@gCAg^zYW!H}3Dsyu%$IPb^6J z42za|cgI(r_T8O5M@t##kB6fK4cT`~eIS>TA(lC`TW!Z~6!8u$yCI60peVf0EoONm zzeJ)a^SDI8@l3i;wzU!q6Xv$|b19Cw1ub)$H($A~Ezg~m+D1T3gZfv0WN^PCaQ8lP z!{+e6U4h1ukeJzl=3hRa2E{%G-_KB~CE4}w-hc*m2Srr3jgXA}&cFJ@NdFE>y0tow z{a>#@gX!DzZ}+~<{Us$0rb_H2lgz)mKjhd6sZJ67+qY*AwuSHOa1D9<>lIK~cjJG( zcj63w6qaLbP><$ci!hnc)Q*37_w092tt4bZM$u7}`~RKvz=Pel$NcNP(^TbebN7B3 zVk7mh)sMaY&GG-RcY5D9<$iRj*WN!~@3}SB`f;LQvY0ThV6`AH%e1ZYYox`5sB^E& zLRLqn@lbD|QSLhlr+J)|=k_J-+arl#FZB!T_7vZ6jduO^`JGngb>)%9OiFdVSYX`Po!i0gnK3Gdd#rvP?tQiHT<)3-q{u&`w z!?Gtz+M0`ysygtQ`(GcuLkvQ(H{lX!cE0RMwk^$8(*RSUO0xCOtp}2^tFeO(vQ9Zb zE+jLy6IP5S6FMjwzy0qI(!yEW1e=4xj4*z2-clHp0-}KoTmSsE6_h&}4d&>|P^_C- z*Ug-))9Z_Gb#a)>$DThsgXM@=by?^!etI@=nzz^bJzp!%qzOaHq>%c|-P@!oNhem) z#W^%YRk9=Belq4lqTce3>vI)(yZ_t~N(FhqSZ_(m+(b{;T;=RY6TV)0=SRQd>cq1N z$6Teb9AS<@*_+CNild;xa5u+%DgKA8#ty@Qg?|hee9J6qKE51-l5TJzrkMABx}DjY zfIUpoGp|pI<*#pL@S?D#t+59l}1gICiafwaa zKaNN34xIUi?K}6GffQL5DPiNbu}$wUN_3_W8f-LvCC|oW&hm#|ao=#ivQy}#LCL4= zURS3}#m;$7)MP^C8z;WMY2337h5oObK7?Hf@hQX~ul==W_^10hu(wCW=bF#sy_nFJ z&BV;d*2=Bc&BzDO!)Zx+c8s#6dH%XXH;o|mb_{=&>ZSz`<~<1+lL#T z;@|E(jT0zYZPZHBGuc?_-7p(V&B?ye@HTb#Xt55FF0&9#!M&K_Pelb( zdybW}=3IG4;k3RqbhG)H`h1UlZ^zEltA?RG7cxd$QZ9vXDvv)puk!ja-zCnXv$+@Kr5y8UiPfpM^RSi9sFOD1_fN0CqGlD#UFonWSsM=!D3*6Lzp%J6S#onA zP&7z0r!cfNP2V)qqBzfuIcsL7?zFwZ#$20$h{?p&+!iN>E}0RDX+cWSYNr+ zm3>pcB;~#aUkI0KHi&6gmqiJFc`3}m)e7J4x`MxXUt-=;YG((&aHjToOef=!i-xKa zbB~IaM^myf4g2jU__Eu}<~vOV7FP9cHONlv(`4k=!(`oPnNGJVC1J{y+z}Qd;nazh z@?5njnQc^py%o^TQA;iwuD}a*FO0RM7#q0Eg&N3t!+B>uKcAd0GP+bhBrlL0DRT1$ z7+KrcWIdkcb2S=ut8E5uH{UJ~>DuzA~PPfAyByMmdNXL+0k{I6Hiq zh?M%AL)Y^7z1@Okl8b#rk)jqcD>-LeBX4FuxtY^rH}T{_e>GRE*~&zLMYqkDQRAaw z%aL0qU`wta(Jz8k8i#|+(MI2X7s&fD_H?gSI{N1FdUlt&sql^FS7!s6b;ep#Q?F z^8QDRij60ky)siqDR4`G?J2$ThhjMQo`i9kLwhl~AP_w=-;85jT8oUDDEnn(>3ZhQ zSi`=~bsi}?SGYFcr7SQ@Zz!)NBxpd_X;FaBzAIqH|SWM78a{s1IJ`RL5jKJm=VvE^1|sYm1wTtSar?v z+!(&~l7+26;l}Drokog9R*P2JM~Xz})o+#NjqcixbE98k!YuumF=|K8x|1*{W7NoG z@QneB;uE=Vz0kCwps*kG-C((Mb_IJjmfj1LjIUGG4|>YT3al`Us@EUhO(r&7bpZcS zwD*V=hR1!oegP;me=vRG@Vf#Jg`EY86L>u>6-$9!!^(@;LFB7qSepA#`r28DOU5BK_sSY|d zjOZJr5a0Ohn9)OmcIYR`sfo68C1Wh|ZF{dV_hg-pKckh$mty}x9txsI*^MQHqPkXf zl=Q<9oqkdU+{7!>`D1A|alYTBqVH^q$O{Y?5s8TqLErkyEh1Rafk~abP`)Ux#@=KQy?O}g1aSqI?{|Ir#0x>UND<~jl@#5=+!d{m9^((;mpw^$W`jX|hntDE|74Z& z`W6?wmuMX%w_r3c`}s1ebDKfU=po4DC?9s zsPT9DLqVt7@Z)N_G}0V25~oX9DTMm<=@uBc+d=+&o)>SdI~hM;U;GkgusSn#ElukY zZz_h+^@Liy>u^)@een`>-woRJl=R|JJ0-PTqX52a%amz->*_=6CRr>puSyEpWT=Fq zEX&9zn0fM(w61AhloRl%J29{$XMc=VXHx<}(QsS9#`@Yymwm6xP>z(q)ZCTR>V{k) zbpcxD-LSW-oQxPQYP?T3d)%}jpqvIz_oi;*wY`ZzxYJE%x%VW zui`>vT0HAvA@mSK;AxXpS=j*@<^$bMlSMs?Pb*G*Nr@Krba|G~99Hk3QuuJh_+Sen z@co~hCT(4Eu770C3BOl%aFmX3I-ce|SFH1u7f)Zwy~5}zaqOnp3PJDu&#BL2Vq8X~ zmf?&)C-oSKc09g9nB&xL{(2<=3l00+j((IUX9llK!;1^NqDvP;J`6D6m$6~b&<#dk zZ_j*vSGZ%&HEBv3qPMmD2==sjV(rg64WtF`LKJG56JM-dnA-8yHf!2x>d@Foa_q#J zT@*Zp;B1qs*AhcD4bEQA?|SRLJ^eJjVLj#TIk&=irdCG<)*Zr_>0-_-p8#~!4cZdU zHz4xcW{(x%7Do%x<}YpRmSBrW*vIeKkVX>}Lz*7tJY6kvrJRiEC^?gIv3Bkm z_q|2sE#=$Nhfg-~ALyqQuE!2Jl-(s??+2&(6hwQJcQ-9uj%Uo1FYm)vPPY!OLOggq ze`O%XfP;}Fv@kyVHbIyJsq@m8u!+p4kZG;~ARHj1y6U{E|o_l0nyu$EpGjD zJ(&|dyf?xaSvqX$B$W0xW?WNpdq5r71ZJxiBEf6AN6yfVD0Ov6an;lIX2bz@vW$xP{rVfs%<%CgbkH>?Z&wJh5fa1<`N zcZsN$mq35U)58rqZH3gAv7Xc!s;AeQ(;=JA$!(c`E1ME%!bFmeArUVsRMPUMV!6(w zXX$RBoYGE`KD36S>t}&nx269 zD-+*6Esq=UZo-+>DPtaB?I<%b++#vSc_32x`AWh(X zlQ>Gg#^9Gm;`P{hoJH>^{8aceOanRJ^sd>Kw5M`=tze%=2%(* ze-b*Mh{{iEni9PT`LZqVNk>_Mnz^!5UDp~D6j}>!+iYZv768`9b<-O?IHpto!V7&^ z6)Qz|LPc!k;D(;Mw1OBab^+4sFy`>;tU5ytJ)XZXO`{8jJ^8jt-$(-kM^1ODtA{Ly zFyI?s&9z?Yf?FPYaYMVxkbA#_b0Nx;u?AC*mCAVEu45d14Riu$pc>#nTq!&2>9fzV ziobaAN=dC%C983I(Y$V>O^OF&NPYZ%w0f>I-P+p%deAIpCrD!^yL$(#6=jK;Zy8iG zPO25W6&EOHnR#Dv{Nd>L*m=G2M7rHqc}=0Dr$h4#y>9j`xNUwF@>veQ$In^_;zs(r!}m)w|LFOzRhW;Nm4DskVA37V8D8SJhnOo4AeZ_~9s$G$ z^9zz=9C@yHpAC@0xO*6mw7-5Dxc6k^hF0OXRGGH=-Ch+ug~#kC^m3Z6y+W+ta;P@i zuUW8zS|}l7>`vK!ia-b1fymN#BKvy`JrvcqY%!nY)7OuU4xt^grF zjp}S!nr%|WzaiQ=I~Hr#X(H%Ow`K@g^(|f!M_CSk2$v5x3Ilu+9Ih|f$cm|7d(W+- zlX*Sx5>*}V^FoZO-Grv=KI+*WEFwp)Yd?}1(kQvXAf5h*3%q#-Ky>DnJJT^&$`NE* zD^>S-w}xLnnA#(4A1#mmDaI%j@?i@tzV3bod?$@XTRmh8bgK-Sz8W|u89;m1UN93i zT$F!xmkH~eFYaz11gmx2C8t|GF9}J3-SS9srQQKJjqpweZM|Jz7>_{4%GbSXZ_c^q zD%kG3@keo1$!xBR9E~or&*|s(DA=y<2T);k`aK?WGpO;PY4fuOE|AW<_Ph&VsytG- zYviEjnJxe64^=VgUAK~f#(D~J zHs-S0&@3}EM)=klt*jdtN;&~O8H*EZV-O!_+I371#_rb;d~zwNUT< z7%7?qUgh)`eHLr{@!jNMihoHv1LrIA9Z0}wK;7+5tBo1fhi7f zCjC$}$!0Onh)6J^M?y>6%&j*`y|McUh8>!!-4I9o-Tr$tQmN1j@(9Ue{DTh}E zB?cv~t;wpf;RA2oy? z-M5FL?Y@L+pB>#9sP8gWO6sZ)IxLIf{@Vwd1=E`*^*ktp>5DCwTvyR5c0sJU@vXJ{`Y2jloYd3 z3*j&gWw;rcM-NBeS8)#=QH`FGS$0TSJ|tFBMoB^7kZ4>NBS=76bfSf_Q$XKEu;;_wO9$yE7w40MOx{~7+7aXY zBhPFrE|v+>M}l(gwFdoZB0 zw4Zn(?v+wpiySXQaPuzrQr=$ImDG`5vh-oMy4cgFJ4{w%cd|)#&+c$cY$u}Xue)C+ zRT_L|f4dhYlWwYR)+)~knb5FNr`MMV(=;oocp2FOQH&e|o{)COA+P&Lv@+-u>aWA3 zc4E|>bRYLzK1IDAWb`@~On(%$-9J!*4cTd4S!Os~azs0j8RGy(Fcol&2Lf?Dj2;6A zDD)gSHl{9C+jZR>veQ>iyj$rcRQ%LX4smy#MOlC>Kj06+LwsX?5|3-zpQRj{-Fbs| z1@wAtS;}BC@`)=Fc(T{i4~SwU*yV{}3Vk9%m}uJPi)7Vtn`&AmtqZ7hI(VTubcMup!j^ z{BQX|o_bcy-=jq*^f}paB)42w~IC&+h_U?rRcCQIv6S8w|Zg!dy6GlC#^Tw&FgUMa03^ zaA+E_DVeom?@3H?6xVVGJB^Q~vQeu%)*^5{t-#C0CA}rM0BTwgwJz#Rm6qI$mUO>{uY;N01=KQtZLx|F~mOhy~5ERbJ8jnuKIXcFTr=p&TiBA^V ze7L)6G*kjHGTxszZ7PMq2`fbq(-(A*Vo?YRQG1@Q;O>qGrpoeBXb@LULg@x?$DpS3`ij@#avHM|Mx1;i##!d7 zBsvdDSywCUXV;*tnlPH;CFDVQnApX3@<)yah4vac75yJ3EJNUpgU$TM<5sdzS5*5F z^$%6?-9~icWaF;utx%3Ziq5@QB&5l;8rUy%W?uhzu6M@2Hq}&y5A5GPon5K|DO@U1yKNjeNSU)cuCuIwbBMR@fH>70 zP|I`!1A=gHx1}47Z|)EX5_m(JRg1WWsv%V^D*(;2@!4I=EjTCNVx}xTn~%bX3-gz# z$4+^~Sfq0wsV}@eBOkT=Ar`Gn8HBh;UA4B`SO;kIVd$6lu;( z=TLv~euZ=V<0^O9B`fz=)ioqVEEzxgIj&%HSz?%0!^ce-uBWQ~YZk0ytHEsPKC zuwDuai02(dd795c4KN$dTv8(z z!>}5LcC1ccX+E#o@x(Z0#7*LI8S(j}6}$lbWgHfISR2nk20CNE@u*~dIpqR~W8MKpE3((HkgPBU(v%XsC^hpECKqFtDYX%dpx@rXX z)F}T}@D5f(UEYST!ft4(%cBO=O5f2dikCt>fq^ol?~)a~=AkgXE0AEiC46eAP3Vkk z=CvJbwe4Rs>;TJo6G{f_Ig-o62Ou6+M`ABV(fTxBbVIvpfgS!zP+c08qNAF({cevo;uSIKMf#LSH4zVsNLdHnip)BWbzSyhT}@|@)WKmMl-w}PSofWt znMz}wEM7?yHfcOK66d!1&4*HQ6~5=%1ILdcrAo~o4u$Zf3sRPcx-UG+h>&W$LC$_c zDvE5(LqE}PMo{Ot_vB4nMWPr7d*jFR&)G>9*AmzZLL-0X3t;@??l9hdhAzrCklVN< z<;5*adF8IXjxSi&!C>ie@Ui!;_c+aW7$XkbRiA_sCw=)<6x3JeAsJig)#&mFpgEWy zyq?qwPV3&3qJz{fm(#Jpl$rh5iXa9g?%wijY&<{iUF|aAJyGr5F1iBeupFsTQ9J&^ z|J=K24YzUGFGGH`2+58aXpvGUsz|2geX}8yEb9dioW1udh*g}kD5#7C3ar@%lTaz~ z)8SJ&U2nA1nPu9QZ#$+Zk@{%^_z$@oDq5{Cbq3J7rtt+e-Yn*rW6vPL`Va^AP|vfl z^VAgT7=P3Iaee!qmh>DbGv`~@T#vlTX!DYgI@WpGZ$ko47+*c1?$7zml%W){3iPgi z+O;Q#_Bug6y2jRn(02;#Cliv}WY&}fiiDETuSuEd<<*Xs^6EBN)kd9E;L`>JU3PZa z0!cHcfQ0bGL&MR$6K8VOcC=Zcb9=hS`p3o+BA(?OBz6?6OoDrw_IiHN5>XdR{Tiy@ z)kTy2lui*?-g!`6P6?G#FSwiDuXV9(=S6Q|rLL+0$nhFjSArv1V)hee_a&E~8Ki^J z6D$ZEC8apd-5fk_G3&q-DQ5eE)n&F}{XT^62ub0B--{)BjQqO=s2ArzwE0rA*G%HT z^B@BnjQny#9O0(I@E{5^os9ns3UjvF@9!L>O5(f1sLp0+2=Emhv-&J!3c+mIc1cJ} z>?-ycKYBI;>vug*j?w+RB4!Mp@oI58`D6sHxO6+q!NSL!StVfmU8BLb*1;WWeGVVE zfBF;J2`{{{@(n#+Q4q{oW&nxV`hDH38`lOZ0(sT5PPuO{YX1aq&YI0WtMXm*Q1`yj zF8#_5uiNE3^YLn0$vehNxlB{l=y+bCddNLDE-K$;J85m?=X86q-v=Kbz&~B$22odp zoqGNIK_giL&tjLAd{m9P9P2g5lPLhx%DRU)sfd5vc+6R1+U6@W)OPnaUXm7l?KOnU z6myy>S|8U}XHGph{>i|1#CfalB{D=EBAg(eG;8i-IB;T{dpEpQb0HAD$ z1kc1!|2*XP{qyr(7L|J=0V$FfJ)20et8XEM;_^`ZZ|+y~*&Co)TxDijf@;6MxX34m ztCwD1k!|!k#t#7_i`XrUU$$vCNA7^9c0YvZuOVPNkhG5YQ7Dqxm#t`D!sXswU!SWP z@5sCfq`$zEDpCkeQVp!25w{JfKE6&;j^vz^m~X$Te3byb=cwTweXDm2hk|$!NXxSv zu+Q#X)qKTM20fk=htwO==%-r|JsiS3Kp5mTwCCruX~DQx;x)wi`~y;JavxY#2tfB=m0 zd%;n?zo1@#3%Nr`+OH9VdJ9M>Jso|!c>%sV!Lf)v-ItbH$YCw6diWTn4{M>ws7*@s zXGf`tP~e3;B1;)Ib|f!^L@BR_zpydOR2zxQX}zfdaGvm>aa4a9f5(fnz{md1#jG2l zU99Yj#|-LXVoDuk#Vz;RcU$pm#@TF_rUKqra99}!g`b0LzsE>Zau?h+TiZ-x7&_y; z%E@;UZ%f%_bcm?(i%i6og%qN;(XHDX=j_%I5qEK^v^bOx^GIwMTJ|n#R!t#y!%) zJ-b_RwlMzn9VpG|K-{IY7Y@_YjwI^)Dwt!PpA1M)IDNa0cepbp+K?=Y<{ZmMKi(d|S&amH>p8Rg=Rx@G z=mvlsHKFC)Br~iS%9AJNX!62TVzJLt5Z`!Xs+8$v|D~}{MNS`HOhlNaR@ZilxI%bn z=k5hzP8$-uit6YJsLy3-^B0UCD*znyvwtX8J$n}b!;zf*PG7+7iR!Bg_%QM74Qtgm zO%QZ&TesDCq8ntay~F@Vyf!!5Vk1z@F#Aj+(LW_V>^TC&UkW_En_cbB!Q2A5T)d-u zIxDI*_0rJBv&(P2?dDpv3tY8dNw15Q*o~>Vk=l3EOFfmlpFNN7s=TJ|R7T)^yzW#J zF2A3EbZ=i!gV72Q#(I=3+eW?elk5h`ijQ*D8=Bh(xXgD{?tECKLU(L1sYex;kr2}h z@jzLO^RxouzN0OGT6(S^${`WgBL{ICUDN$#z0uxa!`r}J(HlN^ady(%<9x(9teXYB zW@Bc)Q8n!fWbHkQ;kpeCyb-qqjcfPj49Fm|c$6j9CQV%g^2o!HEONiQs7XTR1C4i` z(uXHi`L@N&GG%vLD=pvwhAHryq-YtN98ebRX~q$i0kPs*r+PDQXQJl7p8j`xg!WlO z5VbrfgiiF578*epNZcA}d?#ccpDv7!m)%1zLN*bF^~~DsQ_%n=7`|E2S#bVeH!fb~ zU><8IUt<=&kvnN>CV$moxl51o0dc^(w*?fDyJx}x+>Pe;D3BbsSOAW*4)_gyCmi=# zAmP=lazhHv-0M94y3*`vpvbffix7rpAmw%9RJ+zMF;@Fp=|!}etNKI0u5-C|Q5Lwa zQQ?$-Vf*ZARv^ZjQ7(nN8w({Hfwuu)ZBSB4eNy@Hm%L7RVOr{n8k2G$(NaPpbLOBs5LVoj4t@Y}Ir?-Ch`a4myF z5V{x3FckTILU0K{^abh0i~J!44x(Za`Jfygq+J6D=u#~ZC!8QzQM_5eIWu6)mVp7BSwj~#NHa{5$9Z`VNK)<30~yQV9p=0cmU%3#=#Nw*`E z_&#La=px5Z#dvHWA>B8vL(MkvG}ZnLyxlc^Jozy(vdSnmY&kD6^SYbgR1kM{%)5=% zq0{EHUS)!4wtaT(mqj2qr1d#VE;P*Ub%6fF;Z%nLzw(tlJIjWWla4V1p}>UY%=|LM z!1ZR5i@~@q^tVX-nLL5l(474Qq$0FUI|AtrPo;lL=v$PxG?v1@vILys-QHv?auRYJ z*29kbLc?x3OAabN;y4mfp%JKoI;Veo4Q8Bg!ohF-x>gm3`V!zW-5vzG?HqbI-sH}t z8J~c(RFbnEr9qa_)5OfhfUw^UxQ!9?>I;f^F1Zsb!OPbW9_)wXbqVi8S?YY5BWjRv zRx_4%^ap7@SRV{q=2-OelwFvrM@NQae?clgQaDm1g>zRS6Os}bq}Qmg8T0e!ylXn0 zgQmH0<+UP!P2DoXmL?7HUL|FbTIrM%gV?Z~&S;dt&8(C%U^K=|k^GVzF`s!h4$V|UG08z}`jBvcgMQV!HldMnyg=c}i& z2LTI522h87ARs*F?tJ@7@larpt zJ*a_i`nqW0Q&)tjg*l>^T@N@e&T8P?HrCBOR?566l~WQXA=Tq&Z^*MT*1jM`j=$3v z3OQnd&2x}70rMe`hNp4`16j0@TK-M^JCQ~UNDHc!&!}b%ze`2y6$1l#!Yd=~Y3Qub zk|RP@6^O7^)s<4^{lLZhg-U366(Zs+%Dd-cPIZv57$s&8C%)#iWOJS>t&Vu`I95Ox zSA{sq4Lu5Chs%uk1gxd!ve86$UJ_H5u8V;{=*|;;+r+;-I^XSvyJ7G`wl2)Bqn_d} zq!Cu)hlaa5`Qpuc^6h|%m+wbJaSW6ARe6E3fFP1ze-S=)KxVYB!G}wRH7Sg#iR^XRg zuf3>CS=R@8MUkHTGie{{i4H#v>o3Q5C#E((-wlrG`EL6(|KISmG%`$-62Uq`^EC9V z;MXkt#-beDcJYG4krB8#yHb)hzLcvtanFi_jtdhvf%|MbRDbcJrKmSB1TF!~vAb?I z2Ul_ZlfwX&==INQd}$=iy4hwU6)koURzG@jiwdaDh0Hefx3fa7L8#QzyL2P6;xg{2 zUyg%9e83~y9p&Q5XGnCLr3(^9W3rC=tyi>#`&JNSp%iqK9DKIpAygv@tvkKZEwt~s z;Nd_)Oq;5H&XM9L&Swjq?u$V~N8C$Q%E}*d8O(}Uoq?#46lfsB9UYSU%j#eWNp`<^ zj&kM?L_MIy9CAzbA7;QSS^{sKK93^j{x(9|z6H7%qCe^v?59b9zT>6gAztxyNWbC6 z=6_Zh!=q;M7S_}8#LN^=+43m=_!d0)Geq@oJ)sYW;Slzy=NT$=LlC|00_6bAz(7d8 za0g1or=WOlH}g@n3ql_waMUU)S$yhO7uOD2bz)@9ELdHEEABj0gc#_X@@PS+>(&Uiy?Jk|lE3hk<5*0%~XRpBTYTi7d;gnlDlxa{KgzKCkU(B}okAGnvppSC=>@$K z`F&+T+A4RUi~)|LL~t zr5O%nbGN@?8svZ99143E2-^E7wysbZuj zlSA%EX97S)Vc$|9mAKZLXESuqfGd(I7ef7)fY%&0ux``0&w`!}T~K@tNf8#(y^yU7 z_6MBP%Y+uKdFZsd_PIHVj=y5M#!u6ST=UR!_d_8xm(BXBePG$wqg%?JMLj*?16FZ3$&}Vfs)@Af z?Sxc&wtt<~VerjSl72;yM{fpD$4g0Oy+7eU`ADEtb~jUkdf~PXruv`dT!KuQ*5o}*crKmQ#fP^$TMDx~}H-?G2?pkM`%!{g5*i)`pHRWZWazrn0O z0>UvuUhOp8;qyt49DCrz+5u_`owKu&+Ir;@RI@&_hjyB;;ada=f9tbTfB_3sHalp_ zN@nvt{-?qC?e*v%ZJT^c`Ba=-i2m$pYo_1+=Py~i$WtIhoX4}j9cBMlm}8`6=t(6a z@8CW+)@Gbd5XJh-9=nr)Y1+@O{;NUaFQ2o`-I<2_J)Hi^{`TOVMdw(43*({p4g+70 zKdDanb4BbG=nvFB4QGD+`Z#p9lKgtnzki~~qLS=P$TW7Dalaw;x%9i3yL;?nuU9*&Umf^U z@cy~qzu%kty8AhJ+gpd))jp{1SqS=h3-A_sJkThv?c{CuOI(Rz!&9ezuK)M$*wwIv z9qnM6`zzMVF|1OMv~$UqYNZvVQ=A3tI5kN^un?TvlqR@Wzr-W`}0oxnrb zn|PyhjK)k}{4m#_;{f(U)2i<|S=paA<4!>j$LqeR$Nc*y;5?zf^`O(`(2+44*R2nu z2#Hx7sQ)-?;LRLlVMCX=y3Dh@WB5%;$)MA%@4ksB|HxhVx?3Rv7z}7t;WN3#3=q6M? z?EnnnOjRQJWBG0F%_I*4chX_xdmbJ5bxe%{@PxIbs9k@baMUhj+s4d_(wiT~VufGIZJ!<&-eTF0U8u`2O$(`LVBP|bnV2kIcc(E3FZ~M{x~=kC%n0lMwrdd z@dRWEO0aPL!IL|G9?zDX{S?KM2ZK|4_K+PLR7-B6|5Fq|Y~3q=^*gY$A<7{w&~WyT zkAa5NaKADvB`lb(;Z>5zhc0aq!#8)1#YDf|d;#__l4C{U(mI|yl*0J4kRCwIe59lU z1*V63Nr^ZAdVyB08G*pd=ODZ&vp{BHo;e&T z>#blI4sf6+?B~=2wNk<--O+I`rMBO{+pEg6*#Bo(rX~cp;h&VUr3n67fUJ}aI}%cP zHQew1#{>o|$W;4FH|^sIl4GyMrEh!gK&wKSWhEKXy_qKd*t?Md9RK{syq^N64NH$Z z8js$9R{lfpZ~tb@zAsosfK(*0bePQwrVgY0!o-ddienBtAS?Vr>hb=ULxCK#0gN_x zXWCH3k9D}2A(Eqfn({xyQ{@bX+k8lgzFP?Q&vf!_url>A2Z_>2u6GOPtSf)N1vMnE z?>AA#YwowkYlEM&d&(t}fRIQm1FxcS|u zVdW8a&o(+JIP29NwEt;45t(LyCY`v?<9Ww6pJyb89Qg_3Wte4fjPJwJ-$(uo1&j00 z#47#Vc*aC+a4NfJ<@b#r{r|V|eeRm}##MH~rDNn!g@`eJDE@njurUw z#}JCs*T76G5<;pDwXe*-Uk`FFn!!MEVj!-&_T!DJGEh7P$2B#BOAqufgd91&SC9I4 zUjRZ40fU`{=#MxB)j)RiliqH9Wo+EhK|Si(!y{JJH%D9& zOJ8}sTL1Tu9`z3V{j)_$>{jd*tb-&JW09$ukWf4pYWu678igeUg!%clTl{|CZ4v4* z$wPc?FfVAQSFdWu>K)6Iznd3sUGO}zU31+heq5;R0R(@!CH#NjFUZnri-d`=vZ>Ve zbS~hKOvNfp{4u%5S{ly8e3mG6ONc*^LyC2>%Pi&zN?If<@As1B_oL7OA?JGEw|TPe zM<~m?qB*oZckH7oi8Wf{=(j#hxz}+xZXQ^$i(N2pxEvl&W{XYK+@Sv;z`+ceWH}{o|vb6Ws z+xbJaz1Ge#mi6qyaNk7_?xT@chF89UZvGxfRmfT+WM)1JZm(#kT8%l8||_HBp~L=to(=4(C*f3V$$W+4zA18g`$3676*! z5WNmqKz57PrEA$%ahVH~y}baU;)}(hm$<1!XVVWV(t-2O+%iXA{NItkqyL5E-9e?1 zgFi@{Bg2zZ(mP=WfAJ{Q8zSIh+Wv@@ddZ_h3iPs z^EfN%bp-ALoPPGF$yPpU6d=sH5!qbQ9VN9E27cy^TY5Ggh zL&y^()p1BR0`xMFiYBI?Gh~h-ns{9=(?tsm6ywk)Met`_L1v^5P{)xgKc}_%9t2bj zDCwH+$cP#TDBt5BD)C!MK;*jQ=`i{{xsy_$u9EAp=E-0EhpM?i6%QWzVU0}CI zVh|OBdfH7RQH4+vpICjI*MXSzQqm zTTsn^$rXrH+T0uJAl!&wxlE!jAt1t$MNn9Qs!4hWFkX7fr-e;h+Y#ayz{c4KJB-6; z@0H|eyNH!ZZlvWM$O2|aPqt4naF6CeV%mWWVF1A{Ql@W2RG z=chYw4D2lt*Hs567^u@Nam1jwyEWZlGA(6B_-1Ewkod$2q+5!wBLRm%)u2eLGeEQO zLO{d3^j;_*6abxd9JtEIT2gegUW}~6oG0_|97nscy}-UQOUNI2)(jL5s7437y#St2 z>64exbz+|Pg^}g>^?Q8KEC&Q=0hVJ%z6D{8H9#&fLJ&eHG_G+i^CTp< z8>VwBNNpc#m&JTK8RfSO9BUDpS>;}vd-}k7zUDZ8pvQR+ZxQThemt`-V*OIxM|hqI zGI<7wT{=G0tlcG)%R8QdaRIt=H&SRW5l&>t1JYkB=eh8{!nq|VM`xv8%Bju%{%hg4uSZltia|L`o#$8zD{?4WTVtai0;o{ah#nX|_NDqB1B zX{98a4#R!Vb&!8ku(uLb8eiTw+o*SL4FnrR_&0;P_XjPU5CY6tS5A6lI9noyb{*za zTnA#XQrRfXnt{Pcqh%x!t1lIL{A!T7ItXnAx(7rRL*Shyk1Mxp2XiQP0N(@;N2{=# z`(lAz>P;w%t&iXa%3%1{$V8FNQ0)Y|F#e598Yy#H-dE;=fgtf!5$M|J^^&I+A3rK8 zb?Txbr4VL+0q5O7<)LJjI zY)J02U!)UrK(qmk5LxUmZ*wUIDIeq<;@p4XbJ>GUk!rE2#KTy8L;0#4n~RY7fUrplF7!IX^>9fS$1*i( zXgsT~;)=5L80iSq6?(k_+(Olh`gG-4qxo8vJDHSmtuNMf*Cd<;B5tKAw3mjizpXU& zp_t4?CaWpe_QG{_PcW3igcYHV4HzY0cUr@+59H8l{)_bYkZBlnq4C{w=5Q_H z`a5uRKFesjlDCJ@SgDXM;Fhq63dOUM3+*zf?R?FCQ3NP|2;X8nAw-48DjGNsxvV>J zO2Fx)T#X%b?tgR7&RQ+@xzSZ0@25dxHJ_Ykl2id`Jzx?#9rn`1r-)f+?z?hlhX;%Z2 z!sKMX*?eyVaNi5aQm|+AnUF2(o(g2$ADMdocB0<_hhfCC-o=u7-D$D@lbSH47Eg+jMG)X39P_Bg@ooF|(-hvA+ zC)sWfKCr4wuU@I0E~*Q0BAP}G zMGIg}EXt7aiqMEPU$U`QCnU87{gl~Y;|h96#q7p0(7!r0cB5<&X|skx<#b81YXP)k z;DJOkyCN5|*y}VYfw+L~;{yzP4sUykLKRK}Y4jpApscc)>@Vun)~!B^m0B2+=%u*$ z%#EQ+y`dz%v*V2W9{h(mg#{q*%|-I6=Diq3-)Kw2b1sdYicm|pltW6?{L}~{0KD`L zq;|Bio7KLG!>1jXqXw7ne}IllQ)s~}aC7k@MFueG!n@prGq>;6cH^Cmi#|QOFs*gz z=9icd5Q&vaV7ws_gK0h1ePd5^39EkoEvq^`m^qtj{iSBYczHuwIbTg4Gv5AM@Mh}- z-}1r{y<61y)jkG^*k#dxA1E}+1VLs*Hl+z$PvXFa{vR#CPm7D>4-{w=U9)hU?q!(b zKR;eKSg z*}Z}R)YPIL*ww}*;WoVi(Qk;66zAf8_6-^&^0q0N$cl?N@OGsHan7nDtP2fAUO1G@ z@9iqDIkBdVw@(e}?GVD5bu{k0@a!YBMrDFP<~eB?a(;4g5KZax$hqo!W`Ac-93(BZ zA1I0L_RuquyYWLm{L$eDsczx3OXtOl)V$Lo&2s4R*RibU%ESwRJ8s!>LA&D)0nut# zF$nfcXly6nGkb*h(U(x9!^;Kz)(a(_9mDy3f+2kn#9w72N)uZH3Te2FAl&roF6d_2 zOyqy+>1JH}9UD+X5kk-39U|(fNen_ZDIh->k&s%W`=GZg4rO3^#lE-LWuOLH@?Hp8 z_Mw`}hh(n7Kv46cZRwbn1(-Jq6c8ZKhilcf-Izi*NPGZal}a1?3?pl=Olts@W&`Cm zGq9X~Z*TGAi?Q+gj5xZxTDEP-unC}3&|l00$ZPHTm@ANxcOuk7rS|QU%IJcL{FF;1 zy}XIa8apE~VfT>va~s)q`!P*P%H;WQ)=>_h{R9inRVmSZf#@OP!?LRk5e-44=-ZoZhYIOo6BPZ%Uy#;;j_3oQ=5Sqi?atSy9WMP&a8(0V-lGSL+hnEq*VOPFOZm~ttrq&1LNhsXeAS2Fy zkhgy*38zn3Hk1csvsBes$@QEpmU6IBQRCJo8@J)u@zC`*SCs?X-= zC-OTQ@*UFnD zuSE-3IU#1;`)^{#znQJ*BgCfe3*hc7mb2XY$TkD8!*VHokf<}`M2Amsxe<`2LqW#E zMTA`o;m%wFv!DcuF$P=>eK=BOUA6Sr;#$zBL zp)=6Xxp^{rkxWK(6HC^gHsBA1(2LU>cxXjO9dYjaCDMSk%;43_7n?XZbe5mmVCHHntj1IhNP6d#vlTE{|!kcO?zz(jUiIhsy z|FB(ti5`5qiw8a%ITQsy1DUN9zU&M}?TCzavXtfuRPrL;&XQHkUQ?_xS@Rb*g)eya zO7~|gphEIGtX1~v^p8(ZhQAs4PZz0wL|t~fpa3h}y6o7q0k0@~zF$&MH;T}m<3*qj zxv-AQe9vvTcsUA!kYebSl|?I!bCmONXp9#0>Ru4`ztbf+<;Q3SMX$F$cg<6nVuk2Q z_8rJw?X*?{^xdVr+m;7X9#C?W4WTeQRBqV$$a8R+#DG@hy(;thv(m$Yo9QOOXCW8U?wt z$MB&xX4fE~3=78I6JLMfm~b!%<)-eE3a2Vskux7DOj@u#8bAN_oXm8Q3*5y$4+Z;yc#?JTI&rIK@S0{<&5bJ9HKCiS}nvA z$?JRJZK(W|9PI(9im=;E4^;2fR6&x@q-beEF|dS(7Qk=Mk&;&{tGaN>d|aEP>aHLV z9viadyeN@A`Ue`qZ!dHmz<)k9f6?@C#Rw_XHAp>P=g-&;v53x_zv8zacY!?3V-++1 z%ml8*+_wI&n2=K#bFn&W5T&Jf80`V194%1l#MrOeY}wW6Mm{rmcz4u;D!t?0L!6tn z01i-eJ_J6?Y|#id$_+`j)V?iHcy<5*U#^BixS>HAxKKl_@i<;-#H)Tl2roZ2ew;>? z0ORZsFmNc@%Yd!t+iG(D^2nQRvOHkNG)w@6bQ!1>)Is^l=RB~6j=TbjYOQnYluhW@2ni

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

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

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

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

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

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

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

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

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

=nOTijE!73mtXYwyI~?F3OA@AhY2Qq=|N~ux0Rv?mc%dZ+}meD zv4lHTERUVX|FI^5g7Y6?3+@HZYzeU83z`UfCCpiJ%XYK?b(6939T*ZZBWYu9j@sSv zCNNQC*fN{wK*_bKxeBA7=VJ&8FH66ZC5&Y2l2jbGuaz!3WEXV#&A|GCHyfLdd*ndz z0LkbTTg|#UkR*PoHZvOdB?TY3hR8#{A*Q^-;L?{s<8zuKAEg>h%VU1g0qf2I*~0GD zH&*b+O$5Ww-;yBAx;7_MngnBh;fk|a`pWelKI!1%XkYikP*QLBywDki-St-k5`U#K z8t8Km*L!^LeFVI&^cmtVGymIVWL|?i1OhhM`~%LWSw1{yNoQc91YPd?kY@mW_M}Qj zFsck^Lp)U!Hm_OZ+PP|vs*sT0&g!{#iMdFX*&G!05zG6AMRYHk=)dCkwU*uX4c=*> z-}Z^~X*0AFE%f@nI;aQ@4*owUs2fIr>GThOm-jmsKy+Wka*YS| zdb_RI)yhpUiFOcSUs{skS=(WgQ7_t>E}{DF)g)Q<8)qU|s{ei?YwMLn4gznRn$qF<&w_*LvWk=_bc zyZUdnb)*!4!QKnJXj9%h7{fHu3kt$e01h_bgWl)qZ}rjFEdwJU$iit)+l3f?`)?|F+2ghsHy>izc$T>nq0$ z&3Hl*SQbnHxSIL+7B~B1J`Ha$u!_#(G`F~}F^@PsTO%n0P_qnk0J!m;u{D-%q~0CO z>g@<8@~}ROd{QKh&v7l*peF$kGf3MiTf!IL1oQlA)o1-sVv)V4(9am^iRW}WzGg^3 zQ*|;8yxq4&Up2YmD0stlYSY?J_8&43KiP@vQa!cRB2Hn54s?mm)3yeHI1uis1*2%e z?u_T?HY*GSjP_p>gm*;0{_ZtBUpfLyE;0wi(@z2T=T54S789| z!W;F%yBky)-ERB+$&G{QH&m}V67AmObZ_iL|LqMRaU#FBhP&I1(eP;ixwP^(KqDDa ztY1~(16jY}x6=B8(Lrh83k9j%(gk;EJsG|Fcd<=WYCZ0|kd*1oa`}eTM$1?F`vnf& zF~V6)+W8A(>e>sZsNnI+KYJWzL56M$fm_lPS*037mERI!Po1pJE`LH>Cq?p?y2&4M z_W~yA0W5(f=Z3;#Qiz-#1s^@PNZo?q*`0;zRd1Wnm#1aymxGLGY5+TADGaGjC%ADt z43uZNeFgHE)TdWL3E{2_ZK}kP2G^X!&2}|w?SmLw?RV(dtPJgl>wEm;v%20{XSaP2 zcG9Od1@<+osGf~#{R;;C{|v@27cd+J(q^nkXpB8+0<3f(9F4nnzT6=Y5mM(JuYO6V zj1h!SD_;NC&e`Ke9iH~{3A+CIQ28+BFLLqY8=nIf5?dn08aZI108;Xk3|VtM26MjLwd~nZUAQ z=+>?K;)bf?hlPk@WNd9bk->P%$p8cK%11{Kho7Y3dl8NuGzIkvV2!=iFx0gq0){6( z@|;L$T09F|N8F#cRe>2t`I6x^Z=`&y1MTkoT`J8)lwdwXt`DWcMPkhoPRGoG{u>jt zIs^c9{fS9#NPV0!@@O?4mLJ4~`I4jyws4hYO{~RlX1G+G4;)a-agT4iI3MI|!$Pa% z%`TgQ*&vWNouPO+D`M(+`H~FKwHi4B|E(z}YC|;FXLNKr&`WZMs+R2sI~D|V(P{!r z-5e41^J$kmz3}$i+Bk{!&r*5{=wIoKkh|4^pnLY#MHU6J8cpw?bjH4y{LVb5zTtfN z-%)|;u@r6nm-Thz`MkEZJbgLQZ^^h86*C^9PuC&ZyO+-2nN+4|k6q;LRG5Je9&(VY z?g=DB2#LDwLww)7EUOCib`E`MU3543+}#3xXZnAm-}*N?D9s=qLJE_A&|$fZ>)ott zi!%FYsWW}9M;=x{Lqpj+EYebd5OQi(+JL`9fh?~fP6x)i>-I$vZ+@HuBJK=5EZ5Z0F#2kQ+9ZyMnYp%+BvwA)0Vp@oW zlF1FoP7KuTfdB1(nqbNWuK&EVP#)8kMxE~NZZjThqC67;2F{9ukp&Ih4nweUx7%1j z)Gz3vpXjGO6uy*@BhH6qmZ)3MQagqMf~ned%-;0?^o#St3n)(Mv%-@99Tkofc-{Gk z`d-OGh-LcHFLWM9Xp!H+qkArAF+FuGDskt>C-RPisQdqShh`*cX zNCT;>4um&1Q~?_RoBwSe2KM-0(7G}4&uj%tdPt5X6S`7L4!CdvZI8^%1t~~vR@>iQ zH3i-1cy+YPvqYFsGH)l2innLF!SgsqV!D9Z9VppBj-k)Ix{?xg9e>3<8eq%xeB0{~W^ zb+C_hlWpyt-H-nyKJE5Dnf-EG8u>ThFfxr_FzV{%EeC#~Gm;0o*5vm?s=8hOFT625 z>8oD(tAKu7;F)EAnt=^ENl$%p2oNrp&j?15-2@#cP)kZTB$l1g4v_(iXjy4fieJC2 zQ0daGTSJod!d&$&m0m@VEJc$>mUiMlGfbj9U2O~w|G+I7_5&?k-TR}#41j8{gVEB{ zcvB9-@1K6Qyppf^?LrFLnG>ecLS*t~pG-fBmd_f5ygIVTyZbk68^;KF;|5E(|)V3uGl)grLBEuC{3MY9s$~|T8cT=gxsnkc}zwyMclfu@$^HU zhzPQ~$pUG2YhEEJj6kmAht{OAy3IV)SmFEJSZJJGCW-OCAqa-`zSm9FzsG-_ zgp_>1@nDD9=c#oDF=6lySAt7^PbVe-%3w~^hPqCBPTtChQR4y@oNoe(cs9?Q1b;Km z*4GtV530F@#6+vzt)1@?X(@^CW~t>wiG?+j z+N_qZn=|tU&8~d&KBxI@c;_@DFUE3pGd=eFnLkv;*NQf5Ift_`$(CH5b)DvcQ&9@M ze9JVubKB3FKuu1X!3p+zJ$7&e#`V?)m_)TE1(nkolG7&tk1;;bvPDfQ3W%Mno=2~FD*v}B`FgkK9aZ-oLuI~~Hr z5UtFGd}~gl9Ze-QAy4w$*~a{;&p}a9Crxub9};5wx}0c^1MJX66O70CC_kgGn;Qd7 z0?VK8X$_o#6vaTTH<`9=B|KBk8&aKmNOJ!Feocz;537WpVOAuj)>M|*? z>lG%^-_>U8h6dGX=GQ%I+`Yy;32D)eUSMK}pa0h+)l8y2&BMm|IGcs#I@V-?L>+_* zEAnC-Ii5@l%toE1y2tOUY%~mv$zG=4fFR71{e>^_BE~;fCWO)pLEOzN;W-02vW%|Nb2^I_5s+Pl-5KQi-mR#K4Y^#fCiq zcqxsC5qot;kmsof`m#)^X;m@UL4}QH<&pP)s7!#F9SNp2LGiejxz{5wd{&{NHj76e z|8*9#FB%}WPYs()v?K}fzbp_;9LerJ&_ z+-{)Z)=VtsRFW8BO`rjA9aMA^fVR8V*n;+a?&kP&cXy#BQa_wyQ>$w^Fi_)GbH>H- zM+SySy$p3N&lVdUGRe+xrYFCZ6f0#grkyF^%&yivRt^2D88t-ZWCj=M`UNtA@yNe+ zxn?Q#KT8nAX-@cYn~TcNeC`m{ff51axh?lCGeQ@fGmwcnl~rAqAKg-lCXwM2Q59Wl zeGmIM?RGP}Ypa_$olHJp7fjryH7{niJ=>rGT)gLen3i(%a0Dj}>(II_9KlAIWU_e0 zI9TD4d;U_|OODgHHkSoTwPe`CSAY03uLz`F@!J>qDEgmZWReKeKq0x1XEn4%o)+%a zyPXo{wx5p9t=vRV^qUs!y{>08^ju7RoZd+jZy7Dc7M;;E%8Hbmn?Rp`tQ=jTYedWX z>pR@YlHi!~Ib-;w8|`Yevald-u(td4+E{h;)#(p%iqilxi**KtN~D5cc}bv^~fbXU>#I zBT!<60w0v0SpK?EFz~NSHYeC#mHvso2exLJpNJ+gVq{&IYx6aqi;U__d31Y}|GGx1 z75V+J!Cw(FVL1lPmssb|M_XSc7QYFi|8T{*voxdSEg;p9hU9O~?+h9Y^eR}-ND=Iw0KaaaePtn!9%}ht6D*~Nsjr}Cwm!zT%hd&@ z&7T|mWYG$ipL)2aAOA!Ubv$lZ{{62JSvVvk=r{{U+7*R$&^+jOK!;}5xy#QImy1!E zR6HG0@3c@+DP@2)t)dP6du%NgdVt3WmGq3rDi2{{eiwpFVFO}!l3;bIr7G=;3xZ0EQK!5B{1@1wXQ;<{^f2+tQ2S^KmSce zVZe>FDZdVAv$_ENJxPRCsM_Rx9DZ2@+GI>n;Qu4&7^|+BC@!7I$3Yt_Ff^ioTYO^8 z4KFx|WaQQQI`JtA+ujs92YkhUlj;)lDHZRJIE4`pKn2+{{XE?sfHXu;?1vJe93x*= ziWHzS!cE8t%)61PYp+|sfq!g|v%APHv`wKdxz-tXki2G`E!_W;hA#?7`dy0fp@Wlv zoW3m%W!2*&IL&wjf* z6UhU*uO6Pq7;$EBFb8HZAKaH8bh?MUbtw6kK_JcNdUjdG66mpDzb*XH$VzW9Afet3 zd7UH_VgS@xpr76T?%y(4{_8Pil|S~;hTvIFVZF1D#|O{s83yqFFr~Ivk4!PT%_6j! zr7)8(gIR|Uej6#$$kL-`&BA?GzwXR+3Vb%ab3xA&+uTe79IOdCk#6ucOr-XK zG7^%}&zW_@niEkSYH;g65FD*f4z=G%hV$Z|Yr8H4C^^)op!mJ%>dfSro{uk$4+JyG4ZI0dMN50w4P zV)(73?$fTpe?z=9@RE9_k&)277ta9B0-v?%Oh5RVO@t_Dc@0!VNtrhW&;<~f$k6WzPPzRt#i zZ>1bUV#b7i2RxwsB3};_cDr$acAkcG7Voo#YDDtak3*xMi zI?U?Yc8wgSNum`_TRk7iSgnoiF&Rve=&D>p(<8YFx8Ne7OVT3I|GEJwI3J4w;hY=R zyW7c{FUmDTAsXH@(;P-bjU29e8#s}#E_UImD60Dx2eN>NGY4h9*P~w8|n$ zp|cd7kJ5)eq75(U&AUy+v811hD_7QgjI-BgqHWRgC!4%KERW!S9lW(0My6M~H)KSO zy5h*SWo<=`gmoqdbW=%{UWJ&JlQONII6lwo?l)3P7T*D#D$q9m1*lXQ=rWsHHuj=5 zTtWDNK!UtE%L&m4Uakwi}}bPm?Ii;2FkocvGIlCP1TJ)e8~+p?O1~f?c*RlRs1misgt7)e&zuy z1S|ky2urzEv-KOo%)Bx>6h>Ocjto@gC?B_%mw2qK^MCmnE_l%h2&2?x&NwMxV&iv# z77-HS@?>TriA5dob`WshLx8}NBIsdZnQsVEyNiok)vrPxFddytS*7V3C;^o4P6c3}@~M3YthsDwcNEmIb+lWpU*{Yt$s6 z@jR|}7d*9M?|;63e+2fzbGF}-XKn+}FxK^v&$z&2^CRC2GoLfm$>Khx|7pZh=Y`m1 zhvYwzlCGp8BO}|NIN0sA3cM#4axnT=@dtbM!+O4&Cx5<6_y6I3ec&l1-TiZj1?67H z6+biD(H9^8I;-8edBr(_D#rTSS0zp_lk9%lDj#otJ=nz#P08p8CV33gmFKwX(5U(|bV^5;fKcu!uZ--o025)`EA z_#wOBhc&aG@Z%efC#BV*e2uga>cA}tv%s{HnJ1J2@iSljUbnELTNkVOSPE6D=A7)_ z{?l%ng^CJ`e7^!+V*4GL9Pr~*lG+}Ni=LkR63=A>1EPzzqcoPC*90axjJkRxM`1Ai z-MPpwISM5Hzu|)cF%G1Fu_7l8t77OEQ`Uo7WqZ__k;zU4Zt51=>ywiB@|k~f<)3OM zK3DmzS=|uGBYom!pWwfV^ND)FNMd8*N+fs-0{mw@5d8OVFP)^6vLZz~XmUkCVZx*3 z{71A@btZpcCUew~5R~UJLFIVoxUp|Oq)%anr&1GD5|*W>x}R?}bD6)F*W8(cwy)$T zQATpJCL9pbv~Xc(D?+Z@8ToV|ndick0RSHAAvtUW9`q6F{~DIzOLL3NMr`h{Ejp|t z+QF@(dO}tG{*L>T&Ca;ZHU{@1?@cO$AU#x#0f~YiFml$;bTbh!#~VkL>(WGwp&TC8 zLJ1Prd6#aY-1a~U$ZbKxzmKerMF@JUGo|(@GFd0ufpmo{_m+RQa1)DCed)kswPkKY zk!^iV3&rVyq23#jxCy1WrYj*ZkO8Y9T&hv06X^ng0ZPk*ziM6 zbl#wqb#J*YW8n}kn-UGac|ySZp&nuqtuwXYPs5;j%d5*HyGX7Rc|K|9z!N_Z~| z%F5=FgmNnT&K>{tpS*UHnpgTOgjeIrl<}G&A!ej5!zezPU0fv`1{qy*Lf zzv@e{$57b-ZDi=%&Q!DPV2eW3neddhNqNaEm4=Gtt!~b?gS>Fvr))zqWaZ+=Y66H& zQc5hP6efkmPCuALXIgzli4-o4QOLS*tl|WEH63w`eL<1?$1({jN2OR6ws)VYf)tnH z&;nDF;r_qew35Zyk#1rVb4Oba-QP|Q&DR!zA!?)@sTN82I)t2h>W) zG&Y>y>R%`VI+)X_EE7ju18}~70cw9D4bi@pta1y8 zDtk7VDr{{_L2t%Zj2xoEgA83NMnV_$=p+(tH%0&GrwV)uUebr;E*D{2Gp{E&*r;%b zhUT~m(6RN_-Iq5!(9_nQ_osu2gVu_kRl-V)-2LG{>B(j|o0D%&+J6!2`(7uG7ubcw zezYB-XD}TAcXv@aHBXVbMfp<>w%E7cN7@U$TyGN;!hZWR>VC+1vbU_iRh_Kj_qNc5 z@a=`#Hey?aO4RM7j78L@f#%+xjxw0Pudf_Z&wAk$?}vrq!40P_XtIlTWT6 zuf!ZL!AV1kD`w9WcHT6@NlA&7vnKEh6|y3)P}!RWs9^jTA{ikmpWjSy zKCAirwa*g|phm`Feh!P$75%^CU%z!s9{Pxt8a>z792V=qcChx9|1_?Ec+HTiPZ-|@ zbt)MJ4yf!a3`@{B^m)(Kzy+rT?Ghs-(UEUX|18afec(m*q%h9r5Ef$`+>Z5k%eFtd z>`!#w84t42t(-&0DTbBfWwXy*2pzr04j4KBVZkjEM`^IdS<4?K=93ZPi7f1C9IxXw z5;&0D*VkUJUv?OLe}C5vT>0pKh->-XDt&dXEic4}F04@^#HMq(4aTsd6zX{PQ3w}^ z-ddtI6c7tqp4RKrOu;k1B@Ti`jk~V$X$5RO?Y&*mnid^DnLK6gV_18eT>VQZPOmst z=p9d;oEI-86#oYo`8C3!U&CiBI8Bi%!h}Fr5PnP#x+M&7C;ZZLnEg(~tKGx+` zN${7@o3fkkV~O6Yy3!+Qzwv!Qtnp^aj@ttSNe1FUJ(wRijMU0ITp0v9N*{uxkY;~U z;z&b&#Dly3=Tn|u#Rbi{4aD()21pbLD+Q0sNyll}Lgn=+3!gl$iZ`;&SUTeKGd7d7 z^QR)CsMLDXP9g*@ROSw%rDSAcsrbe-X^4GTD|tQBjs%$fa3X$$4Jhe?EE`>t1t{ue zmAB^JgovJO19S6C2xfn(mf1|EV>|Y>FlI1eC2Yzr2Ae? zaec0PbPl}iKx%dGVc`?7XK-*1H=MHHd+l(J>M~3yMpt;>X`eEstCsVPb{YkGclC$% zgFB$T)G9r8yiIB|_k`bSH;yL}+-Z8{a`QFBm(uksJ==%(;)FBR(eYkIC7*KpYU^qt z{OrPbeSNt@79)YP;Wz?3A!qpwl$++9_HR3-~lRw!cL2VIDI3T*IX zRK!j7_&mgFeUy25f6akExPIW#;tx;4JmpRs)=Wz-EXRr@cj*^@`kiSujGohb$sRE~ zsmX<6M78N{MS6%qdWYoRCVW{?|f9%3q1rAYaZR%HSX;^(>C0;6rUoi>pA%UGYm2JfoQhxM|cXu@h4{ zf+edtFj8YK92F_IuWpty@MZ=dqxnmH6x_$@xf!?XMJUY8BOYa#t!m7-_e_47I%Y~H)KgG6bfvtCj# zCJf&V2hu4Zqh-^sL@g>Cv{Xdg-o&y(l2OI_Ge`P z!L}_LXlV^(6UbJKj=htyU*eG5U;Q9N9hDq#b}muVpMnqb=tqz1uoIf~dAJmCmG*%fJQK289q@r&^T_0jQkrrsnQsiZ}UpKIyL;r_4Z@U_`ACPRQgxubF6 zSp%Pdcitp)72SHxHd)oWf@`4xQE5?+d;duYBt!G|Y3G1sT>-O155}=UCa}}7&-;SI z{??>EqYm~j*0+s@RuFZ+R#y4`t|$I^%*j1Vt$*Jk+ZQ*XdBt;tq6V;<#8|6fRDvcM zSHgt_XaPa{ivcvQk08}ppV~OpjccLX=l^!u*X}}8&Ybqsfw&P^dGGaT=w`i6Rg`J5 z*fJ$;uD=Vl!HF|1t;y|_8-V|LKn5=20yxH#14Q~)a6o#@JtZCfBzd`YbIR2sc-J+- z!S^_?AB&zDWl<%4%gDHPDO6u|Pl0WuZm(`qson@Ie-B?PDrx-=b01e7zJ_HW)m$Nql(8$WgqTqi{Dt= zc$s*Q7HI^Rc)t`ri46Px01&N&7wngM~%cF<9&;!M5-Q=9v9f98`}Y0K7$t;LO3)BDr8`nnUG z$O|Dy=KIg9MfG6L3(iV;E+3 zLl&QZXZfs3r2#7|D~oO1uXCR@asLp7o3U2jZ@WxQx*oxI^8OqjqoJrwoj7^uN*Y_# zl~xK!X)S-}Y3{9=U{@cRdS62dL4m7E`|;p!GZn){%yzC@8x17oO+CG!B3-_F?$Xg{ zJAZD^ykOKBgR+n{nbpY;@hf(u!O!^~x8?((w6!?R1My!=w&PDktN4f_O%%dejL42N~OSd3({a(nrnp zugCFXnENrR`wh6LO#z~gQT1$O`^oVxPGvtT8qxmkql)RB+kg*(gdYAW`n`xj(>|5# z@DkM|MEy;&DzO8vcr$Y~rZ%ctzG{M@;@p`ZA@?**W!)f#eq(_-7u5dvhA|EffaRzBs%G$ugE5f+dYc-TA9< za-WhO;q_Ptq27Lw&^P|Dw58F({58+?1-o1iaOvr-x00UeQXFhxrq$ocK=NP7ZDLKN|9MZI32Q$4%QuCc69SKb+$W>E~&f!RbfoM)SrkWyxChpeximrX4v{((gT1N!_MvDW)W`yhD7; ztz`KRr3Taz8q}%r{QS7$X>Y`P+jwR-iLk4Z)!&*5Pr7lj=i7o;N9wAuDN_$@Jp~Ebl1l=dOivPBS`@I zz~`T1z}=p`fzQEMzT<77ShD_C`1Q*d84|D0Z6zxw3pph7&zt0OP-<%s&CKgJWpLn( zYj&1WV#4SolJlrpRk?D_I`GHOAq5%L#L(p!Vd{Q59`M^ZZTc4)BA$mFs-DR-8ki#| z@&D5#xHlN5Z{uY}esl#Mktb~9e5R4}0pw(6Wo_=y;l+dliJwA$V>UALKYwr6O12S( zfykMH;&>!HYk!YNt?p1Ycw^%rmB%c^t#n>S)Jw zl&31Js%C8CxBmFP`<(gO2_hs&^>Rl%_}4Y%V?@&Gm*k3clyXj+uVR$n8_TB6DWAh9 zZw^)EW}m))Uz@@R%g2$_`|nBBZ}-oQD=AQFFjgNXlM{Gr1E$BUeR+9QNPTU1Q^%Q>@T89)FLSE~!fkDBV})kXXTAQ1rf-a{ z^LxUL+PJZ8Hnwd$jcwbuZL6^w8z)B7w6SfQ_x=6vz31y$XRWjM%$|8>=9w8C0aNAR zI=o1U63>V63Y68g;kA34r+@XEBGlN!*AWTZl~nnmz{UjccU%FUfNv`FAyHU_0|5_b zSXVdODO`TLEdJiddTUXm$lsuxJbf_>czjWj;%B$)oq=v*gP?NG*5pCPS4Zaun2%!@ zgJCHH!3~}E$WsqzRj|0PpIdA=N?vB^?ZHt0@ek>7ZY!79qIE0 zTycFo9nTv191(8#zkPy(9sSR?S9%9JQx;d~SxNg$e0 z@ZIV^8^ycGD1<6L6)(3{5OCt*WatXl*Zl@Apw%90$`P`>4cqOz2TQ-H2h8Cx^n2B} z$AJL@9gaHiy`lHMtXU+ft9Nq-zyhx()E+w%7auhKE_u~u@WBs71%2K2c_C>0?(Vnh zIU!w|{B$uJ5M1&~)IZ?&dc9L?=1s;STz&<0+?c9BT0T3oPij7m-mp(#Frd*t0Pd; z)9P~p<;Pk5>FfQ|PS#3c8HrGj$!Q0isG}qsHc6FHp(6>PZM%N~Z7cX738jh$sFF$r z!C2pBMUbIkw({!6=TH21E!45#KIQK zi--3#gVdK$@P2~@faA#G$WcYU=%j6w*tpo8;YP`;xn~y`2k_bQk?YDK#hr;4#J5Yq zS4xKZ?|b!R#i54Tl)ZOHRM-1d`U7h(h_+?8IVnsi1cOvWzWB{UXip!@oL2#T&w6Vc zz0ktQOv{47fU;=6ZI~1c9wzWd80hh*1mr3vH&g^b5z*@p_I>Pc9%?d$u4h-(|zwLUuSXO^!J3bVuuIBxAnv}LMqC|#vE7ijW5=t&LGg>VLJ?(2o$o* z`kyuaSS0ERPg^3$EQggwZ*+Z3d9q-9M+p*vv1N1fIMe{j$oq+L=ojyPxti!aUC7p zw)VEftsPMTPuoZht*zmLZy}7kX&DA1Y1Nw78^=gjryiRF1CY@FnYaHUHed~g9sTAM zsBHTD`;>y>(A$|sqyHht$8|=Zkb>6sKd(gB*ZeaB^#0zYQXJ9!c~XK z><$_dU$lQ&{kG6`{}CHu_EJPncF?(TpQZGp*E+JPxtrD;)_0q_tJP1Svd5&}&(9e)`88Sl-N6Yr{JfQfsG#k& zPn+cg3nT%E>EBnkF_*gsJ$Y&0I*qn`EH?Tr;`!s|q^<>53Iwj0D4``B?VoWs^7=9p z(7+Ps)Vg^CP!gsINB;AVgg}qCp!YNWRLGxSHbf4u67Cm^oJw=(X?E??y zc>dz{HiQ&le9ChM%!mOJq?azTxnp!$tPQ^!!#;Npi45scM=Z%hmy`UTD2_jLBXPz= zcRM=Znqs$ugkzBs4v2Dq_G*jWZx^8GfXgavjB7E7V(RTri_4zfJ-*AKnakU5vy+Rn znFk1ZZz>^FWGPs3ahXzT8I3aX$J`v>XtdYlBbga0Nhbz{i;EQZMibs=v2?$50#Ncl zieyyzsw61kKrt$BZTi;7bt?y-iv$mIck@$Q@CL1J1ON2Qn^rFi_d~zl+4@isO0XoU z(Au2$$th2Xn~gn%?r_Ux@9aA>VN%qJMxODwq%yrb4vob>$v<~pAI&;PC;IOA%eYou z(q{c`6{8bCqA2}DXGn7KGo72)ws4AGp>Aj-P)&mJoSaW7cT9*lArkz<1BhMBZUi)M zF9h+&c{laQh%%=ElP)`g2H3^$!y;LBdxD>Bcvw`3^ z-fk5pi*mP8`ej7YvZ}VEZ0<98qt}mD+D2OGZ`u|iD_YnmWt=bRbex7x!6uz+?WE1g=XnHBVgRr;ZpQpg*b9R$hb*LnQ{y|x)L<%a_m=a5aC9NHS(w|@&XU6L$5o85C)gsO;$*K;yYYWEKibI(rGsfv=|w2Cuzb#cyq~$jV(rMC~&<*Q+I7!kv$k z`@bj52=bC}L3quPl0)RuqyT@_gmYb&z7=hH8ME?i%0%_2F?!IIB7q8wb+HpV6C1aW z&ve~3xa}g1PYuTpc_~h=1}CbnRnBSpU>YcD(AFL`_vlC>PvVe`^i~UbBEQKbDu!E& zn`QQh$tBOQ=<8;Xh|v*Gr^ZJM2M33QA4?R+_iPGc;;jXhL`?Xy*!KH#Fn9@l^i2N& zfnA7Ra#|CfHXZx5^EJ2T-L|4K_dvz6kh`*m-~IkHYNU``8yFCiWp(yuo6SN>HQ*4^ zjSuZQ`%qx+-*(Szv{t`0)pCzp6nJHppKxWoM0o95b3*RY{7Dbl_2TR9hzrSCks7Bl zQc~5EA7i^t9aN1TS>bt+44)texk43MCA(4%#R&RF=%Mi z%_3B}JTQ6)p~B0zJqhCvr#fTLd03%B(=Uget4>*{9CS(Trr$qw@y-UaDY?4MBvdUs z!;yo5Opnv`1O@#ht-zx0rj(yu@<5W&iA{>Bs?~%2>df}8!*?qKaBy(CNnaYWn@UCD z4XTN4LXnh=7*t4FESzR1-u)4o(h4a0pl;tj49Fv1ZbyB%0mIh|F{0yoPi?z~>Zbip zM$O)7?hg*dQA@j!o>$t93u8c4aY+)P#(Z9m*6;Y0kTH$& zr}*O1Ij}BeWR$3zTEmKt#ip)mCe`_Ha66N2Jrvr%6(l-*T*s9|9~y8G7lz7|_WQCFqJk?O z_kY@Ndq2uQKnIf=l0Zm1JvL+RiGeQ%q!F}`$jR@PHEZHvD`t#GH5AROpix=lg1Mf+ zvXum-55B0VV8mc$FiJ%)j~zI#on4swz4CC_t!YtGi#g!-aK`x?pw;@cGUdy&=Hd?B zr)w}dvGET$TIXg<<&IR5W4$`0@)N;}TUJ~3JD=gO(_#)SjJSzSGYR&3=AMf3?{Pf* z={o1`&p_ktBrI+1O;`Aufw6GnO&Ee^@@rvX{)g&p&U}7`NJC3yUZPPd{{}0E*viBo z{Z%P9t^@e!OjsJhWZ{%#)0*rCBbMZBL+5}k>$Iy(K8Ww(&;IULPKe$d-W zmf?l%+)EKNoygef}KzCp%77svVjqrj7mF3#D3%jT1b1Z#@yilXwt-e=EE)S*xija>f8n>?W!5(=}3 z6uI#a*CFEuy$E=}yqap8o&IowZpRbH#*I+q;Ph;7!lNYx&mZgYteo{%Pw~*p^Sx2> zadx^yCuNDIBw>Xu<@p5xPgV;Qc+aOpn};p36$b%5-(fAKiEU_O$~|v~oi?81Be<@% z{CjT)U1DS7cDO#AWND7I+VT}YdkjEM1Rp1KpLv<)m?bn|Rl834{%1}Kxjdk`c`6cv zRWahMs|E`NDek>J&FUd=tV-Qg>x*0dCvZQ{|!3s^h;Xp`T}`qScvaP zrxe#XkzSq0FM}zhKK-uil!Xy3Ru>AGS>c0Z^fJh;!9I^yFwfcs%zdc-G&)U78@v5& zp1fPPe+Y7=bESr=qTgo;mx4~cV#}KUiiwh&pdiTqsicyc{6<1i{r|ZDH-lMoQkm6y z{-q*(xMZg36&kVeao0lyADI>To=A`9D?^OFI~LC`9=%~^I+iLWy}kLfA48i(m7VFX zn`2EY^7?0&JJT~RXEvJ?yQ`1$+-sBLb+TZ#KOOeT9t9-C^ z_-k{PHXBp0h@L2c0fI?qcs#=uk_8kS_-4fX5^m%YqUwm@t-k~h(@kzuZb!Y0NB#5H z+!8PIeAB8S*V`w^%)_7Wx&)&sTX0aQB7NfR^}loK`ICPtT*VZ; zX@BFpBChZLz)d&1e)#8t&+n5wz1o^?XW{3=d%C)Me0)lla<3X`ZEd}@G&gXxgbl3h zIpe!mgn)p!u#t1ZE`Ww79u(5gfy#0FU1*Rt83FI{(QCddMpT9d-0FFCT0~W$%=LL)Ah50K95fv zl3+vJ`Lvs_?dP`<%0FB}GMQY)w8=mLqPfvePgx}tp^v};6ctHed>$|A55MdWw$k(71XnJdr1eN8V$aX^ zGhO2A-|k-d8XrjrfApnTAoWJ{Zu?7QAY&xAeAgH7h_!g=O@ZcVy(S8{ZpQC&kB_p= z{w{xRY8P{v|3uSwH)AoefG4kbl~FIC_!r?;XwxVh%NcdwFF1YdDSpBec^DaS3v7j(d)f zVzT^Z9}jLsq0dGU~&MyaM`D)`8JY|QTf9^OGK#$)p%BjT09wS}&00RC(~2Kbvd*2m^K8@^xyHkK(yaW< zNEq{IDtJFb@xeaI->cvB4#Jx49S{;IE8;;f>!?d|J6*x)+=>a?{`*v;$Ihpi)aZ;* zF_JY_9+RMGI{$W|`59{9zsQQe(wbm5eToAJ_+_8f_qgS7xyv4220$kzzp_S;>n7hO z`(9BM?L7k}+s;e)mqU@6xR@u9W_!jTXS-*@HfAVdaO)|8<~3v~jhMLjhM$H#wKqEG;{dD@7FSe6sweW#dw+dIOBe+<*`>75CVasB_i2Bh;^5LB2X8j-U~6lA_FyrR zP)Uiw6{|;&A&6yc?=fs3Y>+{TdMPioxx%&Z)3M1a4Q$C#apYvyQz-porI07!1D$a6 zux0CmZGqy|`JGdtp~wD2mOEz>lZ*z8QY8gJk={>Y$gAB<-CtVK_h&>7Qm;z)ru!L6 zRo^lMOs2p_Le|etYE#=`Av1AGSrifCFfkZMU5}Al!N=dKZwo&8`?injA6u&dGjZF= z3tkjq%nt0b#}CRh(C+8otCf`to2w`5l~DjMqvLt=yF~4<%hUJ#`Eq@`MEiA$J+TkZ zqH*(MY7@Q7^XzS1v3AMbra4*6jh$I;Cf==xw5={gQ>cG^xMGkuy6tl);AI|T)gD>c z2?<$DrAFXFog2K+fD1vXvGhp04M~PvoD1Fj@SxW9-jy{;0fX0%UR~uV!sp7J(rHyg zQ4`w6!@4~8Nkd;@sytN{lhmvT*ZAi>d*saWJgK=ToG?qip~tC&tNh`9TSB^<&RnUf z#pzd(@bS290p}Su9H*Q;DEj*E$0Gk(;t~tR8Dxyp)e3v)Vp1R;WM|f6kjsE;jtcol zy{F0gV}U|hCjvQGpBFUZ$)BgmyWH-EHl!a<;&Yt>0q!BVoy@ieq3n0!F=<-m*^!bk zj4p$`fMEQ*Vru_!9ecQS(44NSkq*nLsjCT}qt*QPnpU^Ws)(0va-@g;pYwi66ojx- z0aX;h2vuHz=1zHfa<|e=+`)^LxZ9% z;OWkyjkW%dRoqV@PuhTPipyqLm6TXB)mSa7)I;U6<6(Tn z@1}`)av^2Nb>VFH#-Y_y4k9PG_A7!^3NsA7xUA@dZhE?-X8pgEen?kvez|XHiLLyX z*NY1i?Gq`avgQTB%?!#*M`wIHZfC_bf=2u-tyDl=T<+Ns>hF5B^}vx1hpQ z)WvZm$}s9n{PeyN>Tew2tF6Ltq16op5#UYKG(YD=K;X3+ER{Rn3`S)|r~5-(dJ1?8 z`(Fa=#v)|#Mac(kNnz;ECgH$q;9IxLO*w;4;kYS)i0*j8R zzsPt|mpSTUjk+sQf40zur8GNT{}!c$EdjPBWoF(bEP_CjG_K^?MY|X`zIwm;5a-$E zM4UqFFlI~6x%S425@OM0G?WvWmu=H8wiP(+mICc$nkFdES6upNJR*gZ)=Z$1cV@1E@`eqq@&;B!fDL9$b&g{9b@9`6OapD4R{Ux@xmir&~t5Q1J3Ty3S zoSSdVj0LQvh@OeKi%*h%=u%F*G_&V09y`0FAooe0)QIu&$vD-;a($; zMRcJtTFevHi^m_fd!Bz~mPNISQbmhFbz-~A6=g#erIj90FO?W!E)AbDtE`fK+SIA* zpQI6Kgh@9mIwlElHQ@27qfztM@LO|hVEvG5tFy99;UH8}caGcX&}T0G-DhXgL0GO$ z3L9G3=}n8OHd}!@j1a(UoDQ3*%MnvS@8gp{UV1mSqH6V3g-+4pcPSJe!mLnq zvZWfi$jn-V<0PY@a~-=$&NJfE(9!WCuSnrBkAz!lrzgzxeWVmx*q{bsx}z}ks#}q1 zv;W^}BBMe+Bt>ciLh67|&`*W5z6HmDf8|gk4Jm^z6?Fyl4pmG()|RP>_J+8W=G38i z6UeaQKoKu9JSY`aei1CFOqXwV$O(ASBstT}90D?2%3&!^K;n1rkJVlKr-0S7i-|?W zMhGb!g1o5AaSTS5ph0{DGDO+U&bagMQgYi+WSPQa+;DqjW>Gc{4i*l!!5Mj-<2-y4 zd17h^4e&h9t|&3mP!Uyw{GihI7AR+9drUf-8okS%;bqO`MX9V(Y(j!E2g^cZ>1zvv zml&@Sif)1y&)R(&q6hjf@T1-OK?t>BX5Cq&$*zGS5mAmlxN0yMp^+su8!W z>>p}Tr(R2SA-f%uG7jAH9(gg08@e|y@J?M~pt~3Jpr0@>TC3>fV#LG?Tx3?Zs|Stu zT}~?88$5oPHnvb?m?q@x0Ou~VJnB0}io&?pVkQW1lquyddtRtU@In1b2!>!&SAYD}kmHFuEn71q%39CIaso1N(o0&@V z!ITunE7wwf(s4~OApkg&iHrr`MG7&WF@PcU6x@ZCY3+IG}JVvG^JRPF@RJDV^C;&TNF*)cs}#RX2Tce{Qcpu zc?5WPk*|N)62k{f8A8$tsnB7`!bG-{r+;LUpowaFa^q#m1KS1YM@h{r=88$~JfS9A znWm`YZyduQ^lrZdR+d=d+S7(;v#R@)F>wJ!dwJy-L_KdrL835@?XcD0%2X7;R;h69 zg-4{aH$%8%Di?YEpI=VgF~07B0%QrXp4E^@4KB69k#r)V+mVg$ zi_sz(YK)0k`NxMC52k88SwQ|jwOV)*D0c-ExZ|bPxWf(*F(E5@ae!^E1_mOOc>hVU ziZn{XXbAW{D(s%v{u-=wBl69;QJ@Yjjkyig4@xSHLVFG7eG^zcfeQ_|FgAFo|G_L^ zNtsk6STiRmBo5Ci`k%|g+Nvo6jCi%9$?9_|WM4x`oefCIKa+OwJG?UV-sqySyK*Bj1;9chPgVK( z)(U?kv=7~M%k0LtKPf+ZK%ItC#$v*dRCM5}yLfL5CncB7R#7@5&gn3fH^>!?ybMruMdMxhYxhWKf zM`8p9-Ti;L*(%%+nD_ZqDzEhSH#Ozwox-l*2YmFI9kt+u<>iB!j0{c1XJ&(5AD!=> zCUjq+f_DfjP^D2~Bsv^s>kJKhq#(E(JptpBd*8+7cGqRQ*3kRp)q{~N5^L)8z{cQ( z=fZ5kJBN{qRz_boDT&k8Sau|X5*ZyB=#wBMwwCiZy9?XMX;E8!u#kdqyEl&axN{Cv z$S=)M!^ECv$)}*s7CzCr^z0fVLLO{?lo@`Ev=L@t@B9$t-`hkk)H?(T@_7cgq-Rk# z5TW^HwTkkT@#R(@O%87_<6HTmm|FS?6M;>y)Fk%-(#axAT3sliHI6Ji`8 zSpVh_As1WUevm%>8A}UPDotbEea}=TGfubNRgw-;Q?;f>*PezfE3#^$k1kJzT{q#T zpqA)%{cX;+wZN27ij7x5{jC8~y3rH3I5r>{>h?rj2tsncKk}Fqs2|V9Ely(6?6R+k zEJg0Iirui`LTaly62G`AS&VL5jVJiwtULuG{;CrBD{e8JdZQ1EIx<>Exq|e6FFssI z42m9Wn>L#iHvH??da zfoq*lP$chlSRYVvf{6;&%(^lqEH|HY+~&|>ahh}Ns-VLPh}bIZl#<KGF#V4DD9+GDvefNk(Ml)E%#LMYm=IKhCXT+ThAtbmK(#G0B zN<#!-Vb)p`Nt=(XGAvL{W@=bB6I0p^b80>>k1>uLl?Gi~RiQaCEd)fmq@<0`^}~_Y z^X6%A?A5}nvU5-*j27%#5Uhgx;}%WAK$LQB12H*8OG^tIMKZR?C@Q854E{bzsw8cS z#Jn3@<#P*csE|}51*GTVJ-lpJUCbek?&9@o+zD>$og<>%#=y3%=)#}71T$q?ii6mf zOq+jc1^g(^4~u2p%NFml*H;s(?F8+m$~Ij1k+KAtbD*F=E)WpS;x@5*7lwfDoB0wnXdjM|P0?)TfM&l?_{61odBx~jkms!N4$4Kug0Oyy7H5^b^1318`1 zD%$AD|7@h8zFJz4b?kO+J*=r%|M#MafBnuVjmZ2dqFhdh{HB-%NF^!m@0UWX+F?{s z@#Q4!aeu6#nn^3{pCFA07Mh;M0Ler~p*AK?{XmGA_QK5n)H>Jz?Jyde zPr!-`C&nJA9LXe3o6X%4e0SB67q8i>@GQ-pDt?6bk5M0D`W+{p8}nxK%MMRxKFJG( zq%`~nT_hXygP_$6tE=!QDz{M4N5r8d5H#`Qj|!){?q|x14DYCZQK$RVeQFwItI)TZ zicD$()|DGpp{$(8Ww|IZ-}JJqY2?V1Mp}y$Y~5|cXs|B53!!8 zpsNUM&B*+RtT_GlA)k9U+sZG7MbP0b>*|HshcB{H6I8m>p?;AgpE^fIokfeQPf^m! zP<;9C?g|5~V~ZB#^*qs79X;6BJ0Rh-ZjZQ;ilE}J98;lT?i?dc?Y_ss_I)`j<)t`I zQvvP7#S|$asLub|sp;8O!~DT`%g&HKOg~7R)v~nkPu9TiyQVBpL=6-?VtNI9YzHY7 zoT-y=APQ`f`iEC_%m|ZAv>1;km$lOz)R(HNbb&c?77k^8fHW0)i-I0rN5-BNARnys zlPzt8F}@0phE}8y-7@~X!mpjdn_h!*Od~z3AZ*pQqk|ek7=YU3y!6(W&E>ek$q4sq*$DS_2iiL)OT&=GM7tGZM&E-Hn%{yk*+w2RYNp395}?&qP;39b z=%Nf?>JUgIYgAoUVLTPF9efZ(H=y6`k$s}Z@@}Wn%$IJUl={F)Qz_b*e9ue^8aFk9 zt$%e#hKUZ;&XQLNET{t#A6Zb&I}1%((#qL4%%3o{d!kz;>tqrJ%v7TnsVdLr zz0WzCaklpx{?$uGr%0M(LXR&}_Px}KRL?-^uc=FHc!s0I0Xk~)cdZ$<(}h(=YB0XT zg|UMD;;@qI0RIXkQbRWuHa-#g;?7J#^}@b@z?Bu;DPMavJr-%66q1zjji{mSUEs72 zg>DAJ)dmSHbPg7K>J;Pc$pdYhgG{bF%%7yd;wUs&@hiTJaXIhhQOd8Zk%?mJv+p4H z>$YC??)3+AeT65R&6ncL7@<--u?29^kQeO1>wf(_1H(2*^?eWMD~`V+Ql#PO>8C#m zeF_sUf&`4WVWLiGD${<}nIERt4iBPqzP_gWECF~H{U5eyi{`GK+>V`%5c{w)q7#$b zr^PqxFzK9wPyJXg9DDD_I&wrUz7(YUlsF`?-&Y=8hkC6%=p-B$OzG0hY~10<{uyB} zt>!!1)a8G%JzUIA0mfe5bkQ-7`PeWMqV1%yr6mjvd8=8*{uAR@8j9@lqEnvi^63|{ zvfSGWr3&M^0tk~Na<5oPfc=c@Y|hO8YD0A{-Z6OSD} zb98iLQF=)U!R_RuT~&H@vdHT6aD*T|r@I+>$`z{+&)AR_mZhk2=YN2({6xIvarX1| z&%sS6S~cRTc&Qx|yP64x)b?iIC`}}sI#C#{i*{2nAd9woT?8@l{%j%kkt=tO;vdx& zp$AOH5G3%ARQ&x98J$l7S2~)-QvprIBK!;>tj7?#f31_w(M^XLKM&1u~BEPlCoZ*SNCZ3??9$=$IMg5^FnGG;3Loo1BDz)X)8pzR*gXZvW@0 zJb_a6q3{>;kAaketpM+rLr1*~&iVp_n^xNR!m*`c_7tga5-cgDO*pQ4WOHjmKma6^ zsOoQl7{o|~VA89RUR<*sZk4U3u0E%wBT1?+&xV=v0xKDbO`?+OagnJ{SFD1IDlOo2 zL?iHi*9;`mcQrHoKiRCBEo>Z`GVOh+Me zS6=C{W{I}ZH1$nx%jLn;G}RkFd;QqRPt!5vlU_~J@h%@erQi$QFt9+n^ulc7W>c8j zBofV$9}_c+x+oa`)YXBXd{M>#mo5LTTmr-~!kTe`J~5W$u@^zk>rK*}Mbe~y`e`ch zl&JGNm{gO{!KlN^himk>&24fze*EFx_}n5PTz@A9v*2NLDr8^l6gK8Joj@q&4;*gO=S?XIV$O;5S`?@%#)E}fnM>j@mH?-8gToYigA2c#&F zG{gU|%;7lOMy?kbTvJE^&a16<`bR|>d@B26F0tk|192twYbtVNWMJTOl;v0V5p$N5 z&kYqgBZcXS)rs%bt3Rcs%|7}K#%|vjy+tj>jg)DLYm8&2|9J@i)>xDpV|re(2^e)5 z^`DTEM!6ozCXcf81wFK&)^8xURWuy^FkMz=YD)ybD}9uYyvqNg@gKyAXw@k1gGPIn zL<@Bu(_L$E!>vuPz|po31!mj&_*7N?s!@4fUnyd`;SUkvQE%u!mQ0fiXu_Ayz1HpY zmLOv2m_deSa$B57g&{-Ih^i9AqDKm@3JhF`ZW$l`?9lxh&LnPjPz9guqA*+(14S{H5}l&nv>rAdG_Wo78;CS*{VA`x#**@?Y- zi660j-}zn7a7I1osPWrUo3I@U&As~EZPKOor~-H1cBQ|2Uu5Ed^AL4 za~j@pN3o;Lt4PW3ZywJhF#+R}^|~~&&reUPM1{BJn&NZlCZEosMQ;9fft`5rK(Q?B zVMM;$&J6^9Qe_zBTP1{$8ByTi4-dHoslY^VrAe z(!Wj=(ZvqtzoUx@?~#`UJX8I{mQMU6P~%$cmmAl_f-avVtsM1arkSy&lw4lBq?^1S zw1ORu_@jFM0)5EA-{nuAmV!pTOjq@@QQZIoyt=;lw1UTYI{`|GwV3Fmf(u!jjyw0g z+4AwS9epR?g&mov`DP#h%Fy=%TSYT$$gXXk7JS6fbTK%!0no%>D#DUe`KY7VF z%NhS38D-nqe(qu4kuWQ88xyM-e~T6HYG!@1aGOBn6HJiPiV7QnlZ(9{#|mig-f5{s z`N^B5N>gQJ-s7d<@W*slq+~Hde1h}So3y@wS7_cj-t+WhK(a~3%vF8w%@;7aN|G`| zJrnp#-Yb~ZMTb%z%uy#j`)`l8C#$2+U1$+F`av9rEg`39Xm>IHg*u~?*Xv_i^XV^{;=JxD zl8_)^kKab-i4MzBB%gMWdYN~7y6tM>YcjjAzJ&jkiu|2?s-$~Q=`{*Rgb5|i0+~Mk zgE5yoC%0Wke6lAL|0H`Z+Le4|qReua&nBqFiU^C6LbC74VY$(dZo5GcSxQaw^_=j~ zN}T6`Q8L<%3XJ1(YDPN)O%w-ae23Vi78!j`7e`IKUCVNQRp~T9xJ_t%Iw6_2CfTSTOxS!^0diSSv!C|;t?{|Ld!^^>4eS%i>4^|ZXFd{Y2 zZ04-Laeq{IrCIKCqDrt|l_dQEN}{t!=db=;dVqeiAbNEpT=f?;$&zMx*ywlCYvrup zjar9x)Xj+T;~ZPYY-yw=Tx$qf$o?9N%-3rp2vk0u8y~+8RXSy(Nk7!CPSmx=b-N#< zqb;+684c}~APJ20JwI<6nTXOYe(myF=b9=6+WHy`JRCL@W#tJR^!k8$GQ@8c)!Cw2 zA7Ppmylk(XBGJt7@nt%!2L24U>Dsg9Uj*_gxqV)7x#s~N4|Z!a6$Sq39=7Z9BNI;L zx2P#uY)JMSU4CQwDhc%8n zt(@d|jxO+@>9$3|bJjEGOEW&}jt(ii|8giTX-uQ*(F2iYH9Cequ74_gj7$1wwVIOU zLH6W!`X@!nMc396@cnuhXl-$Ky!(SgKRWW;_3NmlrPN=DSn@K{^CsDmfWEk544Yk*t1&jk08=4ktcQPKi2o{q0Dyva-W*z<@~)`D$b$)$*w!peBW8XI^2jQ!p44(9 zFkvV$u*8Bi2h06=Mc>q-apsTvw$EUqd>^zj^z76#oxZfs8=FsFqV-Sv-j@;C?sY#z z&H_U4hAzAR$Ww0voPA?Di;RX{-^%T;bQA?9B?*0F-|^h9M$($Q-QFS8x2cIbKT+~~ zFG=*fT(brJj%{*#yf6Y2?Hw&w1wO`K1M(lwc=}fXbzB=?1XliJSEam->=K##>7fPO zh16e7a|TRFSwqOnay9F}#-0+FO;8xi@pRx7@p7XqYaDLFu7VyczMdFQ`d3j(a` zh>A;}%uD=$utmn#5JyHq>W!r}1$nL+gZJ}*Lug6;qUOFF%i`#OJG#DcfbVpClK>Ac|i%Y(b^{xLMt_5I>U{6JJ%PX9c6Ty5>?bJ?iim?`Bn zk>DdIevfClRzowTKIl;3-s-{Cb~^-`a5tyEZwe1<*759*c5ADVyKvT}+GL`TkU zg*h1;0@3?R03=^%)A?=oOkB)^y6+I*JyuyaSz1fqdYU+4#^rvG zzfKmyra@I1r4A^$AKIgb?e4)C7-KHa6u>9@Ux85WfaO1?p+omG8DQ)-x_rFAR~64z z6m8@o9rU~U6&Z644UK<2W%mZWz>L=Ali6mnsZ+rotJd<$uWuPUP#Flmh)VoH1G#mE zzj8Z2BNz>tiuzUe)s#1PG{#-qX5$U{@pvQcgePX&w`vQK3{*;yms<$~Fbn+7SRg`f3C;?}~W8y*I0O zD8y*sa}L5e?Emdbxb73^NIi__P_Q?)N;UoiGyZg^onZ*g#P>dph>4GTq|1Fxv8l>j z`_Pw%y^;3Yxi47Q4wc2`P8@tiqaO6AOQT-IK%?@<&Hm+{VIF zq5Qu}>c2JAFqtCfu!>$kDKwH`_6GATXp$J)Vu0Au5R}Q7Y;5ZrY^U><4faL4@dw#| zF=Q(cPEy?MZ$=cnb`udOlPEN0jZ+0=)#nQi7HRg*B`h`mK3SeC>LshG)*&g>!ViTsTYGq;uz~4D)_bzom8X zue34><%r5>2t&Q5s0UNBjF(OT3A#uyPbK|@I`pn9k&bI!`C3KRNU?~q1hBrV97A3B z7qJ!MGNv0UYUw{OoLVPWUfLt9R=FU7K!nzwQ*_8~09LagKh4U1v-9i$wvpnQacbMv9~9JG$==z`J9U}VK1-={7S3r|Eq%#x6wb}Cs_Kmdobp=yIZu23=qunCpgGS9`Im*- z!P#hj&snW4iVQPZL=psE-;r~#lBSGrEveoJExM&1lE}{JEg_)5i?@cp1%Xm{Pc53tEPC=Cx&rpU7j1_L~>kWw^dyx(9 zV~fKL_p9nxy3W*`|7{$t#8tP=Dlls1$tlsQUo=G2QF)QP1cB<=N_S@%#_pboJ zb>zzcA|URZuKrAc$dIAeaKXXykyh=t!*+&v6O(KbQx1?C-rwbwOl#~;ecMx>Ri}z3 z))?LJX=EAUMvB2;acKGCJTG?T2hk4tpGLgD1^nF!vdz2Y+EzGVsK3wZ^^Hoyu3`8H!g^8hr?BG z9#VVwXSs3Z=;cN`Q%!Wt`bHUXXJ=nTLG%TTNp8Zd$og>G47;p}pH<(*aO$A|5w=sP z(b9mm+AaHzQiu~%EfCJ{i_tU!!g7|Cdd7YQLf?~Tva6r~nK~=l^7F>eH|)GFS{w0B zQb*m&-Hs7$Z0%vVcx|>#M{n!K@&gbjw?`dW~LAFFXUUd4p=eK{vUC01ySqVd7%4?t893^Arboanu;i;s$>$w zma985t7XV?70quk0G-}PUR!x5+cwHhkv3JCC7q=-6^DcxBI71U(SsE@ra1orG3{^+cU7jibG?*8q4$% zI5iPw`%abHQ820fY@^SPoXgAi-WKIE6%czh_alhOa~2JGFnsD2nbmk$o~JCK3eYh$ zU{R4QA;-MVqc%aX_Cein{~_K&+NmDSZ0Ma(b5CR6Z7Om>fcv~&wA7q$s8!1qzN8nE zgu1~=tyCDzMp?oa`Hs^`k3_Nm)WoAq4G8fDo9`dntQ_2*FJ%~q zzc_Q>|0Y_-fLec_iBtbdP|lx2HDt*oJHrw-SN5LMWV?Z#^Ogx0q$40^e2|(6L&4f} z5Y~^I{Cp7AmuuH~i^C@SnN{X1Aweyx2p z{Jf*=J3U1L`VGE*{I4#^%gaNF(U>EA54cSqg)d#q$h=Fcf5y0xeG`27-NE?g-z6FA zmx6Ea9@{5?Z17=+0~zX2^XHGMWp_Vg1ilq%3AP?z<4eLTQPJ~Vnw_m5j2{BoVh|`H zPo`sU3plQk_WtR!vsnBOAgy&l3zlWUNxek8q#!Y&5=>F{RDEB|%~4}DO|>SsereHl z@tq?OID>OB6YSHv;*pxQ!cd7$g%=m%D>OR-oLn96znYOSxs+GXpMFbmyV!QJ1C8?X z0Mf(lzL%fh5DxPG0n(phCI z^^Q(H`wd84&&-`|Z8;>`cCP!f;cX?Y-_cmKwA`KrUHr8rV&)IFAc0YjVV@MY-xF9& zCwrSTqQ13V4;!TwziJlzN%;M2 zc$aGpgM6DSH}gfCzmJC64d&mkXV`)cXXK~*^54>Y?G|*r1y2t&YP3J8QJOAjkWdKOYhARB$p`ejLgh zX7?Y%7dCspp(RVe4h^3br+6}jzH-RO=YpQ^n(T?D>^!_uGblCXO@Y(;zOpv*pXwXF zoGza{Q2Lnme3{|Kt_**_iJ)~C{*d}cA1HJx84GWUYzGBe7l{&LaeONQ=lsiUwL^8T zuZ%}O@}!QjTN-KlMwH&{eHMUP^>MsWaU<6i*$ui$6G!6{5K^@A1<7usFTY zm2+Q?VsK*2vpr!Tya3I(saPNJVNCP5=q4;XL)qiv$z&#Hz*m{x91B8q70OyaBmcZ% z&3g}|XNrq0+@AQ>`1}eRZ_(-kCnEf$`iD2&na-3b4b5taS6Qm`sSQ!4$?_L#aEgfu zhzeb@LlC)+j81~>(i=T9!{orAnR)K>zt>N_=YgNLd5YBD=^~+J@ejREbFHdtPYH}F zCl%HGmcc})p>{2 zK(YDb7b)4#25V9?-oPCq5E*fG{+(sO3tMBZ0wEw&FW_Ip>gW>Lnq%{0TV%))(YZ0lq6*=RS%%eIAX z<;NdqZ#wRZ4Y#l((4B9dQCly+h8HwZej^K3ZcpnQsodP|{#NKw8hWq;m5*rLH*Vaw z%FSU+7l4 zfNMIsL%mR1cWYy0-0+5AwTtjkm6Fn=p_)2HTh-2qpYKq%)^$y*=eGWH-+2|6?{IlcnLDHrtf9daM=zIv_yi& zrS!Y^2Cp89Jj!o;RiNCxy@iI{x=lRuoshOj@U?Vx4QXczIHl&*AbM;~ z@%p-NKP9$Tj<`9T9+7nncX%F;2)wu${(+jJJG*=hGh^ub7@fY^6=d4_bz4BV)tPi+ zeI1rtbt(6%}eR@`u zW?ZGB;p)&8^R{k1zG^c0mgVc7(&4d->U&mfapxd>L+^e0t!BlbO_440&&GRTh;J{X zK_k(9tGfkfr7Z-*cBi`RGxwP{P;+>8LQ|MH>uO7DJ*#oMY1@*eN9hhvhjC5ufwsu* zXIMZZVVA2NN1r2M?=Q;CXs%?Xa~w^0^c%l4ZJSCkk`Z;>R+e;}CcL;DILq@W?-%@q zFpKc!`(LZ865Mb>PxJ}z6Jw;?vLVd|&5G){5c#6yMGQ)kfF9L1@n??X-QHL)hoTx_ zQorYo7+~t)pLlAa?#hfi-l;`-4K|xrr!&Fl&5+7JcS2dI9u?djy0;Is%rl?)J+5Y5Ajb&x3@Bu5BxSlM`oqj$XstO0KT+uLWj@|75<6d`VC%Oidb}q z`!3>Wl;YWbjpCVN)-#IDqWp2c{i)6=-HYa_eDve3OS+(QcuWRgPo>|ZORMK`i28t| zTpIZ)l#vL@mEr3I-udGx*#xEwvCz}tfcxf5Pdcw>_{`2b&6BmibvJ(9XLsU`t~Qod zz{SbP@a-@0+%k4$7iTpwPS?Ev&CfY9PvURFAO8+Nv_3!cr$3xx1^Il(Zh0HvpK!&o z?t5_3m}IbljV{u{8@E=_X5mc}up^R%d53?+N^C4Ee;_(K<0CCezH^ z`$yx}>6UCcyiWPQ-^3dGtfu#!InQNBu{m|B(x41cpMkqJm+txeF8bFSwpXM+!eb$UxoT@D4if z-^=lf^0fX)KMHu!l)WVPO=m}gZR7H7PCHkO(d5USF0SpK&+Hr9Oh;XL_+0!=YY=66 zHvvlOaP>qbw5;gr_Hm$)3j3zs4Os<{|2bKEVMU~}aKGGxNKS0G9V9IbT9hi-@$q)` zgeb7!MYx=ehpfnJqFmOHpvft?nC-yChf$ha@&B$nq-s#P(O#22;pZsgOp$i}at(t> zWiH*jdD}kW$<$LmgC%QIe4d!Gb;gQ^PHOCHl8T;m;{3I^8H>%FpEyf!5Dqb>x;AqY z*weoXcV}-Dq%cYbA(REUQnUS%OIYv}fxBtw{mX@e^YtJtntVt{)>`YAXsA{IJ7SE} z7w_mB-$%5?0(Fg=v=w>gElO;GJ7~;#?@$O7i?xDjb@Teu!aoyjyy>lY;tc*lHD}^! zmLc5p6+_uL#=m#eS+@)?f3dT+5?mZE$euTK--vdWu?L%KMfPD6rwVqOIj1MvZ6Si( z*l3R{3$#8}Dmg|J&_zF$*J3L~=3O8YC#P=MTL;}Mwpsx8=tBiAAr z5N2g}=Knxbw5NDgLI)`+iIuvN7g1IPK}}(l?=8(fWpOKwk!QH=|ARe; z@$9#5bx*+j0iT~sWEwcR^3}oRZwW1(u5iGj+3eL6|JZ0r(p0bp-a5zY`1#zAIy{AfEK>jpnwakK?5u!Aj$5qi_1V@+!(b`R|5b1-8j0T@mJIG z%Q^y!=#0(x1NZ&Tl1%TqXxWFdaj!A+g4G&@o2 z(+LF(e~Nt&&MVlZ;;e3h*W5LKeT{8OTsDOjv0hG|$JY3LW+tORsVt8z-ZLdAbTFth zhuElNB}UPT*~8%dYN>!wIaa;K;SC}yDu52(Miqec)Jj9fY~lg$kQ$YzWpjwHYJp@;^hjJCf$ig5=9$hc93B|~ z6aHgBA#-OE8$H0-D20k>5ykKBdi`R!sbT1EgKHM;EvZcDv+2Coi=Vx7`1=~fw0lx6 zF2n|`F%J1wQhQapoa8N-a&@II0RRP>6#hd2O}d1C3s7!fztWCcw)CRf_3TZ+xKiRb zsH?gwddG2}Fk(ME&+GEtD3=$)7}fYgwTrA@Le13ySt(yC3DQUH)PF34&c1WSYEvKqn4|h`jLb zv9UUH2l3?PJNn7`#^9kS6_#mop-j8hpJ$zL^yAgP&r8RZvaU8;NCEz2tuJUN`VPlY zNp&DJ8l7CUn0i(@mlL8Zf8c$PkN!)UXtX|Wn*;dZC*xLo9_8YM?A+>96Q^x~2rj)R z{El^JCD!3toH&wYVYVo{A?gh5Al#}4Ch|HLdJ*G38tp5$WSS0f@*I}jHfQ^|hRSQ# zhe3tm?Q^;QAHW>R?LMOJ_6FT9mNgg*Y zd=dzo>g-%R#M(ksIE%@8rt6{7e7p~a|g=XBcwgfv?x*yZXhsGAvopTzxWfnL;`;Uhj0SsWJa*@1PH|<5tGJj zHoZLN@}Su3nw3lL9ubH+CUFWSkHFh#co{@fUTg&HhI!U0UK-C0GD0gNVYiqSiQDGW zKYqTp1IxU@LE5KbyKs@o^45Y;Ctj51-K%^oDCfB145&RcN43zJVHU_z38(pzRxsgO zN3M4_n;cgg?1l>eqbb4U_9W(vtuAk=A_uP+v9?A&H>)eUC2U1vj zxG#lTeKU03bkLV@l%x%#R33ZrgLh%WjyxLArabymg=BB0X<>7QZ&j>#@}Jz zF3RMAB)b^d__>DCF{yPKsxlXQQ3bHDWp;j9Kv5&gI&e)MeEqGCS(I|6Fy0hYQRvAH zFtpeo{<#+-O+fyV=iM=h@#n#JIxg~aGNlbHILUv9n<2qW;9DAVEwNHB%Wy|agne9u zT{7k`f3f>2_%^ey$7tWei`+o2Hc5Foy=`gQb9nu#TthZJZ#-J0$|&&a!w)=zjc?o&|eSAF6=&fSI*xaHCZ` zYW=hDsW;hl?KKKUKx!sh4+}v}dUM0roxQqjUg4qh`0wbCHY7$HF=w$w5}R@NesN_aQMp?rHRhyNz}Pw`sfr^Y3{R%$%%(uHrvR ze@Jx?9KK>j`E(>K<=*6cYCX1Yu{{w=c3V)NUG;+!38tk5jvm=(F zztw|r;>P5pHhMAk|E|2f*)MmKULsLYv*s#V;1Y4!7SP-!wbNAsy>Ff#P_TA|0pVy| zLWlK5@y6cbMVhT>ECMk88O!BssHk#%vbFZ$V)bQ6x_E#3P` z_!kU;?O!&^0arB0zc9Q^V-~1XMeV93B(pO@J2^VgI8EovtTK|ok3v=J;- zOzqDSdu!gejb_79XUJ)qqUzB zN}ZgV+8xG;-~6>Sd~@dCyVA}jTR%01&z~-Yx~;>jj`CC~`mUyKY-9R5;d|a%L_8iY zz07`9w!Y3Y`u9`SJ54P{B z0xB%h7SvB1N?Tc>&R+>zA8cby9s8WWh^vorRHmFtf=Qf7nf&QH9Ak}SWZh#sf=*_g z`LMY1NDFXfq1@PbY%MXkJ%Y$~ER1FB->N_W zxe&f&$`1H3=H^O2$wt2CqS{~h$!|OfqMtJ*eg=+C77`xM0r3ifam&Cp zUQGCiFGf8&{PzT$OvN0nPQsJNw9lB!EHXS!_Pe?^IddprLTxW~mDaPlWpx*tae*(X z5lKun)zwQ!stH_8P8a5tiaA^Fii?Wu?qJ-n=MISJ>bym4W^wx4F5z+ zO6ZreIkJLOhP*z1mf+y;hOu<{+AAnra}y<@Q(N((T?1P_dZywNdlBBUrZ zzsh|i+j`{o)fNX+imC`gY;xYgiMs(MihQKRxqfOhgHK>xySxva?m4WE~`~vbInLOElhQ!gznI69O)u?@!$l^ z8W}`**dB7@C0oxv$1{z|9px5LOC0jD%5va*cuI2m%FWh%FjhjYb%+llZo*CRTl$J| zxw*C#`#S#AnYJi0|E9Jna%-O|R_Qmh$d>#pgS(|}8G|jn=U=-cLv?I9(kghmK z;Lw{ciONsHh|+!jV>D$*JMnJ@3f1)|2i}!e6rs=?A(hZu2O#YksDGF4(B{?$nt482 z>}VOFm2y3K$JsK;(zSHynfxH20xs*WJZOGEqjE+5@Xw03$p7f12vKx7AWTXuR4@i= zDh*;kb0T)}D#BQ0^ZYX3;N<$2=GtbSoIKO$y=o`Bk&6rV2nVZtX)SxC48Zhk@+i~Y z^$aXXx}qpGdiu)t$gGUE%Uy51iGQ&(4is8#HZS*tHd?XoESu>rOm3BQbW!W@Hu2#o z4R&fb`(LD74~W_N$uu$ zPhSvj4fwh-TS(f`Ivr9%o2m+?C-(-ayM4q^*Ssvq0bGLhe-qKc8e&i6uxhvzd8M%< ztX{X|ti)&*zna>b!gmqhNX8Ug(y4|y^_LUCbL+OpoOmP$hw0M%L?Ah4(&_ceY{8ZL zo`>j&h5Mp$!y`2!DruJVFMO4>BOX>5=KVqm9}VrT{i=WNNA?e;jd!rD(-8XsX*oF) zU9Mm&3>TBzijOOiu_GgdDW_nY&$K;l@!`UY6#^Yo@1 zs(kzl5Ab@ho?%)`>^}5lh@S_^n-ti6APOf5u*?e0J}SLb2*L0=%L{TT#sZO_G({3# z(Sc#i!Q!%Ul2D|$o}zg&y3jBA@EPSI9+7`W=nfJt_n7&7m&@vEVO`@)foRSO8zMOO@YNpa4Tp~btqdN~TGK$3f(EgDt?LArErAs637s&}X zSG&OUtdQfe9otY?FrhSWQaz1;_Zm}ROm;|hTaQ-fb4VSPh|8jC8*f2F#)Jf z{0fl7PBuG%jzKMm6a!ull!RfL+_1`&0kF>3c1=_iYY=5?`jvP!b4iDA=Yp=A0aLIEe|0gn*)aB z5z6pCo*q=FA<4$<=DZ8RL3WD^g(MY6-DvQU;eBm{Kk+6-{cSwmD?-TJabP0?95xrJ z&fI@^GvT)%w2y2qT|Jg?nzhY^oNpy+OdEgxxN8?faqW=~9K%5RBu*y}H*u5mXKt~c zy|vBm+W~$_#m!Suo%v1po9PwL3OZ)53SA*7LHiv4w4t8}W(Yjd;>LpFw$|?^I9OrU zS*lph&Y-4T6$hKm_Qe@J17GzcI|mr?WDV(mOgO+Bw;w3W&1V^Z=Hrxg=STU{I%WT1 zLxCFMPA}1R?E{jxNpv8u`G%KJ+5r(UaT??RpXPSM?ja0dL(8b|ILZV$vAM#u>6QkM z+xR(M*5Q2#7kcG{xr^4EK}$kQmCmt+Al+sD>b7B69G%OErA`wklSFv-vZXZ6{^a2~ zzZBfM5SVnGtiZ2YvW;a3+KuXm3K7y-DV*_M>(cpfZ1ocv1s~8DiA_eM&jwdmg;2N# z%Re_YJyRgZ*DM5sWI`IPLQcZd@PZwTnnCq;n75!{d?S9mM5`b>M1SMd4eMp}P81ez z7AIEJc$g{_?13sIFw+_I4XCSr5l<9m(z8}CL;33J-y*#7ov)g*GND@XL$WdS2{TO- zS7^q!U3?pGdp9o3vEuuifpi_58Pl6(S{z~)6%**Dt7n}Eu z1xK1~D#(#1UdHs{+s6E8O}5c`R3F#epp3|-8|0eRH$B#ETqiq|bbz;Tilc(U6@>jT zZ3*PH>|~ZItieFh%_#wnJMT1?tyU{NFaSRoFZ)lfuB&y6^!KF7zu|fmp2{t6p%8Q? zA_icDDb(lG+>FkGy^nIi&Ki@@DDT|olb_bWw$9Yn+LSt}7LS-f{NJ5&T<`&*9txX6 zKrz(GM2nzc4tC<=6f8-+-l;(8Xq!fU!gdsCdW!(hObjx90RuT@*yY}6-oF>rEHxWeIhf{wfMyk8rE*X&n_Et|v#mYo?$4o3d)HwHj4Zp%kTQV>-)w7PGGqs z4N^CWY+17W3bbl~m|?j;hFXjMZ|B!jy75VRyfcQt&Ksz0gjkNhv36toN2nHxA6^8g z{a_<4cFb(V?W5O`c`&+1ftw4sKd*Ez(%)?Q!L=Gjkskg~*h@l)%81f#`2! ze+YpR1;YIMID#HFQ-Z{>15d5OFgxBqh&*AGHSFv-E099Fn&V2$wA3!@>^-l)$Q~vN z0VbZ<%t(VNpkxFP3n9^a4P1i5y5Y6^=97mvLOh9mg=y3WxMx0fFV&l zTs}q*%2DN}_NE$!(Xhcrwg-CQivsngTX;kZZKw$LpqNXNXO{4|qd1Lh(aR(WA^55d+8sNV6;_+#*p4y*Xm$n4!aqrfC)6DndoW?7-Ft@{>c zqg6h2l0Fi=HuF)616=6pPKcn?xdwsl%GJ5j1xwSCHfEH@rx{&%B3#2X4y_L(AqMq) z-(>=nFT<7LP_wr&b9Jvn{a&Ke%OFCl5ywDAm*1x1H1;*`URaJUYGL?UlcgK@(Iup`qOz@;C57eNP*!r+wvCl`oN~!o?dd^uD zsASnlhqr^thNHH~B33NIFj`RQdF`33<(6_%hZZ%dK$b=?|Q4U1QJJJ&1 zcG;YrGeKrsI44xHd8DMzv>hFO%&56bZclD)NB3*UkLF_jiE#cxHxUy)!No(4h(Cny zm&h8t1=N)We*xq*DCv!&gbADnH`Vt7VjTlx5`}f4jnFAb*&UYE~+`C7o z>z^?E<8G3P$t-%<92FRff}~iHD+VUcWz7O0DH@2ViLP+_1?G5X z{G@r``g~R&IPWTiQC_;4#g+29gzxmbs|qLbe|c zXZD}Hd|K04kbMJj;g$pVqiq|)f|zob`- zMKOhXRl=zAmNA>J5he(~C!dR@2nE!<*0Y9?U|i&3>~Y}P)5#EtolMnm!W=hbzG(9T z3ttLp%Ok{LyX1(^6}CKdGkJcB>RKRS}hsFG4wn30I zrGpDz?GExqLT}!UF<;cuUL0P6&kR?bE-wuy7PEW0tJJd-~EKFrCD` zjGZOukiXG?r#pfsTkFE*QGFxOM|g+46rU&3dZCJpA07vWT~!qaS(2@ZShNyRFqFfp z(jU0FcV(QS(_q<83XbU^2-t-XOzZhRYr+P&LqbJ~0uoh%!jxSX9x<3o#?+bzljqzr zgM9o{vWzAxD}y646O0ZfSu$<#7t6=ZKtsxY5eqN?ko{hgLh@#{(W6EHUE*H0BM2uu zTg(jOE2Ps>3di*@zdAfG)62`dEzUo`{ywMrTofeXMw7i4EroY5wq)njVHoutHUS6Y z``q08O{=_h`Tf_Y(U~uIcP-xA;0A|vt3BwN@9t{zJbiX-+_bbbD>wH@N{B*|u%{Ro447U5VI`Lr^m}eD&Ubnc`Tprs!2|yvLmln42PysY{+DYh-t5~1zvp$} zCfy7zo{y>eA}1kutAQ56AkhM;XL*B`>9w4z34wb`>KGElKZuoW?WU){X^u82-v5eQ z71YqsXma0o=FKNir1IE2`-rQ;A-d7~C$!@ca@nOomM|JIvK>=WfRO4+g}?wlaOg%9WWK*pBnDfb%ujTUHt z7X*Z+1}HUV-i|P1{c2AAZ&|LigceV8yr$8)y(AR^BxuepGLN-5CAaYkvP-~m##nYy zI*WMcg>IFM1JNbi|5&-eFbuZ+*8=0CGe)S%*!yPcie?Rxp8Q{``96X~{Zs*x*>q6! z)ns`G|4+Uw;euEKOpTx^3@A#VqY5$>TEd-shp}^|cI(k67b?1}^fFPOVGv z?#f`}>3kdAVQt~Ysd=(K7ruIM9LUg1t@)a(z<_C8vvZPr^2jVyXU-=u$b<=CUk=0stIx_*-I1xL`ti|fF|B+xi^m6xVgP-{l0gz8}=vjMP7CB zlL#uB)`UXS`&#S4PS~dJ6@hEs#4jbx+|X0ld!wo@Zhx&k={wi}kTNlwuC4d-`JrE2 zd*1RJ)htA*CJ5D?P0S4{gyhV0&&OQf+Db?bOa_J|GnME3w>EZM|3v^E2l62*80Y4g zk(Hl6FE&?9C~J4PPW0e!g89O(K{1$?9EFZf9E=ngJ{${#^tnV7lD%5vbY&QXEEiHh zRS?BrF7`bx&aj~>IYpF`2*nf;m_~xHC@vOONm_a9F({%<2!206^wqXjiJ7qg#kmns z-%;H|nSOJDh*)YapeneRNR%uQf~2FQ0PbjYI~GVwk-NKirQ+GQ_zZ!%_Me{$Jbl1Z zpUcM!2Yt8wy7(U!qq8i^En8F`66li~rniTlAyc~jQlxaXZ@5p|%N*K>~rrr~7u zLmPChbUG1KfQKHpX6Y6YLPsOvIw|*|ZxfDs1Q(~rKqhWt7gs@A`_((F_mS{aSH=um z5(x-$3P|}*M=$XXLtT>KfHzW&C!#pvIx^7ZLa(L9t+XIC6om{Rt(PT7erR{7G7@d# z@ku*;dSoG>H^d~RLB>jFus{DpR%skHwP2jz581i(FRQ}rWWEAytEH+~`^fxtmZ71c zwSlnUI0Tyfg&&^^h9^R#%gsw@Ax}E;%CxE4#s+#CS`_bdR@E^f5XgV1PacGm%1;p$ z0qDK!|Mjtq4etQ_3Z0Cene9N>`}lzfgY1r75xe7ds~t?2%~uAat~qFQFhFi%{^=!A zLP9Db*eo02@_hI`ynR^Tm9YAAO=~x98XYc{ z8K=?N^i+L*5O)GSY-F$-&Iyrq{iEl zTi-1P$6XMg`w6M2BG`XTQzA5U@Ki@fdk5%2wd2nOaOFc#7rWUnFRz+3r&ZZDdTYb1 zIacVufl5awDJn_1MDb<@4-&OZ>#uZ64uSMYfPw~vqCQFIFLRpaB^ zgm5u2_b~yoGrpUP1sX-@(_^ET8H?O=zBF+ag-VD@ewH>~ZH@%ex6zp{+-e%y5&=Pu zd-gM=xu>}|*5ZgFHDnSJ5<1y{Orq+%rKO^xaz9zQTRon`#@9*jq@RlP6zu~j>2LSC z5{Of@FXdMlnV{hBSseZ_yp}7xwgeYOkqt@y+2vqt93g;tURz4yxE39xSu^F%d$(e) z)urS9Bg<^LfWwD0@d6TA%{HmD1`{0K;XJ5UZbDR;TVbU5I*ZD@Vbq0z6)us1*RkV3 zp$OVhkgn`A^kr>TVlEHOPh_c z?+a!XJMe0Qmk}Leo87wV^Bq6+{`SFj3~&DhCPFe-r0*IU-Z5p#>z6hQ z0fu_+CFDh9$TS(IZ5R66OZid<@CTbR*aMvvT9r|1YQE3gy85tBiJR%Rvg7zz|GF(XxBT$L^AmH5(T`G-;JqYBG{cK?u+K#r0 zXJzGxpw7#P-^K8HxwuLK8yZq3g=p^>@6Y#W#NsX7ArwDEp?V}S82X%o*MSz6u9 z0YqbD>fiu12nPl*nO`aMr3+M6w5KXa*jj-NFuV?y0q|bq3Ec!{XVjiQ!%^s7-ck@q zH9o+{;@L^Bd^||AI6*EC(6KG<|CA9R<)J7ruRqGgr;vO#!kle?;wSR}Pnm@#8?a^! zfL#riE~N*uc;HkK9D+Y7*>pI2xfG zCtX{=LI<{BfPEzpz5_s0%-TwC@Ni*oZHYX^iixvIzO%^kDj-&y0bEc~NjuKIv#W#U z9o5e3DlyR@Y1988Fw+$Q$CY0}T4IU1#5Fl3WpOLf@hXtT8!-DySFFvxfQTxj=ME~p z+9xOSmq)T#{)eISE1)HkqG=F0r8Irq_G!1}zfM5@02-8yYoe6>S4s4%n+TXJ)5^6T zoo3O)2g8%OhF39UQ&JP9m-m7Z4U_Rl-FL;#dS&6+?C>|^s;ma$=8T$tyD zMja7}Yb9;bxFIuX2g}BqQ0WfUh>$@fOMo&NDaN)8ljlOckSQ%CWrt+*&sxg7rLgr4 z{+9R{alcn)P^MK?VOHARG(kb3gD`-X#Rj>?Rv8^1{lkOiQd2`L!160rEMMLgnU1ap zj2-{IL;2a0qcqnwZA!WpIdn%ov=i|A{(~R_fWq(d7h}6wjO<_JqH>p~6onUENkexNOeKz>TFn_B37m&(1w` zfO~i(^S-6d-_jsR+UGwsi~(qfS*!V~@rT7(nGKrD02pO+k7V3ROMbV4$;3a~8z=AR3x`5Ug zvtFPlW|vuS<*FV`E8$sM5C3Mmn=FmS?+K26QVm(!PD^swUdR4$B?5S722fMpVX1V~sTkm4FWA1fnbYH6G4y#7pe8FuQ}19z!f4FRxP0IYz6 zEO9Ll?Dw){^PgRm0rLz$%p4CVIPsgB%fnVLBnBKgat0>0ty0%-pM0Y(BO35oj?Mb^GL1$|Ap1-PdF z3`ME1$n^Z7D11|VzFYhy)uHvWoHR2ol;i#X2pdVqv)B$D%rEwsvKFlD+)P^Q-AbyeKOX=b4Z!a^!)&~1$0QxafYFfkWL9K1J1wnzLf>xAw1wMqcw z+OIZ6=rTB-|9vZxfCC9EjKhl^9uD_pBySlj^)FAs?L#D04GQ}5lkQce$j+o9*6N7@ z8e9S<2nW)Wt*@J?0dR<o_GNtU@sg4O##|E!+8{BKC zOJl05zp{$KoDH)n=xl1&3my+Rq1BawfcLEpE&>RrHa`B*u6G3&<7>S}RW-;kK)YRe zrx<`PB*5Q^3#J90w&RD#Q}SCduL0_+*G$ukEno(~7nS-62!U0&7#K55;v4+;oFG_a ztA>=~Rb4;e;YJ{61jNQ%C3Mi>8q8qL$=?G3GZ>we%j0UHB(C3fCxNtd4R;;ZZXba3 zEI?E#b{dKNT{RgBh?kXS5PawUXp>z-3>^b`x&>6%2&x+dPg4uH7W;^R{xVw!$S2Ki z4Tp@>z!}sAi%j0M0PTeB{ta6~&sf`692zR^R@^5pp`)>U>~uGb+kUZna&;OhVWxD1 zr!})gUsW_KCo9bekG~3pc7PmDj^m-fQWCG@zJS^Jz6)_Ai#{JC&UH`2NZH}k{5_7| z7pd)t)tB3Ozs0Q@zzte`<%#zESTPAcMli!lAhpvj+KK0~Ib1|&K*So5qJgmSywYx6 zMVbP#TD#tvJDDLySNBeD25m>p5z79mSOUcXPPpU**nNtA>SK=)8X7Vk00C>WEw$EU9bM5L?kAbUy?!QmMP^4S3ZqDur0}c#x?O6jx{l7Y zKYB)tY1kH6Sq!Qtwpj4y`WglB3(&ZYNeJYLB+M}C0MUEG)RQ=z^-|B$L_7S>GDBl{ z?9>Q|@x6Kr-fB5hV`=nkVIQ|8i0NValgQbqs-lKZ1psHW7yu_qglm16h>LEv)Doc{ zNAB`QFl_jm)mPBkc#zv&vYnoPAl}B5uZ7Egrr>psUWr8vDoc_+f)Sq=zQ3C1g9|JB z>g|g%zzz8}zzYnr9Q?Y&!$81~Q$QqWSyXIv`gh7I^xXRqbbGpkx+c`|;=JM7y0scD z>DGe3cxAc4SZ;kI){+siYe})fG#Q|C9|64BJ{^E@Hfv83y_tAYezkTzLTd@S9@IVG zPA9IUokiVBILEKY%0OT0?Ce0&##Du*8$aIik%3tt-Vz(ZKXr{69RmXmfcmR|$(Jy* zK~}T$bBuFFYxpp@AoIBsv@9O20fz>UGiI~Pzy4HpY37C!rX6LB9U~q5MI1wH5k-e zbzSv7^SyJX4vdgG!gU<|oHT+weYrrfmbKc_my7MQkm24yRJ)frZaH8=tYaA4VAG}F zgp~MvC0yXA_3XDD(|$d`NT&G8kfZF1fW9gLMQ+qDGZ!FJz~Sn`~Lo3YeqP(0W~=fY3o9Nl_rA6xPT*e%Rj? z>Wh0HGJ8$|QRxC|9%WP8?tNEBNKEyNk@bu}@!VP~yQ9Xf=OM)R78GbYk+L?{_(Kmu z<5MB!t1tIK_30n;%H|D@|7~$@?j^M&;o?pnWrG2PAa`7KYnIlNPw4@s_~|0ktKGY) z`g6YbYFE5&(y~_6WMo@+)bNp}n@&+fDR*mz;2)s8;9F}msV`&@5picms)OKqnWe6B=z z8|6%$b$f}*>UYg;8I_B(n-mbAEr6&7v&=2i=t6^)zWWh?kVrHaId^@Yz4L4x{~9;! z2v?6t{G`-0S)#zuxO`>rwrXkvVuFyc2zPLiT>C}FiErgU{PodGj*gp_jyw_}35j5> z&yGd{SCqu`N9SK2^fycLu`&0FK1P43fE_ehSCzr~py_t8!IuN2~OXT4Q>}*NM+= z%Q|2lUtR90kM`^KFaOUjB!G$)fmf{}peU-Y0Cur}V6ke}dyl1;WoPn&N-8$DTn|HI z+q3z5KZMS!e05T8-c*p$CqArRlMojd_wGb8sEBR+1oU0M{GM-BKR?fWnQ8a;&T?R0 z2Z53R_4Z^pU>SSjz(qcJumyK7zkE0YG{R!EVawt6juQn|MNbOW`#ZY0lwIhA%3J`+ z0D(t(X_ZA9s4nKQdHVraT<@{^={FZx4Xu?vY^V&XVl*<^`9WbZ@!RWT1!sVBI)ai? zK$|XpI0KZ}3XCBjFj*fBRlQ=*-*dZb9xu%gefweIPGIQ{1Z!Wqot_KQ=XL9$GqApN zSz>xus!tMB^*eim;ur|t_?tt$5pWsmjkB+xLG7yoT6O{!ui*Z-;6$rkwlc<`cBk8+ z+wb?Bmal!=56W3UaH%Da=Xeh&)FuY4f9iY{;)rOtdOzUixmC+Ry>r3FdoYz>K&dD1 zG;pz?i%V60UERLx%N3N2HdPryEr~L5FrMl+eSLS?uZm|Y)vGJgl$4lCwr+`VNxAYh z3lf4odw>m}>7d5ss`x|3moL}++UdV?7O({YOo;PRdlDs+L$8+>L)3bl^t&pO^&8}h uiHWI_$w%H+KKf?E{*0gLu6&>5&;N{UwSpphXR&lK0D-5gpUXO@geCyO3xtXQ literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/terminal_straight_frenet.png b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/terminal_straight_frenet.png new file mode 100644 index 0000000000000000000000000000000000000000..9a36642b2d5451830d70974a84715c7f2d16f9f1 GIT binary patch literal 29125 zcmeFY_qG9Cwa;&)1 z;xuOXT2;GTQ{RM9J2q2MMB#Pa(SpaT(R#8t{P!GagLr5PpU~MAi!5Pe4 zlgGi>p>(q`uWzPMtKH2vT6sRq*E*#AujYySTe{(mX`e`OjM?Gi{t|3*qqiY@jkO<&W6 zQ`fT0f>$M0yF>)l&+LsTYI%eidwzJ-Sm`=_(0Yg?BqBPHc77833B9qMoB5ki*Ap8}=rs8gX^dh|nMDZ4bn4C{ML+t2 z1I-K8=%C{CelJUQo6oXxW>!cwt>?1DErVFR|Bxy+=3Kp2Sa{>n)mw8uQpvv)6F`^p zZ4&5z_t=++&*`m*S!dXX{tWBYJoDWdmoZebqcp@8NAB-V6{cz4BX;U;&`LkNFZbbF zkBlrCJAvy~|8T={r+gbvuE1cxjaLBXav!MegTh}VaY994h|q`T(sHLFl%gz8bn1B$ z-=hpgf<>SW@9HsqOpH-lap;_ZxlT=#0^${^8n<4ko?=&eh)s8UiVkM5jio z%PGk6^btq=WUPwJ=AG@=Vs0hGmNG7y9a)u{Ws;s@iy=PBdRHeZ3w#9r#k2YT`Hy6O z?PO6g+u;r3fmm#bL>ywrBibzE#E9*#D*wZ}5fwQty!VKyP0_R+-ODm|%iSTik2z*m zR#yGXtZ?EKRaaCo$M-%6`K(>kI!KgHE*U(|44zO!e+C$foOnED2{k#HUPnt-fn-ut z{&*uzP5iRt>mBl@prk%JIJb60*Z~nyYurQ>zM=U(wzt^gg_*U`ulLP8Ke-+0tqdqH zeAS*N@m@}=Y!|5c1fU5;QoRJOeE(ELWgdesa$=Mgb^F65YmslBgQC??bc6ANp*21Mvajl8g2WF_q!eq0d+o{**7_sG?%T3V3zLin^a+{k zl~ATj6q67ycWVl=0v9^H$K`(O&zhg>uf`u!|{3e$;0{`tO2^xqv4z& zjY6~-Yje4cKmmaqR-@%B0kOJ;gjFNopo*vldfgIlleg{?svxQPWBL{D2{kw~|A}u5 z^PVbT>U2)<+KBqjIIS9)m6FnL*drN+;OMXZ0jx$PrHhUi3CQM1RsE~od(mpta zU6N;GkJ)Gq`_K04!=6@@xV!^!9osS7zaCc}K3%S>OA+exePC863*Nn#PczE#iam^dwUK<bG2Opvx&OcUtuENz)uGF}M>mAtFPoXy5r$pnNrx~2rQ%f(dsN$qiL96|72AVE}ypP-OAvBH-4$D@0>*feJ1#y<04j>?=~H6>SCI5 z+g0a6AX8N8B_b3z<-0&st^`4FG zKJCcle4t-GV-i*vk`Z)>6(JXdO{BZrpD7g?PWk^hxXg#7%;dbC3$d>vv{<=G0ox*f zRuD67Fu##sUeYm?g4h+g%QKfUswf!W48@>*a_Hnc8Xb;`QW|+t14uA```X#$`tsOw z47E+W|Hm%3qh@G=0HpNDJ-1m;iDWI~o}j%ledsAmsO@b3RpM+PGJ zt53up8m=i-R#s{1$8fEF2LcTjvvi%NjX~@?fH9+!$a;Fs`yQ-o3>u41a_-aT>QK(4y_cMIKGq9G{lz)M(Yr+sjr&H~drdtMcr zT7uTtktp`0BnF^BPI-#GGYP4RN8ZmRN&K<)aw-muq5zV#h=m>j5NxB6L%H_@@P$cR)mg@ zQ4gwm6K6L=b(OBjPZd5>uD#|1%QNZ-j8*I$3T#y-jADxt$dMT{$6=)@x?rDgpFn-QELOOTu`amtQo+}v+&i@HuJ z#yF1eR{{f^t_Q#}RIF#qt(VHrq)M{I|Jn;bhah$eXhTf$8mr7pmUDl>i*IyDUFl$< z$I#=$e3w_%PgV%^oc}S{a_&1PHZf*Zvc1)CeV6>&J#O*|y^2<95datGxuX))mP|E_ zhoa+o4OenahLp)fU;D6!CELyXxnHI-T|zzmk7j|fwPrF$4_vZKwESdR^rE-iAGf6a z;%YzJx_D&go}Wu3)8XIHXM89aFb#{p}N?3M}WaN^VbGrK9Je?qHGJQz)&Kc^2)qNOJAxey9X>5?$@i#hp%A+Og#P0gFvy@n*fdNOL7tmcIWoc6G+b zWc?aIa1jqWWQ)Cr7k!H~zQ7FCB8^zTM&j6&;oX$KV0-jz(jtDdL37?F$k0z!$4`wc zVR7zLJp@iS(#K(m2~ASZ&n{Mf)AKeC^i~qYfGJ%G*@T%?X#P@9)*`0dctQCr9*e!{ zjb z*`jC!pf94kcPemnbHC)mkxSsY%~w0<|5DLA%gfpD6E*YtB#sgfB_~qTeQBUrWou?b zllG8`J!;V)%cE0n()VM9b{Kb0KetvjaU*Mw(OPN7jQs%KLAAmc>6S`4hbTE1LuL1^ zDTJ(5N1KZCz;_giUBsj`EXrFr_XV8A==dYQXunO1rlA4wfV}AMu{Il`%~^$M7{G7y zo-l@B!fKOREH!L6uu3sk4sG)7K}r$2lJp;I`Yd-dRHcqH)GttXrht$g&2KicxkHTh zilmh2=;(`2z3sr<+_2o?(Iwo6X%cF2Pr}UR+=B`&SAnkRN{uHMlUdDw$ZaKp2*sD_ z)^dh_^yNnW1kquN-m4l{%s}fO&G0L)-R3MLxWtm`7CJEIq_@5gvJ5G47v1V*cQGg+ zbJ4|;(U$J^?`>iy+{Q(z<9?h=LVZ|Dv_i6&6PcC zZHFYez-xyN?RA{^P@sMKbXDf=BD=7cf;49%V=R3w{vo@2hw$K(W27C@$ALM+W>7PzID4Av(~Ix zHiT~H04zcS9IG^lU}lB?pXDchWOsg%CLr%))mfDb_*^o8p1Y21mRp!FS5)pju!zB{JeW!wR;ut=AWbUlFIV&}v)8Jy(Mj_LhN;V^X*N zSU_YIZ|aSN6m9Af=Da84ka;451HW5rKSjNLc@?NeI4(oElkxD7jG1vL)b{)WIYsHs z(r1Z&8D%x_#xBZQo-lZDpY3R!Z>X|LQ&>`Nq6+ucC?u&!s)E;wp01q>XYf;!nQ{T} zUyO6~5fK74z1zUREutrP;L~#~6Qbm&R1tSQ{#i47FNZ8UQAw-CndvB{>neyGLq*g? zmcpb@VIh&+16@uxYnt_4(+lU3oU`ftp*dgPRUaiBTc$kz>r6B3(L%nv+M_ja7QD{^ z8fr!s$+Tf3;Y2g5<|A_eS`7wN)(PvJRyF1)q8aHnz+f${RZ5Xw*nTVLp`Rx+Q|%|%K`KA>EGXP0{yFOR;`JAY$uiGI7|L`vsB|d0H8-29d4{+;thYx;S}YvLGOGR`-1+H zxCv|tg{{;>m1be=cGsRW5sxIQm-STNzA$J#7jRtOG~pnaGY+;+2ecX`bv<@zLuWm) zuvld7B&&CD21=$xg=eN?-gSTA5S$T|iuY1-VkAXXOGwu{>r)fFn~7M=FXdY zp_nK(W@O^+X6A^X{mh}dUP$}lCPZfCgU+aSGYduZp!t-}Gc^a%5(CaWUZ6h<{)ejQ z3G#EH+HafcoxN41oEIl`K}PJlETo#*!9T0C06Sc2mvhGQ&9@{?>>umBM)xI9$Dad~ zAwo14&Lv@vd^n8!h7W6dkiD|mLtH%ksrhd1D(~|#6VdD621@BMuaHs0QNNVh@LV%# zWT!G>J($pBg5S-ooC&)`G?u8dl9K$5NKz)$5dpA@W^+)wiBc9F+x+N3F*TNgt@;lg zyC2;AT#gsJu+6sN>`{m>bV1VQLgXSqe2cM{0Faw#fj%5nbH`U%5s#4c1e&QKhw~6& z>Bj>Bn~KF(Xpw>Wb#RUbefb+h29my=U+gKFD-OW&fqyGiT&A>9|FIaCAQu zHCq9J=!KdtZ{1;~2PdR|7vlZNA|;pBeSu$Od(O3&PHej87a_y;Hez8TQya4D`zN|@ z$XH0@g|7dtqu#MnL%5M;-EVg|5IPI0)Q@bO#f|DOgpFY2z%YV#h*8qCU92CrjbQF% zfmQ43>jvS5Q_3Oqb3Y-MUt|c%7yEEqbLCS@NH6@#`E}M8RV)~$nT})2I1^Q6i!l6X z9=wwbod>Gk?gl}Tgyx^=*Jv~qWcRu*Jx9PRqM0?#;LIJ6K^vc_zs+X=Pw(Quv-cE5R9 zo_JrreR>;A-eqYd=tVrT_-T(d-JEK!8jY_-xZs7ntch&#RM8I~+;2HzaD%Zab#@V9 zr0F;>kwXJmt7@mnJj0~xN5czRw+jL{{oB=-Bpypv__XSETGP%}8 z9~Jjtl%2CB)p2GVeA+5iIycVghJh0lc$I{4w-_KbkRk#5#I9sF#3Lo*6;{)E6|^Q2 zlFcnRGd-b8hLFKI-zkiaR`ikXA(D8GLKET(*$NQ9n@aY*yULMOLaAj`X@PBU1m1@Z zi?rA#gj&#sLe6gn`QX0+>$~aDH5UvU%kY5Pqj1{20>cxgGt|IC^D1i#m+aHd8)_-v z?Pq%iS{IVz(RUn|hJo9gv={KQ`MX<~pPpv zYt7#v^S8e+K^>3J$7-w0&kwW?Ha{O}sB_jTLRo|I`&ivIO z&E#u&?OI_^8}!OSdqIUZSmBg=$ZdFm=y4JZe-+eX?d$kbznh(k zh~S>#B&mV*`vvkWcJM_sI3&7ZI&&0*9!k@Z2wsEH524?j)pXrq0L%LcPz0x;Y_t)9 zj|I%Pa2eX&($lV?G_HrwZ;}xE1`VGCe&PzU`()5C>1ey|++F&G?P73Pa&UAE;`_Mc zcssYf#^7`I=Oq+@60O``kxC6|h-dN1!Es=zD>Sw4M{zJHFwuX;%E=5!@G|5xSJ0n^ z@p)G9%RMC|etQe<72e>_y%w~trh&<{9p@;6M)`l=n7sBtm}y(uA`atlm=KMY8@h9( zh4~>=>DqaLTgnM4B;51c_~VYBd}8_a*Zhf>HTTg=$~|()ix)S^N#~s;;Pbt^X-50L zPzlSxtuFaHD$t|S_{TlJ-OlEWpy5N1JcQakTYY@jZ|5c;D;Km2HVMp5%bcug3qn{x zY=C4Bg!cZ8tEqT@gKOuwvRD3jFOg*MDMr~3)*l(V-=6o2gMv5QRZS(qAn_;CNfDQ2 zAE4R_>$kfE9D@Z57^gO_J4iI1 zDVlX0R=`p2FJCk1<;oqvB=;!$4D{`*?9rEC8A(aEb5K^U&v)j`9)2vc|~=;i#w zHHIAAHPIb#LzUa%ku)PBe&~LK6#Hv2)RZ*ad{FVY-ZR&bTdywY-sQ1< zq+0jGs{-1y(RP}>fpZMs$2)RCiAS*;+TA)a+Ks6r#_qe$8u#FPY^0#OSBb(~I0O>C zs~E1k6PKk+r!S~h`kPIIGNc0c!1hB#==}jCSYD!_SK+KSEFg| z+{MQ6>Gm9|yzjv-?d7uC15ZP`(~GqpXjYB(?W|f*3RlohL&wE(-sZfVFvM+==Og9D z_`v(eKdq-{L#5aM{9SbtbFrT1c67h4hP zK>*Ic>C+#o@gGA^2U*R3k+v{^z|Hd%d9BkkLkJA|HuXKV&D=!vVW=GMbpDY$$Cv;> zA~s|msFclgwToRelrlr9zL0^sc12dASUoHMH;4Ve^im=!Pq^{KyVLU>QAvELxs;jfM>yA~vY*taCL+U|o9_6yiQXMt zUP-i|z;q}RR}*Et?KGCD2$U1l1|yPFTzr4XQHaqJbVSGn3Wz3wsCi#aXO~T0?o@!! z$Z6peJ_)qDuTQPXOjq>+-Ju1BFF3C+OS!}+b{7YumeTzbnN8uyrzWEP2q$bdb}X4DmbO!1?+@-Y7fIqD#lTh5zlOsSy_8 z*QM{5SBK!{QdLn%i!k52R>W5`>-n1Z8+Gm9g{Z_s4z6!lK8|C6VW?4v0IdwEnumt_%K(<)up)a5$8S5`#s0J&>lJ4`@6Y|rB)w5*w%|J z&*S~TLeze03YzW2%Ti%Jzq-yUKoY3qlC`utcYEZ|)*!yp z;k!3p-To`%Jt82s2$3QO=kDLA?@(U%fnBKWj2xhe8nwjbaJ^1=C=TS%>R z1AH0F!}#X7XeN;4hrrH0S-+;jOfsu?Q9S6~jSnB}KT8z9qmlF$dfMT7dU(E^*(V+f z;ZbKNx|JMT&Z?OQ*$28s1Om6=GrQiH82T}u)-Ks>fN8chJ`t&YqpGQMqwJCa`!HK) z7!cuxx|1Cf49)9fHNhA0M=vRuX!p*lhSkeJn_az0$K*+3JVLAZ4P^Y=F~TY%%hWiX z-|>$Yl~S2r_ENq*&{Q=QSwG2Ya-+ddN=n0#?z*Z2pD)Vi>$&HnW4}hkxTih&&k+ta zTgaq!*}(s8PrI3I7yF7_Q90eVtopW+$2DK7)8SUYkb_S*?-Y|E55T{LX~{lU-A%bI z$AQ;FrW3ewn=_%EIqJkuMXLOk!6lXP;BMCWZ`@zKF72jybP5@ym6+cBJ<@2CG&Am_Kv&`SczJEfyz+O57LG}{tR zKyhwWYD;rS%%gU>`!_}=RoxqP155$3i?6>3M(&U^A*ESW8M+as4YRxuTP9&Y7MRjf z1KENv@G}7bQAnyGnPZ<#DAW#5yjd{Z{1{R&u>P=8;|4A;RG5nJ;mo&g6PIUjm`Y%f zyN@DUhih%5Ew0LS-0O*3VmbFzg>M^W<$R;q%c{`U!OQ-6eGsS3iesMiCJFHXXiBz* z48J|rMXENaYs{CMF#^Dq?(*d~V8`k;;Q&Wft%R)>hN2ah97pHwwvpE_#dzn4qgtKJ zBWKKKZXD$eDw2WHJVYt!{sp3&HYGidKGV?V_G^E$vNI+Bp~p~-F8BguVOeUR+wVU4 zwja_hBjK=R@R0o&ZF;+mI2zjb9+>T=Q%eG$s>p8>Y2ieCjuEdOZmDtPVzwy4w1xDw za~XvpIv-1_21VU8q&1!2J|3Lj^~tE6{incFx(eu)X*B`+TO!l8TO zg?TRCxziVnmFH*gN#ER2s@!)_7o0Y@`f~ZG8o5A6E;6*m@aCy-U$a%LWxJ2hz}dTD zc~X0k0M{CklVU9;AvUiQhi7U^O-k;Q=2e5)>9Yo{W+bLtQx8K}3JhV7iO!(B!fT9< z=k$6^Vmb}KKS^Vr50Tq`&U>egsN;0%=ead#n6Kdi42(Fg}JOLd-+t+!pUY6W3!Ak)lIBqh;~ug%k@COubBdS(@bP{$t0)GwXvSQ!@7tvm zN%o*Nuc~p5pAU!lXAP}rprCH_h~9YQJ{n1x*Jp+f!FoB8c-;DNhX~RPGK)Fq+!vyI z_Ubt4T$9e#`Q?kLiS{n3DdECt*ILKWKJ?39l6uqcoL?)G15L1)NPCy z%6N%x3s-a*vTq{P3fYF@?r@!*H3&J&@-^RKY3m)LHbVQO1zI}`P<(eOeO6*c3t~!jRaA@{CO`0)GiM|IvS`S zI)LSDP?ykHGMDG#fj#bT;>CsiapYI&GD|0$bqR4FKB=vqb9cjkG2b2AJ|<*okt^6b zQiRl{4qIWE0#;7*Mc&^npaz=l=yXY*yZd~z~n$cvgKQ*qsf*SE@x1{W3$_1L)$j(euWCp`9X zlS*Bm8Zd3NrFhnuuShBnk5gPrigD zsbd3xjFGKC{zSja&db1^uJ+cDBhKJ^LD?!3ts%;!1l$WpP;i3nnnZv1(Us91sJdX1rqmQbwCu(cb@V*;OCH*mh0zMu$$$;|Ao^Z<(l1%h4P+WJo zF{#zZE&-Obnsq$ie28vep$`mmNYrnvuN1?@A+en1ALNUgDZafU^oPy&t0*8s(5tYV zGSLF^zfN-XaO{H3&WGKNbb95~98EXhlfd5-YR|MVrtPrLkH}m4>mGS%Xxs8^OLKhZ zJOZyUyFE`!@Ak_O>6kMV;3(X8mfJh$2=vEQh|6*`W6jfjDEWkGS52)^2j zhc^y)_m~EqO}7{f3@&0N)UEIY15E?qzj{;1Q$IV7{2f=whp%oFGRZb zeFlt3&Tx*7!S41K9NDwezMHARR_GVKGzksDJvd6jbZ1a&+kv-rz+r-+S|-LTs0JO( z8q~x(9_CM^dFFtAdPEJOg7`uD>?H$-!vpQsjTx_F3}(K5VLM}^h2u6PvLXt^Mr&iN zXv6nzezfFzQ|FSJh7JT^5n2yPitu&Q9(*#p0ToJj*$oUt>YmV$mI&C0r|>grGU zdwOOYDnXx-OE z3sxgQ6?i;Y`UjkOyO4JZ>3+Zo36F0exy=Xn7Ifz3wD#!+-#eQ~!0>${0x}11sFVZ{ z)u*nDLgw?zT@t9|&uBzih)5$5NqXnvj+&`&Hf{HV;_yKj)pb=SXtU|OU)+BecwV3m_ADUMt z)}P>}oA4QH?kN9;-elE$Gcz+go)w;`OI^0VotK$vilaKY}q3aE)XuuB_v&F@~Vusr}d#oBkzYK0lE{XW0y6K425Ie zpu|qHq}*T+pDybWRodL5puic3# z&tmYedR33u;o=bK2AHFP8RmTe+C4uHQp2lQW*jQHUKy(cL{jC#$6PxK;v0<>Lq|`1 zG(#T!`-%aOYYEQ6GbQgT0H5w{IHYT$Z1jl0t5F{UHhCawXyiQ=b7O0zvnuBuQ&a2i z#j#yu^hydjU#)R-vXV--$y02YOjhe0`e>bW$w$I=6XLNY9&)zQ?00^Y^KuwYz7E6w zo0|mOtp8N6OSYlDteOuV|2u(-Tu6x};R#`t4-M zMkC2ZG*$)f>_5(z^CCp+&JLn$zQq2-~Hvs$ols4*;*_bsE zI>oQOd+c|2nBy1alF`Y%#Ytfy$5PEx%lyuovQ65lzdS|OROE%XrSF+E#f@u^MO{1n z!K>!&w^_JTOsr1=uEK>Lwr+lxCL`E+Q!?l(N$r>0P27JxQ(+4=Zusy5rBId^jLG&Q@0JDgFePEuTMT| z*v3}@EP6=q^?)Asaf3HO7%c_@?cJW%>f3I+M|C-dN3-akOYFre4%o<8h~NHc1Od8= zv(;FZDI9V6({8SekSG;~KN^0rQi!3TNJdWER&-9%I_;1N@<-@o{oP6oQ0efC%kr?F zj_Ke>D~Z2|$dKBe|MkAEd;ENeJ=qwJjI>S_80Lzx*e4UT4i7ocf6Q~iN3iGoKeHlQ z%zEJwHl)YdwT^5F1W9M}A$w9=e@iB?a4E}@)JW072N`j!nT(-`CAPr}u<3c?7(eYDB!A9OCv6+H&v{v?JE_K;sco8kX zrEk7wMOsw16@9Ec`HFRUt?1|)Wm6b>`mDtY5+qdL{yq6$v;4nax!&p^wUjp%=&ncp z13dAW*?Q33i~QijVrQDgo2&|Ji2+IXQ-*{qyo{P`*8!pl;jM)Q4eY&AJ%szipY1wR6tpgdKlD!TlMNePg)MSMg+PzeSMlgNvXZe{ zPmRc8OFg|Tk5SjVA5wGzep8xK_Ffq?0(FDbm$TRbH_5+O&X`FTg|CVJb{tb&v=9wP zJd3oc7=|tHq3M&GuKSx&FF~Hu`bEVo)2F@D^L-dC{uue~ zacS42ZvGupej^1gqAuzadV^~s_v3Q3t99=-skkn- z%7ic7yWXYq@ZHwdY<|&Bvg^eGdo+PF@G^q{xwag@@Dk&l0A%-)WARIgXiM zPMY^i++IiQyrtbgMlCXrXyuNU=)C_jQQQk;Lt6}~K(oXiv|{@|=Wu$45U_`gv6|tv zNg{rxZqTkWq-HM?sWSD4e~5@%(PCV(Zb}K3a#LUbD0b)sNxS~hAhed8xh`Gw#tu1C zn)F7iX7&RC?&ir-PLLYdj?f6k|gEe{O=YLaGmOFWU?QW== z*COkydHL@5vODPQH@Am2`pMk2Y^BkZxI=nNL|?;6n_ZCRG+59FijWwu*#i~FyzV{T zw`gwvEK`8blaC5xfT! zBJ}AGXXrRUe^eh-|IhCk(OfPi`n?N1rVy+dOsTAzW)MilVPNj}y42gUj|M_W@!M#Y z%3|<~x{pR_2Z6;B5+2o>LnTpkQfMWY0sN&l=NTXUI3!^E9N|S6_e=Ul@Rab|b*bh9 zVbVB-=E`|_+@5^k!PK9>#=awmxNB99hjK_FWLdi$Qdu!Ap5By)7q$!cIH z)d!knmf%A)a{;m%$_JXn+h-oV4$(;U8;5gRJ1F`9 zrA{cJqd2^&VB^57|8K*^$yr?u5*Y z3d+PV;T#JdVTd)`_2TPcC+%Pn$cMBDVFh>l!%hU1_*Jg0XfT_sf-LngTNE*BQPq=R z@79NLixCoLHYgrp6;J1H5&6R3de@DOlgHO>R%Yzv>g6*CR;dl(7|EKC!EJIg<8^Y^ z>9(K#owj9@w2RwAd7GwbEb;4aHfatOuPST0lZ8#hqhC{PQ5)svjVG--<@s2iUD89C zIC-=@7QD)zyvq|KEXs+~s(u6>6zSxVBF?SF#eYn^*q^u}hiOIb?QO$+lKIWSBnVwH zXgDylVU;veni0PT^1oJ~w$I+G)q~KfG~}ytI!8-SifBT5M79`Ts}N5izSf+Y3mL$Q zj)MX+GV7s5Ny4i2!Rl`bUAm?m_pjOqe0Rjt-b+qyQeXMS!x9u?6CGBKyGlk^~T*jzBe2k8r*c8UDjp`C&g}4IC5x^)@50vg>f@t_TL0&WL^nOy%F>O z@`G(n4i*K>%PVjN69QV71Ol`3ocRiXC_IbU*`h26W>r1kKPG9ANzz@>@46`y3Uo(R zXG2y!X4AM&bfA8b7#?601175YI+(SSTYtj}cY?9EF)T?qX}Lh2czD2GajKjW2VH3g zhO;Q#IcV=4N}D>iJF;6J-+DNag2L|Cm-Nfd5BH-2<@j*ktT9zqeoIEhGaD+rp^^)F zt-G`AzUtQu^f~mc!Re;iC1?-NC=;2wK+p1Uo|{vpFtR8~dH15t#AYE_c-2C^#YOJY zRXWz?g7OE6E*A|)E)|i62t^$issHoq_J2z1`r2cpc{(DJfH1N*0#5Bh(^LCF6F&gu zrqdj%SWZPsB^YgyEPx*+yf(8&i%UTpcQk^H3p46xm;6QvN-v|n@SlC3Ek|PrKjyA9 zsrda}AO~n$Mw7x zQOD~gyn-K>#>LGEEe?6!QEb8R!3Kfgt;Vog1fS7WWt#nu$7Bj4mImqOx0nUtgKN=% zA-OUVfFEbh1(1=&e3d7cwr7~v*DhBi&hGty)>an}xIp zxL(z#{v+gPpkXT7^8__9OdfSJ1+0bCZ=iwqMJ7$g z)0ZDQzI0?VKq8CW6~zq;7Ic52d?Ag(32&LvaGr}bR-`{Fl+(pJ z^Uc6@Mgb1IyATIVTfezV+Yx8tQrlu5xD=pS3Ze4jqN8R%Klza6SBi7k$d1>1w0k6O zzf|NT^dCXc5OLdggbXl2v2A!US!mwyv)G33n~5votz@-1CJHUM`yMU_ZYa{w!OLhW z@7t1-{R}p*(;w8$l}0JT*Zh#fb7z!f1RU$*!oA~`&lW|HWu!S7V=YtPFuBN5fGwtu z9_HSW4)aeB#@{fi#BSX#vF0P`lvVPs^(n>I=sUU#R#@O9AgD9o$n+geb^Nfk{^gP;{x%7Dos-zKEfz2z*n8zn9F>?tyJVHQP%MGl-*YK3RW@#UK{bTx>3lTo zV@rE<@0%Zg>VMmmiPg)_J4PQw+u!tI+(hFyzKCyE@}VE%YRgX*%Sh^}{OChJv@-rK zbF03h#eU{hQt!5U5^r)J!K=|+M($pQX|#0^UM`&$mVlHNwoRrlN-NuIoA5fbwVOpX z>@Osrtt%?)b*=erKvb3~NKSqYmO^`qi@5!t7TG*XN_goNzDs0xlGi^h1CIl2D2hnz zrK8@zAq}H53-mxK<;ZUR^lptHU5C>|0dgv0tvFd)&?BxHbyjG@XN9kuvQx zSe84(lBk8I>?1b#l3RsOYn8;^EsdpCMR|Ilo_*@vYR}=*&5G!VpqR94CCRe;hqS(W zcIvUACMWj(@yPc{_7-SndiZj}J&IWiO)_sRQk!Hp7G(Q*=Ja2-a#yd$5%Rp;YM3>1 zzF9$ITTW)fgd2Uf2BJr$l$rf>y#aAqh};IhUAp=}DQUl6yd1aLdgAoS+G0<@$0tb2 z^@a83IlLp^>cyiR!T-1bKL=N;Wa1gJaRPO+lX4sXz2y3404-E@qm-` zt2I!NUA51$(?(V+t0mKhGI+p!sj!8QPgzBcq;8rJZ6QhJ0#3@qEX_#z>L?;6idwol zlH6AoHOEYJVrGG&tf&7Zh8RDR@44q~i(t`kDNiZ8|1^D*X7Ud|Z_fMoHDEuVEM{pJ?c z#*oCT-*19N6E_1sVFlZ;e6{tD5VN4@>a}{6^qeOvMs1rZ)${!_*5J1Yu~$EQyrl^V zV`X`nv+(i)_gKH-_5+=B^Rc`wy3`2K^qjNYh6w^SM@jik_!oV@kHrzI6=5EInwh~} zT_u9|fSPfC=Z+PjV6L=szcw7S*4N>bOAz=pZB1qwuQ}+GZ7%Zoz3Wl;NFXHZJT|7t2!$+MH9;*XnG{MfmYZx~0a>@s zoxlvNE;S3*B$7lzAbOJdZx_m<6~yH#iLCgSdQ8=a7SR??)Oz5ol*<7N9)F9MPAg53 z0B3vr{9tlhN9K~^jS3n>E_|Rei^!l})z2X)+hxdnyz}dhl)#~IH0g@98ZIjWX|uaTHT9EwmoHeO+W2}qpa~6$H#Ap zA6v_x(=C<=xXNsnx;$zNF89RCQP9(wC%yBi{KI1zya)6)i8MI*hE~^yr@*VELZ9fY zpY^%~9nBmAHJX&B#MP`(M7hM4SKAf8=uF{`)0_{Dj3O#i#7Z}YhZxP|Q>=onaGVk) z8};N>=4Bwt@W4q7p`!dbiD2~$bI+iJvMxqng}(4rHb2(lI7MT@vbW0R{|RR*4&nX$ zE$|K8o@ak>`Nm)2y(MoKF6ecVs@++EAmMLJsC*4ydFuTFdbPu~3Jl?y4mRN`BUHZC z%1VxpG%^W%4|x;Y4CfrA)$IfR>?E}EezJJxNHY-jtIv`%+t~`gp5sqJKW^HEgsQT! z*}zZn)5BcBC5%_VP0nvAle`$LiEo1jic-E9aG+qOiwMSp~$k4lIv8$6l>xh zQ26DPNdNEU9LHQ9eTr`{{JIHV#G(!DTu3p6C2frn7mM=+-%UUW2EoX`(wg>N55F;F z?HK#yPTG;K6JR#J@0~{bq0O#yyh||7@mrggr>yZ?FU5BUWgW&kTdAY6pb>gaWtMm5 zqvjSY>+?QO2KK|Lb48#a?c%fe$h0T9v?rWxgUkm<4+gtg)0HX}hSqP~jyvKv4QXCf zO57BN!KLtr0EYL?uspxSdqe*3R9;4MTI9W-g6i;;8B>*CZzn`}3Jf>WbuTF)g!7wS zTL2w<_;1R1Pa2GT(_nijfkwpgZDkZ}0n2&cY%@-<5cmHy_0?ffeb2*4NK2;(xO7Q( zEFefoDBYdXqI4)qmxwGSUDDkp-7Fy`uyl7W&3hL=zvunl=h=Vuo|ro`=S-eCXf{Kn zsmck|pUsz(C;Q`l703U-IGm`N`>vRtjtQ>Xr%6W)BLdL8H%Y)BS<_y+TE_!I^K&iO zYNo8nNNVP2RW`FkVQzAQD(Bl(h(cxG9TkU7JD#2zLP@tolr^c4z9cHT0f=u|{iL7R zMCS)>Y*CD;XQGC}hS^{7T(_C6&%&V}uNG*MG#XIA&HUF1 zhxi-d(y0;wNCd)V6y55F4deB$2b+Jx>?Mv;sLqd0s7g{pskmGs|8+2}XB~|*;f;Yk zy`lQY8-pYs0~rbQ@}BT|395DLvkwu^*_&$pxOM%y896)T4-ljxh+*UfQ+;Xwq_mXq z=R5Efg=`H~gv8&9rF*nnzFjVUfm=G_`K6Vh(-bUx$~I+ap<0!wNxia~fLh1Z8Rz(A z9XsA>1V(B6`h#Bz+l>u&r8zh_(3>caSb-L~3E?tK-x(nZoV)$;q^}%q(K{e0NNSE^wRyAVC8aY}8TM@Oj|a!5<^#Z%&&gx|L-oNw>V zm48{dnNZcfsq4}(zftqm#x<0MM`1k%2)YjJj|4GP<~CM+VSw|Azf|urIvUZ%+Th?_ zJd;hdr2V<}kMo&(D}x9YC)t%P?o2i>gTk#pCnE+T8}l_nfofwRjEqdcA}x5DOkN7d z-`>CJ?efCQSZWge&;Wb+O9+6w!peSDXZHPN*C|{;mEzW{p}3^}cc!nyy?Ul(238oV zndH$xR+#*dh6u*y?&hz4mvGxNOutGc*g)bNCU8uz@6BSq9L7C;MJEgddaXap3*q7K z@AS;kGi{&Wq}(fo%owu{9LdZQi3!XyEy6h5$8M$K62e22@Bx4d%&KHtOLBf<=K?@7 zJj*#^RgTDS^0Qp&YrlTAfgJY!8ge@(o)`o-Ct7K`cy%JEPD&8dZMookQcNPgsK_`A z0;w5)BR53;H)EVMis$s zl2=JNKf#40Q+-p?T;z0{iF<65Brg)2Lx1!q=#e|Fp_|QgUwxA1j$vgL=G$?WUubUL z8M& zwAHZ-&fr-X3m6|I(5!-|3z_>3GozX+QRkM$R!eA?AB+=YtU`d}{l`yi;Z8;lWw~#Z zWwJe|^^7?|Xm>P=;b+uedw*J%O6Dta>!JackKI(kmugw*YBgeP7-^*rt@gPvS$>56 znF|SWi6R$yAsnBT@jf~(a`0g6AbjG_uh!_orRIA?OkfzNEvJ(27gY zkY>ry!FP3rpIe?!jVU0)0!a^5nCu`BWkvq{G(;Rk-W)iZ1k_NG8(_@&3xEdv^#@T@ zL04mWTWHCNzeiJFra&3-Qi~|;a{xDDlrF?_BG7#fXncCi)p@`i8XSzk?y2?wKn#|i z{fvblbFO8q8s_UjGf9Ql%#}SrKLT6JhYAhv(rJmuD-`lG?GrTn2^Bw?ghvv%^G3g| zP6**kAK7s@qYen+L&!D|=wl`@h+PhQ2C8N_0GhnrL)ob@N#YO%ady(Mw&e-4^xSKZ znt0zcB1E?;{D*G1j^z?&cQDvsF*0|4rrH;7<|1;GK;SqTXp9_?3;-T( znu>NpQqSn;`Cc`nk6Va< zxZR3odmGO8NyK60_KzE{rssGid)*-ZNQa|#jw{+uP4Nqt-TtdLtD9lNY-2_LK3Eor zAXFtOqFKBVqaV08kV@?Rd+g3B-tKPXhXX#ea~q!DsU2Gw{bI{p@S_@0aVaE3BMu=* z*cfQPEI+4UX1240*b=(5%lyQTO7!$KTrg*hGhvKlo-P%q>L|BoBpgo&lG0}mGqx}t}T~~3~Dhb)iR$>yee=x@>91!0Hl1TA3n05mo!qk28=#hfp z$yKm@a*4d?cs^=u=oZ>Wcu;#)VCHnLtfV9;rC&U)#n z=r=et_vpJ(dD*U#a$G(TW~DGAS=Z@ojPgBx;7>Kz0gmKTfsd267NCi@@8ln|VfRa# z>e9KeBSyOD@~w5AuW3H*7AfZl553@vZapJh@Ht}oNg;|S=`V+8T(=TyAW)Zb4-Y*U zn}T(T$1n8Oz@$Jb30WJeN7_({UbMiuySnKhyyFg6^ld09W^t6;1 z&iT!Mob%|5E3!N2J~K!a_WI`3a)=)s6t#w2Hf;0M-Ovq%X2zWjC8fDjnn0~&U}QSw#LJ%`T3nap;sT;Ss!q>m{qsopq`4SH?%&u^b;Aoev7 zZYC{$axtlTU_y~BpwgySmEk~2*@3D(aRiTj1jeR#VtG2arYCDZFEs9`@9MTjZbY{Z zcLb;Q2ym3Zd{|nKV0h(O{zMO(Q>r2%>Z8|Lpqm=Gs4$DC?z|$Du8-bluLJ*7pa_D|4*H?=P2H*AEXHU8BqGCH$v) z9(in^X_s*%zpk}kA}guG#JE_IyN4`=0+X()Px*hk--=Q_yh_XxJMDH=V$7YH6aTF& zTC$wBa7)n?+|mt&2_s2g`YEpHE!54?Sh7^0+_)K5!^`hR-TPH{=WpX>%B;lj zwR>xDyeifDQLPbZuYPxTq0^zUbWL0zet5lbXATo~uh`uf#X~lL(wPO(%}TO=jPm^LjlZhIZx5d&BD#+7C@@$^;Tye5 z0LyX#mYtfHI0-^j%A=^8`^My~1#9Fy)*8@+v@L(8V1Jer#~Z~SOfLSRTIpkegWm45 zx#1S&MvucY>x=Q8maeY+!72XfnVz)!ZW`y4VP6ExpfD|fFpzJ4Tc>9Q6Vbi&Svxv7 zyqd`ZoQw{-A6}Wy)!iyO&bct4L#a%CtvP8Lwn?x4HeAH^+(Bqs&ObONt~8uGwtP6S z_B@CxtTTsxyx9xKixi};=R`wumI_#{v*3LoYO8meF^PVJ5 zX=&JBYtEk>?}t_bCIU5mjG`&|<9J6{`|oCP1L3;Zd2xM;RPv14;&8l!#y}a7zSip{ zZP%Wtpmratd-O{h$6N9#$N7!{COqE97ZwFw=S2(M#uC?bcgHg{-{teTaKBu0rY`w6 z-4X%3q3CztQ?%=9(+_AiY8Kz}2O}6EiyGmN= zE?>Ltuk1Gq9&RqBovfw##a6D6eNw_d+Y$5)fzBTj_+3M;FO6GIm@L83j~*Ec$OWhoegtdK6ZXs+d``(%tSeCFM@l(lur>pI+ z?s7pFl}s%ig?X?(G-ITfL}Z>jbC?2d@XBT<6m*rAxJD=!PO9(~t5b?-j6P`7i<*-f z+&Ls#YL%Xa{wZZgpxnK~?MbR|d-y?%?#P1O2de<|Ct}^tyh~QLhvJV@;;Fk*v{|Zt z?$qvC0$k3B^Tt)c<=fmmMSdajRvi-ZTrEs#D zX3MAXUj@0_QSlGIY^2fJHr6j<)21rEziFp;j}Vu1<3#o4O+LpQMj|c=fQGXkWt&J!Q+LD2NW?34 zJ_&VgBLL+0@^z_18&hd(@~oTjYki^q4?ISbCkaEpKyD$x>h5^W1fySjahEzfQXQ3Y zo9t=6Ngg~*J+QZPDS?nLG|lS*HK#?KSJSO&#e@S%DqX@K&dI$eowArF-@@u%r>}h| zwk&Q+ebBM98GysQ*GI#)*fr>eiSEuJ%+J%Yr+=PPU@9X!iwM-G z|7CX{)YQt*lm_-{kE>_Hs!{LH)?Z)Falpq(9H9K}3lpsrpUR%Gddz*`8J;-`um8kk z2jY(WEY;gDCg;0nSWmkPY({UF^V`?Y=gXhij|04|(22>dX=PJcZ!PYS!7MkN);`ck zXo`;t$hIUvvT}M12Ih0WP>CS3KM{-8_}j(9q2wySoXqEOmm@e`Y5BC(d!=+_lC+INU@%VFRobg^C=&nv}Xw}C1)Aq#n@(XIG zC#?fAW-ny;alZ^at|h>ht%LW&UFIj7(W1F=znnY&ICqY~HQdpvIwhc8$`ulKbDWvV zpd-u@oa`H4DdnN&w6{r<&-1ukUCLaVnjRzu_!b-T(yImff%UU((zMmbyc<20DLuW* z|D-3!Yv9bqS*?w;K(Z6LEsZ(5u)k}@H-!bIb@5q2QqycvBKn`XWqA|tHEqyV!pMyM zYIMqKrhTQR`*HsAVElc?-mzMMD|%V{RH8E~6?ZWEdxTOnkt)-XFIYQ=&$wTi%#d(n zqeL;`Qf&Eah>$6uMiw`Jk!5Q%5_1X3A|nmb$g#nb19Z21i=S%OO=N{(Siq*WTF{xf z#6{zOpRzk!9}Y;@`trAg`Sc|lWE^EC8&v_FY8&=Jz2A%^U189&}U_d~BNx({8 z?8WC+6K}4A>)h3&@3igxcghBZ16z8Ug-xk5;NK7CVhq1rMuL2-0*T7LH`EfA+>A3^ zs6x(pzL|N;ugBBBfOWg{su81s?jq{*0!>%AI|;SFAu$fd-pO9}DIK{&|BgC)#&k~j-+Qe4z8zi@M6bJl&6d_fLK7)kj=vo6@Cbk2X}FO39T&fAv3T43Ve}Pv{^wu5_`mFARF;=g zpB|A1)h|j6@Nus*NR@1G^YFH5r(URxhSe0g#^%6#lAzc(nM)c`=7fM##gx~zOR)!J zDF>0Khm+zE5|eJ+&|V*4{R@BFsDU(M2<;z z(vCCkOQb|^Ri@7M-YWqp#IcTtspHAam6QP5YOuFC=;BclYs$=^ksNu(2z+XUQu?xG zdrta5r&Bn-%&wBGfi^}fxSwC!Kt-Rgdn(oY>r^h3ko?i$6W)0%g3zy+AX3BTTU1DF z;UjEW^E&Tqtl_{F$Jkke~lcZ$`d|X@L9aGZ|etW%aeu zGd`=_B-Z~P%v|Z@vqGmEt$>9#wI8C_pw@DC5^Moa{ym^;fj;JvE zClDaXI(Mt5YjOOhPObtUu_-HsHM@i+zR%vQ4@*3*qw!4}rjzLf!%IEgHW*V>yVamAtJPD!_CS|`!%LD(^*p+o*D@dFp(3y(+L9#|(nKjlqK zkvCLv%zq~L1?n3*?Cow*X0!bbiaF$Z^_?6xce2c7Y!KX=ryfvzS=F(Pp5l%gZ;FeZ$3v+ z-*xodu|TQBd$rSUjAo!&^Xq0fj3y&JBD~cmH&*so9e7-f>N-6=iF{C37qcH6Zi2pK zOYMgSB<6Bek^1Oxt8*GvlV>zN+fF?pdC!+kQxn_!XBV(!xdiEXGIlq2@18Nfn(M;& zEy5ql|F%hSj6Upb#t6OC_mha>v+$(h)GWTU&6z0?R&|1SU);~R2iKb0@DzYJA%o^P zLnhReZDM=@x4XJOgQHi(e5iI#W%j}51xN9yAywZ|6;yaScc_YAJ0;18j4%4AyMqDQ z%wRA2)ghQoaDNqH^C83_5@6MtC$6dXz(m{w;$gnAk%l`LgLlRzu27_m8CUy*+1~j5 zTlVAzbS<&Fyr`!3(3t0r({92vt>;ewlRJdSOn>3Agy;PHY4t}J7uNBPB7+V(y1EwV zU9&d+dn&5g+{We<(bDErHqM#8%~kpsn~>2F)D7}JBQApIu@arjm8moa`{25R{$y9^ z>rPD9d;VIN%b?d-=O2Be0qrWt^!L0s+_fil=Y6TBu|C=Ta;kqPf3iE-fs{5{o*dN0 z;{sLNspZGh8epA9BcxHs=#Rgl01%~afIt!z~(58u6fv?hHXmt$QK{ge*2eo2pVOpSAzq$A^&TU(oeRJ)Lm1Pi?x*ihN($@W zkE_5W+-Ix7D3puwa+%3*MrH4m$2Nq%yUF-Xg+Eqem zTJLc1TJDre2>gYq#ScO84zt7aQ+w7uL6H&4%A-^BT^gWafA1@FgH~5g!Gne*)rA}E zCR4EC`4NrS1s`CnSRw3SZa1-;TF`rQfFdY>;GT)Q9ELVhD-(1l-?@I~~sg zR!QsS;f9dk5{`PGkm!}*D246HC}6idh2Gcgx)gN+Hi4MWrss=i)9qyY7xaJ<`6`I% z)%0jTw$*}9BqfWu6X~oaH?kKq=VLD zUWDtTkkXw^^Kr3eP{!a^|44mU=D$1 z!YyLKy}Iweh?eG7F&3^aJH(F82kKgS);JB?*PgnSl~+as%9fc$$dn3=saQ*y=WXw) z5V}fpS6|H1T+Ip@^q9u~W}*Ie`s40`pD^H}p&w)M`*3JW?RkP`QuubcvkB3&4{{*yOiPZVNRW`2lc1(5n~kR|gds zR}!Z-_tcp#PiTD8;Cr)js_vpJY(rowzo1~42gICg*!kTtl^^~HMI-^Ybj0H ztkESYtqz@za>jaQ*!+_QW^TUPBZE@(eHU||+i8>ITjLhMreeEhmpn5Bw6`$4VA z4qXj4OK12orpKpSSX4Oav~fNFk8ip^0ZzlYGA$S!U2flA<%q}I)$W@D_9Ea%1ib8B zT#FTLdvky>7iB0kG%jakIQo5rbMC0`JNy}?IJEYOnBL^k?eDzW;@C#`zP0te6}9M% z>#%av7IQsp$CsCz) zK*Ftl`&J}O;|n4t1jKH&RjSF;O_bjCqF4#FZ+YQmGc1NcUYECs64h)l)v_ z!VLI?aP0Ms0>0&Q0@rr(pf)AewvkTRAjTKVUa(_y*5&)FBV$O@!Oi2-9LiMkrAAJ0 z|4Gl2v1fazQ*NS|v45Yh+W{#cMInv|{rkgfTDuIu;RXYnMuM2mo=zDQUITgG~zQWqUvL|=Yt7B5L3aS#r=4j z8xd@ZlznhTglK5wi+4-5C4{gS?|pD;4yFZh0M!8zGW*Y_F;*V{h+fPC zItg^uA%)Z^XcoX2#WMe9>lMpEwMhR4*`aajnvggkIiAD{XawX&Ai{GY zMckKCy7eShWo7+1#6LqrJ(_|e20IK5HnXxCY*X(rppnioZJd!5(wp>eA<4*48kN7Re9tYw)7tVpO_ zcU-P^%1@TW4E#oT!7>_~BTc7&6&U`*EI|w;^S6x5u_n(?GJw5-CqJQ=ZPW`-N=EO~ zKN0~8kGxNn&zO^mz}8;x9C4Y$!}GD)!C8GGs`wv@0n&tO@Y4T++`(Fafc|=eXd{rt zAp6nn1CWTppYza24^q2vdq&+}(G)3a=U#HxRa#`70*|6ofjyG1 zZpSHwt~oqGF5|63!Nd7FhC=GmiNtxtK!!CQs}-N zZ*8qVGLrYH!3#u)awwa+OWsP{Np-o~piT?41tl{kr7Glm;)X#x{z7&N1NRV=im9SwO$@ST~MAU{<+RP%0( z2Df9fDecQlw9^$5(t59M#L`NA;}8*g7-84)<9oyLgHKey4H?l7U+39&v5Fq zf-B()BeBDGL&KV!upuDgjvw~Ec9+GW^{yC5N@*3gFm^`M`mORP)ics+!^`2~7zc{~aAzyz=J(!(o~)sOI}9rC7aeK_B>dd+@#(w>X`MKG1_eWKBb%yMrqBWb&VpFs1-1 z4t8tzdwEGmxmzo1G2`t755BImqvjl6PH*qAD~@O*^tS@xOpkKvSAwi;*RLlphTn2z z#5!r;Qi0Sw&p#GV$D6K3dPPfSXYea(%Fx+;4U1H?{qY8sI3h&jwE(JKq!kV^DQ=HU zzlI`LrP>6BMFGk0X((7LZUr)M+f0uM9zQ8ux$tkht8`A0qX#&4fO@A$Q#$0;6Rd6V zqbUnxnSu;LQ@NRqpT#Blef95j+SKia$}FIbm+EM7%8vJwxi~#~q3wwguQ08FMO8m7 z7e&o+EfqOt;>sPpa0NZZP6{dVJj0NKsO>Fgr)21K8T}3aIUcpoFPQnSCY~3wtkn}Xu}41DMK(4J z#abyD_%D-`S)^V~^q9Qb_VOFoVb9H{8FvO&^0w!lbzrS*++>;@09D;2u4%S}-usy> z-#Z!EfC#PRKV(^;Oz>M z?N_diP2e~@+F3PK(|6-^xlayXfSmu ze$&@?U`C`1mVdN(iOJ3zu)%a19n#CH^NJ4+$0ElO$({W+K*0Uc^DI^;qlazCm(1GYd1lCCfhih zvLg2Ma#pFMO<)$u`PNnqW+NWNGV*H8~Bt(6-gDujPXx2a0D9LN#@)w8;2_FzhlatfjOPTJ6c-SCI`J7oKYHU z{uP>Ar0~2jZ}Ij`1WmSrccLGqR~kanhR7FI*i{o}zAZ$7jA6u~Bz+@2ZW=s^F`P^Q zx1~Yx#uB?>si|_h`VcSU-v*mG@W6*&MQAmUAO+sno>|#Vqq0obxl7DQvHX_xk~$d= zib+Tjzg06jtr{ka6Y*5qi)o0%p#vpw$qC*-$fWHDP<6S+;o8+W{hTSkSaCY$@LF3Ny#KDvRB7kX!ixH0em{kj z3Wo5;u#-NCYB8lgEgcV$VU>%E0Q!x+YflSp7u*)dBCuru23gB##^i5^hX{ZdH75{g z;%hv#u2Opmv>%|(StHrGwWN%KNGOgE7&ScyU#OM-yZ9wW8WHbE`mw>Z4djd>o|qsY zg=Z2KEYC4*l^7!uA(Q={s?fDf0L=^mE(jEeP+h9B<1wI}lBwj{%>Ow-;RRJ+8k3FiX^niRBEQG3St2Toz z{0kXSwt&aN1*_FUnJe;5+lJq_NzEgGZCgvLBeehLWdhBUgrKa#WrgwA-bC0n!dlkP zUj2h`td7`EVE|iK9J{9e?gQ|znr{K}Lm_Db7C=AKOLeFLvPD6fOK3-#QYA^S@CTp< z0gZ~ISZ9Jvvj1uEk-SVn2cPtXR73h!GeqJa*#Fle9wMg5rcl=*x%6Ic+*#xHA0>H! zgFRL3n!bH{x!eEY7N-%0f}bDsZK5)Lo2`yJqXvg-=v#B|xyGG|QRQFv3$zGEjs&blKQEMxVI1@B*;6sNcqio3fPEAH+^g1bA#ix+n&P@uR6cMa|i!QCx5Z+hR)bJqLu z`~l}fWPU3%Yi93jwp@EA;YtdUD2N1zFfcGE(o*6oFfi{dq2CWaz(L{7aAiBl$O4T}WsDq~ z3Ad!Bjf_#`jF?k_D2SIYmg2H{>5|LVXk^G}ZwU%_~gV*olx zB@&_Cch^J_bZQ0fS{J`C6XFkLpOJouyP=RK|2tYW3_unp6Xi|CyK3k!PqE^EfBf4+ ziR<0eBD%ODfb`uWh5!;&J;oK%@n1iX3VmfD5BrJVeln1C2BQ~f{g2|R(WTVDEJZ$9X=kJic-cAW^}f>a zW;g&b=|{Di-0f$#HRY6+J?C)_GLLKu%fIuB(-*M@zDupeZykN#v`8iHRxN6_A>ZL4 zG&E1Sj{}`*uV{*V!10Z#?00X$MdG`$;CCSC)2~{|A9K!Fp^!@zJA;9YLO!3eH1Kzh zC4ckGebQ?}=N|!m^Y=%OB(NQ*K1cJVssH?^b7E5Ib~8O~^A~_iYd}ah=dx(P8zV;K^S8v;eO7;wKb% z8-nvEGL~6->VqTvQ2!T~cG!s!JeM(zs$$d*nUbBiFljg52fD3Z8n^Vp=!>U*MfOm| ziquaFg2nKP77ki(vQj%WJA95F)5tM0ky!n`9(N&o4w{xZ1eh_ZmEHFu^MFKAa!3_dd$YzttuU*7DeW zjJcoPy*jF-4~g?<5`RrY%DdWzaoUD32?fb>iNm*P;>LdP z6yi8Xk%{9FbUPh)7e7MwwJ4xN7gX{ZSqT15CDOOIhK0aA3K)OL$=TSI1r$&lwRW29 zCHUOA5fr43mUeK?Nj7Lsls};hTVV+P%)1=8VT0l#9P_61uX20Kt8Q1?yxRv@ntCtp zi38AUjY;2SCV+sSU6=sY-@Qw}zTFm=OjR^xdh1YO%*{L_we^j(x7+xp4mzW+X<3@P z-XGYFxeQaMp9v%B1N*z6W1961cr~j6;l>wnh|Eo3=-tgj(2aL%XeZjTZ4kfj@ik`2 z?jAHiJ8qhYY7-hw=KTZb71pvK$=H#55hiZ#(K}91(JOjGl@01wsDa>iYk^&CLX}xf zI5TP@hSBJ;>>hi%`K>)Da`pki?;m9M>Q&oO1&|5()tsDKbFErt74wrywc%qdjOD1g zbDOcf|GucJNJE^n_YvV=uu~<}PiKvc(K}=OF!%n>5KxA03|!n`L8ks^!$W_wNN=6M zkvsq5)*klxe>R2VGT#5%Y5c4g{CBM0ZWDa$hSyZH4O`(|y{f2I=!S{Hm+6MiBvt-W zRUK;azR1u{{F=NHOnh%C6gUz>Mi{tpk8CPWZoU@7D9)u48jLCWfi+{hs04kpP>WX< zD!VK4IQ(aGu6Lyg)lmX65#+&QRQjvWF26IXM{!_8bJe$lk#;?Ur>Wmm|Fehhckd*3LK!YUeT-%@p$?&bt6{wBiQp-(i=6M)^JOT>PwnCoM5#|qoS-HAe6 z`@}QEsaz3&C2h)`bU`JQ>PQXd;sgPUK@C}`%MstwBP_&?(xj1R-@gMK#NYjEFUa^; zS)~d50YYQh>3?<04js9Nvx~D6DV~j|2ZTTVA)bd$YKF!(PiZ~2RR`9JSdzIgPi(gr zp4uCELUmjID~8aLbUXZwi#|DPZaIKTmoGXJ~wZU^ik&2{UB1Pgp0@=?Z_ z(dUGHn__~O6p!G=k))Q?cvU4S=3g-x+x>M|mOrd8y(bFtTdc2HYuQCAKK4U=8HUM- zqQ7ZTg(8L8<~h7U8YXz*a@J$u$7-G9s3teULS)BM8#Rrm9ol-ojz(=2T548j`OXk+ zPcsplBUrs%G{3qGy?xIpm1+sXDu+2;z>-xGScDF391akw1{E% zLSZl7U=^`T@s0Cl`+aFPF zH6`je3V>5fY{f9%Yv$O4HO}v5(!k=s+VQJSrJ@5aRfa;}j}LExvusulvG>?SP}$g>HC}+p@~$b|Yq7 z?wlvsDk-7pN!2Ph{@6;D7jJ@Q)rkU(MW&`l?)efT7R*@1XtLs0Y5$}~IdH|AC}NB* zz>o;sKREcz%^mww!vg%iyjqMjFAhD;B|?ct+>b+?EUl9Zd(wkRfhq*Bh>U__6lS9Y z=jrKr*B+ao5YOgo{4uCCmqKjy6N4^MejAwFc88rO@iS4*LT96J!5hLtrhNnq9!>e4 zX1BxH-_k_V>;Fa&tVd7>-HVclkw1u#FcN8WCseG4=tDwoW1>ZXjb=g%yZqs;UI7;0 zmZ(KpSDnAQ!;xW;CByf*bt@7@YZfg0`L3EC4;_>JZx0D<$O7YNFL%W4Xoa8pTz!e= z2V8x9G|p^8=0a@UKqjT$`9Ur2x;GRaDcW!ZsB3Ja>Jc$awC6G+9NITu5TbFI;5c( zv{U%-ZBFNKObzvNGfJ-2DCIxrCjq&sVUOf#8>ayNpBKTI#wvG zOTGWko^JRG4cS({G*XM%8?ej{vLNS8(j)_N6Ul5md-E@<59E5(6wp`9Q%&o$OYiXE z0gLOUziRq{N`>JyBj3`a2q^%8y-~6hL|t5rD^WoJT?<1KZK32M1PSAwtqBWqaSpzA zl2NI+2$hH^?&PQ@tC^_LqQDCY<}Tb&Rv~~feNa?U5FJ@TCxitnm@&jWy|F#u?B1e0 zO(SjyYX&)kLNVDC-;?1^Hd=AX!grLn>6UW~lSk9vb{WTwW}n0qH-&X#UY>(M!rL>| zL!8V=G#5S82<|!LgTdJyQxHCEft&!g2t6S^M%RbG@H%R~Tk2H$nSq(#p!;!{KE&fa z3X0~R@?x{+OBDqJI|_|zI8DWT8?$8ntj;EbOSmsLg_XX=|60FI0%(-K372V_Zu;V| zUK%7WGBG&cJ>0P0Z)AfyjrBF~A&!{RApK`~5X>j|a(w}T3F1&&V+#p;vVbhPk1B9b zkdQ8a&Bc?Wa3De(hXqJT7x_$C#;SeYpmiuacy}}{bj~5iecUY8IJkKNYt$!5d~_y=Wz^c*N3;>&--Ser6$%3)Tse-RS&JPL zJVZeq<#(Y*>^csn5<#JzI$IAyF_>zS_wD_vMowGGILwBUnwq#Wv=uG|AcO`Lb@hN- zAHKvw|4ZVzD`VrEQ3t?ueG<2d>wgRu&EI$y_HEQS6mx|Hue0oBWl9vO7(0M-RJY(^#*;d?TV-t>DfcBR zjp~?@(e2!tPE!z}^vXY$??)`*KN?E5R6W+J^YEqVp~zB50GZn9NjqnKUIV?G&J&G0 z-#1B%3c8eU6@e#D5^WJ0QcWG|8?)WjLYKjHMdIMdq3(BQ2N*s)o$p&$xCps#ipKT#>Rdk&E8c%K$NY+kr2vDj?FSJ zJE!;f($2%Es4`igA>oL>MH!c?n%EAU1W}Mfd_0r9_hpPD7N>L_+Jb49gx1=YqE{18NR*U8gz-M-JM_6VFDl&Atb23 zYg#*Z-%O%X8_;5XzJw72!er%^nOSinGeeYx^P)Mj-1Ct@Y0KT%9ny?7N#C@97Sa;W@JPvDA}x|tS0j5G@_}6XN~Ye7Lu_80BVRj}RqA$s_x1I6fTRPP^i)ORug|#LoL_i4 z66^S{WC}v;D74uR)M$%=e+i6WbfnMt*qlq=%BgF;BIOsp5ng{?JjaSDa~g=s!8Ju)b#C>mw=%Dr zh1YZ-mF%tDAsy_(VqzPgcwv z4W&wZ9cmG1Ta%6REL?pPx`roBkg;4EM%K2LYQ+aWZ7NR4=Oahgq)p zx_v9e3G=N=XN3IEjFIIOTD zZy!yvxU!@`n26F0Ys-rm_$d$MILJ(w)8o$jI_+Q<|0^x67*i=bL&O_3+%)1PmjWhE zDtKy&O|&OTaQ^mVvzt2IK#<1=8_Yyrw{mA^C&w%fg%Xk<8k$zXOoEoe?oZ@ z)kePKY@77BTx7SIvJFhmqr0jLjx)W?d^WIlw(+cRW|@*(;v^2&ec$!CgRm^F=4Iz; zIg#M%>MSdhDPom;$eG#s3Wo*SGD~ML>90SZb0p7JyM~sm)&xBwrg1YWmiIk> zGe@%p?&*_==CTmZ&0VCycgV?lQw!fs#)b#yTMTzA76c^~*wtog1&<3CWC)8oH69 zKYxA%2EIi^MATB#mXYw}ElpOh_3d$ziMX_D#F(#-{t@skspyG_c%>zw#oY$3(@`)! zNU%3A4&(;gIaYMKgXVWX-Eb{LZIT8Tdu%YA0I~1C@`X!C(-!VODHNmPqmDAf=rK$T zWBQPfRH)#mo``!{z`WM8C)5&IZ=Ir~Z1BTqMLXwyG{frt+5g@%dDh^DU6Hn=G_vVz z4W&#=nRiDhJ-u10x;4J2!-1PVS+T7RN-Q>MLM7noIt!J+NZ?X4pPQhAF#UWvV5hms z3h;S1Q0=eVH;V8S3$unrOydyRj+lb3(ZhS zsvnehmZ8lyH@%zwwRc`FnvNl=)<_>^Z@l4h)V}SjuP@=jb(X78GIOQr@*K9nYxk(; zxPIeAHzdb14Ez#J?QyKSd`IFBK@18i)+Q=I-vmbV{lLN*T77)aRQc=s=B1O>(c!+8 zHSGFIc*2zcog;n3@UY}-vUM{HG@JdviniOqJ$ka~MKDZcP;Twfo(Z560OuFk|7;Jq zz-CLpo}roU%rR{$`xPsH9;ika@(Cs23^V$x0~M_)t6V}~sg=bkL1R5PXSkv7gOFU$ zIy^H;UW>oQ93&^YLSacykaMU;E^iVY%5`vXxlOFH^Nf>c>4&PQsbj^bcw0Yb5zTKc zR1Y67`-iUPXpP3@-?ZM(U1&ogx(Q^Lzl@0ZQ(l??^NQ-|>X0KxA%%=Q0bZt;ZhU`y zXpJ~AJ4ZFofdplke-KvHZJN!4lxeIYhVHMMS8dAl6fEsX@#lB+B+18fRtDfviq6C6 z8Rs+@cjiyMBYaL+|D%SDzu_h9Bx(E$6N1+t1VLfuS#>w!MW^DeGLY9La|+m<=*ZUTbLO~ zH1uNwR{|AvZWj-a1D<=Gw3(J=shnxeOICgdvS^cF;lWsgwE;}D6SKZ4tCx+Y`33)L zj2vH6Zryq2t(NijQGR&EH|RBt#4BxaVQ%)n>u7S;UP#vjUDAEw6)z@MGZvcdc)>oq zlnOa5JYGceS06%b+MiSv9nZ4$v2d{`CfNtC>_6??H^i{byeDkG^(20|$r(Tn`%}!Y zdt(10M9s`~W&Z*;-#=`rUt=ZIU@{))2M`H(ra@41NZN2*W$EwAD}}`S9q(hoPYC>T z^OtGx4NB@7U&zvoz#CUSkPt}I$`q&DbE5IilvB3fH50JB9O`2MENQ#feK^_PS05f@ z4KkDHvVPiD+uEWSdUz0)CTpOhEF)7)WwuU?pc(QGPS$Gn>qA;IX&_+rfqeH$b7=r8 z>GJRT+8oW>oNXw|O@DBh_3kRZ-XR??G$M=95_^4PM_cQNtKCb#KLI~mhhkVF7yK#J z?N#*mWImdoMUM?TIK|)Y?7Di|Uqs_^ZwEXKw;M`II}&%?A)(dUonX8?__xYY7+!W-_G7kA{7IdhvWt%pvZrM8^-^*Pr7vlH{mz&QI;k5KI3~%V0yeG;L zy*2NwTbc-`uzn@h9(m^4vKR{ZivfJml|9Pcjc~o#|uSYh-YTgLhnT_ z%5Qci>ttr*$A_J3G%5?bqpqB?!TR$@NfC0~Ew$I2(x(g>2gsil=a)zsg z-o~H`j2G3ErIr(Fu(BkYimj>)MO^WE7l#LQQOxf2`4}G&Fmbz1tjtBvrCU(+PRFkH zXlA#DMQ#1H2m~4Ypz-KxlWCb`wPc6=Z3(^k9u9d823m7ZyySezkAsFXbJ7l@;ue9N@kQ-^9qV{&YN@BAw4-Zd_b%s(i1!4mIYScAo&vkMUTzJGJJ+ zGH{rd3fWDahd`zW-NB(ijocVo_vysBWn z+ZX5j`;n*bdur9);?hQT*?ssXr{@NRAn73@&~R zjknZbF5Ry7=28K#NQlYe!rb#J`&~Fg&Yg3bGICARd&~)%W@e-H||H7;AhE zaE8`IC??FWawobWKgHF+^>>8$BuK0y(z2 z$+g}Pg7owjOUnad2yc3^6i07iw5+y{>R8^PG0@IHK~j>0T7e5{F1hSW0B3?nJPzwb zf;|Xv&FZsHxAsC^Yl24>cBi`&lDHO@2S(7%d)i_TyHVA*LEfcRUr9>~q84WEuO0Uv z)V0sqK97?{My4n(E#0lKrH4YwR#y|6+VeV=1entGTrMFJ`#E63qZ<5b%eQxF9b(a{ zX-r%y*vaHw7PrJ*Uuk>8p?IYQgRl0eEH{{o0<|rchg=S^nt%K$AxMlLkksNo^+Wf zR@S0bs?6?<{T@JVf1M=(0h4n9Gq`U1kM!m+BAw%C+Yyw@rH#AIxJM;d#s(;=8jw~IIAMg!~p_rY(P+o+w z-}NDUtMfWX#hy_*T*qyaq7wu-yW%{rbC|IN8V+}w@5jc%-adaig79Z) zhIPN#7UPG(J0M8FjC2~m=$lgmC~}^03qr zu`c@t&deSkuw8CYqcpO_$-8RwN;Mg`P9Uh~8Lx+mER2y-jwl&iWqX8*-~phk?7gG1 z&$VNwpNR?+VexoDNw)uj$0N^g#aRb_@7rRY3Pv$<$E*4H z#MEM#O4Xm%AO4Tb*~U=UX`QS-x#k<%hbwiB+-|D-+vhTb+&$wfrvoflGlyZ5STTAn+ zuq1Whbg^?|8s%y6)yI>=Q&l;B{PiXyXKU@m6)M9n5YlMt?F+5fLujMD_otL}KF{49 zSeIL5(O%>GO_lbG(wsc|&s`+X1LizHVV(+GU4f?ws`i(9c+bP|Pcw#g`2_`gg|L1o z+KxBaKcjsksVSMUbiL!{o_oQ2+{?h{fSiDU-{a;czf8X+xGz%n4m3>Sczg%=KDj#= z_e0**m392-8_BrPE9pU95FqU-($F`Gnz$o!K&UBti<&7mranJE)_G5N0ciVPU0s4m zP{&^t1b|j~N!`!R7*qhxdrc4NZ=K}r*|k@tfAFFMZ4O&>Jx-oTg)Dd^`jHCF@0N<% zi<0QuK5d7ZB=#fqw~evMXM4UfhK8PrTK+2a|1QgDyWO9+-5aRx4Xn^t5V6bj4I7K1 zvVaj7-0Zx^6S3b@3M@F_Js)4BXIKO}86?&)*hZzn-4oa%56Hy9^#;BOf zO;ksVsAA?`=2`XclIF&Q6y_T?y@;)?iVU*$1G21tNcOZgp1qT-sM}y3 zg67GRRCYD5YJyO=Q{}132;jc=@Bt~&^QXEFQ>^asX6}_gZKI=*nO2MbAPFF!xk|uGw zlPXhbP~%Ag2-((F(85qvTUngL?J*@5S9ByNE_k#8{?vTBBCAZVK|=#qXT74mu%>1r zOQho9gfa=r08Pu;9p6&H-%nn+(+<=Af_jJM8p>csLNQvW9@ad!A9Y9HGPXM2KVl-J zH}ek&?s^f2yATX>u#SFKuKHb*=rBk|jB+(`8oh;9@vD&~MQX6H@iVSiF+MoSpuP?f z41oquzAIbVXIE3pVV(ykJy_xcw+D~u6{i6R(mzf4*jJeQ2yB0N->P6nGiE^pEa&-9 zZ0LIBroYfiNJzg4RS6cmZG1K*N{PvSnKa-ehr^`hNSESS5W)b`(vEED`LeIJ!D8Mz zZo3H1?wHUM?(Fo^&@=tYZ;6#JO{uZDxT8&gVort@(a9v(Hqz9qc~~Y^7z}a=rDr@* zRWPDu9HKVW)w8l8bRVsot8<4;&MZkdikt?|*Soq*&Mr#|*i5stNO@ius}#RGh!PtF zvWzt8;*>SFq8DIAmkZ866CaSsI2M$9b11`fnOm~N^>d(z0(qM&Js3tnk&KuRFesE$ z9Q6=m8VO4y)WTc`YJEX#E2uoWs%3pnbIW}$65N%Q;|G%Fh?kllERKlRWpp9?-cV>x z)<)}D*!)d*Aa;fl97NqUa*2UM@ji(v`RelADh+jSr&$Ka!!Ku^GX?~U67#C^zH2dv zYRe-WYCSW`d%l&TWUs5cmeXQA*eu{88X(6&QPxToQ&q(k_Pi%YCFWCv+BXQeAwX&Y zI%VXZ&&096kR@n1+6?ja=JV^z%|&~*b91rUp(I0$Vz)&(KAzOne9o`mJSkcny%Rsn zE-88k;?zu6JS$G*XOH2bEU-Dtnv3`46 zfdqDAd)Se;M|-TT&bFkJ1xY4PmJv%95lLo#&}$3_gvbCyO-{Tz}t{Z{1uX&W=g? zZm{#Qmr(Ic?>o>!6C#jXJ^>m`_d7}}PU!*bou7Eo7I7w}e$;IG+}aqjGljF{RTm`0 zWCvJM^CdP@p z6lSI(z1D&E)NG!as)!xd`|Fi&5=C9&R-$0S@-E1;W9iUdKUpwCWP3nw@Vk&o&f+?; ze#dZ$ZoJS(G%w!R6K)BETC3>tzmycH+F6swAurpdUxJo~erT)s zv7xHij`hOghgyHvRp8lhNzGeiG5MoCQ6mH70;~*8W}_QdI(sG#;8rNglY}P=It5*Y z{-$?xJP27VJRF2Ne}hLPV}u76R}~FNE7Pw{l_XvpDM?bNDR3ZS-WSg2r0i=lC9+?d zm902RkdnK6=38O#sA;26MJ-kf^$-ZO9j>IR1*xe*lC`9eO*YjgZA|~@>OR|4q&l-O zEz7|=W4gq?yQ^N&i#hi9SBQb0T9k5v`}uD4Ed{;zs^4YCPjv3Qz)r)XG)@hD4ZXfS zuC?L3KotX_E7GE6LcAdgM}gQUsmz?FqXfK!cLLKD9{6jgc5{=n?maCR zO&^2uTJZ`kovHygB}23HCwj4GN0Yzgj}CSM5(DAg?KdwTfy&^SE+`M2SL*&93W<3k zG#_JFZ(w=aooKmvqItTqf{gXwBrh5g8=GhU%wfg7&+=X7W4i$q$l@hk1L0DCh-D7%UGJ9kB_37iIu$8H_ z1gUHZqIOeV6!jUnJG;E}?gc5#V`DU7p%8@W-Efr#&+YgiN>S}`J$Fehr7&>VM+)a5&*!d`Arwg>|@8B!OgUJ;y&hlt_17rD@{Z_80fpD zd8?wG7F%#xHOgi~9+4Ypg*Qyo%N6vl+=xbw-2ARhvU;?}F`&dYF`q@5PJ97+2##1b zDc2WsIRdk~6hRj=A+BLq?_Kp3Xqx?`Bzg7e{iUB?rS)O-u80nrLfa(rju#w@E9Zus z^lV=@Rd`y6d@1O&4B02wzmt)O)OU_<2WOksZOIG zI!s6clY%$%5~QoO@C-yzU2=lM&a%GgmA?IRbL4=~b&|V^Ci6P&Ne->lI#;*Z;_Pn77X5a9z@R{3&YVM zf1=u*F)l)qF4EsL``G6tXyElUH5G}N0)x0rPsZH#(d19CX?Kro-+rr>xc5MB!5{Xq z&)+`Q7Ik=Ka<6bxXOHzasXh zS|~sp?!qHgoJ`D^rl$r_V6)cvgWY`jZn9Rg$)(ttW7PcD2T8jZ&5%-9b;W_nJBt&A z58vvC23R=oxh0lP`fsSt>|OXrB+%)DQ+3!rJ_&1Kup^~V%;9h~`7LgZ$xN+uGsh#v z#f&gGo>za&&brD|r84X8cSUjOQWwOU+4m1TLB=G*(J5X(3uLKoCltj9bu5?^RV4G=to3hML` zw`|TAo6WH8Urq0rfFvu=C}Ai-JNm*uG`;+1hJ~g4ya(5T5e~!>W>^COQP^gJKV?My zc~X#YABxKc^DBVqCL}0v!iiMbhm_iJ!_N>#v(+Wz+cx)f)goQir#NR5WNMp!ErZO@ zBkWaAdN$zv&%!c>{^`Iutk4YhrMA|_k#C?pQJZ0LOU#0kjSl%Q(NymRIB|Z^XCdk2 zvM4R}OVfLKPjByPZ{vKC-CF=A1F9^2f2K|h^>M=O%mToA!hTLiRv zCg|lvonrLx{x04V9z46{jLyf}JsomrOBTSNhGo*hOfkz;fRxQrP76SM4WV>!|66Bl z#I007msS}QMsB2@#dxm2#Yb0H<;;14uY|&|+k0P&_4Iw z(w9KbWH=leBf*GCTgZy~LbQn+%~@URv4fGkrOfpZFMFVIn^W-?k#xRw-OkHq1esOJ zt}y{z#iZg8qF=G29MZ%co%E6wCE&ftYxsk#&9W9K=A__hy2U=4P?Z5=v$~BCVHtx+-=3Lj^}?>*)zM7uxcXpNXTIQ(?+`qq6V`h!1#!tC#UK+4eTIChl; zaJsy#lz)p)n&Mvkxq({rP`JF}8u9FbL$|es0#HJ5wn2?h*(xlh>46^*v;6dw<$#BW zN0BC7%b_RQ3Z~{ZwsavR47GXRwINfM%Nxr#r{A)uqT-RG$yO*UJkR+Dz^1 zKM?R!TbhH2LYt|NQ}Z$q5N-JME86?kCuCIjYSFzpV;VPo(d&R>IHhj^==^CG(A0Xa zL5@%wUWfgbqk{E||Mp;`335p3`7E6hT+jw4^1bC!%NZFrwT$#Ax_QeOOxNXdtj{H8 zFqz+k1rK+Z(mq3lZ364n#7sO;_W&){5RMmiT zIa3@TG29DC=XGj!K?+Ua5J;n0Gh6YI1O#`sN;wFk%_$tB?8dnCHnX?c-0ZZwV!=XR zbj^QC6*JJAo{jO58AY1XVN>`e233BgqvdEn%S((c`ZQ7%P^4nfy75dsIn*WnejqlK zv0FK%m%`W2tfac0u$&W`+fv_drR4@uGhZEeKP~_(LbC|1JWqnAznnK2)RskfH_SU$ z`d&H}W|LhFy{JOd8r$O)rD15XX0O0K7Pjk91+u0-peR_Am4KUW zK9e93Cifw2e*;Kv#UhyeM@lc62M$?E6c9go^eOWq(*I0m8J-BB}f_K{H-gVSbQhLwUJX91RH6YJ%r zv5VVng4~)O8ZnfR`8-YYU(kna#K=tj0TQlwVi^|-yl*GrfB{9_ET>K|_b8dji-tA` zPP)X&axxz41H&&fMVTOVDsh@4L-7(%Th$FeLdXQFPwj;2-EhlSSA$2+w^unT^Ye>h z&xBrapd91CUDLR5r{MCuLqT~)O`bsVyc!!%;&xV0k>yFFV|{NfJ0nBoP?0-}nC9z( z!0SVyTRWt?#piz7`>xHeO z;kQho&5ty6gFDPGql(U(qU^6=q({rc#`|K*o6#&}s3zs4V(XUsp2Jb$BQ&ExFxO-NQ|S2Rc&R- z`$;eeT758axm~e9+=@QPWZ@Hz7(NncQlGV4@^vYHk-$b z8hkBq4xeJd&nHDZ{?$p4HU3d&W}?Po)`2afl9GstFV3>u;oHX)OCjisVui{KHW&-c zHkZ#0=PSz46J2Jy==Mj18Xqh;D$e3u0(T1EK#9h?7Bv46^Eq(O!w?{G4@U*OI`n#V z=+3j?5xTS~lZ>mWtg8o#4^&Bi^p6<&L;2;mi?n5qiv^U@boOQ@qSsCd!E+ALV4}W!R%2eg9A6r(BN`; z*q%?s=Nb1SPNeu-U$P687!`YUwcUAUkP)7Uvk^+=nef*^pr-?b3R*3fQv`puKNjvM zJj?lI&mv;!DAdw02d!TddIG@8dh_H-j#LaFqGQ7ZIl!Q4=A7$Toy-wnP`4-9{#@caj%2?yRK6^7eL*{0WmueyytyAJ0_5K#x54{IGUI!PY zHGR`j%Q+9^;D$37hUPCgpbH=4$(MK6AK$9%cx4+sS%nrQQI_YJi}FijHE%y{ETnk} zT}@Q1JM##{38GT zHwFOn*bN zl4N%sGz=v!TZqToJl`#|d0wC1*yyW@dAkb>d+eYK`#sXYiqR%BGnt$L)dd{p=?vEV z5yv6Yzu8TR+*h>fL+96oCB&R@4ZUpOp|$=zU~};43n{cnPXiq<_@Qu2w?w8X9qnm9 z%jEZ`l%mtc!G3vJ&~N>}Jo?M-nL%Nj;N6na91?S@$Is0?J-1^m5VUBvwu(zp1l4z%oZ`b(=M@LY zG<2I2TMqzuU#6qoS0G!?!RZRVG*|h+`f5th*G(Pp-0glaf)5R55|^s3D)@IBa%Pu1J4^FyhBV*un*(-^ggbJ{S*t=Bm+TV_Mo|jD~?o=wZ zzp3ax58Auf^YDe9eftqZiAbb4ostSVltf$xn&0S&DhV3n!6jR6daVU-5ABhx_L-9` z_CaZe?Xw(TZ;e<%GOb*T<3?cdU?jo34J@r>!r(iE&gw(l5I`E9Ox#$MJ)*9<#^Ah= zxA1#U$M*XmO$!^F-z~y@eMq=c$S$=$j;wGIb@ocF7L3tZVt5)Xf`C7z;W>7E@*gJ> z49A4$%5r8QdJT1f9Zx-#PNz(n;MU`P3$C?HonfNe+i2ld(bNs`oVC)v&>vwzvy#Pd#NtjjZ!7)P3Rk;}_m=P{HkglFlC?a7=st%BFae*ij^oEKW zB_h({Po-U31n#==sDg)%NHWbFB|f4ZYx(vREcZQ4^BTD*;Q1>PH-8prXMM2MFwp3P z7H9X5_xE~&_9#WjdqtC_CgxWt5dPknm0*L`R*t0TbE39Jyy^$8EzD+q@4{)!sj29t z@}Hckv(rUB$xObSr>uC2NX!i1Y zdwM-keWY-9=RBt0h-H0bRZOX!%*Y!d7?T2uVh4G!pni)2$z>GzXc z#&Y~lwaKW3qilKdjP6O_&YH7=fnH67y2PB!r9nIx?Xx;Is2zf( zU3Lm~_TS44D34AyczxPg*1*l;n1Uw}oaz}^Ha~5-8}E1gZT~Wsa-B49sGQ#WFw0Lu z=dPejSo+Y@aRuN!1uS^3QY)lP^!+KYLzfKD76}$9^t4dlm1v>$5j=GJt{k zPDlRxP5-`Dk)7Tgs!jq@X#0JG;kqU`b1<{n6?a2>@;hV^YvmhuNc&53>y;IU)!{AM^E^pM?(5Z@VQB_HX3WM6mpc3w z4YmGe#oVP9+Xd=jC6^x(grA+CFNE(3UnbrCG+#FjpB?Oa+5yn?34d+Qn*dru)Vygs z^AodgziEFNMq8WN_$bT_y;UE~(fQtoQDsJ6VHHO-)y{o1*g5v~rNh5C=jD)F)9)$Y zoExmYdsv8jDzLgZ5AnYaUGqC5Z#!QJO}|Ocge*a)%?}Zt958RztvGChkG*Dwp7CMw z&4fsZUxKjTrb7=o-1-VGu1$kIb|lK{380$EQcy$_^2~z>J&Ak6+s-};$M*<_C?^gM zTfCl2RTIQ(RQOFHIE)>QulY#!OGSIpS*Km9CFk1}l5||eoC^DtxC?o>Ej~V^DCox_27>|Y3ZB|ZLHOl5~kLYUW?00!o=zI7^6z$qP4r% zLu5`zX-DeB1)TLlYIcIxeec_hoVJS!zuW#6OkNxqn9jVtSs}OB6;=8s*0nno-{`Pk-dX$M(F(#wHTv8ZVzHQy}NnO@?GiQJ_qF zG!IoJ1Cl7gI>7_V$4)8pp2S*yew4uU{A`j3c7y&*dwBw(nZ@#66Z)O!44<_G*023K zp7RNT%0<&jE?()xEYbib9%LApszEv-%QsqPMk9N(U$i*04_;Hg=AUxZ%nha{*rlN} zoq6#R!t6XB$T1yZ8SXV5-h^63C&w&hWuOr^7Sh=spnSU(@|D}8f|0|>;^?H@9iQ!6-51MD+yQvYCXu;yC= zf24~ke7d-2G9l0Y({)+K3Wf3}8AG}}DH#JJ?B`K%`}#el1(|^ zJ*Ww;MS77&S-Gv6Imx7b)2Zn=T+R7wlv(@!v;Mk&5=bE3zw19N+5-`9=h;B%(Cm)Wj)j ztMDp&;Roey^{Kfzoewa@o$)7Xt?p+0Oyxz%xV#cVCkA1X*OXw!ynrxEo@}3d6V?2@ z%s9Do>Z$8qVEzu~!WJp6x6@iuEn*Vu*@)a(&S^uh8PsFZ=E|KwY1fozMXxGzN<2)&{(wLWkYUfZ^x{Lu3UvloS%tS*f~|Yp^Jf_ zoUcH-)7{#Q;ZYeC%%IkXZ}&^_OIlf*Lw2f+cq3LhZSH@;FiPeWL?OMiQ@qN#(hi$c zjm;@c3HH9V+X<&TKb=oU#zooLEe8lLwFdlpE~~u1&))q)Xo)Mg@CUZBL9Jb7zkqG% zw?f)Q*Fr`l6Uzu4K2cc(V{z8V@By{Nk^8tHOB}|oC?h%9+fB+jak*Qf^Rct&tjqg~ z21ko;!{_{3KRvb*_YV>$hcPdQkK@)F_ob6-4O=Y=PQ%NjPw%TF9$98B1{FN`G=}G~ zoI6}Tos~n2n@&y6j;?mH9QyH3Tv!D0-L4=2AIAdoZ;ZV1C=n)w|4s1+uA!;nbPJE6 zM7hR}_-S;Ste9wV`>0~{Rp@%sjJfIB-|ao}O@g(n3qNl~$|gsO_g4RHNar5(5;bK~ zO?R;!G%2R6>ufb&xIUfj_uO+ryLrv$htDVX=H8k-&(2Ws5gbuQW=&aUO&}hZB}9=% z(sGOyofyOWz!WPZy=SbwU<1v1^Jtm7o03lc{${@QdftAGNTtj=6x9@VWoz?I$3rV3 z07!zdQ+m8MFq^n&oXw1sCv#?bQCedvQq}8yJt$rOf*CaC~Rvh$sc95U+9^Vm^p z8W7cx+RS-=0y;uMsOKWw7^ggEHdJDnJMW;E?=Ehm2Di=1i|6J|$uG_P;lGJgyoP&vSP`$SA!64x{Z(N%`wZwVvb{#^R|RoOY(H(esWJ1obx zfTt(jn39%Xv{HUG;hCIXF;15eXV*IVq?(s4STeILgF-d^ee~4em}^;|gi51btB&bC zXEB~?8V^*v=A-YAc)q{;)%7PEUN_}xvXY9|N|f9{-=c~n$jmRu~cg8kQ%lpb_XQa-% za)~auyuvabEmjpV-QA~Jmi~vnINIW=-nX)pLQbE&BA#7OA-W<409M1-M*!P5n%wz5 zxJ)A<-X@ExJ9_n_IvMbh*G9}did}ugIS9-y%q8Ml_@9{FvG)pP!+UogF$0T$b9{$It!U?Vuyl(!ztzG|Zb*V{~-tOKLWO!+n z6`fgmOLe&t+pE0XGNUAk$tkR%vmxF^;N?+u7Vh%Ak2>FEH=z5E2ba!s9YH};9n8u?QUkoqY8H90Ryc&@oiYNN$ z?r#Xx4tfpHFCCl%UB<+Ybn5Fuc1Y>FomAxv_fq`w;+-tcBUkg{mw$KZl+i9E4 z^_jut)s18WZP$=!Ntx{(76i5w5jX0^RFsh%c)p`>m{Tw{nP3(dL=II(*P#s~#UI)* z=0>9#qm+9-k18F@>ASQ(H4=_9_{L}-XQzIh`#+VuSl`1YbKf<)lEn8VuJ;V)HdN}? z^WNnsPwIU7an2Jhx(+vauje*y7M}aq_Z{7|vI;XV$T(ch(SxWm2=|O`okd3xfg=m~pg7%G}z@ zRO`~Tzj^LUeBL+p0Y-^ed8euh78V7WYUeE3B_&A4gtGGPhU{}qrD4;O*13=S+aJV6 zlQ0f?wY5oxMurhK&2xxxnxwd3omWQgMf2^}Q923qW}@P0l%X_qN*cV%vL`v|+{#r) zFO)u>pGOBMkI76;IJ@QkxP>_Rd0~^S5MJ6sij)(5Uy`^@D#ZO??>;gt6L}WKqS)zD zT~`KYl^s&i8GD!8o;t8+9bjd%t+KHEa+q?d)hG!@AsMz1CZG57q?y!BW)Ae(2M6b>Uej{jfK8XK_4Q zD4c8A(^lM2UwMG0RG`9_i(el%!SaXc2kt5ZPmMEq=})imN^qw&P*NsBhPY*1At9yQ zc!(J%spp!C&-<=F@<)??ey4o1$&l{E$#n%C#bFEMop^ohS2rKO_hjEt1sUHGw`Vwa zi`db=WeoqoUWT`>XgMli2d1R^X~MAD!e}*rrpOpMPC4}?I4>|UC+&kw=%;al#b8G>(qtN-Hy5V zTHY%?g|qfPw=C77=3-G5n8qELrH4;Hp^iTCL2pM(vUfjY-l#}7_sfX0-IuZN(L03O z*G5y}H&i~7Kl~VnxPN2AJ#OX)Psgs#LH1uNYOotb((~n2N^L*a4Cv?}+kUjWPbyG# z)N^2mlH#IzEON%vQTAtfJy>aAZt@}-e-vXy&Z@O4Y@I818a>{#-Hbs=N@4QKXZ#iY zTisZ^r~Mcumy&)r>a+T+sGC_}?%gGz^td`t?c$9Ng{CL0M*$mwUmlhBu@VB2qIGRj zUT0Q0<-0{Y5CK*aJz2q|{L zdDFZ3lhKb`eAl{4TfAm!N3lIS_4d&sssHshqzf)wd&p4(X3(f2C;=Pam@8SA5~N2r ziI{L#8(ooEMIa>atZGn_N{px&QL#w0;jT}C?V1Wl9zhV7DD$%NTJ!U-Pqt^q_z0O7 zY-|;nDrxQlKm#*7C13@w9%YfLb$-ys-a^nRMdg+^N^xDydpg^DM{S&kgt$7SAXd{sgTm(E2N&B zV}G;FHHuI6s(WXe{cHbny;AuDO~-x36=~CFuS}0I4`)*o&jxlV)5VL)1_+Wl@kTn$m9Kg#SGZ4+l!zc!@sm27-1P6w( zg7SAaQCS=QrIz^eGt0~7o5@yuMLIgJ1J+N85;k*=`>zmYyf_=)rWWBEULpnEm$$yy z46cm)@U$G}^8vV41ONr+#X_$0-%xMVMgFUm`jtTZu^Qv|eUmrxbU<|IJ+^#R60za- zrK&IwH`HZ(RhV}8)8mU3YAm8zCUb+QAQQ$Gq)R-U7o%A!f1X1Q~*D* z157@6%c1M-1j5JI0Nig5gVr2B^WkskM5*%S^Dp`%UrPUcdu6_vQo!qXrj#tp-O^$h z;95W)wTw|BVsQL*A#o@>Wh!yVFgh?0`k?Fh`YK?oYh7)4MB~m?QUK1T;A^kzWvlT< zXvkV^LpnM_H^agRHvPU_*Ml(mYOA{6sd3%qVbvuvmDInZ>tZ5gs56UKkYL8*Dg5T! z2j56CCAuuB!=#AbNTp7)DZrFFs2sJ|F_>6+qBwWAL5?59_RwAT(&;XmSNFgf+ly z24>m{1({HhgdQ?a)(RdI07;A>tN^rDtXr8=cf;GDcc4x{u+{b^lhPGlpa{a)!gEMa z{W|^!NL;`|DpRgQhYA4lO)LpOkIbkNRE1stN4+D@2mq>2psoOT4-$h^*`co8*aA|a zPxqR#VqG5G90C1n(6C-X(12EZU_S*2JCeBuDOx`k2T_gzB;I))BR&C3lp#|mehsp= z{RBJzAg*8d@$f+NquathP$vc)L_uQ^dy7?E{jUEpEd=BspW4i7yC$M2gqmdZs%g^zQqMgA>~>^w^ObO9N+iXvU1;;&TF&0 zO?Mpe$sLcKKHYQaJF7{99M@(H+U*`p_^MKSMyO!%n77=?hX$N|5I^WA4_dmDh%g%W zyyb5VxXJFJ8)+m@?=IDZu5q-+HU2mNUWc@)U% zU%bc~pob(=7!ItohC^gR57TN)IV%W~+E9VnwSm{sOvqMC>2Dpa`Yi=59}afgSQ2I4 zgg$}PaSv>v@@IF7+TQZ&0A)+AN+ccUe>YE}Ssk_dSV`QU{yH6&xW@#oqZJlBBXjuy z+$0;>OTU6aTw7x)pNClCd#8y|NC5p~lcKKhy8`65vp))Fc(nu`xHU|_pD0H{;@S6C z+dsfzqdDM$OC;gB^NB;x19B^}z~>1KXd&YZuYf0mpG95$^1F0?42oNP`J;%CWP{xI za3zD>)%XQNia)Y4>lvsvLZEt$`kzdV4h6Lu81)97u(Lm%c=1bChnTAlt91Xo!LJ@c zi0vKrtOR7Y0{_F;-+sZe_HU>ZGl=q4MRKHhmb#af%>DgWR>Vz6#+VGGfDslA&F2mr zN};wE@bnh|D4rpcDL+DX-hg7G!kffgOg#$ZHIRq=m^Alm4Do&llu8JJWEUbmKT?k7 zg5vj~I0ukFXMQ8-IY5fuLx|r)V~w6;Crs>yULMHv{U6WF$nBcA6b@o=k^hZvMc%0q zhaqzZ8J~HHd(QThOcl=6fN(9Mo?{dw-@?%3&e}>lZLVLFU?w?f>FB)r&As-b!?3 z(QX2TG+qf{kg279+l<+3>JKd6V(-tG+=*_DfeZs^(RG|_Cr1<){hk$^nH1<~wtIB@ z%=3o%6^>WyhXWI~@m_~(YErKf$?;gaAp-$FAwG2iIw%+b?W+zCh9+6e`_09PBw&AM zI#Y(8Zuu$&h)JKsDgMs5BJD`wb|!!4W$lUd#l|PDNHT!_Us?h5Nw;W^kkg_u_jr6M zfNUFA2$KGNp!tHIhg`z5SD`OKHv)D-2cde&e`mlDEG`8cmU6 zhgLQ3TAG&!tgcjr1xeh)e?8k6{iG+?)y4Koc)`u8X~_ zbKgl@hKL*n5L;?Y)Fm3CowT%4aAQ}#5&;iW`%h>6KW;q&Gi?j2?J;OW85E)K`4S*U zft!Y!I+`$u*e5e5>t}`yGZ5q%&|UCiYwo|8jR41=T?z1;Q+g7D!jZ8K0~-6icz8sO zC-KBWa>W6QVjcLm`@dC0?(8B_OUGrRypMygW=I#L{%}@3Tu?tSiK{ku<#RzMt^e1rt8cFKhQVkRa%W2B&h$Cn}=% zu^^tZmvxwd9#XT@R{zlYJ?(L&c^rJ@LR+TZyz^I3uUf8#ie%uIYcxYZL%0(f9x1!F z9Q;;=^x7M8AP8&SMC;%V$_em=NfD&=^t};ni+!}#UzknXXFEr+)z|N=+NPm11h$z@ zoOzGzuMwvGC_@~Fg>Q$KsNj0!1bpotHgb$=3(QFh4hiAY8dcck`sDvgVv#j^6=1Ae zjgUF5cITC4YvwRCyDi=~PG8?jhK zFdN#WBg)NAj1HagidYY>q^}$I*TUCqg)^NRXk_}rN{nyg_M~kZk-tC3YJR;ncN3DZ z5yqo;L#s#$u0`^xlDgouV{KBA^vHeimu~=|j}h<(+A2Ow8}3kR&5E_OdI-#ol+;I& zI&9|zaUX|mE@#~sf*2{@#gZhBdQD6AvSyfuI9AYi?TztRwMV6e_eMK{^fnvF3qJc= zgD~tkyo&o{Ithi#kfIkV&WaEME2zZC9(h76Dr<-BFyo3MOZnhAnnCsyBn7QJR1WE7 zautvkUKdu*{VwvBsGpetf`JNVGAC_c!5XEqLC@jw|JqvKtJ}KXged=H8i#u1SbU{i zMy+%n*98hj+NIG#LP#t~4tDbo`I8 zRO1_J#`sEzVnvvglW_!uh{m!Y#A}PJf$a_?{E(Pt#H#FMND6Ichv$mCl9Hk0!hd}R zqyT+kAcXRDhoUAGpi5!fH}_Nczs(ZM+Hs--2v;eaB_Rc|phb>vKZ%*dYtPuQ(};mP z6?6~C#{8%Se~ta$cvbDeKfK4lOP~)ds=PYVeveJa+HD1gG>V@zI-IhCgo+tZlhFWu uM literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp index a8b7a670c881b..c11839f0356c6 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp @@ -140,6 +140,18 @@ class NormalLaneChange : public LaneChangeBase bool get_lane_change_paths(LaneChangePaths & candidate_paths) const; + bool get_path_using_frenet( + const std::vector & prepare_metrics, + const lane_change::TargetObjects & target_objects, + const std::vector> & sorted_lane_ids, + LaneChangePaths & candidate_paths) const; + + bool get_path_using_path_shifter( + const std::vector & prepare_metrics, + const lane_change::TargetObjects & target_objects, + const std::vector> & sorted_lane_ids, + LaneChangePaths & candidate_paths) const; + bool check_candidate_path_safety( const LaneChangePath & candidate_path, const lane_change::TargetObjects & target_objects) const; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp index 9e6b9d229d2f2..c844b6b218d10 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/data.hpp @@ -269,6 +269,7 @@ struct CommonData LanesPolygonPtr lanes_polygon_ptr; TransientData transient_data; PathWithLaneId current_lanes_path; + PathWithLaneId target_lanes_path; ModuleType lc_type; Direction direction; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp index 589f2f20ba258..eb07d2f0d3704 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/debug.hpp @@ -39,6 +39,20 @@ struct MetricsDebug double max_lane_changing_length; }; +struct FrenetStateDebug +{ + LaneChangePhaseMetrics prep_metric; + frenet_planner::SamplingParameter sampling_parameter; + double max_lane_changing_length; + + FrenetStateDebug( + LaneChangePhaseMetrics prep_metric, frenet_planner::SamplingParameter sampling_param, + const double max_len) + : prep_metric(prep_metric), sampling_parameter(sampling_param), max_lane_changing_length(max_len) + { + } +}; + struct Debug { std::string module_type; @@ -52,6 +66,7 @@ struct Debug lanelet::ConstLanelets target_lanes; lanelet::ConstLanelets target_backward_lanes; std::vector lane_change_metrics; + std::vector frenet_states; double collision_check_object_debug_lifetime{0.0}; double distance_to_end_of_current_lane{std::numeric_limits::max()}; double distance_to_lane_change_finished{std::numeric_limits::max()}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp index b25dbc99189e8..f0adcb1d69b42 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp @@ -113,6 +113,13 @@ struct SafetyParameters CollisionCheckParameters collision_check{}; }; +struct FrenetPlannerParameters +{ + bool enable{true}; + double th_yaw_diff_deg{10.0}; + double th_curvature_smoothing{0.1}; +}; + struct TrajectoryParameters { double max_prepare_duration{4.0}; @@ -124,6 +131,7 @@ struct TrajectoryParameters double th_lane_changing_length_diff{0.5}; double min_lane_changing_velocity{5.6}; double lane_changing_decel_factor{0.5}; + double th_prepare_curvature{0.03}; int lon_acc_sampling_num{10}; int lat_acc_sampling_num{10}; LateralAccelerationMap lat_acc_map{}; @@ -151,6 +159,7 @@ struct Parameters CancelParameters cancel{}; DelayParameters delay{}; TerminalPathParameters terminal_path{}; + FrenetPlannerParameters frenet{}; // lane change parameters double backward_lane_length{200.0}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/path.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/path.hpp index 0fa0a9d977a26..0fa2c6cc8dfbc 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/path.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/path.hpp @@ -19,19 +19,53 @@ #include "autoware/behavior_path_planner_common/turn_signal_decider.hpp" #include "autoware/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" +#include + #include +#include #include namespace autoware::behavior_path_planner::lane_change { +enum class PathType { ConstantJerk = 0, FrenetPlanner }; + using autoware::behavior_path_planner::TurnSignalInfo; using tier4_planning_msgs::msg::PathWithLaneId; +struct TrajectoryGroup +{ + PathWithLaneId prepare; + PathWithLaneId target_lane_ref_path; + std::vector target_lane_ref_path_dist; + LaneChangePhaseMetrics prepare_metric; + frenet_planner::Trajectory lane_changing; + frenet_planner::FrenetState initial_state; + double max_lane_changing_length{0.0}; + + TrajectoryGroup() = default; + TrajectoryGroup( + PathWithLaneId prepare, PathWithLaneId target_lane_ref_path, + std::vector target_lane_ref_path_dist, LaneChangePhaseMetrics prepare_metric, + frenet_planner::Trajectory lane_changing, frenet_planner::FrenetState initial_state, + const double max_lane_changing_length) + : prepare(std::move(prepare)), + target_lane_ref_path(std::move(target_lane_ref_path)), + target_lane_ref_path_dist(std::move(target_lane_ref_path_dist)), + prepare_metric(prepare_metric), + lane_changing(std::move(lane_changing)), + initial_state(initial_state), + max_lane_changing_length(max_lane_changing_length) + { + } +}; + struct Path { + Info info; PathWithLaneId path; ShiftedPath shifted_path; - Info info; + TrajectoryGroup frenet_path; + PathType type = PathType::ConstantJerk; }; struct Status @@ -39,7 +73,6 @@ struct Status Path lane_change_path; bool is_safe{false}; bool is_valid_path{false}; - double start_distance{0.0}; }; } // namespace autoware::behavior_path_planner::lane_change diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp index 77ba8fe68a653..42586e7b1df92 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/path.hpp @@ -11,7 +11,6 @@ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. - #ifndef AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PATH_HPP_ #define AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PATH_HPP_ @@ -26,6 +25,7 @@ namespace autoware::behavior_path_planner::utils::lane_change { using behavior_path_planner::LaneChangePath; using behavior_path_planner::lane_change::CommonDataPtr; +using behavior_path_planner::lane_change::TrajectoryGroup; /** * @brief Generates a prepare segment for a lane change maneuver. @@ -98,5 +98,65 @@ LaneChangePath construct_candidate_path( const LaneChangeInfo & lane_change_info, const PathWithLaneId & prepare_segment, const PathWithLaneId & target_lane_reference_path, const std::vector> & sorted_lane_ids); + +/** + * @brief Generates candidate trajectories in the Frenet frame for a lane change maneuver. + * + * This function computes a set of candidate trajectories for the ego vehicle in the Frenet frame, + * based on the provided metrics, target lane reference path, and preparation segments. It ensures + * that the generated trajectories adhere to specified constraints, such as lane boundaries and + * velocity limits, while optimizing for smoothness and curvature. + * + * @param common_data_ptr Shared pointer to CommonData containing route, lane, and transient + * information. + * @param prev_module_path The previous module's path used as a base for preparation segments. + * @param prep_metric Metrics for the preparation phase, including path length and velocity. + * + * @return std::vector A vector of trajectory groups representing + * valid lane change candidates, each containing the prepare segment, target reference path, and + * Frenet trajectory. + */ +std::vector generate_frenet_candidates( + const CommonDataPtr & common_data_ptr, const PathWithLaneId & prev_module_path, + const std::vector & prep_metrics); + +/** + * @brief Constructs a lane change path candidate based on a Frenet trajectory group. + * + * This function generates a candidate lane change path by converting a Frenet trajectory group + * into a shifted path and combining it with a prepare segment. It validates the path's feasibility + * by ensuring yaw differences are within allowable thresholds and calculates lane change + * information, such as acceleration, velocity, and duration. + * + * @param trajectory_group A Frenet trajectory group containing the prepared path and Frenet + * trajectory data. + * @param common_data_ptr Shared pointer to CommonData providing parameters and constraints for lane + * changes. + * @param sorted_lane_ids A vector of sorted lane IDs used to update the lane IDs in the path. + * + * @return std::optional The constructed candidate lane change path if valid, or + * std::nullopt if the path is not feasible. + * + * @throws std::logic_error If the yaw difference exceeds the threshold, or other critical errors + * occur. + */ +std::optional get_candidate_path( + const TrajectoryGroup & trajectory_group, const CommonDataPtr & common_data_ptr, + const std::vector> & sorted_lane_ids); + +/** + * @brief Appends the target lane reference path to the candidate lane change path. + * + * This function extends the lane change candidate path by appending points from the + * target lane reference path beyond the lane change end position. The appending process + * is constrained by a curvature threshold to ensure smooth transitions and avoid sharp turns. + * + * @param frenet_candidate The candidate lane change path to which the target reference path is + * appended. This includes the lane change path and associated Frenet trajectory data. + * @param th_curvature_smoothing A threshold for the allowable curvature during the extension + * process. Points with curvature exceeding this threshold are excluded. + */ +void append_target_ref_to_candidate(LaneChangePath & frenet_candidate, const double th_curvature); } // namespace autoware::behavior_path_planner::utils::lane_change + #endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PATH_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp index 69362994dbbac..422c392cac462 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp @@ -24,6 +24,8 @@ #include #include +#include +#include #include #include @@ -56,6 +58,7 @@ using behavior_path_planner::lane_change::LCParamPtr; using behavior_path_planner::lane_change::ModuleType; using behavior_path_planner::lane_change::PathSafetyStatus; using behavior_path_planner::lane_change::TargetLaneLeadingObjects; +using behavior_path_planner::lane_change::TrajectoryGroup; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using geometry_msgs::msg::Twist; @@ -69,9 +72,27 @@ bool is_mandatory_lane_change(const ModuleType lc_type); void set_prepare_velocity( PathWithLaneId & prepare_segment, const double current_velocity, const double prepare_velocity); -std::vector replaceWithSortedIds( - const std::vector & original_lane_ids, - const std::vector> & sorted_lane_ids); +/** + * @brief Replaces the current lane IDs with a sorted set of IDs based on a predefined mapping. + * + * This function checks if the current lane IDs match the previously processed lane IDs. + * If they do, it returns the previously sorted IDs for efficiency. Otherwise, it matches + * the current lane IDs to the appropriate sorted IDs from the provided mapping and updates + * the cached values. + * + * @param current_lane_ids The current lane IDs to be replaced or verified. + * @param sorted_lane_ids A vector of sorted lane ID groups, each representing a predefined + * order of IDs for specific conditions. + * @param prev_lane_ids Reference to the previously processed lane IDs for caching purposes. + * @param prev_sorted_lane_ids Reference to the previously sorted lane IDs for caching purposes. + * + * @return std::vector The sorted lane IDs if a match is found, or the original + * `current_lane_ids` if no match exists. + */ +std::vector replace_with_sorted_ids( + const std::vector & current_lane_ids, + const std::vector> & sorted_lane_ids, std::vector & prev_lane_ids, + std::vector & prev_sorted_lane_ids); std::vector> get_sorted_lane_ids(const CommonDataPtr & common_data_ptr); @@ -432,5 +453,24 @@ std::vector> convert_to_predicted_paths( * @return true if the pose is within the target or target neighbor polygons, false otherwise. */ bool is_valid_start_point(const lane_change::CommonDataPtr & common_data_ptr, const Pose & pose); + +/** + * @brief Converts a lane change frenet candidate into a predicted path for the ego vehicle. + * + * This function generates a predicted path based on the provided Frenet candidate, + * simulating the vehicle's trajectory during the preparation and lane-changing phases. + * It interpolates poses and velocities over the duration of the prediction, considering + * the ego vehicle's initial conditions and the candidate's trajectory data. + * + * @param common_data_ptr Shared pointer to CommonData containing parameters and ego vehicle state. + * @param frenet_candidate A Frenet trajectory group representing the lane change candidate. + * @param deceleration_sampling_num Unused parameter for deceleration sampling count. + * + * @return std::vector The predicted path as a series of stamped poses + * with associated velocities over the prediction time. + */ +std::vector convert_to_predicted_path( + const CommonDataPtr & common_data_ptr, const lane_change::TrajectoryGroup & frenet_candidate, + [[maybe_unused]] const size_t deceleration_sampling_num); } // namespace autoware::behavior_path_planner::utils::lane_change #endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__UTILS_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/package.xml index fad98ecf8f8e1..cf7600556080e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/package.xml @@ -23,6 +23,7 @@ autoware_behavior_path_planner autoware_behavior_path_planner_common + autoware_frenet_planner autoware_motion_utils autoware_rtc_interface autoware_universe_utils diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp index ec000b8fee97c..06a9d505f90ad 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp @@ -63,6 +63,8 @@ LCParamPtr LaneChangeModuleManager::set_params(rclcpp::Node * node, const std::s getOrDeclareParameter(*node, parameter("trajectory.min_lane_changing_velocity")); p.trajectory.lane_changing_decel_factor = getOrDeclareParameter(*node, parameter("trajectory.lane_changing_decel_factor")); + p.trajectory.th_prepare_curvature = + getOrDeclareParameter(*node, parameter("trajectory.th_prepare_curvature")); p.trajectory.lon_acc_sampling_num = getOrDeclareParameter(*node, parameter("trajectory.lon_acc_sampling_num")); p.trajectory.lat_acc_sampling_num = @@ -213,6 +215,12 @@ LCParamPtr LaneChangeModuleManager::set_params(rclcpp::Node * node, const std::s p.delay.th_parked_vehicle_shift_ratio = getOrDeclareParameter( *node, parameter("delay_lane_change.th_parked_vehicle_shift_ratio")); + // trajectory generation near terminal using frenet planner + p.frenet.enable = getOrDeclareParameter(*node, parameter("frenet.enable")); + p.frenet.th_yaw_diff_deg = getOrDeclareParameter(*node, parameter("frenet.th_yaw_diff")); + p.frenet.th_curvature_smoothing = + getOrDeclareParameter(*node, parameter("frenet.th_curvature_smoothing")); + // lane change cancel p.cancel.enable_on_prepare_phase = getOrDeclareParameter(*node, parameter("cancel.enable_on_prepare_phase")); @@ -338,6 +346,8 @@ void LaneChangeModuleManager::updateModuleParams(const std::vectortrajectory.max_longitudinal_acc); updateParam( parameters, ns + "lane_changing_decel_factor", p->trajectory.lane_changing_decel_factor); + updateParam( + parameters, ns + "th_prepare_curvature", p->trajectory.th_prepare_curvature); int longitudinal_acc_sampling_num = 0; updateParam(parameters, ns + "lon_acc_sampling_num", longitudinal_acc_sampling_num); if (longitudinal_acc_sampling_num > 0) { @@ -356,6 +366,14 @@ void LaneChangeModuleManager::updateModuleParams(const std::vectortrajectory.th_lane_changing_length_diff); } + { + const std::string ns = "lane_change.frenet."; + updateParam(parameters, ns + "enable", p->frenet.enable); + updateParam(parameters, ns + "th_yaw_diff", p->frenet.th_yaw_diff_deg); + updateParam( + parameters, ns + "th_curvature_smoothing", p->frenet.th_curvature_smoothing); + } + { const std::string ns = "lane_change.safety_check.lane_expansion."; updateParam(parameters, ns + "left_offset", p->safety.lane_expansion_left_offset); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index 88f58debb886a..7748795851865 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -28,7 +28,10 @@ #include #include #include +#include #include +#include +#include #include #include #include @@ -36,8 +39,11 @@ #include #include +#include + #include #include +#include #include #include @@ -104,6 +110,9 @@ void NormalLaneChange::update_lanes(const bool is_approved) common_data_ptr_->current_lanes_path = route_handler_ptr->getCenterLinePath(current_lanes, 0.0, std::numeric_limits::max()); + common_data_ptr_->target_lanes_path = + route_handler_ptr->getCenterLinePath(target_lanes, 0.0, std::numeric_limits::max()); + common_data_ptr_->lanes_ptr->target_neighbor = utils::lane_change::get_target_neighbor_lanes( *route_handler_ptr, current_lanes, common_data_ptr_->lc_type); @@ -232,8 +241,6 @@ void NormalLaneChange::updateLaneChangeStatus() // Update status status_.is_valid_path = found_valid_path; status_.is_safe = found_safe_path; - - status_.start_distance = common_data_ptr_->transient_data.target_lanes_ego_arc.length; status_.lane_change_path.path.header = getRouteHeader(); } @@ -1124,15 +1131,92 @@ bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths) } const auto & current_lanes = get_current_lanes(); - const auto & target_lanes = get_target_lanes(); - const auto sorted_lane_ids = utils::lane_change::get_sorted_lane_ids(common_data_ptr_); const auto target_objects = get_target_objects(filtered_objects_, current_lanes); const auto prepare_phase_metrics = get_prepare_metrics(); + const auto sorted_lane_ids = utils::lane_change::get_sorted_lane_ids(common_data_ptr_); + if ( + common_data_ptr_->lc_param_ptr->frenet.enable && + common_data_ptr_->transient_data.is_ego_near_current_terminal_start) { + return get_path_using_frenet( + prepare_phase_metrics, target_objects, sorted_lane_ids, candidate_paths); + } + + return get_path_using_path_shifter( + prepare_phase_metrics, target_objects, sorted_lane_ids, candidate_paths); +} + +bool NormalLaneChange::get_path_using_frenet( + const std::vector & prepare_metrics, + const lane_change::TargetObjects & target_objects, + const std::vector> & sorted_lane_ids, + LaneChangePaths & candidate_paths) const +{ + stop_watch_.tic("frenet_candidates"); + constexpr auto found_safe_path = true; + const auto frenet_candidates = utils::lane_change::generate_frenet_candidates( + common_data_ptr_, prev_module_output_.path, prepare_metrics); + RCLCPP_DEBUG( + logger_, "Generated %lu candidate paths in %2.2f[us]", frenet_candidates.size(), + stop_watch_.toc("frenet_candidates")); + + candidate_paths.reserve(frenet_candidates.size()); + lane_change_debug_.frenet_states.clear(); + lane_change_debug_.frenet_states.reserve(frenet_candidates.size()); + for (const auto & frenet_candidate : frenet_candidates) { + lane_change_debug_.frenet_states.emplace_back( + frenet_candidate.prepare_metric, frenet_candidate.lane_changing.sampling_parameter, + frenet_candidate.max_lane_changing_length); + + std::optional candidate_path_opt; + try { + candidate_path_opt = + utils::lane_change::get_candidate_path(frenet_candidate, common_data_ptr_, sorted_lane_ids); + } catch (const std::exception & e) { + RCLCPP_DEBUG(logger_, "%s", e.what()); + } + + if (!candidate_path_opt) { + continue; + } + + try { + if (check_candidate_path_safety(*candidate_path_opt, target_objects)) { + RCLCPP_DEBUG( + logger_, "Found safe path after %lu candidate(s). Total time: %2.2f[us]", + frenet_candidates.size(), stop_watch_.toc("frenet_candidates")); + utils::lane_change::append_target_ref_to_candidate( + *candidate_path_opt, common_data_ptr_->lc_param_ptr->frenet.th_curvature_smoothing); + candidate_paths.push_back(*candidate_path_opt); + return found_safe_path; + } + } catch (const std::exception & e) { + RCLCPP_DEBUG(logger_, "%s", e.what()); + } + + // appending all paths affect performance + if (candidate_paths.empty()) { + candidate_paths.push_back(*candidate_path_opt); + } + } + + RCLCPP_DEBUG( + logger_, "No safe path after %lu candidate(s). Total time: %2.2f[us]", frenet_candidates.size(), + stop_watch_.toc("frenet_candidates")); + return !found_safe_path; +} + +bool NormalLaneChange::get_path_using_path_shifter( + const std::vector & prepare_metrics, + const lane_change::TargetObjects & target_objects, + const std::vector> & sorted_lane_ids, + LaneChangePaths & candidate_paths) const +{ + const auto & target_lanes = get_target_lanes(); candidate_paths.reserve( - prepare_phase_metrics.size() * lane_change_parameters_->trajectory.lat_acc_sampling_num); + prepare_metrics.size() * lane_change_parameters_->trajectory.lat_acc_sampling_num); const bool only_tl = getStopTime() >= lane_change_parameters_->th_stop_time; const auto dist_to_next_regulatory_element = @@ -1151,7 +1235,7 @@ bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths) return lc_diff > lane_change_parameters_->trajectory.th_lane_changing_length_diff; }; - for (const auto & prep_metric : prepare_phase_metrics) { + for (const auto & prep_metric : prepare_metrics) { const auto debug_print = [&](const std::string & s) { RCLCPP_DEBUG( logger_, "%s | prep_time: %.5f | lon_acc: %.5f | prep_len: %.5f", s.c_str(), @@ -1195,7 +1279,7 @@ bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths) prepare_segment, common_data_ptr_->get_ego_speed(), prep_metric.velocity); for (const auto & lc_metric : lane_changing_metrics) { - debug_metrics.lc_metrics.push_back({lc_metric, -1}); + debug_metrics.lc_metrics.emplace_back(lc_metric, -1); const auto debug_print_lat = [&](const std::string & s) { RCLCPP_DEBUG( @@ -1218,7 +1302,7 @@ bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths) } candidate_paths.push_back(candidate_path); - debug_metrics.lc_metrics.back().second = candidate_paths.size() - 1; + debug_metrics.lc_metrics.back().second = static_cast(candidate_paths.size()) - 1; try { if (check_candidate_path_safety(candidate_path, target_objects)) { diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp index ef899cceea0d4..bf0af0d133dc7 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp @@ -73,6 +73,34 @@ MarkerArray showAllValidLaneChangePath( marker.points.push_back(point.point.pose.position); } + const auto & info = lc_path.info; + auto text_marker = createDefaultMarker( + "map", current_time, ns_with_idx, ++id, visualization_msgs::msg::Marker::TEXT_VIEW_FACING, + createMarkerScale(0.1, 0.1, 0.8), colors::yellow()); + const auto prep_idx = points.size() / 4; + text_marker.pose = points.at(prep_idx).point.pose; + text_marker.pose.position.z += 2.0; + text_marker.text = fmt::format( + "vel: {vel:.3f}[m/s] | lon_acc: {lon_acc:.3f}[m/s2] | t: {time:.3f}[s] | L: {length:.3f}[m]", + fmt::arg("vel", info.velocity.prepare), + fmt::arg("lon_acc", info.longitudinal_acceleration.prepare), + fmt::arg("time", info.duration.prepare), fmt::arg("length", info.length.prepare)); + marker_array.markers.push_back(text_marker); + + const auto lc_idx = points.size() / 2; + text_marker.id = ++id; + text_marker.pose = points.at(lc_idx).point.pose; + text_marker.text = fmt::format( + "type: {type} | vel: {vel:.3f}[m/s] | lon_acc: {lon_acc:.3f}[m/s2] | lat_acc: " + "{lat_acc:.3f}[m/s2] | t: " + "{time:.3f}[s] | L: {length:.3f}[m]", + fmt::arg("type", magic_enum::enum_name(lc_path.type)), + fmt::arg("vel", info.velocity.lane_changing), + fmt::arg("lon_acc", info.longitudinal_acceleration.lane_changing), + fmt::arg("lat_acc", info.lateral_acceleration), fmt::arg("time", info.duration.lane_changing), + fmt::arg("length", info.length.lane_changing)); + marker_array.markers.push_back(text_marker); + marker_array.markers.push_back(marker); } return marker_array; @@ -171,43 +199,78 @@ MarkerArray ShowLaneChangeMetricsInfo( const Debug & debug_data, const geometry_msgs::msg::Pose & pose) { MarkerArray marker_array; - if (debug_data.lane_change_metrics.empty()) { - return marker_array; - } auto text_marker = createDefaultMarker( "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "sampling_metrics", 0, Marker::TEXT_VIEW_FACING, createMarkerScale(0.6, 0.6, 0.6), colors::yellow()); text_marker.pose = autoware::universe_utils::calcOffsetPose(pose, 10.0, 15.0, 0.0); - text_marker.text = - fmt::format("{:<12}", "") + fmt::format("{:^18}|", "lat_accel[m/s2]") + - fmt::format("{:^18}|", "lon_accel[m/s2]") + fmt::format("{:^17}|", "velocity[m/s]") + - fmt::format("{:^15}|", "duration[s]") + fmt::format("{:^15}|", "length[m]") + - fmt::format("{:^20}|", "max_length_th[m]") + fmt::format("{:^15}\n", "path_index"); - for (const auto & metrics : debug_data.lane_change_metrics) { - text_marker.text += fmt::format("{:-<190}\n", ""); - const auto & p_m = metrics.prep_metric; - text_marker.text += - fmt::format("{:<17}", "prep_metrics:") + fmt::format("{:^10.3f}", p_m.lat_accel) + - fmt::format("{:^21.3f}", p_m.actual_lon_accel) + fmt::format("{:^12.3f}", p_m.velocity) + - fmt::format("{:^15.3f}", p_m.duration) + fmt::format("{:^15.3f}", p_m.length) + - fmt::format("{:^17.3f}", metrics.max_prepare_length) + fmt::format("{:^15}\n", "-"); - text_marker.text += fmt::format("{:<20}\n", "lc_metrics:"); - for (const auto & lc_m : metrics.lc_metrics) { - const auto & metric = lc_m.first; - const auto path_index = lc_m.second < 0 ? "-" : std::to_string(lc_m.second); - text_marker.text += fmt::format("{:<15}", "") + fmt::format("{:^10.3f}", metric.lat_accel) + - fmt::format("{:^21.3f}", metric.actual_lon_accel) + - fmt::format("{:^12.3f}", metric.velocity) + - fmt::format("{:^15.3f}", metric.duration) + - fmt::format("{:^15.3f}", metric.length) + - fmt::format("{:^17.3f}", metrics.max_lane_changing_length) + - fmt::format("{:^15}\n", path_index); + if (!debug_data.lane_change_metrics.empty()) { + text_marker.text = + fmt::format("{:<12}", "") + fmt::format("{:^18}|", "lat_accel[m/s2]") + + fmt::format("{:^18}|", "lon_accel[m/s2]") + fmt::format("{:^17}|", "velocity[m/s]") + + fmt::format("{:^15}|", "duration[s]") + fmt::format("{:^15}|", "length[m]") + + fmt::format("{:^20}|", "max_length_th[m]") + fmt::format("{:^15}\n", "path_index"); + for (const auto & metrics : debug_data.lane_change_metrics) { + text_marker.text += fmt::format("{:-<190}\n", ""); + const auto & p_m = metrics.prep_metric; + text_marker.text += + fmt::format("{:<17}", "prep_metrics:") + fmt::format("{:^10.3f}", p_m.lat_accel) + + fmt::format("{:^21.3f}", p_m.actual_lon_accel) + fmt::format("{:^12.3f}", p_m.velocity) + + fmt::format("{:^15.3f}", p_m.duration) + fmt::format("{:^15.3f}", p_m.length) + + fmt::format("{:^17.3f}", metrics.max_prepare_length) + fmt::format("{:^15}\n", "-"); + text_marker.text += fmt::format("{:<20}\n", "lc_metrics:"); + for (const auto & lc_m : metrics.lc_metrics) { + const auto & metric = lc_m.first; + const auto path_index = lc_m.second < 0 ? "-" : std::to_string(lc_m.second); + text_marker.text += fmt::format("{:<15}", "") + fmt::format("{:^10.3f}", metric.lat_accel) + + fmt::format("{:^21.3f}", metric.actual_lon_accel) + + fmt::format("{:^12.3f}", metric.velocity) + + fmt::format("{:^15.3f}", metric.duration) + + fmt::format("{:^15.3f}", metric.length) + + fmt::format("{:^17.3f}", metrics.max_lane_changing_length) + + fmt::format("{:^15}\n", path_index); + } } + marker_array.markers.push_back(text_marker); + } + + if (!debug_data.frenet_states.empty()) { + text_marker.text = fmt::format("{:<12}", "") + fmt::format("{:^18}|", "lon_accel[m/s2]") + + fmt::format("{:^17}|", "lon_vel[m/s]") + + fmt::format("{:^15}|", "duration[s]") + fmt::format("{:^15}|", "length[m]") + + fmt::format("{:^17}|", "lat_accel[m/s2]") + + fmt::format("{:^15}|", "lat_vel[m/s2]") + fmt::format("{:^15}|", "s[m]") + + fmt::format("{:^15}|", "d[m]") + fmt::format("{:^20}\n", "max_length_th[m]"); + for (const auto & metrics : debug_data.frenet_states) { + text_marker.text += fmt::format("{:-<250}\n", ""); + const auto & p_m = metrics.prep_metric; + const auto max_len = metrics.max_lane_changing_length; + text_marker.text += + fmt::format("{:<17}", "prep_metrics:") + fmt::format("{:^13.3f}", p_m.actual_lon_accel) + + fmt::format("{:^15.3f}", p_m.velocity) + fmt::format("{:^15.3f}", p_m.duration) + + fmt::format("{:^12.3f}", p_m.length) + + fmt::format("{:^13}", "") + // Empty string for lat_accel + fmt::format("{:^13}", "") + // Empty string for lat_vel + fmt::format("{:^15}", "") + // Empty string for s + fmt::format("{:^15}", "") + // Empty string for d // Empty string for d + fmt::format("{:^20.3f}\n", max_len); // Empty string for max_length_t + const auto & lc_m = metrics.sampling_parameter.target_state; // Assuming lc_metric exists + const auto duration = metrics.sampling_parameter.target_duration; + text_marker.text += + fmt::format("{:<17}", "frenet_state:") + + fmt::format("{:^15.3f}", lc_m.longitudinal_acceleration) + + fmt::format("{:^13.3f}", lc_m.longitudinal_velocity) + fmt::format("{:^17.3f}", duration) + + fmt::format("{:^10.3f}", lc_m.position.s) + + fmt::format("{:^19.3f}", lc_m.lateral_acceleration) + + fmt::format("{:^10.3f}", lc_m.lateral_velocity) + + fmt::format("{:^18.3f}", lc_m.position.s) + fmt::format("{:^15.3f}", lc_m.position.d) + + fmt::format("{:^16.3f}\n", max_len); // Empty string for max_length_t + } + + marker_array.markers.push_back(text_marker); } - marker_array.markers.push_back(text_marker); return marker_array; } diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/path.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/path.cpp index 44ee1624f0f51..df45da3f08fa1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/path.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/path.cpp @@ -15,17 +15,22 @@ #include "autoware/behavior_path_lane_change_module/utils/path.hpp" #include "autoware/behavior_path_lane_change_module/structs/data.hpp" +#include "autoware/behavior_path_lane_change_module/utils/calculation.hpp" #include "autoware/behavior_path_lane_change_module/utils/utils.hpp" #include "autoware/behavior_path_planner_common/utils/path_utils.hpp" #include "autoware/behavior_path_planner_common/utils/utils.hpp" #include #include +#include #include +#include #include #include #include +#include + #include #include #include @@ -42,8 +47,22 @@ using autoware::behavior_path_planner::lane_change::LCParamPtr; using autoware::behavior_path_planner::LaneChangePhaseMetrics; using autoware::behavior_path_planner::ShiftLine; +using autoware::behavior_path_planner::lane_change::TrajectoryGroup; +using autoware::frenet_planner::FrenetState; +using autoware::frenet_planner::SamplingParameters; +using autoware::route_handler::Direction; +using autoware::sampler_common::FrenetPoint; +using autoware::sampler_common::transform::Spline2D; +using autoware::universe_utils::LineString2d; +using autoware::universe_utils::Point2d; using geometry_msgs::msg::Pose; +template +T sign(const Direction direction) +{ + return static_cast(direction == Direction::LEFT ? 1.0 : -1.0); +} + double calc_resample_interval( const double lane_changing_length, const double lane_changing_velocity) { @@ -53,7 +72,7 @@ double calc_resample_interval( lane_changing_length / min_resampling_points, lane_changing_velocity * resampling_dt); } -PathWithLaneId get_reference_path_from_target_Lane( +PathWithLaneId get_reference_path_from_target_lane( const CommonDataPtr & common_data_ptr, const Pose & lane_changing_start_pose, const double lane_changing_length, const double resample_interval) { @@ -146,11 +165,197 @@ std::optional exceed_yaw_threshold( } return std::nullopt; } + +Spline2D init_reference_spline(const std::vector & target_lanes_ref_path) +{ + std::vector xs; + std::vector ys; + xs.reserve(target_lanes_ref_path.size()); + ys.reserve(target_lanes_ref_path.size()); + for (const auto & p : target_lanes_ref_path) { + xs.push_back(p.point.pose.position.x); + ys.push_back(p.point.pose.position.y); + } + + return {xs, ys}; +} + +FrenetState init_frenet_state( + const FrenetPoint & start_position, const LaneChangePhaseMetrics & prepare_metrics) +{ + FrenetState initial_state; + initial_state.position = start_position; + initial_state.longitudinal_velocity = prepare_metrics.velocity; + initial_state.lateral_velocity = + 0.0; // TODO(Maxime): this can be sampled if we want but it would impact the LC duration + initial_state.longitudinal_acceleration = prepare_metrics.sampled_lon_accel; + initial_state.lateral_acceleration = prepare_metrics.lat_accel; + return initial_state; +} + +std::optional init_sampling_parameters( + const CommonDataPtr & common_data_ptr, const LaneChangePhaseMetrics & prepare_metrics, + const FrenetState & initial_state, const Spline2D & ref_spline, const Pose & lc_start_pose) +{ + const auto & trajectory = common_data_ptr->lc_param_ptr->trajectory; + const auto min_lc_vel = trajectory.min_lane_changing_velocity; + const auto [min_lateral_acc, max_lateral_acc] = + trajectory.lat_acc_map.find(std::max(min_lc_vel, prepare_metrics.velocity)); + const auto duration = autoware::motion_utils::calc_shift_time_from_jerk( + std::abs(initial_state.position.d), trajectory.lateral_jerk, max_lateral_acc); + const auto final_velocity = + std::max(min_lc_vel, prepare_metrics.velocity + prepare_metrics.sampled_lon_accel * duration); + const auto lc_length = duration * (prepare_metrics.velocity + final_velocity) * 0.5; + const auto target_s = initial_state.position.s + lc_length; + const auto initial_yaw = tf2::getYaw(lc_start_pose.orientation); + const auto target_lat_vel = + (1.0 - ref_spline.curvature(target_s + 1e-3) * initial_state.position.d) * + std::tan(initial_yaw - ref_spline.yaw(target_s)); + + if (std::isnan(target_lat_vel)) { + return std::nullopt; + } + + SamplingParameters sampling_parameters; + const auto & safety = common_data_ptr->lc_param_ptr->safety; + sampling_parameters.resolution = safety.collision_check.prediction_time_resolution; + sampling_parameters.parameters.emplace_back(); + sampling_parameters.parameters.back().target_duration = duration; + sampling_parameters.parameters.back().target_state.position = {target_s, 0.0}; + // TODO(Maxime): not sure if we should use curvature at initial or target s + sampling_parameters.parameters.back().target_state.lateral_velocity = + sign(common_data_ptr->direction) * target_lat_vel; + sampling_parameters.parameters.back().target_state.lateral_acceleration = 0.0; + sampling_parameters.parameters.back().target_state.longitudinal_velocity = final_velocity; + sampling_parameters.parameters.back().target_state.longitudinal_acceleration = + prepare_metrics.sampled_lon_accel; + return sampling_parameters; +} + +std::vector calc_curvatures( + const std::vector & points, const Pose & current_pose) +{ + const auto nearest_segment_idx = + autoware::motion_utils::findNearestSegmentIndex(points, current_pose.position); + + // Ignore all path points behind ego vehicle. + if (points.size() <= nearest_segment_idx + 2) { + return {}; + } + + std::vector curvatures; + curvatures.reserve(points.size() - nearest_segment_idx + 2); + for (const auto & [p1, p2, p3] : ranges::views::zip( + points | ranges::views::drop(nearest_segment_idx), + points | ranges::views::drop(nearest_segment_idx + 1), + points | ranges::views::drop(nearest_segment_idx + 2))) { + const auto point1 = autoware::universe_utils::getPoint(p1); + const auto point2 = autoware::universe_utils::getPoint(p2); + const auto point3 = autoware::universe_utils::getPoint(p3); + + curvatures.push_back(autoware::universe_utils::calcCurvature(point1, point2, point3)); + } + + return curvatures; +} + +double calc_average_curvature(const std::vector & curvatures) +{ + const auto filter_zeros = [](const auto & k) { return k != 0.0; }; + auto filtered_k = curvatures | ranges::views::filter(filter_zeros); + if (filtered_k.empty()) { + return 0.0; + } + const auto sums_of_curvatures = [](float sum, const double k) { return sum + std::abs(k); }; + const auto sum_of_k = ranges::accumulate(filtered_k, 0.0, sums_of_curvatures); + const auto count_k = static_cast(ranges::distance(filtered_k)); + return sum_of_k / count_k; +} + +LineString2d get_linestring_bound(const lanelet::ConstLanelets & lanes, const Direction direction) +{ + LineString2d line_string; + const auto & get_bound = [&](const lanelet::ConstLanelet & lane) { + return (direction == Direction::LEFT) ? lane.leftBound2d() : lane.rightBound2d(); + }; + + const auto reserve_size = ranges::accumulate( + lanes, 0UL, + [&](auto sum, const lanelet::ConstLanelet & lane) { return sum + get_bound(lane).size(); }); + line_string.reserve(reserve_size); + for (const auto & lane : lanes) { + ranges::for_each(get_bound(lane), [&line_string](const auto & point) { + boost::geometry::append(line_string, Point2d(point.x(), point.y())); + }); + } + return line_string; +} + +Point2d shift_point(const Point2d & p1, const Point2d & p2, const double offset) +{ + // Calculate the perpendicular vector + double dx = p2.x() - p1.x(); + double dy = p2.y() - p1.y(); + double length = std::sqrt(dx * dx + dy * dy); + + // Normalize and find the perpendicular direction + double nx = -dy / length; + double ny = dx / length; + + return {p1.x() + nx * offset, p1.y() + ny * offset}; +} + +bool check_out_of_bound_paths( + const CommonDataPtr & common_data_ptr, const std::vector & lane_changing_poses, + const LineString2d & lane_boundary, const Direction direction) +{ + const auto distance = (0.5 * common_data_ptr->bpp_param_ptr->vehicle_width + 0.1); + const auto offset = sign(direction) * distance; // invert direction + if (lane_changing_poses.size() <= 2) { + return true; // Remove candidates with insufficient poses + } + + LineString2d path_ls; + path_ls.reserve(lane_changing_poses.size()); + + const auto segments = lane_changing_poses | ranges::views::sliding(2); + ranges::for_each(segments | ranges::views::drop(1), [&](const auto & segment) { + const auto & p1 = segment[0].position; + const auto & p2 = segment[1].position; + boost::geometry::append(path_ls, shift_point({p2.x, p2.y}, {p1.x, p1.y}, offset)); + }); + + return boost::geometry::disjoint(path_ls, lane_boundary); // Remove if disjoint +} + +double calc_limit(const CommonDataPtr & common_data_ptr, const Pose & lc_end_pose) +{ + const auto dist_to_target_end = std::invoke([&]() { + if (common_data_ptr->lanes_ptr->target_lane_in_goal_section) { + return autoware::motion_utils::calcSignedArcLength( + common_data_ptr->target_lanes_path.points, lc_end_pose.position, + common_data_ptr->route_handler_ptr->getGoalPose().position); + } + return autoware::motion_utils::calcSignedArcLength( + common_data_ptr->target_lanes_path.points, lc_end_pose.position, + common_data_ptr->target_lanes_path.points.back().point.pose.position); + }); + + // v2 = u2 + 2ad + // u = sqrt(2ad) + return std::clamp( + std::sqrt( + std::abs(2.0 * common_data_ptr->bpp_param_ptr->min_acc * std::max(dist_to_target_end, 0.0))), + common_data_ptr->lc_param_ptr->trajectory.min_lane_changing_velocity, + common_data_ptr->bpp_param_ptr->max_vel); +} + }; // namespace namespace autoware::behavior_path_planner::utils::lane_change { using behavior_path_planner::lane_change::CommonDataPtr; +using behavior_path_planner::lane_change::PathType; bool get_prepare_segment( const CommonDataPtr & common_data_ptr, const PathWithLaneId & prev_module_path, @@ -187,7 +392,17 @@ bool get_prepare_segment( throw std::logic_error("lane change start is behind target lanelet!"); } - return true; + const auto curvatures = calc_curvatures(prepare_segment.points, common_data_ptr->get_ego_pose()); + + // curvatures may be empty if ego is near the terminal start of the path. + if (curvatures.empty()) { + return true; + } + + const auto average_curvature = calc_average_curvature(curvatures); + + RCLCPP_DEBUG(get_logger(), "average curvature: %.3f", average_curvature); + return average_curvature <= common_data_ptr->lc_param_ptr->trajectory.th_prepare_curvature; } LaneChangePath get_candidate_path( @@ -205,7 +420,7 @@ LaneChangePath get_candidate_path( } const auto & lc_start_pose = prep_segment.points.back().point.pose; - const auto target_lane_reference_path = get_reference_path_from_target_Lane( + const auto target_lane_reference_path = get_reference_path_from_target_lane( common_data_ptr, lc_start_pose, lc_metric.length, resample_interval); if (target_lane_reference_path.points.empty()) { @@ -259,10 +474,14 @@ LaneChangePath construct_candidate_path( throw std::logic_error("Lane change end idx not found on target path."); } + std::vector prev_ids; + std::vector prev_sorted_ids; for (size_t i = 0; i < shifted_path.path.points.size(); ++i) { auto & point = shifted_path.path.points.at(i); if (i < *lc_end_idx_opt) { - point.lane_ids = replaceWithSortedIds(point.lane_ids, sorted_lane_ids); + const auto & current_ids = point.lane_ids; + point.lane_ids = + replace_with_sorted_ids(current_ids, sorted_lane_ids, prev_ids, prev_sorted_ids); point.point.longitudinal_velocity_mps = std::min( point.point.longitudinal_velocity_mps, static_cast(terminal_lane_changing_velocity)); continue; @@ -286,7 +505,251 @@ LaneChangePath construct_candidate_path( candidate_path.path = utils::combinePath(prepare_segment, shifted_path.path); candidate_path.shifted_path = shifted_path; candidate_path.info = lane_change_info; + candidate_path.type = PathType::ConstantJerk; return candidate_path; } + +std::vector generate_frenet_candidates( + const CommonDataPtr & common_data_ptr, const PathWithLaneId & prev_module_path, + const std::vector & prep_metrics) +{ + std::vector trajectory_groups; + universe_utils::StopWatch sw; + + const auto & transient_data = common_data_ptr->transient_data; + const auto & current_lanes = common_data_ptr->lanes_ptr->current; + const auto & target_lanes = common_data_ptr->lanes_ptr->target; + const auto direction = common_data_ptr->direction; + const auto current_lane_boundary = get_linestring_bound(current_lanes, direction); + + for (const auto & metric : prep_metrics) { + PathWithLaneId prepare_segment; + try { + if (!utils::lane_change::get_prepare_segment( + common_data_ptr, prev_module_path, metric.length, prepare_segment)) { + RCLCPP_DEBUG(get_logger(), "Reject: failed to get valid prepare segment!"); + continue; + } + } catch (const std::exception & e) { + RCLCPP_WARN(get_logger(), "%s", e.what()); + break; + } + const auto lc_start_pose = prepare_segment.points.back().point.pose; + + const auto dist_to_end_from_lc_start = + calculation::calc_dist_from_pose_to_terminal_end( + common_data_ptr, target_lanes, lc_start_pose) - + common_data_ptr->lc_param_ptr->lane_change_finish_judge_buffer; + const auto max_lc_len = transient_data.lane_changing_length.max; + const auto max_lane_changing_length = std::min(dist_to_end_from_lc_start, max_lc_len); + + constexpr auto resample_interval = 0.5; + const auto target_lane_reference_path = get_reference_path_from_target_lane( + common_data_ptr, lc_start_pose, max_lane_changing_length, resample_interval); + if (target_lane_reference_path.points.empty()) { + continue; + } + + std::vector target_ref_path_sums{0.0}; + target_ref_path_sums.reserve(target_lane_reference_path.points.size() - 1); + double ref_s = 0.0; + for (auto it = target_lane_reference_path.points.begin(); + std::next(it) != target_lane_reference_path.points.end(); ++it) { + ref_s += universe_utils::calcDistance2d(*it, *std::next(it)); + target_ref_path_sums.push_back(ref_s); + } + + const auto reference_spline = init_reference_spline(target_lane_reference_path.points); + + const auto initial_state = init_frenet_state( + reference_spline.frenet({lc_start_pose.position.x, lc_start_pose.position.y}), metric); + + RCLCPP_DEBUG( + get_logger(), "Initial state [s=%2.2f, d=%2.2f, s'=%2.2f, d'=%2.2f, s''=%2.2f, d''=%2.2f]", + initial_state.position.s, initial_state.position.d, initial_state.longitudinal_velocity, + initial_state.lateral_velocity, initial_state.longitudinal_acceleration, + initial_state.lateral_acceleration); + + const auto sampling_parameters_opt = init_sampling_parameters( + common_data_ptr, metric, initial_state, reference_spline, lc_start_pose); + + if (!sampling_parameters_opt) { + continue; + } + + auto frenet_trajectories = frenet_planner::generateTrajectories( + reference_spline, initial_state, *sampling_parameters_opt); + + trajectory_groups.reserve(trajectory_groups.size() + frenet_trajectories.size()); + for (const auto & traj : frenet_trajectories) { + if (!trajectory_groups.empty()) { + const auto diff = std::abs( + traj.frenet_points.back().s - + trajectory_groups.back().lane_changing.frenet_points.back().s); + if (diff < common_data_ptr->lc_param_ptr->trajectory.th_lane_changing_length_diff) { + continue; + } + } + + const auto out_of_bound = + check_out_of_bound_paths(common_data_ptr, traj.poses, current_lane_boundary, direction); + + if (out_of_bound) { + continue; + } + + trajectory_groups.emplace_back( + prepare_segment, target_lane_reference_path, target_ref_path_sums, metric, traj, + initial_state, max_lane_changing_length); + } + } + + const auto limit_vel = [&](TrajectoryGroup & group) { + const auto max_vel = calc_limit(common_data_ptr, group.lane_changing.poses.back()); + for (auto & vel : group.lane_changing.longitudinal_velocities) { + vel = std::clamp(vel, 0.0, max_vel); + } + }; + + ranges::for_each(trajectory_groups, limit_vel); + + ranges::sort(trajectory_groups, [&](const auto & p1, const auto & p2) { + return calc_average_curvature(p1.lane_changing.curvatures) < + calc_average_curvature(p2.lane_changing.curvatures); + }); + + return trajectory_groups; +} + +std::optional get_candidate_path( + const TrajectoryGroup & trajectory_group, const CommonDataPtr & common_data_ptr, + const std::vector> & sorted_lane_ids) +{ + if (trajectory_group.lane_changing.frenet_points.empty()) { + return std::nullopt; + } + + ShiftedPath shifted_path; + std::vector prev_ids; + std::vector prev_sorted_ids; + const auto & lane_changing_candidate = trajectory_group.lane_changing; + const auto & target_lane_ref_path = trajectory_group.target_lane_ref_path; + const auto & prepare_segment = trajectory_group.prepare; + const auto & prepare_metric = trajectory_group.prepare_metric; + const auto & initial_state = trajectory_group.initial_state; + const auto & target_ref_sums = trajectory_group.target_lane_ref_path_dist; + auto zipped_candidates = ranges::views::zip( + lane_changing_candidate.poses, lane_changing_candidate.frenet_points, + lane_changing_candidate.longitudinal_velocities, lane_changing_candidate.lateral_velocities, + lane_changing_candidate.curvatures); + + shifted_path.path.points.reserve(zipped_candidates.size()); + shifted_path.shift_length.reserve(zipped_candidates.size()); + for (const auto & [pose, frenet_point, longitudinal_velocity, lateral_velocity, curvature] : + zipped_candidates) { + // Find the reference index + const auto & s = frenet_point.s; + auto ref_i_itr = std::find_if( + target_ref_sums.begin(), target_ref_sums.end(), + [s](const double ref_s) { return ref_s > s; }); + auto ref_i = std::distance(target_ref_sums.begin(), ref_i_itr); + + PathPointWithLaneId point; + point.point.pose = pose; + point.point.longitudinal_velocity_mps = static_cast(longitudinal_velocity); + point.point.lateral_velocity_mps = static_cast(lateral_velocity); + point.point.heading_rate_rps = static_cast(curvature); + point.point.pose.position.z = target_lane_ref_path.points[ref_i].point.pose.position.z; + const auto & current_ids = target_lane_ref_path.points[ref_i].lane_ids; + point.lane_ids = + replace_with_sorted_ids(current_ids, sorted_lane_ids, prev_ids, prev_sorted_ids); + + // Add to shifted path + shifted_path.shift_length.push_back(frenet_point.d); + shifted_path.path.points.push_back(point); + } + + if (shifted_path.path.points.empty()) { + return std::nullopt; + } + + for (auto & point : shifted_path.path.points) { + point.point.longitudinal_velocity_mps = std::min( + point.point.longitudinal_velocity_mps, + static_cast(shifted_path.path.points.back().point.longitudinal_velocity_mps)); + } + + const auto th_yaw_diff_deg = common_data_ptr->lc_param_ptr->frenet.th_yaw_diff_deg; + if ( + const auto yaw_diff_opt = exceed_yaw_threshold( + prepare_segment, shifted_path.path, autoware::universe_utils::deg2rad(th_yaw_diff_deg))) { + const auto yaw_diff_deg = autoware::universe_utils::rad2deg(yaw_diff_opt.value()); + const auto err_msg = fmt::format( + "Excessive yaw difference {yaw_diff:2.2f}[deg]. The threshold is {th_yaw_diff:2.2f}[deg].", + fmt::arg("yaw_diff", yaw_diff_deg), fmt::arg("th_yaw_diff", th_yaw_diff_deg)); + throw std::logic_error(err_msg); + } + + LaneChangeInfo info; + info.longitudinal_acceleration = { + prepare_metric.actual_lon_accel, lane_changing_candidate.longitudinal_accelerations.front()}; + info.velocity = {prepare_metric.velocity, initial_state.longitudinal_velocity}; + info.duration = { + prepare_metric.duration, lane_changing_candidate.sampling_parameter.target_duration}; + info.length = {prepare_metric.length, lane_changing_candidate.lengths.back()}; + info.lane_changing_start = prepare_segment.points.back().point.pose; + info.lane_changing_end = lane_changing_candidate.poses.back(); + + ShiftLine sl; + + sl.start = lane_changing_candidate.poses.front(); + sl.end = lane_changing_candidate.poses.back(); + sl.start_shift_length = 0.0; + sl.end_shift_length = initial_state.position.d; + sl.start_idx = 0UL; + sl.end_idx = shifted_path.shift_length.size() - 1; + + info.shift_line = sl; + info.terminal_lane_changing_velocity = lane_changing_candidate.longitudinal_velocities.back(); + info.lateral_acceleration = lane_changing_candidate.lateral_accelerations.front(); + + LaneChangePath candidate_path; + candidate_path.path = utils::combinePath(prepare_segment, shifted_path.path); + candidate_path.info = info; + candidate_path.shifted_path = shifted_path; + candidate_path.frenet_path = trajectory_group; + candidate_path.type = PathType::FrenetPlanner; + + return candidate_path; +} + +void append_target_ref_to_candidate( + LaneChangePath & frenet_candidate, const double th_curvature_smoothing) +{ + const auto & target_lane_ref_path = frenet_candidate.frenet_path.target_lane_ref_path.points; + const auto & lc_end_pose = frenet_candidate.info.lane_changing_end; + const auto lc_end_idx = + motion_utils::findNearestIndex(target_lane_ref_path, lc_end_pose.position); + auto & candidate_path = frenet_candidate.path.points; + if (target_lane_ref_path.size() <= lc_end_idx + 2) { + return; + } + const auto add_size = target_lane_ref_path.size() - (lc_end_idx + 1); + candidate_path.reserve(candidate_path.size() + add_size); + const auto & points = target_lane_ref_path; + for (const auto & [p2, p3] : ranges::views::zip( + points | ranges::views::drop(lc_end_idx + 1), + points | ranges::views::drop(lc_end_idx + 2))) { + const auto point1 = autoware::universe_utils::getPoint(candidate_path.back().point.pose); + const auto point2 = autoware::universe_utils::getPoint(p2); + const auto point3 = autoware::universe_utils::getPoint(p3); + const auto curvature = + std::abs(autoware::universe_utils::calcCurvature(point1, point2, point3)); + if (curvature < th_curvature_smoothing) { + candidate_path.push_back(p2); + } + } + candidate_path.push_back(target_lane_ref_path.back()); +} } // namespace autoware::behavior_path_planner::utils::lane_change diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp index 9360435891632..9002270185847 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp @@ -24,12 +24,18 @@ #include "autoware/object_recognition_utils/predicted_path_utils.hpp" #include "autoware/universe_utils/math/unit_conversion.hpp" +// for the geometry types +#include +#include +// for the svg mapper #include #include #include #include #include #include +#include +#include #include #include #include @@ -40,9 +46,10 @@ #include #include -#include - +#include #include +#include +#include #include #include @@ -64,9 +71,11 @@ namespace autoware::behavior_path_planner::utils::lane_change { using autoware::route_handler::RouteHandler; using autoware::universe_utils::LineString2d; +using autoware::universe_utils::Point2d; using autoware::universe_utils::Polygon2d; using autoware_perception_msgs::msg::ObjectClassification; using autoware_perception_msgs::msg::PredictedObjects; +using behavior_path_planner::lane_change::PathType; using geometry_msgs::msg::Pose; using tier4_planning_msgs::msg::PathWithLaneId; @@ -382,18 +391,26 @@ std::vector> get_sorted_lane_ids(const CommonDataPtr & comm return sorted_lane_ids; } -std::vector replaceWithSortedIds( - const std::vector & original_lane_ids, - const std::vector> & sorted_lane_ids) +std::vector replace_with_sorted_ids( + const std::vector & current_lane_ids, + const std::vector> & sorted_lane_ids, std::vector & prev_lane_ids, + std::vector & prev_sorted_lane_ids) { - for (const auto original_id : original_lane_ids) { + if (current_lane_ids == prev_lane_ids) { + return prev_sorted_lane_ids; + } + + for (const auto original_id : current_lane_ids) { for (const auto & sorted_id : sorted_lane_ids) { if (std::find(sorted_id.cbegin(), sorted_id.cend(), original_id) != sorted_id.cend()) { - return sorted_id; + prev_lane_ids = current_lane_ids; + prev_sorted_lane_ids = sorted_id; + return prev_sorted_lane_ids; } } } - return original_lane_ids; + + return current_lane_ids; } CandidateOutput assignToCandidate( @@ -475,6 +492,7 @@ std::vector convert_to_predicted_path( 0.5 * lane_changing_acceleration * delta_t * delta_t + offset; const auto pose = autoware::motion_utils::calcInterpolatedPose( path.points, vehicle_pose_frenet.length + length); + predicted_path.emplace_back(t, pose, velocity); } @@ -1127,6 +1145,10 @@ std::vector> convert_to_predicted_paths( const auto acc_resolution = (min_acc - lane_changing_acc) / static_cast(sampling_num); const auto ego_predicted_path = [&](size_t n) { + if (lane_change_path.type == PathType::FrenetPlanner) { + return convert_to_predicted_path( + common_data_ptr, lane_change_path.frenet_path, deceleration_sampling_num); + } auto acc = lane_changing_acc + static_cast(n) * acc_resolution; return utils::lane_change::convert_to_predicted_path(common_data_ptr, lane_change_path, acc); }; @@ -1135,6 +1157,48 @@ std::vector> convert_to_predicted_paths( ranges::to(); } +std::vector convert_to_predicted_path( + const CommonDataPtr & common_data_ptr, const lane_change::TrajectoryGroup & frenet_candidate, + [[maybe_unused]] const size_t deceleration_sampling_num) +{ + const auto initial_velocity = common_data_ptr->get_ego_speed(); + const auto prepare_time = frenet_candidate.prepare_metric.duration; + const auto resolution = + common_data_ptr->lc_param_ptr->safety.collision_check.prediction_time_resolution; + const auto prepare_acc = frenet_candidate.prepare_metric.sampled_lon_accel; + std::vector predicted_path; + const auto & path = frenet_candidate.prepare.points; + const auto & vehicle_pose = common_data_ptr->get_ego_pose(); + const auto & bpp_param_ptr = common_data_ptr->bpp_param_ptr; + const auto nearest_seg_idx = + autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + path, vehicle_pose, bpp_param_ptr->ego_nearest_dist_threshold, + bpp_param_ptr->ego_nearest_yaw_threshold); + + const auto vehicle_pose_frenet = + convertToFrenetPoint(path, vehicle_pose.position, nearest_seg_idx); + + for (double t = 0.0; t < prepare_time; t += resolution) { + const auto velocity = + std::clamp(initial_velocity + prepare_acc * t, 0.0, frenet_candidate.prepare_metric.velocity); + const auto length = initial_velocity * t + 0.5 * prepare_acc * t * t; + const auto pose = + autoware::motion_utils::calcInterpolatedPose(path, vehicle_pose_frenet.length + length); + predicted_path.emplace_back(t, pose, velocity); + } + + const auto & poses = frenet_candidate.lane_changing.poses; + const auto & velocities = frenet_candidate.lane_changing.longitudinal_velocities; + const auto & times = frenet_candidate.lane_changing.times; + + for (const auto [t, pose, velocity] : + ranges::views::zip(times, poses, velocities) | ranges::views::drop(1)) { + predicted_path.emplace_back(prepare_time + t, pose, velocity); + } + + return predicted_path; +} + bool is_valid_start_point(const lane_change::CommonDataPtr & common_data_ptr, const Pose & pose) { const lanelet::BasicPoint2d lc_start_point(pose.position.x, pose.position.y); diff --git a/planning/sampling_based_planner/autoware_frenet_planner/src/frenet_planner/frenet_planner.cpp b/planning/sampling_based_planner/autoware_frenet_planner/src/frenet_planner/frenet_planner.cpp index cab4acfbb8556..54d4bc2e90714 100644 --- a/planning/sampling_based_planner/autoware_frenet_planner/src/frenet_planner/frenet_planner.cpp +++ b/planning/sampling_based_planner/autoware_frenet_planner/src/frenet_planner/frenet_planner.cpp @@ -197,6 +197,15 @@ void calculateCartesian( trajectory.longitudinal_accelerations.push_back(0.0); trajectory.lateral_accelerations.push_back(0.0); } + for (auto i = 0UL; i < trajectory.points.size(); ++i) { + geometry_msgs::msg::Pose pose; + pose.position.x = trajectory.points[i].x(); + pose.position.y = trajectory.points[i].y(); + pose.position.z = 0.0; + pose.orientation = + autoware::universe_utils::createQuaternionFromRPY(0.0, 0.0, trajectory.yaws[i]); + trajectory.poses.push_back(pose); + } } } From 96998925ad72498c77e0e6a52f5132bb2cb8a92b Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Tue, 14 Jan 2025 17:23:20 +0900 Subject: [PATCH 190/334] fix(learning_based_vehicle_model): fix clang-diagnostic-delete-abstract-non-virtual-dtor (#9506) Signed-off-by: Y.Hisaki --- .../learning_based_vehicle_model/src/interconnected_model.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/simulator/learning_based_vehicle_model/src/interconnected_model.cpp b/simulator/learning_based_vehicle_model/src/interconnected_model.cpp index d2fef15aa4e88..e495aceb8da9c 100644 --- a/simulator/learning_based_vehicle_model/src/interconnected_model.cpp +++ b/simulator/learning_based_vehicle_model/src/interconnected_model.cpp @@ -79,8 +79,7 @@ void InterconnectedModel::addSubmodel( std::tuple submodel_desc) { const auto [lib_path, param_path, class_name] = submodel_desc; - auto new_model = new SimplePyModel(lib_path, param_path, class_name); - submodels.push_back(std::unique_ptr(new_model)); + submodels.emplace_back(std::make_unique(lib_path, param_path, class_name)); } void InterconnectedModel::initState(std::vector new_state) From 215cae29afaa5923e8c74e216d99e6549980990d Mon Sep 17 00:00:00 2001 From: Ismet Atabay <56237550+ismetatabay@users.noreply.github.com> Date: Tue, 14 Jan 2025 11:31:53 +0300 Subject: [PATCH 191/334] feat(remaining_distance_time_calculator): skip calculation during parking (#9013) Signed-off-by: ismetatabay --- .../README.md | 1 + ...aining_distance_time_calculator.launch.xml | 2 ++ ...emaining_distance_time_calculator_node.cpp | 21 ++++++++++++++++++- ...emaining_distance_time_calculator_node.hpp | 5 +++++ 4 files changed, 28 insertions(+), 1 deletion(-) diff --git a/planning/autoware_remaining_distance_time_calculator/README.md b/planning/autoware_remaining_distance_time_calculator/README.md index 694c6764de91c..c227b73b87448 100644 --- a/planning/autoware_remaining_distance_time_calculator/README.md +++ b/planning/autoware_remaining_distance_time_calculator/README.md @@ -8,6 +8,7 @@ This package aims to provide mission remaining distance and remaining time calcu - The calculations are activated once we have a route planned for a mission in Autoware. - The calculations are triggered timely based on the `update_rate` parameter. +- The calculations are skipped if the scenario is PARKING, and the remaining time and distance values are set to 0.0. ### Module Parameters diff --git a/planning/autoware_remaining_distance_time_calculator/launch/remaining_distance_time_calculator.launch.xml b/planning/autoware_remaining_distance_time_calculator/launch/remaining_distance_time_calculator.launch.xml index cfb456c57ca41..be7898bdd8913 100644 --- a/planning/autoware_remaining_distance_time_calculator/launch/remaining_distance_time_calculator.launch.xml +++ b/planning/autoware_remaining_distance_time_calculator/launch/remaining_distance_time_calculator.launch.xml @@ -4,6 +4,7 @@ + @@ -13,6 +14,7 @@ + diff --git a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp index 383e85731604e..7932a2531185f 100644 --- a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp +++ b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp @@ -37,6 +37,7 @@ RemainingDistanceTimeCalculatorNode::RemainingDistanceTimeCalculatorNode( : Node("remaining_distance_time_calculator", options), is_graph_ready_{false}, has_received_route_{false}, + has_received_scenario_{false}, velocity_limit_{99.99}, remaining_distance_{0.0}, remaining_time_{0.0} @@ -57,6 +58,8 @@ RemainingDistanceTimeCalculatorNode::RemainingDistanceTimeCalculatorNode( sub_planning_velocity_ = create_subscription( "/planning/scenario_planning/current_max_velocity", qos_transient_local, std::bind(&RemainingDistanceTimeCalculatorNode::on_velocity_limit, this, _1)); + sub_scenario_ = this->create_subscription( + "~/input/scenario", 1, std::bind(&RemainingDistanceTimeCalculatorNode::on_scenario, this, _1)); pub_mission_remaining_distance_time_ = create_publisher( "~/output/mission_remaining_distance_time", @@ -100,9 +103,25 @@ void RemainingDistanceTimeCalculatorNode::on_velocity_limit( } } +void RemainingDistanceTimeCalculatorNode::on_scenario( + const tier4_planning_msgs::msg::Scenario::ConstSharedPtr & msg) +{ + scenario_ = msg; + has_received_scenario_ = true; +} + void RemainingDistanceTimeCalculatorNode::on_timer() { - if (is_graph_ready_ && has_received_route_) { + if (!has_received_scenario_) { + return; + } + + // check if the scenario is parking or not + if (scenario_->current_scenario == tier4_planning_msgs::msg::Scenario::PARKING) { + remaining_distance_ = 0.0; + remaining_time_ = 0.0; + publish_mission_remaining_distance_time(); + } else if (is_graph_ready_ && has_received_route_) { calculate_remaining_distance(); calculate_remaining_time(); publish_mission_remaining_distance_time(); diff --git a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp index d6c900af4dfed..b7af8861bf524 100644 --- a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp +++ b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp @@ -24,6 +24,7 @@ #include #include #include +#include #include #include @@ -59,6 +60,7 @@ class RemainingDistanceTimeCalculatorNode : public rclcpp::Node rclcpp::Subscription::SharedPtr sub_map_; rclcpp::Subscription::SharedPtr sub_odometry_; rclcpp::Subscription::SharedPtr sub_planning_velocity_; + rclcpp::Subscription::SharedPtr sub_scenario_; rclcpp::Publisher::SharedPtr pub_mission_remaining_distance_time_; @@ -75,7 +77,9 @@ class RemainingDistanceTimeCalculatorNode : public rclcpp::Node geometry_msgs::msg::Pose current_vehicle_pose_; geometry_msgs::msg::Vector3 current_vehicle_velocity_; geometry_msgs::msg::Pose goal_pose_; + tier4_planning_msgs::msg::Scenario::ConstSharedPtr scenario_; bool has_received_route_; + bool has_received_scenario_; double velocity_limit_; double remaining_distance_; @@ -90,6 +94,7 @@ class RemainingDistanceTimeCalculatorNode : public rclcpp::Node void on_route(const LaneletRoute::ConstSharedPtr & msg); void on_map(const HADMapBin::ConstSharedPtr & msg); void on_velocity_limit(const VelocityLimit::ConstSharedPtr & msg); + void on_scenario(const tier4_planning_msgs::msg::Scenario::ConstSharedPtr & msg); /** * @brief calculate mission remaining distance From 36b74c23311d677c06600a55d37bfed36e01d163 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Tue, 14 Jan 2025 17:35:13 +0900 Subject: [PATCH 192/334] =?UTF-8?q?feat(autoware=5Fobject=5Fmerger):=20tie?= =?UTF-8?q?r4=5Fdebug=5Fmsgs=20changed=20to=20autoware=5Finternal=5Fdebug?= =?UTF-8?q?=5Fmsgs=20in=20fil=E2=80=A6=20(#9893)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files perception/autoware_object_merger Signed-off-by: vish0012 Co-authored-by: Taekjin LEE --- .../src/object_association_merger_node.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/autoware_object_merger/src/object_association_merger_node.cpp b/perception/autoware_object_merger/src/object_association_merger_node.cpp index 0e2b88f4aa566..40bdd0a7d6938 100644 --- a/perception/autoware_object_merger/src/object_association_merger_node.cpp +++ b/perception/autoware_object_merger/src/object_association_merger_node.cpp @@ -235,9 +235,9 @@ void ObjectAssociationMergerNode::objectsCallback( merged_object_pub_->publish(output_msg); published_time_publisher_->publish_if_subscribed(merged_object_pub_, output_msg.header.stamp); // publish processing time - processing_time_publisher_->publish( + processing_time_publisher_->publish( "debug/cyclic_time_ms", stop_watch_ptr_->toc("cyclic_time", true)); - processing_time_publisher_->publish( + processing_time_publisher_->publish( "debug/processing_time_ms", stop_watch_ptr_->toc("processing_time", true)); } } // namespace autoware::object_merger From 9c0e183d25c1a76a8091f7c210c95ac32f94d5f4 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> Date: Tue, 14 Jan 2025 17:50:46 +0900 Subject: [PATCH 193/334] feat(lane_change_module): add update paramter function for non defined paramters (#9887) * feat(lane_change_module): add new parameters for collision check and delay lane change functionality Signed-off-by: Kyoichi Sugahara * feat(lane_change_module): add validation for longitudinal and lateral acceleration sampling parameters Signed-off-by: Kyoichi Sugahara * feat(lane_change): update parameter handling and add lateral acceleration mapping Signed-off-by: Kyoichi Sugahara --------- Signed-off-by: Kyoichi Sugahara --- .../src/manager.cpp | 125 +++++++++++++++++- 1 file changed, 122 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp index 06a9d505f90ad..07b05ab0ea131 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp @@ -324,10 +324,12 @@ void LaneChangeModuleManager::updateModuleParams(const std::vectorlane_change_finish_judge_buffer); updateParam( parameters, ns + "enable_stopped_vehicle_buffer", p->enable_stopped_vehicle_buffer); - updateParam( parameters, ns + "finish_judge_lateral_threshold", p->th_finish_judge_lateral_diff); updateParam(parameters, ns + "publish_debug_marker", p->publish_debug_marker); + updateParam( + parameters, ns + "min_length_for_turn_signal_activation", + p->min_length_for_turn_signal_activation); } { @@ -338,8 +340,7 @@ void LaneChangeModuleManager::updateModuleParams(const std::vectortrajectory.min_prepare_duration); updateParam(parameters, ns + "lateral_jerk", p->trajectory.lateral_jerk); updateParam( - parameters, ns + ".min_lane_changing_velocity", p->trajectory.min_lane_changing_velocity); - // longitudinal acceleration + parameters, ns + "min_lane_changing_velocity", p->trajectory.min_lane_changing_velocity); updateParam( parameters, ns + "min_longitudinal_acc", p->trajectory.min_longitudinal_acc); updateParam( @@ -352,12 +353,22 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector(parameters, ns + "lon_acc_sampling_num", longitudinal_acc_sampling_num); if (longitudinal_acc_sampling_num > 0) { p->trajectory.lon_acc_sampling_num = longitudinal_acc_sampling_num; + } else { + RCLCPP_WARN_ONCE( + node_->get_logger(), + "Parameter 'lon_acc_sampling_num' is not updated because the value (%d) is not positive", + longitudinal_acc_sampling_num); } int lateral_acc_sampling_num = 0; updateParam(parameters, ns + "lat_acc_sampling_num", lateral_acc_sampling_num); if (lateral_acc_sampling_num > 0) { p->trajectory.lat_acc_sampling_num = lateral_acc_sampling_num; + } else { + RCLCPP_WARN_ONCE( + node_->get_logger(), + "Parameter 'lat_acc_sampling_num' is not updated because the value (%d) is not positive", + lateral_acc_sampling_num); } updateParam( @@ -380,6 +391,57 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector(parameters, ns + "right_offset", p->safety.lane_expansion_right_offset); } + { + const std::string ns = "lane_change.lateral_acceleration."; + std::vector velocity = p->trajectory.lat_acc_map.base_vel; + std::vector min_values = p->trajectory.lat_acc_map.base_min_acc; + std::vector max_values = p->trajectory.lat_acc_map.base_max_acc; + + updateParam>(parameters, ns + "velocity", velocity); + updateParam>(parameters, ns + "min_values", min_values); + updateParam>(parameters, ns + "max_values", max_values); + if ( + velocity.size() >= 2 && velocity.size() == min_values.size() && + velocity.size() == max_values.size()) { + LateralAccelerationMap lat_acc_map; + for (size_t i = 0; i < velocity.size(); ++i) { + lat_acc_map.add(velocity.at(i), min_values.at(i), max_values.at(i)); + } + p->trajectory.lat_acc_map = lat_acc_map; + } else { + RCLCPP_WARN_ONCE( + node_->get_logger(), + "Mismatched size for lateral acceleration. Expected size: %lu, but velocity: %lu, " + "min_values: %lu, max_values: %lu", + std::max(2ul, velocity.size()), velocity.size(), min_values.size(), max_values.size()); + } + } + + { + const std::string ns = "lane_change.collision_check."; + updateParam( + parameters, ns + "enable_for_prepare_phase.general_lanes", + p->safety.collision_check.enable_for_prepare_phase_in_general_lanes); + updateParam( + parameters, ns + "enable_for_prepare_phase.intersection", + p->safety.collision_check.enable_for_prepare_phase_in_intersection); + updateParam( + parameters, ns + "enable_for_prepare_phase.turns", + p->safety.collision_check.enable_for_prepare_phase_in_turns); + updateParam( + parameters, ns + "check_current_lanes", p->safety.collision_check.check_current_lane); + updateParam( + parameters, ns + "check_other_lanes", p->safety.collision_check.check_other_lanes); + updateParam( + parameters, ns + "use_all_predicted_paths", + p->safety.collision_check.use_all_predicted_paths); + updateParam( + parameters, ns + "prediction_time_resolution", + p->safety.collision_check.prediction_time_resolution); + updateParam( + parameters, ns + "yaw_diff_threshold", p->safety.collision_check.th_yaw_diff); + } + { const std::string ns = "lane_change.target_object."; updateParam(parameters, ns + "car", p->safety.target_object_types.check_car); @@ -407,6 +469,50 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector(parameters, ns + "stop_time", p->th_stop_time); } + auto update_rss_params = [¶meters](const std::string & prefix, auto & params) { + using autoware::universe_utils::updateParam; + updateParam( + parameters, prefix + "longitudinal_distance_min_threshold", + params.longitudinal_distance_min_threshold); + updateParam( + parameters, prefix + "longitudinal_velocity_delta_time", + params.longitudinal_velocity_delta_time); + updateParam( + parameters, prefix + "expected_front_deceleration", params.front_vehicle_deceleration); + updateParam( + parameters, prefix + "expected_rear_deceleration", params.rear_vehicle_deceleration); + updateParam( + parameters, prefix + "rear_vehicle_reaction_time", params.rear_vehicle_reaction_time); + updateParam( + parameters, prefix + "rear_vehicle_safety_time_margin", + params.rear_vehicle_safety_time_margin); + updateParam( + parameters, prefix + "lateral_distance_max_threshold", params.lateral_distance_max_threshold); + }; + + update_rss_params("lane_change.safety_check.execution.", p->safety.rss_params); + update_rss_params("lane_change.safety_check.parked.", p->safety.rss_params_for_parked); + update_rss_params("lane_change.safety_check.cancel.", p->safety.rss_params_for_abort); + update_rss_params("lane_change.safety_check.stuck.", p->safety.rss_params_for_stuck); + + { + const std::string ns = "lane_change.delay_lane_change."; + updateParam(parameters, ns + "enable", p->delay.enable); + updateParam( + parameters, ns + "check_only_parked_vehicle", p->delay.check_only_parked_vehicle); + updateParam( + parameters, ns + "min_road_shoulder_width", p->delay.min_road_shoulder_width); + updateParam( + parameters, ns + "th_parked_vehicle_shift_ratio", p->delay.th_parked_vehicle_shift_ratio); + } + + { + const std::string ns = "lane_change.terminal_path."; + updateParam(parameters, ns + "enable", p->terminal_path.enable); + updateParam(parameters, ns + "disable_near_goal", p->terminal_path.disable_near_goal); + updateParam(parameters, ns + "stop_at_boundary", p->terminal_path.stop_at_boundary); + } + { const std::string ns = "lane_change.cancel."; bool enable_on_prepare_phase = true; @@ -424,6 +530,18 @@ void LaneChangeModuleManager::updateModuleParams(const std::vectorcancel.enable_on_lane_changing_phase = enable_on_lane_changing_phase; } + int deceleration_sampling_num = 0; + updateParam(parameters, ns + "deceleration_sampling_num", deceleration_sampling_num); + if (deceleration_sampling_num > 0) { + p->cancel.deceleration_sampling_num = deceleration_sampling_num; + } else { + RCLCPP_WARN_ONCE( + node_->get_logger(), + "Parameter 'deceleration_sampling_num' is not updated because the value (%d) is not " + "positive", + deceleration_sampling_num); + } + updateParam(parameters, ns + "delta_time", p->cancel.delta_time); updateParam(parameters, ns + "duration", p->cancel.duration); updateParam(parameters, ns + "max_lateral_jerk", p->cancel.max_lateral_jerk); @@ -431,6 +549,7 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector( parameters, ns + "unsafe_hysteresis_threshold", p->cancel.th_unsafe_hysteresis); } + std::for_each(observers_.begin(), observers_.end(), [&p](const auto & observer) { if (!observer.expired()) observer.lock()->updateModuleParams(p); }); From 6e0e6c09f422063d72a727229bf34daffef279a9 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Tue, 14 Jan 2025 19:23:19 +0900 Subject: [PATCH 194/334] fix(behavior_velocity_planner_common): fix unregister process (#9913) Signed-off-by: yuki-takagi-66 --- .../behavior_velocity_planner_common/scene_module_interface.hpp | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp index d8d640a078267..a891b011dbab8 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp @@ -228,6 +228,7 @@ class SceneModuleManagerInterface auto itr = scene_modules_.begin(); while (itr != scene_modules_.end()) { if (isModuleExpired(*itr)) { + registered_module_id_set_.erase((*itr)->getModuleId()); itr = scene_modules_.erase(itr); } else { itr++; From 5f88055f48c885733cfa6217c811a17a21470a36 Mon Sep 17 00:00:00 2001 From: Kirill Glinskiy <56448851+PurplePegasuss@users.noreply.github.com> Date: Tue, 14 Jan 2025 19:10:07 +0300 Subject: [PATCH 195/334] docs(autoware_mission_planner): added odometry input in README.md (#7281) added odometry input in README.md Signed-off-by: Ryohsuke Mitsudome --- planning/autoware_mission_planner/README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/autoware_mission_planner/README.md b/planning/autoware_mission_planner/README.md index b5993d0106add..720ecd976f65f 100644 --- a/planning/autoware_mission_planner/README.md +++ b/planning/autoware_mission_planner/README.md @@ -53,6 +53,7 @@ It distributes route requests and planning results according to current MRM oper | `input/vector_map` | autoware_map_msgs/msg/LaneletMapBin | vector map of Lanelet2 | | `input/modified_goal` | geometry_msgs/PoseWithUuidStamped | modified goal pose | | `input/operation_mode_state` | autoware_adapi_v1_msgs/OperationModeState | operation mode state | +| `input/odometry` | nav_msgs/msg/Odometry | vehicle odometry | ### Publications From 951b1df19373a57c813ece9dd15dcd6a6f6bb0cf Mon Sep 17 00:00:00 2001 From: cyn-liu <104069308+cyn-liu@users.noreply.github.com> Date: Wed, 15 Jan 2025 00:22:37 +0800 Subject: [PATCH 196/334] fix(autoware_tensorrt_yolox): modify tensorrt_yolox_node name (#9156) Signed-off-by: liu cui --- .../launch/multiple_yolox.launch.xml | 16 ++++++++++++++++ .../launch/yolox_s_plus_opt.launch.xml | 6 ++++-- 2 files changed, 20 insertions(+), 2 deletions(-) diff --git a/perception/autoware_tensorrt_yolox/launch/multiple_yolox.launch.xml b/perception/autoware_tensorrt_yolox/launch/multiple_yolox.launch.xml index a7952b12414b1..606fd1299cf35 100644 --- a/perception/autoware_tensorrt_yolox/launch/multiple_yolox.launch.xml +++ b/perception/autoware_tensorrt_yolox/launch/multiple_yolox.launch.xml @@ -11,34 +11,50 @@ + + + + + + + + + + + + + + + + diff --git a/perception/autoware_tensorrt_yolox/launch/yolox_s_plus_opt.launch.xml b/perception/autoware_tensorrt_yolox/launch/yolox_s_plus_opt.launch.xml index 0096a219c8573..6d40905d78127 100644 --- a/perception/autoware_tensorrt_yolox/launch/yolox_s_plus_opt.launch.xml +++ b/perception/autoware_tensorrt_yolox/launch/yolox_s_plus_opt.launch.xml @@ -1,6 +1,8 @@ + + @@ -15,13 +17,13 @@ - + - + From bc0dcccbec3131cea2bde0761f811f971f0f10e4 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Wed, 15 Jan 2025 09:25:04 +0900 Subject: [PATCH 197/334] test(external_velocity_limit_selector): add node test (#8944) add node smoke test Signed-off-by: Maxime CLEMENT --- .../CMakeLists.txt | 7 + .../package.xml | 1 + .../external_velocity_limit_selector_node.cpp | 1 - ...nal_velocity_limit_selector_node_launch.py | 178 ++++++++++++++++++ 4 files changed, 186 insertions(+), 1 deletion(-) create mode 100644 planning/autoware_external_velocity_limit_selector/test/test_external_velocity_limit_selector_node_launch.py diff --git a/planning/autoware_external_velocity_limit_selector/CMakeLists.txt b/planning/autoware_external_velocity_limit_selector/CMakeLists.txt index ca758d1262b48..aa8d07d91135e 100644 --- a/planning/autoware_external_velocity_limit_selector/CMakeLists.txt +++ b/planning/autoware_external_velocity_limit_selector/CMakeLists.txt @@ -21,6 +21,13 @@ rclcpp_components_register_node(external_velocity_limit_selector_node EXECUTABLE external_velocity_limit_selector ) +if(BUILD_TESTING) + add_launch_test( + test/test_external_velocity_limit_selector_node_launch.py + TIMEOUT "30" + ) +endif() + ament_auto_package(INSTALL_TO_SHARE launch config diff --git a/planning/autoware_external_velocity_limit_selector/package.xml b/planning/autoware_external_velocity_limit_selector/package.xml index b75a4fab72d7c..5bfd3fa936d50 100644 --- a/planning/autoware_external_velocity_limit_selector/package.xml +++ b/planning/autoware_external_velocity_limit_selector/package.xml @@ -28,6 +28,7 @@ ament_lint_auto autoware_lint_common + ros_testing ament_cmake diff --git a/planning/autoware_external_velocity_limit_selector/src/external_velocity_limit_selector_node.cpp b/planning/autoware_external_velocity_limit_selector/src/external_velocity_limit_selector_node.cpp index cf42763fc6b60..cc2b134900a31 100644 --- a/planning/autoware_external_velocity_limit_selector/src/external_velocity_limit_selector_node.cpp +++ b/planning/autoware_external_velocity_limit_selector/src/external_velocity_limit_selector_node.cpp @@ -14,7 +14,6 @@ #include "autoware/external_velocity_limit_selector/external_velocity_limit_selector_node.hpp" -#include #include #include #include diff --git a/planning/autoware_external_velocity_limit_selector/test/test_external_velocity_limit_selector_node_launch.py b/planning/autoware_external_velocity_limit_selector/test/test_external_velocity_limit_selector_node_launch.py new file mode 100644 index 0000000000000..1c7e882fbc81f --- /dev/null +++ b/planning/autoware_external_velocity_limit_selector/test/test_external_velocity_limit_selector_node_launch.py @@ -0,0 +1,178 @@ +#!/usr/bin/env python3 + +# Copyright 2024 TIER IV, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os +import unittest + +from ament_index_python import get_package_share_directory +import launch +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import AnyLaunchDescriptionSource +from launch.logging import get_logger +import launch_testing +import pytest +from rcl_interfaces.msg import Parameter +from rcl_interfaces.msg import ParameterType +from rcl_interfaces.msg import ParameterValue +from rcl_interfaces.srv import SetParameters +import rclpy +import rclpy.qos +from tier4_planning_msgs.msg import VelocityLimit +from tier4_planning_msgs.msg import VelocityLimitClearCommand + +logger = get_logger(__name__) + + +@pytest.mark.launch_test +def generate_test_description(): + test_external_velocity_limit_selector_launch_file = os.path.join( + get_package_share_directory("autoware_external_velocity_limit_selector"), + "launch", + "external_velocity_limit_selector.launch.xml", + ) + external_velocity_limit_selector = IncludeLaunchDescription( + AnyLaunchDescriptionSource(test_external_velocity_limit_selector_launch_file), + ) + + return launch.LaunchDescription( + [ + external_velocity_limit_selector, + # Start tests right away - no need to wait for anything + launch_testing.actions.ReadyToTest(), + ] + ) + + +class TestExternalVelocityLimitSelector(unittest.TestCase): + @classmethod + def setUpClass(cls): + # Initialize the ROS context for the test node + rclpy.init() + + @classmethod + def tearDownClass(cls): + # Shutdown the ROS context + rclpy.shutdown() + + def velocity_limit_callback(self, msg): + self.msg_buffer_ = msg + + def setUp(self): + # Create a ROS node for tests + self.test_node = rclpy.create_node("test_node") + qos = rclpy.qos.QoSProfile(depth=1, durability=rclpy.qos.DurabilityPolicy.TRANSIENT_LOCAL) + self.pub_api_limit_ = self.test_node.create_publisher( + VelocityLimit, "/planning/scenario_planning/max_velocity_default", qos + ) + self.pub_internal_limit_ = self.test_node.create_publisher( + VelocityLimit, "/planning/scenario_planning/max_velocity_candidates", qos + ) + self.pub_clear_limit_ = self.test_node.create_publisher( + VelocityLimitClearCommand, "/planning/scenario_planning/clear_velocity_limit", qos + ) + self.msg_buffer_ = None + self.velocity_limit_output_ = None + self.test_node.create_subscription( + VelocityLimit, + "/planning/scenario_planning/max_velocity", + self.velocity_limit_callback, + 1, + ) + + def wait_for_output(self): + while not self.msg_buffer_: + rclpy.spin_once(self.test_node, timeout_sec=0.1) + self.velocity_limit_output_ = self.msg_buffer_ + self.msg_buffer_ = None + + def tearDown(self): + self.test_node.destroy_node() + + def update_max_vel_param(self, max_vel): + set_params_client = self.test_node.create_client( + SetParameters, "/external_velocity_limit_selector/set_parameters" + ) + while not set_params_client.wait_for_service(timeout_sec=1.0): + continue + set_params_request = SetParameters.Request() + set_params_request.parameters = [ + Parameter( + name="max_vel", + value=ParameterValue(type=ParameterType.PARAMETER_DOUBLE, double_value=max_vel), + ), + ] + future = set_params_client.call_async(set_params_request) + rclpy.spin_until_future_complete(self.test_node, future) + + if future.result() is None: + self.test_node.get_logger().error( + "Exception while calling service: %r" % future.exception() + ) + raise self.failureException("setting of initial parameters failed") + + @staticmethod + def make_velocity_limit_msg(vel): + msg = VelocityLimit() + msg.use_constraints = False + msg.max_velocity = vel + return msg + + def test_external_velocity_limit_selector_node(self): + self.update_max_vel_param(15.0) + # clear velocity limit to trigger first output + clear_cmd = VelocityLimitClearCommand(command=True) + self.pub_clear_limit_.publish(clear_cmd) + self.wait_for_output() + # velocity limit is 0 before any limit is set + self.assertEqual(self.velocity_limit_output_.max_velocity, 0.0) + + # Send velocity limits + # new API velocity limit: higher than the node param -> limit is set to the param value + api_limit = self.make_velocity_limit_msg(20.0) + self.pub_api_limit_.publish(api_limit) + self.wait_for_output() + self.assertEqual(self.velocity_limit_output_.max_velocity, 15.0) + # new API velocity limit + api_limit = self.make_velocity_limit_msg(10.0) + self.pub_api_limit_.publish(api_limit) + self.wait_for_output() + self.assertEqual(self.velocity_limit_output_.max_velocity, 10.0) + # new INTERNAL velocity limit + internal_limit = self.make_velocity_limit_msg(5.0) + self.pub_internal_limit_.publish(internal_limit) + self.wait_for_output() + self.assertEqual(self.velocity_limit_output_.max_velocity, 5.0) + # CLEAR: back to API velocity limit + self.pub_clear_limit_.publish(clear_cmd) + self.wait_for_output() + self.assertEqual(self.velocity_limit_output_.max_velocity, 10.0) + # lower the max_vel node parameter + self.update_max_vel_param(2.5) + self.pub_clear_limit_.publish(clear_cmd) + self.wait_for_output() + self.assertEqual(self.velocity_limit_output_.max_velocity, 2.5) + # velocity limit set by internal limit is no longer applied since above max_vel parameter + internal_limit = self.make_velocity_limit_msg(5.0) + self.pub_internal_limit_.publish(internal_limit) + self.wait_for_output() + self.assertEqual(self.velocity_limit_output_.max_velocity, 2.5) + + +@launch_testing.post_shutdown_test() +class TestProcessOutput(unittest.TestCase): + def test_exit_code(self, proc_info): + # Check that process exits with code 0: no error + launch_testing.asserts.assertExitCodes(proc_info) From bc409a755a2d0abce18f73c9d84aa05d851cdc5d Mon Sep 17 00:00:00 2001 From: Mitsuhiro Sakamoto <50359861+mitukou1109@users.noreply.github.com> Date: Wed, 15 Jan 2025 09:32:12 +0900 Subject: [PATCH 198/334] feat(remaining_distance_time_calculator): integrate generate_parameter_library (#8826) * add parameter description Signed-off-by: mitukou1109 * use parameter listener Signed-off-by: mitukou1109 * supress deprecated error Signed-off-by: mitukou1109 * change scope of compile option to private Signed-off-by: mitukou1109 --------- Signed-off-by: mitukou1109 --- .../CMakeLists.txt | 12 ++++++++++++ .../package.xml | 1 + ...emaining_distance_time_calculator_parameters.yaml | 4 ++++ .../src/remaining_distance_time_calculator_node.cpp | 6 ++++-- .../src/remaining_distance_time_calculator_node.hpp | 8 ++------ 5 files changed, 23 insertions(+), 8 deletions(-) create mode 100644 planning/autoware_remaining_distance_time_calculator/param/remaining_distance_time_calculator_parameters.yaml diff --git a/planning/autoware_remaining_distance_time_calculator/CMakeLists.txt b/planning/autoware_remaining_distance_time_calculator/CMakeLists.txt index d29a153a0ce5d..31fc4b1572f33 100644 --- a/planning/autoware_remaining_distance_time_calculator/CMakeLists.txt +++ b/planning/autoware_remaining_distance_time_calculator/CMakeLists.txt @@ -4,10 +4,22 @@ project(autoware_remaining_distance_time_calculator) find_package(autoware_cmake REQUIRED) autoware_package() +generate_parameter_library(remaining_distance_time_calculator_parameters + param/remaining_distance_time_calculator_parameters.yaml +) + ament_auto_add_library(${PROJECT_NAME} SHARED src/remaining_distance_time_calculator_node.cpp ) +target_link_libraries(${PROJECT_NAME} + remaining_distance_time_calculator_parameters +) + +target_compile_options(${PROJECT_NAME} PRIVATE + -Wno-error=deprecated-declarations +) + rclcpp_components_register_node(${PROJECT_NAME} PLUGIN "autoware::remaining_distance_time_calculator::RemainingDistanceTimeCalculatorNode" EXECUTABLE ${PROJECT_NAME}_node diff --git a/planning/autoware_remaining_distance_time_calculator/package.xml b/planning/autoware_remaining_distance_time_calculator/package.xml index 924e6d62d6aba..568f677a0c13d 100644 --- a/planning/autoware_remaining_distance_time_calculator/package.xml +++ b/planning/autoware_remaining_distance_time_calculator/package.xml @@ -18,6 +18,7 @@ autoware_route_handler autoware_test_utils autoware_universe_utils + generate_parameter_library geometry_msgs nav_msgs rclcpp diff --git a/planning/autoware_remaining_distance_time_calculator/param/remaining_distance_time_calculator_parameters.yaml b/planning/autoware_remaining_distance_time_calculator/param/remaining_distance_time_calculator_parameters.yaml new file mode 100644 index 0000000000000..0f1b1b9efbb6d --- /dev/null +++ b/planning/autoware_remaining_distance_time_calculator/param/remaining_distance_time_calculator_parameters.yaml @@ -0,0 +1,4 @@ +remaining_distance_time_calculator: + update_rate: + type: double + description: Timer callback period. [Hz] diff --git a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp index 7932a2531185f..74f3f2f43077d 100644 --- a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp +++ b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp @@ -65,9 +65,11 @@ RemainingDistanceTimeCalculatorNode::RemainingDistanceTimeCalculatorNode( "~/output/mission_remaining_distance_time", rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable()); - node_param_.update_rate = declare_parameter("update_rate"); + param_listener_ = std::make_shared<::remaining_distance_time_calculator::ParamListener>( + this->get_node_parameters_interface()); + const auto param = param_listener_->get_params(); - const auto period_ns = rclcpp::Rate(node_param_.update_rate).period(); + const auto period_ns = rclcpp::Rate(param.update_rate).period(); timer_ = rclcpp::create_timer( this, get_clock(), period_ns, std::bind(&RemainingDistanceTimeCalculatorNode::on_timer, this)); } diff --git a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp index b7af8861bf524..8a38941d383ee 100644 --- a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp +++ b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp @@ -17,6 +17,7 @@ #include #include +#include #include #include @@ -39,11 +40,6 @@ namespace autoware::remaining_distance_time_calculator { -struct NodeParam -{ - double update_rate{0.0}; -}; - class RemainingDistanceTimeCalculatorNode : public rclcpp::Node { public: @@ -86,7 +82,7 @@ class RemainingDistanceTimeCalculatorNode : public rclcpp::Node double remaining_time_; // Parameter - NodeParam node_param_; + std::shared_ptr<::remaining_distance_time_calculator::ParamListener> param_listener_; // Callbacks void on_timer(); From 87d7988fae3ac1b135caa6de0c6911da8e4e154d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=E5=BF=83=E5=88=9A?= <90366790+liuXinGangChina@users.noreply.github.com> Date: Wed, 15 Jan 2025 09:41:50 +0800 Subject: [PATCH 199/334] feat(autoware_localization_util): porting from universe to core, autoware_localization_util, remove from universe repo (#9888) task: porting from universe to core, autoware_localization_util, remove from universe repo : v0.0 Signed-off-by: liuXinGangChina --- .../autoware_localization_util/CHANGELOG.rst | 51 ---- .../autoware_localization_util/CMakeLists.txt | 29 -- .../autoware_localization_util/README.md | 5 - .../localization_util/covariance_ellipse.hpp | 44 --- .../localization_util/matrix_type.hpp | 26 -- .../localization_util/smart_pose_buffer.hpp | 71 ----- .../tree_structured_parzen_estimator.hpp | 87 ------ .../autoware/localization_util/util_func.hpp | 88 ------ .../autoware_localization_util/package.xml | 35 --- .../src/covariance_ellipse.cpp | 92 ------- .../src/smart_pose_buffer.cpp | 158 ----------- .../src/tree_structured_parzen_estimator.cpp | 185 ------------- .../src/util_func.cpp | 257 ------------------ .../test/test_smart_pose_buffer.cpp | 109 -------- .../test/test_tpe.cpp | 75 ----- 15 files changed, 1312 deletions(-) delete mode 100644 localization/autoware_localization_util/CHANGELOG.rst delete mode 100644 localization/autoware_localization_util/CMakeLists.txt delete mode 100644 localization/autoware_localization_util/README.md delete mode 100644 localization/autoware_localization_util/include/autoware/localization_util/covariance_ellipse.hpp delete mode 100644 localization/autoware_localization_util/include/autoware/localization_util/matrix_type.hpp delete mode 100644 localization/autoware_localization_util/include/autoware/localization_util/smart_pose_buffer.hpp delete mode 100644 localization/autoware_localization_util/include/autoware/localization_util/tree_structured_parzen_estimator.hpp delete mode 100644 localization/autoware_localization_util/include/autoware/localization_util/util_func.hpp delete mode 100644 localization/autoware_localization_util/package.xml delete mode 100644 localization/autoware_localization_util/src/covariance_ellipse.cpp delete mode 100644 localization/autoware_localization_util/src/smart_pose_buffer.cpp delete mode 100644 localization/autoware_localization_util/src/tree_structured_parzen_estimator.cpp delete mode 100644 localization/autoware_localization_util/src/util_func.cpp delete mode 100644 localization/autoware_localization_util/test/test_smart_pose_buffer.cpp delete mode 100644 localization/autoware_localization_util/test/test_tpe.cpp diff --git a/localization/autoware_localization_util/CHANGELOG.rst b/localization/autoware_localization_util/CHANGELOG.rst deleted file mode 100644 index be40e3ee8560e..0000000000000 --- a/localization/autoware_localization_util/CHANGELOG.rst +++ /dev/null @@ -1,51 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package autoware_localization_util -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -0.40.0 (2024-12-12) -------------------- -* Merge branch 'main' into release-0.40.0 -* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" - This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. -* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) -* chore(package.xml): bump version to 0.39.0 (`#9587 `_) - * chore(package.xml): bump version to 0.39.0 - * fix: fix ticket links in CHANGELOG.rst - * fix: remove unnecessary diff - --------- - Co-authored-by: Yutaka Kondo -* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) -* fix(cpplint): include what you use - localization (`#9567 `_) -* 0.39.0 -* update changelog -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) - * unify package.xml version to 0.37.0 - * remove system_monitor/CHANGELOG.rst - * add changelog - * 0.38.0 - --------- -* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo - -0.39.0 (2024-11-25) -------------------- -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) - * unify package.xml version to 0.37.0 - * remove system_monitor/CHANGELOG.rst - * add changelog - * 0.38.0 - --------- -* Contributors: Esteve Fernandez, Yutaka Kondo - -0.38.0 (2024-11-08) -------------------- -* unify package.xml version to 0.37.0 -* refactor(localization_util)!: prefix package and namespace with autoware (`#8922 `_) - add autoware prefix to localization_util -* Contributors: Masaki Baba, Yutaka Kondo - -0.26.0 (2024-04-03) -------------------- diff --git a/localization/autoware_localization_util/CMakeLists.txt b/localization/autoware_localization_util/CMakeLists.txt deleted file mode 100644 index de62633124f3d..0000000000000 --- a/localization/autoware_localization_util/CMakeLists.txt +++ /dev/null @@ -1,29 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(autoware_localization_util) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -ament_auto_add_library(${PROJECT_NAME} SHARED - src/util_func.cpp - src/smart_pose_buffer.cpp - src/tree_structured_parzen_estimator.cpp - src/covariance_ellipse.cpp -) - -if(BUILD_TESTING) - find_package(ament_cmake_gtest REQUIRED) - ament_auto_add_gtest(test_smart_pose_buffer - test/test_smart_pose_buffer.cpp - src/smart_pose_buffer.cpp - ) - - ament_auto_add_gtest(test_tpe - test/test_tpe.cpp - src/tree_structured_parzen_estimator.cpp - ) -endif() - -ament_auto_package( - INSTALL_TO_SHARE -) diff --git a/localization/autoware_localization_util/README.md b/localization/autoware_localization_util/README.md deleted file mode 100644 index f7fddd9eebf05..0000000000000 --- a/localization/autoware_localization_util/README.md +++ /dev/null @@ -1,5 +0,0 @@ -# autoware_localization_util - -`autoware_localization_util` is a localization utility package. - -This package does not have a node, it is just a library. diff --git a/localization/autoware_localization_util/include/autoware/localization_util/covariance_ellipse.hpp b/localization/autoware_localization_util/include/autoware/localization_util/covariance_ellipse.hpp deleted file mode 100644 index abd0af46856b0..0000000000000 --- a/localization/autoware_localization_util/include/autoware/localization_util/covariance_ellipse.hpp +++ /dev/null @@ -1,44 +0,0 @@ -// Copyright 2024 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__LOCALIZATION_UTIL__COVARIANCE_ELLIPSE_HPP_ -#define AUTOWARE__LOCALIZATION_UTIL__COVARIANCE_ELLIPSE_HPP_ - -#include - -#include -#include - -namespace autoware::localization_util -{ - -struct Ellipse -{ - double long_radius; - double short_radius; - double yaw; - Eigen::Matrix2d P; - double size_lateral_direction; -}; - -Ellipse calculate_xy_ellipse( - const geometry_msgs::msg::PoseWithCovariance & pose_with_covariance, const double scale); - -visualization_msgs::msg::Marker create_ellipse_marker( - const Ellipse & ellipse, const std_msgs::msg::Header & header, - const geometry_msgs::msg::PoseWithCovariance & pose_with_covariance); - -} // namespace autoware::localization_util - -#endif // AUTOWARE__LOCALIZATION_UTIL__COVARIANCE_ELLIPSE_HPP_ diff --git a/localization/autoware_localization_util/include/autoware/localization_util/matrix_type.hpp b/localization/autoware_localization_util/include/autoware/localization_util/matrix_type.hpp deleted file mode 100644 index bda6ff19f2867..0000000000000 --- a/localization/autoware_localization_util/include/autoware/localization_util/matrix_type.hpp +++ /dev/null @@ -1,26 +0,0 @@ -// Copyright 2021 TierIV -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__LOCALIZATION_UTIL__MATRIX_TYPE_HPP_ -#define AUTOWARE__LOCALIZATION_UTIL__MATRIX_TYPE_HPP_ - -#include - -namespace autoware::localization_util -{ -using Matrix6d = Eigen::Matrix; -using RowMatrixXd = Eigen::Matrix; -} // namespace autoware::localization_util - -#endif // AUTOWARE__LOCALIZATION_UTIL__MATRIX_TYPE_HPP_ diff --git a/localization/autoware_localization_util/include/autoware/localization_util/smart_pose_buffer.hpp b/localization/autoware_localization_util/include/autoware/localization_util/smart_pose_buffer.hpp deleted file mode 100644 index 8c10506c36753..0000000000000 --- a/localization/autoware_localization_util/include/autoware/localization_util/smart_pose_buffer.hpp +++ /dev/null @@ -1,71 +0,0 @@ -// Copyright 2015-2019 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__LOCALIZATION_UTIL__SMART_POSE_BUFFER_HPP_ -#define AUTOWARE__LOCALIZATION_UTIL__SMART_POSE_BUFFER_HPP_ - -#include "autoware/localization_util/util_func.hpp" - -#include - -#include - -#include - -namespace autoware::localization_util -{ -class SmartPoseBuffer -{ -private: - using PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped; - -public: - struct InterpolateResult - { - PoseWithCovarianceStamped old_pose; - PoseWithCovarianceStamped new_pose; - PoseWithCovarianceStamped interpolated_pose; - }; - - SmartPoseBuffer() = delete; - SmartPoseBuffer( - const rclcpp::Logger & logger, const double & pose_timeout_sec, - const double & pose_distance_tolerance_meters); - - std::optional interpolate(const rclcpp::Time & target_ros_time); - - void push_back(const PoseWithCovarianceStamped::ConstSharedPtr & pose_msg_ptr); - - void pop_old(const rclcpp::Time & target_ros_time); - - void clear(); - -private: - rclcpp::Logger logger_; - std::deque pose_buffer_; - std::mutex mutex_; // This mutex is for pose_buffer_ - - const double pose_timeout_sec_; - const double pose_distance_tolerance_meters_; - - [[nodiscard]] bool validate_time_stamp_difference( - const rclcpp::Time & target_time, const rclcpp::Time & reference_time, - const double time_tolerance_sec) const; - [[nodiscard]] bool validate_position_difference( - const geometry_msgs::msg::Point & target_point, - const geometry_msgs::msg::Point & reference_point, const double distance_tolerance_m_) const; -}; -} // namespace autoware::localization_util - -#endif // AUTOWARE__LOCALIZATION_UTIL__SMART_POSE_BUFFER_HPP_ diff --git a/localization/autoware_localization_util/include/autoware/localization_util/tree_structured_parzen_estimator.hpp b/localization/autoware_localization_util/include/autoware/localization_util/tree_structured_parzen_estimator.hpp deleted file mode 100644 index ddf7625c202ec..0000000000000 --- a/localization/autoware_localization_util/include/autoware/localization_util/tree_structured_parzen_estimator.hpp +++ /dev/null @@ -1,87 +0,0 @@ -// Copyright 2023 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__LOCALIZATION_UTIL__TREE_STRUCTURED_PARZEN_ESTIMATOR_HPP_ -#define AUTOWARE__LOCALIZATION_UTIL__TREE_STRUCTURED_PARZEN_ESTIMATOR_HPP_ - -/* -A implementation of tree-structured parzen estimator (TPE) -See below pdf for the TPE algorithm detail. -https://papers.nips.cc/paper_files/paper/2011/file/86e8f7ab32cfd12577bc2619bc635690-Paper.pdf - -Optuna is also used as a reference for implementation. -https://github.com/optuna/optuna -*/ - -#include -#include -#include - -namespace autoware::localization_util -{ -class TreeStructuredParzenEstimator -{ -public: - using Input = std::vector; - using Score = double; - struct Trial - { - Input input; - Score score; - }; - - enum Direction { - MINIMIZE = 0, - MAXIMIZE = 1, - }; - - enum Index { - TRANS_X = 0, - TRANS_Y = 1, - TRANS_Z = 2, - ANGLE_X = 3, - ANGLE_Y = 4, - ANGLE_Z = 5, - INDEX_NUM = 6, - }; - - TreeStructuredParzenEstimator() = delete; - TreeStructuredParzenEstimator( - const Direction direction, const int64_t n_startup_trials, std::vector sample_mean, - std::vector sample_stddev); - void add_trial(const Trial & trial); - [[nodiscard]] Input get_next_input() const; - -private: - static constexpr double max_good_rate = 0.10; - static constexpr int64_t n_ei_candidates = 100; - - static std::mt19937_64 engine; - - [[nodiscard]] double compute_log_likelihood_ratio(const Input & input) const; - [[nodiscard]] static double log_gaussian_pdf( - const Input & input, const Input & mu, const Input & sigma); - - std::vector trials_; - int64_t above_num_; - const Direction direction_; - const int64_t n_startup_trials_; - const int64_t input_dimension_; - const std::vector sample_mean_; - const std::vector sample_stddev_; - Input base_stddev_; -}; -} // namespace autoware::localization_util - -#endif // AUTOWARE__LOCALIZATION_UTIL__TREE_STRUCTURED_PARZEN_ESTIMATOR_HPP_ diff --git a/localization/autoware_localization_util/include/autoware/localization_util/util_func.hpp b/localization/autoware_localization_util/include/autoware/localization_util/util_func.hpp deleted file mode 100644 index bef9968f34b6f..0000000000000 --- a/localization/autoware_localization_util/include/autoware/localization_util/util_func.hpp +++ /dev/null @@ -1,88 +0,0 @@ -// Copyright 2015-2019 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__LOCALIZATION_UTIL__UTIL_FUNC_HPP_ -#define AUTOWARE__LOCALIZATION_UTIL__UTIL_FUNC_HPP_ - -#include -#include -#include -#include - -#ifdef ROS_DISTRO_GALACTIC -#include -#include -#else -#include - -#include -#endif - -#include -#include -#include -#include -#include -#include - -namespace autoware::localization_util -{ -// ref by http://takacity.blog.fc2.com/blog-entry-69.html -std_msgs::msg::ColorRGBA exchange_color_crc(double x); - -double calc_diff_for_radian(const double lhs_rad, const double rhs_rad); - -// x: roll, y: pitch, z: yaw -geometry_msgs::msg::Vector3 get_rpy(const geometry_msgs::msg::Pose & pose); -geometry_msgs::msg::Vector3 get_rpy(const geometry_msgs::msg::PoseStamped & pose); -geometry_msgs::msg::Vector3 get_rpy(const geometry_msgs::msg::PoseWithCovarianceStamped & pose); - -geometry_msgs::msg::Quaternion rpy_rad_to_quaternion( - const double r_rad, const double p_rad, const double y_rad); -geometry_msgs::msg::Quaternion rpy_deg_to_quaternion( - const double r_deg, const double p_deg, const double y_deg); - -geometry_msgs::msg::Twist calc_twist( - const geometry_msgs::msg::PoseStamped & pose_a, const geometry_msgs::msg::PoseStamped & pose_b); - -geometry_msgs::msg::PoseStamped interpolate_pose( - const geometry_msgs::msg::PoseStamped & pose_a, const geometry_msgs::msg::PoseStamped & pose_b, - const rclcpp::Time & time_stamp); - -geometry_msgs::msg::PoseStamped interpolate_pose( - const geometry_msgs::msg::PoseWithCovarianceStamped & pose_a, - const geometry_msgs::msg::PoseWithCovarianceStamped & pose_b, const rclcpp::Time & time_stamp); - -Eigen::Affine3d pose_to_affine3d(const geometry_msgs::msg::Pose & ros_pose); -Eigen::Matrix4f pose_to_matrix4f(const geometry_msgs::msg::Pose & ros_pose); -geometry_msgs::msg::Pose matrix4f_to_pose(const Eigen::Matrix4f & eigen_pose_matrix); -Eigen::Vector3d point_to_vector3d(const geometry_msgs::msg::Point & ros_pos); - -template -T transform(const T & input, const geometry_msgs::msg::TransformStamped & transform) -{ - T output; - tf2::doTransform(input, output, transform); - return output; -} - -double norm(const geometry_msgs::msg::Point & p1, const geometry_msgs::msg::Point & p2); - -void output_pose_with_cov_to_log( - const rclcpp::Logger & logger, const std::string & prefix, - const geometry_msgs::msg::PoseWithCovarianceStamped & pose_with_cov); - -} // namespace autoware::localization_util - -#endif // AUTOWARE__LOCALIZATION_UTIL__UTIL_FUNC_HPP_ diff --git a/localization/autoware_localization_util/package.xml b/localization/autoware_localization_util/package.xml deleted file mode 100644 index 89ad7c24840dd..0000000000000 --- a/localization/autoware_localization_util/package.xml +++ /dev/null @@ -1,35 +0,0 @@ - - - - autoware_localization_util - 0.40.0 - The autoware_localization_util package - Yamato Ando - Masahiro Sakamoto - Shintaro Sakoda - Kento Yabuuchi - NGUYEN Viet Anh - Taiki Yamada - Ryu Yamamoto - Apache License 2.0 - Yamato Ando - - ament_cmake_auto - autoware_cmake - - diagnostic_msgs - geometry_msgs - rclcpp - std_msgs - tf2 - tf2_eigen - tf2_geometry_msgs - visualization_msgs - - ament_cmake_cppcheck - ament_lint_auto - - - ament_cmake - - diff --git a/localization/autoware_localization_util/src/covariance_ellipse.cpp b/localization/autoware_localization_util/src/covariance_ellipse.cpp deleted file mode 100644 index 847f89e0da9b3..0000000000000 --- a/localization/autoware_localization_util/src/covariance_ellipse.cpp +++ /dev/null @@ -1,92 +0,0 @@ -// Copyright 2024 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/localization_util/covariance_ellipse.hpp" - -#include - -#include -#ifdef ROS_DISTRO_GALACTIC -#include -#else -#include -#endif - -namespace autoware::localization_util -{ - -Ellipse calculate_xy_ellipse( - const geometry_msgs::msg::PoseWithCovariance & pose_with_covariance, const double scale) -{ - // input geometry_msgs::PoseWithCovariance contain 6x6 matrix - Eigen::Matrix2d xy_covariance; - const auto cov = pose_with_covariance.covariance; - xy_covariance(0, 0) = cov[0 * 6 + 0]; - xy_covariance(0, 1) = cov[0 * 6 + 1]; - xy_covariance(1, 0) = cov[1 * 6 + 0]; - xy_covariance(1, 1) = cov[1 * 6 + 1]; - - Eigen::SelfAdjointEigenSolver eigensolver(xy_covariance); - - Ellipse ellipse; - - // eigen values and vectors are sorted in ascending order - ellipse.long_radius = scale * std::sqrt(eigensolver.eigenvalues()(1)); - ellipse.short_radius = scale * std::sqrt(eigensolver.eigenvalues()(0)); - - // principal component vector - const Eigen::Vector2d pc_vector = eigensolver.eigenvectors().col(1); - ellipse.yaw = std::atan2(pc_vector.y(), pc_vector.x()); - - // ellipse size along lateral direction (body-frame) - ellipse.P = xy_covariance; - const double yaw_vehicle = tf2::getYaw(pose_with_covariance.pose.orientation); - const Eigen::Matrix2d & p_inv = ellipse.P.inverse(); - Eigen::MatrixXd e(2, 1); - e(0, 0) = std::cos(yaw_vehicle); - e(1, 0) = std::sin(yaw_vehicle); - const double d = std::sqrt((e.transpose() * p_inv * e)(0, 0) / p_inv.determinant()); - ellipse.size_lateral_direction = scale * d; - - return ellipse; -} - -visualization_msgs::msg::Marker create_ellipse_marker( - const Ellipse & ellipse, const std_msgs::msg::Header & header, - const geometry_msgs::msg::PoseWithCovariance & pose_with_covariance) -{ - tf2::Quaternion quat; - quat.setEuler(0, 0, ellipse.yaw); - - const double ellipse_long_radius = std::min(ellipse.long_radius, 30.0); - const double ellipse_short_radius = std::min(ellipse.short_radius, 30.0); - visualization_msgs::msg::Marker marker; - marker.header = header; - marker.ns = "error_ellipse"; - marker.id = 0; - marker.type = visualization_msgs::msg::Marker::SPHERE; - marker.action = visualization_msgs::msg::Marker::ADD; - marker.pose = pose_with_covariance.pose; - marker.pose.orientation = tf2::toMsg(quat); - marker.scale.x = ellipse_long_radius * 2; - marker.scale.y = ellipse_short_radius * 2; - marker.scale.z = 0.01; - marker.color.a = 0.1; - marker.color.r = 0.0; - marker.color.g = 0.0; - marker.color.b = 1.0; - return marker; -} - -} // namespace autoware::localization_util diff --git a/localization/autoware_localization_util/src/smart_pose_buffer.cpp b/localization/autoware_localization_util/src/smart_pose_buffer.cpp deleted file mode 100644 index 3b529d68cf6c5..0000000000000 --- a/localization/autoware_localization_util/src/smart_pose_buffer.cpp +++ /dev/null @@ -1,158 +0,0 @@ -// Copyright 2023- Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/localization_util/smart_pose_buffer.hpp" - -namespace autoware::localization_util -{ -SmartPoseBuffer::SmartPoseBuffer( - const rclcpp::Logger & logger, const double & pose_timeout_sec, - const double & pose_distance_tolerance_meters) -: logger_(logger), - pose_timeout_sec_(pose_timeout_sec), - pose_distance_tolerance_meters_(pose_distance_tolerance_meters) -{ -} - -std::optional SmartPoseBuffer::interpolate( - const rclcpp::Time & target_ros_time) -{ - InterpolateResult result; - - { - std::lock_guard lock(mutex_); - - if (pose_buffer_.size() < 2) { - RCLCPP_INFO(logger_, "pose_buffer_.size() < 2"); - return std::nullopt; - } - - const rclcpp::Time time_first = pose_buffer_.front()->header.stamp; - const rclcpp::Time time_last = pose_buffer_.back()->header.stamp; - - if (target_ros_time < time_first) { - RCLCPP_INFO(logger_, "Mismatch between pose timestamp and current timestamp"); - return std::nullopt; - } - - // [time_last < target_ros_time] is acceptable here. - // It is possible that the target_ros_time (often sensor timestamp) is newer than the latest - // timestamp of buffered pose (often EKF). - // However, if the timestamp difference is too large, - // it will later be rejected by validate_time_stamp_difference. - - // get the nearest poses - result.old_pose = *pose_buffer_.front(); - for (const PoseWithCovarianceStamped::ConstSharedPtr & pose_cov_msg_ptr : pose_buffer_) { - result.new_pose = *pose_cov_msg_ptr; - const rclcpp::Time pose_time_stamp = result.new_pose.header.stamp; - if (pose_time_stamp > target_ros_time) { - break; - } - result.old_pose = *pose_cov_msg_ptr; - } - } - - // check the time stamp - const bool is_old_pose_valid = validate_time_stamp_difference( - result.old_pose.header.stamp, target_ros_time, pose_timeout_sec_); - const bool is_new_pose_valid = validate_time_stamp_difference( - result.new_pose.header.stamp, target_ros_time, pose_timeout_sec_); - - // check the position jumping (ex. immediately after the initial pose estimation) - const bool is_pose_diff_valid = validate_position_difference( - result.old_pose.pose.pose.position, result.new_pose.pose.pose.position, - pose_distance_tolerance_meters_); - - // all validations must be true - if (!(is_old_pose_valid && is_new_pose_valid && is_pose_diff_valid)) { - return std::nullopt; - } - - // interpolate the pose - const geometry_msgs::msg::PoseStamped interpolated_pose_msg = - interpolate_pose(result.old_pose, result.new_pose, target_ros_time); - result.interpolated_pose.header = interpolated_pose_msg.header; - result.interpolated_pose.pose.pose = interpolated_pose_msg.pose; - // This does not interpolate the covariance. - // interpolated_pose.pose.covariance is always set to old_pose.covariance - result.interpolated_pose.pose.covariance = result.old_pose.pose.covariance; - return result; -} - -void SmartPoseBuffer::push_back(const PoseWithCovarianceStamped::ConstSharedPtr & pose_msg_ptr) -{ - std::lock_guard lock(mutex_); - if (!pose_buffer_.empty()) { - // Check for non-chronological timestamp order - // This situation can arise when replaying a rosbag multiple times - const rclcpp::Time end_time = pose_buffer_.back()->header.stamp; - const rclcpp::Time msg_time = pose_msg_ptr->header.stamp; - if (msg_time < end_time) { - // Clear the buffer if timestamps are reversed to maintain chronological order - pose_buffer_.clear(); - } - } - pose_buffer_.push_back(pose_msg_ptr); -} - -void SmartPoseBuffer::pop_old(const rclcpp::Time & target_ros_time) -{ - std::lock_guard lock(mutex_); - while (!pose_buffer_.empty()) { - if (rclcpp::Time(pose_buffer_.front()->header.stamp) >= target_ros_time) { - break; - } - pose_buffer_.pop_front(); - } -} - -void SmartPoseBuffer::clear() -{ - std::lock_guard lock(mutex_); - pose_buffer_.clear(); -} - -bool SmartPoseBuffer::validate_time_stamp_difference( - const rclcpp::Time & target_time, const rclcpp::Time & reference_time, - const double time_tolerance_sec) const -{ - const double dt = std::abs((target_time - reference_time).seconds()); - const bool success = dt < time_tolerance_sec; - if (!success) { - RCLCPP_WARN( - logger_, - "Validation error. The reference time is %lf[sec], but the target time is %lf[sec]. The " - "difference is %lf[sec] (the tolerance is %lf[sec]).", - reference_time.seconds(), target_time.seconds(), dt, time_tolerance_sec); - } - return success; -} - -bool SmartPoseBuffer::validate_position_difference( - const geometry_msgs::msg::Point & target_point, const geometry_msgs::msg::Point & reference_point, - const double distance_tolerance_m_) const -{ - const double distance = norm(target_point, reference_point); - const bool success = distance < distance_tolerance_m_; - if (!success) { - RCLCPP_WARN( - logger_, - "Validation error. The distance from reference position to target position is %lf[m] (the " - "tolerance is %lf[m]).", - distance, distance_tolerance_m_); - } - return success; -} -} // namespace autoware::localization_util diff --git a/localization/autoware_localization_util/src/tree_structured_parzen_estimator.cpp b/localization/autoware_localization_util/src/tree_structured_parzen_estimator.cpp deleted file mode 100644 index e9f0318d1e06d..0000000000000 --- a/localization/autoware_localization_util/src/tree_structured_parzen_estimator.cpp +++ /dev/null @@ -1,185 +0,0 @@ -// Copyright 2023 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/localization_util/tree_structured_parzen_estimator.hpp" - -#include -#include -#include -#include -#include -#include -#include - -namespace autoware::localization_util -{ -// random number generator -std::mt19937_64 TreeStructuredParzenEstimator::engine(0); - -TreeStructuredParzenEstimator::TreeStructuredParzenEstimator( - const Direction direction, const int64_t n_startup_trials, std::vector sample_mean, - std::vector sample_stddev) -: above_num_(0), - direction_(direction), - n_startup_trials_(n_startup_trials), - input_dimension_(INDEX_NUM), - sample_mean_(std::move(sample_mean)), - sample_stddev_(std::move(sample_stddev)) -{ - if (sample_mean_.size() != ANGLE_Z) { - std::cerr << "sample_mean size is invalid" << std::endl; - throw std::runtime_error("sample_mean size is invalid"); - } - if (sample_stddev_.size() != ANGLE_Z) { - std::cerr << "sample_stddev size is invalid" << std::endl; - throw std::runtime_error("sample_stddev size is invalid"); - } - // base_stddev_ is defined as the stable convergence range of ndt_scan_matcher. - base_stddev_.resize(input_dimension_); - base_stddev_[TRANS_X] = 0.25; // [m] - base_stddev_[TRANS_Y] = 0.25; // [m] - base_stddev_[TRANS_Z] = 0.25; // [m] - base_stddev_[ANGLE_X] = 1.0 / 180.0 * M_PI; // [rad] - base_stddev_[ANGLE_Y] = 1.0 / 180.0 * M_PI; // [rad] - base_stddev_[ANGLE_Z] = 2.5 / 180.0 * M_PI; // [rad] -} - -void TreeStructuredParzenEstimator::add_trial(const Trial & trial) -{ - trials_.push_back(trial); - std::sort(trials_.begin(), trials_.end(), [this](const Trial & lhs, const Trial & rhs) { - return (direction_ == Direction::MAXIMIZE ? lhs.score > rhs.score : lhs.score < rhs.score); - }); - above_num_ = std::min( - {static_cast(10), - static_cast(static_cast(trials_.size()) * max_good_rate)}); -} - -TreeStructuredParzenEstimator::Input TreeStructuredParzenEstimator::get_next_input() const -{ - std::normal_distribution dist_normal_trans_x( - sample_mean_[TRANS_X], sample_stddev_[TRANS_X]); - std::normal_distribution dist_normal_trans_y( - sample_mean_[TRANS_Y], sample_stddev_[TRANS_Y]); - std::normal_distribution dist_normal_trans_z( - sample_mean_[TRANS_Z], sample_stddev_[TRANS_Z]); - std::normal_distribution dist_normal_angle_x( - sample_mean_[ANGLE_X], sample_stddev_[ANGLE_X]); - std::normal_distribution dist_normal_angle_y( - sample_mean_[ANGLE_Y], sample_stddev_[ANGLE_Y]); - std::uniform_real_distribution dist_uniform_angle_z(-M_PI, M_PI); - - if (static_cast(trials_.size()) < n_startup_trials_ || above_num_ == 0) { - // Random sampling based on prior until the number of trials reaches `n_startup_trials_`. - Input input(input_dimension_); - input[TRANS_X] = dist_normal_trans_x(engine); - input[TRANS_Y] = dist_normal_trans_y(engine); - input[TRANS_Z] = dist_normal_trans_z(engine); - input[ANGLE_X] = dist_normal_angle_x(engine); - input[ANGLE_Y] = dist_normal_angle_y(engine); - input[ANGLE_Z] = dist_uniform_angle_z(engine); - return input; - } - - Input best_input; - double best_log_likelihood_ratio = std::numeric_limits::lowest(); - for (int64_t i = 0; i < n_ei_candidates; i++) { - Input input(input_dimension_); - input[TRANS_X] = dist_normal_trans_x(engine); - input[TRANS_Y] = dist_normal_trans_y(engine); - input[TRANS_Z] = dist_normal_trans_z(engine); - input[ANGLE_X] = dist_normal_angle_x(engine); - input[ANGLE_Y] = dist_normal_angle_y(engine); - input[ANGLE_Z] = dist_uniform_angle_z(engine); - const double log_likelihood_ratio = compute_log_likelihood_ratio(input); - if (log_likelihood_ratio > best_log_likelihood_ratio) { - best_log_likelihood_ratio = log_likelihood_ratio; - best_input = input; - } - } - return best_input; -} - -double TreeStructuredParzenEstimator::compute_log_likelihood_ratio(const Input & input) const -{ - const auto n = static_cast(trials_.size()); - - // The above KDE and the below KDE are calculated respectively, and the ratio is the criteria to - // select best sample. - std::vector above_logs; - std::vector below_logs; - - for (int64_t i = 0; i < n; i++) { - const double log_p = log_gaussian_pdf(input, trials_[i].input, base_stddev_); - if (i < above_num_) { - const double w = 1.0 / static_cast(above_num_); - const double log_w = std::log(w); - above_logs.push_back(log_p + log_w); - } else { - const double w = 1.0 / static_cast(n - above_num_); - const double log_w = std::log(w); - below_logs.push_back(log_p + log_w); - } - } - - auto log_sum_exp = [](const std::vector & log_vec) { - const double max = *std::max_element(log_vec.begin(), log_vec.end()); - double sum = std::accumulate( - log_vec.begin(), log_vec.end(), 0.0, - [max](double total, double log_v) { return total + std::exp(log_v - max); }); - return max + std::log(sum); - }; - - const double above = log_sum_exp(above_logs); - const double below = log_sum_exp(below_logs); - - // Multiply by a constant so that the score near the "below sample" becomes lower. - // cspell:disable-line TODO(Shintaro Sakoda): It's theoretically incorrect, consider it again - // later. - const double r = above - below * 5.0; - return r; -} - -double TreeStructuredParzenEstimator::log_gaussian_pdf( - const Input & input, const Input & mu, const Input & sigma) -{ - const double log_2pi = std::log(2.0 * M_PI); - auto log_gaussian_pdf_1d = [&](const double diff, const double sigma) { - return -0.5 * log_2pi - std::log(sigma) - (diff * diff) / (2.0 * sigma * sigma); - }; - - const auto n = static_cast(input.size()); - - double result = 0.0; - for (int64_t i = 0; i < n; i++) { - double diff = input[i] - mu[i]; - if (i == ANGLE_Z) { - // Normalize the loop variable to [-pi, pi) - while (diff >= M_PI) { - diff -= 2 * M_PI; - } - while (diff < -M_PI) { - diff += 2 * M_PI; - } - } - // Experimentally, it is better to consider only trans_xy and yaw, so ignore trans_z, angle_x, - // angle_y. - if (i == TRANS_Z || i == ANGLE_X || i == ANGLE_Y) { - continue; - } - result += log_gaussian_pdf_1d(diff, sigma[i]); - } - return result; -} -} // namespace autoware::localization_util diff --git a/localization/autoware_localization_util/src/util_func.cpp b/localization/autoware_localization_util/src/util_func.cpp deleted file mode 100644 index 17187a8d732f0..0000000000000 --- a/localization/autoware_localization_util/src/util_func.cpp +++ /dev/null @@ -1,257 +0,0 @@ -// Copyright 2015-2019 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/localization_util/util_func.hpp" - -#include "autoware/localization_util/matrix_type.hpp" - -#include -#include - -namespace autoware::localization_util -{ -// ref by http://takacity.blog.fc2.com/blog-entry-69.html -std_msgs::msg::ColorRGBA exchange_color_crc(double x) -{ - std_msgs::msg::ColorRGBA color; - - x = std::max(x, 0.0); - x = std::min(x, 0.9999); - - if (x <= 0.25) { - color.b = 1.0; - color.g = static_cast(std::sin(x * 2.0 * M_PI)); - color.r = 0; - } else if (x <= 0.5) { - color.b = static_cast(std::sin(x * 2 * M_PI)); - color.g = 1.0; - color.r = 0; - } else if (x <= 0.75) { - color.b = 0; - color.g = 1.0; - color.r = static_cast(-std::sin(x * 2.0 * M_PI)); - } else { - color.b = 0; - color.g = static_cast(-std::sin(x * 2.0 * M_PI)); - color.r = 1.0; - } - color.a = 0.999; - return color; -} - -double calc_diff_for_radian(const double lhs_rad, const double rhs_rad) -{ - double diff_rad = lhs_rad - rhs_rad; - if (diff_rad > M_PI) { - diff_rad = diff_rad - 2 * M_PI; - } else if (diff_rad < -M_PI) { - diff_rad = diff_rad + 2 * M_PI; - } - return diff_rad; -} - -Eigen::Map make_eigen_covariance(const std::array & covariance) -{ - return {covariance.data(), 6, 6}; -} - -// x: roll, y: pitch, z: yaw -geometry_msgs::msg::Vector3 get_rpy(const geometry_msgs::msg::Pose & pose) -{ - geometry_msgs::msg::Vector3 rpy; - tf2::Quaternion q(pose.orientation.x, pose.orientation.y, pose.orientation.z, pose.orientation.w); - tf2::Matrix3x3(q).getRPY(rpy.x, rpy.y, rpy.z); - return rpy; -} - -geometry_msgs::msg::Vector3 get_rpy(const geometry_msgs::msg::PoseStamped & pose) -{ - return get_rpy(pose.pose); -} - -geometry_msgs::msg::Vector3 get_rpy(const geometry_msgs::msg::PoseWithCovarianceStamped & pose) -{ - return get_rpy(pose.pose.pose); -} - -geometry_msgs::msg::Quaternion rpy_rad_to_quaternion( - const double r_rad, const double p_rad, const double y_rad) -{ - tf2::Quaternion q; - q.setRPY(r_rad, p_rad, y_rad); - geometry_msgs::msg::Quaternion quaternion_msg; - quaternion_msg.x = q.x(); - quaternion_msg.y = q.y(); - quaternion_msg.z = q.z(); - quaternion_msg.w = q.w(); - return quaternion_msg; -} - -geometry_msgs::msg::Quaternion rpy_deg_to_quaternion( - const double r_deg, const double p_deg, const double y_deg) -{ - const double r_rad = r_deg * M_PI / 180.0; - const double p_rad = p_deg * M_PI / 180.0; - const double y_rad = y_deg * M_PI / 180.0; - return rpy_rad_to_quaternion(r_rad, p_rad, y_rad); -} - -geometry_msgs::msg::Twist calc_twist( - const geometry_msgs::msg::PoseStamped & pose_a, const geometry_msgs::msg::PoseStamped & pose_b) -{ - const rclcpp::Duration dt = rclcpp::Time(pose_b.header.stamp) - rclcpp::Time(pose_a.header.stamp); - const double dt_s = dt.seconds(); - - if (dt_s == 0) { - return geometry_msgs::msg::Twist(); - } - - const auto pose_a_rpy = get_rpy(pose_a); - const auto pose_b_rpy = get_rpy(pose_b); - - geometry_msgs::msg::Vector3 diff_xyz; - geometry_msgs::msg::Vector3 diff_rpy; - - diff_xyz.x = pose_b.pose.position.x - pose_a.pose.position.x; - diff_xyz.y = pose_b.pose.position.y - pose_a.pose.position.y; - diff_xyz.z = pose_b.pose.position.z - pose_a.pose.position.z; - diff_rpy.x = calc_diff_for_radian(pose_b_rpy.x, pose_a_rpy.x); - diff_rpy.y = calc_diff_for_radian(pose_b_rpy.y, pose_a_rpy.y); - diff_rpy.z = calc_diff_for_radian(pose_b_rpy.z, pose_a_rpy.z); - - geometry_msgs::msg::Twist twist; - twist.linear.x = diff_xyz.x / dt_s; - twist.linear.y = diff_xyz.y / dt_s; - twist.linear.z = diff_xyz.z / dt_s; - twist.angular.x = diff_rpy.x / dt_s; - twist.angular.y = diff_rpy.y / dt_s; - twist.angular.z = diff_rpy.z / dt_s; - - return twist; -} - -geometry_msgs::msg::PoseStamped interpolate_pose( - const geometry_msgs::msg::PoseStamped & pose_a, const geometry_msgs::msg::PoseStamped & pose_b, - const rclcpp::Time & time_stamp) -{ - const rclcpp::Time pose_a_time_stamp = pose_a.header.stamp; - const rclcpp::Time pose_b_time_stamp = pose_b.header.stamp; - if ( - (pose_a_time_stamp.seconds() == 0.0) || (pose_b_time_stamp.seconds() == 0.0) || - (time_stamp.seconds() == 0.0)) { - return geometry_msgs::msg::PoseStamped(); - } - - const auto twist = calc_twist(pose_a, pose_b); - const double dt = (time_stamp - pose_a_time_stamp).seconds(); - - const auto pose_a_rpy = get_rpy(pose_a); - - geometry_msgs::msg::Vector3 xyz; - geometry_msgs::msg::Vector3 rpy; - xyz.x = pose_a.pose.position.x + twist.linear.x * dt; - xyz.y = pose_a.pose.position.y + twist.linear.y * dt; - xyz.z = pose_a.pose.position.z + twist.linear.z * dt; - rpy.x = pose_a_rpy.x + twist.angular.x * dt; - rpy.y = pose_a_rpy.y + twist.angular.y * dt; - rpy.z = pose_a_rpy.z + twist.angular.z * dt; - - tf2::Quaternion tf_quaternion; - tf_quaternion.setRPY(rpy.x, rpy.y, rpy.z); - - geometry_msgs::msg::PoseStamped pose; - pose.header = pose_a.header; - pose.header.stamp = time_stamp; - pose.pose.position.x = xyz.x; - pose.pose.position.y = xyz.y; - pose.pose.position.z = xyz.z; - pose.pose.orientation = tf2::toMsg(tf_quaternion); - return pose; -} - -geometry_msgs::msg::PoseStamped interpolate_pose( - const geometry_msgs::msg::PoseWithCovarianceStamped & pose_a, - const geometry_msgs::msg::PoseWithCovarianceStamped & pose_b, const rclcpp::Time & time_stamp) -{ - geometry_msgs::msg::PoseStamped tmp_pose_a; - tmp_pose_a.header = pose_a.header; - tmp_pose_a.pose = pose_a.pose.pose; - - geometry_msgs::msg::PoseStamped tmp_pose_b; - tmp_pose_b.header = pose_b.header; - tmp_pose_b.pose = pose_b.pose.pose; - - return interpolate_pose(tmp_pose_a, tmp_pose_b, time_stamp); -} - -Eigen::Affine3d pose_to_affine3d(const geometry_msgs::msg::Pose & ros_pose) -{ - Eigen::Affine3d eigen_pose; - tf2::fromMsg(ros_pose, eigen_pose); - return eigen_pose; -} - -Eigen::Matrix4f pose_to_matrix4f(const geometry_msgs::msg::Pose & ros_pose) -{ - Eigen::Affine3d eigen_pose_affine = pose_to_affine3d(ros_pose); - Eigen::Matrix4f eigen_pose_matrix = eigen_pose_affine.matrix().cast(); - return eigen_pose_matrix; -} - -Eigen::Vector3d point_to_vector3d(const geometry_msgs::msg::Point & ros_pos) -{ - Eigen::Vector3d eigen_pos; - eigen_pos.x() = ros_pos.x; - eigen_pos.y() = ros_pos.y; - eigen_pos.z() = ros_pos.z; - return eigen_pos; -} - -geometry_msgs::msg::Pose matrix4f_to_pose(const Eigen::Matrix4f & eigen_pose_matrix) -{ - Eigen::Affine3d eigen_pose_affine; - eigen_pose_affine.matrix() = eigen_pose_matrix.cast(); - geometry_msgs::msg::Pose ros_pose = tf2::toMsg(eigen_pose_affine); - return ros_pose; -} - -double norm(const geometry_msgs::msg::Point & p1, const geometry_msgs::msg::Point & p2) -{ - const double dx = p1.x - p2.x; - const double dy = p1.y - p2.y; - const double dz = p1.z - p2.z; - return std::sqrt(dx * dx + dy * dy + dz * dz); -} - -void output_pose_with_cov_to_log( - const rclcpp::Logger & logger, const std::string & prefix, - const geometry_msgs::msg::PoseWithCovarianceStamped & pose_with_cov) -{ - const Eigen::Map covariance = - make_eigen_covariance(pose_with_cov.pose.covariance); - const geometry_msgs::msg::Pose pose = pose_with_cov.pose.pose; - geometry_msgs::msg::Vector3 rpy = get_rpy(pose); - rpy.x = rpy.x * 180.0 / M_PI; - rpy.y = rpy.y * 180.0 / M_PI; - rpy.z = rpy.z * 180.0 / M_PI; - - RCLCPP_DEBUG_STREAM( - logger, std::fixed << prefix << "," << pose.position.x << "," << pose.position.y << "," - << pose.position.z << "," << pose.orientation.x << "," << pose.orientation.y - << "," << pose.orientation.z << "," << pose.orientation.w << "," << rpy.x - << "," << rpy.y << "," << rpy.z << "," << covariance(0, 0) << "," - << covariance(1, 1) << "," << covariance(2, 2) << "," << covariance(3, 3) - << "," << covariance(4, 4) << "," << covariance(5, 5)); -} -} // namespace autoware::localization_util diff --git a/localization/autoware_localization_util/test/test_smart_pose_buffer.cpp b/localization/autoware_localization_util/test/test_smart_pose_buffer.cpp deleted file mode 100644 index d55555682be84..0000000000000 --- a/localization/autoware_localization_util/test/test_smart_pose_buffer.cpp +++ /dev/null @@ -1,109 +0,0 @@ -// Copyright 2023- Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/localization_util/smart_pose_buffer.hpp" -#include "autoware/localization_util/util_func.hpp" - -#include -#include - -#include -#include - -#include -#include -#include - -using PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped; -using SmartPoseBuffer = autoware::localization_util::SmartPoseBuffer; - -bool compare_pose( - const PoseWithCovarianceStamped & pose_a, const PoseWithCovarianceStamped & pose_b) -{ - return pose_a.header.stamp == pose_b.header.stamp && - pose_a.header.frame_id == pose_b.header.frame_id && - pose_a.pose.covariance == pose_b.pose.covariance && - pose_a.pose.pose.position.x == pose_b.pose.pose.position.x && - pose_a.pose.pose.position.y == pose_b.pose.pose.position.y && - pose_a.pose.pose.position.z == pose_b.pose.pose.position.z && - pose_a.pose.pose.orientation.x == pose_b.pose.pose.orientation.x && - pose_a.pose.pose.orientation.y == pose_b.pose.pose.orientation.y && - pose_a.pose.pose.orientation.z == pose_b.pose.pose.orientation.z && - pose_a.pose.pose.orientation.w == pose_b.pose.pose.orientation.w; -} - -TEST(TestSmartPoseBuffer, interpolate_pose) // NOLINT -{ - rclcpp::Logger logger = rclcpp::get_logger("test_logger"); - const double pose_timeout_sec = 10.0; - const double pose_distance_tolerance_meters = 100.0; - SmartPoseBuffer smart_pose_buffer(logger, pose_timeout_sec, pose_distance_tolerance_meters); - - // first data - PoseWithCovarianceStamped::SharedPtr old_pose_ptr = std::make_shared(); - old_pose_ptr->header.stamp.sec = 10; - old_pose_ptr->header.stamp.nanosec = 0; - old_pose_ptr->pose.pose.position.x = 10.0; - old_pose_ptr->pose.pose.position.y = 20.0; - old_pose_ptr->pose.pose.position.z = 0.0; - old_pose_ptr->pose.pose.orientation = - autoware::localization_util::rpy_deg_to_quaternion(0.0, 0.0, 0.0); - smart_pose_buffer.push_back(old_pose_ptr); - - // second data - PoseWithCovarianceStamped::SharedPtr new_pose_ptr = std::make_shared(); - new_pose_ptr->header.stamp.sec = 20; - new_pose_ptr->header.stamp.nanosec = 0; - new_pose_ptr->pose.pose.position.x = 20.0; - new_pose_ptr->pose.pose.position.y = 40.0; - new_pose_ptr->pose.pose.position.z = 0.0; - new_pose_ptr->pose.pose.orientation = - autoware::localization_util::rpy_deg_to_quaternion(0.0, 0.0, 90.0); - smart_pose_buffer.push_back(new_pose_ptr); - - // interpolate - builtin_interfaces::msg::Time target_ros_time_msg; - target_ros_time_msg.sec = 15; - target_ros_time_msg.nanosec = 0; - const std::optional & interpolate_result = - smart_pose_buffer.interpolate(target_ros_time_msg); - ASSERT_TRUE(interpolate_result.has_value()); - const SmartPoseBuffer::InterpolateResult result = interpolate_result.value(); - - // check old - EXPECT_TRUE(compare_pose(result.old_pose, *old_pose_ptr)); - - // check new - EXPECT_TRUE(compare_pose(result.new_pose, *new_pose_ptr)); - - // check interpolated - EXPECT_EQ(result.interpolated_pose.header.stamp.sec, 15); - EXPECT_EQ(result.interpolated_pose.header.stamp.nanosec, static_cast(0)); - EXPECT_EQ(result.interpolated_pose.pose.pose.position.x, 15.0); - EXPECT_EQ(result.interpolated_pose.pose.pose.position.y, 30.0); - EXPECT_EQ(result.interpolated_pose.pose.pose.position.z, 0.0); - const auto rpy = autoware::localization_util::get_rpy(result.interpolated_pose.pose.pose); - EXPECT_NEAR(rpy.x * 180 / M_PI, 0.0, 1e-6); - EXPECT_NEAR(rpy.y * 180 / M_PI, 0.0, 1e-6); - EXPECT_NEAR(rpy.z * 180 / M_PI, 45.0, 1e-6); -} - -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - ::testing::InitGoogleTest(&argc, argv); - int result = RUN_ALL_TESTS(); - rclcpp::shutdown(); - return result; -} diff --git a/localization/autoware_localization_util/test/test_tpe.cpp b/localization/autoware_localization_util/test/test_tpe.cpp deleted file mode 100644 index 2d71a385246b7..0000000000000 --- a/localization/autoware_localization_util/test/test_tpe.cpp +++ /dev/null @@ -1,75 +0,0 @@ -// Copyright 2023 The Autoware Contributors -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/localization_util/tree_structured_parzen_estimator.hpp" - -#include - -#include -#include -#include -#include -#include - -using TreeStructuredParzenEstimator = autoware::localization_util::TreeStructuredParzenEstimator; - -TEST(TreeStructuredParzenEstimatorTest, TPE_is_better_than_random_search_on_sphere_function) -{ - auto sphere_function = [](const TreeStructuredParzenEstimator::Input & input) { - double value = 0.0; - const auto n = static_cast(input.size()); - for (int64_t i = 0; i < n; i++) { - const double v = input[i] * 10; - value += v * v; - } - return value; - }; - - constexpr int64_t k_outer_trials_num = 20; - constexpr int64_t k_inner_trials_num = 200; - std::cout << std::fixed; - std::vector mean_scores; - std::vector sample_mean(5, 0.0); - std::vector sample_stddev{1.0, 1.0, 0.1, 0.1, 0.1}; - - for (const int64_t n_startup_trials : {k_inner_trials_num, k_inner_trials_num / 2}) { - const std::string method = ((n_startup_trials == k_inner_trials_num) ? "Random" : "TPE"); - - std::vector scores; - for (int64_t i = 0; i < k_outer_trials_num; i++) { - double best_score = std::numeric_limits::lowest(); - TreeStructuredParzenEstimator estimator( - TreeStructuredParzenEstimator::Direction::MAXIMIZE, n_startup_trials, sample_mean, - sample_stddev); - for (int64_t trial = 0; trial < k_inner_trials_num; trial++) { - const TreeStructuredParzenEstimator::Input input = estimator.get_next_input(); - const double score = -sphere_function(input); - estimator.add_trial({input, score}); - best_score = std::max(best_score, score); - } - scores.push_back(best_score); - } - - const double sum = std::accumulate(scores.begin(), scores.end(), 0.0); - const double mean = sum / static_cast(scores.size()); - mean_scores.push_back(mean); - double sq_sum = std::accumulate( - scores.begin(), scores.end(), 0.0, - [mean](double total, double score) { return total + (score - mean) * (score - mean); }); - const double stddev = std::sqrt(sq_sum / static_cast(scores.size())); - - std::cout << method << ", mean = " << mean << ", stddev = " << stddev << std::endl; - } - ASSERT_LT(mean_scores[0], mean_scores[1]); -} From 557a71e16695083aa40091b60f17c1daa90a257d Mon Sep 17 00:00:00 2001 From: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Date: Wed, 15 Jan 2025 10:52:13 +0900 Subject: [PATCH 200/334] fix(dummy_infrastructure): fix bugprone-reserved-identifier (#9919) Signed-off-by: kobayu858 Co-authored-by: kobayu858 --- .../src/dummy_infrastructure_node/dummy_infrastructure_node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system/dummy_infrastructure/src/dummy_infrastructure_node/dummy_infrastructure_node.cpp b/system/dummy_infrastructure/src/dummy_infrastructure_node/dummy_infrastructure_node.cpp index 485d85c926268..4760c9366da46 100644 --- a/system/dummy_infrastructure/src/dummy_infrastructure_node/dummy_infrastructure_node.cpp +++ b/system/dummy_infrastructure/src/dummy_infrastructure_node/dummy_infrastructure_node.cpp @@ -24,7 +24,6 @@ using namespace std::literals; using std::chrono::duration; using std::chrono::duration_cast; using std::chrono::nanoseconds; -using std::placeholders::_1; namespace dummy_infrastructure { @@ -84,6 +83,7 @@ boost::optional findCommand( DummyInfrastructureNode::DummyInfrastructureNode(const rclcpp::NodeOptions & node_options) : Node("dummy_infrastructure", node_options) { + using std::placeholders::_1; // Parameter Server set_param_res_ = this->add_on_set_parameters_callback(std::bind(&DummyInfrastructureNode::onSetParam, this, _1)); From 6939a3da23a41781a6d973a8267e2ea1cb3a600d Mon Sep 17 00:00:00 2001 From: NorahXiong <103234047+NorahXiong@users.noreply.github.com> Date: Wed, 15 Jan 2025 09:57:09 +0800 Subject: [PATCH 201/334] feat(autoware_qp_interface): porting autoware_qp_interface package to autoware.core (#9824) Signed-off-by: NorahXiong --- common/autoware_qp_interface/CHANGELOG.rst | 81 ---- common/autoware_qp_interface/CMakeLists.txt | 64 --- .../design/qp_interface-design.md | 48 --- .../qp_interface/osqp_csc_matrix_conv.hpp | 46 -- .../autoware/qp_interface/osqp_interface.hpp | 147 ------- .../qp_interface/proxqp_interface.hpp | 57 --- .../autoware/qp_interface/qp_interface.hpp | 61 --- common/autoware_qp_interface/package.xml | 30 -- .../src/osqp_csc_matrix_conv.cpp | 134 ------ .../src/osqp_interface.cpp | 394 ------------------ .../src/proxqp_interface.cpp | 157 ------- .../src/qp_interface.cpp | 70 ---- .../test/test_csc_matrix_conv.cpp | 181 -------- .../test/test_osqp_interface.cpp | 170 -------- .../test/test_proxqp_interface.cpp | 85 ---- 15 files changed, 1725 deletions(-) delete mode 100644 common/autoware_qp_interface/CHANGELOG.rst delete mode 100644 common/autoware_qp_interface/CMakeLists.txt delete mode 100644 common/autoware_qp_interface/design/qp_interface-design.md delete mode 100644 common/autoware_qp_interface/include/autoware/qp_interface/osqp_csc_matrix_conv.hpp delete mode 100644 common/autoware_qp_interface/include/autoware/qp_interface/osqp_interface.hpp delete mode 100644 common/autoware_qp_interface/include/autoware/qp_interface/proxqp_interface.hpp delete mode 100644 common/autoware_qp_interface/include/autoware/qp_interface/qp_interface.hpp delete mode 100644 common/autoware_qp_interface/package.xml delete mode 100644 common/autoware_qp_interface/src/osqp_csc_matrix_conv.cpp delete mode 100644 common/autoware_qp_interface/src/osqp_interface.cpp delete mode 100644 common/autoware_qp_interface/src/proxqp_interface.cpp delete mode 100644 common/autoware_qp_interface/src/qp_interface.cpp delete mode 100644 common/autoware_qp_interface/test/test_csc_matrix_conv.cpp delete mode 100644 common/autoware_qp_interface/test/test_osqp_interface.cpp delete mode 100644 common/autoware_qp_interface/test/test_proxqp_interface.cpp diff --git a/common/autoware_qp_interface/CHANGELOG.rst b/common/autoware_qp_interface/CHANGELOG.rst deleted file mode 100644 index f76dac861e1e6..0000000000000 --- a/common/autoware_qp_interface/CHANGELOG.rst +++ /dev/null @@ -1,81 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package autoware_qp_interface -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -0.40.0 (2024-12-12) -------------------- -* Merge branch 'main' into release-0.40.0 -* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" - This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. -* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) -* chore(package.xml): bump version to 0.39.0 (`#9587 `_) - * chore(package.xml): bump version to 0.39.0 - * fix: fix ticket links in CHANGELOG.rst - * fix: remove unnecessary diff - --------- - Co-authored-by: Yutaka Kondo -* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) -* fix(cpplint): include what you use - common (`#9564 `_) -* fix: fix package names in changelog files (`#9500 `_) -* fix(autoware_osqp_interface): fix clang-tidy errors (`#9440 `_) -* 0.39.0 -* update changelog -* Merge commit '6a1ddbd08bd' into release-0.39.0 -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) - * unify package.xml version to 0.37.0 - * remove system_monitor/CHANGELOG.rst - * add changelog - * 0.38.0 - --------- -* refactor(qp_interface): prefix package and namespace with autoware (`#9236 `_) -* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Ryuta Kambe, Yutaka Kondo - -0.39.0 (2024-11-25) -------------------- -* Merge commit '6a1ddbd08bd' into release-0.39.0 -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) - * unify package.xml version to 0.37.0 - * remove system_monitor/CHANGELOG.rst - * add changelog - * 0.38.0 - --------- -* refactor(qp_interface): prefix package and namespace with autoware (`#9236 `_) -* Contributors: Esteve Fernandez, Yutaka Kondo - -0.38.0 (2024-11-08) -------------------- -* unify package.xml version to 0.37.0 -* fix(qp_interface): fix unreadVariable (`#8349 `_) - * fix:unreadVariable - * fix:unreadVariable - * fix:unreadVariable - --------- -* perf(velocity_smoother): use ProxQP for faster optimization (`#8028 `_) - * perf(velocity_smoother): use ProxQP for faster optimization - * consider max_iteration - * disable warm start - * fix test - --------- -* refactor(qp_interface): clean up the code (`#8029 `_) - * refactor qp_interface - * variable names: m_XXX -> XXX\_ - * update - * update - --------- -* fix(fake_test_node, osqp_interface, qp_interface): remove unnecessary cppcheck inline suppressions (`#7855 `_) - * fix(fake_test_node, osqp_interface, qp_interface): remove unnecessary cppcheck inline suppressions - * style(pre-commit): autofix - --------- - Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> -* Contributors: Ryuta Kambe, Takayuki Murooka, Yutaka Kondo, kobayu858 - -0.26.0 (2024-04-03) -------------------- -* feat(qp_interface): support proxqp (`#3699 `_) - * feat(qp_interface): add proxqp interface - * update - --------- -* feat(qp_interface): add new package which will contain various qp solvers (`#3697 `_) -* Contributors: Takayuki Murooka diff --git a/common/autoware_qp_interface/CMakeLists.txt b/common/autoware_qp_interface/CMakeLists.txt deleted file mode 100644 index 1df75d2d719a0..0000000000000 --- a/common/autoware_qp_interface/CMakeLists.txt +++ /dev/null @@ -1,64 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(autoware_qp_interface) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -find_package(Eigen3 REQUIRED) -find_package(proxsuite REQUIRED) - -# after find_package(osqp_vendor) in ament_auto_find_build_dependencies -find_package(osqp REQUIRED) -get_target_property(OSQP_INCLUDE_SUB_DIR osqp::osqp INTERFACE_INCLUDE_DIRECTORIES) -get_filename_component(OSQP_INCLUDE_DIR ${OSQP_INCLUDE_SUB_DIR} PATH) - -set(QP_INTERFACE_LIB_SRC - src/qp_interface.cpp - src/osqp_interface.cpp - src/osqp_csc_matrix_conv.cpp - src/proxqp_interface.cpp -) - -set(QP_INTERFACE_LIB_HEADERS - include/autoware/qp_interface/qp_interface.hpp - include/autoware/qp_interface/osqp_interface.hpp - include/autoware/qp_interface/osqp_csc_matrix_conv.hpp - include/autoware/qp_interface/proxqp_interface.hpp -) - -ament_auto_add_library(${PROJECT_NAME} SHARED - ${QP_INTERFACE_LIB_SRC} - ${QP_INTERFACE_LIB_HEADERS} -) -target_compile_options(${PROJECT_NAME} PRIVATE -Wno-error=old-style-cast) - -target_include_directories(${PROJECT_NAME} - SYSTEM PUBLIC - "${OSQP_INCLUDE_DIR}" - "${EIGEN3_INCLUDE_DIR}" -) - -ament_target_dependencies(${PROJECT_NAME} - Eigen3 - osqp_vendor - proxsuite -) - -# crucial so downstream package builds because osqp_interface exposes osqp.hpp -ament_export_include_directories("${OSQP_INCLUDE_DIR}") -# crucial so the linking order is correct in a downstream package: libosqp_interface.a should come before libosqp.a -ament_export_libraries(osqp::osqp) - -if(BUILD_TESTING) - set(TEST_SOURCES - test/test_osqp_interface.cpp - test/test_csc_matrix_conv.cpp - test/test_proxqp_interface.cpp - ) - set(TEST_OSQP_INTERFACE_EXE test_osqp_interface) - ament_add_ros_isolated_gtest(${TEST_OSQP_INTERFACE_EXE} ${TEST_SOURCES}) - target_link_libraries(${TEST_OSQP_INTERFACE_EXE} ${PROJECT_NAME}) -endif() - -ament_auto_package(INSTALL_TO_SHARE -) diff --git a/common/autoware_qp_interface/design/qp_interface-design.md b/common/autoware_qp_interface/design/qp_interface-design.md deleted file mode 100644 index edc7fa9845206..0000000000000 --- a/common/autoware_qp_interface/design/qp_interface-design.md +++ /dev/null @@ -1,48 +0,0 @@ -# Interface for QP solvers - -This is the design document for the `autoware_qp_interface` package. - -## Purpose / Use cases - -This packages provides a C++ interface for QP solvers. -Currently, supported QP solvers are - -- [OSQP library](https://osqp.org/docs/solver/index.html) - -## Design - -The class `QPInterface` takes a problem formulation as Eigen matrices and vectors, converts these objects into -C-style Compressed-Column-Sparse matrices and dynamic arrays, loads the data into the QP workspace dataholder, and runs the optimizer. - -## Inputs / Outputs / API - -The interface can be used in several ways: - -1. Initialize the interface, and load the problem formulation at the optimization call. - - ```cpp - QPInterface qp_interface; - qp_interface.optimize(P, A, q, l, u); - ``` - -2. WARM START OPTIMIZATION by modifying the problem formulation between optimization runs. - - ```cpp - QPInterface qp_interface(true); - qp_interface.optimize(P, A, q, l, u); - qp_interface.optimize(P_new, A_new, q_new, l_new, u_new); - ``` - - The optimization results are returned as a vector by the optimization function. - - ```cpp - const auto solution = qp_interface.optimize(); - double x_0 = solution[0]; - double x_1 = solution[1]; - ``` - -## References / External links - -- OSQP library: - -## Related issues diff --git a/common/autoware_qp_interface/include/autoware/qp_interface/osqp_csc_matrix_conv.hpp b/common/autoware_qp_interface/include/autoware/qp_interface/osqp_csc_matrix_conv.hpp deleted file mode 100644 index 9575d9d18c69f..0000000000000 --- a/common/autoware_qp_interface/include/autoware/qp_interface/osqp_csc_matrix_conv.hpp +++ /dev/null @@ -1,46 +0,0 @@ -// Copyright 2023 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__QP_INTERFACE__OSQP_CSC_MATRIX_CONV_HPP_ -#define AUTOWARE__QP_INTERFACE__OSQP_CSC_MATRIX_CONV_HPP_ - -#include "osqp/glob_opts.h" - -#include - -#include - -namespace autoware::qp_interface -{ -/// \brief Compressed-Column-Sparse Matrix -struct CSC_Matrix -{ - /// Vector of non-zero values. Ex: [4,1,1,2] - std::vector vals_; - /// Vector of row index corresponding to values. Ex: [0, 1, 0, 1] (Eigen: 'inner') - std::vector row_idxs_; - /// Vector of 'val' indices where each column starts. Ex: [0, 2, 4] (Eigen: 'outer') - std::vector col_idxs_; -}; - -/// \brief Calculate CSC matrix from Eigen matrix -CSC_Matrix calCSCMatrix(const Eigen::MatrixXd & mat); -/// \brief Calculate upper trapezoidal CSC matrix from square Eigen matrix -CSC_Matrix calCSCMatrixTrapezoidal(const Eigen::MatrixXd & mat); -/// \brief Print the given CSC matrix to the standard output -void printCSCMatrix(const CSC_Matrix & csc_mat); - -} // namespace autoware::qp_interface - -#endif // AUTOWARE__QP_INTERFACE__OSQP_CSC_MATRIX_CONV_HPP_ diff --git a/common/autoware_qp_interface/include/autoware/qp_interface/osqp_interface.hpp b/common/autoware_qp_interface/include/autoware/qp_interface/osqp_interface.hpp deleted file mode 100644 index a5777dd545e9f..0000000000000 --- a/common/autoware_qp_interface/include/autoware/qp_interface/osqp_interface.hpp +++ /dev/null @@ -1,147 +0,0 @@ -// Copyright 2023 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__QP_INTERFACE__OSQP_INTERFACE_HPP_ -#define AUTOWARE__QP_INTERFACE__OSQP_INTERFACE_HPP_ - -#include "autoware/qp_interface/osqp_csc_matrix_conv.hpp" -#include "autoware/qp_interface/qp_interface.hpp" -#include "osqp/osqp.h" - -#include -#include -#include -#include - -namespace autoware::qp_interface -{ -constexpr c_float OSQP_INF = 1e30; - -class OSQPInterface : public QPInterface -{ -public: - /// \brief Constructor without problem formulation - OSQPInterface( - const bool enable_warm_start = false, const int max_iteration = 20000, - const c_float eps_abs = std::numeric_limits::epsilon(), - const c_float eps_rel = std::numeric_limits::epsilon(), const bool polish = true, - const bool verbose = false); - /// \brief Constructor with problem setup - /// \param P: (n,n) matrix defining relations between parameters. - /// \param A: (m,n) matrix defining parameter constraints relative to the lower and upper bound. - /// \param q: (n) vector defining the linear cost of the problem. - /// \param l: (m) vector defining the lower bound problem constraint. - /// \param u: (m) vector defining the upper bound problem constraint. - /// \param eps_abs: Absolute convergence tolerance. - OSQPInterface( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u, - const bool enable_warm_start = false, - const c_float eps_abs = std::numeric_limits::epsilon()); - OSQPInterface( - const CSC_Matrix & P, const CSC_Matrix & A, const std::vector & q, - const std::vector & l, const std::vector & u, - const bool enable_warm_start = false, - const c_float eps_abs = std::numeric_limits::epsilon()); - ~OSQPInterface(); - - static void OSQPWorkspaceDeleter(OSQPWorkspace * ptr) noexcept; - - std::vector optimize( - CSC_Matrix P, CSC_Matrix A, const std::vector & q, const std::vector & l, - const std::vector & u); - - int getIterationNumber() const override; - bool isSolved() const override; - std::string getStatus() const override; - - int getPolishStatus() const; - std::vector getDualSolution() const; - - void updateEpsAbs(const double eps_abs) override; - void updateEpsRel(const double eps_rel) override; - void updateVerbose(const bool verbose) override; - - // Updates problem parameters while keeping solution in memory. - // - // Args: - // P_new: (n,n) matrix defining relations between parameters. - // A_new: (m,n) matrix defining parameter constraints relative to the lower and upper bound. - // q_new: (n) vector defining the linear cost of the problem. - // l_new: (m) vector defining the lower bound problem constraint. - // u_new: (m) vector defining the upper bound problem constraint. - void updateP(const Eigen::MatrixXd & P_new); - void updateCscP(const CSC_Matrix & P_csc); - void updateA(const Eigen::MatrixXd & A_new); - void updateCscA(const CSC_Matrix & A_csc); - void updateQ(const std::vector & q_new); - void updateL(const std::vector & l_new); - void updateU(const std::vector & u_new); - void updateBounds(const std::vector & l_new, const std::vector & u_new); - - void updateMaxIter(const int iter); - void updateRhoInterval(const int rho_interval); - void updateRho(const double rho); - void updateAlpha(const double alpha); - void updateScaling(const int scaling); - void updatePolish(const bool polish); - void updatePolishRefinementIteration(const int polish_refine_iter); - void updateCheckTermination(const int check_termination); - - /// \brief Get the number of iteration taken to solve the problem - inline int64_t getTakenIter() const { return static_cast(latest_work_info_.iter); } - /// \brief Get the status message for the latest problem solved - inline std::string getStatusMessage() const - { - return static_cast(latest_work_info_.status); - } - /// \brief Get the runtime of the latest problem solved - inline double getRunTime() const { return latest_work_info_.run_time; } - /// \brief Get the objective value the latest problem solved - inline double getObjVal() const { return latest_work_info_.obj_val; } - /// \brief Returns flag asserting interface condition (Healthy condition: 0). - inline int64_t getExitFlag() const { return exitflag_; } - - // Setter functions for warm start - bool setWarmStart( - const std::vector & primal_variables, const std::vector & dual_variables); - bool setPrimalVariables(const std::vector & primal_variables); - bool setDualVariables(const std::vector & dual_variables); - -private: - std::unique_ptr> work_; - std::unique_ptr settings_; - std::unique_ptr data_; - // store last work info since work is cleaned up at every execution to prevent memory leak. - OSQPInfo latest_work_info_; - // Number of parameters to optimize - int64_t param_n_; - // Flag to check if the current work exists - bool work__initialized = false; - // Exitflag - int64_t exitflag_; - - void initializeProblemImpl( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u) override; - - void initializeCSCProblemImpl( - CSC_Matrix P, CSC_Matrix A, const std::vector & q, const std::vector & l, - const std::vector & u); - - std::vector optimizeImpl() override; -}; -} // namespace autoware::qp_interface - -#endif // AUTOWARE__QP_INTERFACE__OSQP_INTERFACE_HPP_ diff --git a/common/autoware_qp_interface/include/autoware/qp_interface/proxqp_interface.hpp b/common/autoware_qp_interface/include/autoware/qp_interface/proxqp_interface.hpp deleted file mode 100644 index 324da4b18c6fd..0000000000000 --- a/common/autoware_qp_interface/include/autoware/qp_interface/proxqp_interface.hpp +++ /dev/null @@ -1,57 +0,0 @@ -// Copyright 2023 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__QP_INTERFACE__PROXQP_INTERFACE_HPP_ -#define AUTOWARE__QP_INTERFACE__PROXQP_INTERFACE_HPP_ - -#include "autoware/qp_interface/qp_interface.hpp" - -#include -#include - -#include -#include -#include -#include - -namespace autoware::qp_interface -{ -class ProxQPInterface : public QPInterface -{ -public: - explicit ProxQPInterface( - const bool enable_warm_start, const int max_iteration, const double eps_abs, - const double eps_rel, const bool verbose = false); - - int getIterationNumber() const override; - bool isSolved() const override; - std::string getStatus() const override; - - void updateEpsAbs(const double eps_abs) override; - void updateEpsRel(const double eps_rel) override; - void updateVerbose(const bool verbose) override; - -private: - proxsuite::proxqp::Settings settings_{}; - std::shared_ptr> qp_ptr_{nullptr}; - - void initializeProblemImpl( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u) override; - - std::vector optimizeImpl() override; -}; -} // namespace autoware::qp_interface - -#endif // AUTOWARE__QP_INTERFACE__PROXQP_INTERFACE_HPP_ diff --git a/common/autoware_qp_interface/include/autoware/qp_interface/qp_interface.hpp b/common/autoware_qp_interface/include/autoware/qp_interface/qp_interface.hpp deleted file mode 100644 index be3c598512bf6..0000000000000 --- a/common/autoware_qp_interface/include/autoware/qp_interface/qp_interface.hpp +++ /dev/null @@ -1,61 +0,0 @@ -// Copyright 2023 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__QP_INTERFACE__QP_INTERFACE_HPP_ -#define AUTOWARE__QP_INTERFACE__QP_INTERFACE_HPP_ - -#include - -#include -#include -#include - -namespace autoware::qp_interface -{ -class QPInterface -{ -public: - explicit QPInterface(const bool enable_warm_start) : enable_warm_start_(enable_warm_start) {} - - std::vector optimize( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u); - - virtual bool isSolved() const = 0; - virtual int getIterationNumber() const = 0; - virtual std::string getStatus() const = 0; - - virtual void updateEpsAbs([[maybe_unused]] const double eps_abs) = 0; - virtual void updateEpsRel([[maybe_unused]] const double eps_rel) = 0; - virtual void updateVerbose([[maybe_unused]] const bool verbose) {} - -protected: - bool enable_warm_start_{false}; - - void initializeProblem( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u); - - virtual void initializeProblemImpl( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u) = 0; - - virtual std::vector optimizeImpl() = 0; - - std::optional variables_num_{std::nullopt}; - std::optional constraints_num_{std::nullopt}; -}; -} // namespace autoware::qp_interface - -#endif // AUTOWARE__QP_INTERFACE__QP_INTERFACE_HPP_ diff --git a/common/autoware_qp_interface/package.xml b/common/autoware_qp_interface/package.xml deleted file mode 100644 index b61d03a36db72..0000000000000 --- a/common/autoware_qp_interface/package.xml +++ /dev/null @@ -1,30 +0,0 @@ - - - - autoware_qp_interface - 0.40.0 - Interface for the QP solvers - Takayuki Murooka - Fumiya Watanabe - Maxime CLEMENT - Satoshi Ota - Apache 2.0 - - ament_cmake_auto - autoware_cmake - - eigen - osqp_vendor - proxsuite - rclcpp - rclcpp_components - - ament_cmake_ros - ament_lint_auto - autoware_lint_common - eigen - - - ament_cmake - - diff --git a/common/autoware_qp_interface/src/osqp_csc_matrix_conv.cpp b/common/autoware_qp_interface/src/osqp_csc_matrix_conv.cpp deleted file mode 100644 index 15314a9e4a5fa..0000000000000 --- a/common/autoware_qp_interface/src/osqp_csc_matrix_conv.cpp +++ /dev/null @@ -1,134 +0,0 @@ -// Copyright 2023 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/qp_interface/osqp_csc_matrix_conv.hpp" - -#include -#include - -#include -#include -#include - -namespace autoware::qp_interface -{ -CSC_Matrix calCSCMatrix(const Eigen::MatrixXd & mat) -{ - const size_t elem = static_cast(mat.nonZeros()); - const Eigen::Index rows = mat.rows(); - const Eigen::Index cols = mat.cols(); - - std::vector vals; - vals.reserve(elem); - std::vector row_idxs; - row_idxs.reserve(elem); - std::vector col_idxs; - col_idxs.reserve(elem); - - // Construct CSC matrix arrays - c_float val; - c_int elem_count = 0; - - col_idxs.push_back(0); - - for (Eigen::Index j = 0; j < cols; j++) { // col iteration - for (Eigen::Index i = 0; i < rows; i++) { // row iteration - // Get values of nonzero elements - val = mat(i, j); - if (std::fabs(val) < 1e-9) { - continue; - } - elem_count += 1; - - // Store values - vals.push_back(val); - row_idxs.push_back(i); - } - - col_idxs.push_back(elem_count); - } - - CSC_Matrix csc_matrix = {vals, row_idxs, col_idxs}; - - return csc_matrix; -} - -CSC_Matrix calCSCMatrixTrapezoidal(const Eigen::MatrixXd & mat) -{ - const size_t elem = static_cast(mat.nonZeros()); - const Eigen::Index rows = mat.rows(); - const Eigen::Index cols = mat.cols(); - - if (rows != cols) { - throw std::invalid_argument("Matrix must be square (n, n)"); - } - - std::vector vals; - vals.reserve(elem); - std::vector row_idxs; - row_idxs.reserve(elem); - std::vector col_idxs; - col_idxs.reserve(elem); - - // Construct CSC matrix arrays - c_float val; - Eigen::Index trap_last_idx = 0; - c_int elem_count = 0; - - col_idxs.push_back(0); - - for (Eigen::Index j = 0; j < cols; j++) { // col iteration - for (Eigen::Index i = 0; i <= trap_last_idx; i++) { // row iteration - // Get values of nonzero elements - val = mat(i, j); - if (std::fabs(val) < 1e-9) { - continue; - } - elem_count += 1; - - // Store values - vals.push_back(val); - row_idxs.push_back(i); - } - - col_idxs.push_back(elem_count); - trap_last_idx += 1; - } - - CSC_Matrix csc_matrix = {vals, row_idxs, col_idxs}; - - return csc_matrix; -} - -void printCSCMatrix(const CSC_Matrix & csc_mat) -{ - std::cout << "["; - for (const c_float & val : csc_mat.vals_) { - std::cout << val << ", "; - } - std::cout << "]\n"; - - std::cout << "["; - for (const c_int & row : csc_mat.row_idxs_) { - std::cout << row << ", "; - } - std::cout << "]\n"; - - std::cout << "["; - for (const c_int & col : csc_mat.col_idxs_) { - std::cout << col << ", "; - } - std::cout << "]\n"; -} -} // namespace autoware::qp_interface diff --git a/common/autoware_qp_interface/src/osqp_interface.cpp b/common/autoware_qp_interface/src/osqp_interface.cpp deleted file mode 100644 index fbb8e71f4c251..0000000000000 --- a/common/autoware_qp_interface/src/osqp_interface.cpp +++ /dev/null @@ -1,394 +0,0 @@ -// Copyright 2023 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/qp_interface/osqp_interface.hpp" - -#include "autoware/qp_interface/osqp_csc_matrix_conv.hpp" - -#include - -#include -#include -#include -#include - -namespace autoware::qp_interface -{ -OSQPInterface::OSQPInterface( - const bool enable_warm_start, const int max_iteration, const c_float eps_abs, - const c_float eps_rel, const bool polish, const bool verbose) -: QPInterface(enable_warm_start), work_{nullptr, OSQPWorkspaceDeleter} -{ - settings_ = std::make_unique(); - data_ = std::make_unique(); - - if (settings_) { - osqp_set_default_settings(settings_.get()); - settings_->alpha = 1.6; // Change alpha parameter - settings_->eps_rel = eps_rel; - settings_->eps_abs = eps_abs; - settings_->eps_prim_inf = 1.0E-4; - settings_->eps_dual_inf = 1.0E-4; - settings_->warm_start = enable_warm_start; - settings_->max_iter = max_iteration; - settings_->verbose = verbose; - settings_->polish = polish; - } - exitflag_ = 0; -} - -OSQPInterface::OSQPInterface( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u, const bool enable_warm_start, - const c_float eps_abs) -: OSQPInterface(enable_warm_start, eps_abs) -{ - initializeProblem(P, A, q, l, u); -} - -OSQPInterface::OSQPInterface( - const CSC_Matrix & P, const CSC_Matrix & A, const std::vector & q, - const std::vector & l, const std::vector & u, const bool enable_warm_start, - const c_float eps_abs) -: OSQPInterface(enable_warm_start, eps_abs) -{ - initializeCSCProblemImpl(P, A, q, l, u); -} - -OSQPInterface::~OSQPInterface() -{ - if (data_->P) free(data_->P); - if (data_->A) free(data_->A); -} - -void OSQPInterface::initializeProblemImpl( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u) -{ - CSC_Matrix P_csc = calCSCMatrixTrapezoidal(P); - CSC_Matrix A_csc = calCSCMatrix(A); - initializeCSCProblemImpl(P_csc, A_csc, q, l, u); -} - -void OSQPInterface::initializeCSCProblemImpl( - CSC_Matrix P_csc, CSC_Matrix A_csc, const std::vector & q, const std::vector & l, - const std::vector & u) -{ - // Dynamic float arrays - std::vector q_tmp(q.begin(), q.end()); - std::vector l_tmp(l.begin(), l.end()); - std::vector u_tmp(u.begin(), u.end()); - double * q_dyn = q_tmp.data(); - double * l_dyn = l_tmp.data(); - double * u_dyn = u_tmp.data(); - - /********************** - * OBJECTIVE FUNCTION - **********************/ - param_n_ = static_cast(q.size()); - data_->m = static_cast(l.size()); - - /***************** - * POPULATE DATA - *****************/ - data_->n = param_n_; - if (data_->P) free(data_->P); - data_->P = csc_matrix( - data_->n, data_->n, static_cast(P_csc.vals_.size()), P_csc.vals_.data(), - P_csc.row_idxs_.data(), P_csc.col_idxs_.data()); - data_->q = q_dyn; - if (data_->A) free(data_->A); - data_->A = csc_matrix( - data_->m, data_->n, static_cast(A_csc.vals_.size()), A_csc.vals_.data(), - A_csc.row_idxs_.data(), A_csc.col_idxs_.data()); - data_->l = l_dyn; - data_->u = u_dyn; - - // Setup workspace - OSQPWorkspace * workspace; - exitflag_ = osqp_setup(&workspace, data_.get(), settings_.get()); - work_.reset(workspace); - work__initialized = true; -} - -void OSQPInterface::OSQPWorkspaceDeleter(OSQPWorkspace * ptr) noexcept -{ - if (ptr != nullptr) { - osqp_cleanup(ptr); - } -} - -void OSQPInterface::updateEpsAbs(const double eps_abs) -{ - settings_->eps_abs = eps_abs; // for default setting - if (work__initialized) { - osqp_update_eps_abs(work_.get(), eps_abs); // for current work - } -} - -void OSQPInterface::updateEpsRel(const double eps_rel) -{ - settings_->eps_rel = eps_rel; // for default setting - if (work__initialized) { - osqp_update_eps_rel(work_.get(), eps_rel); // for current work - } -} - -void OSQPInterface::updateMaxIter(const int max_iter) -{ - settings_->max_iter = max_iter; // for default setting - if (work__initialized) { - osqp_update_max_iter(work_.get(), max_iter); // for current work - } -} - -void OSQPInterface::updateVerbose(const bool is_verbose) -{ - settings_->verbose = is_verbose; // for default setting - if (work__initialized) { - osqp_update_verbose(work_.get(), is_verbose); // for current work - } -} - -void OSQPInterface::updateRhoInterval(const int rho_interval) -{ - settings_->adaptive_rho_interval = rho_interval; // for default setting -} - -void OSQPInterface::updateRho(const double rho) -{ - settings_->rho = rho; - if (work__initialized) { - osqp_update_rho(work_.get(), rho); - } -} - -void OSQPInterface::updateAlpha(const double alpha) -{ - settings_->alpha = alpha; - if (work__initialized) { - osqp_update_alpha(work_.get(), alpha); - } -} - -void OSQPInterface::updateScaling(const int scaling) -{ - settings_->scaling = scaling; -} - -void OSQPInterface::updatePolish(const bool polish) -{ - settings_->polish = polish; - if (work__initialized) { - osqp_update_polish(work_.get(), polish); - } -} - -void OSQPInterface::updatePolishRefinementIteration(const int polish_refine_iter) -{ - if (polish_refine_iter < 0) { - std::cerr << "Polish refinement iterations must be positive" << std::endl; - return; - } - - settings_->polish_refine_iter = polish_refine_iter; - if (work__initialized) { - osqp_update_polish_refine_iter(work_.get(), polish_refine_iter); - } -} - -void OSQPInterface::updateCheckTermination(const int check_termination) -{ - if (check_termination < 0) { - std::cerr << "Check termination must be positive" << std::endl; - return; - } - - settings_->check_termination = check_termination; - if (work__initialized) { - osqp_update_check_termination(work_.get(), check_termination); - } -} - -bool OSQPInterface::setWarmStart( - const std::vector & primal_variables, const std::vector & dual_variables) -{ - return setPrimalVariables(primal_variables) && setDualVariables(dual_variables); -} - -bool OSQPInterface::setPrimalVariables(const std::vector & primal_variables) -{ - if (!work__initialized) { - return false; - } - - const auto result = osqp_warm_start_x(work_.get(), primal_variables.data()); - if (result != 0) { - std::cerr << "Failed to set primal variables for warm start" << std::endl; - return false; - } - - return true; -} - -bool OSQPInterface::setDualVariables(const std::vector & dual_variables) -{ - if (!work__initialized) { - return false; - } - - const auto result = osqp_warm_start_y(work_.get(), dual_variables.data()); - if (result != 0) { - std::cerr << "Failed to set dual variables for warm start" << std::endl; - return false; - } - - return true; -} - -void OSQPInterface::updateP(const Eigen::MatrixXd & P_new) -{ - /* - // Transform 'P' into an 'upper trapezoidal matrix' - Eigen::MatrixXd P_trap = P_new.triangularView(); - // Transform 'P' into a sparse matrix and extract data as dynamic arrays - Eigen::SparseMatrix P_sparse = P_trap.sparseView(); - double *P_val_ptr = P_sparse.valuePtr(); - // Convert dynamic 'int' arrays to 'c_int' arrays (OSQP input type) - c_int P_elem_N = P_sparse.nonZeros(); - */ - CSC_Matrix P_csc = calCSCMatrixTrapezoidal(P_new); - osqp_update_P(work_.get(), P_csc.vals_.data(), OSQP_NULL, static_cast(P_csc.vals_.size())); -} - -void OSQPInterface::updateCscP(const CSC_Matrix & P_csc) -{ - osqp_update_P(work_.get(), P_csc.vals_.data(), OSQP_NULL, static_cast(P_csc.vals_.size())); -} - -void OSQPInterface::updateA(const Eigen::MatrixXd & A_new) -{ - /* - // Transform 'A' into a sparse matrix and extract data as dynamic arrays - Eigen::SparseMatrix A_sparse = A_new.sparseView(); - double *A_val_ptr = A_sparse.valuePtr(); - // Convert dynamic 'int' arrays to 'c_int' arrays (OSQP input type) - c_int A_elem_N = A_sparse.nonZeros(); - */ - CSC_Matrix A_csc = calCSCMatrix(A_new); - osqp_update_A(work_.get(), A_csc.vals_.data(), OSQP_NULL, static_cast(A_csc.vals_.size())); - return; -} - -void OSQPInterface::updateCscA(const CSC_Matrix & A_csc) -{ - osqp_update_A(work_.get(), A_csc.vals_.data(), OSQP_NULL, static_cast(A_csc.vals_.size())); -} - -void OSQPInterface::updateQ(const std::vector & q_new) -{ - std::vector q_tmp(q_new.begin(), q_new.end()); - double * q_dyn = q_tmp.data(); - osqp_update_lin_cost(work_.get(), q_dyn); -} - -void OSQPInterface::updateL(const std::vector & l_new) -{ - std::vector l_tmp(l_new.begin(), l_new.end()); - double * l_dyn = l_tmp.data(); - osqp_update_lower_bound(work_.get(), l_dyn); -} - -void OSQPInterface::updateU(const std::vector & u_new) -{ - std::vector u_tmp(u_new.begin(), u_new.end()); - double * u_dyn = u_tmp.data(); - osqp_update_upper_bound(work_.get(), u_dyn); -} - -void OSQPInterface::updateBounds( - const std::vector & l_new, const std::vector & u_new) -{ - std::vector l_tmp(l_new.begin(), l_new.end()); - std::vector u_tmp(u_new.begin(), u_new.end()); - double * l_dyn = l_tmp.data(); - double * u_dyn = u_tmp.data(); - osqp_update_bounds(work_.get(), l_dyn, u_dyn); -} - -int OSQPInterface::getIterationNumber() const -{ - return work_->info->iter; -} - -std::string OSQPInterface::getStatus() const -{ - return "OSQP_SOLVED"; -} - -bool OSQPInterface::isSolved() const -{ - return latest_work_info_.status_val == 1; -} - -int OSQPInterface::getPolishStatus() const -{ - return static_cast(latest_work_info_.status_polish); -} - -std::vector OSQPInterface::getDualSolution() const -{ - double * sol_y = work_->solution->y; - std::vector dual_solution(sol_y, sol_y + data_->m); - return dual_solution; -} - -std::vector OSQPInterface::optimizeImpl() -{ - osqp_solve(work_.get()); - - double * sol_x = work_->solution->x; - std::vector sol_primal(sol_x, sol_x + param_n_); - - latest_work_info_ = *(work_->info); - - if (!enable_warm_start_) { - work_.reset(); - work__initialized = false; - } - - return sol_primal; -} - -std::vector OSQPInterface::optimize( - CSC_Matrix P, CSC_Matrix A, const std::vector & q, const std::vector & l, - const std::vector & u) -{ - initializeCSCProblemImpl(P, A, q, l, u); - const auto result = optimizeImpl(); - - // show polish status if not successful - const int status_polish = static_cast(latest_work_info_.status_polish); - if (status_polish != 1) { - const auto msg = status_polish == 0 ? "unperformed" - : status_polish == -1 ? "unsuccessful" - : "unknown"; - std::cerr << "osqp polish process failed : " << msg << ". The result may be inaccurate" - << std::endl; - } - - return result; -} - -} // namespace autoware::qp_interface diff --git a/common/autoware_qp_interface/src/proxqp_interface.cpp b/common/autoware_qp_interface/src/proxqp_interface.cpp deleted file mode 100644 index a0ebbf0db0510..0000000000000 --- a/common/autoware_qp_interface/src/proxqp_interface.cpp +++ /dev/null @@ -1,157 +0,0 @@ -// Copyright 2023 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/qp_interface/proxqp_interface.hpp" - -#include -#include -#include - -namespace autoware::qp_interface -{ -using proxsuite::proxqp::QPSolverOutput; - -ProxQPInterface::ProxQPInterface( - const bool enable_warm_start, const int max_iteration, const double eps_abs, const double eps_rel, - const bool verbose) -: QPInterface(enable_warm_start) -{ - settings_.max_iter = max_iteration; - settings_.eps_abs = eps_abs; - settings_.eps_rel = eps_rel; - settings_.verbose = verbose; -} - -void ProxQPInterface::initializeProblemImpl( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u) -{ - const size_t variables_num = q.size(); - const size_t constraints_num = l.size(); - - const bool enable_warm_start = [&]() { - if ( - !enable_warm_start_ // Warm start is designated - || !qp_ptr_ // QP pointer is initialized - // The number of variables is the same as the previous one. - || !variables_num_ || - *variables_num_ != variables_num - // The number of constraints is the same as the previous one - || !constraints_num_ || *constraints_num_ != constraints_num) { - return false; - } - return true; - }(); - - if (!enable_warm_start) { - qp_ptr_ = std::make_shared>( - variables_num, 0, constraints_num); - } - - settings_.initial_guess = - enable_warm_start ? proxsuite::proxqp::InitialGuessStatus::WARM_START_WITH_PREVIOUS_RESULT - : proxsuite::proxqp::InitialGuessStatus::NO_INITIAL_GUESS; - - qp_ptr_->settings = settings_; - - Eigen::SparseMatrix P_sparse(variables_num, constraints_num); - P_sparse = P.sparseView(); - - // NOTE: const std vector cannot be converted to eigen vector - std::vector non_const_q = q; - Eigen::VectorXd eigen_q = - Eigen::Map(non_const_q.data(), non_const_q.size()); - std::vector l_std_vec = l; - Eigen::VectorXd eigen_l = - Eigen::Map(l_std_vec.data(), l_std_vec.size()); - std::vector u_std_vec = u; - Eigen::VectorXd eigen_u = - Eigen::Map(u_std_vec.data(), u_std_vec.size()); - - if (enable_warm_start) { - qp_ptr_->update( - P_sparse, eigen_q, proxsuite::nullopt, proxsuite::nullopt, A.sparseView(), eigen_l, eigen_u); - } else { - qp_ptr_->init( - P_sparse, eigen_q, proxsuite::nullopt, proxsuite::nullopt, A.sparseView(), eigen_l, eigen_u); - } -} - -void ProxQPInterface::updateEpsAbs(const double eps_abs) -{ - settings_.eps_abs = eps_abs; -} - -void ProxQPInterface::updateEpsRel(const double eps_rel) -{ - settings_.eps_rel = eps_rel; -} - -void ProxQPInterface::updateVerbose(const bool is_verbose) -{ - settings_.verbose = is_verbose; -} - -bool ProxQPInterface::isSolved() const -{ - if (qp_ptr_) { - return qp_ptr_->results.info.status == QPSolverOutput::PROXQP_SOLVED; - } - return false; -} - -int ProxQPInterface::getIterationNumber() const -{ - if (qp_ptr_) { - return qp_ptr_->results.info.iter; - } - return 0; -} - -std::string ProxQPInterface::getStatus() const -{ - if (qp_ptr_) { - if (qp_ptr_->results.info.status == QPSolverOutput::PROXQP_SOLVED) { - return "PROXQP_SOLVED"; - } - if (qp_ptr_->results.info.status == QPSolverOutput::PROXQP_MAX_ITER_REACHED) { - return "PROXQP_MAX_ITER_REACHED"; - } - if (qp_ptr_->results.info.status == QPSolverOutput::PROXQP_PRIMAL_INFEASIBLE) { - return "PROXQP_PRIMAL_INFEASIBLE"; - } - // if (qp_ptr_->results.info.status == QPSolverOutput::PROXQP_SOLVED_CLOSEST_PRIMAL_FEASIBLE) { - // return "PROXQP_SOLVED_CLOSEST_PRIMAL_FEASIBLE"; - // } - if (qp_ptr_->results.info.status == QPSolverOutput::PROXQP_DUAL_INFEASIBLE) { - return "PROXQP_DUAL_INFEASIBLE"; - } - if (qp_ptr_->results.info.status == QPSolverOutput::PROXQP_NOT_RUN) { - return "PROXQP_NOT_RUN"; - } - } - return "None"; -} - -std::vector ProxQPInterface::optimizeImpl() -{ - qp_ptr_->solve(); - - std::vector result; - for (Eigen::Index i = 0; i < qp_ptr_->results.x.size(); ++i) { - result.push_back(qp_ptr_->results.x[i]); - } - return result; -} -} // namespace autoware::qp_interface diff --git a/common/autoware_qp_interface/src/qp_interface.cpp b/common/autoware_qp_interface/src/qp_interface.cpp deleted file mode 100644 index f01e57772dc4f..0000000000000 --- a/common/autoware_qp_interface/src/qp_interface.cpp +++ /dev/null @@ -1,70 +0,0 @@ -// Copyright 2023 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/qp_interface/qp_interface.hpp" - -#include -#include -#include - -namespace autoware::qp_interface -{ -void QPInterface::initializeProblem( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u) -{ - // check if arguments are valid - std::stringstream ss; - if (P.rows() != P.cols()) { - ss << "P.rows() and P.cols() are not the same. P.rows() = " << P.rows() - << ", P.cols() = " << P.cols(); - throw std::invalid_argument(ss.str()); - } - if (P.rows() != static_cast(q.size())) { - ss << "P.rows() and q.size() are not the same. P.rows() = " << P.rows() - << ", q.size() = " << q.size(); - throw std::invalid_argument(ss.str()); - } - if (P.rows() != A.cols()) { - ss << "P.rows() and A.cols() are not the same. P.rows() = " << P.rows() - << ", A.cols() = " << A.cols(); - throw std::invalid_argument(ss.str()); - } - if (A.rows() != static_cast(l.size())) { - ss << "A.rows() and l.size() are not the same. A.rows() = " << A.rows() - << ", l.size() = " << l.size(); - throw std::invalid_argument(ss.str()); - } - if (A.rows() != static_cast(u.size())) { - ss << "A.rows() and u.size() are not the same. A.rows() = " << A.rows() - << ", u.size() = " << u.size(); - throw std::invalid_argument(ss.str()); - } - - initializeProblemImpl(P, A, q, l, u); - - variables_num_ = q.size(); - constraints_num_ = l.size(); -} - -std::vector QPInterface::optimize( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u) -{ - initializeProblem(P, A, q, l, u); - const auto result = optimizeImpl(); - - return result; -} -} // namespace autoware::qp_interface diff --git a/common/autoware_qp_interface/test/test_csc_matrix_conv.cpp b/common/autoware_qp_interface/test/test_csc_matrix_conv.cpp deleted file mode 100644 index 1f377a1a24535..0000000000000 --- a/common/autoware_qp_interface/test/test_csc_matrix_conv.cpp +++ /dev/null @@ -1,181 +0,0 @@ -// Copyright 2023 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/qp_interface/osqp_csc_matrix_conv.hpp" -#include "gtest/gtest.h" - -#include - -#include -#include -#include - -TEST(TestCscMatrixConv, Nominal) -{ - using autoware::qp_interface::calCSCMatrix; - using autoware::qp_interface::CSC_Matrix; - - Eigen::MatrixXd rect1(1, 2); - rect1 << 0.0, 1.0; - - const CSC_Matrix rect_m1 = calCSCMatrix(rect1); - ASSERT_EQ(rect_m1.vals_.size(), size_t(1)); - EXPECT_EQ(rect_m1.vals_[0], 1.0); - ASSERT_EQ(rect_m1.row_idxs_.size(), size_t(1)); - EXPECT_EQ(rect_m1.row_idxs_[0], c_int(0)); - ASSERT_EQ(rect_m1.col_idxs_.size(), size_t(3)); // nb of columns + 1 - EXPECT_EQ(rect_m1.col_idxs_[0], c_int(0)); - EXPECT_EQ(rect_m1.col_idxs_[1], c_int(0)); - EXPECT_EQ(rect_m1.col_idxs_[2], c_int(1)); - - Eigen::MatrixXd rect2(2, 4); - rect2 << 1.0, 0.0, 3.0, 0.0, 0.0, 6.0, 7.0, 0.0; - - const CSC_Matrix rect_m2 = calCSCMatrix(rect2); - ASSERT_EQ(rect_m2.vals_.size(), size_t(4)); - EXPECT_EQ(rect_m2.vals_[0], 1.0); - EXPECT_EQ(rect_m2.vals_[1], 6.0); - EXPECT_EQ(rect_m2.vals_[2], 3.0); - EXPECT_EQ(rect_m2.vals_[3], 7.0); - ASSERT_EQ(rect_m2.row_idxs_.size(), size_t(4)); - EXPECT_EQ(rect_m2.row_idxs_[0], c_int(0)); - EXPECT_EQ(rect_m2.row_idxs_[1], c_int(1)); - EXPECT_EQ(rect_m2.row_idxs_[2], c_int(0)); - EXPECT_EQ(rect_m2.row_idxs_[3], c_int(1)); - ASSERT_EQ(rect_m2.col_idxs_.size(), size_t(5)); // nb of columns + 1 - EXPECT_EQ(rect_m2.col_idxs_[0], c_int(0)); - EXPECT_EQ(rect_m2.col_idxs_[1], c_int(1)); - EXPECT_EQ(rect_m2.col_idxs_[2], c_int(2)); - EXPECT_EQ(rect_m2.col_idxs_[3], c_int(4)); - EXPECT_EQ(rect_m2.col_idxs_[4], c_int(4)); - - // Example from http://netlib.org/linalg/html_templates/node92.html - Eigen::MatrixXd square2(6, 6); - square2 << 10.0, 0.0, 0.0, 0.0, -2.0, 0.0, 3.0, 9.0, 0.0, 0.0, 0.0, 3.0, 0.0, 7.0, 8.0, 7.0, 0.0, - 0.0, 3.0, 0.0, 8.0, 7.0, 5.0, 0.0, 0.0, 8.0, 0.0, 9.0, 9.0, 13.0, 0.0, 4.0, 0.0, 0.0, 2.0, -1.0; - - const CSC_Matrix square_m2 = calCSCMatrix(square2); - ASSERT_EQ(square_m2.vals_.size(), size_t(19)); - EXPECT_EQ(square_m2.vals_[0], 10.0); - EXPECT_EQ(square_m2.vals_[1], 3.0); - EXPECT_EQ(square_m2.vals_[2], 3.0); - EXPECT_EQ(square_m2.vals_[3], 9.0); - EXPECT_EQ(square_m2.vals_[4], 7.0); - EXPECT_EQ(square_m2.vals_[5], 8.0); - EXPECT_EQ(square_m2.vals_[6], 4.0); - EXPECT_EQ(square_m2.vals_[7], 8.0); - EXPECT_EQ(square_m2.vals_[8], 8.0); - EXPECT_EQ(square_m2.vals_[9], 7.0); - EXPECT_EQ(square_m2.vals_[10], 7.0); - EXPECT_EQ(square_m2.vals_[11], 9.0); - EXPECT_EQ(square_m2.vals_[12], -2.0); - EXPECT_EQ(square_m2.vals_[13], 5.0); - EXPECT_EQ(square_m2.vals_[14], 9.0); - EXPECT_EQ(square_m2.vals_[15], 2.0); - EXPECT_EQ(square_m2.vals_[16], 3.0); - EXPECT_EQ(square_m2.vals_[17], 13.0); - EXPECT_EQ(square_m2.vals_[18], -1.0); - ASSERT_EQ(square_m2.row_idxs_.size(), size_t(19)); - EXPECT_EQ(square_m2.row_idxs_[0], c_int(0)); - EXPECT_EQ(square_m2.row_idxs_[1], c_int(1)); - EXPECT_EQ(square_m2.row_idxs_[2], c_int(3)); - EXPECT_EQ(square_m2.row_idxs_[3], c_int(1)); - EXPECT_EQ(square_m2.row_idxs_[4], c_int(2)); - EXPECT_EQ(square_m2.row_idxs_[5], c_int(4)); - EXPECT_EQ(square_m2.row_idxs_[6], c_int(5)); - EXPECT_EQ(square_m2.row_idxs_[7], c_int(2)); - EXPECT_EQ(square_m2.row_idxs_[8], c_int(3)); - EXPECT_EQ(square_m2.row_idxs_[9], c_int(2)); - EXPECT_EQ(square_m2.row_idxs_[10], c_int(3)); - EXPECT_EQ(square_m2.row_idxs_[11], c_int(4)); - EXPECT_EQ(square_m2.row_idxs_[12], c_int(0)); - EXPECT_EQ(square_m2.row_idxs_[13], c_int(3)); - EXPECT_EQ(square_m2.row_idxs_[14], c_int(4)); - EXPECT_EQ(square_m2.row_idxs_[15], c_int(5)); - EXPECT_EQ(square_m2.row_idxs_[16], c_int(1)); - EXPECT_EQ(square_m2.row_idxs_[17], c_int(4)); - EXPECT_EQ(square_m2.row_idxs_[18], c_int(5)); - ASSERT_EQ(square_m2.col_idxs_.size(), size_t(7)); // nb of columns + 1 - EXPECT_EQ(square_m2.col_idxs_[0], c_int(0)); - EXPECT_EQ(square_m2.col_idxs_[1], c_int(3)); - EXPECT_EQ(square_m2.col_idxs_[2], c_int(7)); - EXPECT_EQ(square_m2.col_idxs_[3], c_int(9)); - EXPECT_EQ(square_m2.col_idxs_[4], c_int(12)); - EXPECT_EQ(square_m2.col_idxs_[5], c_int(16)); - EXPECT_EQ(square_m2.col_idxs_[6], c_int(19)); -} -TEST(TestCscMatrixConv, Trapezoidal) -{ - using autoware::qp_interface::calCSCMatrixTrapezoidal; - using autoware::qp_interface::CSC_Matrix; - - Eigen::MatrixXd square1(2, 2); - Eigen::MatrixXd square2(3, 3); - Eigen::MatrixXd rect1(1, 2); - square1 << 1.0, 2.0, 2.0, 4.0; - square2 << 0.0, 2.0, 0.0, 4.0, 5.0, 6.0, 0.0, 0.0, 0.0; - rect1 << 0.0, 1.0; - - const CSC_Matrix square_m1 = calCSCMatrixTrapezoidal(square1); - // Trapezoidal: skip the lower left triangle (2.0 in this example) - ASSERT_EQ(square_m1.vals_.size(), size_t(3)); - EXPECT_EQ(square_m1.vals_[0], 1.0); - EXPECT_EQ(square_m1.vals_[1], 2.0); - EXPECT_EQ(square_m1.vals_[2], 4.0); - ASSERT_EQ(square_m1.row_idxs_.size(), size_t(3)); - EXPECT_EQ(square_m1.row_idxs_[0], c_int(0)); - EXPECT_EQ(square_m1.row_idxs_[1], c_int(0)); - EXPECT_EQ(square_m1.row_idxs_[2], c_int(1)); - ASSERT_EQ(square_m1.col_idxs_.size(), size_t(3)); - EXPECT_EQ(square_m1.col_idxs_[0], c_int(0)); - EXPECT_EQ(square_m1.col_idxs_[1], c_int(1)); - EXPECT_EQ(square_m1.col_idxs_[2], c_int(3)); - - const CSC_Matrix square_m2 = calCSCMatrixTrapezoidal(square2); - ASSERT_EQ(square_m2.vals_.size(), size_t(3)); - EXPECT_EQ(square_m2.vals_[0], 2.0); - EXPECT_EQ(square_m2.vals_[1], 5.0); - EXPECT_EQ(square_m2.vals_[2], 6.0); - ASSERT_EQ(square_m2.row_idxs_.size(), size_t(3)); - EXPECT_EQ(square_m2.row_idxs_[0], c_int(0)); - EXPECT_EQ(square_m2.row_idxs_[1], c_int(1)); - EXPECT_EQ(square_m2.row_idxs_[2], c_int(1)); - ASSERT_EQ(square_m2.col_idxs_.size(), size_t(4)); - EXPECT_EQ(square_m2.col_idxs_[0], c_int(0)); - EXPECT_EQ(square_m2.col_idxs_[1], c_int(0)); - EXPECT_EQ(square_m2.col_idxs_[2], c_int(2)); - EXPECT_EQ(square_m2.col_idxs_[3], c_int(3)); - - try { - const CSC_Matrix rect_m1 = calCSCMatrixTrapezoidal(rect1); - FAIL() << "calCSCMatrixTrapezoidal should fail with non-square inputs"; - } catch (const std::invalid_argument & e) { - EXPECT_EQ(e.what(), std::string("Matrix must be square (n, n)")); - } -} -TEST(TestCscMatrixConv, Print) -{ - using autoware::qp_interface::calCSCMatrix; - using autoware::qp_interface::calCSCMatrixTrapezoidal; - using autoware::qp_interface::CSC_Matrix; - using autoware::qp_interface::printCSCMatrix; - Eigen::MatrixXd square1(2, 2); - Eigen::MatrixXd rect1(1, 2); - square1 << 1.0, 2.0, 2.0, 4.0; - rect1 << 0.0, 1.0; - const CSC_Matrix square_m1 = calCSCMatrixTrapezoidal(square1); - const CSC_Matrix rect_m1 = calCSCMatrix(rect1); - printCSCMatrix(square_m1); - printCSCMatrix(rect_m1); -} diff --git a/common/autoware_qp_interface/test/test_osqp_interface.cpp b/common/autoware_qp_interface/test/test_osqp_interface.cpp deleted file mode 100644 index f97cc2888afa0..0000000000000 --- a/common/autoware_qp_interface/test/test_osqp_interface.cpp +++ /dev/null @@ -1,170 +0,0 @@ -// Copyright 2023 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/qp_interface/osqp_interface.hpp" -#include "gtest/gtest.h" - -#include - -#include -#include -#include -#include - -namespace -{ -// Problem taken from https://github.com/osqp/osqp/blob/master/tests/basic_qp/generate_problem.py -// -// min 1/2 * x' * P * x + q' * x -// s.t. lb <= A * x <= ub -// -// P = [4, 1], q = [1], A = [1, 1], lb = [ 1], ub = [1.0] -// [1, 2] [1] [1, 0] [ 0] [0.7] -// [0, 1] [ 0] [0.7] -// [0, 1] [-inf] [inf] -// -// The optimal solution is -// x = [0.3, 0.7]' -// y = [-2.9, 0.0, 0.2, 0.0]` -// obj = 1.88 - -TEST(TestOsqpInterface, BasicQp) -{ - using autoware::qp_interface::calCSCMatrix; - using autoware::qp_interface::calCSCMatrixTrapezoidal; - using autoware::qp_interface::CSC_Matrix; - - auto check_result = - [](const auto & solution, const std::string & status, const int polish_status) { - EXPECT_EQ(status, "OSQP_SOLVED"); - EXPECT_EQ(polish_status, 1); - - static const auto ep = 1.0e-8; - - ASSERT_EQ(solution.size(), size_t(2)); - EXPECT_NEAR(solution[0], 0.3, ep); - EXPECT_NEAR(solution[1], 0.7, ep); - }; - - const Eigen::MatrixXd P = (Eigen::MatrixXd(2, 2) << 4, 1, 1, 2).finished(); - const Eigen::MatrixXd A = (Eigen::MatrixXd(4, 2) << 1, 1, 1, 0, 0, 1, 0, 1).finished(); - const std::vector q = {1.0, 1.0}; - const std::vector l = {1.0, 0.0, 0.0, -autoware::qp_interface::OSQP_INF}; - const std::vector u = {1.0, 0.7, 0.7, autoware::qp_interface::OSQP_INF}; - - { - // Define problem during optimization - autoware::qp_interface::OSQPInterface osqp(false, 4000, 1e-6); - const auto solution = osqp.QPInterface::optimize(P, A, q, l, u); - const auto status = osqp.getStatus(); - const auto polish_status = osqp.getPolishStatus(); - check_result(solution, status, polish_status); - } - - { - // Define problem during initialization - autoware::qp_interface::OSQPInterface osqp(false, 4000, 1e-6); - const auto solution = osqp.QPInterface::optimize(P, A, q, l, u); - const auto status = osqp.getStatus(); - const auto polish_status = osqp.getPolishStatus(); - check_result(solution, status, polish_status); - } - - { - std::tuple, std::vector, int, int, int> result; - // Dummy initial problem - Eigen::MatrixXd P_ini = Eigen::MatrixXd::Zero(2, 2); - Eigen::MatrixXd A_ini = Eigen::MatrixXd::Zero(4, 2); - std::vector q_ini(2, 0.0); - std::vector l_ini(4, 0.0); - std::vector u_ini(4, 0.0); - autoware::qp_interface::OSQPInterface osqp(false, 4000, 1e-6); - osqp.QPInterface::optimize(P_ini, A_ini, q_ini, l_ini, u_ini); - } - - { - // Define problem during initialization with csc matrix - CSC_Matrix P_csc = calCSCMatrixTrapezoidal(P); - CSC_Matrix A_csc = calCSCMatrix(A); - autoware::qp_interface::OSQPInterface osqp(false, 4000, 1e-6); - - const auto solution = osqp.optimize(P_csc, A_csc, q, l, u); - const auto status = osqp.getStatus(); - const auto polish_status = osqp.getPolishStatus(); - check_result(solution, status, polish_status); - } - - { - std::tuple, std::vector, int, int, int> result; - // Dummy initial problem with csc matrix - CSC_Matrix P_ini_csc = calCSCMatrixTrapezoidal(Eigen::MatrixXd::Zero(2, 2)); - CSC_Matrix A_ini_csc = calCSCMatrix(Eigen::MatrixXd::Zero(4, 2)); - std::vector q_ini(2, 0.0); - std::vector l_ini(4, 0.0); - std::vector u_ini(4, 0.0); - autoware::qp_interface::OSQPInterface osqp(false, 4000, 1e-6); - osqp.optimize(P_ini_csc, A_ini_csc, q_ini, l_ini, u_ini); - - // Redefine problem before optimization - CSC_Matrix P_csc = calCSCMatrixTrapezoidal(P); - CSC_Matrix A_csc = calCSCMatrix(A); - - const auto solution = osqp.optimize(P_csc, A_csc, q, l, u); - const auto status = osqp.getStatus(); - const auto polish_status = osqp.getPolishStatus(); - check_result(solution, status, polish_status); - } - - // add warm startup - { - // Dummy initial problem with csc matrix - CSC_Matrix P_ini_csc = calCSCMatrixTrapezoidal(Eigen::MatrixXd::Zero(2, 2)); - CSC_Matrix A_ini_csc = calCSCMatrix(Eigen::MatrixXd::Zero(4, 2)); - std::vector q_ini(2, 0.0); - std::vector l_ini(4, 0.0); - std::vector u_ini(4, 0.0); - autoware::qp_interface::OSQPInterface osqp(true, 4000, 1e-6); // enable warm start - osqp.optimize(P_ini_csc, A_ini_csc, q_ini, l_ini, u_ini); - - // Redefine problem before optimization - CSC_Matrix P_csc = calCSCMatrixTrapezoidal(P); - CSC_Matrix A_csc = calCSCMatrix(A); - { - const auto solution = osqp.optimize(P_csc, A_csc, q, l, u); - const auto status = osqp.getStatus(); - const auto polish_status = osqp.getPolishStatus(); - check_result(solution, status, polish_status); - - osqp.updateCheckTermination(1); - const auto primal_val = solution; - const auto dual_val = osqp.getDualSolution(); - for (size_t i = 0; i < primal_val.size(); ++i) { - std::cerr << primal_val.at(i) << std::endl; - } - osqp.setWarmStart(primal_val, dual_val); - } - - { - const auto solution = osqp.optimize(P_csc, A_csc, q, l, u); - const auto status = osqp.getStatus(); - const auto polish_status = osqp.getPolishStatus(); - check_result(solution, status, polish_status); - } - - // NOTE: This should be true, but currently optimize function reset the workspace, which - // disables warm start. - // EXPECT_EQ(osqp.getTakenIter(), 1); - } -} -} // namespace diff --git a/common/autoware_qp_interface/test/test_proxqp_interface.cpp b/common/autoware_qp_interface/test/test_proxqp_interface.cpp deleted file mode 100644 index e47af10c7aabd..0000000000000 --- a/common/autoware_qp_interface/test/test_proxqp_interface.cpp +++ /dev/null @@ -1,85 +0,0 @@ -// Copyright 2023 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/qp_interface/proxqp_interface.hpp" -#include "gtest/gtest.h" - -#include - -#include -#include -#include -#include - -namespace -{ -// Problem taken from -// https://github.com/proxqp/proxqp/blob/master/tests/basic_qp/generate_problem.py -// -// min 1/2 * x' * P * x + q' * x -// s.t. lb <= A * x <= ub -// -// P = [4, 1], q = [1], A = [1, 1], lb = [ 1], ub = [1.0] -// [1, 2] [1] [1, 0] [ 0] [0.7] -// [0, 1] [ 0] [0.7] -// [0, 1] [-inf] [inf] -// -// The optimal solution is -// x = [0.3, 0.7]' -// y = [-2.9, 0.0, 0.2, 0.0]` -// obj = 1.88 - -TEST(TestProxqpInterface, BasicQp) -{ - auto check_result = [](const auto & solution, const std::string & status) { - EXPECT_EQ(status, "PROXQP_SOLVED"); - - static const auto ep = 1.0e-8; - ASSERT_EQ(solution.size(), size_t(2)); - EXPECT_NEAR(solution[0], 0.3, ep); - EXPECT_NEAR(solution[1], 0.7, ep); - }; - - const Eigen::MatrixXd P = (Eigen::MatrixXd(2, 2) << 4, 1, 1, 2).finished(); - const Eigen::MatrixXd A = (Eigen::MatrixXd(4, 2) << 1, 1, 1, 0, 0, 1, 0, 1).finished(); - const std::vector q = {1.0, 1.0}; - const std::vector l = {1.0, 0.0, 0.0, -std::numeric_limits::max()}; - const std::vector u = {1.0, 0.7, 0.7, std::numeric_limits::max()}; - - { - // Define problem during optimization - autoware::qp_interface::ProxQPInterface proxqp(false, 4000, 1e-9, 1e-9, false); - const auto solution = proxqp.QPInterface::optimize(P, A, q, l, u); - const auto status = proxqp.getStatus(); - check_result(solution, status); - } - - { - // Define problem during optimization with warm start - autoware::qp_interface::ProxQPInterface proxqp(true, 4000, 1e-9, 1e-9, false); - { - const auto solution = proxqp.QPInterface::optimize(P, A, q, l, u); - const auto status = proxqp.getStatus(); - check_result(solution, status); - EXPECT_NE(proxqp.getIterationNumber(), 1); - } - { - const auto solution = proxqp.QPInterface::optimize(P, A, q, l, u); - const auto status = proxqp.getStatus(); - check_result(solution, status); - EXPECT_EQ(proxqp.getIterationNumber(), 0); - } - } -} -} // namespace From 997146c94c4f5eaa0547206981b1566879c0a266 Mon Sep 17 00:00:00 2001 From: NorahXiong <103234047+NorahXiong@users.noreply.github.com> Date: Wed, 15 Jan 2025 10:11:09 +0800 Subject: [PATCH 202/334] feat(autoware_osqp_interface): porting autoware_osqp_interface package to autoware.core (#9890) Signed-off-by: NorahXiong --- common/autoware_osqp_interface/CHANGELOG.rst | 51 -- common/autoware_osqp_interface/CMakeLists.txt | 58 --- .../design/osqp_interface-design.md | 70 --- .../osqp_interface/csc_matrix_conv.hpp | 47 -- .../osqp_interface/osqp_interface.hpp | 194 -------- .../osqp_interface/visibility_control.hpp | 37 -- common/autoware_osqp_interface/package.xml | 29 -- .../src/csc_matrix_conv.cpp | 135 ------ .../src/osqp_interface.cpp | 435 ------------------ .../test/test_csc_matrix_conv.cpp | 181 -------- .../test/test_osqp_interface.cpp | 164 ------- 11 files changed, 1401 deletions(-) delete mode 100644 common/autoware_osqp_interface/CHANGELOG.rst delete mode 100644 common/autoware_osqp_interface/CMakeLists.txt delete mode 100644 common/autoware_osqp_interface/design/osqp_interface-design.md delete mode 100644 common/autoware_osqp_interface/include/autoware/osqp_interface/csc_matrix_conv.hpp delete mode 100644 common/autoware_osqp_interface/include/autoware/osqp_interface/osqp_interface.hpp delete mode 100644 common/autoware_osqp_interface/include/autoware/osqp_interface/visibility_control.hpp delete mode 100644 common/autoware_osqp_interface/package.xml delete mode 100644 common/autoware_osqp_interface/src/csc_matrix_conv.cpp delete mode 100644 common/autoware_osqp_interface/src/osqp_interface.cpp delete mode 100644 common/autoware_osqp_interface/test/test_csc_matrix_conv.cpp delete mode 100644 common/autoware_osqp_interface/test/test_osqp_interface.cpp diff --git a/common/autoware_osqp_interface/CHANGELOG.rst b/common/autoware_osqp_interface/CHANGELOG.rst deleted file mode 100644 index d400b77f4bf61..0000000000000 --- a/common/autoware_osqp_interface/CHANGELOG.rst +++ /dev/null @@ -1,51 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package autoware_osqp_interface -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -0.40.0 (2024-12-12) -------------------- -* Merge branch 'main' into release-0.40.0 -* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" - This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. -* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) -* chore(package.xml): bump version to 0.39.0 (`#9587 `_) - * chore(package.xml): bump version to 0.39.0 - * fix: fix ticket links in CHANGELOG.rst - * fix: remove unnecessary diff - --------- - Co-authored-by: Yutaka Kondo -* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) -* fix(cpplint): include what you use - common (`#9564 `_) -* fix(autoware_osqp_interface): fix clang-tidy errors (`#9440 `_) -* 0.39.0 -* update changelog -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) - * unify package.xml version to 0.37.0 - * remove system_monitor/CHANGELOG.rst - * add changelog - * 0.38.0 - --------- -* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Ryuta Kambe, Yutaka Kondo - -0.39.0 (2024-11-25) -------------------- -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) - * unify package.xml version to 0.37.0 - * remove system_monitor/CHANGELOG.rst - * add changelog - * 0.38.0 - --------- -* Contributors: Esteve Fernandez, Yutaka Kondo - -0.38.0 (2024-11-08) -------------------- -* unify package.xml version to 0.37.0 -* refactor(osqp_interface): added autoware prefix to osqp_interface (`#8958 `_) -* Contributors: Esteve Fernandez, Yutaka Kondo - -0.26.0 (2024-04-03) -------------------- diff --git a/common/autoware_osqp_interface/CMakeLists.txt b/common/autoware_osqp_interface/CMakeLists.txt deleted file mode 100644 index b770af659e52a..0000000000000 --- a/common/autoware_osqp_interface/CMakeLists.txt +++ /dev/null @@ -1,58 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(autoware_osqp_interface) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -find_package(Eigen3 REQUIRED) - -# after find_package(osqp_vendor) in ament_auto_find_build_dependencies -find_package(osqp REQUIRED) -get_target_property(OSQP_INCLUDE_SUB_DIR osqp::osqp INTERFACE_INCLUDE_DIRECTORIES) -get_filename_component(OSQP_INCLUDE_DIR ${OSQP_INCLUDE_SUB_DIR} PATH) - -set(OSQP_INTERFACE_LIB_SRC - src/csc_matrix_conv.cpp - src/osqp_interface.cpp -) - -set(OSQP_INTERFACE_LIB_HEADERS - include/autoware/osqp_interface/csc_matrix_conv.hpp - include/autoware/osqp_interface/osqp_interface.hpp - include/autoware/osqp_interface/visibility_control.hpp -) - -ament_auto_add_library(${PROJECT_NAME} SHARED - ${OSQP_INTERFACE_LIB_SRC} - ${OSQP_INTERFACE_LIB_HEADERS} -) -target_compile_options(${PROJECT_NAME} PRIVATE -Wno-error=old-style-cast) - -target_include_directories(${PROJECT_NAME} - SYSTEM PUBLIC - "${OSQP_INCLUDE_DIR}" - "${EIGEN3_INCLUDE_DIR}" -) - -ament_target_dependencies(${PROJECT_NAME} - Eigen3 - osqp_vendor -) - -# crucial so downstream package builds because autoware_osqp_interface exposes osqp.hpp -ament_export_include_directories("${OSQP_INCLUDE_DIR}") -# crucial so the linking order is correct in a downstream package: libosqp_interface.a should come before libosqp.a -ament_export_libraries(osqp::osqp) - -if(BUILD_TESTING) - set(TEST_SOURCES - test/test_osqp_interface.cpp - test/test_csc_matrix_conv.cpp - ) - set(TEST_OSQP_INTERFACE_EXE test_osqp_interface) - ament_add_ros_isolated_gtest(${TEST_OSQP_INTERFACE_EXE} ${TEST_SOURCES}) - target_link_libraries(${TEST_OSQP_INTERFACE_EXE} ${PROJECT_NAME}) -endif() - -ament_auto_package(INSTALL_TO_SHARE -) diff --git a/common/autoware_osqp_interface/design/osqp_interface-design.md b/common/autoware_osqp_interface/design/osqp_interface-design.md deleted file mode 100644 index 887a4b4d9af3f..0000000000000 --- a/common/autoware_osqp_interface/design/osqp_interface-design.md +++ /dev/null @@ -1,70 +0,0 @@ -# Interface for the OSQP library - -This is the design document for the `autoware_osqp_interface` package. - -## Purpose / Use cases - - - - -This packages provides a C++ interface for the [OSQP library](https://osqp.org/docs/solver/index.html). - -## Design - - - - -The class `OSQPInterface` takes a problem formulation as Eigen matrices and vectors, converts these objects into -C-style Compressed-Column-Sparse matrices and dynamic arrays, loads the data into the OSQP workspace dataholder, and runs the optimizer. - -## Inputs / Outputs / API - - - - -The interface can be used in several ways: - -1. Initialize the interface WITHOUT data. Load the problem formulation at the optimization call. - - ```cpp - osqp_interface = OSQPInterface(); - osqp_interface.optimize(P, A, q, l, u); - ``` - -2. Initialize the interface WITH data. - - ```cpp - osqp_interface = OSQPInterface(P, A, q, l, u); - osqp_interface.optimize(); - ``` - -3. WARM START OPTIMIZATION by modifying the problem formulation between optimization runs. - - ```cpp - osqp_interface = OSQPInterface(P, A, q, l, u); - osqp_interface.optimize(); - osqp.initializeProblem(P_new, A_new, q_new, l_new, u_new); - osqp_interface.optimize(); - ``` - - The optimization results are returned as a vector by the optimization function. - - ```cpp - std::tuple, std::vector> result = osqp_interface.optimize(); - std::vector param = std::get<0>(result); - double x_0 = param[0]; - double x_1 = param[1]; - ``` - -## References / External links - - - -- OSQP library: - -## Related issues - - diff --git a/common/autoware_osqp_interface/include/autoware/osqp_interface/csc_matrix_conv.hpp b/common/autoware_osqp_interface/include/autoware/osqp_interface/csc_matrix_conv.hpp deleted file mode 100644 index 8c21553152d70..0000000000000 --- a/common/autoware_osqp_interface/include/autoware/osqp_interface/csc_matrix_conv.hpp +++ /dev/null @@ -1,47 +0,0 @@ -// Copyright 2021 The Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__OSQP_INTERFACE__CSC_MATRIX_CONV_HPP_ -#define AUTOWARE__OSQP_INTERFACE__CSC_MATRIX_CONV_HPP_ - -#include "autoware/osqp_interface/visibility_control.hpp" -#include "osqp/glob_opts.h" // for 'c_int' type ('long' or 'long long') - -#include - -#include - -namespace autoware::osqp_interface -{ -/// \brief Compressed-Column-Sparse Matrix -struct OSQP_INTERFACE_PUBLIC CSC_Matrix -{ - /// Vector of non-zero values. Ex: [4,1,1,2] - std::vector m_vals; - /// Vector of row index corresponding to values. Ex: [0, 1, 0, 1] (Eigen: 'inner') - std::vector m_row_idxs; - /// Vector of 'val' indices where each column starts. Ex: [0, 2, 4] (Eigen: 'outer') - std::vector m_col_idxs; -}; - -/// \brief Calculate CSC matrix from Eigen matrix -OSQP_INTERFACE_PUBLIC CSC_Matrix calCSCMatrix(const Eigen::MatrixXd & mat); -/// \brief Calculate upper trapezoidal CSC matrix from square Eigen matrix -OSQP_INTERFACE_PUBLIC CSC_Matrix calCSCMatrixTrapezoidal(const Eigen::MatrixXd & mat); -/// \brief Print the given CSC matrix to the standard output -OSQP_INTERFACE_PUBLIC void printCSCMatrix(const CSC_Matrix & csc_mat); - -} // namespace autoware::osqp_interface - -#endif // AUTOWARE__OSQP_INTERFACE__CSC_MATRIX_CONV_HPP_ diff --git a/common/autoware_osqp_interface/include/autoware/osqp_interface/osqp_interface.hpp b/common/autoware_osqp_interface/include/autoware/osqp_interface/osqp_interface.hpp deleted file mode 100644 index ff3013bd61514..0000000000000 --- a/common/autoware_osqp_interface/include/autoware/osqp_interface/osqp_interface.hpp +++ /dev/null @@ -1,194 +0,0 @@ -// Copyright 2021 The Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__OSQP_INTERFACE__OSQP_INTERFACE_HPP_ -#define AUTOWARE__OSQP_INTERFACE__OSQP_INTERFACE_HPP_ - -#include "autoware/osqp_interface/csc_matrix_conv.hpp" -#include "autoware/osqp_interface/visibility_control.hpp" -#include "osqp/osqp.h" - -#include -#include - -#include -#include -#include -#include -#include - -namespace autoware::osqp_interface -{ -constexpr c_float INF = 1e30; - -/** - * Implementation of a native C++ interface for the OSQP solver. - * - */ -class OSQP_INTERFACE_PUBLIC OSQPInterface -{ -private: - std::unique_ptr> m_work; - std::unique_ptr m_settings; - std::unique_ptr m_data; - // store last work info since work is cleaned up at every execution to prevent memory leak. - OSQPInfo m_latest_work_info; - // Number of parameters to optimize - int64_t m_param_n; - // Flag to check if the current work exists - bool m_work_initialized = false; - // Exitflag - int64_t m_exitflag; - - // Runs the solver on the stored problem. - std::tuple, std::vector, int64_t, int64_t, int64_t> solve(); - - static void OSQPWorkspaceDeleter(OSQPWorkspace * ptr) noexcept; - -public: - /// \brief Constructor without problem formulation - explicit OSQPInterface( - const c_float eps_abs = std::numeric_limits::epsilon(), const bool polish = true); - /// \brief Constructor with problem setup - /// \param P: (n,n) matrix defining relations between parameters. - /// \param A: (m,n) matrix defining parameter constraints relative to the lower and upper bound. - /// \param q: (n) vector defining the linear cost of the problem. - /// \param l: (m) vector defining the lower bound problem constraint. - /// \param u: (m) vector defining the upper bound problem constraint. - /// \param eps_abs: Absolute convergence tolerance. - OSQPInterface( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u, const c_float eps_abs); - OSQPInterface( - const CSC_Matrix & P, const CSC_Matrix & A, const std::vector & q, - const std::vector & l, const std::vector & u, const c_float eps_abs); - ~OSQPInterface(); - - /**************** - * OPTIMIZATION - ****************/ - /// \brief Solves the stored convex quadratic program (QP) problem using the OSQP solver. - // - /// \return The function returns a tuple containing the solution as two float vectors. - /// \return The first element of the tuple contains the 'primal' solution. - /// \return The second element contains the 'lagrange multiplier' solution. - /// \return The third element contains an integer with solver polish status information. - - /// \details How to use: - /// \details 1. Generate the Eigen matrices P, A and vectors q, l, u according to the problem. - /// \details 2. Initialize the interface and set up the problem. - /// \details osqp_interface = OSQPInterface(P, A, q, l, u, 1e-6); - /// \details 3. Call the optimization function. - /// \details std::tuple, std::vector> result; - /// \details result = osqp_interface.optimize(); - /// \details 4. Access the optimized parameters. - /// \details std::vector param = std::get<0>(result); - /// \details double x_0 = param[0]; - /// \details double x_1 = param[1]; - std::tuple, std::vector, int64_t, int64_t, int64_t> optimize(); - - /// \brief Solves convex quadratic programs (QPs) using the OSQP solver. - /// \return The function returns a tuple containing the solution as two float vectors. - /// \return The first element of the tuple contains the 'primal' solution. - /// \return The second element contains the 'lagrange multiplier' solution. - /// \return The third element contains an integer with solver polish status information. - /// \details How to use: - /// \details 1. Generate the Eigen matrices P, A and vectors q, l, u according to the problem. - /// \details 2. Initialize the interface. - /// \details osqp_interface = OSQPInterface(1e-6); - /// \details 3. Call the optimization function with the problem formulation. - /// \details std::tuple, std::vector> result; - /// \details result = osqp_interface.optimize(P, A, q, l, u, 1e-6); - /// \details 4. Access the optimized parameters. - /// \details std::vector param = std::get<0>(result); - /// \details double x_0 = param[0]; - /// \details double x_1 = param[1]; - std::tuple, std::vector, int64_t, int64_t, int64_t> optimize( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u); - - /// \brief Converts the input data and sets up the workspace object. - /// \param P (n,n) matrix defining relations between parameters. - /// \param A (m,n) matrix defining parameter constraints relative to the lower and upper bound. - /// \param q (n) vector defining the linear cost of the problem. - /// \param l (m) vector defining the lower bound problem constraint. - /// \param u (m) vector defining the upper bound problem constraint. - int64_t initializeProblem( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u); - int64_t initializeProblem( - CSC_Matrix P, CSC_Matrix A, const std::vector & q, const std::vector & l, - const std::vector & u); - - // Setter functions for warm start - bool setWarmStart( - const std::vector & primal_variables, const std::vector & dual_variables); - bool setPrimalVariables(const std::vector & primal_variables); - bool setDualVariables(const std::vector & dual_variables); - - // Updates problem parameters while keeping solution in memory. - // - // Args: - // P_new: (n,n) matrix defining relations between parameters. - // A_new: (m,n) matrix defining parameter constraints relative to the lower and upper bound. - // q_new: (n) vector defining the linear cost of the problem. - // l_new: (m) vector defining the lower bound problem constraint. - // u_new: (m) vector defining the upper bound problem constraint. - void updateP(const Eigen::MatrixXd & P_new); - void updateCscP(const CSC_Matrix & P_csc); - void updateA(const Eigen::MatrixXd & A_new); - void updateCscA(const CSC_Matrix & A_csc); - void updateQ(const std::vector & q_new); - void updateL(const std::vector & l_new); - void updateU(const std::vector & u_new); - void updateBounds(const std::vector & l_new, const std::vector & u_new); - void updateEpsAbs(const double eps_abs); - void updateEpsRel(const double eps_rel); - void updateMaxIter(const int iter); - void updateVerbose(const bool verbose); - void updateRhoInterval(const int rho_interval); - void updateRho(const double rho); - void updateAlpha(const double alpha); - void updateScaling(const int scaling); - void updatePolish(const bool polish); - void updatePolishRefinementIteration(const int polish_refine_iter); - void updateCheckTermination(const int check_termination); - - /// \brief Get the number of iteration taken to solve the problem - inline int64_t getTakenIter() const { return static_cast(m_latest_work_info.iter); } - /// \brief Get the status message for the latest problem solved - inline std::string getStatusMessage() const - { - return static_cast(m_latest_work_info.status); - } - /// \brief Get the status value for the latest problem solved - inline int64_t getStatus() const { return static_cast(m_latest_work_info.status_val); } - /// \brief Get the status polish for the latest problem solved - inline int64_t getStatusPolish() const - { - return static_cast(m_latest_work_info.status_polish); - } - /// \brief Get the runtime of the latest problem solved - inline double getRunTime() const { return m_latest_work_info.run_time; } - /// \brief Get the objective value the latest problem solved - inline double getObjVal() const { return m_latest_work_info.obj_val; } - /// \brief Returns flag asserting interface condition (Healthy condition: 0). - inline int64_t getExitFlag() const { return m_exitflag; } - - void logUnsolvedStatus(const std::string & prefix_message = "") const; -}; - -} // namespace autoware::osqp_interface - -#endif // AUTOWARE__OSQP_INTERFACE__OSQP_INTERFACE_HPP_ diff --git a/common/autoware_osqp_interface/include/autoware/osqp_interface/visibility_control.hpp b/common/autoware_osqp_interface/include/autoware/osqp_interface/visibility_control.hpp deleted file mode 100644 index a6cdaa8a0a74e..0000000000000 --- a/common/autoware_osqp_interface/include/autoware/osqp_interface/visibility_control.hpp +++ /dev/null @@ -1,37 +0,0 @@ -// Copyright 2021 The Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__OSQP_INTERFACE__VISIBILITY_CONTROL_HPP_ -#define AUTOWARE__OSQP_INTERFACE__VISIBILITY_CONTROL_HPP_ - -//////////////////////////////////////////////////////////////////////////////// -#if defined(__WIN32) -#if defined(OSQP_INTERFACE_BUILDING_DLL) || defined(OSQP_INTERFACE_EXPORTS) -#define OSQP_INTERFACE_PUBLIC __declspec(dllexport) -#define OSQP_INTERFACE_LOCAL -#else // defined(OSQP_INTERFACE_BUILDING_DLL) || defined(OSQP_INTERFACE_EXPORTS) -#define OSQP_INTERFACE_PUBLIC __declspec(dllimport) -#define OSQP_INTERFACE_LOCAL -#endif // defined(OSQP_INTERFACE_BUILDING_DLL) || defined(OSQP_INTERFACE_EXPORTS) -#elif defined(__linux__) -#define OSQP_INTERFACE_PUBLIC __attribute__((visibility("default"))) -#define OSQP_INTERFACE_LOCAL __attribute__((visibility("hidden"))) -#elif defined(__APPLE__) -#define OSQP_INTERFACE_PUBLIC __attribute__((visibility("default"))) -#define OSQP_INTERFACE_LOCAL __attribute__((visibility("hidden"))) -#else -#error "Unsupported Build Configuration" -#endif - -#endif // AUTOWARE__OSQP_INTERFACE__VISIBILITY_CONTROL_HPP_ diff --git a/common/autoware_osqp_interface/package.xml b/common/autoware_osqp_interface/package.xml deleted file mode 100644 index 92a2afeccc4e0..0000000000000 --- a/common/autoware_osqp_interface/package.xml +++ /dev/null @@ -1,29 +0,0 @@ - - - - autoware_osqp_interface - 0.40.0 - Interface for the OSQP solver - Maxime CLEMENT - Takayuki Murooka - Fumiya Watanabe - Satoshi Ota - Apache 2.0 - - ament_cmake_auto - autoware_cmake - - eigen - osqp_vendor - rclcpp - rclcpp_components - - ament_cmake_ros - ament_lint_auto - autoware_lint_common - eigen - - - ament_cmake - - diff --git a/common/autoware_osqp_interface/src/csc_matrix_conv.cpp b/common/autoware_osqp_interface/src/csc_matrix_conv.cpp deleted file mode 100644 index c6e1a0a42d938..0000000000000 --- a/common/autoware_osqp_interface/src/csc_matrix_conv.cpp +++ /dev/null @@ -1,135 +0,0 @@ -// Copyright 2021 The Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/osqp_interface/csc_matrix_conv.hpp" - -#include -#include - -#include -#include -#include - -namespace autoware::osqp_interface -{ -CSC_Matrix calCSCMatrix(const Eigen::MatrixXd & mat) -{ - const size_t elem = static_cast(mat.nonZeros()); - const Eigen::Index rows = mat.rows(); - const Eigen::Index cols = mat.cols(); - - std::vector vals; - vals.reserve(elem); - std::vector row_idxs; - row_idxs.reserve(elem); - std::vector col_idxs; - col_idxs.reserve(elem); - - // Construct CSC matrix arrays - c_float val; - c_int elem_count = 0; - - col_idxs.push_back(0); - - for (Eigen::Index j = 0; j < cols; j++) { // col iteration - for (Eigen::Index i = 0; i < rows; i++) { // row iteration - // Get values of nonzero elements - val = mat(i, j); - if (std::fabs(val) < 1e-9) { - continue; - } - elem_count += 1; - - // Store values - vals.push_back(val); - row_idxs.push_back(i); - } - - col_idxs.push_back(elem_count); - } - - CSC_Matrix csc_matrix = {vals, row_idxs, col_idxs}; - - return csc_matrix; -} - -CSC_Matrix calCSCMatrixTrapezoidal(const Eigen::MatrixXd & mat) -{ - const size_t elem = static_cast(mat.nonZeros()); - const Eigen::Index rows = mat.rows(); - const Eigen::Index cols = mat.cols(); - - if (rows != cols) { - throw std::invalid_argument("Matrix must be square (n, n)"); - } - - std::vector vals; - vals.reserve(elem); - std::vector row_idxs; - row_idxs.reserve(elem); - std::vector col_idxs; - col_idxs.reserve(elem); - - // Construct CSC matrix arrays - c_float val; - Eigen::Index trap_last_idx = 0; - c_int elem_count = 0; - - col_idxs.push_back(0); - - for (Eigen::Index j = 0; j < cols; j++) { // col iteration - for (Eigen::Index i = 0; i <= trap_last_idx; i++) { // row iteration - // Get values of nonzero elements - val = mat(i, j); - if (std::fabs(val) < 1e-9) { - continue; - } - elem_count += 1; - - // Store values - vals.push_back(val); - row_idxs.push_back(i); - } - - col_idxs.push_back(elem_count); - trap_last_idx += 1; - } - - CSC_Matrix csc_matrix = {vals, row_idxs, col_idxs}; - - return csc_matrix; -} - -void printCSCMatrix(const CSC_Matrix & csc_mat) -{ - std::cout << "["; - for (const c_float & val : csc_mat.m_vals) { - std::cout << val << ", "; - } - std::cout << "]\n"; - - std::cout << "["; - for (const c_int & row : csc_mat.m_row_idxs) { - std::cout << row << ", "; - } - std::cout << "]\n"; - - std::cout << "["; - for (const c_int & col : csc_mat.m_col_idxs) { - std::cout << col << ", "; - } - std::cout << "]\n"; -} - -} // namespace autoware::osqp_interface diff --git a/common/autoware_osqp_interface/src/osqp_interface.cpp b/common/autoware_osqp_interface/src/osqp_interface.cpp deleted file mode 100644 index ceeae626222ca..0000000000000 --- a/common/autoware_osqp_interface/src/osqp_interface.cpp +++ /dev/null @@ -1,435 +0,0 @@ -// Copyright 2021 The Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/osqp_interface/osqp_interface.hpp" - -#include "autoware/osqp_interface/csc_matrix_conv.hpp" -#include "osqp/osqp.h" - -#include -#include -#include -#include -#include -#include -#include - -namespace autoware::osqp_interface -{ -OSQPInterface::OSQPInterface(const c_float eps_abs, const bool polish) -: m_work{nullptr, OSQPWorkspaceDeleter} -{ - m_settings = std::make_unique(); - m_data = std::make_unique(); - - if (m_settings) { - osqp_set_default_settings(m_settings.get()); - m_settings->alpha = 1.6; // Change alpha parameter - m_settings->eps_rel = 1.0E-4; - m_settings->eps_abs = eps_abs; - m_settings->eps_prim_inf = 1.0E-4; - m_settings->eps_dual_inf = 1.0E-4; - m_settings->warm_start = true; - m_settings->max_iter = 4000; - m_settings->verbose = false; - m_settings->polish = polish; - } - m_exitflag = 0; -} - -OSQPInterface::OSQPInterface( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u, const c_float eps_abs) -: OSQPInterface(eps_abs) -{ - initializeProblem(P, A, q, l, u); -} - -OSQPInterface::OSQPInterface( - const CSC_Matrix & P, const CSC_Matrix & A, const std::vector & q, - const std::vector & l, const std::vector & u, const c_float eps_abs) -: OSQPInterface(eps_abs) -{ - initializeProblem(P, A, q, l, u); -} - -OSQPInterface::~OSQPInterface() -{ - if (m_data->P) free(m_data->P); - if (m_data->A) free(m_data->A); -} - -void OSQPInterface::OSQPWorkspaceDeleter(OSQPWorkspace * ptr) noexcept -{ - if (ptr != nullptr) { - osqp_cleanup(ptr); - } -} - -void OSQPInterface::updateP(const Eigen::MatrixXd & P_new) -{ - /* - // Transform 'P' into an 'upper trapezoidal matrix' - Eigen::MatrixXd P_trap = P_new.triangularView(); - // Transform 'P' into a sparse matrix and extract data as dynamic arrays - Eigen::SparseMatrix P_sparse = P_trap.sparseView(); - double *P_val_ptr = P_sparse.valuePtr(); - // Convert dynamic 'int' arrays to 'c_int' arrays (OSQP input type) - c_int P_elem_N = P_sparse.nonZeros(); - */ - CSC_Matrix P_csc = calCSCMatrixTrapezoidal(P_new); - osqp_update_P( - m_work.get(), P_csc.m_vals.data(), OSQP_NULL, static_cast(P_csc.m_vals.size())); -} - -void OSQPInterface::updateCscP(const CSC_Matrix & P_csc) -{ - osqp_update_P( - m_work.get(), P_csc.m_vals.data(), OSQP_NULL, static_cast(P_csc.m_vals.size())); -} - -void OSQPInterface::updateA(const Eigen::MatrixXd & A_new) -{ - /* - // Transform 'A' into a sparse matrix and extract data as dynamic arrays - Eigen::SparseMatrix A_sparse = A_new.sparseView(); - double *A_val_ptr = A_sparse.valuePtr(); - // Convert dynamic 'int' arrays to 'c_int' arrays (OSQP input type) - c_int A_elem_N = A_sparse.nonZeros(); - */ - CSC_Matrix A_csc = calCSCMatrix(A_new); - osqp_update_A( - m_work.get(), A_csc.m_vals.data(), OSQP_NULL, static_cast(A_csc.m_vals.size())); - return; -} - -void OSQPInterface::updateCscA(const CSC_Matrix & A_csc) -{ - osqp_update_A( - m_work.get(), A_csc.m_vals.data(), OSQP_NULL, static_cast(A_csc.m_vals.size())); -} - -void OSQPInterface::updateQ(const std::vector & q_new) -{ - std::vector q_tmp(q_new.begin(), q_new.end()); - double * q_dyn = q_tmp.data(); - osqp_update_lin_cost(m_work.get(), q_dyn); -} - -void OSQPInterface::updateL(const std::vector & l_new) -{ - std::vector l_tmp(l_new.begin(), l_new.end()); - double * l_dyn = l_tmp.data(); - osqp_update_lower_bound(m_work.get(), l_dyn); -} - -void OSQPInterface::updateU(const std::vector & u_new) -{ - std::vector u_tmp(u_new.begin(), u_new.end()); - double * u_dyn = u_tmp.data(); - osqp_update_upper_bound(m_work.get(), u_dyn); -} - -void OSQPInterface::updateBounds( - const std::vector & l_new, const std::vector & u_new) -{ - std::vector l_tmp(l_new.begin(), l_new.end()); - std::vector u_tmp(u_new.begin(), u_new.end()); - double * l_dyn = l_tmp.data(); - double * u_dyn = u_tmp.data(); - osqp_update_bounds(m_work.get(), l_dyn, u_dyn); -} - -void OSQPInterface::updateEpsAbs(const double eps_abs) -{ - m_settings->eps_abs = eps_abs; // for default setting - if (m_work_initialized) { - osqp_update_eps_abs(m_work.get(), eps_abs); // for current work - } -} - -void OSQPInterface::updateEpsRel(const double eps_rel) -{ - m_settings->eps_rel = eps_rel; // for default setting - if (m_work_initialized) { - osqp_update_eps_rel(m_work.get(), eps_rel); // for current work - } -} - -void OSQPInterface::updateMaxIter(const int max_iter) -{ - m_settings->max_iter = max_iter; // for default setting - if (m_work_initialized) { - osqp_update_max_iter(m_work.get(), max_iter); // for current work - } -} - -void OSQPInterface::updateVerbose(const bool is_verbose) -{ - m_settings->verbose = is_verbose; // for default setting - if (m_work_initialized) { - osqp_update_verbose(m_work.get(), is_verbose); // for current work - } -} - -void OSQPInterface::updateRhoInterval(const int rho_interval) -{ - m_settings->adaptive_rho_interval = rho_interval; // for default setting -} - -void OSQPInterface::updateRho(const double rho) -{ - m_settings->rho = rho; - if (m_work_initialized) { - osqp_update_rho(m_work.get(), rho); - } -} - -void OSQPInterface::updateAlpha(const double alpha) -{ - m_settings->alpha = alpha; - if (m_work_initialized) { - osqp_update_alpha(m_work.get(), alpha); - } -} - -void OSQPInterface::updateScaling(const int scaling) -{ - m_settings->scaling = scaling; -} - -void OSQPInterface::updatePolish(const bool polish) -{ - m_settings->polish = polish; - if (m_work_initialized) { - osqp_update_polish(m_work.get(), polish); - } -} - -void OSQPInterface::updatePolishRefinementIteration(const int polish_refine_iter) -{ - if (polish_refine_iter < 0) { - std::cerr << "Polish refinement iterations must be positive" << std::endl; - return; - } - - m_settings->polish_refine_iter = polish_refine_iter; - if (m_work_initialized) { - osqp_update_polish_refine_iter(m_work.get(), polish_refine_iter); - } -} - -void OSQPInterface::updateCheckTermination(const int check_termination) -{ - if (check_termination < 0) { - std::cerr << "Check termination must be positive" << std::endl; - return; - } - - m_settings->check_termination = check_termination; - if (m_work_initialized) { - osqp_update_check_termination(m_work.get(), check_termination); - } -} - -bool OSQPInterface::setWarmStart( - const std::vector & primal_variables, const std::vector & dual_variables) -{ - return setPrimalVariables(primal_variables) && setDualVariables(dual_variables); -} - -bool OSQPInterface::setPrimalVariables(const std::vector & primal_variables) -{ - if (!m_work_initialized) { - return false; - } - - const auto result = osqp_warm_start_x(m_work.get(), primal_variables.data()); - if (result != 0) { - std::cerr << "Failed to set primal variables for warm start" << std::endl; - return false; - } - - return true; -} - -bool OSQPInterface::setDualVariables(const std::vector & dual_variables) -{ - if (!m_work_initialized) { - return false; - } - - const auto result = osqp_warm_start_y(m_work.get(), dual_variables.data()); - if (result != 0) { - std::cerr << "Failed to set dual variables for warm start" << std::endl; - return false; - } - - return true; -} - -int64_t OSQPInterface::initializeProblem( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u) -{ - // check if arguments are valid - std::stringstream ss; - if (P.rows() != P.cols()) { - ss << "P.rows() and P.cols() are not the same. P.rows() = " << P.rows() - << ", P.cols() = " << P.cols(); - throw std::invalid_argument(ss.str()); - } - if (P.rows() != static_cast(q.size())) { - ss << "P.rows() and q.size() are not the same. P.rows() = " << P.rows() - << ", q.size() = " << q.size(); - throw std::invalid_argument(ss.str()); - } - if (P.rows() != A.cols()) { - ss << "P.rows() and A.cols() are not the same. P.rows() = " << P.rows() - << ", A.cols() = " << A.cols(); - throw std::invalid_argument(ss.str()); - } - if (A.rows() != static_cast(l.size())) { - ss << "A.rows() and l.size() are not the same. A.rows() = " << A.rows() - << ", l.size() = " << l.size(); - throw std::invalid_argument(ss.str()); - } - if (A.rows() != static_cast(u.size())) { - ss << "A.rows() and u.size() are not the same. A.rows() = " << A.rows() - << ", u.size() = " << u.size(); - throw std::invalid_argument(ss.str()); - } - - CSC_Matrix P_csc = calCSCMatrixTrapezoidal(P); - CSC_Matrix A_csc = calCSCMatrix(A); - return initializeProblem(P_csc, A_csc, q, l, u); -} - -int64_t OSQPInterface::initializeProblem( - CSC_Matrix P_csc, CSC_Matrix A_csc, const std::vector & q, const std::vector & l, - const std::vector & u) -{ - // Dynamic float arrays - std::vector q_tmp(q.begin(), q.end()); - std::vector l_tmp(l.begin(), l.end()); - std::vector u_tmp(u.begin(), u.end()); - double * q_dyn = q_tmp.data(); - double * l_dyn = l_tmp.data(); - double * u_dyn = u_tmp.data(); - - /********************** - * OBJECTIVE FUNCTION - **********************/ - m_param_n = static_cast(q.size()); - m_data->m = static_cast(l.size()); - - /***************** - * POPULATE DATA - *****************/ - m_data->n = m_param_n; - if (m_data->P) free(m_data->P); - m_data->P = csc_matrix( - m_data->n, m_data->n, static_cast(P_csc.m_vals.size()), P_csc.m_vals.data(), - P_csc.m_row_idxs.data(), P_csc.m_col_idxs.data()); - m_data->q = q_dyn; - if (m_data->A) free(m_data->A); - m_data->A = csc_matrix( - m_data->m, m_data->n, static_cast(A_csc.m_vals.size()), A_csc.m_vals.data(), - A_csc.m_row_idxs.data(), A_csc.m_col_idxs.data()); - m_data->l = l_dyn; - m_data->u = u_dyn; - - // Setup workspace - OSQPWorkspace * workspace; - m_exitflag = osqp_setup(&workspace, m_data.get(), m_settings.get()); - m_work.reset(workspace); - m_work_initialized = true; - - return m_exitflag; -} - -std::tuple, std::vector, int64_t, int64_t, int64_t> -OSQPInterface::solve() -{ - // Solve Problem - osqp_solve(m_work.get()); - - /******************** - * EXTRACT SOLUTION - ********************/ - double * sol_x = m_work->solution->x; - double * sol_y = m_work->solution->y; - std::vector sol_primal(sol_x, sol_x + m_param_n); - std::vector sol_lagrange_multiplier(sol_y, sol_y + m_data->m); - - int64_t status_polish = m_work->info->status_polish; - int64_t status_solution = m_work->info->status_val; - int64_t status_iteration = m_work->info->iter; - - // Result tuple - std::tuple, std::vector, int64_t, int64_t, int64_t> result = - std::make_tuple( - sol_primal, sol_lagrange_multiplier, status_polish, status_solution, status_iteration); - - m_latest_work_info = *(m_work->info); - - return result; -} - -std::tuple, std::vector, int64_t, int64_t, int64_t> -OSQPInterface::optimize() -{ - // Run the solver on the stored problem representation. - std::tuple, std::vector, int64_t, int64_t, int64_t> result = solve(); - return result; -} - -std::tuple, std::vector, int64_t, int64_t, int64_t> -OSQPInterface::optimize( - const Eigen::MatrixXd & P, const Eigen::MatrixXd & A, const std::vector & q, - const std::vector & l, const std::vector & u) -{ - // Allocate memory for problem - initializeProblem(P, A, q, l, u); - - // Run the solver on the stored problem representation. - std::tuple, std::vector, int64_t, int64_t, int64_t> result = solve(); - - m_work.reset(); - m_work_initialized = false; - - return result; -} - -void OSQPInterface::logUnsolvedStatus(const std::string & prefix_message) const -{ - const int status = getStatus(); - if (status == 1) { - // No need to log since optimization was solved. - return; - } - - // create message - std::string output_message = ""; - if (prefix_message != "") { - output_message = prefix_message + " "; - } - - const auto status_message = getStatusMessage(); - output_message += "Optimization failed due to " + status_message; - - // log with warning - RCLCPP_WARN(rclcpp::get_logger("osqp_interface"), "%s", output_message.c_str()); -} -} // namespace autoware::osqp_interface diff --git a/common/autoware_osqp_interface/test/test_csc_matrix_conv.cpp b/common/autoware_osqp_interface/test/test_csc_matrix_conv.cpp deleted file mode 100644 index a63f979a966bf..0000000000000 --- a/common/autoware_osqp_interface/test/test_csc_matrix_conv.cpp +++ /dev/null @@ -1,181 +0,0 @@ -// Copyright 2021 The Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/osqp_interface/csc_matrix_conv.hpp" -#include "gtest/gtest.h" - -#include - -#include -#include -#include - -TEST(TestCscMatrixConv, Nominal) -{ - using autoware::osqp_interface::calCSCMatrix; - using autoware::osqp_interface::CSC_Matrix; - - Eigen::MatrixXd rect1(1, 2); - rect1 << 0.0, 1.0; - - const CSC_Matrix rect_m1 = calCSCMatrix(rect1); - ASSERT_EQ(rect_m1.m_vals.size(), size_t(1)); - EXPECT_EQ(rect_m1.m_vals[0], 1.0); - ASSERT_EQ(rect_m1.m_row_idxs.size(), size_t(1)); - EXPECT_EQ(rect_m1.m_row_idxs[0], c_int(0)); - ASSERT_EQ(rect_m1.m_col_idxs.size(), size_t(3)); // nb of columns + 1 - EXPECT_EQ(rect_m1.m_col_idxs[0], c_int(0)); - EXPECT_EQ(rect_m1.m_col_idxs[1], c_int(0)); - EXPECT_EQ(rect_m1.m_col_idxs[2], c_int(1)); - - Eigen::MatrixXd rect2(2, 4); - rect2 << 1.0, 0.0, 3.0, 0.0, 0.0, 6.0, 7.0, 0.0; - - const CSC_Matrix rect_m2 = calCSCMatrix(rect2); - ASSERT_EQ(rect_m2.m_vals.size(), size_t(4)); - EXPECT_EQ(rect_m2.m_vals[0], 1.0); - EXPECT_EQ(rect_m2.m_vals[1], 6.0); - EXPECT_EQ(rect_m2.m_vals[2], 3.0); - EXPECT_EQ(rect_m2.m_vals[3], 7.0); - ASSERT_EQ(rect_m2.m_row_idxs.size(), size_t(4)); - EXPECT_EQ(rect_m2.m_row_idxs[0], c_int(0)); - EXPECT_EQ(rect_m2.m_row_idxs[1], c_int(1)); - EXPECT_EQ(rect_m2.m_row_idxs[2], c_int(0)); - EXPECT_EQ(rect_m2.m_row_idxs[3], c_int(1)); - ASSERT_EQ(rect_m2.m_col_idxs.size(), size_t(5)); // nb of columns + 1 - EXPECT_EQ(rect_m2.m_col_idxs[0], c_int(0)); - EXPECT_EQ(rect_m2.m_col_idxs[1], c_int(1)); - EXPECT_EQ(rect_m2.m_col_idxs[2], c_int(2)); - EXPECT_EQ(rect_m2.m_col_idxs[3], c_int(4)); - EXPECT_EQ(rect_m2.m_col_idxs[4], c_int(4)); - - // Example from http://netlib.org/linalg/html_templates/node92.html - Eigen::MatrixXd square2(6, 6); - square2 << 10.0, 0.0, 0.0, 0.0, -2.0, 0.0, 3.0, 9.0, 0.0, 0.0, 0.0, 3.0, 0.0, 7.0, 8.0, 7.0, 0.0, - 0.0, 3.0, 0.0, 8.0, 7.0, 5.0, 0.0, 0.0, 8.0, 0.0, 9.0, 9.0, 13.0, 0.0, 4.0, 0.0, 0.0, 2.0, -1.0; - - const CSC_Matrix square_m2 = calCSCMatrix(square2); - ASSERT_EQ(square_m2.m_vals.size(), size_t(19)); - EXPECT_EQ(square_m2.m_vals[0], 10.0); - EXPECT_EQ(square_m2.m_vals[1], 3.0); - EXPECT_EQ(square_m2.m_vals[2], 3.0); - EXPECT_EQ(square_m2.m_vals[3], 9.0); - EXPECT_EQ(square_m2.m_vals[4], 7.0); - EXPECT_EQ(square_m2.m_vals[5], 8.0); - EXPECT_EQ(square_m2.m_vals[6], 4.0); - EXPECT_EQ(square_m2.m_vals[7], 8.0); - EXPECT_EQ(square_m2.m_vals[8], 8.0); - EXPECT_EQ(square_m2.m_vals[9], 7.0); - EXPECT_EQ(square_m2.m_vals[10], 7.0); - EXPECT_EQ(square_m2.m_vals[11], 9.0); - EXPECT_EQ(square_m2.m_vals[12], -2.0); - EXPECT_EQ(square_m2.m_vals[13], 5.0); - EXPECT_EQ(square_m2.m_vals[14], 9.0); - EXPECT_EQ(square_m2.m_vals[15], 2.0); - EXPECT_EQ(square_m2.m_vals[16], 3.0); - EXPECT_EQ(square_m2.m_vals[17], 13.0); - EXPECT_EQ(square_m2.m_vals[18], -1.0); - ASSERT_EQ(square_m2.m_row_idxs.size(), size_t(19)); - EXPECT_EQ(square_m2.m_row_idxs[0], c_int(0)); - EXPECT_EQ(square_m2.m_row_idxs[1], c_int(1)); - EXPECT_EQ(square_m2.m_row_idxs[2], c_int(3)); - EXPECT_EQ(square_m2.m_row_idxs[3], c_int(1)); - EXPECT_EQ(square_m2.m_row_idxs[4], c_int(2)); - EXPECT_EQ(square_m2.m_row_idxs[5], c_int(4)); - EXPECT_EQ(square_m2.m_row_idxs[6], c_int(5)); - EXPECT_EQ(square_m2.m_row_idxs[7], c_int(2)); - EXPECT_EQ(square_m2.m_row_idxs[8], c_int(3)); - EXPECT_EQ(square_m2.m_row_idxs[9], c_int(2)); - EXPECT_EQ(square_m2.m_row_idxs[10], c_int(3)); - EXPECT_EQ(square_m2.m_row_idxs[11], c_int(4)); - EXPECT_EQ(square_m2.m_row_idxs[12], c_int(0)); - EXPECT_EQ(square_m2.m_row_idxs[13], c_int(3)); - EXPECT_EQ(square_m2.m_row_idxs[14], c_int(4)); - EXPECT_EQ(square_m2.m_row_idxs[15], c_int(5)); - EXPECT_EQ(square_m2.m_row_idxs[16], c_int(1)); - EXPECT_EQ(square_m2.m_row_idxs[17], c_int(4)); - EXPECT_EQ(square_m2.m_row_idxs[18], c_int(5)); - ASSERT_EQ(square_m2.m_col_idxs.size(), size_t(7)); // nb of columns + 1 - EXPECT_EQ(square_m2.m_col_idxs[0], c_int(0)); - EXPECT_EQ(square_m2.m_col_idxs[1], c_int(3)); - EXPECT_EQ(square_m2.m_col_idxs[2], c_int(7)); - EXPECT_EQ(square_m2.m_col_idxs[3], c_int(9)); - EXPECT_EQ(square_m2.m_col_idxs[4], c_int(12)); - EXPECT_EQ(square_m2.m_col_idxs[5], c_int(16)); - EXPECT_EQ(square_m2.m_col_idxs[6], c_int(19)); -} -TEST(TestCscMatrixConv, Trapezoidal) -{ - using autoware::osqp_interface::calCSCMatrixTrapezoidal; - using autoware::osqp_interface::CSC_Matrix; - - Eigen::MatrixXd square1(2, 2); - Eigen::MatrixXd square2(3, 3); - Eigen::MatrixXd rect1(1, 2); - square1 << 1.0, 2.0, 2.0, 4.0; - square2 << 0.0, 2.0, 0.0, 4.0, 5.0, 6.0, 0.0, 0.0, 0.0; - rect1 << 0.0, 1.0; - - const CSC_Matrix square_m1 = calCSCMatrixTrapezoidal(square1); - // Trapezoidal: skip the lower left triangle (2.0 in this example) - ASSERT_EQ(square_m1.m_vals.size(), size_t(3)); - EXPECT_EQ(square_m1.m_vals[0], 1.0); - EXPECT_EQ(square_m1.m_vals[1], 2.0); - EXPECT_EQ(square_m1.m_vals[2], 4.0); - ASSERT_EQ(square_m1.m_row_idxs.size(), size_t(3)); - EXPECT_EQ(square_m1.m_row_idxs[0], c_int(0)); - EXPECT_EQ(square_m1.m_row_idxs[1], c_int(0)); - EXPECT_EQ(square_m1.m_row_idxs[2], c_int(1)); - ASSERT_EQ(square_m1.m_col_idxs.size(), size_t(3)); - EXPECT_EQ(square_m1.m_col_idxs[0], c_int(0)); - EXPECT_EQ(square_m1.m_col_idxs[1], c_int(1)); - EXPECT_EQ(square_m1.m_col_idxs[2], c_int(3)); - - const CSC_Matrix square_m2 = calCSCMatrixTrapezoidal(square2); - ASSERT_EQ(square_m2.m_vals.size(), size_t(3)); - EXPECT_EQ(square_m2.m_vals[0], 2.0); - EXPECT_EQ(square_m2.m_vals[1], 5.0); - EXPECT_EQ(square_m2.m_vals[2], 6.0); - ASSERT_EQ(square_m2.m_row_idxs.size(), size_t(3)); - EXPECT_EQ(square_m2.m_row_idxs[0], c_int(0)); - EXPECT_EQ(square_m2.m_row_idxs[1], c_int(1)); - EXPECT_EQ(square_m2.m_row_idxs[2], c_int(1)); - ASSERT_EQ(square_m2.m_col_idxs.size(), size_t(4)); - EXPECT_EQ(square_m2.m_col_idxs[0], c_int(0)); - EXPECT_EQ(square_m2.m_col_idxs[1], c_int(0)); - EXPECT_EQ(square_m2.m_col_idxs[2], c_int(2)); - EXPECT_EQ(square_m2.m_col_idxs[3], c_int(3)); - - try { - const CSC_Matrix rect_m1 = calCSCMatrixTrapezoidal(rect1); - FAIL() << "calCSCMatrixTrapezoidal should fail with non-square inputs"; - } catch (const std::invalid_argument & e) { - EXPECT_EQ(e.what(), std::string("Matrix must be square (n, n)")); - } -} -TEST(TestCscMatrixConv, Print) -{ - using autoware::osqp_interface::calCSCMatrix; - using autoware::osqp_interface::calCSCMatrixTrapezoidal; - using autoware::osqp_interface::CSC_Matrix; - using autoware::osqp_interface::printCSCMatrix; - Eigen::MatrixXd square1(2, 2); - Eigen::MatrixXd rect1(1, 2); - square1 << 1.0, 2.0, 2.0, 4.0; - rect1 << 0.0, 1.0; - const CSC_Matrix square_m1 = calCSCMatrixTrapezoidal(square1); - const CSC_Matrix rect_m1 = calCSCMatrix(rect1); - printCSCMatrix(square_m1); - printCSCMatrix(rect_m1); -} diff --git a/common/autoware_osqp_interface/test/test_osqp_interface.cpp b/common/autoware_osqp_interface/test/test_osqp_interface.cpp deleted file mode 100644 index f65b07e6d792d..0000000000000 --- a/common/autoware_osqp_interface/test/test_osqp_interface.cpp +++ /dev/null @@ -1,164 +0,0 @@ -// Copyright 2021 The Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/osqp_interface/osqp_interface.hpp" -#include "gtest/gtest.h" - -#include - -#include -#include -#include - -namespace -{ -// Problem taken from https://github.com/osqp/osqp/blob/master/tests/basic_qp/generate_problem.py -// -// min 1/2 * x' * P * x + q' * x -// s.t. lb <= A * x <= ub -// -// P = [4, 1], q = [1], A = [1, 1], lb = [ 1], ub = [1.0] -// [1, 2] [1] [1, 0] [ 0] [0.7] -// [0, 1] [ 0] [0.7] -// [0, 1] [-inf] [inf] -// -// The optimal solution is -// x = [0.3, 0.7]' -// y = [-2.9, 0.0, 0.2, 0.0]` -// obj = 1.88 - -TEST(TestOsqpInterface, BasicQp) -{ - using autoware::osqp_interface::calCSCMatrix; - using autoware::osqp_interface::calCSCMatrixTrapezoidal; - using autoware::osqp_interface::CSC_Matrix; - - auto check_result = - [](const std::tuple, std::vector, int, int, int> & result) { - EXPECT_EQ(std::get<2>(result), 1); // polish succeeded - EXPECT_EQ(std::get<3>(result), 1); // solution succeeded - - static const auto ep = 1.0e-8; - - const auto prime_val = std::get<0>(result); - ASSERT_EQ(prime_val.size(), size_t(2)); - EXPECT_NEAR(prime_val[0], 0.3, ep); - EXPECT_NEAR(prime_val[1], 0.7, ep); - - const auto dual_val = std::get<1>(result); - ASSERT_EQ(dual_val.size(), size_t(4)); - EXPECT_NEAR(dual_val[0], -2.9, ep); - EXPECT_NEAR(dual_val[1], 0.0, ep); - EXPECT_NEAR(dual_val[2], 0.2, ep); - EXPECT_NEAR(dual_val[3], 0.0, ep); - }; - - const Eigen::MatrixXd P = (Eigen::MatrixXd(2, 2) << 4, 1, 1, 2).finished(); - const Eigen::MatrixXd A = (Eigen::MatrixXd(4, 2) << 1, 1, 1, 0, 0, 1, 0, 1).finished(); - const std::vector q = {1.0, 1.0}; - const std::vector l = {1.0, 0.0, 0.0, -autoware::osqp_interface::INF}; - const std::vector u = {1.0, 0.7, 0.7, autoware::osqp_interface::INF}; - - { - // Define problem during optimization - autoware::osqp_interface::OSQPInterface osqp; - std::tuple, std::vector, int, int, int> result = - osqp.optimize(P, A, q, l, u); - check_result(result); - } - - { - // Define problem during initialization - autoware::osqp_interface::OSQPInterface osqp(P, A, q, l, u, 1e-6); - std::tuple, std::vector, int, int, int> result = osqp.optimize(); - check_result(result); - } - - { - std::tuple, std::vector, int, int, int> result; - // Dummy initial problem - Eigen::MatrixXd P_ini = Eigen::MatrixXd::Zero(2, 2); - Eigen::MatrixXd A_ini = Eigen::MatrixXd::Zero(4, 2); - std::vector q_ini(2, 0.0); - std::vector l_ini(4, 0.0); - std::vector u_ini(4, 0.0); - autoware::osqp_interface::OSQPInterface osqp(P_ini, A_ini, q_ini, l_ini, u_ini, 1e-6); - osqp.optimize(); - - // Redefine problem before optimization - osqp.initializeProblem(P, A, q, l, u); - result = osqp.optimize(); - check_result(result); - } - - { - // Define problem during initialization with csc matrix - CSC_Matrix P_csc = calCSCMatrixTrapezoidal(P); - CSC_Matrix A_csc = calCSCMatrix(A); - autoware::osqp_interface::OSQPInterface osqp(P_csc, A_csc, q, l, u, 1e-6); - std::tuple, std::vector, int, int, int> result = osqp.optimize(); - check_result(result); - } - - { - std::tuple, std::vector, int, int, int> result; - // Dummy initial problem with csc matrix - CSC_Matrix P_ini_csc = calCSCMatrixTrapezoidal(Eigen::MatrixXd::Zero(2, 2)); - CSC_Matrix A_ini_csc = calCSCMatrix(Eigen::MatrixXd::Zero(4, 2)); - std::vector q_ini(2, 0.0); - std::vector l_ini(4, 0.0); - std::vector u_ini(4, 0.0); - autoware::osqp_interface::OSQPInterface osqp(P_ini_csc, A_ini_csc, q_ini, l_ini, u_ini, 1e-6); - osqp.optimize(); - - // Redefine problem before optimization - CSC_Matrix P_csc = calCSCMatrixTrapezoidal(P); - CSC_Matrix A_csc = calCSCMatrix(A); - osqp.initializeProblem(P_csc, A_csc, q, l, u); - result = osqp.optimize(); - check_result(result); - } - - // add warm startup - { - std::tuple, std::vector, int, int, int> result; - // Dummy initial problem with csc matrix - CSC_Matrix P_ini_csc = calCSCMatrixTrapezoidal(Eigen::MatrixXd::Zero(2, 2)); - CSC_Matrix A_ini_csc = calCSCMatrix(Eigen::MatrixXd::Zero(4, 2)); - std::vector q_ini(2, 0.0); - std::vector l_ini(4, 0.0); - std::vector u_ini(4, 0.0); - autoware::osqp_interface::OSQPInterface osqp(P_ini_csc, A_ini_csc, q_ini, l_ini, u_ini, 1e-6); - osqp.optimize(); - - // Redefine problem before optimization - CSC_Matrix P_csc = calCSCMatrixTrapezoidal(P); - CSC_Matrix A_csc = calCSCMatrix(A); - osqp.initializeProblem(P_csc, A_csc, q, l, u); - result = osqp.optimize(); - check_result(result); - - osqp.updateCheckTermination(1); - const auto primal_val = std::get<0>(result); - const auto dual_val = std::get<1>(result); - for (size_t i = 0; i < primal_val.size(); ++i) { - std::cerr << primal_val.at(i) << std::endl; - } - osqp.setWarmStart(primal_val, dual_val); - result = osqp.optimize(); - check_result(result); - EXPECT_EQ(osqp.getTakenIter(), 1); - } -} -} // namespace From a6b5f3c6992e6978eec4c110d1956df99c0219ca Mon Sep 17 00:00:00 2001 From: cyn-liu <104069308+cyn-liu@users.noreply.github.com> Date: Wed, 15 Jan 2025 10:17:04 +0800 Subject: [PATCH 203/334] feat(autoware_kalman_filter): move autoware_kalman_filter to autowar.core (#9872) feat(autoware_kalman_filter): move autoware_kalman_filter to autoware.core Signed-off-by: liu cui --- common/autoware_kalman_filter/CHANGELOG.rst | 55 ----- common/autoware_kalman_filter/CMakeLists.txt | 29 --- common/autoware_kalman_filter/README.md | 9 - .../autoware/kalman_filter/kalman_filter.hpp | 214 ------------------ .../time_delay_kalman_filter.hpp | 89 -------- common/autoware_kalman_filter/package.xml | 28 --- .../src/kalman_filter.cpp | 161 ------------- .../src/time_delay_kalman_filter.cpp | 109 --------- .../test/test_kalman_filter.cpp | 96 -------- .../test/test_time_delay_kalman_filter.cpp | 123 ---------- 10 files changed, 913 deletions(-) delete mode 100644 common/autoware_kalman_filter/CHANGELOG.rst delete mode 100644 common/autoware_kalman_filter/CMakeLists.txt delete mode 100644 common/autoware_kalman_filter/README.md delete mode 100644 common/autoware_kalman_filter/include/autoware/kalman_filter/kalman_filter.hpp delete mode 100644 common/autoware_kalman_filter/include/autoware/kalman_filter/time_delay_kalman_filter.hpp delete mode 100644 common/autoware_kalman_filter/package.xml delete mode 100644 common/autoware_kalman_filter/src/kalman_filter.cpp delete mode 100644 common/autoware_kalman_filter/src/time_delay_kalman_filter.cpp delete mode 100644 common/autoware_kalman_filter/test/test_kalman_filter.cpp delete mode 100644 common/autoware_kalman_filter/test/test_time_delay_kalman_filter.cpp diff --git a/common/autoware_kalman_filter/CHANGELOG.rst b/common/autoware_kalman_filter/CHANGELOG.rst deleted file mode 100644 index a7e68f8843e74..0000000000000 --- a/common/autoware_kalman_filter/CHANGELOG.rst +++ /dev/null @@ -1,55 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package autoware_kalman_filter -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -0.40.0 (2024-12-12) -------------------- -* Merge branch 'main' into release-0.40.0 -* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" - This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. -* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) -* chore(package.xml): bump version to 0.39.0 (`#9587 `_) - * chore(package.xml): bump version to 0.39.0 - * fix: fix ticket links in CHANGELOG.rst - * fix: remove unnecessary diff - --------- - Co-authored-by: Yutaka Kondo -* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) -* fix(cpplint): include what you use - common (`#9564 `_) -* 0.39.0 -* update changelog -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) - * unify package.xml version to 0.37.0 - * remove system_monitor/CHANGELOG.rst - * add changelog - * 0.38.0 - --------- -* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo - -0.39.0 (2024-11-25) -------------------- -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) - * unify package.xml version to 0.37.0 - * remove system_monitor/CHANGELOG.rst - * add changelog - * 0.38.0 - --------- -* Contributors: Esteve Fernandez, Yutaka Kondo - -0.38.0 (2024-11-08) -------------------- -* unify package.xml version to 0.37.0 -* refactor(kalman_filter): prefix package and namespace with autoware (`#7787 `_) - * refactor(kalman_filter): prefix package and namespace with autoware - * move headers to include/autoware/ - * style(pre-commit): autofix - --------- - Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> -* Contributors: Esteve Fernandez, Yutaka Kondo - -0.26.0 (2024-04-03) -------------------- diff --git a/common/autoware_kalman_filter/CMakeLists.txt b/common/autoware_kalman_filter/CMakeLists.txt deleted file mode 100644 index 076d2d3cad4e8..0000000000000 --- a/common/autoware_kalman_filter/CMakeLists.txt +++ /dev/null @@ -1,29 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(autoware_kalman_filter) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -find_package(eigen3_cmake_module REQUIRED) -find_package(Eigen3 REQUIRED) - -include_directories( - SYSTEM - ${EIGEN3_INCLUDE_DIR} -) - -ament_auto_add_library(${PROJECT_NAME} SHARED - src/kalman_filter.cpp - src/time_delay_kalman_filter.cpp - include/autoware/kalman_filter/kalman_filter.hpp - include/autoware/kalman_filter/time_delay_kalman_filter.hpp -) - -if(BUILD_TESTING) - file(GLOB_RECURSE test_files test/*.cpp) - ament_add_ros_isolated_gtest(test_${PROJECT_NAME} ${test_files}) - - target_link_libraries(test_${PROJECT_NAME} ${PROJECT_NAME}) -endif() - -ament_auto_package() diff --git a/common/autoware_kalman_filter/README.md b/common/autoware_kalman_filter/README.md deleted file mode 100644 index 7c0feb9c2a61a..0000000000000 --- a/common/autoware_kalman_filter/README.md +++ /dev/null @@ -1,9 +0,0 @@ -# kalman_filter - -## Purpose - -This common package contains the kalman filter with time delay and the calculation of the kalman filter. - -## Assumptions / Known limits - -TBD. diff --git a/common/autoware_kalman_filter/include/autoware/kalman_filter/kalman_filter.hpp b/common/autoware_kalman_filter/include/autoware/kalman_filter/kalman_filter.hpp deleted file mode 100644 index 74db04f6e838b..0000000000000 --- a/common/autoware_kalman_filter/include/autoware/kalman_filter/kalman_filter.hpp +++ /dev/null @@ -1,214 +0,0 @@ -// Copyright 2018-2019 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__KALMAN_FILTER__KALMAN_FILTER_HPP_ -#define AUTOWARE__KALMAN_FILTER__KALMAN_FILTER_HPP_ - -#include -#include - -namespace autoware::kalman_filter -{ - -/** - * @file kalman_filter.h - * @brief kalman filter class - * @author Takamasa Horibe - * @date 2019.05.01 - */ - -class KalmanFilter -{ -public: - /** - * @brief No initialization constructor. - */ - KalmanFilter(); - - /** - * @brief constructor with initialization - * @param x initial state - * @param A coefficient matrix of x for process model - * @param B coefficient matrix of u for process model - * @param C coefficient matrix of x for measurement model - * @param Q covariance matrix for process model - * @param R covariance matrix for measurement model - * @param P initial covariance of estimated state - */ - KalmanFilter( - const Eigen::MatrixXd & x, const Eigen::MatrixXd & A, const Eigen::MatrixXd & B, - const Eigen::MatrixXd & C, const Eigen::MatrixXd & Q, const Eigen::MatrixXd & R, - const Eigen::MatrixXd & P); - - /** - * @brief destructor - */ - ~KalmanFilter(); - - /** - * @brief initialization of kalman filter - * @param x initial state - * @param A coefficient matrix of x for process model - * @param B coefficient matrix of u for process model - * @param C coefficient matrix of x for measurement model - * @param Q covariance matrix for process model - * @param R covariance matrix for measurement model - * @param P initial covariance of estimated state - */ - bool init( - const Eigen::MatrixXd & x, const Eigen::MatrixXd & A, const Eigen::MatrixXd & B, - const Eigen::MatrixXd & C, const Eigen::MatrixXd & Q, const Eigen::MatrixXd & R, - const Eigen::MatrixXd & P); - - /** - * @brief initialization of kalman filter - * @param x initial state - * @param P initial covariance of estimated state - */ - bool init(const Eigen::MatrixXd & x, const Eigen::MatrixXd & P0); - - /** - * @brief set A of process model - * @param A coefficient matrix of x for process model - */ - void setA(const Eigen::MatrixXd & A); - - /** - * @brief set B of process model - * @param B coefficient matrix of u for process model - */ - void setB(const Eigen::MatrixXd & B); - - /** - * @brief set C of measurement model - * @param C coefficient matrix of x for measurement model - */ - void setC(const Eigen::MatrixXd & C); - - /** - * @brief set covariance matrix Q for process model - * @param Q covariance matrix for process model - */ - void setQ(const Eigen::MatrixXd & Q); - - /** - * @brief set covariance matrix R for measurement model - * @param R covariance matrix for measurement model - */ - void setR(const Eigen::MatrixXd & R); - - /** - * @brief get current kalman filter state - * @param x kalman filter state - */ - void getX(Eigen::MatrixXd & x) const; - - /** - * @brief get current kalman filter covariance - * @param P kalman filter covariance - */ - void getP(Eigen::MatrixXd & P) const; - - /** - * @brief get component of current kalman filter state - * @param i index of kalman filter state - * @return value of i's component of the kalman filter state x[i] - */ - double getXelement(unsigned int i) const; - - /** - * @brief calculate kalman filter state and covariance by prediction model with A, B, Q matrix. - * This is mainly for EKF with variable matrix. - * @param u input for model - * @param A coefficient matrix of x for process model - * @param B coefficient matrix of u for process model - * @param Q covariance matrix for process model - * @return bool to check matrix operations are being performed properly - */ - bool predict( - const Eigen::MatrixXd & u, const Eigen::MatrixXd & A, const Eigen::MatrixXd & B, - const Eigen::MatrixXd & Q); - - /** - * @brief calculate kalman filter covariance with prediction model with x, A, Q matrix. This is - * mainly for EKF with variable matrix. - * @param x_next predicted state - * @param A coefficient matrix of x for process model - * @param Q covariance matrix for process model - * @return bool to check matrix operations are being performed properly - */ - bool predict( - const Eigen::MatrixXd & x_next, const Eigen::MatrixXd & A, const Eigen::MatrixXd & Q); - - /** - * @brief calculate kalman filter covariance with prediction model with x, A, Q matrix. This is - * mainly for EKF with variable matrix. - * @param x_next predicted state - * @param A coefficient matrix of x for process model - * @return bool to check matrix operations are being performed properly - */ - bool predict(const Eigen::MatrixXd & x_next, const Eigen::MatrixXd & A); - - /** - * @brief calculate kalman filter state by prediction model with A, B and Q being class member - * variables. - * @param u input for the model - * @return bool to check matrix operations are being performed properly - */ - bool predict(const Eigen::MatrixXd & u); - - /** - * @brief calculate kalman filter state by measurement model with y_pred, C and R matrix. This is - * mainly for EKF with variable matrix. - * @param y measured values - * @param y output values expected from measurement model - * @param C coefficient matrix of x for measurement model - * @param R covariance matrix for measurement model - * @return bool to check matrix operations are being performed properly - */ - bool update( - const Eigen::MatrixXd & y, const Eigen::MatrixXd & y_pred, const Eigen::MatrixXd & C, - const Eigen::MatrixXd & R); - - /** - * @brief calculate kalman filter state by measurement model with C and R matrix. This is mainly - * for EKF with variable matrix. - * @param y measured values - * @param C coefficient matrix of x for measurement model - * @param R covariance matrix for measurement model - * @return bool to check matrix operations are being performed properly - */ - bool update(const Eigen::MatrixXd & y, const Eigen::MatrixXd & C, const Eigen::MatrixXd & R); - - /** - * @brief calculate kalman filter state by measurement model with C and R being class member - * variables. - * @param y measured values - * @return bool to check matrix operations are being performed properly - */ - bool update(const Eigen::MatrixXd & y); - -protected: - Eigen::MatrixXd x_; //!< @brief current estimated state - Eigen::MatrixXd - A_; //!< @brief coefficient matrix of x for process model x[k+1] = A*x[k] + B*u[k] - Eigen::MatrixXd - B_; //!< @brief coefficient matrix of u for process model x[k+1] = A*x[k] + B*u[k] - Eigen::MatrixXd C_; //!< @brief coefficient matrix of x for measurement model y[k] = C * x[k] - Eigen::MatrixXd Q_; //!< @brief covariance matrix for process model x[k+1] = A*x[k] + B*u[k] - Eigen::MatrixXd R_; //!< @brief covariance matrix for measurement model y[k] = C * x[k] - Eigen::MatrixXd P_; //!< @brief covariance of estimated state -}; -} // namespace autoware::kalman_filter -#endif // AUTOWARE__KALMAN_FILTER__KALMAN_FILTER_HPP_ diff --git a/common/autoware_kalman_filter/include/autoware/kalman_filter/time_delay_kalman_filter.hpp b/common/autoware_kalman_filter/include/autoware/kalman_filter/time_delay_kalman_filter.hpp deleted file mode 100644 index 80375b7579e62..0000000000000 --- a/common/autoware_kalman_filter/include/autoware/kalman_filter/time_delay_kalman_filter.hpp +++ /dev/null @@ -1,89 +0,0 @@ -// Copyright 2018-2019 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__KALMAN_FILTER__TIME_DELAY_KALMAN_FILTER_HPP_ -#define AUTOWARE__KALMAN_FILTER__TIME_DELAY_KALMAN_FILTER_HPP_ - -#include "autoware/kalman_filter/kalman_filter.hpp" - -#include -#include - -#include - -namespace autoware::kalman_filter -{ -/** - * @file time_delay_kalman_filter.h - * @brief kalman filter with delayed measurement class - * @author Takamasa Horibe - * @date 2019.05.01 - */ - -class TimeDelayKalmanFilter : public KalmanFilter -{ -public: - /** - * @brief No initialization constructor. - */ - TimeDelayKalmanFilter(); - - /** - * @brief initialization of kalman filter - * @param x initial state - * @param P0 initial covariance of estimated state - * @param max_delay_step Maximum number of delay steps, which determines the dimension of the - * extended kalman filter - */ - void init(const Eigen::MatrixXd & x, const Eigen::MatrixXd & P, const int max_delay_step); - - /** - * @brief get latest time estimated state - */ - Eigen::MatrixXd getLatestX() const; - - /** - * @brief get latest time estimation covariance - */ - Eigen::MatrixXd getLatestP() const; - - /** - * @brief calculate kalman filter covariance by precision model with time delay. This is mainly - * for EKF of nonlinear process model. - * @param x_next predicted state by prediction model - * @param A coefficient matrix of x for process model - * @param Q covariance matrix for process model - */ - bool predictWithDelay( - const Eigen::MatrixXd & x_next, const Eigen::MatrixXd & A, const Eigen::MatrixXd & Q); - - /** - * @brief calculate kalman filter covariance by measurement model with time delay. This is mainly - * for EKF of nonlinear process model. - * @param y measured values - * @param C coefficient matrix of x for measurement model - * @param R covariance matrix for measurement model - * @param delay_step measurement delay - */ - bool updateWithDelay( - const Eigen::MatrixXd & y, const Eigen::MatrixXd & C, const Eigen::MatrixXd & R, - const int delay_step); - -private: - int max_delay_step_; //!< @brief maximum number of delay steps - int dim_x_; //!< @brief dimension of latest state - int dim_x_ex_; //!< @brief dimension of extended state with dime delay -}; -} // namespace autoware::kalman_filter -#endif // AUTOWARE__KALMAN_FILTER__TIME_DELAY_KALMAN_FILTER_HPP_ diff --git a/common/autoware_kalman_filter/package.xml b/common/autoware_kalman_filter/package.xml deleted file mode 100644 index e51bb06e9de43..0000000000000 --- a/common/autoware_kalman_filter/package.xml +++ /dev/null @@ -1,28 +0,0 @@ - - - - autoware_kalman_filter - 0.40.0 - The kalman filter package - Yukihiro Saito - Takeshi Ishita - Koji Minoda - Apache License 2.0 - - Takamasa Horibe - - ament_cmake_auto - autoware_cmake - - eigen - eigen3_cmake_module - - ament_cmake_cppcheck - ament_cmake_ros - ament_lint_auto - autoware_lint_common - - - ament_cmake - - diff --git a/common/autoware_kalman_filter/src/kalman_filter.cpp b/common/autoware_kalman_filter/src/kalman_filter.cpp deleted file mode 100644 index bbd963675f9e2..0000000000000 --- a/common/autoware_kalman_filter/src/kalman_filter.cpp +++ /dev/null @@ -1,161 +0,0 @@ -// Copyright 2018-2019 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/kalman_filter/kalman_filter.hpp" - -namespace autoware::kalman_filter -{ -KalmanFilter::KalmanFilter() -{ -} -KalmanFilter::KalmanFilter( - const Eigen::MatrixXd & x, const Eigen::MatrixXd & A, const Eigen::MatrixXd & B, - const Eigen::MatrixXd & C, const Eigen::MatrixXd & Q, const Eigen::MatrixXd & R, - const Eigen::MatrixXd & P) -{ - init(x, A, B, C, Q, R, P); -} -KalmanFilter::~KalmanFilter() -{ -} -bool KalmanFilter::init( - const Eigen::MatrixXd & x, const Eigen::MatrixXd & A, const Eigen::MatrixXd & B, - const Eigen::MatrixXd & C, const Eigen::MatrixXd & Q, const Eigen::MatrixXd & R, - const Eigen::MatrixXd & P) -{ - if ( - x.cols() == 0 || x.rows() == 0 || A.cols() == 0 || A.rows() == 0 || B.cols() == 0 || - B.rows() == 0 || C.cols() == 0 || C.rows() == 0 || Q.cols() == 0 || Q.rows() == 0 || - R.cols() == 0 || R.rows() == 0 || P.cols() == 0 || P.rows() == 0) { - return false; - } - x_ = x; - A_ = A; - B_ = B; - C_ = C; - Q_ = Q; - R_ = R; - P_ = P; - return true; -} -bool KalmanFilter::init(const Eigen::MatrixXd & x, const Eigen::MatrixXd & P0) -{ - if (x.cols() == 0 || x.rows() == 0 || P0.cols() == 0 || P0.rows() == 0) { - return false; - } - x_ = x; - P_ = P0; - return true; -} - -void KalmanFilter::setA(const Eigen::MatrixXd & A) -{ - A_ = A; -} -void KalmanFilter::setB(const Eigen::MatrixXd & B) -{ - B_ = B; -} -void KalmanFilter::setC(const Eigen::MatrixXd & C) -{ - C_ = C; -} -void KalmanFilter::setQ(const Eigen::MatrixXd & Q) -{ - Q_ = Q; -} -void KalmanFilter::setR(const Eigen::MatrixXd & R) -{ - R_ = R; -} -void KalmanFilter::getX(Eigen::MatrixXd & x) const -{ - x = x_; -} -void KalmanFilter::getP(Eigen::MatrixXd & P) const -{ - P = P_; -} -double KalmanFilter::getXelement(unsigned int i) const -{ - return x_(i); -} - -bool KalmanFilter::predict( - const Eigen::MatrixXd & x_next, const Eigen::MatrixXd & A, const Eigen::MatrixXd & Q) -{ - if ( - x_.rows() != x_next.rows() || A.cols() != P_.rows() || Q.cols() != Q.rows() || - A.rows() != Q.cols()) { - return false; - } - x_ = x_next; - P_ = A * P_ * A.transpose() + Q; - return true; -} -bool KalmanFilter::predict(const Eigen::MatrixXd & x_next, const Eigen::MatrixXd & A) -{ - return predict(x_next, A, Q_); -} - -bool KalmanFilter::predict( - const Eigen::MatrixXd & u, const Eigen::MatrixXd & A, const Eigen::MatrixXd & B, - const Eigen::MatrixXd & Q) -{ - if (A.cols() != x_.rows() || B.cols() != u.rows()) { - return false; - } - const Eigen::MatrixXd x_next = A * x_ + B * u; - return predict(x_next, A, Q); -} -bool KalmanFilter::predict(const Eigen::MatrixXd & u) -{ - return predict(u, A_, B_, Q_); -} - -bool KalmanFilter::update( - const Eigen::MatrixXd & y, const Eigen::MatrixXd & y_pred, const Eigen::MatrixXd & C, - const Eigen::MatrixXd & R) -{ - if ( - P_.cols() != C.cols() || R.rows() != R.cols() || R.rows() != C.rows() || - y.rows() != y_pred.rows() || y.rows() != C.rows()) { - return false; - } - const Eigen::MatrixXd PCT = P_ * C.transpose(); - const Eigen::MatrixXd K = PCT * ((R + C * PCT).inverse()); - - if (isnan(K.array()).any() || isinf(K.array()).any()) { - return false; - } - - x_ = x_ + K * (y - y_pred); - P_ = P_ - K * (C * P_); - return true; -} - -bool KalmanFilter::update( - const Eigen::MatrixXd & y, const Eigen::MatrixXd & C, const Eigen::MatrixXd & R) -{ - if (C.cols() != x_.rows()) { - return false; - } - const Eigen::MatrixXd y_pred = C * x_; - return update(y, y_pred, C, R); -} -bool KalmanFilter::update(const Eigen::MatrixXd & y) -{ - return update(y, C_, R_); -} -} // namespace autoware::kalman_filter diff --git a/common/autoware_kalman_filter/src/time_delay_kalman_filter.cpp b/common/autoware_kalman_filter/src/time_delay_kalman_filter.cpp deleted file mode 100644 index 4d1dd8f33b7a6..0000000000000 --- a/common/autoware_kalman_filter/src/time_delay_kalman_filter.cpp +++ /dev/null @@ -1,109 +0,0 @@ -// Copyright 2018-2019 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/kalman_filter/time_delay_kalman_filter.hpp" - -#include - -namespace autoware::kalman_filter -{ -TimeDelayKalmanFilter::TimeDelayKalmanFilter() -{ -} - -void TimeDelayKalmanFilter::init( - const Eigen::MatrixXd & x, const Eigen::MatrixXd & P0, const int max_delay_step) -{ - max_delay_step_ = max_delay_step; - dim_x_ = x.rows(); - dim_x_ex_ = dim_x_ * max_delay_step; - - x_ = Eigen::MatrixXd::Zero(dim_x_ex_, 1); - P_ = Eigen::MatrixXd::Zero(dim_x_ex_, dim_x_ex_); - - for (int i = 0; i < max_delay_step_; ++i) { - x_.block(i * dim_x_, 0, dim_x_, 1) = x; - P_.block(i * dim_x_, i * dim_x_, dim_x_, dim_x_) = P0; - } -} - -Eigen::MatrixXd TimeDelayKalmanFilter::getLatestX() const -{ - return x_.block(0, 0, dim_x_, 1); -} - -Eigen::MatrixXd TimeDelayKalmanFilter::getLatestP() const -{ - return P_.block(0, 0, dim_x_, dim_x_); -} - -bool TimeDelayKalmanFilter::predictWithDelay( - const Eigen::MatrixXd & x_next, const Eigen::MatrixXd & A, const Eigen::MatrixXd & Q) -{ - /* - * time delay model: - * - * [A 0 0] [P11 P12 P13] [Q 0 0] - * A = [I 0 0], P = [P21 P22 P23], Q = [0 0 0] - * [0 I 0] [P31 P32 P33] [0 0 0] - * - * covariance calculation in prediction : P = A * P * A' + Q - * - * [A*P11*A'*+Q A*P11 A*P12] - * P = [ P11*A' P11 P12] - * [ P21*A' P21 P22] - */ - - const int d_dim_x = dim_x_ex_ - dim_x_; - - /* slide states in the time direction */ - Eigen::MatrixXd x_tmp = Eigen::MatrixXd::Zero(dim_x_ex_, 1); - x_tmp.block(0, 0, dim_x_, 1) = x_next; - x_tmp.block(dim_x_, 0, d_dim_x, 1) = x_.block(0, 0, d_dim_x, 1); - x_ = x_tmp; - - /* update P with delayed measurement A matrix structure */ - Eigen::MatrixXd P_tmp = Eigen::MatrixXd::Zero(dim_x_ex_, dim_x_ex_); - P_tmp.block(0, 0, dim_x_, dim_x_) = A * P_.block(0, 0, dim_x_, dim_x_) * A.transpose() + Q; - P_tmp.block(0, dim_x_, dim_x_, d_dim_x) = A * P_.block(0, 0, dim_x_, d_dim_x); - P_tmp.block(dim_x_, 0, d_dim_x, dim_x_) = P_.block(0, 0, d_dim_x, dim_x_) * A.transpose(); - P_tmp.block(dim_x_, dim_x_, d_dim_x, d_dim_x) = P_.block(0, 0, d_dim_x, d_dim_x); - P_ = P_tmp; - - return true; -} - -bool TimeDelayKalmanFilter::updateWithDelay( - const Eigen::MatrixXd & y, const Eigen::MatrixXd & C, const Eigen::MatrixXd & R, - const int delay_step) -{ - if (delay_step >= max_delay_step_) { - std::cerr << "delay step is larger than max_delay_step. ignore update." << std::endl; - return false; - } - - const int dim_y = y.rows(); - - /* set measurement matrix */ - Eigen::MatrixXd C_ex = Eigen::MatrixXd::Zero(dim_y, dim_x_ex_); - C_ex.block(0, dim_x_ * delay_step, dim_y, dim_x_) = C; - - /* update */ - if (!update(y, C_ex, R)) { - return false; - } - - return true; -} -} // namespace autoware::kalman_filter diff --git a/common/autoware_kalman_filter/test/test_kalman_filter.cpp b/common/autoware_kalman_filter/test/test_kalman_filter.cpp deleted file mode 100644 index 34e23ef9d06e2..0000000000000 --- a/common/autoware_kalman_filter/test/test_kalman_filter.cpp +++ /dev/null @@ -1,96 +0,0 @@ -// Copyright 2023 The Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/kalman_filter/kalman_filter.hpp" - -#include - -using autoware::kalman_filter::KalmanFilter; - -TEST(kalman_filter, kf) -{ - KalmanFilter kf_; - - Eigen::MatrixXd x_t(2, 1); - x_t << 1, 2; - - Eigen::MatrixXd P_t(2, 2); - P_t << 1, 0, 0, 1; - - Eigen::MatrixXd Q_t(2, 2); - Q_t << 0.01, 0, 0, 0.01; - - Eigen::MatrixXd R_t(2, 2); - R_t << 0.09, 0, 0, 0.09; - - Eigen::MatrixXd C_t(2, 2); - C_t << 1, 0, 0, 1; - - Eigen::MatrixXd A_t(2, 2); - A_t << 1, 0, 0, 1; - - Eigen::MatrixXd B_t(2, 2); - B_t << 1, 0, 0, 1; - - // Initialize the filter and check if initialization was successful - EXPECT_TRUE(kf_.init(x_t, A_t, B_t, C_t, Q_t, R_t, P_t)); - - // Perform prediction - Eigen::MatrixXd u_t(2, 1); - u_t << 0.1, 0.1; - EXPECT_TRUE(kf_.predict(u_t)); - - // Check the updated state and covariance matrix - Eigen::MatrixXd x_predict_expected = A_t * x_t + B_t * u_t; - Eigen::MatrixXd P_predict_expected = A_t * P_t * A_t.transpose() + Q_t; - - Eigen::MatrixXd x_predict; - kf_.getX(x_predict); - Eigen::MatrixXd P_predict; - kf_.getP(P_predict); - - EXPECT_NEAR(x_predict(0, 0), x_predict_expected(0, 0), 1e-5); - EXPECT_NEAR(x_predict(1, 0), x_predict_expected(1, 0), 1e-5); - EXPECT_NEAR(P_predict(0, 0), P_predict_expected(0, 0), 1e-5); - EXPECT_NEAR(P_predict(1, 1), P_predict_expected(1, 1), 1e-5); - - // Perform update - Eigen::MatrixXd y_t(2, 1); - y_t << 1.05, 2.05; - EXPECT_TRUE(kf_.update(y_t)); - - // Check the updated state and covariance matrix - const Eigen::MatrixXd PCT_t = P_predict_expected * C_t.transpose(); - const Eigen::MatrixXd K_t = PCT_t * ((R_t + C_t * PCT_t).inverse()); - const Eigen::MatrixXd y_pred = C_t * x_predict_expected; - Eigen::MatrixXd x_update_expected = x_predict_expected + K_t * (y_t - y_pred); - Eigen::MatrixXd P_update_expected = P_predict_expected - K_t * (C_t * P_predict_expected); - - Eigen::MatrixXd x_update; - kf_.getX(x_update); - Eigen::MatrixXd P_update; - kf_.getP(P_update); - - EXPECT_NEAR(x_update(0, 0), x_update_expected(0, 0), 1e-5); - EXPECT_NEAR(x_update(1, 0), x_update_expected(1, 0), 1e-5); - EXPECT_NEAR(P_update(0, 0), P_update_expected(0, 0), 1e-5); - EXPECT_NEAR(P_update(1, 1), P_update_expected(1, 1), 1e-5); -} - -int main(int argc, char * argv[]) -{ - testing::InitGoogleTest(&argc, argv); - bool result = RUN_ALL_TESTS(); - return result; -} diff --git a/common/autoware_kalman_filter/test/test_time_delay_kalman_filter.cpp b/common/autoware_kalman_filter/test/test_time_delay_kalman_filter.cpp deleted file mode 100644 index 50c22fae123bc..0000000000000 --- a/common/autoware_kalman_filter/test/test_time_delay_kalman_filter.cpp +++ /dev/null @@ -1,123 +0,0 @@ -// Copyright 2023 The Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/kalman_filter/time_delay_kalman_filter.hpp" - -#include - -using autoware::kalman_filter::TimeDelayKalmanFilter; - -TEST(time_delay_kalman_filter, td_kf) -{ - TimeDelayKalmanFilter td_kf_; - - Eigen::MatrixXd x_t(3, 1); - x_t << 1.0, 2.0, 3.0; - Eigen::MatrixXd P_t(3, 3); - P_t << 0.1, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, 0.3; - const int max_delay_step = 5; - const int dim_x = x_t.rows(); - const int dim_x_ex = dim_x * max_delay_step; - // Initialize the filter - td_kf_.init(x_t, P_t, max_delay_step); - - // Check if initialization was successful - Eigen::MatrixXd x_init = td_kf_.getLatestX(); - Eigen::MatrixXd P_init = td_kf_.getLatestP(); - Eigen::MatrixXd x_ex_t = Eigen::MatrixXd::Zero(dim_x_ex, 1); - Eigen::MatrixXd P_ex_t = Eigen::MatrixXd::Zero(dim_x_ex, dim_x_ex); - for (int i = 0; i < max_delay_step; ++i) { - x_ex_t.block(i * dim_x, 0, dim_x, 1) = x_t; - P_ex_t.block(i * dim_x, i * dim_x, dim_x, dim_x) = P_t; - } - - EXPECT_EQ(x_init.rows(), 3); - EXPECT_EQ(x_init.cols(), 1); - EXPECT_EQ(P_init.rows(), 3); - EXPECT_EQ(P_init.cols(), 3); - EXPECT_NEAR(x_init(0, 0), x_t(0, 0), 1e-5); - EXPECT_NEAR(x_init(1, 0), x_t(1, 0), 1e-5); - EXPECT_NEAR(x_init(2, 0), x_t(2, 0), 1e-5); - EXPECT_NEAR(P_init(0, 0), P_t(0, 0), 1e-5); - EXPECT_NEAR(P_init(1, 1), P_t(1, 1), 1e-5); - EXPECT_NEAR(P_init(2, 2), P_t(2, 2), 1e-5); - - // Define prediction parameters - Eigen::MatrixXd A_t(3, 3); - A_t << 2.0, 0.0, 0.0, 0.0, 2.0, 0.0, 0.0, 0.0, 2.0; - Eigen::MatrixXd Q_t(3, 3); - Q_t << 0.01, 0.0, 0.0, 0.0, 0.02, 0.0, 0.0, 0.0, 0.03; - Eigen::MatrixXd x_next(3, 1); - x_next << 2.0, 4.0, 6.0; - - // Perform prediction - EXPECT_TRUE(td_kf_.predictWithDelay(x_next, A_t, Q_t)); - - // Check the prediction state and covariance matrix - Eigen::MatrixXd x_predict = td_kf_.getLatestX(); - Eigen::MatrixXd P_predict = td_kf_.getLatestP(); - Eigen::MatrixXd x_tmp = Eigen::MatrixXd::Zero(dim_x_ex, 1); - x_tmp.block(0, 0, dim_x, 1) = A_t * x_t; - x_tmp.block(dim_x, 0, dim_x_ex - dim_x, 1) = x_ex_t.block(0, 0, dim_x_ex - dim_x, 1); - x_ex_t = x_tmp; - Eigen::MatrixXd x_predict_expected = x_ex_t.block(0, 0, dim_x, 1); - Eigen::MatrixXd P_tmp = Eigen::MatrixXd::Zero(dim_x_ex, dim_x_ex); - P_tmp.block(0, 0, dim_x, dim_x) = A_t * P_ex_t.block(0, 0, dim_x, dim_x) * A_t.transpose() + Q_t; - P_tmp.block(0, dim_x, dim_x, dim_x_ex - dim_x) = - A_t * P_ex_t.block(0, 0, dim_x, dim_x_ex - dim_x); - P_tmp.block(dim_x, 0, dim_x_ex - dim_x, dim_x) = - P_ex_t.block(0, 0, dim_x_ex - dim_x, dim_x) * A_t.transpose(); - P_tmp.block(dim_x, dim_x, dim_x_ex - dim_x, dim_x_ex - dim_x) = - P_ex_t.block(0, 0, dim_x_ex - dim_x, dim_x_ex - dim_x); - P_ex_t = P_tmp; - Eigen::MatrixXd P_predict_expected = P_ex_t.block(0, 0, dim_x, dim_x); - EXPECT_NEAR(x_predict(0, 0), x_predict_expected(0, 0), 1e-5); - EXPECT_NEAR(x_predict(1, 0), x_predict_expected(1, 0), 1e-5); - EXPECT_NEAR(x_predict(2, 0), x_predict_expected(2, 0), 1e-5); - EXPECT_NEAR(P_predict(0, 0), P_predict_expected(0, 0), 1e-5); - EXPECT_NEAR(P_predict(1, 1), P_predict_expected(1, 1), 1e-5); - EXPECT_NEAR(P_predict(2, 2), P_predict_expected(2, 2), 1e-5); - - // Define update parameters - Eigen::MatrixXd C_t(3, 3); - C_t << 0.5, 0.0, 0.0, 0.0, 0.5, 0.0, 0.0, 0.0, 0.5; - Eigen::MatrixXd R_t(3, 3); - R_t << 0.001, 0.0, 0.0, 0.0, 0.002, 0.0, 0.0, 0.0, 0.003; - Eigen::MatrixXd y_t(3, 1); - y_t << 1.05, 2.05, 3.05; - const int delay_step = 2; // Choose an appropriate delay step - const int dim_y = y_t.rows(); - - // Perform update - EXPECT_TRUE(td_kf_.updateWithDelay(y_t, C_t, R_t, delay_step)); - - // Check the updated state and covariance matrix - Eigen::MatrixXd x_update = td_kf_.getLatestX(); - Eigen::MatrixXd P_update = td_kf_.getLatestP(); - - Eigen::MatrixXd C_ex_t = Eigen::MatrixXd::Zero(dim_y, dim_x_ex); - const Eigen::MatrixXd PCT_t = P_ex_t * C_ex_t.transpose(); - const Eigen::MatrixXd K_t = PCT_t * ((R_t + C_ex_t * PCT_t).inverse()); - const Eigen::MatrixXd y_pred = C_ex_t * x_ex_t; - x_ex_t = x_ex_t + K_t * (y_t - y_pred); - P_ex_t = P_ex_t - K_t * (C_ex_t * P_ex_t); - Eigen::MatrixXd x_update_expected = x_ex_t.block(0, 0, dim_x, 1); - Eigen::MatrixXd P_update_expected = P_ex_t.block(0, 0, dim_x, dim_x); - EXPECT_NEAR(x_update(0, 0), x_update_expected(0, 0), 1e-5); - EXPECT_NEAR(x_update(1, 0), x_update_expected(1, 0), 1e-5); - EXPECT_NEAR(x_update(2, 0), x_update_expected(2, 0), 1e-5); - EXPECT_NEAR(P_update(0, 0), P_update_expected(0, 0), 1e-5); - EXPECT_NEAR(P_update(1, 1), P_update_expected(1, 1), 1e-5); - EXPECT_NEAR(P_update(2, 2), P_update_expected(2, 2), 1e-5); -} From 7f496888b6ef10eb5ee9e9897505220d92415164 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Wed, 15 Jan 2025 11:18:06 +0900 Subject: [PATCH 204/334] feat(autoware_costmap_generator): tier4_debug_msgs changed to autoware_internal-debug_msgs in autoware_costmap_generator (#9901) feat: tier4_debug_msgs changed to autoware_internal-debug_msgs in files planning/autoware_costmap_generator Signed-off-by: vish0012 --- .../autoware/costmap_generator/costmap_generator.hpp | 5 +++-- .../autoware_costmap_generator/src/costmap_generator.cpp | 7 ++++--- 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/planning/autoware_costmap_generator/include/autoware/costmap_generator/costmap_generator.hpp b/planning/autoware_costmap_generator/include/autoware/costmap_generator/costmap_generator.hpp index 4fed5bcb6cff3..b6749117a6177 100644 --- a/planning/autoware_costmap_generator/include/autoware/costmap_generator/costmap_generator.hpp +++ b/planning/autoware_costmap_generator/include/autoware/costmap_generator/costmap_generator.hpp @@ -58,10 +58,10 @@ #include #include +#include #include #include #include -#include #include #include @@ -99,7 +99,8 @@ class CostmapGenerator : public rclcpp::Node rclcpp::Publisher::SharedPtr pub_costmap_; rclcpp::Publisher::SharedPtr pub_occupancy_grid_; rclcpp::Publisher::SharedPtr pub_processing_time_; - rclcpp::Publisher::SharedPtr pub_processing_time_ms_; + rclcpp::Publisher::SharedPtr + pub_processing_time_ms_; rclcpp::Subscription::SharedPtr sub_lanelet_bin_map_; autoware::universe_utils::InterProcessPollingSubscriber diff --git a/planning/autoware_costmap_generator/src/costmap_generator.cpp b/planning/autoware_costmap_generator/src/costmap_generator.cpp index 081a6ead91cda..70b8051bcdc12 100644 --- a/planning/autoware_costmap_generator/src/costmap_generator.cpp +++ b/planning/autoware_costmap_generator/src/costmap_generator.cpp @@ -176,7 +176,8 @@ CostmapGenerator::CostmapGenerator(const rclcpp::NodeOptions & node_options) create_publisher("processing_time", 1); time_keeper_ = std::make_shared(pub_processing_time_); pub_processing_time_ms_ = - this->create_publisher("~/debug/processing_time_ms", 1); + this->create_publisher( + "~/debug/processing_time_ms", 1); // Timer const auto period_ns = rclcpp::Rate(param_->update_rate).period(); @@ -269,7 +270,7 @@ void CostmapGenerator::onTimer() if (!isActive()) { // Publish ProcessingTime - tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg; processing_time_msg.stamp = get_clock()->now(); processing_time_msg.data = stop_watch.toc(); pub_processing_time_ms_->publish(processing_time_msg); @@ -485,7 +486,7 @@ void CostmapGenerator::publishCostmap( pub_costmap_->publish(*out_gridmap_msg); // Publish ProcessingTime - tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg; processing_time_msg.stamp = get_clock()->now(); processing_time_msg.data = stop_watch.toc(); pub_processing_time_ms_->publish(processing_time_msg); From 9a2ebcc9f1f55f3aa28ad46a6d0b825f52e45cea Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Wed, 15 Jan 2025 11:21:18 +0900 Subject: [PATCH 205/334] feat(autoware_surround_obstacle_checker): tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_surround_obstacle_checker (#9915) feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files planning/autoware_surround_obstacle_checker Signed-off-by: vish0012 --- planning/autoware_surround_obstacle_checker/src/node.cpp | 6 +++--- planning/autoware_surround_obstacle_checker/src/node.hpp | 5 +++-- 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/planning/autoware_surround_obstacle_checker/src/node.cpp b/planning/autoware_surround_obstacle_checker/src/node.cpp index 0adca312ca733..b3881a8f4fbd9 100644 --- a/planning/autoware_surround_obstacle_checker/src/node.cpp +++ b/planning/autoware_surround_obstacle_checker/src/node.cpp @@ -81,8 +81,8 @@ SurroundObstacleCheckerNode::SurroundObstacleCheckerNode(const rclcpp::NodeOptio "~/output/velocity_limit_clear_command", rclcpp::QoS{1}.transient_local()); pub_velocity_limit_ = this->create_publisher( "~/output/max_velocity", rclcpp::QoS{1}.transient_local()); - pub_processing_time_ = - this->create_publisher("~/debug/processing_time_ms", 1); + pub_processing_time_ = this->create_publisher( + "~/debug/processing_time_ms", 1); using std::chrono_literals::operator""ms; timer_ = rclcpp::create_timer( @@ -231,7 +231,7 @@ void SurroundObstacleCheckerNode::onTimer() debug_ptr_->pushPose(odometry_ptr_->pose.pose, PoseType::NoStart); } - tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg; processing_time_msg.stamp = get_clock()->now(); processing_time_msg.data = stop_watch.toc(); pub_processing_time_->publish(processing_time_msg); diff --git a/planning/autoware_surround_obstacle_checker/src/node.hpp b/planning/autoware_surround_obstacle_checker/src/node.hpp index f84ad3a8f5987..b6d6bffefed1a 100644 --- a/planning/autoware_surround_obstacle_checker/src/node.hpp +++ b/planning/autoware_surround_obstacle_checker/src/node.hpp @@ -24,12 +24,12 @@ #include #include +#include #include #include #include #include #include -#include #include #include #include @@ -106,7 +106,8 @@ class SurroundObstacleCheckerNode : public rclcpp::Node this, "~/input/objects"}; rclcpp::Publisher::SharedPtr pub_clear_velocity_limit_; rclcpp::Publisher::SharedPtr pub_velocity_limit_; - rclcpp::Publisher::SharedPtr pub_processing_time_; + rclcpp::Publisher::SharedPtr + pub_processing_time_; // parameter callback result OnSetParametersCallbackHandle::SharedPtr set_param_res_; From 2028af955d261cc3dfd4836f7501b60a5e030a59 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Wed, 15 Jan 2025 11:23:07 +0900 Subject: [PATCH 206/334] feat(autoware_freespace_planner): tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_freespace_planner (#9903) feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in flies planning/autoware_freespace_planner Signed-off-by: vish0012 --- .../autoware/freespace_planner/freespace_planner_node.hpp | 5 +++-- .../autoware_freespace_planner/freespace_planner_node.cpp | 6 +++--- 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/planning/autoware_freespace_planner/include/autoware/freespace_planner/freespace_planner_node.hpp b/planning/autoware_freespace_planner/include/autoware/freespace_planner/freespace_planner_node.hpp index 1f5a52ca040a0..bd431372b70dc 100644 --- a/planning/autoware_freespace_planner/include/autoware/freespace_planner/freespace_planner_node.hpp +++ b/planning/autoware_freespace_planner/include/autoware/freespace_planner/freespace_planner_node.hpp @@ -39,13 +39,13 @@ #include #include +#include #include #include #include #include #include #include -#include #include #ifdef ROS_DISTRO_GALACTIC @@ -112,7 +112,8 @@ class FreespacePlannerNode : public rclcpp::Node rclcpp::Publisher::SharedPtr debug_pose_array_pub_; rclcpp::Publisher::SharedPtr debug_partial_pose_array_pub_; rclcpp::Publisher::SharedPtr parking_state_pub_; - rclcpp::Publisher::SharedPtr processing_time_pub_; + rclcpp::Publisher::SharedPtr + processing_time_pub_; rclcpp::Subscription::SharedPtr route_sub_; diff --git a/planning/autoware_freespace_planner/src/autoware_freespace_planner/freespace_planner_node.cpp b/planning/autoware_freespace_planner/src/autoware_freespace_planner/freespace_planner_node.cpp index a937114e653c6..2749408bedb7b 100644 --- a/planning/autoware_freespace_planner/src/autoware_freespace_planner/freespace_planner_node.cpp +++ b/planning/autoware_freespace_planner/src/autoware_freespace_planner/freespace_planner_node.cpp @@ -95,8 +95,8 @@ FreespacePlannerNode::FreespacePlannerNode(const rclcpp::NodeOptions & node_opti debug_pose_array_pub_ = create_publisher("~/debug/pose_array", qos); debug_partial_pose_array_pub_ = create_publisher("~/debug/partial_pose_array", qos); parking_state_pub_ = create_publisher("is_completed", qos); - processing_time_pub_ = - create_publisher("~/debug/processing_time_ms", 1); + processing_time_pub_ = create_publisher( + "~/debug/processing_time_ms", 1); } // TF @@ -362,7 +362,7 @@ void FreespacePlannerNode::onTimer() is_new_parking_cycle_ = false; // Publish ProcessingTime - tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg; processing_time_msg.stamp = get_clock()->now(); processing_time_msg.data = stop_watch.toc(); processing_time_pub_->publish(processing_time_msg); From e96b361fc3d6f49bc4b097ca402ffbd3b590bb89 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Wed, 15 Jan 2025 11:24:36 +0900 Subject: [PATCH 207/334] feat(autoware_scenario_selector): tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_scenario_selector (#9914) feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files planning/autoware_scenario_selector Signed-off-by: vish0012 --- .../include/autoware/scenario_selector/node.hpp | 5 +++-- planning/autoware_scenario_selector/src/node.cpp | 6 +++--- 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/planning/autoware_scenario_selector/include/autoware/scenario_selector/node.hpp b/planning/autoware_scenario_selector/include/autoware/scenario_selector/node.hpp index 244876ee2cb22..7e215fcfef8dd 100644 --- a/planning/autoware_scenario_selector/include/autoware/scenario_selector/node.hpp +++ b/planning/autoware_scenario_selector/include/autoware/scenario_selector/node.hpp @@ -19,13 +19,13 @@ #include #include +#include #include #include #include #include #include #include -#include #include #include @@ -97,7 +97,8 @@ class ScenarioSelectorNode : public rclcpp::Node rclcpp::Subscription::SharedPtr sub_parking_trajectory_; rclcpp::Publisher::SharedPtr pub_trajectory_; rclcpp::Publisher::SharedPtr pub_scenario_; - rclcpp::Publisher::SharedPtr pub_processing_time_; + rclcpp::Publisher::SharedPtr + pub_processing_time_; // polling subscribers universe_utils::InterProcessPollingSubscriber< diff --git a/planning/autoware_scenario_selector/src/node.cpp b/planning/autoware_scenario_selector/src/node.cpp index defbde4f6aabc..91e86bfea6dba 100644 --- a/planning/autoware_scenario_selector/src/node.cpp +++ b/planning/autoware_scenario_selector/src/node.cpp @@ -390,7 +390,7 @@ void ScenarioSelectorNode::onTimer() pub_scenario_->publish(scenario); // Publish ProcessingTime - tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg; processing_time_msg.stamp = get_clock()->now(); processing_time_msg.data = stop_watch.toc(); pub_processing_time_->publish(processing_time_msg); @@ -490,8 +490,8 @@ ScenarioSelectorNode::ScenarioSelectorNode(const rclcpp::NodeOptions & node_opti this, get_clock(), period_ns, std::bind(&ScenarioSelectorNode::onTimer, this)); published_time_publisher_ = std::make_unique(this); - pub_processing_time_ = - this->create_publisher("~/debug/processing_time_ms", 1); + pub_processing_time_ = this->create_publisher( + "~/debug/processing_time_ms", 1); } } // namespace autoware::scenario_selector From 9b8b3fc3280a678ea0205009339c587b5febf096 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Wed, 15 Jan 2025 15:44:22 +0900 Subject: [PATCH 208/334] =?UTF-8?q?feat(autoware=5Foccupancy=5Fgrid=5Fmap?= =?UTF-8?q?=5Foutlier=5Ffilter):=20tier4=5Fdebug=5Fmsgs=20changed=20to=20a?= =?UTF-8?q?utoware=5Finternal=5Fdebug=5Fmsgs=20in=20fil=E2=80=A6=20(#9894)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files perception/autoware_occupancy_grid_map_outlier_filter Signed-off-by: vish0012 Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> --- .../src/occupancy_grid_map_outlier_filter_node.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp b/perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp index eb52b903b90ca..094825056e62c 100644 --- a/perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp +++ b/perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp @@ -420,9 +420,9 @@ void OccupancyGridMapOutlierFilterComponent::onOccupancyGridMapAndPointCloud2( if (debug_publisher_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); } } From b7ce209a911eac03593240b8b42676b688991626 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Wed, 15 Jan 2025 15:47:29 +0900 Subject: [PATCH 209/334] =?UTF-8?q?feat(autoware=5Flidar=5Fapollo=5Finstan?= =?UTF-8?q?ce=5Fsegmentation):=20tier4=5Fdebug=5Fmsgs=20to=20autoware=5Fin?= =?UTF-8?q?ternal=5Fdebug=5Fmsgs=20in=20files=20perce=E2=80=A6=20(#9876)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs to autoware_internal_debug_msgs in files perception/autoware_lidar_apollo_instance_segmentation Signed-off-by: vish0012 Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> --- .../CMakeLists.txt | 4 ++-- .../autoware_lidar_apollo_instance_segmentation/package.xml | 2 +- .../autoware_lidar_apollo_instance_segmentation/src/node.cpp | 4 ++-- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/perception/autoware_lidar_apollo_instance_segmentation/CMakeLists.txt b/perception/autoware_lidar_apollo_instance_segmentation/CMakeLists.txt index 16ab7ecccae60..0555cedc235d9 100644 --- a/perception/autoware_lidar_apollo_instance_segmentation/CMakeLists.txt +++ b/perception/autoware_lidar_apollo_instance_segmentation/CMakeLists.txt @@ -9,7 +9,7 @@ find_package(rclcpp REQUIRED) find_package(rclcpp_components REQUIRED) find_package(tf2_eigen REQUIRED) find_package(autoware_universe_utils REQUIRED) -find_package(tier4_debug_msgs REQUIRED) +find_package(autoware_internal_debug_msgs REQUIRED) find_package(tier4_perception_msgs REQUIRED) find_package(autoware_tensorrt_common) @@ -50,7 +50,7 @@ target_link_libraries(${PROJECT_NAME} rclcpp_components::component tf2_eigen::tf2_eigen ${autoware_tensorrt_common_TARGETS} - ${tier4_debug_msgs_TARGETS} + ${autoware_internal_debug_msgs_TARGETS} ${tier4_perception_msgs_TARGETS} ) diff --git a/perception/autoware_lidar_apollo_instance_segmentation/package.xml b/perception/autoware_lidar_apollo_instance_segmentation/package.xml index 8a3d5a7ea6f76..8ff7ce77d943d 100755 --- a/perception/autoware_lidar_apollo_instance_segmentation/package.xml +++ b/perception/autoware_lidar_apollo_instance_segmentation/package.xml @@ -14,6 +14,7 @@ ament_cmake autoware_cuda_utils + autoware_internal_debug_msgs autoware_perception_msgs autoware_tensorrt_common autoware_universe_utils @@ -22,7 +23,6 @@ rclcpp rclcpp_components tf2_eigen - tier4_debug_msgs tier4_perception_msgs ament_lint_auto diff --git a/perception/autoware_lidar_apollo_instance_segmentation/src/node.cpp b/perception/autoware_lidar_apollo_instance_segmentation/src/node.cpp index 9a3e13b81120f..c535fc6762e1f 100644 --- a/perception/autoware_lidar_apollo_instance_segmentation/src/node.cpp +++ b/perception/autoware_lidar_apollo_instance_segmentation/src/node.cpp @@ -62,9 +62,9 @@ void LidarInstanceSegmentationNode::pointCloudCallback( if (debug_publisher_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); } } From acaa40c95a109e21687fe7f2e7f4b37f2ebb1d6b Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Wed, 15 Jan 2025 15:50:03 +0900 Subject: [PATCH 210/334] =?UTF-8?q?feat(autoware=5Fground=5Fsegmentation):?= =?UTF-8?q?=20tier4=5Fdebug=5Fmsgs=20changed=20to=20autoware=5Finternal=5F?= =?UTF-8?q?debug=5Fmsgs=20in=20fil=E2=80=A6=20(#9878)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files perception/autoware_ground_segmentation Signed-off-by: vish0012 --- .../src/scan_ground_filter/node.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/autoware_ground_segmentation/src/scan_ground_filter/node.cpp b/perception/autoware_ground_segmentation/src/scan_ground_filter/node.cpp index 74b4edbe595ea..8fda0c1395caf 100644 --- a/perception/autoware_ground_segmentation/src/scan_ground_filter/node.cpp +++ b/perception/autoware_ground_segmentation/src/scan_ground_filter/node.cpp @@ -369,9 +369,9 @@ void ScanGroundFilterComponent::faster_filter( if (debug_publisher_ptr_ && stop_watch_ptr_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_ptr_->publish( + debug_publisher_ptr_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_ptr_->publish( + debug_publisher_ptr_->publish( "debug/processing_time_ms", processing_time_ms); } } From b65e042ebd1df00a09d6a47648dfb07df3e0f68a Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Wed, 15 Jan 2025 15:50:22 +0900 Subject: [PATCH 211/334] feat(autoware_image_diagnostics): tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_image_diagnostics (#9918) feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files sensing/autoware_image_diagnostics Signed-off-by: vish0012 --- sensing/autoware_image_diagnostics/README.md | 14 +++++++------- sensing/autoware_image_diagnostics/package.xml | 2 +- .../src/image_diagnostics_node.cpp | 4 ++-- .../src/image_diagnostics_node.hpp | 11 ++++++----- 4 files changed, 16 insertions(+), 15 deletions(-) diff --git a/sensing/autoware_image_diagnostics/README.md b/sensing/autoware_image_diagnostics/README.md index 03858088564b3..42fcbdc8dc612 100644 --- a/sensing/autoware_image_diagnostics/README.md +++ b/sensing/autoware_image_diagnostics/README.md @@ -28,13 +28,13 @@ After all image's blocks state are evaluated, the whole image status is summariz ### Output -| Name | Type | Description | -| ----------------------------------- | --------------------------------------- | ------------------------------------- | -| `image_diag/debug/gray_image` | `sensor_msgs::msg::Image` | gray image | -| `image_diag/debug/dft_image` | `sensor_msgs::msg::Image` | discrete Fourier transformation image | -| `image_diag/debug/diag_block_image` | `sensor_msgs::msg::Image` | each block state colorization | -| `image_diag/image_state_diag` | `tier4_debug_msgs::msg::Int32Stamped` | image diagnostics status value | -| `/diagnostics` | `diagnostic_msgs::msg::DiagnosticArray` | diagnostics | +| Name | Type | Description | +| ----------------------------------- | ------------------------------------------------- | ------------------------------------- | +| `image_diag/debug/gray_image` | `sensor_msgs::msg::Image` | gray image | +| `image_diag/debug/dft_image` | `sensor_msgs::msg::Image` | discrete Fourier transformation image | +| `image_diag/debug/diag_block_image` | `sensor_msgs::msg::Image` | each block state colorization | +| `image_diag/image_state_diag` | `autoware_internal_debug_msgs::msg::Int32Stamped` | image diagnostics status value | +| `/diagnostics` | `diagnostic_msgs::msg::DiagnosticArray` | diagnostics | ## Parameters diff --git a/sensing/autoware_image_diagnostics/package.xml b/sensing/autoware_image_diagnostics/package.xml index 2e4556de2b92b..3140b87e1f1b9 100644 --- a/sensing/autoware_image_diagnostics/package.xml +++ b/sensing/autoware_image_diagnostics/package.xml @@ -12,6 +12,7 @@ ament_cmake_auto + autoware_internal_debug_msgs autoware_universe_utils cv_bridge diagnostic_updater @@ -19,7 +20,6 @@ rclcpp rclcpp_components sensor_msgs - tier4_debug_msgs ament_lint_auto autoware_lint_common diff --git a/sensing/autoware_image_diagnostics/src/image_diagnostics_node.cpp b/sensing/autoware_image_diagnostics/src/image_diagnostics_node.cpp index 1625cba5b72aa..57e53aee46328 100644 --- a/sensing/autoware_image_diagnostics/src/image_diagnostics_node.cpp +++ b/sensing/autoware_image_diagnostics/src/image_diagnostics_node.cpp @@ -33,7 +33,7 @@ ImageDiagNode::ImageDiagNode(const rclcpp::NodeOptions & node_options) dft_image_pub_ = image_transport::create_publisher(this, "image_diag/debug/dft_image"); gray_image_pub_ = image_transport::create_publisher(this, "image_diag/debug/gray_image"); - image_state_pub_ = create_publisher( + image_state_pub_ = create_publisher( "image_diag/image_state_diag", rclcpp::SensorDataQoS()); updater_.setHardwareID("Image_Diagnostics"); @@ -225,7 +225,7 @@ void ImageDiagNode::ImageChecker(const sensor_msgs::msg::Image::ConstSharedPtr i } else { params_.diagnostic_status = 0; } - tier4_debug_msgs::msg::Int32Stamped image_state_out; + autoware_internal_debug_msgs::msg::Int32Stamped image_state_out; image_state_out.data = params_.diagnostic_status; image_state_pub_->publish(image_state_out); diff --git a/sensing/autoware_image_diagnostics/src/image_diagnostics_node.hpp b/sensing/autoware_image_diagnostics/src/image_diagnostics_node.hpp index 325624062b90b..9383da33160f9 100644 --- a/sensing/autoware_image_diagnostics/src/image_diagnostics_node.hpp +++ b/sensing/autoware_image_diagnostics/src/image_diagnostics_node.hpp @@ -21,10 +21,10 @@ #include #include +#include +#include +#include #include -#include -#include -#include #if __has_include() #include @@ -95,8 +95,9 @@ class ImageDiagNode : public rclcpp::Node image_transport::Publisher block_diag_image_pub_; image_transport::Publisher dft_image_pub_; image_transport::Publisher gray_image_pub_; - rclcpp::Publisher::SharedPtr average_pub_; - rclcpp::Publisher::SharedPtr image_state_pub_; + rclcpp::Publisher::SharedPtr + average_pub_; + rclcpp::Publisher::SharedPtr image_state_pub_; }; } // namespace autoware::image_diagnostics From 221a7bc0eb333f27638d5bdc5a9d7ecc4fd79be0 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Wed, 15 Jan 2025 15:50:56 +0900 Subject: [PATCH 212/334] =?UTF-8?q?feat(autoware=5Fcompare=5Fmap=5Fsegment?= =?UTF-8?q?ation):=20tier4=5Fdebug=5Fmsgs=20changed=20to=20autoware=5Finte?= =?UTF-8?q?rnal=5Fdebug=5Fmsgs=20in=20fil=E2=80=A6=20(#9869)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files perception/autoware_compare_map_segmentation Signed-off-by: vish0012 Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> --- .../src/distance_based_compare_map_filter/node.cpp | 4 ++-- .../src/voxel_based_approximate_compare_map_filter/node.cpp | 4 ++-- .../src/voxel_based_compare_map_filter/node.cpp | 4 ++-- .../src/voxel_distance_based_compare_map_filter/node.cpp | 4 ++-- 4 files changed, 8 insertions(+), 8 deletions(-) diff --git a/perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.cpp b/perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.cpp index ae07d54ad53d6..ac759504de557 100644 --- a/perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.cpp +++ b/perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.cpp @@ -173,9 +173,9 @@ void DistanceBasedCompareMapFilterComponent::filter( if (debug_publisher_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); } } diff --git a/perception/autoware_compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.cpp b/perception/autoware_compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.cpp index 9f325b36676be..5794cfe37a45b 100644 --- a/perception/autoware_compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.cpp +++ b/perception/autoware_compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.cpp @@ -141,9 +141,9 @@ void VoxelBasedApproximateCompareMapFilterComponent::filter( if (debug_publisher_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); } } diff --git a/perception/autoware_compare_map_segmentation/src/voxel_based_compare_map_filter/node.cpp b/perception/autoware_compare_map_segmentation/src/voxel_based_compare_map_filter/node.cpp index a31d5ec5dd6d6..db5e46a0eff5a 100644 --- a/perception/autoware_compare_map_segmentation/src/voxel_based_compare_map_filter/node.cpp +++ b/perception/autoware_compare_map_segmentation/src/voxel_based_compare_map_filter/node.cpp @@ -100,9 +100,9 @@ void VoxelBasedCompareMapFilterComponent::filter( if (debug_publisher_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); } } diff --git a/perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.cpp b/perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.cpp index d0bcf381cd62f..775a931ac4c4c 100644 --- a/perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.cpp +++ b/perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.cpp @@ -173,9 +173,9 @@ void VoxelDistanceBasedCompareMapFilterComponent::filter( if (debug_publisher_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); } } From cee6ef912154312c3a4e6eff3ee04013cb9d7175 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Wed, 15 Jan 2025 15:54:14 +0900 Subject: [PATCH 213/334] feat(autoware_probabilistic_occupancy_grid_map): tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_probabilistic_occupancy_grid_map (#9895) feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files perception/autoware_probabilistic_occupancy_grid_map Signed-off-by: vish0012 Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> --- .../src/fusion/synchronized_grid_map_fusion_node.cpp | 6 +++--- .../pointcloud_based_occupancy_grid_map_node.cpp | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/perception/autoware_probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.cpp b/perception/autoware_probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.cpp index 880dfda03c495..7cde04ca9614b 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.cpp +++ b/perception/autoware_probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.cpp @@ -332,11 +332,11 @@ void GridMapFusionNode::publish() std::chrono::duration( std::chrono::nanoseconds((this->get_clock()->now() - latest_stamp).nanoseconds())) .count(); - debug_publisher_ptr_->publish( + debug_publisher_ptr_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_ptr_->publish( + debug_publisher_ptr_->publish( "debug/processing_time_ms", processing_time_ms); - debug_publisher_ptr_->publish( + debug_publisher_ptr_->publish( "debug/pipeline_latency_ms", pipeline_latency_ms); } } diff --git a/perception/autoware_probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp b/perception/autoware_probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp index 4d442ad2c33db..ff836a1ddf760 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp +++ b/perception/autoware_probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp @@ -261,11 +261,11 @@ void PointcloudBasedOccupancyGridMapNode::onPointcloudWithObstacleAndRaw( std::chrono::nanoseconds( (this->get_clock()->now() - input_raw_msg->header.stamp).nanoseconds())) .count(); - debug_publisher_ptr_->publish( + debug_publisher_ptr_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_ptr_->publish( + debug_publisher_ptr_->publish( "debug/processing_time_ms", processing_time_ms); - debug_publisher_ptr_->publish( + debug_publisher_ptr_->publish( "debug/pipeline_latency_ms", pipeline_latency_ms); } } From 95e7939e7e3b6164913ce5b5119247de94a89ac8 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Wed, 15 Jan 2025 16:06:17 +0900 Subject: [PATCH 214/334] feat(autoware_pointcloud_preprocessor): tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_pointcloud_preprocessor (#9920) feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files sensing/autoware_pointcloud_preprocessor Signed-off-by: vish0012 --- .../docs/blockage-diag.md | 20 +++++++++---------- .../docs/dual-return-outlier-filter.md | 10 +++++----- .../blockage_diag/blockage_diag_node.hpp | 13 +++++++----- .../concatenate_and_time_sync_nodelet.hpp | 4 ++-- .../concatenate_pointclouds.hpp | 4 ++-- .../dual_return_outlier_filter_node.hpp | 4 ++-- .../ring_outlier_filter_node.hpp | 2 +- .../time_synchronizer_node.hpp | 4 ++-- .../package.xml | 2 +- .../src/blockage_diag/blockage_diag_node.cpp | 12 +++++------ .../concatenate_and_time_sync_nodelet.cpp | 6 +++--- .../concatenate_pointclouds.cpp | 6 +++--- .../crop_box_filter/crop_box_filter_node.cpp | 6 +++--- .../distortion_corrector_node.cpp | 6 +++--- ...ased_voxel_grid_downsample_filter_node.cpp | 6 +++--- .../dual_return_outlier_filter_node.cpp | 4 ++-- .../ring_outlier_filter_node.cpp | 10 +++++----- .../time_synchronizer_node.cpp | 6 +++--- 18 files changed, 64 insertions(+), 61 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/docs/blockage-diag.md b/sensing/autoware_pointcloud_preprocessor/docs/blockage-diag.md index 911cda3823021..a9dcb8437ec67 100644 --- a/sensing/autoware_pointcloud_preprocessor/docs/blockage-diag.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/blockage-diag.md @@ -38,16 +38,16 @@ This implementation inherits `autoware::pointcloud_preprocessor::Filter` class, ### Output -| Name | Type | Description | -| :-------------------------------------------------------- | :-------------------------------------- | ------------------------------------------------------------------------------------------------ | -| `~/output/blockage_diag/debug/blockage_mask_image` | `sensor_msgs::msg::Image` | The mask image of detected blockage | -| `~/output/blockage_diag/debug/ground_blockage_ratio` | `tier4_debug_msgs::msg::Float32Stamped` | The area ratio of blockage region in ground region | -| `~/output/blockage_diag/debug/sky_blockage_ratio` | `tier4_debug_msgs::msg::Float32Stamped` | The area ratio of blockage region in sky region | -| `~/output/blockage_diag/debug/lidar_depth_map` | `sensor_msgs::msg::Image` | The depth map image of input point cloud | -| `~/output/blockage_diag/debug/single_frame_dust_mask` | `sensor_msgs::msg::Image` | The mask image of detected dusty area in latest single frame | -| `~/output/blockage_diag/debug/multi_frame_dust_mask` | `sensor_msgs::msg::Image` | The mask image of continuous detected dusty area | -| `~/output/blockage_diag/debug/blockage_dust_merged_image` | `sensor_msgs::msg::Image` | The merged image of blockage detection(red) and multi frame dusty area detection(yellow) results | -| `~/output/blockage_diag/debug/ground_dust_ratio` | `tier4_debug_msgs::msg::Float32Stamped` | The ratio of dusty area divided by area where ray usually returns from the ground. | +| Name | Type | Description | +| :-------------------------------------------------------- | :-------------------------------------------------- | ------------------------------------------------------------------------------------------------ | +| `~/output/blockage_diag/debug/blockage_mask_image` | `sensor_msgs::msg::Image` | The mask image of detected blockage | +| `~/output/blockage_diag/debug/ground_blockage_ratio` | `autoware_internal_debug_msgs::msg::Float32Stamped` | The area ratio of blockage region in ground region | +| `~/output/blockage_diag/debug/sky_blockage_ratio` | `autoware_internal_debug_msgs::msg::Float32Stamped` | The area ratio of blockage region in sky region | +| `~/output/blockage_diag/debug/lidar_depth_map` | `sensor_msgs::msg::Image` | The depth map image of input point cloud | +| `~/output/blockage_diag/debug/single_frame_dust_mask` | `sensor_msgs::msg::Image` | The mask image of detected dusty area in latest single frame | +| `~/output/blockage_diag/debug/multi_frame_dust_mask` | `sensor_msgs::msg::Image` | The mask image of continuous detected dusty area | +| `~/output/blockage_diag/debug/blockage_dust_merged_image` | `sensor_msgs::msg::Image` | The merged image of blockage detection(red) and multi frame dusty area detection(yellow) results | +| `~/output/blockage_diag/debug/ground_dust_ratio` | `autoware_internal_debug_msgs::msg::Float32Stamped` | The ratio of dusty area divided by area where ray usually returns from the ground. | ## Parameters diff --git a/sensing/autoware_pointcloud_preprocessor/docs/dual-return-outlier-filter.md b/sensing/autoware_pointcloud_preprocessor/docs/dual-return-outlier-filter.md index 8f4da273861a3..0d0423d40ab83 100644 --- a/sensing/autoware_pointcloud_preprocessor/docs/dual-return-outlier-filter.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/dual-return-outlier-filter.md @@ -36,11 +36,11 @@ This implementation inherits `autoware::pointcloud_preprocessor::Filter` class, ### Output -| Name | Type | Description | -| ---------------------------------------------- | --------------------------------------- | ------------------------------------------------------- | -| `/dual_return_outlier_filter/frequency_image` | `sensor_msgs::msg::Image` | The histogram image that represent visibility | -| `/dual_return_outlier_filter/visibility` | `tier4_debug_msgs::msg::Float32Stamped` | A representation of visibility with a value from 0 to 1 | -| `/dual_return_outlier_filter/pointcloud_noise` | `sensor_msgs::msg::Pointcloud2` | The pointcloud removed as noise | +| Name | Type | Description | +| ---------------------------------------------- | --------------------------------------------------- | ------------------------------------------------------- | +| `/dual_return_outlier_filter/frequency_image` | `sensor_msgs::msg::Image` | The histogram image that represent visibility | +| `/dual_return_outlier_filter/visibility` | `autoware_internal_debug_msgs::msg::Float32Stamped` | A representation of visibility with a value from 0 to 1 | +| `/dual_return_outlier_filter/pointcloud_noise` | `sensor_msgs::msg::Pointcloud2` | The pointcloud removed as noise | ## Parameters diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/blockage_diag/blockage_diag_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/blockage_diag/blockage_diag_node.hpp index 3601b492c4fe3..2dbda770f6cec 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/blockage_diag/blockage_diag_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/blockage_diag/blockage_diag_node.hpp @@ -22,10 +22,10 @@ #include #include +#include #include #include #include -#include #if __has_include() #include @@ -58,10 +58,13 @@ class BlockageDiagComponent : public autoware::pointcloud_preprocessor::Filter image_transport::Publisher single_frame_dust_mask_pub; image_transport::Publisher multi_frame_dust_mask_pub; image_transport::Publisher blockage_dust_merged_pub; - rclcpp::Publisher::SharedPtr ground_blockage_ratio_pub_; - rclcpp::Publisher::SharedPtr sky_blockage_ratio_pub_; - rclcpp::Publisher::SharedPtr ground_dust_ratio_pub_; - rclcpp::Publisher::SharedPtr blockage_type_pub_; + rclcpp::Publisher::SharedPtr + ground_blockage_ratio_pub_; + rclcpp::Publisher::SharedPtr + sky_blockage_ratio_pub_; + rclcpp::Publisher::SharedPtr + ground_dust_ratio_pub_; + rclcpp::Publisher::SharedPtr blockage_type_pub_; private: void onBlockageChecker(DiagnosticStatusWrapper & stat); diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp index 40adad3521f8d..6164e85c35717 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp @@ -69,14 +69,14 @@ #include #include +#include +#include #include #include #include #include #include #include -#include -#include #include #include diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp index 0e959eedae1b6..d57e44431a8d2 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp @@ -68,13 +68,13 @@ #include #include +#include +#include #include #include #include #include #include -#include -#include #include #include diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_node.hpp index ef33e88ef5c98..fa55222fb6530 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_node.hpp @@ -22,9 +22,9 @@ #include #include +#include #include #include -#include #if __has_include() #include @@ -54,7 +54,7 @@ class DualReturnOutlierFilterComponent : public autoware::pointcloud_preprocesso /** \brief Parameter service callback */ rcl_interfaces::msg::SetParametersResult paramCallback(const std::vector & p); image_transport::Publisher image_pub_; - rclcpp::Publisher::SharedPtr visibility_pub_; + rclcpp::Publisher::SharedPtr visibility_pub_; rclcpp::Publisher::SharedPtr noise_cloud_pub_; private: diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_node.hpp index c898cbacf33ea..96bd2fb2411a0 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_node.hpp @@ -53,7 +53,7 @@ class RingOutlierFilterComponent : public autoware::pointcloud_preprocessor::Fil const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output, const TransformInfo & transform_info) override; - rclcpp::Publisher::SharedPtr visibility_pub_; + rclcpp::Publisher::SharedPtr visibility_pub_; private: /** \brief publisher of excluded pointcloud for debug reason. **/ diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/time_synchronizer/time_synchronizer_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/time_synchronizer/time_synchronizer_node.hpp index d36fcb36a7be1..f4921be66a7e2 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/time_synchronizer/time_synchronizer_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/time_synchronizer/time_synchronizer_node.hpp @@ -68,14 +68,14 @@ #include #include +#include +#include #include #include #include #include #include #include -#include -#include #include #include diff --git a/sensing/autoware_pointcloud_preprocessor/package.xml b/sensing/autoware_pointcloud_preprocessor/package.xml index 4511c5497a3a0..525b1f3eb0699 100644 --- a/sensing/autoware_pointcloud_preprocessor/package.xml +++ b/sensing/autoware_pointcloud_preprocessor/package.xml @@ -26,6 +26,7 @@ ament_cmake_auto autoware_cmake + autoware_internal_debug_msgs autoware_lanelet2_extension autoware_pcl_extensions autoware_point_types @@ -51,7 +52,6 @@ tf2_eigen tf2_geometry_msgs tf2_ros - tier4_debug_msgs ament_lint_auto autoware_lint_common diff --git a/sensing/autoware_pointcloud_preprocessor/src/blockage_diag/blockage_diag_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/blockage_diag/blockage_diag_node.cpp index 5021a3551c939..e05d5f789f680 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/blockage_diag/blockage_diag_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/blockage_diag/blockage_diag_node.cpp @@ -68,7 +68,7 @@ BlockageDiagComponent::BlockageDiagComponent(const rclcpp::NodeOptions & options std::string(this->get_namespace()) + ": dust_validation", this, &BlockageDiagComponent::dustChecker); - ground_dust_ratio_pub_ = create_publisher( + ground_dust_ratio_pub_ = create_publisher( "blockage_diag/debug/ground_dust_ratio", rclcpp::SensorDataQoS()); if (publish_debug_image_) { single_frame_dust_mask_pub = @@ -86,9 +86,9 @@ BlockageDiagComponent::BlockageDiagComponent(const rclcpp::NodeOptions & options blockage_mask_pub_ = image_transport::create_publisher(this, "blockage_diag/debug/blockage_mask_image"); } - ground_blockage_ratio_pub_ = create_publisher( + ground_blockage_ratio_pub_ = create_publisher( "blockage_diag/debug/ground_blockage_ratio", rclcpp::SensorDataQoS()); - sky_blockage_ratio_pub_ = create_publisher( + sky_blockage_ratio_pub_ = create_publisher( "blockage_diag/debug/sky_blockage_ratio", rclcpp::SensorDataQoS()); using std::placeholders::_1; set_param_res_ = this->add_on_set_parameters_callback( @@ -315,7 +315,7 @@ void BlockageDiagComponent::filter( cv::Mat ground_mask(cv::Size(ideal_horizontal_bins, horizontal_ring_id_), CV_8UC1); cv::vconcat(sky_blank, single_dust_ground_img, single_dust_img); - tier4_debug_msgs::msg::Float32Stamped ground_dust_ratio_msg; + autoware_internal_debug_msgs::msg::Float32Stamped ground_dust_ratio_msg; ground_dust_ratio_ = static_cast(cv::countNonZero(single_dust_ground_img)) / (single_dust_ground_img.cols * single_dust_ground_img.rows); ground_dust_ratio_msg.data = ground_dust_ratio_; @@ -386,12 +386,12 @@ void BlockageDiagComponent::filter( } } - tier4_debug_msgs::msg::Float32Stamped ground_blockage_ratio_msg; + autoware_internal_debug_msgs::msg::Float32Stamped ground_blockage_ratio_msg; ground_blockage_ratio_msg.data = ground_blockage_ratio_; ground_blockage_ratio_msg.stamp = now(); ground_blockage_ratio_pub_->publish(ground_blockage_ratio_msg); - tier4_debug_msgs::msg::Float32Stamped sky_blockage_ratio_msg; + autoware_internal_debug_msgs::msg::Float32Stamped sky_blockage_ratio_msg; sky_blockage_ratio_msg.data = sky_blockage_ratio_; sky_blockage_ratio_msg.stamp = now(); sky_blockage_ratio_pub_->publish(sky_blockage_ratio_msg); diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp index f8baae3405873..b49e21b8f30be 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp @@ -455,9 +455,9 @@ void PointCloudConcatenateDataSynchronizerComponent::publish() if (debug_publisher_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); } for (const auto & e : cloud_stdmap_) { @@ -468,7 +468,7 @@ void PointCloudConcatenateDataSynchronizerComponent::publish() std::chrono::nanoseconds( (this->get_clock()->now() - e.second->header.stamp).nanoseconds())) .count(); - debug_publisher_->publish( + debug_publisher_->publish( "debug" + e.first + "/pipeline_latency_ms", pipeline_latency_ms); } } diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp index ba29389b88bf7..ba5e2eb51997a 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp @@ -271,7 +271,7 @@ void PointCloudConcatenationComponent::publish() std::chrono::nanoseconds( (this->get_clock()->now() - e.second->header.stamp).nanoseconds())) .count(); - debug_publisher_->publish( + debug_publisher_->publish( "debug" + e.first + "/pipeline_latency_ms", pipeline_latency_ms); } } @@ -297,9 +297,9 @@ void PointCloudConcatenationComponent::publish() if (debug_publisher_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); } } diff --git a/sensing/autoware_pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_node.cpp index ecbc5b8fd13ef..54c940d414db8 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_node.cpp @@ -194,9 +194,9 @@ void CropBoxFilterComponent::faster_filter( if (debug_publisher_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); auto pipeline_latency_ms = @@ -204,7 +204,7 @@ void CropBoxFilterComponent::faster_filter( std::chrono::nanoseconds((this->get_clock()->now() - input->header.stamp).nanoseconds())) .count(); - debug_publisher_->publish( + debug_publisher_->publish( "debug/pipeline_latency_ms", pipeline_latency_ms); } } diff --git a/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector_node.cpp index 9eaafeae9dbc7..cc05a6cc2765c 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector_node.cpp @@ -123,7 +123,7 @@ void DistortionCorrectorComponent::pointcloud_callback(PointCloud2::UniquePtr po std::chrono::nanoseconds( (this->get_clock()->now() - pointcloud_msg->header.stamp).nanoseconds())) .count(); - debug_publisher_->publish( + debug_publisher_->publish( "debug/pipeline_latency_ms", pipeline_latency_ms); } @@ -133,9 +133,9 @@ void DistortionCorrectorComponent::pointcloud_callback(PointCloud2::UniquePtr po if (debug_publisher_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); } } diff --git a/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter_node.cpp index 3d2bc0a206c94..0c467234d6591 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter_node.cpp @@ -142,9 +142,9 @@ void PickupBasedVoxelGridDownsampleFilterComponent::filter( if (debug_publisher_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); auto pipeline_latency_ms = @@ -152,7 +152,7 @@ void PickupBasedVoxelGridDownsampleFilterComponent::filter( std::chrono::nanoseconds((this->get_clock()->now() - input->header.stamp).nanoseconds())) .count(); - debug_publisher_->publish( + debug_publisher_->publish( "debug/pipeline_latency_ms", pipeline_latency_ms); } } diff --git a/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_node.cpp index a8024e02de2c1..bac3a59e09528 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_node.cpp @@ -65,7 +65,7 @@ DualReturnOutlierFilterComponent::DualReturnOutlierFilterComponent( image_pub_ = image_transport::create_publisher(this, "dual_return_outlier_filter/debug/frequency_image"); - visibility_pub_ = create_publisher( + visibility_pub_ = create_publisher( "dual_return_outlier_filter/debug/visibility", rclcpp::SensorDataQoS()); { rclcpp::PublisherOptions pub_options; @@ -322,7 +322,7 @@ void DualReturnOutlierFilterComponent::filter( frequency_image_msg->header = input->header; // Publish histogram image image_pub_.publish(frequency_image_msg); - tier4_debug_msgs::msg::Float32Stamped visibility_msg; + autoware_internal_debug_msgs::msg::Float32Stamped visibility_msg; visibility_msg.data = (1.0f - filled); visibility_msg.stamp = now(); visibility_pub_->publish(visibility_msg); diff --git a/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_node.cpp index fae9043143ba4..fcea299ba5aff 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_node.cpp @@ -41,7 +41,7 @@ RingOutlierFilterComponent::RingOutlierFilterComponent(const rclcpp::NodeOptions outlier_pointcloud_publisher_ = this->create_publisher("debug/ring_outlier_filter", 1, pub_options); } - visibility_pub_ = create_publisher( + visibility_pub_ = create_publisher( "ring_outlier_filter/debug/visibility", rclcpp::SensorDataQoS()); stop_watch_ptr_->tic("cyclic_time"); stop_watch_ptr_->tic("processing_time"); @@ -262,7 +262,7 @@ void RingOutlierFilterComponent::faster_filter( outlier.header = input->header; outlier_pointcloud_publisher_->publish(outlier); - tier4_debug_msgs::msg::Float32Stamped visibility_msg; + autoware_internal_debug_msgs::msg::Float32Stamped visibility_msg; visibility_msg.data = calculateVisibilityScore(outlier); visibility_msg.stamp = input->header.stamp; visibility_pub_->publish(visibility_msg); @@ -272,9 +272,9 @@ void RingOutlierFilterComponent::faster_filter( if (debug_publisher_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); auto pipeline_latency_ms = @@ -282,7 +282,7 @@ void RingOutlierFilterComponent::faster_filter( std::chrono::nanoseconds((this->get_clock()->now() - input->header.stamp).nanoseconds())) .count(); - debug_publisher_->publish( + debug_publisher_->publish( "debug/pipeline_latency_ms", pipeline_latency_ms); } } diff --git a/sensing/autoware_pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_node.cpp index 42170fd88ee36..e5bd4a955590f 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_node.cpp @@ -378,7 +378,7 @@ void PointCloudDataSynchronizerComponent::publish() std::chrono::nanoseconds( (this->get_clock()->now() - e.second->header.stamp).nanoseconds())) .count(); - debug_publisher_->publish( + debug_publisher_->publish( "debug" + e.first + "/pipeline_latency_ms", pipeline_latency_ms); } auto output = std::make_unique(*e.second); @@ -400,9 +400,9 @@ void PointCloudDataSynchronizerComponent::publish() if (debug_publisher_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); } } From b20d7f05df2da1dd1580e824c82316ed77f49059 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 15 Jan 2025 16:20:10 +0900 Subject: [PATCH 215/334] chore(autoware_test_utils): move rviz config to autoware_launch (#9925) Signed-off-by: Mamoru Sobue --- common/autoware_test_utils/CMakeLists.txt | 1 - .../launch/psim_intersection.launch.xml | 2 +- .../launch/psim_road_shoulder.launch.xml | 2 +- .../rviz/psim_test_map.rviz | 4569 ----------------- 4 files changed, 2 insertions(+), 4572 deletions(-) delete mode 100644 common/autoware_test_utils/rviz/psim_test_map.rviz diff --git a/common/autoware_test_utils/CMakeLists.txt b/common/autoware_test_utils/CMakeLists.txt index 8bfa44f7bf0ba..20b8f964f879f 100644 --- a/common/autoware_test_utils/CMakeLists.txt +++ b/common/autoware_test_utils/CMakeLists.txt @@ -25,5 +25,4 @@ ament_auto_package(INSTALL_TO_SHARE test_map test_data launch - rviz ) diff --git a/common/autoware_test_utils/launch/psim_intersection.launch.xml b/common/autoware_test_utils/launch/psim_intersection.launch.xml index 723dd7352219d..dc3e75cca1d96 100644 --- a/common/autoware_test_utils/launch/psim_intersection.launch.xml +++ b/common/autoware_test_utils/launch/psim_intersection.launch.xml @@ -3,7 +3,7 @@ - + diff --git a/common/autoware_test_utils/launch/psim_road_shoulder.launch.xml b/common/autoware_test_utils/launch/psim_road_shoulder.launch.xml index 7dd888a036f9d..58b71524e72b8 100644 --- a/common/autoware_test_utils/launch/psim_road_shoulder.launch.xml +++ b/common/autoware_test_utils/launch/psim_road_shoulder.launch.xml @@ -3,7 +3,7 @@ - + diff --git a/common/autoware_test_utils/rviz/psim_test_map.rviz b/common/autoware_test_utils/rviz/psim_test_map.rviz deleted file mode 100644 index 8475c94b86bb4..0000000000000 --- a/common/autoware_test_utils/rviz/psim_test_map.rviz +++ /dev/null @@ -1,4569 +0,0 @@ -Panels: - - Class: rviz_common/Displays - Help Height: 0 - Name: Displays - Property Tree Widget: - Expanded: - - /Sensing1/LiDAR1/ConcatenatePointCloud1/Autocompute Value Bounds1 - Splitter Ratio: 0.557669460773468 - Tree Height: 225 - - Class: rviz_common/Selection - Name: Selection - - Class: rviz_common/Tool Properties - Expanded: ~ - Name: Tool Properties - Splitter Ratio: 0.5886790156364441 - - Class: rviz_common/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 - - Class: AutowareDateTimePanel - Name: AutowareDateTimePanel - - Class: rviz_plugins::AutowareStatePanel - Name: AutowareStatePanel - - Class: rviz_plugins::SimulatedClockPanel - Name: SimulatedClockPanel - - Class: rviz_plugins::TrafficLightPublishPanel - Name: TrafficLightPublishPanel -Visualization Manager: - Class: "" - Displays: - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/TF - Enabled: false - Frame Timeout: 15 - Frames: - All Enabled: true - Marker Scale: 1 - Name: TF - Show Arrows: true - Show Axes: true - Show Names: true - Tree: - {} - Update Interval: 0 - Value: false - - Alpha: 0.5 - Cell Size: 1 - Class: rviz_default_plugins/Grid - Color: 160; 160; 164 - Enabled: false - Line Style: - Line Width: 0.029999999329447746 - Value: Lines - Name: Grid - Normal Cell Count: 0 - Offset: - X: 0 - Y: 0 - Z: 0 - Plane: XY - Plane Cell Count: 10 - Reference Frame: - Value: false - - Class: rviz_common/Group - Displays: - - Alpha: 0.30000001192092896 - Class: rviz_default_plugins/RobotModel - Collision Enabled: false - Description File: "" - Description Source: Topic - Description Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /robot_description - Enabled: true - Links: - All Links Enabled: true - Expand Joint Details: false - Expand Link Details: false - Expand Tree: false - Link Tree Style: Links in Alphabetic Order - ars408_front_center: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - camera0/camera_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - camera0/camera_optical_link: - Alpha: 1 - Show Axes: false - Show Trail: false - camera1/camera_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - camera1/camera_optical_link: - Alpha: 1 - Show Axes: false - Show Trail: false - camera2/camera_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - camera2/camera_optical_link: - Alpha: 1 - Show Axes: false - Show Trail: false - camera3/camera_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - camera3/camera_optical_link: - Alpha: 1 - Show Axes: false - Show Trail: false - camera4/camera_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - camera4/camera_optical_link: - Alpha: 1 - Show Axes: false - Show Trail: false - camera5/camera_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - camera5/camera_optical_link: - Alpha: 1 - Show Axes: false - Show Trail: false - camera6/camera_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - camera6/camera_optical_link: - Alpha: 1 - Show Axes: false - Show Trail: false - camera7/camera_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - camera7/camera_optical_link: - Alpha: 1 - Show Axes: false - Show Trail: false - gnss_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - livox_front_left: - Alpha: 1 - Show Axes: false - Show Trail: false - livox_front_left_base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - livox_front_right: - Alpha: 1 - Show Axes: false - Show Trail: false - livox_front_right_base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - sensor_kit_base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - tamagawa/imu_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - velodyne_left: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - velodyne_left_base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - velodyne_rear: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - velodyne_rear_base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - velodyne_right: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - velodyne_right_base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - velodyne_top: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - velodyne_top_base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - Mass Properties: - Inertia: false - Mass: false - Name: VehicleModel - TF Prefix: "" - Update Interval: 0 - Value: true - Visual Enabled: true - - Class: rviz_plugins/PolarGridDisplay - Color: 255; 255; 255 - Delta Range: 10 - Enabled: true - Max Alpha: 0.5 - Max Range: 100 - Max Wave Alpha: 0.5 - Min Alpha: 0.009999999776482582 - Min Wave Alpha: 0.009999999776482582 - Name: PolarGridDisplay - Reference Frame: base_link - Value: true - Wave Color: 255; 255; 255 - Wave Velocity: 40 - - Background Alpha: 0.5 - Background Color: 23; 28; 31 - Class: autoware_overlay_rviz_plugin/SignalDisplay - Dark Traffic Color: 255; 51; 51 - Enabled: true - Gear Topic Test: /vehicle/status/gear_status - Handle Angle Scale: 17 - Hazard Lights Topic: /vehicle/status/hazard_lights_status - Height: 100 - Left: 0 - Light Traffic Color: 255; 153; 153 - Name: SignalDisplay - Primary Color: 174; 174; 174 - Signal Color: 0; 230; 120 - Speed Limit Topic: /planning/scenario_planning/current_max_velocity - Speed Topic: /vehicle/status/velocity_status - Steering Topic: /vehicle/status/steering_status - Top: 10 - Traffic Topic: /planning/scenario_planning/lane_driving/behavior_planning/debug/traffic_signal - Turn Signals Topic: /vehicle/status/turn_indicators_status - Value: true - Width: 550 - Enabled: true - Name: Vehicle - - Class: rviz_plugins/MrmSummaryOverlayDisplay - Enabled: false - Font Size: 10 - Left: 512 - Max Letter Num: 100 - Name: MRM Summary - Text Color: 25; 255; 240 - Top: 64 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /system/emergency/hazard_status - Value: false - Value height offset: 0 - Enabled: true - Name: System - - Class: rviz_common/Group - Displays: - - Alpha: 0.20000000298023224 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 28.71826171875 - Min Value: -7.4224700927734375 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz_default_plugins/PointCloud2 - Color: 255; 255; 255 - Color Transformer: FlatColor - Decay Time: 0 - Enabled: false - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 237 - Min Color: 211; 215; 207 - Min Intensity: 0 - Name: PointCloudMap - Position Transformer: XYZ - Selectable: false - Size (Pixels): 1 - Size (m): 0.019999999552965164 - Style: Points - Topic: - Depth: 5 - Durability Policy: Transient Local - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /map/pointcloud_map - Use Fixed Frame: true - Use rainbow: false - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: Lanelet2VectorMap - Namespaces: - bus_stop_area: true - center_lane_line: false - center_line_arrows: false - curbstone: true - lane_start_bound: false - lanelet direction: true - lanelet_id: false - left_lane_bound: true - no_parking_area: true - parking_lots: true - parking_space: true - partitions: true - right_lane_bound: true - road_lanelets: false - shoulder_center_lane_line: false - shoulder_center_line_arrows: true - shoulder_lane_start_bound: true - shoulder_left_lane_bound: true - shoulder_right_lane_bound: true - shoulder_road_lanelets: false - Topic: - Depth: 5 - Durability Policy: Transient Local - History Policy: Keep Last - Reliability Policy: Reliable - Value: /map/vector_map_marker - Value: true - Enabled: true - Name: Map - - Class: rviz_common/Group - Displays: - - Class: rviz_common/Group - Displays: - - Alpha: 0.4000000059604645 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 5 - Min Value: -1 - Value: false - Axis: Z - Channel Name: intensity - Class: rviz_default_plugins/PointCloud2 - Color: 255; 255; 255 - Color Transformer: AxisColor - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: ConcatenatePointCloud - Position Transformer: XYZ - Selectable: false - Size (Pixels): 1 - Size (m): 0.019999999552965164 - Style: Points - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /sensing/lidar/concatenated/pointcloud - Use Fixed Frame: false - Use rainbow: true - Value: true - - Alpha: 0.9990000128746033 - Class: rviz_default_plugins/Polygon - Color: 25; 255; 0 - Enabled: false - Name: MeasurementRange - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /sensing/lidar/crop_box_filter/crop_box_polygon - Value: false - Enabled: true - Name: LiDAR - - Class: rviz_common/Group - Displays: - - Alpha: 0.9990000128746033 - Axes Length: 1 - Axes Radius: 0.10000000149011612 - Class: rviz_default_plugins/PoseWithCovariance - Color: 233; 185; 110 - Covariance: - Orientation: - Alpha: 0.5 - Color: 255; 255; 127 - Color Style: Unique - Frame: Local - Offset: 1 - Scale: 1 - Value: false - Position: - Alpha: 0.20000000298023224 - Color: 204; 51; 204 - Scale: 1 - Value: true - Value: true - Enabled: true - Head Length: 0.699999988079071 - Head Radius: 1.2000000476837158 - Name: PoseWithCovariance - Shaft Length: 1 - Shaft Radius: 0.5 - Shape: Arrow - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /sensing/gnss/pose_with_covariance - Value: true - Enabled: false - Name: GNSS - Enabled: true - Name: Sensing - - Class: rviz_common/Group - Displays: - - Class: rviz_common/Group - Displays: - - Alpha: 0.9990000128746033 - Axes Length: 1 - Axes Radius: 0.10000000149011612 - Class: rviz_default_plugins/PoseWithCovariance - Color: 0; 170; 255 - Covariance: - Orientation: - Alpha: 0.5 - Color: 255; 255; 127 - Color Style: Unique - Frame: Local - Offset: 1 - Scale: 1 - Value: true - Position: - Alpha: 0.30000001192092896 - Color: 204; 51; 204 - Scale: 1 - Value: true - Value: true - Enabled: false - Head Length: 0.4000000059604645 - Head Radius: 0.6000000238418579 - Name: PoseWithCovInitial - Shaft Length: 0.6000000238418579 - Shaft Radius: 0.30000001192092896 - Shape: Arrow - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /localization/pose_estimator/initial_pose_with_covariance - Value: false - - Alpha: 0.9990000128746033 - Axes Length: 1 - Axes Radius: 0.10000000149011612 - Class: rviz_default_plugins/PoseWithCovariance - Color: 0; 255; 0 - Covariance: - Orientation: - Alpha: 0.5 - Color: 255; 255; 127 - Color Style: Unique - Frame: Local - Offset: 1 - Scale: 1 - Value: true - Position: - Alpha: 0.30000001192092896 - Color: 204; 51; 204 - Scale: 1 - Value: true - Value: true - Enabled: false - Head Length: 0.4000000059604645 - Head Radius: 0.6000000238418579 - Name: PoseWithCovAligned - Shaft Length: 0.6000000238418579 - Shaft Radius: 0.30000001192092896 - Shape: Arrow - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /localization/pose_estimator/pose_with_covariance - Value: false - - Buffer Size: 200 - Class: rviz_plugins::PoseHistory - Enabled: false - Line: - Alpha: 0.9990000128746033 - Color: 170; 255; 127 - Value: true - Width: 0.10000000149011612 - Name: PoseHistory - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /localization/pose_estimator/pose - Value: false - - Alpha: 0.9990000128746033 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz_default_plugins/PointCloud2 - Color: 0; 255; 255 - Color Transformer: "" - Decay Time: 0 - Enabled: false - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: Initial - Position Transformer: XYZ - Selectable: false - Size (Pixels): 10 - Size (m): 0.5 - Style: Squares - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /localization/util/downsample/pointcloud - Use Fixed Frame: true - Use rainbow: true - Value: false - - Alpha: 0.9990000128746033 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz_default_plugins/PointCloud2 - Color: 85; 255; 0 - Color Transformer: FlatColor - Decay Time: 0 - Enabled: false - Invert Rainbow: false - Max Color: 85; 255; 127 - Max Intensity: 0 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: Aligned - Position Transformer: XYZ - Selectable: false - Size (Pixels): 10 - Size (m): 0.5 - Style: Squares - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /localization/pose_estimator/points_aligned - Use Fixed Frame: true - Use rainbow: true - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: MonteCarloInitialPose - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /localization/pose_estimator/monte_carlo_initial_pose_marker - Value: true - Enabled: true - Name: NDT - - Class: rviz_common/Group - Displays: - - Buffer Size: 1000 - Class: rviz_plugins::PoseHistory - Enabled: true - Line: - Alpha: 0.9990000128746033 - Color: 0; 255; 255 - Value: true - Width: 0.10000000149011612 - Name: PoseHistory - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /localization/pose_twist_fusion_filter/pose - Value: true - Enabled: true - Name: EKF - Enabled: true - Name: Localization - - Class: rviz_common/Group - Displays: - - Class: rviz_common/Group - Displays: - - Alpha: 0.9990000128746033 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 15 - Min Value: -2 - Value: false - Axis: Z - Channel Name: z - Class: rviz_default_plugins/PointCloud2 - Color: 200; 200; 200 - Color Transformer: FlatColor - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 15 - Min Color: 0; 0; 0 - Min Intensity: -5 - Name: NoGroundPointCloud - Position Transformer: XYZ - Selectable: false - Size (Pixels): 3 - Size (m): 0.019999999552965164 - Style: Points - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/obstacle_segmentation/pointcloud - Use Fixed Frame: true - Use rainbow: true - Value: true - Enabled: true - Name: Segmentation - - Class: rviz_common/Group - Displays: - - Class: rviz_common/Group - Displays: - - BUS: - Alpha: 0.9990000128746033 - Color: 30; 144; 255 - CAR: - Alpha: 0.9990000128746033 - Color: 30; 144; 255 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 119; 11; 32 - Class: autoware_perception_rviz_plugin/DetectedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Enabled: true - Line Width: 0.029999999329447746 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 119; 11; 32 - Name: DetectedObjects - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 255; 192; 203 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 30; 144; 255 - TRUCK: - Alpha: 0.9990000128746033 - Color: 30; 144; 255 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/detection/objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 255; 255; 255 - Value: true - Visualization Type: Normal - Enabled: false - Name: Detection - - Class: rviz_common/Group - Displays: - - BUS: - Alpha: 0.9990000128746033 - Color: 30; 144; 255 - CAR: - Alpha: 0.9990000128746033 - Color: 30; 144; 255 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 119; 11; 32 - Class: autoware_perception_rviz_plugin/TrackedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Dynamic Status: All - Enabled: true - Line Width: 0.029999999329447746 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 119; 11; 32 - Name: TrackedObjects - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 255; 192; 203 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 30; 144; 255 - TRUCK: - Alpha: 0.9990000128746033 - Color: 30; 144; 255 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/tracking/objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 255; 255; 255 - Value: true - Visualization Type: Normal - Enabled: false - Name: Tracking - - Class: rviz_common/Group - Displays: - - BUS: - Alpha: 0.9990000128746033 - Color: 30; 144; 255 - CAR: - Alpha: 0.9990000128746033 - Color: 30; 144; 255 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 119; 11; 32 - Class: autoware_perception_rviz_plugin/PredictedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Enabled: true - Line Width: 0.029999999329447746 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 119; 11; 32 - Name: PredictedObjects - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 255; 192; 203 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 30; 144; 255 - TRUCK: - Alpha: 0.9990000128746033 - Color: 30; 144; 255 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 255; 255; 255 - Value: true - Visualization Type: Normal - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Maneuver - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/prediction/maneuver - Value: false - Enabled: true - Name: Prediction - Enabled: true - Name: ObjectRecognition - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/Image - Enabled: false - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: RecognitionResultOnImage - Normalize Range: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/traffic_light_recognition/traffic_light/debug/rois - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: MapBasedDetectionResult - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/traffic_light_recognition/traffic_light_map_based_detector/debug/markers - Value: true - Enabled: true - Name: TrafficLight - - Class: rviz_common/Group - Displays: - - Alpha: 0.5 - Class: rviz_default_plugins/Map - Color Scheme: map - Draw Behind: false - Enabled: true - Name: Map - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/occupancy_grid_map/map - Update Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/occupancy_grid_map/map_updates - Use Timestamp: false - Value: true - Enabled: false - Name: OccupancyGrid - Enabled: true - Name: Perception - - Class: rviz_common/Group - Displays: - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: RouteArea - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Transient Local - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/mission_planning/route_marker - Value: true - - Alpha: 0.9990000128746033 - Axes Length: 1 - Axes Radius: 0.30000001192092896 - Class: rviz_default_plugins/Pose - Color: 255; 25; 0 - Enabled: true - Head Length: 0.30000001192092896 - Head Radius: 0.5 - Name: GoalPose - Shaft Length: 3 - Shaft Radius: 0.20000000298023224 - Shape: Axes - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/mission_planning/echo_back_goal_pose - Value: true - - Background Alpha: 0.5 - Background Color: 23; 28; 31 - Class: autoware_mission_details_overlay_rviz_plugin/MissionDetailsDisplay - Enabled: true - Height: 100 - Name: MissionDetailsDisplay - Remaining Distance and Time Topic: /planning/mission_remaining_distance_time - Right: 10 - Text Color: 194; 194; 194 - Top: 10 - Value: true - Width: 170 - Enabled: true - Name: MissionPlanning - - Class: rviz_common/Group - Displays: - - Class: rviz_plugins/Trajectory - Color Border Vel Max: 3 - Enabled: true - Name: ScenarioTrajectory - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/trajectory - Value: true - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.9990000128746033 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.9990000128746033 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: true - - Class: rviz_common/Group - Displays: - - Class: rviz_common/Group - Displays: - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: true - Name: Path - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/path - Value: true - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.4000000059604645 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.4000000059604645 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: true - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: false - Name: PathReference_AvoidanceByLC - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_reference/avoidance_by_lane_change - Value: false - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: false - Name: PathReference_Avoidance - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_reference/static_obstacle_avoidance - Value: false - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: false - Name: PathReference_LaneChangeRight - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_reference/lane_change_right - Value: false - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: false - Name: PathReference_LaneChangeLeft - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_reference/lane_change_left - Value: false - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: false - Name: PathReference_GoalPlanner - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_reference/goal_planner - Value: false - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: false - Name: PathReference_StartPlanner - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_reference/start_planner - Value: false - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: true - Name: PathChangeCandidate_AvoidanceByLC - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_candidate/avoidance_by_lane_change - Value: true - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: true - Name: (old)PathChangeCandidate_LaneChange - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_candidate/lane_change - Value: true - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: true - Name: PathChangeCandidate_LaneChangeRight - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_candidate/lane_change_right - Value: true - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: true - Name: PathChangeCandidate_LaneChangeLeft - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_candidate/lane_change_left - Value: true - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: true - Name: PathChangeCandidate_ExternalRequestLaneChangeRight - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_candidate/external_request_lane_change_right - Value: true - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: true - Name: PathChangeCandidate_ExternalRequestLaneChangeLeft - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_candidate/external_request_lane_change_left - Value: true - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: true - Name: PathChangeCandidate_Avoidance - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_candidate/static_obstacle_avoidance - Value: true - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: true - Name: PathChangeCandidate_StartPlanner - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_candidate/start_planner - Value: true - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Path - Color Border Vel Max: 3 - Enabled: true - Name: PathChangeCandidate_GoalPlanner - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/path_candidate/goal_planner - Value: true - View Drivable Area: - Alpha: 0.9990000128746033 - Color: 0; 148; 205 - Value: true - Width: 0.30000001192092896 - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.30000001192092896 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.30000001192092896 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Bound - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/bound - Value: false - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (StaticObstacleAvoidance) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/static_obstacle_avoidance - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (AvoidanceByLC) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/avoidance_by_lane_change - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (LaneChangeRight) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/lane_change_right - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (LaneChangeLeft) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/lane_change_left - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (ExtLaneChangeRight) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/external_request_lane_change_right - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (ExtLaneChangeLeft) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/external_request_lane_change_left - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (GoalPlanner) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/goal_planner - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (StartPlanner) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/virtual_wall/start_planner - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (BlindSpot) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/blind_spot - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (Crosswalk) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/crosswalk - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (Walkway) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/walkway - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (DetectionArea) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/detection_area - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (Intersection) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/intersection - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (MergeFromPrivateArea) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/merge_from_private - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (NoStoppingArea) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/no_stopping_area - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (OcclusionSpot) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/occlusion_spot - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (StopLine) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/stop_line - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (TrafficLight) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/traffic_light - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (VirtualTrafficLight) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/virtual_traffic_light - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (RunOut) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/run_out - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (SpeedBump) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/speed_bump - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (NoDrivableLane) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/virtual_wall/no_drivable_lane - Value: true - Enabled: true - Name: VirtualWall - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Arrow - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/path - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Crosswalk - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/crosswalk - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Intersection - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/intersection - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Blind Spot - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/blind_spot - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: TrafficLight - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/traffic_light - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: VirtualTrafficLight - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/virtual_traffic_light - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: StopLine - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/stop_line - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: DetectionArea - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/detection_area - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: OcclusionSpot - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/occlusion_spot - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: NoStoppingArea - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/no_stopping_area - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: RunOut - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/run_out - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: StaticObstacleAvoidance - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/static_obstacle_avoidance - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: LeftLaneChange - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/lane_change_left - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: RightLaneChange - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/lane_change_right - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: LaneFollowing - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/lane_following - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: GoalPlanner - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/goal_planner - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: StartPlanner - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/start_planner - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: SideShift - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/side_shift - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: SpeedBump - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/speed_bump - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: DynamicObstacleAvoidance - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/dynamic_obstacle_avoidance - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: NoDrivableLane - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/no_drivable_lane - Value: false - Enabled: false - Name: DebugMarker - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Info (StaticObstacleAvoidance) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/static_obstacle_avoidance - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Info (AvoidanceByLC) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/avoidance_by_lane_change - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Info (LaneChangeLeft) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/lane_change_left - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Info (LaneChangeRight) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/lane_change_right - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Info (ExtLaneChangeLeft) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/external_request_lane_change_left - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Info (ExtLaneChangeRight) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/external_request_lane_change_right - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Info (GoalPlanner) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/goal_planner - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Info (StartPlanner) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/start_planner - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Info (DynamicObstacleAvoidance) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/info/dynamic_obstacle_avoidance - Value: false - Enabled: false - Name: InfoMarker - Enabled: true - Name: BehaviorPlanning - - Class: rviz_common/Group - Displays: - - Class: rviz_plugins/Trajectory - Color Border Vel Max: 3 - Enabled: false - Name: Trajectory - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/trajectory - Value: false - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 0.9990000128746033 - Constant Width: false - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 2 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 0.9990000128746033 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: true - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (ObstacleStop) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/virtual_wall - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (SurroundObstacle) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/virtual_wall - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (ObstacleAvoidance) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/virtual_wall - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (ObstacleCruise) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/virtual_wall - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (MotionVelocitySmoother) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/velocity_smoother/virtual_wall - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (OutOfLane) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/out_of_lane/virtual_walls - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (ObstacleVelocityLimiter) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/obstacle_velocity_limiter/virtual_walls - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (DynamicObstacleStop) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/dynamic_obstacle_stop/virtual_walls - Value: true - Enabled: true - Name: VirtualWall - - Class: rviz_common/Group - Displays: - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: SurroundObstacleCheck - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/marker - Value: true - - Alpha: 1 - Class: rviz_default_plugins/Polygon - Color: 25; 255; 0 - Enabled: false - Name: Footprint - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/footprint - Value: false - - Alpha: 1 - Class: rviz_default_plugins/Polygon - Color: 239; 41; 41 - Enabled: false - Name: FootprintOffset - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/footprint_offset - Value: false - - Alpha: 1 - Class: rviz_default_plugins/Polygon - Color: 10; 21; 255 - Enabled: false - Name: FootprintRecoverOffset - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/footprint_recover_offset - Value: false - Enabled: false - Name: SurroundObstacleChecker - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: ObstacleStop - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/debug/marker - Value: false - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: CruiseVirtualWall - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/cruise/virtual_wall - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: SlowDownVirtualWall - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/slow_down/virtual_wall - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: DebugMarker - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner/debug/marker - Value: true - Enabled: false - Name: ObstacleCruise - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: ObstacleAvoidance - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/debug/marker - Value: false - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: OutOfLane - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/out_of_lane/debug_markers - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: ObstacleVelocityLimiter - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/obstacle_velocity_limiter/debug_markers - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: DynamicObstacleStop - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/dynamic_obstacle_stop/debug_markers - Value: true - Enabled: false - Name: MotionVelocityPlanner - Enabled: false - Name: DebugMarker - Enabled: true - Name: MotionPlanning - Enabled: true - Name: LaneDriving - - Class: rviz_common/Group - Displays: - - Alpha: 0.699999988079071 - Class: rviz_default_plugins/Map - Color Scheme: map - Draw Behind: false - Enabled: false - Name: Costmap - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/parking/costmap_generator/occupancy_grid - Update Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/parking/costmap_generator/occupancy_grid_updates - Use Timestamp: false - Value: false - - Alpha: 0.9990000128746033 - Arrow Length: 0.30000001192092896 - Axes Length: 0.30000001192092896 - Axes Radius: 0.009999999776482582 - Class: rviz_default_plugins/PoseArray - Color: 255; 25; 0 - Enabled: true - Head Length: 0.10000000149011612 - Head Radius: 0.20000000298023224 - Name: PartialPoseArray - Shaft Length: 0.20000000298023224 - Shaft Radius: 0.05000000074505806 - Shape: Arrow (3D) - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/parking/freespace_planner/debug/partial_pose_array - Value: true - - Alpha: 0.9990000128746033 - Arrow Length: 0.5 - Axes Length: 0.30000001192092896 - Axes Radius: 0.009999999776482582 - Class: rviz_default_plugins/PoseArray - Color: 0; 0; 255 - Enabled: true - Head Length: 0.10000000149011612 - Head Radius: 0.20000000298023224 - Name: PoseArray - Shaft Length: 0.20000000298023224 - Shaft Radius: 0.05000000074505806 - Shape: Arrow (Flat) - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/parking/freespace_planner/debug/pose_array - Value: true - Enabled: true - Name: Parking - - Class: rviz_plugins/PoseWithUuidStamped - Enabled: true - Length: 1.5 - Name: ModifiedGoal - Radius: 0.5 - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/scenario_planning/modified_goal - UUID: - Scale: 0.30000001192092896 - Value: false - Value: true - Enabled: true - Name: ScenarioPlanning - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: PlanningErrorMarker - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /planning/planning_diagnostics/planning_error_monitor/debug/marker - Value: true - Enabled: false - Name: Diagnostic - Enabled: true - Name: Planning - - Class: rviz_common/Group - Displays: - - Class: rviz_plugins/Trajectory - Color Border Vel Max: 3 - Enabled: true - Name: Predicted Trajectory - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /control/trajectory_follower/controller_node_exe/debug/predicted_trajectory_in_frenet_coordinate - Value: true - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 1 - Constant Width: true - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: true - Width: 0.05000000074505806 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: false - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 1 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_plugins/Trajectory - Color Border Vel Max: 3 - Enabled: false - Name: Resampled Reference Trajectory - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /control/trajectory_follower/controller_node_exe/debug/resampled_reference_trajectory - Value: false - View Footprint: - Alpha: 1 - Color: 230; 230; 50 - Offset from BaseLink: 0 - Rear Overhang: 1.0299999713897705 - Value: false - Vehicle Length: 4.769999980926514 - Vehicle Width: 1.8300000429153442 - View Path: - Alpha: 1 - Constant Width: true - Fade Out Distance: 0 - Max Velocity Color: 0; 230; 120 - Mid Velocity Color: 32; 138; 174 - Min Velocity Color: 63; 46; 227 - Value: false - Width: 0.20000000298023224 - View Point: - Alpha: 1 - Color: 0; 60; 255 - Offset: 0 - Radius: 0.10000000149011612 - Value: true - View Text Slope: - Scale: 0.30000001192092896 - Value: false - View Text Velocity: - Scale: 0.30000001192092896 - Value: false - View Velocity: - Alpha: 1 - Color: 0; 0; 0 - Constant Color: false - Scale: 0.30000001192092896 - Value: false - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: VirtualWall (AEB) - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /control/autonomous_emergency_braking/virtual_wall - Value: true - Enabled: true - Name: VirtualWall - - Class: rviz_default_plugins/Marker - Enabled: false - Name: Stop Reason - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /control/trajectory_follower/longitudinal/stop_reason - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Debug/MPC - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /control/trajectory_follower/mpc_follower/debug/markers - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Debug/PurePursuit - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /control/trajectory_follower/controller_node_exe/debug/markers - Value: false - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Debug/AEB - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /control/autonomous_emergency_braking/debug/markers - Value: false - Enabled: true - Name: Control - - Class: rviz_common/Group - Displays: - - Class: rviz_common/Group - Displays: ~ - Enabled: true - Name: Map - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/Camera - Enabled: true - Far Plane Distance: 100 - Image Rendering: background and overlay - Name: PointcloudOnCamera - Overlay Alpha: 0.5 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /sensing/camera/camera6/image_raw - Value: true - Visibility: - Control: - Debug/AEB: true - Debug/MPC: true - Debug/PurePursuit: true - Predicted Trajectory: true - Resampled Reference Trajectory: true - Stop Reason: true - Value: false - VirtualWall: - Value: true - VirtualWall (AEB): true - Debug: - Control: true - Localization: - "": true - Value: true - Map: true - Perception: - "": true - Value: true - Planning: - "": - "": true - Value: true - Value: true - Sensing: - ConcatenatePointCloud: true - RadarRawObjects(white): true - Value: true - Value: true - Localization: - EKF: - PoseHistory: true - Value: true - NDT: - Aligned: true - Initial: true - MonteCarloInitialPose: true - PoseHistory: true - PoseWithCovAligned: true - PoseWithCovInitial: true - Value: true - Value: false - Map: - Lanelet2VectorMap: true - PointCloudMap: true - Value: false - Perception: - ObjectRecognition: - Detection: - DetectedObjects: true - Value: true - Prediction: - Maneuver: true - PredictedObjects: true - Value: true - Tracking: - TrackedObjects: true - Value: true - Value: true - OccupancyGrid: - Map: true - Value: true - Segmentation: - NoGroundPointCloud: true - Value: true - TrafficLight: - MapBasedDetectionResult: true - RecognitionResultOnImage: true - Value: true - Value: false - Planning: - Diagnostic: - PlanningErrorMarker: true - Value: true - MissionPlanning: - GoalPose: true - MissionDetailsDisplay: true - RouteArea: true - Value: true - ScenarioPlanning: - LaneDriving: - BehaviorPlanning: - (old)PathChangeCandidate_LaneChange: true - Bound: true - DebugMarker: - Arrow: true - Blind Spot: true - Crosswalk: true - DetectionArea: true - DynamicObstacleAvoidance: true - GoalPlanner: true - Intersection: true - LaneFollowing: true - LeftLaneChange: true - NoDrivableLane: true - NoStoppingArea: true - OcclusionSpot: true - RightLaneChange: true - RunOut: true - SideShift: true - SpeedBump: true - StartPlanner: true - StaticObstacleAvoidance: true - StopLine: true - TrafficLight: true - Value: true - VirtualTrafficLight: true - InfoMarker: - Info (AvoidanceByLC): true - Info (DynamicObstacleAvoidance): true - Info (ExtLaneChangeLeft): true - Info (ExtLaneChangeRight): true - Info (GoalPlanner): true - Info (LaneChangeLeft): true - Info (LaneChangeRight): true - Info (StartPlanner): true - Info (StaticObstacleAvoidance): true - Value: true - Path: true - PathChangeCandidate_Avoidance: true - PathChangeCandidate_AvoidanceByLC: true - PathChangeCandidate_ExternalRequestLaneChangeLeft: true - PathChangeCandidate_ExternalRequestLaneChangeRight: true - PathChangeCandidate_GoalPlanner: true - PathChangeCandidate_LaneChangeLeft: true - PathChangeCandidate_LaneChangeRight: true - PathChangeCandidate_StartPlanner: true - PathReference_Avoidance: true - PathReference_AvoidanceByLC: true - PathReference_GoalPlanner: true - PathReference_LaneChangeLeft: true - PathReference_LaneChangeRight: true - PathReference_StartPlanner: true - Value: true - VirtualWall: - Value: true - VirtualWall (AvoidanceByLC): true - VirtualWall (BlindSpot): true - VirtualWall (Crosswalk): true - VirtualWall (DetectionArea): true - VirtualWall (ExtLaneChangeLeft): true - VirtualWall (ExtLaneChangeRight): true - VirtualWall (GoalPlanner): true - VirtualWall (Intersection): true - VirtualWall (LaneChangeLeft): true - VirtualWall (LaneChangeRight): true - VirtualWall (MergeFromPrivateArea): true - VirtualWall (NoDrivableLane): true - VirtualWall (NoStoppingArea): true - VirtualWall (OcclusionSpot): true - VirtualWall (RunOut): true - VirtualWall (SpeedBump): true - VirtualWall (StartPlanner): true - VirtualWall (StaticObstacleAvoidance): true - VirtualWall (StopLine): true - VirtualWall (TrafficLight): true - VirtualWall (VirtualTrafficLight): true - VirtualWall (Walkway): true - MotionPlanning: - DebugMarker: - MotionVelocityPlanner: - DynamicObstacleStop: true - ObstacleVelocityLimiter: true - OutOfLane: true - Value: true - ObstacleAvoidance: true - ObstacleCruise: - CruiseVirtualWall: true - DebugMarker: true - SlowDownVirtualWall: true - Value: true - ObstacleStop: true - SurroundObstacleChecker: - Footprint: true - FootprintOffset: true - FootprintRecoverOffset: true - SurroundObstacleCheck: true - Value: true - Value: true - Trajectory: true - Value: true - VirtualWall: - Value: true - VirtualWall (DynamicObstacleStop): true - VirtualWall (MotionVelocitySmoother): true - VirtualWall (ObstacleAvoidance): true - VirtualWall (ObstacleCruise): true - VirtualWall (ObstacleStop): true - VirtualWall (ObstacleVelocityLimiter): true - VirtualWall (OutOfLane): true - VirtualWall (SurroundObstacle): true - Value: true - ModifiedGoal: true - Parking: - Costmap: true - PartialPoseArray: true - PoseArray: true - Value: true - ScenarioTrajectory: true - Value: true - Value: false - Sensing: - GNSS: - PoseWithCovariance: true - Value: true - LiDAR: - ConcatenatePointCloud: true - MeasurementRange: true - Value: true - Value: true - System: - Grid: true - MRM Summary: true - TF: true - Value: false - Vehicle: - PolarGridDisplay: true - SignalDisplay: true - Value: true - VehicleModel: true - Value: true - Zoom Factor: 1 - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 5 - Min Value: -1 - Value: false - Axis: Z - Channel Name: intensity - Class: rviz_default_plugins/PointCloud2 - Color: 255; 255; 255 - Color Transformer: AxisColor - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: ConcatenatePointCloud - Position Transformer: XYZ - Selectable: false - Size (Pixels): 3 - Size (m): 0.019999999552965164 - Style: Points - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /sensing/lidar/concatenated/pointcloud - Use Fixed Frame: false - Use rainbow: true - Value: true - - BUS: - Alpha: 0.5 - Color: 255; 255; 255 - CAR: - Alpha: 0.5 - Color: 255; 255; 255 - CYCLIST: - Alpha: 0.5 - Color: 255; 255; 255 - Class: autoware_perception_rviz_plugin/DetectedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Enabled: true - Line Width: 0.029999999329447746 - MOTORCYCLE: - Alpha: 0.5 - Color: 255; 255; 255 - Name: RadarRawObjects(white) - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.5 - Color: 255; 255; 255 - Polygon Type: 3d - TRAILER: - Alpha: 0.5 - Color: 255; 255; 255 - TRUCK: - Alpha: 0.5 - Color: 255; 255; 255 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /sensing/radar/detected_objects - UNKNOWN: - Alpha: 0.5 - Color: 255; 255; 255 - Value: true - Visualization Type: Normal - Enabled: false - Name: Sensing - - Class: rviz_common/Group - Displays: - - Alpha: 0.9990000128746033 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz_default_plugins/PointCloud2 - Color: 85; 255; 0 - Color Transformer: FlatColor - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 85; 255; 127 - Max Intensity: 0 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: NDT pointclouds - Position Transformer: XYZ - Selectable: false - Size (Pixels): 10 - Size (m): 0.5 - Style: Squares - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /localization/pose_estimator/points_aligned - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz_default_plugins/PointCloud2 - Color: 255; 255; 255 - Color Transformer: "" - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: NDTLoadedPCDMap - Position Transformer: "" - Selectable: true - Size (Pixels): 3 - Size (m): 0.10000000149011612 - Style: Flat Squares - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /localization/pose_estimator/debug/loaded_pointcloud_map - Use Fixed Frame: true - Use rainbow: true - Value: true - - Buffer Size: 200 - Class: rviz_plugins::PoseHistory - Enabled: true - Line: - Alpha: 0.9990000128746033 - Color: 170; 255; 127 - Value: true - Width: 0.10000000149011612 - Name: NDTPoseHistory - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /localization/pose_estimator/pose - Value: true - - Buffer Size: 1000 - Class: rviz_plugins::PoseHistory - Enabled: true - Line: - Alpha: 0.9990000128746033 - Color: 0; 255; 255 - Value: true - Width: 0.10000000149011612 - Name: EKFPoseHistory - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /localization/pose_twist_fusion_filter/pose - Value: true - Enabled: true - Name: Localization - - Class: rviz_common/Group - Displays: - - BUS: - Alpha: 0.9990000128746033 - Color: 255; 138; 128 - CAR: - Alpha: 0.9990000128746033 - Color: 255; 138; 128 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 255; 138; 128 - Class: autoware_perception_rviz_plugin/DetectedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Enabled: true - Line Width: 0.10000000149011612 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 255; 138; 128 - Name: Centerpoint(red1) - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 255; 138; 128 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 255; 138; 128 - TRUCK: - Alpha: 0.9990000128746033 - Color: 255; 138; 128 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/detection/centerpoint/objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 255; 138; 128 - Value: true - Visualization Type: Normal - - BUS: - Alpha: 0.9990000128746033 - Color: 255; 82; 82 - CAR: - Alpha: 0.9990000128746033 - Color: 255; 82; 82 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 255; 82; 82 - Class: autoware_perception_rviz_plugin/DetectedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Enabled: true - Line Width: 0.10000000149011612 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 255; 82; 82 - Name: CenterpointROIFusion(red2) - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 255; 82; 82 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 255; 82; 82 - TRUCK: - Alpha: 0.9990000128746033 - Color: 255; 82; 82 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/detection/centerpoint/roi_fusion/objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 255; 82; 82 - Value: true - Visualization Type: Normal - - BUS: - Alpha: 0.9990000128746033 - Color: 213; 0; 0 - CAR: - Alpha: 0.9990000128746033 - Color: 213; 0; 0 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 213; 0; 0 - Class: autoware_perception_rviz_plugin/DetectedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Enabled: true - Line Width: 0.10000000149011612 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 213; 0; 0 - Name: CenterpointValidator(red3) - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 213; 0; 0 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 213; 0; 0 - TRUCK: - Alpha: 0.9990000128746033 - Color: 213; 0; 0 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/detection/centerpoint/validation/objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 213; 0; 0 - Value: true - Visualization Type: Normal - - BUS: - Alpha: 0.9990000128746033 - Color: 178; 255; 89 - CAR: - Alpha: 0.9990000128746033 - Color: 178; 255; 89 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 178; 255; 89 - Class: autoware_perception_rviz_plugin/DetectedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Enabled: true - Line Width: 0.10000000149011612 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 178; 255; 89 - Name: PointPainting(light_green1) - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 178; 255; 89 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 178; 255; 89 - TRUCK: - Alpha: 0.9990000128746033 - Color: 178; 255; 89 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/detection/pointpainting/objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 178; 255; 89 - Value: true - Visualization Type: Normal - - BUS: - Alpha: 0.9990000128746033 - Color: 118; 255; 3 - CAR: - Alpha: 0.9990000128746033 - Color: 118; 255; 3 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 118; 255; 3 - Class: autoware_perception_rviz_plugin/DetectedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Enabled: true - Line Width: 0.10000000149011612 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 118; 255; 3 - Name: PointPaintingROIFusion(light_green2) - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 118; 255; 3 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 118; 255; 3 - TRUCK: - Alpha: 0.9990000128746033 - Color: 118; 255; 3 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/detection/pointpainting/roi_fusion/objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 118; 255; 3 - Value: true - Visualization Type: Normal - - BUS: - Alpha: 0.9990000128746033 - Color: 100; 221; 23 - CAR: - Alpha: 0.9990000128746033 - Color: 100; 221; 23 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 100; 221; 23 - Class: autoware_perception_rviz_plugin/DetectedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Enabled: true - Line Width: 0.10000000149011612 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 100; 221; 23 - Name: PointPaintingValidator(light_green3) - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 100; 221; 23 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 100; 221; 23 - TRUCK: - Alpha: 0.9990000128746033 - Color: 100; 221; 23 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/detection/pointpainting/validation/objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 100; 221; 23 - Value: true - Visualization Type: Normal - - BUS: - Alpha: 0.9990000128746033 - Color: 255; 145; 0 - CAR: - Alpha: 0.9990000128746033 - Color: 255; 145; 0 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 255; 145; 0 - Class: autoware_perception_rviz_plugin/DetectedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Enabled: true - Line Width: 0.10000000149011612 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 255; 145; 0 - Name: DetectionByTracker(orange) - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 255; 145; 0 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 255; 145; 0 - TRUCK: - Alpha: 0.9990000128746033 - Color: 255; 145; 0 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/detection/detection_by_tracker/objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 255; 145; 0 - Value: true - Visualization Type: Normal - - BUS: - Alpha: 0.9990000128746033 - Color: 213; 0; 249 - CAR: - Alpha: 0.9990000128746033 - Color: 213; 0; 249 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 213; 0; 249 - Class: autoware_perception_rviz_plugin/DetectedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Enabled: true - Line Width: 0.10000000149011612 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 213; 0; 249 - Name: CameraLidarFusion(purple) - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 213; 0; 249 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 213; 0; 249 - TRUCK: - Alpha: 0.9990000128746033 - Color: 213; 0; 249 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/detection/clustering/camera_lidar_fusion/objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 213; 0; 249 - Value: true - Visualization Type: Normal - - BUS: - Alpha: 0.9990000128746033 - Color: 255; 255; 255 - CAR: - Alpha: 0.9990000128746033 - Color: 255; 255; 255 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 255; 255; 255 - Class: autoware_perception_rviz_plugin/DetectedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Enabled: true - Line Width: 0.10000000149011612 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 255; 255; 255 - Name: RadarFarObjects(white) - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 255; 255; 255 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 255; 255; 255 - TRUCK: - Alpha: 0.9990000128746033 - Color: 255; 255; 255 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/detection/radar/far_objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 255; 255; 255 - Value: true - Visualization Type: Normal - - BUS: - Alpha: 0.9990000128746033 - Color: 255; 234; 0 - CAR: - Alpha: 0.9990000128746033 - Color: 255; 234; 0 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 255; 234; 0 - Class: autoware_perception_rviz_plugin/DetectedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Enabled: true - Line Width: 0.10000000149011612 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 255; 234; 0 - Name: Detection(yellow) - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 255; 234; 0 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 255; 234; 0 - TRUCK: - Alpha: 0.9990000128746033 - Color: 255; 234; 0 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/detection/objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 255; 234; 0 - Value: true - Visualization Type: Normal - - BUS: - Alpha: 0.9990000128746033 - Color: 0; 230; 118 - CAR: - Alpha: 0.9990000128746033 - Color: 0; 230; 118 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 0; 230; 118 - Class: autoware_perception_rviz_plugin/TrackedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Dynamic Status: All - Enabled: true - Line Width: 0.10000000149011612 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 0; 230; 118 - Name: Tracking(green) - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 0; 230; 118 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 0; 230; 118 - TRUCK: - Alpha: 0.9990000128746033 - Color: 0; 230; 118 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/tracking/objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 0; 230; 118 - Value: true - Visualization Type: Normal - - BUS: - Alpha: 0.9990000128746033 - Color: 0; 176; 255 - CAR: - Alpha: 0.9990000128746033 - Color: 0; 176; 255 - CYCLIST: - Alpha: 0.9990000128746033 - Color: 0; 176; 255 - Class: autoware_perception_rviz_plugin/PredictedObjects - Confidence Interval: 95% - Display Acceleration: true - Display Existence Probability: false - Display Label: true - Display Pose Covariance: true - Display Predicted Path Confidence: true - Display Predicted Paths: true - Display Twist: true - Display Twist Covariance: false - Display UUID: true - Display Velocity: true - Display Yaw Covariance: false - Display Yaw Rate: false - Display Yaw Rate Covariance: false - Enabled: true - Line Width: 0.10000000149011612 - MOTORCYCLE: - Alpha: 0.9990000128746033 - Color: 0; 176; 255 - Name: Prediction(light_blue) - Namespaces: - {} - Object Fill Type: skeleton - PEDESTRIAN: - Alpha: 0.9990000128746033 - Color: 0; 176; 255 - Polygon Type: 3d - TRAILER: - Alpha: 0.9990000128746033 - Color: 0; 176; 255 - TRUCK: - Alpha: 0.9990000128746033 - Color: 0; 176; 255 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /perception/object_recognition/objects - UNKNOWN: - Alpha: 0.9990000128746033 - Color: 0; 176; 255 - Value: true - Visualization Type: Normal - Enabled: true - Name: Perception - - Class: rviz_common/Group - Displays: - - Class: rviz_common/Group - Displays: - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: LaneChangeLeft - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/debug/objects_of_interest/lane_change_left - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: LaneChangeRight - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/debug/objects_of_interest/lane_change_right - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: AvoidanceLeft - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/debug/objects_of_interest/static_obstacle_avoidance_left - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: AvoidanceRight - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/debug/objects_of_interest/static_obstacle_avoidance_right - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: AvoidanceByLCLeft - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/debug/objects_of_interest/avoidance_by_lc_left - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: AvoidanceByLCRight - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/debug/objects_of_interest/avoidance_by_lc_right - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: StartPlanner - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/debug/objects_of_interest/start_planner - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: GoalPlanner - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/debug/objects_of_interest/goal_planner - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: Crosswalk - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/debug/objects_of_interest/crosswalk - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: Intersection - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/debug/objects_of_interest/intersection - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: BlindSpot - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/debug/objects_of_interest/blind_spot - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: TrafficLight - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/debug/objects_of_interest/traffic_light - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: DetectionArea - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/debug/objects_of_interest/detection_area - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: NoStoppingArea - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/debug/objects_of_interest/no_stopping_area - Value: true - Enabled: true - Name: Objects Of Interest - Enabled: true - Name: Planning - - Class: rviz_common/Group - Displays: ~ - Enabled: true - Name: Control - Enabled: false - Name: Debug - Enabled: true - Global Options: - Background Color: 15; 20; 23 - Fixed Frame: map - Frame Rate: 30 - Name: root - Tools: - - Class: rviz_default_plugins/Interact - Hide Inactive Objects: true - - Class: rviz_default_plugins/MoveCamera - - Class: rviz_default_plugins/Select - - Class: rviz_default_plugins/FocusCamera - - Class: rviz_default_plugins/Measure - Line color: 128; 128; 0 - - Class: rviz_default_plugins/SetInitialPose - Covariance x: 0.25 - Covariance y: 0.25 - Covariance yaw: 0.06853891909122467 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /initialpose - - Class: rviz_default_plugins/SetGoal - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /planning/mission_planning/goal - - Class: tier4_adapi_rviz_plugins::RouteTool - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /rviz/routing/rough_goal - - Acceleration: 0 - Class: rviz_plugins/PedestrianInitialPoseTool - Interactive: false - Max velocity: 33.29999923706055 - Min velocity: -33.29999923706055 - Pose Topic: /simulation/dummy_perception_publisher/object_info - Target Frame: - Theta std deviation: 0.0872664600610733 - Velocity: 0 - X std deviation: 0.029999999329447746 - Y std deviation: 0.029999999329447746 - Z position: 1 - Z std deviation: 0.029999999329447746 - - Acceleration: 0 - Class: rviz_plugins/CarInitialPoseTool - H vehicle height: 2 - Interactive: false - L vehicle length: 4 - Max velocity: 33.29999923706055 - Min velocity: -33.29999923706055 - Pose Topic: /simulation/dummy_perception_publisher/object_info - Target Frame: - Theta std deviation: 0.0872664600610733 - Velocity: 3 - W vehicle width: 1.7999999523162842 - X std deviation: 0.029999999329447746 - Y std deviation: 0.029999999329447746 - Z position: 0 - Z std deviation: 0.029999999329447746 - - Acceleration: 0 - Class: rviz_plugins/BusInitialPoseTool - H vehicle height: 3.5 - Interactive: false - L vehicle length: 10.5 - Max velocity: 33.29999923706055 - Min velocity: -33.29999923706055 - Pose Topic: /simulation/dummy_perception_publisher/object_info - Target Frame: - Theta std deviation: 0.0872664600610733 - Velocity: 0 - W vehicle width: 2.5 - X std deviation: 0.029999999329447746 - Y std deviation: 0.029999999329447746 - Z position: 0 - Z std deviation: 0.029999999329447746 - - Class: rviz_plugins/MissionCheckpointTool - Pose Topic: /planning/mission_planning/checkpoint - Theta std deviation: 0.2617993950843811 - X std deviation: 0.5 - Y std deviation: 0.5 - Z position: 0 - - Class: rviz_plugins/DeleteAllObjectsTool - Pose Topic: /simulation/dummy_perception_publisher/object_info - Transformation: - Current: - Class: rviz_default_plugins/TF - Value: true - Views: - Current: - Angle: 0 - Class: rviz_default_plugins/TopDownOrtho - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Scale: 10 - Target Frame: viewer - Value: TopDownOrtho (rviz_default_plugins) - X: 0 - Y: 0 - Saved: - - Class: rviz_default_plugins/ThirdPersonFollower - Distance: 18 - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Focal Point: - X: 0 - Y: 0 - Z: 0 - Focal Shape Fixed Size: true - Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false - Name: ThirdPersonFollower - Near Clip Distance: 0.009999999776482582 - Pitch: 0.20000000298023224 - Target Frame: base_link - Value: ThirdPersonFollower (rviz) - Yaw: 3.141592025756836 - - Angle: 0 - Class: rviz_default_plugins/TopDownOrtho - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Invert Z Axis: false - Name: TopDownOrtho - Near Clip Distance: 0.009999999776482582 - Scale: 10 - Target Frame: viewer - Value: TopDownOrtho (rviz) - X: 0 - Y: 0 -Window Geometry: - AutowareDateTimePanel: - collapsed: false - AutowareStatePanel: - collapsed: false - Displays: - collapsed: false - Height: 939 - Hide Left Dock: false - Hide Right Dock: false - PointcloudOnCamera: - collapsed: false - QMainWindow State: 000000ff00000000fd0000000400000000000001ef00000349fc020000000ffb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006b00fffffffb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb00000024004100750074006f00770061007200650053007400610074006500500061006e0065006c01000000440000029b0000008100fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d0065007200610100000682000000eb0000000000000000fb0000000a0049006d0061006700650100000505000002680000000000000000fb0000002c0049006e0069007400690061006c0050006f007300650042007500740074006f006e00500061006e0065006c000000068f000000de0000000000000000fb0000002c0049006e0069007400690061006c0050006f007300650042007500740074006f006e00500061006e0065006c000000068f000000de0000000000000000fb00000030005200650063006f0067006e006900740069006f006e0052006500730075006c0074004f006e0049006d0061006700650000000246000000c10000002c00fffffffb0000002a004100750074006f0077006100720065004400610074006500540069006d006500500061006e0065006c0000000332000000720000004600fffffffb000000240050006f0069006e00740063006c006f00750064004f006e00430061006d006500720061000000039d000000560000002c00fffffffb0000002600530069006d0075006c00610074006500640043006c006f0063006b00500061006e0065006c01000002e6000000a70000007f00ffffff00000001000001ab00000349fc0200000004fb000000100044006900730070006c006100790073010000004400000122000000eb00fffffffc0000016d00000220000000da01000020fa000000000100000002fb0000000a0056006900650077007301000005d5000001ab0000010200fffffffb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000000ffffffff000000a400fffffffb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000e7a0000005afc0100000001fb0000000a00560069006500770073030000004e00000080000002e1000001970000000300000e7a0000005afc0100000002fb0000000800540069006d0065010000000000000e7a0000000000000000fb0000000800540069006d00650100000000000004500000000000000000000003d80000034900000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 - RecognitionResultOnImage: - collapsed: false - Selection: - collapsed: false - SimulatedClockPanel: - collapsed: false - Tool Properties: - collapsed: false - TrafficLightPublishPanel: - collapsed: false - Views: - collapsed: false - Width: 1920 - X: 0 - Y: 34 From 87537bd02e6479e0bb5f95d874822c8e81181c13 Mon Sep 17 00:00:00 2001 From: Masato Saeki <78376491+MasatoSaeki@users.noreply.github.com> Date: Wed, 15 Jan 2025 18:04:13 +0900 Subject: [PATCH 216/334] chore(autoware_traffic_light_occlusion_predictor): modify docs (#9820) * fix docs Signed-off-by: MasatoSaeki * fix docs Signed-off-by: MasatoSaeki --------- Signed-off-by: MasatoSaeki --- .../README.md | 25 +++++++++++-------- 1 file changed, 15 insertions(+), 10 deletions(-) diff --git a/perception/autoware_traffic_light_occlusion_predictor/README.md b/perception/autoware_traffic_light_occlusion_predictor/README.md index bc57dbea76c97..5d2e320dfc72a 100644 --- a/perception/autoware_traffic_light_occlusion_predictor/README.md +++ b/perception/autoware_traffic_light_occlusion_predictor/README.md @@ -1,8 +1,10 @@ -# The `autoware_traffic_light_occlusion_predictor` Package +# autoware_traffic_light_occlusion_predictor ## Overview `autoware_traffic_light_occlusion_predictor` receives the detected traffic lights rois and calculates the occlusion ratios of each roi with point cloud. +If that rois is judged as occlusion, color, shape, and confidence of `~/output/traffic_signals` become `UNKNOWN`, `UNKNOWN`, and `0.0`. +This node publishes when each car and pedestrian `traffic_signals` is arrived and processed. For each traffic light roi, hundreds of pixels would be selected and projected into the 3D space. Then from the camera point of view, the number of projected pixels that are occluded by the point cloud is counted and used for calculating the occlusion ratio for the roi. As shown in follow image, the red pixels are occluded and the occlusion ratio is the number of red pixels divided by the total pixel numbers. @@ -12,18 +14,20 @@ If no point cloud is received or all point clouds have very large stamp differen ## Input topics -| Name | Type | Description | -| -------------------- | ---------------------------------------------- | ------------------------ | -| `~input/vector_map` | autoware_map_msgs::msg::LaneletMapBin | vector map | -| `~/input/rois` | autoware_perception_msgs::TrafficLightRoiArray | traffic light detections | -| `~input/camera_info` | sensor_msgs::CameraInfo | target camera parameter | -| `~/input/cloud` | sensor_msgs::PointCloud2 | LiDAR point cloud | +| Name | Type | Description | +| ------------------------------------ | ------------------------------------------------ | -------------------------------- | +| `~/input/vector_map` | autoware_map_msgs::msg::LaneletMapBin | vector map | +| `~/input/car/traffic_signals` | tier4_perception_msgs::msg::TrafficLightArray | vehicular traffic light signals | +| `~/input/pedestrian/traffic_signals` | tier4_perception_msgs::msg::TrafficLightArray | pedestrian traffic light signals | +| `~/input/rois` | tier4_perception_msgs::msg::TrafficLightRoiArray | traffic light detections | +| `~/input/camera_info` | sensor_msgs::msg::CameraInfo | target camera parameter | +| `~/input/cloud` | sensor_msgs::msg::PointCloud2 | LiDAR point cloud | ## Output topics -| Name | Type | Description | -| -------------------- | ---------------------------------------------------- | ---------------------------- | -| `~/output/occlusion` | autoware_perception_msgs::TrafficLightOcclusionArray | occlusion ratios of each roi | +| Name | Type | Description | +| -------------------------- | --------------------------------------------- | -------------------------------------------------------------- | +| `~/output/traffic_signals` | tier4_perception_msgs::msg::TrafficLightArray | traffic light signals which occluded image results overwritten | ## Node parameters @@ -34,3 +38,4 @@ If no point cloud is received or all point clouds have very large stamp differen | `max_valid_pt_dist` | double | The points within this distance would be used for calculation | | `max_image_cloud_delay` | double | The maximum delay between LiDAR point cloud and camera image | | `max_wait_t` | double | The maximum time waiting for the LiDAR point cloud | +| `max_occlusion_ratio` | int | The maximum occlusion ratio for setting signal as unknown | From ab6c3b5bd159a723f7ed6836671d370a30929226 Mon Sep 17 00:00:00 2001 From: Masato Saeki <78376491+MasatoSaeki@users.noreply.github.com> Date: Wed, 15 Jan 2025 18:04:27 +0900 Subject: [PATCH 217/334] chore(autoware_traffic_light_multi_camera_fusion): modify docs (#9821) * fix docs Signed-off-by: MasatoSaeki * add condition Signed-off-by: MasatoSaeki --------- Signed-off-by: MasatoSaeki --- .../README.md | 31 ++++++++++++------- 1 file changed, 19 insertions(+), 12 deletions(-) diff --git a/perception/autoware_traffic_light_multi_camera_fusion/README.md b/perception/autoware_traffic_light_multi_camera_fusion/README.md index f7ee294cda147..b54c623f5d750 100644 --- a/perception/autoware_traffic_light_multi_camera_fusion/README.md +++ b/perception/autoware_traffic_light_multi_camera_fusion/README.md @@ -1,29 +1,36 @@ -# The `traffic_light_multi_camera_fusion` Package +# autoware_traffic_light_multi_camera_fusion ## Overview -`traffic_light_multi_camera_fusion` performs traffic light signal fusion which can be summarized as the following two tasks: +`autoware_traffic_light_multi_camera_fusion` performs traffic light signal fusion which can be summarized as the following two tasks: -1. Multi-Camera-Fusion: performed on single traffic light signal detected by different cameras. -2. Group-Fusion: performed on traffic light signals within the same group, which means traffic lights sharing the same regulatory element id defined in lanelet2 map. +1. Multi-Camera-Fusion: fusion each traffic light signal detected by different cameras. +2. Group-Fusion: Fusion each traffic light signal within the same group, which means traffic lights share the same regulatory element ID defined in lanelet2 map. + +The fusion method is below. + +1. Use the results of the new timestamp if the results are from the same sensor +2. Use the results that are not `elements.size() == 1 && color == UNKNOWN && shape == UNKNOWN` +3. Use the results that each vertex of ROI is not at the edge of the image +4. Use the results of high confidence ## Input topics For every camera, the following three topics are subscribed: -| Name | Type | Description | -| -------------------------------------- | ---------------------------------------------- | --------------------------------------------------- | -| `~//camera_info` | sensor_msgs::CameraInfo | camera info from traffic_light_map_based_detector | -| `~//rois` | tier4_perception_msgs::TrafficLightRoiArray | detection roi from traffic_light_fine_detector | -| `~//traffic_signals` | tier4_perception_msgs::TrafficLightSignalArray | classification result from traffic_light_classifier | +| Name | Type | Description | +| ----------------------------------------------------- | ------------------------------------------------ | ------------------------------------- | +| `~//camera_info` | sensor_msgs::msg::CameraInfo | camera info from map_based_detector | +| `~//detection/rois` | tier4_perception_msgs::msg::TrafficLightRoiArray | detection roi from fine_detector | +| `~//classification/traffic_signals` | tier4_perception_msgs::msg::TrafficLightArray | classification result from classifier | You don't need to configure these topics manually. Just provide the `camera_namespaces` parameter and the node will automatically extract the `` and create the subscribers. ## Output topics -| Name | Type | Description | -| -------------------------- | ------------------------------------------------- | ---------------------------------- | -| `~/output/traffic_signals` | autoware_perception_msgs::TrafficLightSignalArray | traffic light signal fusion result | +| Name | Type | Description | +| -------------------------- | ----------------------------------------------------- | ---------------------------------- | +| `~/output/traffic_signals` | autoware_perception_msgs::msg::TrafficLightGroupArray | traffic light signal fusion result | ## Node parameters From 65f6417db4bf4bda100eb961a841f6d31c94c05b Mon Sep 17 00:00:00 2001 From: Masato Saeki <78376491+MasatoSaeki@users.noreply.github.com> Date: Wed, 15 Jan 2025 18:04:41 +0900 Subject: [PATCH 218/334] chore(autoware_traffic_light_classifier): modify docs (#9819) * modify docs Signed-off-by: MasatoSaeki * style(pre-commit): autofix * fix docs Signed-off-by: MasatoSaeki --------- Signed-off-by: MasatoSaeki Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../README.md | 32 +++++++++++++------ 1 file changed, 22 insertions(+), 10 deletions(-) diff --git a/perception/autoware_traffic_light_classifier/README.md b/perception/autoware_traffic_light_classifier/README.md index 6e720aabc7593..7dcd4a73380bb 100644 --- a/perception/autoware_traffic_light_classifier/README.md +++ b/perception/autoware_traffic_light_classifier/README.md @@ -1,22 +1,33 @@ -# traffic_light_classifier +# autoware_traffic_light_classifier ## Purpose -traffic_light_classifier is a package for classifying traffic light labels using cropped image around a traffic light. This package has two classifier models: `cnn_classifier` and `hsv_classifier`. +`autoware_traffic_light_classifier` is a package for classifying traffic light labels using cropped image around a traffic light. This package has two classifier models: `cnn_classifier` and `hsv_classifier`. ## Inner-workings / Algorithms +If height and width of `~/input/rois` is `0`, color, shape, and confidence of `~/output/traffic_signals` become `UNKNOWN`, `CIRCLE`, and `0.0`. +If `~/input/rois` is judged as backlight, color, shape, and confidence of `~/output/traffic_signals` become `UNKNOWN`, `UNKNOWN`, and `0.0`. + ### cnn_classifier -Traffic light labels are classified by EfficientNet-b1 or MobileNet-v2. -Totally 83400 (58600 for training, 14800 for evaluation and 10000 for test) TIER IV internal images of Japanese traffic lights were used for fine-tuning. -The information of the models is listed here: +Traffic light labels are classified by EfficientNet-b1 or MobileNet-v2. +We trained classifiers for vehicular signals and pedestrian signals separately. +For vehicular signals, a total of 83400 (58600 for training, 14800 for evaluation and 10000 for test) TIER IV internal images of Japanese traffic lights were used for fine-tuning. | Name | Input Size | Test Accuracy | | --------------- | ---------- | ------------- | | EfficientNet-b1 | 128 x 128 | 99.76% | | MobileNet-v2 | 224 x 224 | 99.81% | +For pedestrian signals, a total of 21199 (17860 for training, 2114 for evaluation and 1225 for test) TIER IV internal images of Japanese traffic lights were used for fine-tuning. +The information of the models is listed here: + +| Name | Input Size | Test Accuracy | +| --------------- | ---------- | ------------- | +| EfficientNet-b1 | 128 x 128 | 97.89% | +| MobileNet-v2 | 224 x 224 | 99.10% | + ### hsv_classifier Traffic light colors (green, yellow and red) are classified in HSV model. @@ -52,11 +63,12 @@ These colors and shapes are assigned to the message as follows: ### Node Parameters -| Name | Type | Description | -| --------------------- | ----- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| `classifier_type` | int | if the value is `1`, cnn_classifier is used | -| `data_path` | str | packages data and artifacts directory path | -| `backlight_threshold` | float | If the intensity get grater than this overwrite with UNKNOWN in corresponding RoI. Note that, if the value is much higher, the node only overwrites in the harsher backlight situations. Therefore, If you wouldn't like to use this feature set this value to `1.0`. The value can be `[0.0, 1.0]`. The confidence of overwritten signal is set to `0.0`. | +| Name | Type | Description | +| ----------------------------- | ------ | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `classifier_type` | int | If the value is `1`, cnn_classifier is used | +| `data_path` | str | Packages data and artifacts directory path | +| `backlight_threshold` | double | If the intensity of light is grater than this threshold, the color and shape of the corresponding ROI will be overwritten with UNKNOWN, and the confidence of the overwritten signal will be set to `0.0`. The value should be set in the range of `[0.0, 1.0]`. If you wouldn't like to use this feature, please set it to `1.0`. | +| `classify_traffic_light_type` | int | If the value is `0`, vehicular signals are classified. If the value is `1`, pedestrian signals are classified. | ### Core Parameters From b69241f6659c042a05bc9362c3d254e25fbaa290 Mon Sep 17 00:00:00 2001 From: Masato Saeki <78376491+MasatoSaeki@users.noreply.github.com> Date: Wed, 15 Jan 2025 18:04:56 +0900 Subject: [PATCH 219/334] chore(autoware_crosswalk_traffic_light_estimator): fix docs (#9822) * fix docs Signed-off-by: MasatoSaeki * fix docs Signed-off-by: MasatoSaeki * add tlr output image Signed-off-by: MasatoSaeki * modify sentense Signed-off-by: MasatoSaeki * modify sentense Signed-off-by: MasatoSaeki * refactor readme Signed-off-by: MasatoSaeki * fix docs Signed-off-by: MasatoSaeki * fix Signed-off-by: MasatoSaeki * style(pre-commit): autofix --------- Signed-off-by: MasatoSaeki Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../README.md | 81 ++++++++++++++---- .../images/flashing_state.png | Bin 0 -> 24574 bytes .../images/traffic_light.png | Bin 0 -> 54297 bytes 3 files changed, 63 insertions(+), 18 deletions(-) create mode 100644 perception/autoware_crosswalk_traffic_light_estimator/images/flashing_state.png create mode 100644 perception/autoware_crosswalk_traffic_light_estimator/images/traffic_light.png diff --git a/perception/autoware_crosswalk_traffic_light_estimator/README.md b/perception/autoware_crosswalk_traffic_light_estimator/README.md index b14fefbd43beb..1b24b115f5812 100644 --- a/perception/autoware_crosswalk_traffic_light_estimator/README.md +++ b/perception/autoware_crosswalk_traffic_light_estimator/README.md @@ -1,40 +1,85 @@ -# crosswalk_traffic_light_estimator +# autoware_crosswalk_traffic_light_estimator ## Purpose -`crosswalk_traffic_light_estimator` is a module that estimates pedestrian traffic signals from HDMap and detected vehicle traffic signals. +`autoware_crosswalk_traffic_light_estimator` estimates pedestrian traffic signals which can be summarized as the following two tasks: + +- Estimate pedestrian traffic signals that are not subject to be detected by perception pipeline. +- Estimate whether pedestrian traffic signals are flashing and modify the result. + +This module works without `~/input/route`, but its behavior is outputting the subscribed results as is. ## Inputs / Outputs ### Input -| Name | Type | Description | -| ------------------------------------ | ------------------------------------------------ | ------------------ | -| `~/input/vector_map` | `autoware_map_msgs::msg::LaneletMapBin` | vector map | -| `~/input/route` | `autoware_planning_msgs::msg::LaneletRoute` | route | -| `~/input/classified/traffic_signals` | `tier4_perception_msgs::msg::TrafficSignalArray` | classified signals | +| Name | Type | Description | +| ------------------------------------ | ----------------------------------------------------- | ------------------ | +| `~/input/vector_map` | autoware_map_msgs::msg::LaneletMapBin | vector map | +| `~/input/route` | autoware_planning_msgs::msg::LaneletRoute | optional: route | +| `~/input/classified/traffic_signals` | autoware_perception_msgs::msg::TrafficLightGroupArray | classified signals | ### Output -| Name | Type | Description | -| -------------------------- | ------------------------------------------------------- | --------------------------------------------------------- | -| `~/output/traffic_signals` | `autoware_perception_msgs::msg::TrafficLightGroupArray` | output that contains estimated pedestrian traffic signals | +| Name | Type | Description | +| -------------------------- | ----------------------------------------------------- | --------------------------------------------------------- | +| `~/output/traffic_signals` | autoware_perception_msgs::msg::TrafficLightGroupArray | output that contains estimated pedestrian traffic signals | ## Parameters -| Name | Type | Description | Default value | -| :---------------------------- | :------- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ | -| `use_last_detect_color` | `bool` | If this parameter is `true`, this module estimates pedestrian's traffic signal as RED not only when vehicle's traffic signal is detected as GREEN/AMBER but also when detection results change GREEN/AMBER to UNKNOWN. (If detection results change RED or AMBER to UNKNOWN, this module estimates pedestrian's traffic signal as UNKNOWN.) If this parameter is `false`, this module use only latest detection results for estimation. (Only when the detection result is GREEN/AMBER, this module estimates pedestrian's traffic signal as RED.) | `true` | -| `last_detect_color_hold_time` | `double` | The time threshold to hold for last detect color. | `2.0` | +| Name | Type | Description | Default value | +| :---------------------------- | :----- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ | +| `use_last_detect_color` | bool | If this parameter is `true`, this module estimates pedestrian's traffic signal as RED not only when vehicle's traffic signal is detected as GREEN/AMBER but also when detection results change GREEN/AMBER to UNKNOWN. (If detection results change RED or AMBER to UNKNOWN, this module estimates pedestrian's traffic signal as UNKNOWN.) If this parameter is `false`, this module use only latest detection results for estimation. (Only when the detection result is GREEN/AMBER, this module estimates pedestrian's traffic signal as RED.) | true | +| `last_detect_color_hold_time` | double | The time threshold to hold for last detect color. The unit is second. | 2.0 | +| `last_colors_hold_time` | double | The time threshold to hold for history detected pedestrian traffic light color. The unit is second. | 1.0 | ## Inner-workings / Algorithms +When the pedestrian traffic signals **are detected** by perception pipeline + +- If estimates the pedestrian traffic signals are flashing, overwrite the results +- Prefer the output from perception pipeline, but overwrite it if the pedestrian traffic signals are invalid(`no detection`, `backlight`, or `occlusion`) + +When the pedestrian traffic signals **are NOT detected** by perception pipeline + +- Estimate the color of pedestrian traffic signals based on detected vehicle traffic signals, HDMap, and route + +### Estimate whether pedestrian traffic signals are flashing + +```plantumul +start +if (the pedestrian traffic light classification result exists)then + : update the flashing flag according to the classification result(in_signal) and last_signals + if (the traffic light is flashing?)then(yes) + : update the traffic light state + else(no) + : the traffic light state is the same with the classification result +if (the classification result not exists) + : the traffic light state is the same with the estimation + : output the current traffic light state +end +``` + +#### Update flashing flag + +

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

8$+XP=l#U|mr)63y?Tn+Jtb=m4PNJN;TY?N?g<2; zo*`zSMMqnX>GfQXlFS?$(kFr6Q!RHw&-5lAltBi?GYLY_g^~9~9*T-_)`c(0xoL<| z1hQUYr7*o>2oyr16byEnmmX3{&S(9pD#|u@k^!QQWYtwqCz#+Q0Cd=_NP`=1ILOF> zAPco|J=X;vyhBR=GQGapTHNA>*Gch!>HnryBX@BCoz(9%+ z5F)F1EUnIOoQ^#6_9rWyUkhE(kx!GfQe^{e9d0{}PzgnlD{uPdbbO9oJw1KubgZK~Y9 zV0Fi0@i+4(Cf>sBsqQ(fp*}!MJIEM95~T6>7BBLjbK@EyfmW~M*f%YUGZB? zj4FB7#{-$r8Ni_xs}+JItO8+hq(XU0_h=4RF5S2Pk}iSlMW#3fi{kTj=9~w;*`Gwo z{jTM<1YhtnIW&I$)~Jc7%4o zQTDx?@zwrmlnU-#5sf&5$)Dr}A8L{_Q?PH&D}HIMav?1)UZlkjKv|I&9=SpVOZ6jd z$~+f9iBl+pkAZWO_Nv_06)|CbA9olo{5l^Pg=tCfp1Sr=^@? zzfz3AR)PNcS5A2{1ihtSMp9Z?P3)0%m}Ui?J4P5fXp@5|${A14TL}Qzu6C%ma1V4 zyOl422S}qW1E)Rcw)OAi5BSJu08Ly)Pe%~tH2bI8{v0D(?U&hltLxQ`%=T=Y3 zP^yS>E7Ufu(2t~}4$9|E8_6uPuG&qr+NXXk%8#iRmv)Z}3XzKBU69z5tGl+sdQUq- zW>g9H)H>HIAGJN5DU3ygsS-8DQLNkYpsCZl)UzXEm-%;=6bXTj24%hLZErv@WBQBR z`rJdX0%%5TARpVTi%TW84asX1KBZjT{23%`Z zqHF^B#b>ahx0kCP5^KBJb=t!;zCXxzV%Gz9xV_!@pF*QP?8mF*$!f!QZuyeC{{!q~ z91Y%CLRa%!kh40+gnUrytyBLO*x_?ycAU;C1S1EfKvigk&vb!U^mzpWk^2Qb{mZ|a?lzwyrUcQVoeRvzfWplv zB#cxiaqU-@PUvT3Kt1l`$km}*95qhkJ|WZGU!x~*xZ$&KsJ-jWH_XD`;}8%T>0kAf zANZ>|U2iN?2lC2#zU>){h(FH?4ThpZJMIBs{nr6eH=x~g0wflF2fk}Gs0%={0Qmei zKH8R!A|@pJ)wun3B_L!@EBrDA1a@T=tSWO9A!*e}XW2Zq$XV#+=LxD6%MygULWH^R zu~cgZ*zEHItV07AcgI)J!q?I@Ykk``-~LFszJ>x%!v}+lhy|dvqUt~lb*W&w4Fv0c zLrkTB@v#PUBY>cVF>k(E?3T})!scyYFhf6kOkY^NTay2>Z5Gme!kl{b6zt<&Y%)2$ zE)KiUjIawi*9FBqk4=VQmALxv?$ufudb>)H{|EDtb(cN|l1iPd{SIo^Hr%iCEOA`O6`?KWsqhkEwpAgX6^Ee-e=C_+m_NK7%lj7g?S;KL`aA%lEU04i-_d7t}QoU+QUlb zaS>O!mmV*+WdSmk{YJQ2p#=d6W4)UAd8q)!1)*ZKq6q+q30PQF2g+J$V-|34m_{Ca zHZHl{(asTNPXf)?6p8wcge-&!;3Ktll`6azlGPMrk2-PI4m^DfN%}=tpEnqwmZvE) zyDrZh&?6B5wYC7k(`y^0007xfP`~S79=2DNl zkDF7Fvx0)nWZPJR=nX6Zr#4^;TS3QmbfqC#Y_3thWBf9rx(zquzp81RX(FOuyZ{r6 z2z;0OKUCIicSS}Bd3jKBeuhS#eW#Ic6wPXloq;PT@*qoqc+&$iiv1=2v03X9DAO7r z!M+mFRt!uDzx2vbExxcK;2yF1T-E0EJHcnb$1h@?&O#ZSH=)2t5%pW@@B=|I!%~O- zfUe4EAg`}*6zz`)kLp4#_Eg{aK}gMajiJp(eDj-=b|m%tb1I$}k)lLiJ38nURBqh; zviPb}lC8A2*8;f@YNSqS1@X%}CKNaXw?NTi_zFbknOu=k{0CS)#OBut{{TLDE-|B6 z*GE1mP^qY^L>HP_8!`S`uaR%Kou?i2?Xxz*%NeR(D{>*|=*~6c3SYBnr+jg*+S%X# zO9ToO)ZjgQ1e6D#ByXLl#T0TYqzYFWr1>5n#Um-P*{w3oB!siPPi3%g-#AqRy(L=DVnM-V$1Ic5s1x=w~R%PXr)c5z^Zek ztG`%&t-wD2nU=6oIrwHu7b^L8H~F)Qep7a@?6xX3M2w4_u)>%z{jNagj|NnADVdf^gZbrrnQs-~&NZuE&-T){j?I`xQ9C zZaQ{pU+oaafF23EZ~(D;Rxtq!@=qg(jPeBlKAo8l_WmhYU#xcf9AV0m1u42Vda5_CDHKg6Li z-lIEkP?-*r-#^VaKF#DG-G!}>hDEiMC&jdn=@!*4bK$6fpCH=r)F&ZZ2ovEiHc9W3gffMN9IBM>qJ>C zNwS`sas8ED+hYdaCV6;KYmL#JoA~kO)@FIx^=K*WX#3(}Eu|IZ=+$c+8U)n`GV1$J|+6eD+M>?;Uf83{eB7aQK6LGMysY%72Gl$8)qnd)H-?uMxZx>D!5 zdBhjpMpYH#-_@&l!BhrkE(>4umdZ=fgECV>nLLucY9Gm|*ZHn~eyt=|E%!e>{DQVc z(qsg!^shTMa~c2DNjIE5-xIU{SclW&d_ZhAx^#Pk@7nCwv#cl6@Pu(EA8ytfZs&x3 zEH}OSbhQ@YkE)6+r7+*#wx%2gSF?i0z0hJ1TpkoWE2|=@)DAfn$|G}Vsq0fQ)y6+u zot&biLOzIOI!=G0N|XV)nQesiFY~BcS4ufujiZ)?xpgE%S&)zl$eK?epBy%t{%OKxGfgj!UQ;4h}0_3b6CC!rKe^e-EvY5rG+B zkJvJg--i}QbMJQ8dcu4mG);6Ty&b(_AFHTcmy7EToDWs&eeJ?)*IUufyz12{Te#g} zRHt#u$MYrvyl`7yO5<()y(K4`$?+&zMN}1AZEY7OffneVTH2&@SJC40Y>`X&e*P6F zcRFl8(isDqEfKNPTHFMaNk*lc7~53TdIO6}+t_BmJ9Ozfr5x#Ny=q(Fq8vy|w-QDd z9z7tonB6%i9z};~A$FonIA8+pKa4aRJQzk4b$kaL<9M4bg&Uu4_D4Z|Y7vdnb+VD^ zUvh`^$G#KtYbK6#4Fs`6Dk^kxF)>{+SIz?O9@i5Ux?+d%M)vnL=W97;^p!V0IV(L* zQi_UkDS{XJkvu;3q*nR}B5FTruUhMU+Ydi+Qqt`;RTUC~*JNbkszD}|50g0J9B%rA zgn9^?Ku18mWfQlJ&-MqB5{>U&*>1!0$aaD1UGp8v2NJ|)sVHA?gCVY|g0a;PIveYw+x^V; zpZ@loLMtpRDCGH8M~J;614Wq^*s%mm_xDK9ZbFK>yRU10{ysV5c%}3cXXdb7Q{RV^ zUv1d-=}MPZM*MVI?l-G6D&1^3N%tWl$CXO zN20FbN8&4dvFi#s*()oOz6pCCYNTXtALu)WGs!*)p_bwsV@|g-jaVidUG0f_O6bK@ zxg%};5~OmP?2e52$)y3#xwzrr5w*5|O}1CiViHCSI^z3UP-8{X$h*~r)1DDQf_=7# z#)Y{(+%D$!9MflVB*pH|aq-;y4I{EN3BXqo3pZX_-PjfcpZ7dU-AGw;4g zeO@3fL3ox?#mWE$)ip1sXK%{(DZ`hj)KLf_%n;uIf=9;XnA}o0TW9ly!}PaECh(ws zMZOoKUtq_{G+IQsZ-u|wLtuI2C-rVM>(#JFn?NN{mg?ynK1%p-I7IB&7v5?Txz@F+ zKNuB-MizxLFW?=2?jUtDEc&V@Y5Zbp!{Y(Vfb+hH9m(pB>{D0t?7&c$?Khx$j6J`5Zh+s;;|a^3<#%NU8lX?5i%xN~&NCg?Tms7^bq|ENq^|5SY1J%? zrO?05^hrT!cH?Ev3!hd*8H-<}k+BM!9PliCO}>Xj(l3iPm@Vin!XD#c#Di~!TwO~S zoE|E(fCD3~^#v*_=<9?=_Hg%I2LjA~pn=cuAekmlCf-C*MMIO@1Pn29$wT&?-?21| z3E64`{4{E$=%HR`9UNS=Md_zx^Z8GWS2Ojd`vd3%Y^s9Wcbq2+`%IEF3kg4@7_=z- zIEnmW`A^J__q~RNc+FYT2U(`u#zD&g*;OMGn1@tzE?$TiQLbYn^zl^l?1Urb%~X<^i)y#t(7YmF=4@=dkiZ0cWxiyY}f_A zS}ebg057`gM%^#IpXi9$aVDN%33FM(43E5&AUhrpUYYQ6MW`EuC6X@xXI&w zRVkAU2S=4S(Rt$il29@xtk5^}&Ev^?7Mu~?!Saboh-KWZdB-ZDr}!4(vG@Xu2I`z8vB`{zhnmRDs~^WNFKep z-_ZKKcl(gOdnb{6vyf?M=Y9{OIWLC^vcC5JN}&$R+x_-+xKzGETaD3;!p=s&@_NiP z0N!wJQDR5br!PnSmCIL($L}D1cqFy(o>o{Q%Au1-JepZa&soeDmlj!wnhK~rn83L) zab~43Z+f*yftf>`V_NutktWk(x-7RL@DRl3GjjD;xzSI;pNK7OY2b|FGwFw|``*_p z14JGT__`Dfq7D#!_C{WD#~IC=EGumo;$qzv-->lSxz5o#UD+c;?i&%7e=}6Nz=zYn z^W05aXM;*xdVhIXux^`Qk`l%hx;k=PfZ|*#KKF52l=e_WVQoYQ8^RP&pPqL7MHj8^ zkX&k5cu_Ho^OF2|TakxP{e+in)||XoO(CjXx7|!T*BRzv^5wQ!jY%QyFB6NCJ05Il zW^g2rwBZNF#!a{-)1c&H(!u_%JDQD`|C$HKx7mn`>!;rl8^=tqM=w2cYMxvsTct-T zScP)g@o6(}+vr1@zs`K-8Wf%uTX(>aXr!3IM=UgC*Ig+s&O7n_co_m=u?fz1gW1(A zxPqbsuc}#4hUWb|($Y@7AIE-LM%K1?HJ3)`KH`-Z=Iz}4?fI#6zQPMt*GEbTs$ANk zb``$AR`q+Wtz(T@uCRdCks?dhZMjW+CN^8;%gMOAs3Ebr$UyeA+1>1Ts<-513P#dK z0fmO7q=5~d^mG@Plb`KAi(l=pisTn+Y6fM9y@xa$Cl70q*FDuX7QFp=^Xo(DnylM| zjj}5C=5WZpUmdwWl5%1A*3T*;YIDSCZ+mcy>dp|CR(OpJoFMZvRnv`oF}AaWSWP8w zOe9)?x146IcW|(Y2yWpChz2`0anyo;ot%~B-)^SmiyE06MfqI$3ril1EbVCAfZ zUK8mw z9uxhLN$Iib?U?}Uu$fj9YpbFu-&hm*`XaQcDn zm&hQQ-i07mEosP z{oG{kOba*PJ#!ZY6-TKFY{-WaYOiFkvLYJRMj->=%ZPcnh zto3@Qz&Kl{lSfqc*5d=oy%sAsI@ri0;=(qlJ1|1{fHo}hB1>paazF3zcc_*!l~R3F z%`i_>WwEzb?os&ahhi7W)k}vSE+k>yTcC+skpalEOPYW9P>8aX9jiadWR+rhxJ5xb zbsTLP3CV#&RSuW!*Nrjmuv+N#{Fl3O!Wulq-r4G;cNqQVo#G$|2yx&See+M$PcNC5 zOY;snU+%ro@ro<9gBg147IPXDf60Bp6~(Po$5>;=)FI_}He%K^Cwik{L0FX$Wn-l-5If`C_1=N!ogW!U zdr2F70Ae&W(B|GqK1S_{@ZO|y+Qs5r;$$($hzE{)<@(|Nbhms4v{!!aDX5h7XjOT?$1bkp&6oQLX0B5O-+gv` z#)luCm1#+JaWwV*7nZB)`_5$u;5y7MTiVnjx|eixHmY@>A*%5U2-@a9Kga^drJ9dx zA|x;{0-LGw&mJ(c``&a6-SrTq>X~U~ySehb^UBE^YZhxsv@YPR(FjMm!hQ3T9Z(6uI=r$ZJR`yH;=mEJ37!mO|4zTP)*!d}_Xk2o zpcmQm$+xH?h(K4q=Zlyc@K>L&h^q9pf1e191AVgoef0m=P3!6g9}s+VwYmTOzHV$| z-r93_AfSPd1SyyW`8h{3`p?7sO{~1n{^V7LSpNnh4e+@Je@4pZ9 wRR-d;f0xnsZr~7f;L3&r+MqsPk)I#&J?Y3JpgvdeFMvx#5F${*r}^vu0SvkRuK)l5 literal 0 HcmV?d00001 From a2755a4926c41618c2fbd4da41324f46cca0b7f8 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Thu, 16 Jan 2025 10:01:43 +0900 Subject: [PATCH 220/334] fix(mrm_handler): simplify hazard command choice (#9929) Signed-off-by: Ryuta Kambe --- system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp | 7 +------ 1 file changed, 1 insertion(+), 6 deletions(-) diff --git a/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp b/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp index 4022bdaadebef..b5f4bbaeefc46 100644 --- a/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp +++ b/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp @@ -115,12 +115,7 @@ void MrmHandler::publishHazardCmd() HazardLightsCommand msg; msg.stamp = this->now(); - if (is_emergency_holding_) { - // turn hazard on during emergency holding - msg.command = HazardLightsCommand::ENABLE; - } else if (isEmergency() && param_.turning_hazard_on.emergency) { - // turn hazard on if vehicle is in emergency state and - // turning hazard on if emergency flag is true + if (param_.turning_hazard_on.emergency && isEmergency()) { msg.command = HazardLightsCommand::ENABLE; } else { msg.command = HazardLightsCommand::NO_COMMAND; From 347a2e48109452c70447ce219a207b5fd75591f1 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 16 Jan 2025 13:34:45 +0900 Subject: [PATCH 221/334] fix(goal_planner): fix geometric pull over (#9932) Signed-off-by: kosuke55 --- .../src/pull_over_planner/geometric_pull_over.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp index bf2ce86b49bab..44dca13ccfd66 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp @@ -28,6 +28,7 @@ namespace autoware::behavior_path_planner GeometricPullOver::GeometricPullOver( rclcpp::Node & node, const GoalPlannerParameters & parameters, const bool is_forward) : PullOverPlannerBase{node, parameters}, + parallel_parking_parameters_{parameters.parallel_parking_parameters}, lane_departure_checker_{ lane_departure_checker::Param{parameters.lane_departure_check_expansion_margin}, vehicle_info_}, is_forward_{is_forward}, From e09193784833044b8597c4d3dd7dda9bf169de74 Mon Sep 17 00:00:00 2001 From: mkquda <168697710+mkquda@users.noreply.github.com> Date: Thu, 16 Jan 2025 13:51:37 +0900 Subject: [PATCH 222/334] feat(lane_change): ensure path generation doesn't exceed time limit (#9908) * add time limit for lane change candidate path generation Signed-off-by: mohammad alqudah * apply time limit for frenet method as well Signed-off-by: mohammad alqudah * ensure param update value is valid Signed-off-by: mohammad alqudah * fix param update initial value Signed-off-by: mohammad alqudah * fix spelling Signed-off-by: mohammad alqudah * fix param update initial values Signed-off-by: mohammad alqudah --------- Signed-off-by: mohammad alqudah --- .../README.md | 1 + .../config/lane_change.param.yaml | 1 + .../structs/parameters.hpp | 1 + .../src/manager.cpp | 52 +++++++++++++------ .../src/scene.cpp | 18 +++++-- 5 files changed, 52 insertions(+), 21 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md index ee371f8592833..20fd564049133 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md @@ -1039,6 +1039,7 @@ The following parameters are configurable in [lane_change.param.yaml](https://gi | Name | Unit | Type | Description | Default value | | :------------------------------------------- | ------ | ------ | ---------------------------------------------------------------------------------------------------------------------- | ------------------ | +| `time_limit` | [ms] | double | Time limit for lane change candidate path generation | 50.0 | | `backward_lane_length` | [m] | double | The backward length to check incoming objects in lane change target lane. | 200.0 | | `backward_length_buffer_for_end_of_lane` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change | 3.0 | | `backward_length_buffer_for_blocking_object` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change when there is an object in front | 3.0 | diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml index df9491576a4ee..15eb23daecf95 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml @@ -1,6 +1,7 @@ /**: ros__parameters: lane_change: + time_limit: 50.0 # [ms] backward_lane_length: 200.0 backward_length_buffer_for_end_of_lane: 3.0 # [m] backward_length_buffer_for_blocking_object: 3.0 # [m] diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp index f0adcb1d69b42..60386f535fc64 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp @@ -162,6 +162,7 @@ struct Parameters FrenetPlannerParameters frenet{}; // lane change parameters + double time_limit{50.0}; double backward_lane_length{200.0}; double backward_length_buffer_for_end_of_lane{0.0}; double backward_length_buffer_for_blocking_object{0.0}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp index 07b05ab0ea131..f26cf79e8b120 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp @@ -190,6 +190,7 @@ LCParamPtr LaneChangeModuleManager::set_params(rclcpp::Node * node, const std::s } // lane change parameters + p.time_limit = getOrDeclareParameter(*node, parameter("time_limit")); p.backward_lane_length = getOrDeclareParameter(*node, parameter("backward_lane_length")); p.backward_length_buffer_for_end_of_lane = getOrDeclareParameter(*node, parameter("backward_length_buffer_for_end_of_lane")); @@ -313,6 +314,17 @@ void LaneChangeModuleManager::updateModuleParams(const std::vectortime_limit; + updateParam(parameters, ns + "time_limit", time_limit); + if (time_limit >= 10.0) { + p->time_limit = time_limit; + } else { + RCLCPP_WARN_THROTTLE( + node_->get_logger(), *node_->get_clock(), 1000, + "WARNING! Parameter 'time_limit' is not updated because the value (%.3f ms) is not valid, " + "keep current value (%.3f ms)", + time_limit, p->time_limit); + } updateParam(parameters, ns + "backward_lane_length", p->backward_lane_length); updateParam( parameters, ns + "backward_length_buffer_for_end_of_lane", @@ -349,25 +361,27 @@ void LaneChangeModuleManager::updateModuleParams(const std::vectortrajectory.lane_changing_decel_factor); updateParam( parameters, ns + "th_prepare_curvature", p->trajectory.th_prepare_curvature); - int longitudinal_acc_sampling_num = 0; + int longitudinal_acc_sampling_num = p->trajectory.lon_acc_sampling_num; updateParam(parameters, ns + "lon_acc_sampling_num", longitudinal_acc_sampling_num); if (longitudinal_acc_sampling_num > 0) { p->trajectory.lon_acc_sampling_num = longitudinal_acc_sampling_num; } else { - RCLCPP_WARN_ONCE( - node_->get_logger(), - "Parameter 'lon_acc_sampling_num' is not updated because the value (%d) is not positive", + RCLCPP_WARN_THROTTLE( + node_->get_logger(), *node_->get_clock(), 1000, + "WARNING! Parameter 'lon_acc_sampling_num' is not updated because the value (%d) is not " + "positive", longitudinal_acc_sampling_num); } - int lateral_acc_sampling_num = 0; + int lateral_acc_sampling_num = p->trajectory.lat_acc_sampling_num; updateParam(parameters, ns + "lat_acc_sampling_num", lateral_acc_sampling_num); if (lateral_acc_sampling_num > 0) { p->trajectory.lat_acc_sampling_num = lateral_acc_sampling_num; } else { - RCLCPP_WARN_ONCE( - node_->get_logger(), - "Parameter 'lat_acc_sampling_num' is not updated because the value (%d) is not positive", + RCLCPP_WARN_THROTTLE( + node_->get_logger(), *node_->get_clock(), 1000, + "WARNING! Parameter 'lat_acc_sampling_num' is not updated because the value (%d) is not " + "positive", lateral_acc_sampling_num); } @@ -409,8 +423,8 @@ void LaneChangeModuleManager::updateModuleParams(const std::vectortrajectory.lat_acc_map = lat_acc_map; } else { - RCLCPP_WARN_ONCE( - node_->get_logger(), + RCLCPP_WARN_THROTTLE( + node_->get_logger(), *node_->get_clock(), 1000, "Mismatched size for lateral acceleration. Expected size: %lu, but velocity: %lu, " "min_values: %lu, max_values: %lu", std::max(2ul, velocity.size()), velocity.size(), min_values.size(), max_values.size()); @@ -515,28 +529,32 @@ void LaneChangeModuleManager::updateModuleParams(const std::vectorcancel.enable_on_prepare_phase; updateParam(parameters, ns + "enable_on_prepare_phase", enable_on_prepare_phase); if (!enable_on_prepare_phase) { - RCLCPP_WARN_ONCE(node_->get_logger(), "WARNING! Lane Change cancel function is disabled."); + RCLCPP_WARN_THROTTLE( + node_->get_logger(), *node_->get_clock(), 1000, + "WARNING! Lane Change cancel function is disabled."); p->cancel.enable_on_prepare_phase = enable_on_prepare_phase; } - bool enable_on_lane_changing_phase = true; + bool enable_on_lane_changing_phase = p->cancel.enable_on_lane_changing_phase; updateParam( parameters, ns + "enable_on_lane_changing_phase", enable_on_lane_changing_phase); if (!enable_on_lane_changing_phase) { - RCLCPP_WARN_ONCE(node_->get_logger(), "WARNING! Lane Change abort function is disabled."); + RCLCPP_WARN_THROTTLE( + node_->get_logger(), *node_->get_clock(), 1000, + "WARNING! Lane Change abort function is disabled."); p->cancel.enable_on_lane_changing_phase = enable_on_lane_changing_phase; } - int deceleration_sampling_num = 0; + int deceleration_sampling_num = p->cancel.deceleration_sampling_num; updateParam(parameters, ns + "deceleration_sampling_num", deceleration_sampling_num); if (deceleration_sampling_num > 0) { p->cancel.deceleration_sampling_num = deceleration_sampling_num; } else { - RCLCPP_WARN_ONCE( - node_->get_logger(), + RCLCPP_WARN_THROTTLE( + node_->get_logger(), *node_->get_clock(), 1000, "Parameter 'deceleration_sampling_num' is not updated because the value (%d) is not " "positive", deceleration_sampling_num); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index 7748795851865..45fcd6fa99086 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -1154,18 +1154,22 @@ bool NormalLaneChange::get_path_using_frenet( const std::vector> & sorted_lane_ids, LaneChangePaths & candidate_paths) const { - stop_watch_.tic("frenet_candidates"); + stop_watch_.tic(__func__); constexpr auto found_safe_path = true; const auto frenet_candidates = utils::lane_change::generate_frenet_candidates( common_data_ptr_, prev_module_output_.path, prepare_metrics); RCLCPP_DEBUG( logger_, "Generated %lu candidate paths in %2.2f[us]", frenet_candidates.size(), - stop_watch_.toc("frenet_candidates")); + stop_watch_.toc(__func__)); candidate_paths.reserve(frenet_candidates.size()); lane_change_debug_.frenet_states.clear(); lane_change_debug_.frenet_states.reserve(frenet_candidates.size()); for (const auto & frenet_candidate : frenet_candidates) { + if (stop_watch_.toc(__func__) >= lane_change_parameters_->time_limit) { + break; + } + lane_change_debug_.frenet_states.emplace_back( frenet_candidate.prepare_metric, frenet_candidate.lane_changing.sampling_parameter, frenet_candidate.max_lane_changing_length); @@ -1186,7 +1190,7 @@ bool NormalLaneChange::get_path_using_frenet( if (check_candidate_path_safety(*candidate_path_opt, target_objects)) { RCLCPP_DEBUG( logger_, "Found safe path after %lu candidate(s). Total time: %2.2f[us]", - frenet_candidates.size(), stop_watch_.toc("frenet_candidates")); + frenet_candidates.size(), stop_watch_.toc("__func__")); utils::lane_change::append_target_ref_to_candidate( *candidate_path_opt, common_data_ptr_->lc_param_ptr->frenet.th_curvature_smoothing); candidate_paths.push_back(*candidate_path_opt); @@ -1204,7 +1208,7 @@ bool NormalLaneChange::get_path_using_frenet( RCLCPP_DEBUG( logger_, "No safe path after %lu candidate(s). Total time: %2.2f[us]", frenet_candidates.size(), - stop_watch_.toc("frenet_candidates")); + stop_watch_.toc(__func__)); return !found_safe_path; } @@ -1214,6 +1218,7 @@ bool NormalLaneChange::get_path_using_path_shifter( const std::vector> & sorted_lane_ids, LaneChangePaths & candidate_paths) const { + stop_watch_.tic(__func__); const auto & target_lanes = get_target_lanes(); candidate_paths.reserve( prepare_metrics.size() * lane_change_parameters_->trajectory.lat_acc_sampling_num); @@ -1279,6 +1284,11 @@ bool NormalLaneChange::get_path_using_path_shifter( prepare_segment, common_data_ptr_->get_ego_speed(), prep_metric.velocity); for (const auto & lc_metric : lane_changing_metrics) { + if (stop_watch_.toc(__func__) >= lane_change_parameters_->time_limit) { + RCLCPP_DEBUG(logger_, "Time limit reached and no safe path was found."); + return false; + } + debug_metrics.lc_metrics.emplace_back(lc_metric, -1); const auto debug_print_lat = [&](const std::string & s) { From 099591a740cec19de99c4590f7b468ab9e1d5572 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Thu, 16 Jan 2025 14:01:58 +0900 Subject: [PATCH 223/334] chore(simple_planning_simulator): add maintainer (#9934) --- .github/CODEOWNERS | 2 +- simulator/simple_planning_simulator/package.xml | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 5bbc4d1c6177b..4fea7c85e1926 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -204,7 +204,7 @@ simulator/autoware_carla_interface/** maxime.clement@tier4.jp mradityagio@gmail. simulator/dummy_perception_publisher/** yukihiro.saito@tier4.jp simulator/fault_injection/** keisuke.shima@tier4.jp simulator/learning_based_vehicle_model/** maxime.clement@tier4.jp nagy.tomas@tier4.jp -simulator/simple_planning_simulator/** mamoru.sobue@tier4.jp maxime.clement@tier4.jp takamasa.horibe@tier4.jp temkei.kem@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp +simulator/simple_planning_simulator/** mamoru.sobue@tier4.jp maxime.clement@tier4.jp takamasa.horibe@tier4.jp temkei.kem@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp kotaro.yoshimoto@tier4.jp simulator/tier4_dummy_object_rviz_plugin/** yukihiro.saito@tier4.jp simulator/vehicle_door_simulator/** isamu.takagi@tier4.jp system/autoware_component_monitor/** baris@leodrive.ai memin@leodrive.ai yavuz@leodrive.ai diff --git a/simulator/simple_planning_simulator/package.xml b/simulator/simple_planning_simulator/package.xml index fdc782182f9a5..5bd7a2f74eacc 100644 --- a/simulator/simple_planning_simulator/package.xml +++ b/simulator/simple_planning_simulator/package.xml @@ -10,6 +10,7 @@ Mamoru Sobue Zulfaqar Azmi Temkei Kem + Kotaro Yoshimoto Apache License 2.0 ament_cmake_auto From 01a764782c86e614a27808b973d073c12da2217e Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Thu, 16 Jan 2025 14:23:18 +0900 Subject: [PATCH 224/334] feat(autoware_shape_estimation): tier4_debug_msgs chnaged to autoware_internal_debug_msgs in autoware_shape_estimation (#9897) feat: tier4_debug_msgs chnaged to autoware_internal_debug_msgs in files perception/autoware_shape_estimation Signed-off-by: vish0012 --- .../autoware_shape_estimation/src/shape_estimation_node.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/autoware_shape_estimation/src/shape_estimation_node.cpp b/perception/autoware_shape_estimation/src/shape_estimation_node.cpp index c5450dc14adb0..28b2a6e398e91 100644 --- a/perception/autoware_shape_estimation/src/shape_estimation_node.cpp +++ b/perception/autoware_shape_estimation/src/shape_estimation_node.cpp @@ -179,9 +179,9 @@ void ShapeEstimationNode::callback(const DetectedObjectsWithFeature::ConstShared // Publish pub_->publish(output_msg); published_time_publisher_->publish_if_subscribed(pub_, output_msg.header.stamp); - processing_time_publisher_->publish( + processing_time_publisher_->publish( "debug/cyclic_time_ms", stop_watch_ptr_->toc("cyclic_time", true)); - processing_time_publisher_->publish( + processing_time_publisher_->publish( "debug/processing_time_ms", stop_watch_ptr_->toc("processing_time", true)); } } // namespace autoware::shape_estimation From 415e1ec0bc0e1a7f446c664f4161a1219f48ca36 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 16 Jan 2025 17:27:22 +0900 Subject: [PATCH 225/334] fix: remove unnecessary parameters (#9935) Signed-off-by: Takayuki Murooka --- .../autoware_pid_longitudinal_controller/README.md | 2 -- .../param/lateral/mpc.param.yaml | 2 -- .../param/longitudinal/pid.param.yaml | 2 -- .../config/crosswalk.param.yaml | 2 -- .../README.md | 13 ++++++------- 5 files changed, 6 insertions(+), 15 deletions(-) diff --git a/control/autoware_pid_longitudinal_controller/README.md b/control/autoware_pid_longitudinal_controller/README.md index aba0f36f04d65..957379866b62a 100644 --- a/control/autoware_pid_longitudinal_controller/README.md +++ b/control/autoware_pid_longitudinal_controller/README.md @@ -195,8 +195,6 @@ AutonomouStuff Lexus RX 450h for under 40 km/h driving. | stopped_state_entry_vel | double | threshold of the ego velocity in transition to the STOPPED state [m/s] | 0.01 | | stopped_state_entry_acc | double | threshold of the ego acceleration in transition to the STOPPED state [m/s^2] | 0.1 | | emergency_state_overshoot_stop_dist | double | If `enable_overshoot_emergency` is true and the ego is `emergency_state_overshoot_stop_dist`-meter ahead of the stop point, the state will transit to EMERGENCY. [m] | 1.5 | -| emergency_state_traj_trans_dev | double | If the ego's position is `emergency_state_traj_tran_dev` meter away from the nearest trajectory point, the state will transit to EMERGENCY. [m] | 3.0 | -| emergency_state_traj_rot_dev | double | If the ego's orientation is `emergency_state_traj_rot_dev` rad away from the nearest trajectory point orientation, the state will transit to EMERGENCY. [rad] | 0.784 | ### DRIVE Parameter diff --git a/control/autoware_trajectory_follower_node/param/lateral/mpc.param.yaml b/control/autoware_trajectory_follower_node/param/lateral/mpc.param.yaml index b358e95f86f99..1d30a28d05cb8 100644 --- a/control/autoware_trajectory_follower_node/param/lateral/mpc.param.yaml +++ b/control/autoware_trajectory_follower_node/param/lateral/mpc.param.yaml @@ -3,8 +3,6 @@ # -- system -- 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 - admissible_yaw_error_rad: 1.57 # stop mpc calculation when error is larger than the following value use_delayed_initial_state: true # flag to use x0_delayed as initial state for predicted trajectory # -- path smoothing -- diff --git a/control/autoware_trajectory_follower_node/param/longitudinal/pid.param.yaml b/control/autoware_trajectory_follower_node/param/longitudinal/pid.param.yaml index 5c5d65a13b2d5..f3139308db37c 100644 --- a/control/autoware_trajectory_follower_node/param/longitudinal/pid.param.yaml +++ b/control/autoware_trajectory_follower_node/param/longitudinal/pid.param.yaml @@ -16,8 +16,6 @@ stopped_state_entry_vel: 0.01 stopped_state_entry_acc: 0.1 emergency_state_overshoot_stop_dist: 1.5 - emergency_state_traj_trans_dev: 3.0 - emergency_state_traj_rot_dev: 0.7854 # drive state kp: 1.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/config/crosswalk.param.yaml b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/config/crosswalk.param.yaml index bc0d4f613f10b..97e00ade8256c 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/config/crosswalk.param.yaml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/config/crosswalk.param.yaml @@ -13,8 +13,6 @@ # For the Lanelet2 map with no explicit stop lines stop_distance_from_crosswalk: 3.5 # [m] make stop line away from crosswalk - # For the case where the crosswalk width is very wide - far_object_threshold: 10.0 # [m] If objects cross X meters behind the stop line, the stop position is determined according to the object position (stop_distance_from_object meters before the object). # For the case where the stop position is determined according to the object position. stop_distance_from_object_preferred: 3.0 # [m] stop_distance_from_object_limit: 3.0 # [m] diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/README.md b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/README.md index efe4a9a353ecc..963d75e5a8492 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/README.md +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/README.md @@ -12,13 +12,12 @@ This module is activated when there is a stop line in a target lane. ## Module Parameters -| Parameter | Type | Description | -| -------------------------------- | ------ | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| `stop_margin` | double | Margin that the vehicle tries to stop in before stop_line | -| `stop_duration_sec` | double | [s] Time parameter for the ego vehicle to stop before stop line | -| `hold_stop_margin_distance` | double | [m] Parameter for restart prevention (See Algorithm section). Also, when the ego vehicle is within this distance from a stop line, the ego state becomes STOPPED from APPROACHING | -| `use_initialization_stop_state` | bool | Flag to determine whether to return to the approaching state when the vehicle moves away from a stop line. | -| `show_stop_line_collision_check` | bool | Flag to determine whether to show the debug information of collision check with a stop line | +| Parameter | Type | Description | +| ------------------------------- | ------ | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `stop_margin` | double | Margin that the vehicle tries to stop in before stop_line | +| `stop_duration_sec` | double | [s] Time parameter for the ego vehicle to stop before stop line | +| `hold_stop_margin_distance` | double | [m] Parameter for restart prevention (See Algorithm section). Also, when the ego vehicle is within this distance from a stop line, the ego state becomes STOPPED from APPROACHING | +| `use_initialization_stop_state` | bool | Flag to determine whether to return to the approaching state when the vehicle moves away from a stop line. | ## Inner-workings / Algorithms From cb33b74ccd35b9b29bc11daf83209d9db72c6ab4 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 16 Jan 2025 17:27:46 +0900 Subject: [PATCH 226/334] feat(velocity_smoother): introduce diagnostics (#9933) * feat(velocity_smoother): introduce diagnostics Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../include/autoware/velocity_smoother/node.hpp | 11 ++++++----- .../autoware_velocity_smoother/src/node.cpp | 17 +++++++++-------- 2 files changed, 15 insertions(+), 13 deletions(-) diff --git a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp index fc0066b1a84f3..d519356c7aa18 100644 --- a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp +++ b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp @@ -20,6 +20,7 @@ #include "autoware/osqp_interface/osqp_interface.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" #include "autoware/universe_utils/math/unit_conversion.hpp" +#include "autoware/universe_utils/ros/diagnostics_interface.hpp" #include "autoware/universe_utils/ros/logger_level_configure.hpp" #include "autoware/universe_utils/ros/polling_subscriber.hpp" #include "autoware/universe_utils/ros/self_pose_listener.hpp" @@ -45,8 +46,7 @@ #include "autoware_planning_msgs/msg/trajectory_point.hpp" #include "geometry_msgs/msg/accel_with_covariance_stamped.hpp" #include "nav_msgs/msg/odometry.hpp" -#include "tier4_planning_msgs/msg/stop_speed_exceeded.hpp" // temporary -#include "tier4_planning_msgs/msg/velocity_limit.hpp" // temporary +#include "tier4_planning_msgs/msg/velocity_limit.hpp" // temporary #include "visualization_msgs/msg/marker_array.hpp" #include @@ -61,6 +61,7 @@ namespace autoware::velocity_smoother using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; using TrajectoryPoints = std::vector; +using autoware::universe_utils::DiagnosticsInterface; using autoware_adapi_v1_msgs::msg::OperationModeState; using autoware_internal_debug_msgs::msg::Float32Stamped; using autoware_internal_debug_msgs::msg::Float64Stamped; @@ -68,8 +69,7 @@ using geometry_msgs::msg::AccelWithCovarianceStamped; using geometry_msgs::msg::Pose; using geometry_msgs::msg::PoseStamped; using nav_msgs::msg::Odometry; -using tier4_planning_msgs::msg::StopSpeedExceeded; // temporary -using tier4_planning_msgs::msg::VelocityLimit; // temporary +using tier4_planning_msgs::msg::VelocityLimit; // temporary using visualization_msgs::msg::MarkerArray; struct Motion @@ -89,7 +89,6 @@ class VelocitySmootherNode : public rclcpp::Node private: rclcpp::Publisher::SharedPtr pub_trajectory_; rclcpp::Publisher::SharedPtr pub_virtual_wall_; - rclcpp::Publisher::SharedPtr pub_over_stop_velocity_; rclcpp::Subscription::SharedPtr sub_current_trajectory_; autoware::universe_utils::InterProcessPollingSubscriber sub_current_odometry_{ this, "/localization/kinematic_state"}; @@ -290,6 +289,8 @@ class VelocitySmootherNode : public rclcpp::Node std::unique_ptr published_time_publisher_; mutable std::shared_ptr time_keeper_{nullptr}; + + std::unique_ptr diagnostics_interface_{nullptr}; }; } // namespace autoware::velocity_smoother diff --git a/planning/autoware_velocity_smoother/src/node.cpp b/planning/autoware_velocity_smoother/src/node.cpp index 1e0f6119ac21e..1f2b1cad6e42a 100644 --- a/planning/autoware_velocity_smoother/src/node.cpp +++ b/planning/autoware_velocity_smoother/src/node.cpp @@ -36,7 +36,8 @@ namespace autoware::velocity_smoother { VelocitySmootherNode::VelocitySmootherNode(const rclcpp::NodeOptions & node_options) -: Node("velocity_smoother", node_options) +: Node("velocity_smoother", node_options), + diagnostics_interface_(std::make_unique(this, "velocity_smoother")) { using std::placeholders::_1; @@ -63,7 +64,6 @@ VelocitySmootherNode::VelocitySmootherNode(const rclcpp::NodeOptions & node_opti pub_velocity_limit_ = create_publisher( "~/output/current_velocity_limit_mps", rclcpp::QoS{1}.transient_local()); pub_dist_to_stopline_ = create_publisher("~/distance_to_stopline", 1); - pub_over_stop_velocity_ = create_publisher("~/stop_speed_exceeded", 1); sub_current_trajectory_ = create_subscription( "~/input/trajectory", 1, std::bind(&VelocitySmootherNode::onCurrentTrajectory, this, _1)); @@ -444,6 +444,7 @@ void VelocitySmootherNode::onCurrentTrajectory(const Trajectory::ConstSharedPtr RCLCPP_DEBUG(get_logger(), "========================= run start ========================="); stop_watch_.tic(); + diagnostics_interface_->clear(); base_traj_raw_ptr_ = msg; // receive data @@ -524,6 +525,10 @@ void VelocitySmootherNode::onCurrentTrajectory(const Trajectory::ConstSharedPtr // Publish Calculation Time publishStopWatchTime(); + + // Publish diagnostics + diagnostics_interface_->publish(now()); + RCLCPP_DEBUG(get_logger(), "========================== run() end ==========================\n\n"); } @@ -906,12 +911,8 @@ void VelocitySmootherNode::overwriteStopPoint( input_stop_vel, output_stop_vel, over_stop_velocity_warn_thr_); } - { - StopSpeedExceeded msg{}; - msg.stamp = this->now(); - msg.stop_speed_exceeded = is_stop_velocity_exceeded; - pub_over_stop_velocity_->publish(msg); - } + diagnostics_interface_->add_key_value( + "The velocity on the stop point is larger than 0.", is_stop_velocity_exceeded); } void VelocitySmootherNode::applyExternalVelocityLimit(TrajectoryPoints & traj) const From ed1f844ce77f496cc44894d23492646354a12217 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> Date: Thu, 16 Jan 2025 17:36:00 +0900 Subject: [PATCH 227/334] test(start_planner): disable GenerateValidFreespacePullOutPath test (#9937) Signed-off-by: kyoichi-sugahara --- .../test/test_freespace_pull_out.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_freespace_pull_out.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_freespace_pull_out.cpp index 79c58c37f0dcf..5078c463d7c36 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_freespace_pull_out.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/test/test_freespace_pull_out.cpp @@ -78,7 +78,7 @@ class TestFreespacePullOut : public ::testing::Test } }; -TEST_F(TestFreespacePullOut, GenerateValidFreespacePullOutPath) +TEST_F(TestFreespacePullOut, DISABLED_GenerateValidFreespacePullOutPath) { const auto start_pose = geometry_msgs::build() From cde1c78dd8d971514650793448f177a688667321 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 16 Jan 2025 18:30:31 +0900 Subject: [PATCH 228/334] feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (#9927) Signed-off-by: satoshi-ota Signed-off-by: Mamoru Sobue Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Co-authored-by: satoshi-ota --- .../planner_interface.hpp | 11 +- .../obstacle_cruise_planner/type_alias.hpp | 5 - .../obstacle_cruise_planner/utils.hpp | 3 - .../package.xml | 1 - .../src/node.cpp | 1 + .../pid_based_planner/pid_based_planner.cpp | 7 +- .../src/planner_interface.cpp | 18 +- .../src/utils.cpp | 21 -- .../package.xml | 1 - .../src/debug_marker.cpp | 33 +-- .../src/debug_marker.hpp | 14 +- .../src/interface.cpp | 4 +- .../src/interface.hpp | 3 +- .../src/manager.cpp | 2 +- .../manager.hpp | 2 +- .../scene.hpp | 3 +- .../src/scene.cpp | 5 +- .../src/manager.cpp | 4 +- .../goal_planner_module.hpp | 5 +- .../src/goal_planner_module.cpp | 26 +-- .../src/manager.cpp | 2 +- .../interface.hpp | 1 + .../src/interface.cpp | 48 ++-- .../src/manager.cpp | 2 +- .../behavior_path_planner_node.hpp | 7 +- .../src/behavior_path_planner_node.cpp | 39 ++-- .../src/planner_manager.cpp | 3 +- .../interface/scene_module_interface.hpp | 44 ++-- .../scene_module_manager_interface.hpp | 50 +--- .../scene_module_manager_interface.cpp | 9 +- .../manager.hpp | 2 +- .../sampling_planner_module.hpp | 3 +- .../src/sampling_planner_module.cpp | 5 +- .../manager.hpp | 2 +- .../behavior_path_side_shift_module/scene.hpp | 3 +- .../src/scene.cpp | 5 +- .../manager.hpp | 2 +- .../start_planner_module.hpp | 11 +- .../src/start_planner_module.cpp | 39 ++-- .../manager.hpp | 2 +- .../scene.hpp | 15 +- .../src/scene.cpp | 20 +- .../scene.hpp | 4 +- .../src/decisions.cpp | 14 +- .../src/manager.cpp | 2 +- .../src/scene.cpp | 7 +- .../src/manager.cpp | 4 +- .../src/scene_crosswalk.cpp | 23 +- .../src/scene_crosswalk.hpp | 4 +- .../src/manager.cpp | 3 +- .../src/scene.cpp | 6 +- .../src/scene.hpp | 4 +- .../src/manager.cpp | 9 +- .../src/scene_intersection.cpp | 167 ++++++++----- .../src/scene_intersection.hpp | 4 +- .../src/scene_merge_from_private_road.cpp | 13 +- .../src/scene_merge_from_private_road.hpp | 4 +- .../src/manager.cpp | 3 +- .../src/scene.cpp | 8 +- .../src/scene.hpp | 4 +- .../src/manager.cpp | 2 +- .../src/scene_no_stopping_area.cpp | 7 +- .../src/scene_no_stopping_area.hpp | 4 +- .../src/manager.cpp | 4 +- .../src/scene_occlusion_spot.cpp | 7 +- .../src/scene_occlusion_spot.hpp | 4 +- .../scene_module_interface.hpp | 22 +- .../src/scene_module_interface.cpp | 7 +- .../scene_module_interface_with_rtc.hpp | 4 +- .../src/scene_module_interface_with_rtc.cpp | 6 +- .../src/manager.cpp | 3 +- .../src/scene.cpp | 22 +- .../src/scene.hpp | 4 +- .../src/manager.cpp | 2 +- .../src/scene.cpp | 7 +- .../src/scene.hpp | 5 +- .../src/manager.cpp | 2 +- .../src/scene.cpp | 7 +- .../src/scene.hpp | 5 +- .../test/test_scene.cpp | 5 +- .../src/manager.cpp | 5 +- .../src/scene.cpp | 7 +- .../src/scene.hpp | 6 +- .../src/manager.cpp | 3 +- .../src/scene.cpp | 6 +- .../src/scene.hpp | 4 +- .../src/manager.cpp | 3 +- .../src/scene.cpp | 7 +- .../src/scene.hpp | 5 +- .../src/manager.cpp | 3 +- .../src/scene_walkway.cpp | 16 +- .../src/scene_walkway.hpp | 4 +- .../src/dynamic_obstacle_stop_module.cpp | 16 +- .../src/dynamic_obstacle_stop_module.hpp | 1 + .../src/obstacle_velocity_limiter_module.cpp | 1 - .../src/out_of_lane_module.cpp | 16 +- .../src/out_of_lane_module.hpp | 1 + .../plugin_module_interface.hpp | 10 +- .../velocity_planning_result.hpp | 2 - .../README.md | 8 +- .../src/node.cpp | 10 - .../src/node.hpp | 2 - .../src/planner_manager.cpp | 2 + system/autoware_default_adapi/package.xml | 1 + .../autoware_default_adapi/src/planning.cpp | 221 ++++++++++++++---- .../autoware_default_adapi/src/planning.hpp | 20 +- 106 files changed, 731 insertions(+), 544 deletions(-) diff --git a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/planner_interface.hpp b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/planner_interface.hpp index ef6ae1662dcee..823771e173c48 100644 --- a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/planner_interface.hpp +++ b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/planner_interface.hpp @@ -15,6 +15,7 @@ #ifndef AUTOWARE__OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_ #define AUTOWARE__OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_ +#include "autoware/motion_utils/factor/planning_factor_interface.hpp" #include "autoware/motion_utils/trajectory/trajectory.hpp" #include "autoware/obstacle_cruise_planner/common_structs.hpp" #include "autoware/obstacle_cruise_planner/stop_planning_debug_info.hpp" @@ -47,15 +48,15 @@ class PlannerInterface rclcpp::Node & node, const LongitudinalInfo & longitudinal_info, const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const EgoNearestParam & ego_nearest_param, const std::shared_ptr debug_data_ptr) - : longitudinal_info_(longitudinal_info), + : planning_factor_interface_{std::make_unique( + &node, "obstacle_cruise_planner")}, + longitudinal_info_(longitudinal_info), vehicle_info_(vehicle_info), ego_nearest_param_(ego_nearest_param), debug_data_ptr_(debug_data_ptr), slow_down_param_(SlowDownParam(node)), stop_param_(StopParam(node, longitudinal_info)) { - velocity_factors_pub_ = - node.create_publisher("/planning/velocity_factors/obstacle_cruise", 1); stop_speed_exceeded_pub_ = node.create_publisher("~/output/stop_speed_exceeded", 1); metrics_pub_ = node.create_publisher("~/metrics", 10); @@ -101,6 +102,7 @@ class PlannerInterface const std::optional & stop_pose = std::nullopt, const std::optional & stop_obstacle = std::nullopt); void publishMetrics(const rclcpp::Time & current_time); + void publishPlanningFactors() { planning_factor_interface_->publish(); } void clearMetrics(); void onParam(const std::vector & parameters) @@ -128,6 +130,8 @@ class PlannerInterface double getSafeDistanceMargin() const { return longitudinal_info_.safe_distance_margin; } protected: + std::unique_ptr planning_factor_interface_; + // Parameters bool enable_debug_info_{false}; bool enable_calculation_time_info_{false}; @@ -145,7 +149,6 @@ class PlannerInterface stop_watch_; // Publishers - rclcpp::Publisher::SharedPtr velocity_factors_pub_; rclcpp::Publisher::SharedPtr stop_speed_exceeded_pub_; rclcpp::Publisher::SharedPtr metrics_pub_; diff --git a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp index 04badd2a956ef..31344903b6809 100644 --- a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp +++ b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp @@ -17,8 +17,6 @@ #include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" -#include "autoware_adapi_v1_msgs/msg/planning_behavior.hpp" -#include "autoware_adapi_v1_msgs/msg/velocity_factor_array.hpp" #include "autoware_perception_msgs/msg/predicted_object.hpp" #include "autoware_perception_msgs/msg/predicted_objects.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" @@ -39,9 +37,6 @@ #include using autoware::vehicle_info_utils::VehicleInfo; -using autoware_adapi_v1_msgs::msg::PlanningBehavior; -using autoware_adapi_v1_msgs::msg::VelocityFactor; -using autoware_adapi_v1_msgs::msg::VelocityFactorArray; using autoware_perception_msgs::msg::ObjectClassification; using autoware_perception_msgs::msg::PredictedObject; using autoware_perception_msgs::msg::PredictedObjects; diff --git a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/utils.hpp b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/utils.hpp index d929647d9bcd0..ebabd96a54608 100644 --- a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/utils.hpp +++ b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/utils.hpp @@ -94,9 +94,6 @@ size_t getIndexWithLongitudinalOffset( return 0; } -VelocityFactorArray makeVelocityFactorArray( - const rclcpp::Time & time, const std::string & behavior = PlanningBehavior::ROUTE_OBSTACLE, - const std::optional pose = std::nullopt); } // namespace obstacle_cruise_utils #endif // AUTOWARE__OBSTACLE_CRUISE_PLANNER__UTILS_HPP_ diff --git a/planning/autoware_obstacle_cruise_planner/package.xml b/planning/autoware_obstacle_cruise_planner/package.xml index 8583d0639e5ce..7c6d0b286c9b0 100644 --- a/planning/autoware_obstacle_cruise_planner/package.xml +++ b/planning/autoware_obstacle_cruise_planner/package.xml @@ -18,7 +18,6 @@ ament_cmake_auto autoware_cmake - autoware_adapi_v1_msgs autoware_interpolation autoware_lanelet2_extension autoware_motion_utils diff --git a/planning/autoware_obstacle_cruise_planner/src/node.cpp b/planning/autoware_obstacle_cruise_planner/src/node.cpp index 6931ff58e8457..4242f0d559946 100644 --- a/planning/autoware_obstacle_cruise_planner/src/node.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/node.cpp @@ -726,6 +726,7 @@ void ObstacleCruisePlannerNode::onTrajectory(const Trajectory::ConstSharedPtr ms // 8. Publish debug data published_time_publisher_->publish_if_subscribed(trajectory_pub_, output_traj.header.stamp); planner_ptr_->publishMetrics(now()); + planner_ptr_->publishPlanningFactors(); publishDebugMarker(); publishDebugInfo(); objects_of_interest_marker_interface_.publishMarkerArray(); diff --git a/planning/autoware_obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp b/planning/autoware_obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp index 544597f05ff75..20b564addf149 100644 --- a/planning/autoware_obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp @@ -335,9 +335,10 @@ std::vector PIDBasedPlanner::planCruise( debug_data_ptr_->obstacles_to_cruise.push_back(cruise_obstacle_info->obstacle); debug_data_ptr_->cruise_metrics = makeMetrics("PIDBasedPlanner", "cruise", planner_data); - velocity_factors_pub_->publish(obstacle_cruise_utils::makeVelocityFactorArray( - planner_data.current_time, PlanningBehavior::ADAPTIVE_CRUISE, - stop_traj_points.at(wall_idx).pose)); + planning_factor_interface_->add( + stop_traj_points, planner_data.ego_pose, stop_traj_points.at(wall_idx).pose, + tier4_planning_msgs::msg::PlanningFactor::NONE, + tier4_planning_msgs::msg::SafetyFactorArray{}); } // do cruise planning diff --git a/planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp b/planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp index b08bb10ef69cf..b32d7f3a1bcbb 100644 --- a/planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp @@ -182,8 +182,6 @@ std::vector PlannerInterface::generateStopTrajectory( : std::abs(vehicle_info_.min_longitudinal_offset_m); if (stop_obstacles.empty()) { - velocity_factors_pub_->publish( - obstacle_cruise_utils::makeVelocityFactorArray(planner_data.current_time)); // delete marker const auto markers = autoware::motion_utils::createDeletedStopVirtualWallMarker(planner_data.current_time, 0); @@ -336,8 +334,10 @@ std::vector PlannerInterface::generateStopTrajectory( // Publish Stop Reason const auto stop_pose = output_traj_points.at(*zero_vel_idx).pose; - velocity_factors_pub_->publish(obstacle_cruise_utils::makeVelocityFactorArray( - planner_data.current_time, PlanningBehavior::ROUTE_OBSTACLE, stop_pose)); + planning_factor_interface_->add( + output_traj_points, planner_data.ego_pose, stop_pose, + tier4_planning_msgs::msg::PlanningFactor::STOP, + tier4_planning_msgs::msg::SafetyFactorArray{}); // Store stop reason debug data debug_data_ptr_->stop_metrics = makeMetrics("PlannerInterface", "stop", planner_data, stop_pose, *determined_stop_obstacle); @@ -590,10 +590,14 @@ std::vector PlannerInterface::generateSlowDownTrajectory( const auto markers = autoware::motion_utils::createSlowDownVirtualWallMarker( slow_down_traj_points.at(slow_down_wall_idx).pose, "obstacle slow down", planner_data.current_time, i, abs_ego_offset, "", planner_data.is_driving_forward); - velocity_factors_pub_->publish(obstacle_cruise_utils::makeVelocityFactorArray( - planner_data.current_time, PlanningBehavior::ROUTE_OBSTACLE, - slow_down_traj_points.at(slow_down_wall_idx).pose)); autoware::universe_utils::appendMarkerArray(markers, &debug_data_ptr_->slow_down_wall_marker); + planning_factor_interface_->add( + slow_down_traj_points, planner_data.ego_pose, + slow_down_traj_points.at(*slow_down_start_idx).pose, + slow_down_traj_points.at(*slow_down_end_idx).pose, + tier4_planning_msgs::msg::PlanningFactor::SLOW_DOWN, + tier4_planning_msgs::msg::SafetyFactorArray{}, planner_data.is_driving_forward, + stable_slow_down_vel); } // add debug virtual wall diff --git a/planning/autoware_obstacle_cruise_planner/src/utils.cpp b/planning/autoware_obstacle_cruise_planner/src/utils.cpp index 82f4e6978181f..b27def0bfcbe5 100644 --- a/planning/autoware_obstacle_cruise_planner/src/utils.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/utils.cpp @@ -118,25 +118,4 @@ std::vector getClosestStopObstacles(const std::vector pose) -{ - VelocityFactorArray velocity_factor_array; - velocity_factor_array.header.frame_id = "map"; - velocity_factor_array.header.stamp = time; - - if (pose) { - using distance_type = VelocityFactor::_distance_type; - VelocityFactor velocity_factor; - velocity_factor.behavior = behavior; - velocity_factor.pose = pose.value(); - velocity_factor.distance = std::numeric_limits::quiet_NaN(); - velocity_factor.status = VelocityFactor::UNKNOWN; - velocity_factor.detail = std::string(); - velocity_factor_array.factors.push_back(velocity_factor); - } - return velocity_factor_array; -} - } // namespace obstacle_cruise_utils diff --git a/planning/autoware_surround_obstacle_checker/package.xml b/planning/autoware_surround_obstacle_checker/package.xml index 4a6f946b8eb90..8bbc0b6bf4e02 100644 --- a/planning/autoware_surround_obstacle_checker/package.xml +++ b/planning/autoware_surround_obstacle_checker/package.xml @@ -14,7 +14,6 @@ autoware_cmake eigen3_cmake_module - autoware_adapi_v1_msgs autoware_motion_utils autoware_perception_msgs autoware_planning_msgs diff --git a/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp b/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp index bbd1cac04ed89..2acf6ba1c92f5 100644 --- a/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp +++ b/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp @@ -67,7 +67,9 @@ SurroundObstacleCheckerDebugNode::SurroundObstacleCheckerDebugNode( const double & surround_check_back_distance, const double & surround_check_hysteresis_distance, const geometry_msgs::msg::Pose & self_pose, const rclcpp::Clock::SharedPtr clock, rclcpp::Node & node) -: vehicle_info_(vehicle_info), +: planning_factor_interface_{std::make_unique( + &node, "surround_obstacle_checker")}, + vehicle_info_(vehicle_info), object_label_(object_label), surround_check_front_distance_(surround_check_front_distance), surround_check_side_distance_(surround_check_side_distance), @@ -77,8 +79,6 @@ SurroundObstacleCheckerDebugNode::SurroundObstacleCheckerDebugNode( clock_(clock) { debug_viz_pub_ = node.create_publisher("~/debug/marker", 1); - velocity_factor_pub_ = - node.create_publisher("/planning/velocity_factors/surround_obstacle", 1); vehicle_footprint_pub_ = node.create_publisher("~/debug/footprint", 1); vehicle_footprint_offset_pub_ = node.create_publisher("~/debug/footprint_offset", 1); @@ -143,8 +143,12 @@ void SurroundObstacleCheckerDebugNode::publish() debug_viz_pub_->publish(visualization_msg); /* publish stop reason for autoware api */ - const auto velocity_factor_msg = makeVelocityFactorArray(); - velocity_factor_pub_->publish(velocity_factor_msg); + if (stop_pose_ptr_ != nullptr) { + planning_factor_interface_->add( + 0.0, *stop_pose_ptr_, tier4_planning_msgs::msg::PlanningFactor::STOP, + tier4_planning_msgs::msg::SafetyFactorArray{}); + } + planning_factor_interface_->publish(); /* reset variables */ stop_pose_ptr_ = nullptr; @@ -170,25 +174,6 @@ MarkerArray SurroundObstacleCheckerDebugNode::makeVisualizationMarker() return msg; } -VelocityFactorArray SurroundObstacleCheckerDebugNode::makeVelocityFactorArray() -{ - VelocityFactorArray velocity_factor_array; - velocity_factor_array.header.frame_id = "map"; - velocity_factor_array.header.stamp = clock_->now(); - - if (stop_pose_ptr_) { - using distance_type = VelocityFactor::_distance_type; - VelocityFactor velocity_factor; - velocity_factor.behavior = PlanningBehavior::SURROUNDING_OBSTACLE; - velocity_factor.pose = *stop_pose_ptr_; - velocity_factor.distance = std::numeric_limits::quiet_NaN(); - velocity_factor.status = VelocityFactor::UNKNOWN; - velocity_factor.detail = std::string(); - velocity_factor_array.factors.push_back(velocity_factor); - } - return velocity_factor_array; -} - PolygonStamped SurroundObstacleCheckerDebugNode::boostPolygonToPolygonStamped( const Polygon2d & boost_polygon, const double & z) { diff --git a/planning/autoware_surround_obstacle_checker/src/debug_marker.hpp b/planning/autoware_surround_obstacle_checker/src/debug_marker.hpp index b2c350c1b4698..c49e277f2dc6c 100644 --- a/planning/autoware_surround_obstacle_checker/src/debug_marker.hpp +++ b/planning/autoware_surround_obstacle_checker/src/debug_marker.hpp @@ -15,13 +15,13 @@ #ifndef DEBUG_MARKER_HPP_ #define DEBUG_MARKER_HPP_ +#include #include #include -#include -#include #include #include +#include #include #include @@ -34,10 +34,10 @@ namespace autoware::surround_obstacle_checker { using autoware::vehicle_info_utils::VehicleInfo; -using autoware_adapi_v1_msgs::msg::PlanningBehavior; -using autoware_adapi_v1_msgs::msg::VelocityFactor; -using autoware_adapi_v1_msgs::msg::VelocityFactorArray; using geometry_msgs::msg::PolygonStamped; +using tier4_planning_msgs::msg::ControlPoint; +using tier4_planning_msgs::msg::PlanningFactor; +using tier4_planning_msgs::msg::PlanningFactorArray; using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; @@ -65,12 +65,13 @@ class SurroundObstacleCheckerDebugNode private: rclcpp::Publisher::SharedPtr debug_viz_pub_; - rclcpp::Publisher::SharedPtr velocity_factor_pub_; rclcpp::Publisher::SharedPtr vehicle_footprint_pub_; rclcpp::Publisher::SharedPtr vehicle_footprint_offset_pub_; rclcpp::Publisher::SharedPtr vehicle_footprint_recover_offset_pub_; + std::unique_ptr planning_factor_interface_; + autoware::vehicle_info_utils::VehicleInfo vehicle_info_; std::string object_label_; double surround_check_front_distance_; @@ -80,7 +81,6 @@ class SurroundObstacleCheckerDebugNode geometry_msgs::msg::Pose self_pose_; MarkerArray makeVisualizationMarker(); - VelocityFactorArray makeVelocityFactorArray(); PolygonStamped boostPolygonToPolygonStamped(const Polygon2d & boost_polygon, const double & z); diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.cpp index 3080ba1045b41..37bee1a178f90 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.cpp @@ -32,13 +32,15 @@ AvoidanceByLaneChangeInterface::AvoidanceByLaneChangeInterface( const std::shared_ptr & avoidance_by_lane_change_parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) + objects_of_interest_marker_interface_ptr_map, + const std::shared_ptr & planning_factor_interface) : LaneChangeInterface{ name, node, parameters, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, + planning_factor_interface, std::make_unique(parameters, avoidance_by_lane_change_parameters)} { } diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.hpp index c7fbba34b1adb..6e524f3c91341 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.hpp @@ -40,7 +40,8 @@ class AvoidanceByLaneChangeInterface : public LaneChangeInterface const std::shared_ptr & avoidance_by_lane_change_parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); + objects_of_interest_marker_interface_ptr_map, + const std::shared_ptr & planning_factor_interface); bool isExecutionRequested() const override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp index c54774a575332..2bf8a60676d72 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp @@ -190,7 +190,7 @@ SMIPtr AvoidanceByLaneChangeModuleManager::createNewSceneModuleInstance() { return std::make_unique( name_, *node_, parameters_, avoidance_parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); + objects_of_interest_marker_interface_ptr_map_, planning_factor_interface_); } } // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/manager.hpp index f09196b2cc8e1..ea8f09c4f9336 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/manager.hpp @@ -42,7 +42,7 @@ class DynamicObstacleAvoidanceModuleManager : public SceneModuleManagerInterface { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); + objects_of_interest_marker_interface_ptr_map_, planning_factor_interface_); } void updateModuleParams(const std::vector & parameters) override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp index 44b56f4ea0990..8987e7c0446ee 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp @@ -351,7 +351,8 @@ class DynamicObstacleAvoidanceModule : public SceneModuleInterface std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); + objects_of_interest_marker_interface_ptr_map, + const std::shared_ptr planning_factor_interface); void updateModuleParams(const std::any & parameters) override { diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp index dc7efebe88fba..145e0df2675b4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp @@ -331,8 +331,9 @@ DynamicObstacleAvoidanceModule::DynamicObstacleAvoidanceModule( std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT + objects_of_interest_marker_interface_ptr_map, + const std::shared_ptr planning_factor_interface) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, planning_factor_interface}, // NOLINT parameters_{std::move(parameters)}, target_objects_manager_{TargetObjectsManager( parameters_->successive_num_to_entry_dynamic_avoidance_condition, diff --git a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/src/manager.cpp index 45c997f364633..0b438d1a1758e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/src/manager.cpp @@ -28,7 +28,7 @@ ExternalRequestLaneChangeRightModuleManager::createNewSceneModuleInstance() { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_, + objects_of_interest_marker_interface_ptr_map_, planning_factor_interface_, std::make_unique(parameters_, direction_)); } @@ -37,7 +37,7 @@ ExternalRequestLaneChangeLeftModuleManager::createNewSceneModuleInstance() { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_, + objects_of_interest_marker_interface_ptr_map_, planning_factor_interface_, std::make_unique(parameters_, direction_)); } diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp index 41524b1b8193c..84367fdd91b80 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -240,7 +240,8 @@ class GoalPlannerModule : public SceneModuleInterface const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); + objects_of_interest_marker_interface_ptr_map, + const std::shared_ptr planning_factor_interface); ~GoalPlannerModule() { @@ -455,7 +456,7 @@ class GoalPlannerModule : public SceneModuleInterface // steering factor void updateSteeringFactor( const PullOverContextData & context_data, const std::array & pose, - const std::array distance, const uint16_t type); + const std::array distance); // rtc std::pair calcDistanceToPathChange( diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 0a6185127fcf0..c7e32a47a59f9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -66,8 +66,9 @@ GoalPlannerModule::GoalPlannerModule( const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT + objects_of_interest_marker_interface_ptr_map, + const std::shared_ptr planning_factor_interface) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, planning_factor_interface}, // NOLINT parameters_{parameters}, vehicle_info_{autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()}, is_lane_parking_cb_running_{false}, @@ -120,9 +121,6 @@ GoalPlannerModule::GoalPlannerModule( initializeSafetyCheckParameters(); } - steering_factor_interface_.init(PlanningBehavior::GOAL_PLANNER); - velocity_factor_interface_.init(PlanningBehavior::GOAL_PLANNER); - /** * NOTE: Add `universe_utils::ScopedTimeTrack st(__func__, *time_keeper_);` to functions called * from the main thread only. @@ -1344,19 +1342,20 @@ void GoalPlannerModule::setTurnSignalInfo( void GoalPlannerModule::updateSteeringFactor( const PullOverContextData & context_data, const std::array & pose, - const std::array distance, const uint16_t type) + const std::array distance) { - const uint16_t steering_factor_direction = std::invoke([&]() { + const uint16_t planning_factor_direction = std::invoke([&]() { const auto turn_signal = calcTurnSignalInfo(context_data); if (turn_signal.turn_signal.command == TurnIndicatorsCommand::ENABLE_LEFT) { - return SteeringFactor::LEFT; + return PlanningFactor::SHIFT_LEFT; } else if (turn_signal.turn_signal.command == TurnIndicatorsCommand::ENABLE_RIGHT) { - return SteeringFactor::RIGHT; + return PlanningFactor::SHIFT_RIGHT; } - return SteeringFactor::STRAIGHT; + return PlanningFactor::NONE; }); - steering_factor_interface_.set(pose, distance, steering_factor_direction, type, ""); + planning_factor_interface_->add( + distance[0], distance[1], pose[0], pose[1], planning_factor_direction, SafetyFactorArray{}); } void GoalPlannerModule::decideVelocity(PullOverPath & pull_over_path) @@ -1568,10 +1567,9 @@ void GoalPlannerModule::postProcess() updateSteeringFactor( context_data, {pull_over_path.start_pose(), pull_over_path.modified_goal_pose()}, - {distance_to_path_change.first, distance_to_path_change.second}, - has_decided_path ? SteeringFactor::TURNING : SteeringFactor::APPROACHING); + {distance_to_path_change.first, distance_to_path_change.second}); - setVelocityFactor(pull_over_path.full_path()); + set_longitudinal_planning_factor(pull_over_path.full_path()); } BehaviorModuleOutput GoalPlannerModule::planWaitingApproval() diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp index 6bbc34a495080..a99252c923328 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp @@ -31,7 +31,7 @@ std::unique_ptr GoalPlannerModuleManager::createNewSceneMo { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); + objects_of_interest_marker_interface_ptr_map_, planning_factor_interface_); } GoalPlannerParameters GoalPlannerModuleManager::initGoalPlannerParameters( diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp index 4b97fb0d069a0..82b042d1135d2 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp @@ -53,6 +53,7 @@ class LaneChangeInterface : public SceneModuleInterface const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & objects_of_interest_marker_interface_ptr_map, + const std::shared_ptr & planning_factor_interface, std::unique_ptr && module_type); LaneChangeInterface(const LaneChangeInterface &) = delete; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp index ebcd4eb4809fc..4519b20d4644d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp @@ -40,15 +40,14 @@ LaneChangeInterface::LaneChangeInterface( const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & objects_of_interest_marker_interface_ptr_map, + const std::shared_ptr & planning_factor_interface, std::unique_ptr && module_type) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, planning_factor_interface}, // NOLINT parameters_{std::move(parameters)}, module_type_{std::move(module_type)} { module_type_->setTimeKeeper(getTimeKeeper()); logger_ = utils::lane_change::getLogger(module_type_->getModuleTypeStr()); - steering_factor_interface_.init(PlanningBehavior::LANE_CHANGE); - velocity_factor_interface_.init(PlanningBehavior::LANE_CHANGE); } void LaneChangeInterface::processOnExit() @@ -145,7 +144,7 @@ BehaviorModuleOutput LaneChangeInterface::plan() } } - setVelocityFactor(output.path); + set_longitudinal_planning_factor(output.path); return output; } @@ -179,7 +178,7 @@ BehaviorModuleOutput LaneChangeInterface::planWaitingApproval() isExecutionReady(), State::WAITING_FOR_EXECUTION); is_abort_path_approved_ = false; - setVelocityFactor(out.path); + set_longitudinal_planning_factor(out.path); return out; } @@ -384,15 +383,6 @@ MarkerArray LaneChangeInterface::getModuleVirtualWall() void LaneChangeInterface::updateSteeringFactorPtr(const BehaviorModuleOutput & output) { universe_utils::ScopedTimeTrack st(__func__, *getTimeKeeper()); - const auto steering_factor_direction = std::invoke([&]() { - if (module_type_->getDirection() == Direction::LEFT) { - return SteeringFactor::LEFT; - } - if (module_type_->getDirection() == Direction::RIGHT) { - return SteeringFactor::RIGHT; - } - return SteeringFactor::UNKNOWN; - }); const auto current_position = module_type_->getEgoPosition(); const auto status = module_type_->getLaneChangeStatus(); @@ -401,24 +391,34 @@ void LaneChangeInterface::updateSteeringFactorPtr(const BehaviorModuleOutput & o const auto finish_distance = autoware::motion_utils::calcSignedArcLength( output.path.points, current_position, status.lane_change_path.info.shift_line.end.position); - steering_factor_interface_.set( - {status.lane_change_path.info.shift_line.start, status.lane_change_path.info.shift_line.end}, - {start_distance, finish_distance}, steering_factor_direction, SteeringFactor::TURNING, ""); + const auto planning_factor_direction = std::invoke([&]() { + if (module_type_->getDirection() == Direction::LEFT) { + return PlanningFactor::SHIFT_LEFT; + } + if (module_type_->getDirection() == Direction::RIGHT) { + return PlanningFactor::SHIFT_RIGHT; + } + return PlanningFactor::UNKNOWN; + }); + + planning_factor_interface_->add( + start_distance, finish_distance, status.lane_change_path.info.shift_line.start, + status.lane_change_path.info.shift_line.end, planning_factor_direction, SafetyFactorArray{}); } void LaneChangeInterface::updateSteeringFactorPtr( const CandidateOutput & output, const LaneChangePath & selected_path) const { - const uint16_t steering_factor_direction = std::invoke([&output]() { + const uint16_t planning_factor_direction = std::invoke([&output]() { if (output.lateral_shift > 0.0) { - return SteeringFactor::LEFT; + return PlanningFactor::SHIFT_LEFT; } - return SteeringFactor::RIGHT; + return PlanningFactor::SHIFT_RIGHT; }); - steering_factor_interface_.set( - {selected_path.info.shift_line.start, selected_path.info.shift_line.end}, - {output.start_distance_to_path_change, output.finish_distance_to_path_change}, - steering_factor_direction, SteeringFactor::APPROACHING, ""); + planning_factor_interface_->add( + output.start_distance_to_path_change, output.finish_distance_to_path_change, + selected_path.info.shift_line.start, selected_path.info.shift_line.end, + planning_factor_direction, SafetyFactorArray{}); } } // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp index f26cf79e8b120..450497fb2ca29 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp @@ -302,7 +302,7 @@ std::unique_ptr LaneChangeModuleManager::createNewSceneMod { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_, + objects_of_interest_marker_interface_ptr_map_, planning_factor_interface_, std::make_unique(parameters_, LaneChangeModuleType::NORMAL, direction_)); } diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/behavior_path_planner_node.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/behavior_path_planner_node.hpp index ebe7c47e6fab2..7f7ecd7326b08 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/behavior_path_planner_node.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/behavior_path_planner_node.hpp @@ -20,7 +20,7 @@ #include "autoware/universe_utils/ros/logger_level_configure.hpp" #include "planner_manager.hpp" -#include +#include #include #include @@ -51,7 +51,7 @@ namespace autoware::behavior_path_planner { -using autoware::motion_utils::SteeringFactorInterface; +using autoware::motion_utils::PlanningFactorInterface; using autoware_adapi_v1_msgs::msg::OperationModeState; using autoware_map_msgs::msg::LaneletMapBin; using autoware_perception_msgs::msg::PredictedObject; @@ -121,7 +121,6 @@ class BehaviorPathPlannerNode : public rclcpp::Node rclcpp::Publisher::SharedPtr bound_publisher_; rclcpp::Publisher::SharedPtr modified_goal_publisher_; rclcpp::Publisher::SharedPtr reroute_availability_publisher_; - rclcpp::Publisher::SharedPtr pub_steering_factors_; rclcpp::TimerBase::SharedPtr timer_; std::map::SharedPtr> path_candidate_publishers_; @@ -136,7 +135,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node std::shared_ptr planner_manager_; - SteeringFactorInterface steering_factor_interface_; + std::unique_ptr planning_factor_interface_; std::mutex mutex_pd_; // mutex for planner_data_ std::mutex mutex_manager_; // mutex for bt_manager_ or planner_manager_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp index 7758ab530e88c..568d432e1faa3 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp @@ -32,7 +32,9 @@ using autoware::vehicle_info_utils::VehicleInfoUtils; using tier4_planning_msgs::msg::PathChangeModuleId; BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & node_options) -: Node("behavior_path_planner", node_options) +: Node("behavior_path_planner", node_options), + planning_factor_interface_{ + std::make_unique(this, "behavior_path_planner")} { using std::placeholders::_1; using std::chrono_literals::operator""ms; @@ -51,8 +53,6 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod const auto durable_qos = rclcpp::QoS(1).transient_local(); modified_goal_publisher_ = create_publisher("~/output/modified_goal", durable_qos); - pub_steering_factors_ = - create_publisher("/planning/steering_factor/intersection", 1); reroute_availability_publisher_ = create_publisher("~/output/is_reroute_available", 1); debug_avoidance_msg_array_publisher_ = @@ -115,8 +115,6 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod turn_signal_search_time, turn_signal_intersection_angle_threshold_deg); } - steering_factor_interface_.init(PlanningBehavior::INTERSECTION); - // Start timer { const auto planning_hz = declare_parameter("planning_hz"); @@ -463,33 +461,22 @@ void BehaviorPathPlannerNode::publish_steering_factor( const auto [intersection_flag, approaching_intersection_flag] = planner_data->turn_signal_decider.getIntersectionTurnSignalFlag(); if (intersection_flag || approaching_intersection_flag) { - const uint16_t steering_factor_direction = std::invoke([&turn_signal]() { - if (turn_signal.command == TurnIndicatorsCommand::ENABLE_LEFT) { - return SteeringFactor::LEFT; - } - return SteeringFactor::RIGHT; - }); - const auto [intersection_pose, intersection_distance] = planner_data->turn_signal_decider.getIntersectionPoseAndDistance(); - steering_factor_interface_.set( - {intersection_pose, intersection_pose}, {intersection_distance, intersection_distance}, - steering_factor_direction, SteeringFactor::TURNING, ""); - } else { - steering_factor_interface_.reset(); - } - - autoware_adapi_v1_msgs::msg::SteeringFactorArray steering_factor_array; - steering_factor_array.header.frame_id = "map"; - steering_factor_array.header.stamp = this->now(); + const uint16_t planning_factor_direction = std::invoke([&turn_signal]() { + if (turn_signal.command == TurnIndicatorsCommand::ENABLE_LEFT) { + return PlanningFactor::TURN_LEFT; + } + return PlanningFactor::TURN_RIGHT; + }); - const auto steering_factor = steering_factor_interface_.get(); - if (steering_factor.behavior != PlanningBehavior::UNKNOWN) { - steering_factor_array.factors.emplace_back(steering_factor); + planning_factor_interface_->add( + intersection_distance, intersection_distance, intersection_pose, intersection_pose, + planning_factor_direction, SafetyFactorArray{}); } - pub_steering_factors_->publish(steering_factor_array); + planning_factor_interface_->publish(); } void BehaviorPathPlannerNode::publish_reroute_availability() const diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp index 041b7ad20a107..322209d46732b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp @@ -182,8 +182,7 @@ BehaviorModuleOutput PlannerManager::run(const std::shared_ptr & da std::for_each(manager_ptrs_.begin(), manager_ptrs_.end(), [](const auto & m) { m->updateObserver(); m->publishRTCStatus(); - m->publishSteeringFactor(); - m->publishVelocityFactor(); + m->publish_planning_factors(); }); generateCombinedDrivableArea(result_output.valid_output, data); diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp index 391ac92411220..c96bc601b6403 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp @@ -21,8 +21,7 @@ #include "autoware/behavior_path_planner_common/utils/utils.hpp" #include -#include -#include +#include #include #include #include @@ -36,7 +35,6 @@ #include #include -#include #include #include #include @@ -54,18 +52,16 @@ namespace autoware::behavior_path_planner { -using autoware::motion_utils::SteeringFactorInterface; -using autoware::motion_utils::VelocityFactorInterface; +using autoware::motion_utils::PlanningFactorInterface; using autoware::objects_of_interest_marker_interface::ColorName; using autoware::objects_of_interest_marker_interface::ObjectsOfInterestMarkerInterface; using autoware::rtc_interface::RTCInterface; using autoware::universe_utils::calcOffsetPose; using autoware::universe_utils::generateUUID; -using autoware_adapi_v1_msgs::msg::PlanningBehavior; -using autoware_adapi_v1_msgs::msg::SteeringFactor; -using autoware_adapi_v1_msgs::msg::VelocityFactor; using tier4_planning_msgs::msg::AvoidanceDebugMsgArray; using tier4_planning_msgs::msg::PathWithLaneId; +using tier4_planning_msgs::msg::PlanningFactor; +using tier4_planning_msgs::msg::SafetyFactorArray; using tier4_rtc_msgs::msg::State; using unique_identifier_msgs::msg::UUID; using visualization_msgs::msg::MarkerArray; @@ -86,13 +82,15 @@ class SceneModuleInterface const std::string & name, rclcpp::Node & node, std::unordered_map> rtc_interface_ptr_map, std::unordered_map> - objects_of_interest_marker_interface_ptr_map) + objects_of_interest_marker_interface_ptr_map, + const std::shared_ptr planning_factor_interface) : name_{name}, logger_{node.get_logger().get_child(name)}, clock_{node.get_clock()}, rtc_interface_ptr_map_(std::move(rtc_interface_ptr_map)), objects_of_interest_marker_interface_ptr_map_( std::move(objects_of_interest_marker_interface_ptr_map)), + planning_factor_interface_{planning_factor_interface}, time_keeper_(std::make_shared()) { for (const auto & [module_name, ptr] : rtc_interface_ptr_map_) { @@ -184,8 +182,6 @@ class SceneModuleInterface unlockNewModuleLaunch(); unlockOutputPath(); - reset_factor(); - processOnExit(); } @@ -258,16 +254,6 @@ class SceneModuleInterface ModuleStatus getCurrentStatus() const { return current_state_; } - void reset_factor() - { - steering_factor_interface_.reset(); - velocity_factor_interface_.reset(); - } - - auto get_steering_factor() const -> SteeringFactor { return steering_factor_interface_.get(); } - - auto get_velocity_factor() const -> VelocityFactor { return velocity_factor_interface_.get(); } - std::string name() const { return name_; } PoseWithDetailOpt getStopPose() const @@ -558,11 +544,12 @@ class SceneModuleInterface } } - void setVelocityFactor(const PathWithLaneId & path) + void set_longitudinal_planning_factor(const PathWithLaneId & path) { if (stop_pose_.has_value()) { - velocity_factor_interface_.set( - path.points, getEgoPose(), stop_pose_.value().pose, VelocityFactor::APPROACHING, "stop"); + planning_factor_interface_->add( + path.points, getEgoPose(), stop_pose_.value().pose, PlanningFactor::STOP, + SafetyFactorArray{}); return; } @@ -570,8 +557,9 @@ class SceneModuleInterface return; } - velocity_factor_interface_.set( - path.points, getEgoPose(), slow_pose_.value().pose, VelocityFactor::APPROACHING, "slow down"); + planning_factor_interface_->add( + path.points, getEgoPose(), slow_pose_.value().pose, PlanningFactor::SLOW_DOWN, + SafetyFactorArray{}); } void setDrivableLanes(const std::vector & drivable_lanes); @@ -627,9 +615,7 @@ class SceneModuleInterface std::unordered_map> objects_of_interest_marker_interface_ptr_map_; - mutable SteeringFactorInterface steering_factor_interface_; - - mutable VelocityFactorInterface velocity_factor_interface_; + mutable std::shared_ptr planning_factor_interface_; mutable PoseWithDetailOpt stop_pose_{std::nullopt}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp index 73b133952935b..446829d1d0f9d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp @@ -24,8 +24,6 @@ #include #include -#include -#include #include #include @@ -42,8 +40,6 @@ using autoware::motion_utils::createDeadLineVirtualWallMarker; using autoware::motion_utils::createSlowDownVirtualWallMarker; using autoware::motion_utils::createStopVirtualWallMarker; using autoware::universe_utils::toHexString; -using autoware_adapi_v1_msgs::msg::SteeringFactorArray; -using autoware_adapi_v1_msgs::msg::VelocityFactorArray; using unique_identifier_msgs::msg::UUID; using SceneModulePtr = std::shared_ptr; using SceneModuleObserver = std::weak_ptr; @@ -106,45 +102,7 @@ class SceneModuleManagerInterface } } - void publishSteeringFactor() - { - SteeringFactorArray steering_factor_array; - steering_factor_array.header.frame_id = "map"; - steering_factor_array.header.stamp = node_->now(); - - for (const auto & m : observers_) { - if (m.expired()) { - continue; - } - - const auto steering_factor = m.lock()->get_steering_factor(); - if (steering_factor.behavior != PlanningBehavior::UNKNOWN) { - steering_factor_array.factors.emplace_back(steering_factor); - } - } - - pub_steering_factors_->publish(steering_factor_array); - } - - void publishVelocityFactor() - { - VelocityFactorArray velocity_factor_array; - velocity_factor_array.header.frame_id = "map"; - velocity_factor_array.header.stamp = node_->now(); - - for (const auto & m : observers_) { - if (m.expired()) { - continue; - } - - const auto velocity_factor = m.lock()->get_velocity_factor(); - if (velocity_factor.behavior != PlanningBehavior::UNKNOWN) { - velocity_factor_array.factors.emplace_back(velocity_factor); - } - } - - pub_velocity_factors_->publish(velocity_factor_array); - } + void publish_planning_factors() { planning_factor_interface_->publish(); } void publishVirtualWall() const { @@ -304,10 +262,6 @@ class SceneModuleManagerInterface rclcpp::Publisher::SharedPtr pub_drivable_lanes_; - rclcpp::Publisher::SharedPtr pub_steering_factors_; - - rclcpp::Publisher::SharedPtr pub_velocity_factors_; - rclcpp::Publisher::SharedPtr pub_processing_time_; std::string name_; @@ -318,6 +272,8 @@ class SceneModuleManagerInterface std::unique_ptr idle_module_ptr_; + std::shared_ptr planning_factor_interface_; + std::unordered_map> rtc_interface_ptr_map_; std::unordered_map> diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_manager_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_manager_interface.cpp index b91db3a740cfe..11be3b28a7f94 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_manager_interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_manager_interface.cpp @@ -61,10 +61,11 @@ void SceneModuleManagerInterface::initInterface( pub_drivable_lanes_ = node->create_publisher("~/drivable_lanes/" + name_, 20); pub_processing_time_ = node->create_publisher( "~/processing_time/" + name_, 20); - pub_steering_factors_ = - node->create_publisher("/planning/steering_factor/" + name_, 1); - pub_velocity_factors_ = - node->create_publisher("/planning/velocity_factors/" + name_, 1); + } + + // planning factor + { + planning_factor_interface_ = std::make_shared(node, name_); } // misc diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/manager.hpp index 28c310ae20ec2..f25c073e879da 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/manager.hpp @@ -38,7 +38,7 @@ class SamplingPlannerModuleManager : public SceneModuleManagerInterface { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); + objects_of_interest_marker_interface_ptr_map_, planning_factor_interface_); } void updateModuleParams( diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp index c9b75f7fa96de..f84fe45d08ca4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp @@ -86,7 +86,8 @@ class SamplingPlannerModule : public SceneModuleInterface const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); + objects_of_interest_marker_interface_ptr_map, + const std::shared_ptr planning_factor_interface); bool isExecutionRequested() const override; bool isExecutionReady() const override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/sampling_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/sampling_planner_module.cpp index fac3cc92de1d6..5bb57f17ce813 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/sampling_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/sampling_planner_module.cpp @@ -42,8 +42,9 @@ SamplingPlannerModule::SamplingPlannerModule( const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT + objects_of_interest_marker_interface_ptr_map, + const std::shared_ptr planning_factor_interface) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, planning_factor_interface}, // NOLINT vehicle_info_{autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()} { internal_params_ = std::make_shared(); diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/manager.hpp index b495e6619a1c7..2b4a20ddc8cca 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/manager.hpp @@ -39,7 +39,7 @@ class SideShiftModuleManager : public SceneModuleManagerInterface { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); + objects_of_interest_marker_interface_ptr_map_, planning_factor_interface_); } void updateModuleParams(const std::vector & parameters) override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/scene.hpp index 15d81ff45abcf..c8a5e47287477 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/scene.hpp @@ -45,7 +45,8 @@ class SideShiftModule : public SceneModuleInterface const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); + objects_of_interest_marker_interface_ptr_map, + const std::shared_ptr planning_factor_interface); bool isExecutionRequested() const override; bool isExecutionReady() const override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp index 22ee7ab77e077..9536c1ba17336 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp @@ -42,8 +42,9 @@ SideShiftModule::SideShiftModule( const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT + objects_of_interest_marker_interface_ptr_map, + const std::shared_ptr planning_factor_interface) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, planning_factor_interface}, // NOLINT parameters_{parameters} { } diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/manager.hpp index 5d3d224673124..68b1e67e484c3 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/manager.hpp @@ -38,7 +38,7 @@ class StartPlannerModuleManager : public SceneModuleManagerInterface { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); + objects_of_interest_marker_interface_ptr_map_, planning_factor_interface_); } void updateModuleParams(const std::vector & parameters) override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp index cf9227c2387f8..9b1186cb5fc66 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp @@ -86,7 +86,8 @@ class StartPlannerModule : public SceneModuleInterface const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); + objects_of_interest_marker_interface_ptr_map, + const std::shared_ptr planning_factor_interface); ~StartPlannerModule() override { @@ -198,18 +199,18 @@ class StartPlannerModule : public SceneModuleInterface bool requiresDynamicObjectsCollisionDetection() const; - uint16_t getSteeringFactorDirection( + uint16_t getPlanningFactorDirection( const autoware::behavior_path_planner::BehaviorModuleOutput & output) const { switch (output.turn_signal_info.turn_signal.command) { case TurnIndicatorsCommand::ENABLE_LEFT: - return SteeringFactor::LEFT; + return PlanningFactor::SHIFT_LEFT; case TurnIndicatorsCommand::ENABLE_RIGHT: - return SteeringFactor::RIGHT; + return PlanningFactor::SHIFT_RIGHT; default: - return SteeringFactor::STRAIGHT; + return PlanningFactor::NONE; } }; diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp index 0bac50a37fdbf..ae05bcf4c084e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp @@ -62,8 +62,9 @@ StartPlannerModule::StartPlannerModule( const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT + objects_of_interest_marker_interface_ptr_map, + const std::shared_ptr planning_factor_interface) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, planning_factor_interface}, // NOLINT parameters_{parameters}, vehicle_info_{autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()}, is_freespace_planner_cb_running_{false} @@ -89,9 +90,6 @@ StartPlannerModule::StartPlannerModule( std::bind(&StartPlannerModule::onFreespacePlannerTimer, this), freespace_planner_timer_cb_group_); } - - steering_factor_interface_.init(PlanningBehavior::START_PLANNER); - velocity_factor_interface_.init(PlanningBehavior::START_PLANNER); } void StartPlannerModule::onFreespacePlannerTimer() @@ -732,9 +730,9 @@ BehaviorModuleOutput StartPlannerModule::plan() setDrivableAreaInfo(output); - setVelocityFactor(output.path); + set_longitudinal_planning_factor(output.path); - const auto steering_factor_direction = getSteeringFactorDirection(output); + const auto planning_factor_direction = getPlanningFactorDirection(output); if (status_.driving_forward) { const double start_distance = autoware::motion_utils::calcSignedArcLength( @@ -744,9 +742,9 @@ BehaviorModuleOutput StartPlannerModule::plan() path.points, planner_data_->self_odometry->pose.pose.position, status_.pull_out_path.end_pose.position); updateRTCStatus(start_distance, finish_distance); - steering_factor_interface_.set( - {status_.pull_out_path.start_pose, status_.pull_out_path.end_pose}, - {start_distance, finish_distance}, steering_factor_direction, SteeringFactor::TURNING, ""); + planning_factor_interface_->add( + start_distance, finish_distance, status_.pull_out_path.start_pose, + status_.pull_out_path.end_pose, planning_factor_direction, SafetyFactorArray{}); setDebugData(); return output; } @@ -754,9 +752,9 @@ BehaviorModuleOutput StartPlannerModule::plan() path.points, planner_data_->self_odometry->pose.pose.position, status_.pull_out_path.start_pose.position); updateRTCStatus(0.0, distance); - steering_factor_interface_.set( - {status_.pull_out_path.start_pose, status_.pull_out_path.end_pose}, {0.0, distance}, - steering_factor_direction, SteeringFactor::TURNING, ""); + planning_factor_interface_->add( + 0.0, distance, status_.pull_out_path.start_pose, status_.pull_out_path.end_pose, + planning_factor_direction, SafetyFactorArray{}); setDebugData(); @@ -839,7 +837,7 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval() setDrivableAreaInfo(output); - const auto steering_factor_direction = getSteeringFactorDirection(output); + const auto planning_factor_direction = getPlanningFactorDirection(output); if (status_.driving_forward) { const double start_distance = autoware::motion_utils::calcSignedArcLength( @@ -849,10 +847,9 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval() stop_path.points, planner_data_->self_odometry->pose.pose.position, status_.pull_out_path.end_pose.position); updateRTCStatus(start_distance, finish_distance); - steering_factor_interface_.set( - {status_.pull_out_path.start_pose, status_.pull_out_path.end_pose}, - {start_distance, finish_distance}, steering_factor_direction, SteeringFactor::APPROACHING, - ""); + planning_factor_interface_->add( + start_distance, finish_distance, status_.pull_out_path.start_pose, + status_.pull_out_path.end_pose, planning_factor_direction, SafetyFactorArray{}); setDebugData(); return output; @@ -861,9 +858,9 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval() stop_path.points, planner_data_->self_odometry->pose.pose.position, status_.pull_out_path.start_pose.position); updateRTCStatus(0.0, distance); - steering_factor_interface_.set( - {status_.pull_out_path.start_pose, status_.pull_out_path.end_pose}, {0.0, distance}, - steering_factor_direction, SteeringFactor::APPROACHING, ""); + planning_factor_interface_->add( + 0.0, distance, status_.pull_out_path.start_pose, status_.pull_out_path.end_pose, + planning_factor_direction, SafetyFactorArray{}); setDebugData(); diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/manager.hpp index 895390f91cc16..6296acd8e71f7 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/manager.hpp @@ -41,7 +41,7 @@ class StaticObstacleAvoidanceModuleManager : public SceneModuleManagerInterface { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_); + objects_of_interest_marker_interface_ptr_map_, planning_factor_interface_); } void updateModuleParams(const std::vector & parameters) override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp index 5848cc75f148e..247e22e1aedad 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp @@ -46,7 +46,8 @@ class StaticObstacleAvoidanceModule : public SceneModuleInterface const std::string & name, rclcpp::Node & node, std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map); + objects_of_interest_marker_interface_ptr_map, + const std::shared_ptr & planning_factor_interface); CandidateOutput planCandidate() const override; BehaviorModuleOutput plan() override; @@ -131,9 +132,9 @@ class StaticObstacleAvoidanceModule : public SceneModuleInterface } if (finish_distance > -1.0e-03) { - steering_factor_interface_.set( - {left_shift.start_pose, left_shift.finish_pose}, {start_distance, finish_distance}, - SteeringFactor::LEFT, SteeringFactor::TURNING, ""); + planning_factor_interface_->add( + start_distance, finish_distance, left_shift.start_pose, left_shift.finish_pose, + PlanningFactor::SHIFT_LEFT, SafetyFactorArray{}); } } @@ -151,9 +152,9 @@ class StaticObstacleAvoidanceModule : public SceneModuleInterface } if (finish_distance > -1.0e-03) { - steering_factor_interface_.set( - {right_shift.start_pose, right_shift.finish_pose}, {start_distance, finish_distance}, - SteeringFactor::RIGHT, SteeringFactor::TURNING, ""); + planning_factor_interface_->add( + start_distance, finish_distance, right_shift.start_pose, right_shift.finish_pose, + PlanningFactor::SHIFT_RIGHT, SafetyFactorArray{}); } } } diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp index 48729c9c4fa0c..739b5b21f59dc 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp @@ -79,14 +79,13 @@ StaticObstacleAvoidanceModule::StaticObstacleAvoidanceModule( const std::string & name, rclcpp::Node & node, std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT + objects_of_interest_marker_interface_ptr_map, + const std::shared_ptr & planning_factor_interface) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, planning_factor_interface}, // NOLINT helper_{std::make_shared(parameters)}, parameters_{parameters}, generator_{parameters} { - steering_factor_interface_.init(PlanningBehavior::AVOIDANCE); - velocity_factor_interface_.init(PlanningBehavior::AVOIDANCE); } bool StaticObstacleAvoidanceModule::isExecutionRequested() const @@ -776,7 +775,7 @@ void StaticObstacleAvoidanceModule::updateEgoBehavior( insertReturnDeadLine(isBestEffort(parameters_->policy_deceleration), path); - setVelocityFactor(path.path); + set_longitudinal_planning_factor(path.path); } bool StaticObstacleAvoidanceModule::isSafePath( @@ -1209,13 +1208,12 @@ CandidateOutput StaticObstacleAvoidanceModule::planCandidate() const output.start_distance_to_path_change = sl_front.start_longitudinal; output.finish_distance_to_path_change = sl_back.end_longitudinal; - const uint16_t steering_factor_direction = std::invoke([&output]() { - return output.lateral_shift > 0.0 ? SteeringFactor::LEFT : SteeringFactor::RIGHT; + const uint16_t planning_factor_direction = std::invoke([&output]() { + return output.lateral_shift > 0.0 ? PlanningFactor::SHIFT_LEFT : PlanningFactor::SHIFT_RIGHT; }); - steering_factor_interface_.set( - {sl_front.start, sl_back.end}, - {output.start_distance_to_path_change, output.finish_distance_to_path_change}, - steering_factor_direction, SteeringFactor::APPROACHING, ""); + planning_factor_interface_->add( + output.start_distance_to_path_change, output.finish_distance_to_path_change, sl_front.start, + sl_back.end, planning_factor_direction, SafetyFactorArray{}, true, 0.0, output.lateral_shift); output.path_candidate = shifted_path.path; return output; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/scene.hpp index 5e8ef9fc8a063..91eff0b01346a 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/scene.hpp @@ -74,7 +74,9 @@ class BlindSpotModule : public SceneModuleInterfaceWithRTC BlindSpotModule( const int64_t module_id, const int64_t lane_id, const TurnDirection turn_direction, const std::shared_ptr planner_data, const PlannerParam & planner_param, - const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock); + const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface); /** * @brief plan go-stop velocity at traffic crossing with collision check between reference path diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/decisions.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/decisions.cpp index 64e1435167a89..a978c074e0018 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/decisions.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/decisions.cpp @@ -101,8 +101,11 @@ void BlindSpotModule::reactRTCApprovalByDecision( decision.stop_line_idx, planner_data_->vehicle_info_.max_longitudinal_offset_m, *path); const auto stop_pose = path->points.at(decision.stop_line_idx).point.pose; - velocity_factor_.set( - path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::UNKNOWN); + planning_factor_interface_->add( + path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose, + tier4_planning_msgs::msg::PlanningFactor::STOP, tier4_planning_msgs::msg::SafetyFactorArray{}, + true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, + "blind_spot(module is judging as UNSAFE)"); } return; } @@ -132,8 +135,11 @@ void BlindSpotModule::reactRTCApprovalByDecision( decision.stop_line_idx, planner_data_->vehicle_info_.max_longitudinal_offset_m, *path); const auto stop_pose = path->points.at(decision.stop_line_idx).point.pose; - velocity_factor_.set( - path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::UNKNOWN); + planning_factor_interface_->add( + path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose, + tier4_planning_msgs::msg::PlanningFactor::STOP, tier4_planning_msgs::msg::SafetyFactorArray{}, + true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, + "blind_spot(module is judging as SAFE and RTC is not approved)"); } return; } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/manager.cpp index d6cae9004600a..ee6516f025709 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/manager.cpp @@ -59,7 +59,7 @@ void BlindSpotModuleManager::launchNewModules(const tier4_planning_msgs::msg::Pa registerModule(std::make_shared( module_id, lane_id, turn_direction, planner_data_, planner_param_, - logger_.get_child("blind_spot_module"), clock_)); + logger_.get_child("blind_spot_module"), clock_, time_keeper_, planning_factor_interface_)); generateUUID(module_id); updateRTCStatus( getUUID(module_id), true, State::WAITING_FOR_EXECUTION, std::numeric_limits::lowest(), diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp index 8a9401646aaea..4fca5f821f934 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp @@ -40,14 +40,15 @@ namespace bg = boost::geometry; BlindSpotModule::BlindSpotModule( const int64_t module_id, const int64_t lane_id, const TurnDirection turn_direction, const std::shared_ptr planner_data, const PlannerParam & planner_param, - const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock) -: SceneModuleInterfaceWithRTC(module_id, logger, clock), + const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface) +: SceneModuleInterfaceWithRTC(module_id, logger, clock, time_keeper, planning_factor_interface), lane_id_(lane_id), planner_param_{planner_param}, turn_direction_(turn_direction), is_over_pass_judge_line_(false) { - velocity_factor_.init(PlanningBehavior::REAR_CHECK); sibling_straight_lanelet_ = getSiblingStraightLanelet( planner_data->route_handler_->getLaneletMapPtr()->laneletLayer.get(lane_id_), planner_data->route_handler_->getRoutingGraphPtr()); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.cpp index cdaff7225a7d2..5bfd31b75976a 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.cpp @@ -192,8 +192,8 @@ void CrosswalkModuleManager::launchNewModules(const PathWithLaneId & path) // NOTE: module_id is always a lane id so that isModuleRegistered works correctly in the case // where both regulatory element and non-regulatory element crosswalks exist. registerModule(std::make_shared( - node_, road_lanelet_id, crosswalk_lanelet_id, reg_elem_id, lanelet_map_ptr, p, logger, - clock_)); + node_, road_lanelet_id, crosswalk_lanelet_id, reg_elem_id, lanelet_map_ptr, p, logger, clock_, + time_keeper_, planning_factor_interface_)); generateUUID(crosswalk_lanelet_id); updateRTCStatus( getUUID(crosswalk_lanelet_id), true, State::WAITING_FOR_EXECUTION, diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 64f7e9e14dcd1..844647e33f8c0 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -34,12 +34,12 @@ #include #include #include +#include #include #include #include #include #include - namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; @@ -175,13 +175,14 @@ CrosswalkModule::CrosswalkModule( rclcpp::Node & node, const int64_t lane_id, const int64_t module_id, const std::optional & reg_elem_id, const lanelet::LaneletMapPtr & lanelet_map_ptr, const PlannerParam & planner_param, const rclcpp::Logger & logger, - const rclcpp::Clock::SharedPtr clock) -: SceneModuleInterfaceWithRTC(module_id, logger, clock), + const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface) +: SceneModuleInterfaceWithRTC(module_id, logger, clock, time_keeper, planning_factor_interface), module_id_(module_id), planner_param_(planner_param), use_regulatory_element_(reg_elem_id) { - velocity_factor_.init(PlanningBehavior::CROSSWALK); passed_safety_slow_point_ = false; if (use_regulatory_element_) { @@ -898,9 +899,11 @@ void CrosswalkModule::applySlowDown( } } if (slowdown_pose) - velocity_factor_.set( - output.points, planner_data_->current_odometry->pose, *slowdown_pose, - VelocityFactor::APPROACHING); + planning_factor_interface_->add( + output.points, planner_data_->current_odometry->pose, *slowdown_pose, *slowdown_pose, + tier4_planning_msgs::msg::PlanningFactor::SLOW_DOWN, + tier4_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, + safety_slow_down_speed, 0.0 /*shift distance*/, "crosswalk_safety_slowdown_for_approaching"); } void CrosswalkModule::applySlowDownByLanelet2Map( @@ -1377,9 +1380,11 @@ void CrosswalkModule::planStop( // Plan stop insertDecelPointWithDebugInfo(stop_factor->stop_pose.position, 0.0, ego_path); - velocity_factor_.set( + planning_factor_interface_->add( ego_path.points, planner_data_->current_odometry->pose, stop_factor->stop_pose, - VelocityFactor::UNKNOWN); + stop_factor->stop_pose, tier4_planning_msgs::msg::PlanningFactor::STOP, + tier4_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0 /*velocity*/, + 0.0 /*shift distance*/, "crosswalk_stop"); } bool CrosswalkModule::checkRestartSuppression( diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index d5a9e463c730b..f32ee96623822 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -334,7 +334,9 @@ class CrosswalkModule : public SceneModuleInterfaceWithRTC rclcpp::Node & node, const int64_t lane_id, const int64_t module_id, const std::optional & reg_elem_id, const lanelet::LaneletMapPtr & lanelet_map_ptr, const PlannerParam & planner_param, const rclcpp::Logger & logger, - const rclcpp::Clock::SharedPtr clock); + const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface); bool modifyPathVelocity(PathWithLaneId * path) override; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/manager.cpp index fb2c17d9e3745..f231d7adc3326 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/manager.cpp @@ -64,7 +64,8 @@ void DetectionAreaModuleManager::launchNewModules( if (!isModuleRegistered(module_id)) { registerModule(std::make_shared( module_id, lane_id, *detection_area_with_lane_id.first, planner_param_, - logger_.get_child("detection_area_module"), clock_)); + logger_.get_child("detection_area_module"), clock_, time_keeper_, + planning_factor_interface_)); } } } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp index 031c45753022e..59f6f20937f41 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp @@ -36,8 +36,10 @@ DetectionAreaModule::DetectionAreaModule( const int64_t module_id, const int64_t lane_id, const lanelet::autoware::DetectionArea & detection_area_reg_elem, const PlannerParam & planner_param, const rclcpp::Logger & logger, - const rclcpp::Clock::SharedPtr clock) -: SceneModuleInterface(module_id, logger, clock), + const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface) +: SceneModuleInterface(module_id, logger, clock, time_keeper, planning_factor_interface), lane_id_(lane_id), detection_area_reg_elem_(detection_area_reg_elem), state_(State::GO), diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.hpp index 9224cf4624687..1d3e5f3540ff3 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.hpp @@ -68,7 +68,9 @@ class DetectionAreaModule : public SceneModuleInterface const int64_t module_id, const int64_t lane_id, const lanelet::autoware::DetectionArea & detection_area_reg_elem, const PlannerParam & planner_param, const rclcpp::Logger & logger, - const rclcpp::Clock::SharedPtr clock); + const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface); bool modifyPathVelocity(PathWithLaneId * path) override; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.cpp index 41bdbe3e43c8b..d6f7dfbac92d4 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.cpp @@ -338,7 +338,8 @@ void IntersectionModuleManager::launchNewModules( } const auto new_module = std::make_shared( module_id, lane_id, planner_data_, intersection_param_, associative_ids, turn_direction, - has_traffic_light, node_, logger_.get_child("intersection_module"), clock_); + has_traffic_light, node_, logger_.get_child("intersection_module"), clock_, time_keeper_, + planning_factor_interface_); generateUUID(module_id); /* set RTC status as non_occluded status initially */ const UUID uuid = getUUID(new_module->getModuleId()); @@ -526,7 +527,8 @@ void MergeFromPrivateModuleManager::launchNewModules( planning_utils::getAssociativeIntersectionLanelets(ll, lanelet_map, routing_graph); registerModule(std::make_shared( module_id, lane_id, planner_data_, merge_from_private_area_param_, associative_ids, - logger_.get_child("merge_from_private_road_module"), clock_)); + logger_.get_child("merge_from_private_road_module"), clock_, time_keeper_, + planning_factor_interface_)); continue; } } else { @@ -540,7 +542,8 @@ void MergeFromPrivateModuleManager::launchNewModules( planning_utils::getAssociativeIntersectionLanelets(ll, lanelet_map, routing_graph); registerModule(std::make_shared( module_id, lane_id, planner_data_, merge_from_private_area_param_, associative_ids, - logger_.get_child("merge_from_private_road_module"), clock_)); + logger_.get_child("merge_from_private_road_module"), clock_, time_keeper_, + planning_factor_interface_)); continue; } } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp index 93a13a4d62737..2d5da0f070ed9 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -18,7 +18,6 @@ #include // for toGeomPoly #include -#include #include #include // for toPolygon2d #include @@ -52,8 +51,10 @@ IntersectionModule::IntersectionModule( [[maybe_unused]] std::shared_ptr planner_data, const PlannerParam & planner_param, const std::set & associative_ids, const std::string & turn_direction, const bool has_traffic_light, rclcpp::Node & node, - const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock) -: SceneModuleInterfaceWithRTC(module_id, logger, clock), + const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface) +: SceneModuleInterfaceWithRTC(module_id, logger, clock, time_keeper, planning_factor_interface), planner_param_(planner_param), lane_id_(lane_id), associative_ids_(associative_ids), @@ -61,8 +62,6 @@ IntersectionModule::IntersectionModule( has_traffic_light_(has_traffic_light), occlusion_uuid_(autoware::universe_utils::generateUUID()) { - velocity_factor_.init(PlanningBehavior::INTERSECTION); - { collision_state_machine_.setMarginTime( planner_param_.collision_detection.collision_detection_hold_time); @@ -705,7 +704,7 @@ void reactRTCApprovalByDecisionResult( [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, [[maybe_unused]] const double baselink2front, [[maybe_unused]] tier4_planning_msgs::msg::PathWithLaneId * path, - [[maybe_unused]] VelocityFactorInterface * velocity_factor, + [[maybe_unused]] motion_utils::PlanningFactorInterface * planning_factor_interface, [[maybe_unused]] IntersectionModule::DebugData * debug_data) { static_assert("Unsupported type passed to reactRTCByDecisionResult"); @@ -720,7 +719,7 @@ void reactRTCApprovalByDecisionResult( [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, [[maybe_unused]] const double baselink2front, [[maybe_unused]] tier4_planning_msgs::msg::PathWithLaneId * path, - [[maybe_unused]] VelocityFactorInterface * velocity_factor, + [[maybe_unused]] motion_utils::PlanningFactorInterface * planning_factor_interface, [[maybe_unused]] IntersectionModule::DebugData * debug_data) { return; @@ -734,7 +733,7 @@ void reactRTCApprovalByDecisionResult( [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, [[maybe_unused]] const double baselink2front, [[maybe_unused]] tier4_planning_msgs::msg::PathWithLaneId * path, - [[maybe_unused]] VelocityFactorInterface * velocity_factor, + [[maybe_unused]] motion_utils::PlanningFactorInterface * planning_factor_interface, [[maybe_unused]] IntersectionModule::DebugData * debug_data) { return; @@ -746,7 +745,8 @@ void reactRTCApprovalByDecisionResult( const StuckStop & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, - VelocityFactorInterface * velocity_factor, IntersectionModule::DebugData * debug_data) + motion_utils::PlanningFactorInterface * planning_factor_interface, + IntersectionModule::DebugData * debug_data) { RCLCPP_DEBUG( rclcpp::get_logger("reactRTCApprovalByDecisionResult"), @@ -760,9 +760,12 @@ void reactRTCApprovalByDecisionResult( debug_data->collision_stop_wall_pose = planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { - velocity_factor->set( + planning_factor_interface->add( path->points, path->points.at(closest_idx).point.pose, - path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, path->points.at(stopline_idx).point.pose, + tier4_planning_msgs::msg::PlanningFactor::STOP, + tier4_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0, + 0.0 /*shift distance*/, "intersection(pure StuckStop)"); } } if (!rtc_occlusion_approved && decision_result.occlusion_stopline_idx) { @@ -771,9 +774,13 @@ void reactRTCApprovalByDecisionResult( debug_data->occlusion_stop_wall_pose = planning_utils::getAheadPose(occlusion_stopline_idx, baselink2front, *path); { - velocity_factor->set( + planning_factor_interface->add( path->points, path->points.at(closest_idx).point.pose, - path->points.at(occlusion_stopline_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(occlusion_stopline_idx).point.pose, + path->points.at(occlusion_stopline_idx).point.pose, + tier4_planning_msgs::msg::PlanningFactor::STOP, + tier4_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0, + 0.0 /*shift distance*/, "intersection(StuckStop with occlusion)"); } } return; @@ -785,7 +792,8 @@ void reactRTCApprovalByDecisionResult( const YieldStuckStop & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, - VelocityFactorInterface * velocity_factor, IntersectionModule::DebugData * debug_data) + motion_utils::PlanningFactorInterface * planning_factor_interface, + IntersectionModule::DebugData * debug_data) { RCLCPP_DEBUG( rclcpp::get_logger("reactRTCApprovalByDecisionResult"), @@ -799,9 +807,12 @@ void reactRTCApprovalByDecisionResult( debug_data->collision_stop_wall_pose = planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { - velocity_factor->set( + planning_factor_interface->add( path->points, path->points.at(closest_idx).point.pose, - path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, path->points.at(stopline_idx).point.pose, + tier4_planning_msgs::msg::PlanningFactor::STOP, + tier4_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0, + 0.0 /*shift distance*/, "intersection(Yield Stuck)"); } } return; @@ -813,7 +824,8 @@ void reactRTCApprovalByDecisionResult( const NonOccludedCollisionStop & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, - VelocityFactorInterface * velocity_factor, IntersectionModule::DebugData * debug_data) + motion_utils::PlanningFactorInterface * planning_factor_interface, + IntersectionModule::DebugData * debug_data) { RCLCPP_DEBUG( rclcpp::get_logger("reactRTCApprovalByDecisionResult"), @@ -825,9 +837,12 @@ void reactRTCApprovalByDecisionResult( debug_data->collision_stop_wall_pose = planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { - velocity_factor->set( + planning_factor_interface->add( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, path->points.at(stopline_idx).point.pose, + tier4_planning_msgs::msg::PlanningFactor::STOP, + tier4_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0, + 0.0 /*shift distance*/, "intersection(CollisionStop)"); } } if (!rtc_occlusion_approved) { @@ -836,9 +851,12 @@ void reactRTCApprovalByDecisionResult( debug_data->occlusion_stop_wall_pose = planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { - velocity_factor->set( + planning_factor_interface->add( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, path->points.at(stopline_idx).point.pose, + tier4_planning_msgs::msg::PlanningFactor::STOP, + tier4_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0, + 0.0 /*shift distance*/, "intersection(CollisionStop with occlusion)"); } } return; @@ -849,7 +867,8 @@ void reactRTCApprovalByDecisionResult( const bool rtc_default_approved, const bool rtc_occlusion_approved, const FirstWaitBeforeOcclusion & decision_result, const IntersectionModule::PlannerParam & planner_param, const double baselink2front, - tier4_planning_msgs::msg::PathWithLaneId * path, VelocityFactorInterface * velocity_factor, + tier4_planning_msgs::msg::PathWithLaneId * path, + motion_utils::PlanningFactorInterface * planning_factor_interface, IntersectionModule::DebugData * debug_data) { RCLCPP_DEBUG( @@ -862,9 +881,12 @@ void reactRTCApprovalByDecisionResult( debug_data->occlusion_first_stop_wall_pose = planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { - velocity_factor->set( + planning_factor_interface->add( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, path->points.at(stopline_idx).point.pose, + tier4_planning_msgs::msg::PlanningFactor::STOP, + tier4_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0, + 0.0 /*shift distance*/, "intersection(FirstWaitBeforeOcclusion with collision)"); } } if (!rtc_occlusion_approved) { @@ -881,9 +903,12 @@ void reactRTCApprovalByDecisionResult( debug_data->occlusion_stop_wall_pose = planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { - velocity_factor->set( + planning_factor_interface->add( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, path->points.at(stopline_idx).point.pose, + tier4_planning_msgs::msg::PlanningFactor::STOP, + tier4_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0, + 0.0 /*shift distance*/, "intersection(FirstWaitBeforeOcclusion with occlusion)"); } } return; @@ -894,7 +919,8 @@ void reactRTCApprovalByDecisionResult( const bool rtc_default_approved, const bool rtc_occlusion_approved, const PeekingTowardOcclusion & decision_result, const IntersectionModule::PlannerParam & planner_param, const double baselink2front, - tier4_planning_msgs::msg::PathWithLaneId * path, VelocityFactorInterface * velocity_factor, + tier4_planning_msgs::msg::PathWithLaneId * path, + motion_utils::PlanningFactorInterface * planning_factor_interface, IntersectionModule::DebugData * debug_data) { RCLCPP_DEBUG( @@ -920,9 +946,13 @@ void reactRTCApprovalByDecisionResult( debug_data->static_occlusion_with_traffic_light_timeout = decision_result.static_occlusion_timeout; { - velocity_factor->set( + planning_factor_interface->add( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(occlusion_peeking_stopline).point.pose, VelocityFactor::UNKNOWN); + path->points.at(occlusion_peeking_stopline).point.pose, + path->points.at(occlusion_peeking_stopline).point.pose, + tier4_planning_msgs::msg::PlanningFactor::STOP, + tier4_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0, + 0.0 /*shift distance*/, "intersection(PeekingToOcclusion)"); } } if (!rtc_default_approved) { @@ -931,9 +961,12 @@ void reactRTCApprovalByDecisionResult( debug_data->collision_stop_wall_pose = planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { - velocity_factor->set( + planning_factor_interface->add( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, path->points.at(stopline_idx).point.pose, + tier4_planning_msgs::msg::PlanningFactor::STOP, + tier4_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0, + 0.0 /*shift distance*/, "intersection(PeekingToOcclusion while stopping for collision)"); } } return; @@ -945,7 +978,8 @@ void reactRTCApprovalByDecisionResult( const OccludedCollisionStop & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, - VelocityFactorInterface * velocity_factor, IntersectionModule::DebugData * debug_data) + motion_utils::PlanningFactorInterface * planning_factor_interface, + IntersectionModule::DebugData * debug_data) { RCLCPP_DEBUG( rclcpp::get_logger("reactRTCApprovalByDecisionResult"), @@ -957,9 +991,12 @@ void reactRTCApprovalByDecisionResult( debug_data->collision_stop_wall_pose = planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { - velocity_factor->set( + planning_factor_interface->add( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, path->points.at(stopline_idx).point.pose, + tier4_planning_msgs::msg::PlanningFactor::STOP, + tier4_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0, + 0.0 /*shift distance*/, "intersection(CollisionStop with occlusion)"); } } if (!rtc_occlusion_approved) { @@ -972,9 +1009,12 @@ void reactRTCApprovalByDecisionResult( debug_data->static_occlusion_with_traffic_light_timeout = decision_result.static_occlusion_timeout; { - velocity_factor->set( + planning_factor_interface->add( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, path->points.at(stopline_idx).point.pose, + tier4_planning_msgs::msg::PlanningFactor::STOP, + tier4_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0, + 0.0 /*shift distance*/, "intersection(CollisionStop with occlusion)"); } } return; @@ -986,7 +1026,8 @@ void reactRTCApprovalByDecisionResult( const OccludedAbsenceTrafficLight & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, - VelocityFactorInterface * velocity_factor, IntersectionModule::DebugData * debug_data) + motion_utils::PlanningFactorInterface * planning_factor_interface, + IntersectionModule::DebugData * debug_data) { RCLCPP_DEBUG( rclcpp::get_logger("reactRTCApprovalByDecisionResult"), @@ -998,9 +1039,13 @@ void reactRTCApprovalByDecisionResult( debug_data->collision_stop_wall_pose = planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { - velocity_factor->set( + planning_factor_interface->add( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, path->points.at(stopline_idx).point.pose, + tier4_planning_msgs::msg::PlanningFactor::STOP, + tier4_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0, + 0.0 /*shift distance*/, + "intersection(Occlusion without traffic light, collision detected)"); } } if (!rtc_occlusion_approved && decision_result.temporal_stop_before_attention_required) { @@ -1009,9 +1054,12 @@ void reactRTCApprovalByDecisionResult( debug_data->occlusion_stop_wall_pose = planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { - velocity_factor->set( + planning_factor_interface->add( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, path->points.at(stopline_idx).point.pose, + tier4_planning_msgs::msg::PlanningFactor::STOP, + tier4_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0, + 0.0 /*shift distance*/, "intersection(Occlusion without traffic light)"); } } if (!rtc_occlusion_approved && !decision_result.temporal_stop_before_attention_required) { @@ -1032,7 +1080,8 @@ void reactRTCApprovalByDecisionResult( const bool rtc_default_approved, const bool rtc_occlusion_approved, const Safe & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, - VelocityFactorInterface * velocity_factor, IntersectionModule::DebugData * debug_data) + motion_utils::PlanningFactorInterface * planning_factor_interface, + IntersectionModule::DebugData * debug_data) { RCLCPP_DEBUG( rclcpp::get_logger("reactRTCApprovalByDecisionResult"), @@ -1043,9 +1092,12 @@ void reactRTCApprovalByDecisionResult( debug_data->collision_stop_wall_pose = planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { - velocity_factor->set( + planning_factor_interface->add( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, path->points.at(stopline_idx).point.pose, + tier4_planning_msgs::msg::PlanningFactor::STOP, + tier4_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0, + 0.0 /*shift distance*/, "intersection(Safe, but RTC interrupted for collision)"); } } if (!rtc_occlusion_approved) { @@ -1054,9 +1106,12 @@ void reactRTCApprovalByDecisionResult( debug_data->occlusion_stop_wall_pose = planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { - velocity_factor->set( + planning_factor_interface->add( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, path->points.at(stopline_idx).point.pose, + tier4_planning_msgs::msg::PlanningFactor::STOP, + tier4_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0, + 0.0 /*shift distance*/, "intersection(Safe, but RTC interrupted for occlusion)"); } } return; @@ -1068,7 +1123,8 @@ void reactRTCApprovalByDecisionResult( const FullyPrioritized & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, - VelocityFactorInterface * velocity_factor, IntersectionModule::DebugData * debug_data) + motion_utils::PlanningFactorInterface * planning_factor_interface, + IntersectionModule::DebugData * debug_data) { RCLCPP_DEBUG( rclcpp::get_logger("reactRTCApprovalByDecisionResult"), @@ -1080,9 +1136,12 @@ void reactRTCApprovalByDecisionResult( debug_data->collision_stop_wall_pose = planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { - velocity_factor->set( + planning_factor_interface->add( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, path->points.at(stopline_idx).point.pose, + tier4_planning_msgs::msg::PlanningFactor::STOP, + tier4_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0, + 0.0 /*shift distance*/, "intersection(FullyPrioritized, collision detected)"); } } if (!rtc_occlusion_approved) { @@ -1091,9 +1150,13 @@ void reactRTCApprovalByDecisionResult( debug_data->occlusion_stop_wall_pose = planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { - velocity_factor->set( + planning_factor_interface->add( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, path->points.at(stopline_idx).point.pose, + tier4_planning_msgs::msg::PlanningFactor::STOP, + tier4_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0, + 0.0 /*shift distance*/, + "intersection(FullyPrioritized, RTC for occlusion is interrupting)"); } } return; @@ -1107,7 +1170,7 @@ void IntersectionModule::reactRTCApproval( VisitorSwitch{[&](const auto & decision) { reactRTCApprovalByDecisionResult( activated_, occlusion_activated_, decision, planner_param_, baselink2front, path, - &velocity_factor_, &debug_data_); + planning_factor_interface_.get(), &debug_data_); }}, decision_result); return; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp index 6c31be2ce83b9..db0cfbe98d53c 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -304,7 +304,9 @@ class IntersectionModule : public SceneModuleInterfaceWithRTC const int64_t module_id, const int64_t lane_id, std::shared_ptr planner_data, const PlannerParam & planner_param, const std::set & associative_ids, const std::string & turn_direction, const bool has_traffic_light, rclcpp::Node & node, - const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock); + const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface); /** *********************************************************** diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp index 3dfdcc36c0cff..fc442337198af 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp @@ -41,12 +41,13 @@ MergeFromPrivateRoadModule::MergeFromPrivateRoadModule( const int64_t module_id, const int64_t lane_id, [[maybe_unused]] std::shared_ptr planner_data, const PlannerParam & planner_param, const std::set & associative_ids, - const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock) -: SceneModuleInterface(module_id, logger, clock), + const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface) +: SceneModuleInterface(module_id, logger, clock, time_keeper, planning_factor_interface), lane_id_(lane_id), associative_ids_(associative_ids) { - velocity_factor_.init(PlanningBehavior::MERGE); planner_param_ = planner_param; state_machine_.setState(StateMachine::State::STOP); } @@ -153,8 +154,10 @@ bool MergeFromPrivateRoadModule::modifyPathVelocity(PathWithLaneId * path) /* get stop point and stop factor */ const auto & stop_pose = path->points.at(stopline_idx).point.pose; - velocity_factor_.set( - path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::UNKNOWN); + planning_factor_interface_->add( + path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose, + tier4_planning_msgs::msg::PlanningFactor::STOP, tier4_planning_msgs::msg::SafetyFactorArray{}, + true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, "merge_from_private"); const double signed_arc_dist_to_stop_point = autoware::motion_utils::calcSignedArcLength( path->points, current_pose.position, path->points.at(stopline_idx).point.pose.position); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp index dc8bf1a96a7a2..fe446d304d9e0 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp @@ -61,7 +61,9 @@ class MergeFromPrivateRoadModule : public SceneModuleInterface MergeFromPrivateRoadModule( const int64_t module_id, const int64_t lane_id, std::shared_ptr planner_data, const PlannerParam & planner_param, const std::set & associative_ids, - const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock); + const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface); /** * @brief plan go-stop velocity at traffic crossing with collision check between reference path diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/manager.cpp index 9cb1153a8edd2..517568c93bd35 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/manager.cpp @@ -51,7 +51,8 @@ void NoDrivableLaneModuleManager::launchNewModules( } registerModule(std::make_shared( - module_id, lane_id, planner_param_, logger_.get_child("no_drivable_lane_module"), clock_)); + module_id, lane_id, planner_param_, logger_.get_child("no_drivable_lane_module"), clock_, + time_keeper_, planning_factor_interface_)); } } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp index 8365251904b18..f32210bc502bf 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp @@ -21,14 +21,18 @@ #include #include +#include + namespace autoware::behavior_velocity_planner { using autoware::universe_utils::createPoint; NoDrivableLaneModule::NoDrivableLaneModule( const int64_t module_id, const int64_t lane_id, const PlannerParam & planner_param, - const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock) -: SceneModuleInterface(module_id, logger, clock), + const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface) +: SceneModuleInterface(module_id, logger, clock, time_keeper, planning_factor_interface), lane_id_(lane_id), planner_param_(planner_param), debug_data_(), diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.hpp index d8c5e3e0425d1..835e946443e90 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.hpp @@ -55,7 +55,9 @@ class NoDrivableLaneModule : public SceneModuleInterface NoDrivableLaneModule( const int64_t module_id, const int64_t lane_id, const PlannerParam & planner_param, - const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock); + const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface); bool modifyPathVelocity(PathWithLaneId * path) override; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/manager.cpp index dca2dde33b693..55b6c0dffd1a4 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/manager.cpp @@ -60,7 +60,7 @@ void NoStoppingAreaModuleManager::launchNewModules( // assign 1 no stopping area for each module registerModule(std::make_shared( module_id, lane_id, *m.first, planner_param_, logger_.get_child("no_stopping_area_module"), - clock_)); + clock_, time_keeper_, planning_factor_interface_)); generateUUID(module_id); updateRTCStatus( getUUID(module_id), true, State::WAITING_FOR_EXECUTION, diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp index 5c79ec69a9d98..bcb8b365f6205 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp @@ -30,6 +30,7 @@ #include #include +#include #include namespace autoware::behavior_velocity_planner @@ -40,8 +41,10 @@ NoStoppingAreaModule::NoStoppingAreaModule( const int64_t module_id, const int64_t lane_id, const lanelet::autoware::NoStoppingArea & no_stopping_area_reg_elem, const PlannerParam & planner_param, const rclcpp::Logger & logger, - const rclcpp::Clock::SharedPtr clock) -: SceneModuleInterfaceWithRTC(module_id, logger, clock), + const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface) +: SceneModuleInterfaceWithRTC(module_id, logger, clock, time_keeper, planning_factor_interface), lane_id_(lane_id), no_stopping_area_reg_elem_(no_stopping_area_reg_elem), planner_param_(planner_param), diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.hpp index 1eafcf157623d..0d53441924805 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.hpp @@ -57,7 +57,9 @@ class NoStoppingAreaModule : public SceneModuleInterfaceWithRTC const int64_t module_id, const int64_t lane_id, const lanelet::autoware::NoStoppingArea & no_stopping_area_reg_elem, const PlannerParam & planner_param, const rclcpp::Logger & logger, - const rclcpp::Clock::SharedPtr clock); + const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface); bool modifyPathVelocity(PathWithLaneId * path) override; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/manager.cpp index c4dace9d49244..d28cff55a7a8d 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/manager.cpp @@ -123,8 +123,8 @@ void OcclusionSpotModuleManager::launchNewModules( // general if (!isModuleRegistered(module_id_)) { registerModule(std::make_shared( - module_id_, planner_data_, planner_param_, logger_.get_child("occlusion_spot_module"), - clock_)); + module_id_, planner_data_, planner_param_, logger_.get_child("occlusion_spot_module"), clock_, + time_keeper_, planning_factor_interface_)); } } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp index c5d1cf61614b2..1163b00e08ccb 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp @@ -64,8 +64,11 @@ namespace utils = occlusion_spot_utils; OcclusionSpotModule::OcclusionSpotModule( const int64_t module_id, const std::shared_ptr & planner_data, const PlannerParam & planner_param, const rclcpp::Logger & logger, - const rclcpp::Clock::SharedPtr clock) -: SceneModuleInterface(module_id, logger, clock), param_(planner_param) + const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface) +: SceneModuleInterface(module_id, logger, clock, time_keeper, planning_factor_interface), + param_(planner_param) { velocity_factor_.init(PlanningBehavior::UNKNOWN); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp index 35c409a9c459b..22b2a91be66b0 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp @@ -48,7 +48,9 @@ class OcclusionSpotModule : public SceneModuleInterface OcclusionSpotModule( const int64_t module_id, const std::shared_ptr & planner_data, const PlannerParam & planner_param, const rclcpp::Logger & logger, - const rclcpp::Clock::SharedPtr clock); + const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface); /** * @brief plan occlusion spot velocity at unknown area in occupancy grid diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp index a891b011dbab8..ad1ae1d47664a 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp @@ -17,6 +17,7 @@ #include #include +#include #include #include #include @@ -79,7 +80,9 @@ class SceneModuleInterface { public: explicit SceneModuleInterface( - const int64_t module_id, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock); + const int64_t module_id, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface); virtual ~SceneModuleInterface() = default; virtual bool modifyPathVelocity(PathWithLaneId * path) = 0; @@ -94,13 +97,6 @@ class SceneModuleInterface planner_data_ = planner_data; } - void setTimeKeeper(const std::shared_ptr & time_keeper) - { - time_keeper_ = time_keeper; - } - - std::shared_ptr getTimeKeeper() { return time_keeper_; } - void resetVelocityFactor() { velocity_factor_.reset(); } VelocityFactor getVelocityFactor() const { return velocity_factor_.get(); } std::vector getObjectsOfInterestData() const { return objects_of_interest_; } @@ -111,9 +107,10 @@ class SceneModuleInterface rclcpp::Logger logger_; rclcpp::Clock::SharedPtr clock_; std::shared_ptr planner_data_; - autoware::motion_utils::VelocityFactorInterface velocity_factor_; + autoware::motion_utils::VelocityFactorInterface velocity_factor_; // TODO(soblin): remove this std::vector objects_of_interest_; mutable std::shared_ptr time_keeper_; + std::shared_ptr planning_factor_interface_; void setObjectsOfInterestData( const geometry_msgs::msg::Pose & pose, const autoware_perception_msgs::msg::Shape & shape, @@ -148,6 +145,8 @@ class SceneModuleManagerInterface std::string("~/virtual_wall/") + module_name, 5); pub_velocity_factor_ = node.create_publisher( std::string("/planning/velocity_factors/") + module_name, 1); + planning_factor_interface_ = + std::make_shared(&node, module_name); processing_time_publisher_ = std::make_shared(&node, "~/debug"); @@ -191,6 +190,7 @@ class SceneModuleManagerInterface scene_module->modifyPathVelocity(path); // The velocity factor must be called after modifyPathVelocity. + // TODO(soblin): remove this const auto velocity_factor = scene_module->getVelocityFactor(); if (velocity_factor.behavior != PlanningBehavior::UNKNOWN) { velocity_factor_array.factors.emplace_back(velocity_factor); @@ -204,6 +204,7 @@ class SceneModuleManagerInterface } pub_velocity_factor_->publish(velocity_factor_array); + planning_factor_interface_->publish(); pub_debug_->publish(debug_marker_array); if (is_publish_debug_path_) { tier4_planning_msgs::msg::PathWithLaneId debug_path; @@ -247,7 +248,6 @@ class SceneModuleManagerInterface logger_, "register task: module = %s, id = %lu", getModuleName(), scene_module->getModuleId()); registered_module_id_set_.emplace(scene_module->getModuleId()); - scene_module->setTimeKeeper(time_keeper_); scene_modules_.insert(scene_module); } @@ -282,6 +282,8 @@ class SceneModuleManagerInterface rclcpp::Publisher::SharedPtr pub_processing_time_detail_; std::shared_ptr time_keeper_; + + std::shared_ptr planning_factor_interface_; }; extern template SceneModuleManagerInterface::SceneModuleManagerInterface( rclcpp::Node & node, [[maybe_unused]] const char * module_name); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp index ffd454012d13e..db2a274272f9f 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp @@ -25,11 +25,14 @@ namespace autoware::behavior_velocity_planner { SceneModuleInterface::SceneModuleInterface( - const int64_t module_id, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock) + const int64_t module_id, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface) : module_id_(module_id), logger_(logger), clock_(clock), - time_keeper_(std::shared_ptr()) + time_keeper_(time_keeper), + planning_factor_interface_(planning_factor_interface) { } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp index 4e30ab019aa4e..a955538f4f9fe 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp @@ -52,7 +52,9 @@ class SceneModuleInterfaceWithRTC : public SceneModuleInterface { public: explicit SceneModuleInterfaceWithRTC( - const int64_t module_id, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock); + const int64_t module_id, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface); virtual ~SceneModuleInterfaceWithRTC() = default; void setActivation(const bool activated) { activated_ = activated; } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/src/scene_module_interface_with_rtc.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/src/scene_module_interface_with_rtc.cpp index abac509fd2b2b..2e73b35e20ed9 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/src/scene_module_interface_with_rtc.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/src/scene_module_interface_with_rtc.cpp @@ -27,8 +27,10 @@ namespace autoware::behavior_velocity_planner { SceneModuleInterfaceWithRTC::SceneModuleInterfaceWithRTC( - const int64_t module_id, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock) -: SceneModuleInterface(module_id, logger, clock), + const int64_t module_id, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface) +: SceneModuleInterface(module_id, logger, clock, time_keeper, planning_factor_interface), activated_(false), safe_(false), distance_(std::numeric_limits::lowest()) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/manager.cpp index 4a16f263d0a54..4af7882461643 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/manager.cpp @@ -156,7 +156,8 @@ void RunOutModuleManager::launchNewModules(const tier4_planning_msgs::msg::PathW if (!isModuleRegistered(module_id)) { registerModule(std::make_shared( module_id, planner_data_, planner_param_, logger_.get_child("run_out_module"), - std::move(dynamic_obstacle_creator_), debug_ptr_, clock_)); + std::move(dynamic_obstacle_creator_), debug_ptr_, clock_, time_keeper_, + planning_factor_interface_)); } } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp index efc2d458ae2a7..193ba5eab0553 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp @@ -45,15 +45,15 @@ RunOutModule::RunOutModule( const int64_t module_id, const std::shared_ptr & planner_data, const PlannerParam & planner_param, const rclcpp::Logger logger, std::unique_ptr dynamic_obstacle_creator, - const std::shared_ptr & debug_ptr, const rclcpp::Clock::SharedPtr clock) -: SceneModuleInterface(module_id, logger, clock), + const std::shared_ptr & debug_ptr, const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface) +: SceneModuleInterface(module_id, logger, clock, time_keeper, planning_factor_interface), planner_param_(planner_param), dynamic_obstacle_creator_(std::move(dynamic_obstacle_creator)), debug_ptr_(debug_ptr), state_machine_(std::make_unique(planner_param.approaching.state)) { - velocity_factor_.init(PlanningBehavior::RUN_OUT); - if (planner_param.run_out.use_partition_lanelet) { const lanelet::LaneletMapConstPtr & ll = planner_data->route_handler_->getLaneletMapPtr(); planning_utils::getAllPartitionLanelets(ll, partition_lanelets_); @@ -770,9 +770,10 @@ bool RunOutModule::insertStopPoint( stop_point_with_lane_id.point.pose = *stop_point; planning_utils::insertVelocity(path, stop_point_with_lane_id, 0.0, insert_idx); - velocity_factor_.set( - path.points, planner_data_->current_odometry->pose, stop_point.value(), VelocityFactor::UNKNOWN, - "run_out"); + planning_factor_interface_->add( + path.points, planner_data_->current_odometry->pose, stop_point.value(), stop_point.value(), + tier4_planning_msgs::msg::PlanningFactor::STOP, tier4_planning_msgs::msg::SafetyFactorArray{}, + true /*is_driving_forward*/, 0.0 /*velocity*/, 0.0 /*shift_distance*/, "run_out_stop"); return true; } @@ -876,8 +877,11 @@ void RunOutModule::insertApproachingVelocity( return; } - velocity_factor_.set( - output_path.points, current_pose, stop_point.value(), VelocityFactor::UNKNOWN, "run_out"); + planning_factor_interface_->add( + output_path.points, planner_data_->current_odometry->pose, stop_point.value(), + stop_point.value(), tier4_planning_msgs::msg::PlanningFactor::STOP, + tier4_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0 /*velocity*/, + 0.0 /*shift_distance*/, "run_out_approaching_velocity"); // debug debug_ptr_->pushStopPose(autoware::universe_utils::calcOffsetPose( diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.hpp index 83123c71f461e..49de16753a869 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.hpp @@ -47,7 +47,9 @@ class RunOutModule : public SceneModuleInterface const int64_t module_id, const std::shared_ptr & planner_data, const PlannerParam & planner_param, const rclcpp::Logger logger, std::unique_ptr dynamic_obstacle_creator, - const std::shared_ptr & debug_ptr, const rclcpp::Clock::SharedPtr clock); + const std::shared_ptr & debug_ptr, const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface); bool modifyPathVelocity(PathWithLaneId * path) override; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/manager.cpp index 4677d49b78f4b..a69e33e9e0391 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/manager.cpp @@ -63,7 +63,7 @@ void SpeedBumpModuleManager::launchNewModules(const tier4_planning_msgs::msg::Pa if (!isModuleRegistered(module_id)) { registerModule(std::make_shared( module_id, lane_id, *speed_bump_with_lane_id.first, planner_param_, - logger_.get_child("speed_bump_module"), clock_)); + logger_.get_child("speed_bump_module"), clock_, time_keeper_, planning_factor_interface_)); } } } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/scene.cpp index 54ea807f3268b..4af7801e50ba3 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/scene.cpp @@ -21,6 +21,7 @@ #include #include +#include #include namespace autoware::behavior_velocity_planner @@ -33,8 +34,10 @@ using geometry_msgs::msg::Point32; SpeedBumpModule::SpeedBumpModule( const int64_t module_id, const int64_t lane_id, const lanelet::autoware::SpeedBump & speed_bump_reg_elem, const PlannerParam & planner_param, - const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock) -: SceneModuleInterface(module_id, logger, clock), + const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface) +: SceneModuleInterface(module_id, logger, clock, time_keeper, planning_factor_interface), module_id_(module_id), lane_id_(lane_id), speed_bump_reg_elem_(std::move(speed_bump_reg_elem)), diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/scene.hpp index 176a01d5112c5..e3ee2c0566381 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/scene.hpp @@ -21,6 +21,7 @@ #include #include +#include #include #include @@ -54,7 +55,9 @@ class SpeedBumpModule : public SceneModuleInterface SpeedBumpModule( const int64_t module_id, const int64_t lane_id, const lanelet::autoware::SpeedBump & speed_bump_reg_elem, const PlannerParam & planner_param, - const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock); + const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface); bool modifyPathVelocity(PathWithLaneId * path) override; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/manager.cpp index b305a1d2aa404..e289779df34b6 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/manager.cpp @@ -81,7 +81,7 @@ void StopLineModuleManager::launchNewModules(const tier4_planning_msgs::msg::Pat if (!isModuleRegistered(module_id)) { registerModule(std::make_shared( module_id, stop_line_with_lane_id.first, planner_param_, - logger_.get_child("stop_line_module"), clock_)); + logger_.get_child("stop_line_module"), clock_, time_keeper_, planning_factor_interface_)); } } } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp index 2a9c5dab1ebd9..71a5ea3b9e807 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp @@ -20,6 +20,7 @@ #include +#include #include #include @@ -28,8 +29,10 @@ namespace autoware::behavior_velocity_planner StopLineModule::StopLineModule( const int64_t module_id, lanelet::ConstLineString3d stop_line, const PlannerParam & planner_param, - const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock) -: SceneModuleInterface(module_id, logger, clock), + const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface) +: SceneModuleInterface(module_id, logger, clock, time_keeper, planning_factor_interface), stop_line_(std::move(stop_line)), planner_param_(planner_param), state_(State::APPROACH), diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.hpp index 9ac1463da8618..aac830b0e9f24 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.hpp @@ -30,6 +30,7 @@ #include +#include #include #include @@ -68,7 +69,9 @@ class StopLineModule : public SceneModuleInterface StopLineModule( const int64_t module_id, lanelet::ConstLineString3d stop_line, const PlannerParam & planner_param, const rclcpp::Logger & logger, - const rclcpp::Clock::SharedPtr clock); + const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface); bool modifyPathVelocity(PathWithLaneId * path) override; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/test/test_scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/test/test_scene.cpp index 1eafb71eb403c..e304b479a005d 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/test/test_scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/test/test_scene.cpp @@ -74,7 +74,10 @@ class StopLineModuleTest : public ::testing::Test clock_ = std::make_shared(); module_ = std::make_shared( - 1, stop_line_, planner_param_, rclcpp::get_logger("test_logger"), clock_); + 1, stop_line_, planner_param_, rclcpp::get_logger("test_logger"), clock_, + std::make_shared(), + std::make_shared( + node_.get(), "test_stopline")); module_->setPlannerData(planner_data_); } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/manager.cpp index 4325cc1d5aaf9..a004f5b823138 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/manager.cpp @@ -42,8 +42,9 @@ void TemplateModuleManager::launchNewModules( { int64_t module_id = 0; if (!isModuleRegistered(module_id)) { - registerModule( - std::make_shared(module_id, logger_.get_child(getModuleName()), clock_)); + registerModule(std::make_shared( + module_id, logger_.get_child(getModuleName()), clock_, time_keeper_, + planning_factor_interface_)); } } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.cpp index 3ce8502baaf63..d8eea337e7186 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.cpp @@ -19,14 +19,17 @@ #include +#include #include namespace autoware::behavior_velocity_planner { TemplateModule::TemplateModule( - const int64_t module_id, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock) -: SceneModuleInterface(module_id, logger, clock) + const int64_t module_id, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface) +: SceneModuleInterface(module_id, logger, clock, time_keeper, planning_factor_interface) { } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.hpp index 70cd5cb1235e7..ba078f3fd6421 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.hpp @@ -18,9 +18,9 @@ #include #include +#include #include #include - namespace autoware::behavior_velocity_planner { using tier4_planning_msgs::msg::PathWithLaneId; @@ -29,7 +29,9 @@ class TemplateModule : public SceneModuleInterface { public: TemplateModule( - const int64_t module_id, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock); + const int64_t module_id, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface); /** * @brief Modify the velocity of path points. diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.cpp index 1b66824d04623..9a402f31af0e4 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.cpp @@ -114,7 +114,8 @@ void TrafficLightModuleManager::launchNewModules( if (!isModuleRegisteredFromExistingAssociatedModule(lane_id)) { registerModule(std::make_shared( lane_id, *(traffic_light_reg_elem.first), traffic_light_reg_elem.second, planner_param_, - logger_.get_child("traffic_light_module"), clock_)); + logger_.get_child("traffic_light_module"), clock_, time_keeper_, + planning_factor_interface_)); generateUUID(lane_id); updateRTCStatus( getUUID(lane_id), true, State::WAITING_FOR_EXECUTION, std::numeric_limits::lowest(), diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp index 458d8e1588a5b..b051d5ff7eb76 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp @@ -43,8 +43,10 @@ namespace autoware::behavior_velocity_planner TrafficLightModule::TrafficLightModule( const int64_t lane_id, const lanelet::TrafficLight & traffic_light_reg_elem, lanelet::ConstLanelet lane, const PlannerParam & planner_param, const rclcpp::Logger logger, - const rclcpp::Clock::SharedPtr clock) -: SceneModuleInterfaceWithRTC(lane_id, logger, clock), + const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface) +: SceneModuleInterfaceWithRTC(lane_id, logger, clock, time_keeper, planning_factor_interface), lane_id_(lane_id), traffic_light_reg_elem_(traffic_light_reg_elem), lane_(lane), diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.hpp index 3af13bc1927ce..c30cbbdfc1477 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.hpp @@ -69,7 +69,9 @@ class TrafficLightModule : public SceneModuleInterfaceWithRTC TrafficLightModule( const int64_t lane_id, const lanelet::TrafficLight & traffic_light_reg_elem, lanelet::ConstLanelet lane, const PlannerParam & planner_param, const rclcpp::Logger logger, - const rclcpp::Clock::SharedPtr clock); + const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface); bool modifyPathVelocity(PathWithLaneId * path) override; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/manager.cpp index 3815c83d3b6ab..dade98dfc1133 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/manager.cpp @@ -94,7 +94,8 @@ void VirtualTrafficLightModuleManager::launchNewModules( ego_path_linestring, lanelet::utils::to2D(stop_line_opt.value()).basicLineString())) { registerModule(std::make_shared( module_id, lane_id, *m.first, m.second, planner_param_, - logger_.get_child("virtual_traffic_light_module"), clock_)); + logger_.get_child("virtual_traffic_light_module"), clock_, time_keeper_, + planning_factor_interface_)); } } } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp index 86239816ed6f2..9ba7b0bccf1b9 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp @@ -20,6 +20,7 @@ #include #include +#include #include #include @@ -38,8 +39,10 @@ VirtualTrafficLightModule::VirtualTrafficLightModule( const int64_t module_id, const int64_t lane_id, const lanelet::autoware::VirtualTrafficLight & reg_elem, lanelet::ConstLanelet lane, const PlannerParam & planner_param, const rclcpp::Logger logger, - const rclcpp::Clock::SharedPtr clock) -: SceneModuleInterface(module_id, logger, clock), + const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface) +: SceneModuleInterface(module_id, logger, clock, time_keeper, planning_factor_interface), lane_id_(lane_id), reg_elem_(reg_elem), lane_(lane), diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp index 7f37e7078a431..9e7a1192d9869 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp @@ -31,6 +31,7 @@ #include #include +#include #include #include @@ -81,7 +82,9 @@ class VirtualTrafficLightModule : public SceneModuleInterface const int64_t module_id, const int64_t lane_id, const lanelet::autoware::VirtualTrafficLight & reg_elem, lanelet::ConstLanelet lane, const PlannerParam & planner_param, const rclcpp::Logger logger, - const rclcpp::Clock::SharedPtr clock); + const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface); bool modifyPathVelocity(PathWithLaneId * path) override; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/manager.cpp index 0f1a7509043b5..bfa8a96531090 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/manager.cpp @@ -61,7 +61,8 @@ void WalkwayModuleManager::launchNewModules(const PathWithLaneId & path) const auto lanelet_map_ptr = planner_data_->route_handler_->getLaneletMapPtr(); registerModule(std::make_shared( - lanelet.id(), lanelet_map_ptr, p, use_regulatory_element, logger, clock_)); + lanelet.id(), lanelet_map_ptr, p, use_regulatory_element, logger, clock_, time_keeper_, + planning_factor_interface_)); }; const auto crosswalk_leg_elem_map = planning_utils::getRegElemMapOnPath( diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.cpp index 6a7505930a334..94421ae27e077 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.cpp @@ -18,6 +18,7 @@ #include #include +#include #include namespace autoware::behavior_velocity_planner @@ -32,15 +33,15 @@ using autoware::universe_utils::getPose; WalkwayModule::WalkwayModule( const int64_t module_id, const lanelet::LaneletMapPtr & lanelet_map_ptr, const PlannerParam & planner_param, const bool use_regulatory_element, - const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock) -: SceneModuleInterface(module_id, logger, clock), + const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface) +: SceneModuleInterface(module_id, logger, clock, time_keeper, planning_factor_interface), module_id_(module_id), state_(State::APPROACH), planner_param_(planner_param), use_regulatory_element_(use_regulatory_element) { - velocity_factor_.init(PlanningBehavior::SIDEWALK); - if (use_regulatory_element_) { const auto reg_elem_ptr = std::dynamic_pointer_cast( lanelet_map_ptr->regulatoryElementLayer.get(module_id)); @@ -119,9 +120,10 @@ bool WalkwayModule::modifyPathVelocity(PathWithLaneId * path) } /* get stop point and stop factor */ - velocity_factor_.set( - path->points, planner_data_->current_odometry->pose, stop_pose.value(), - VelocityFactor::UNKNOWN); + planning_factor_interface_->add( + path->points, planner_data_->current_odometry->pose, stop_pose.value(), stop_pose.value(), + tier4_planning_msgs::msg::PlanningFactor::STOP, tier4_planning_msgs::msg::SafetyFactorArray{}, + true /*is_driving_forward*/, 0.0 /*velocity*/, 0.0 /*shift distance*/, "walkway_stop"); // use arc length to identify if ego vehicle is in front of walkway stop or not. const double signed_arc_dist_to_stop_point = diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.hpp index df54eafd11cc2..1bd5003498d34 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.hpp @@ -44,7 +44,9 @@ class WalkwayModule : public SceneModuleInterface WalkwayModule( const int64_t module_id, const lanelet::LaneletMapPtr & lanelet_map_ptr, const PlannerParam & planner_param, const bool use_regulatory_element, - const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock); + const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock, + const std::shared_ptr time_keeper, + const std::shared_ptr planning_factor_interface); bool modifyPathVelocity(PathWithLaneId * path) override; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp index 7fd5834ba2cfa..2000615b51e2c 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp @@ -43,7 +43,9 @@ void DynamicObstacleStopModule::init(rclcpp::Node & node, const std::string & mo module_name_ = module_name; logger_ = node.get_logger().get_child(ns_); clock_ = node.get_clock(); - velocity_factor_interface_.init(autoware::motion_utils::PlanningBehavior::ROUTE_OBSTACLE); + + planning_factor_interface_ = std::make_unique( + &node, "dynamic_obstacle_stop"); debug_publisher_ = node.create_publisher("~/" + ns_ + "/debug_markers", 1); @@ -160,15 +162,9 @@ VelocityPlanningResult DynamicObstacleStopModule::plan( debug_data_.stop_pose = stop_pose; if (stop_pose) { result.stop_points.push_back(stop_pose->position); - const auto stop_pose_reached = - planner_data->current_odometry.twist.twist.linear.x < 1e-3 && - autoware::universe_utils::calcDistance2d(ego_data.pose, *stop_pose) < 1e-3; - velocity_factor_interface_.set( - ego_trajectory_points, ego_data.pose, *stop_pose, - stop_pose_reached ? autoware::motion_utils::VelocityFactor::STOPPED - : autoware::motion_utils::VelocityFactor::APPROACHING, - "dynamic_obstacle_stop"); - result.velocity_factor = velocity_factor_interface_.get(); + planning_factor_interface_->add( + ego_trajectory_points, ego_data.pose, *stop_pose, PlanningFactor::STOP, + SafetyFactorArray{}); create_virtual_walls(); } } diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.hpp index 1843d26a22a29..82a6d790bebe7 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.hpp @@ -33,6 +33,7 @@ class DynamicObstacleStopModule : public PluginModuleInterface { public: void init(rclcpp::Node & node, const std::string & module_name) override; + void publish_planning_factor() override { planning_factor_interface_->publish(); }; void update_parameters(const std::vector & parameters) override; VelocityPlanningResult plan( const std::vector & ego_trajectory_points, diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp index 1923f023552e3..eb89c027a3b48 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp @@ -48,7 +48,6 @@ void ObstacleVelocityLimiterModule::init(rclcpp::Node & node, const std::string projection_params_ = obstacle_velocity_limiter::ProjectionParameters(node); obstacle_params_ = obstacle_velocity_limiter::ObstacleParameters(node); velocity_params_ = obstacle_velocity_limiter::VelocityParameters(node); - velocity_factor_interface_.init(autoware::motion_utils::PlanningBehavior::ROUTE_OBSTACLE); debug_publisher_ = node.create_publisher("~/" + ns_ + "/debug_markers", 1); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp index bd85546cb6c56..532cc1e8c7d51 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp @@ -58,7 +58,9 @@ void OutOfLaneModule::init(rclcpp::Node & node, const std::string & module_name) logger_ = node.get_logger(); clock_ = node.get_clock(); init_parameters(node); - velocity_factor_interface_.init(motion_utils::PlanningBehavior::ROUTE_OBSTACLE); + + planning_factor_interface_ = + std::make_unique(&node, "out_of_lane"); debug_publisher_ = node.create_publisher("~/" + ns_ + "/debug_markers", 1); @@ -310,15 +312,9 @@ VelocityPlanningResult OutOfLaneModule::plan( slowdown_pose->position, slowdown_pose->position, slowdown_velocity); } - const auto is_approaching = - motion_utils::calcSignedArcLength( - ego_trajectory_points, ego_data.pose.position, slowdown_pose->position) > 0.1 && - planner_data->current_odometry.twist.twist.linear.x > 0.1; - const auto status = is_approaching ? motion_utils::VelocityFactor::APPROACHING - : motion_utils::VelocityFactor::STOPPED; - velocity_factor_interface_.set( - ego_trajectory_points, ego_data.pose, *slowdown_pose, status, "out_of_lane"); - result.velocity_factor = velocity_factor_interface_.get(); + planning_factor_interface_->add( + ego_trajectory_points, ego_data.pose, *slowdown_pose, PlanningFactor::SLOW_DOWN, + SafetyFactorArray{}); virtual_wall_marker_creator.add_virtual_walls( out_of_lane::debug::create_virtual_walls(*slowdown_pose, slowdown_velocity == 0.0, params_)); virtual_wall_publisher_->publish(virtual_wall_marker_creator.create_markers(clock_->now())); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp index 72f20f1c63d96..0e73994dd73a7 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp @@ -38,6 +38,7 @@ class OutOfLaneModule : public PluginModuleInterface { public: void init(rclcpp::Node & node, const std::string & module_name) override; + void publish_planning_factor() override { planning_factor_interface_->publish(); }; void update_parameters(const std::vector & parameters) override; VelocityPlanningResult plan( const std::vector & ego_trajectory_points, diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp index 53860c390b4db..6d683acff667f 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp @@ -18,7 +18,7 @@ #include "planner_data.hpp" #include "velocity_planning_result.hpp" -#include +#include #include #include @@ -32,6 +32,9 @@ namespace autoware::motion_velocity_planner { +using tier4_planning_msgs::msg::PlanningFactor; +using tier4_planning_msgs::msg::SafetyFactorArray; + class PluginModuleInterface { public: @@ -42,7 +45,7 @@ class PluginModuleInterface const std::vector & ego_trajectory_points, const std::shared_ptr planner_data) = 0; virtual std::string get_module_name() const = 0; - autoware::motion_utils::VelocityFactorInterface velocity_factor_interface_; + virtual void publish_planning_factor() {} rclcpp::Logger logger_ = rclcpp::get_logger(""); rclcpp::Publisher::SharedPtr debug_publisher_; rclcpp::Publisher::SharedPtr virtual_wall_publisher_; @@ -50,6 +53,9 @@ class PluginModuleInterface rclcpp::Publisher::SharedPtr processing_time_publisher_; autoware::motion_utils::VirtualWallMarkerCreator virtual_wall_marker_creator{}; + +protected: + std::unique_ptr planning_factor_interface_; }; } // namespace autoware::motion_velocity_planner diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/velocity_planning_result.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/velocity_planning_result.hpp index 1288884a37979..7b41bf0ee9e3e 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/velocity_planning_result.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/velocity_planning_result.hpp @@ -17,7 +17,6 @@ #include -#include #include #include @@ -43,7 +42,6 @@ struct VelocityPlanningResult { std::vector stop_points{}; std::vector slowdown_intervals{}; - std::optional velocity_factor{}; }; } // namespace autoware::motion_velocity_planner diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/README.md b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/README.md index 01062f81e77a2..c65593497b8d5 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/README.md +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/README.md @@ -30,10 +30,10 @@ This means that to stop before a wall, a stop point is inserted in the trajector ## Output topics -| Name | Type | Description | -| --------------------------- | ------------------------------------------------- | -------------------------------------------------- | -| `~/output/trajectory` | autoware_planning_msgs::msg::Trajectory | Ego trajectory with updated velocity profile | -| `~/output/velocity_factors` | autoware_adapi_v1_msgs::msg::VelocityFactorsArray | factors causing change in the ego velocity profile | +| Name | Type | Description | +| ----------------------------------------- | ---------------------------------------------- | -------------------------------------------------- | +| `~/output/trajectory` | autoware_planning_msgs::msg::Trajectory | Ego trajectory with updated velocity profile | +| `~/output/planning_factors/` | tier4_planning_msgs::msg::PlanningFactorsArray | factors causing change in the ego velocity profile | ## Services diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp index a78ab1489e080..8f5aa761573b7 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp @@ -82,9 +82,6 @@ MotionVelocityPlannerNode::MotionVelocityPlannerNode(const rclcpp::NodeOptions & // Publishers trajectory_pub_ = this->create_publisher("~/output/trajectory", 1); - velocity_factor_publisher_ = - this->create_publisher( - "~/output/velocity_factors", 1); processing_time_publisher_ = this->create_publisher( "~/debug/processing_time_ms", 1); @@ -422,20 +419,13 @@ autoware_planning_msgs::msg::Trajectory MotionVelocityPlannerNode::generate_traj resampled_trajectory, std::make_shared(planner_data_)); processing_times["plan_velocities"] = stop_watch.toc("plan_velocities"); - autoware_adapi_v1_msgs::msg::VelocityFactorArray velocity_factors; - velocity_factors.header.frame_id = "map"; - velocity_factors.header.stamp = get_clock()->now(); - for (const auto & planning_result : planning_results) { for (const auto & stop_point : planning_result.stop_points) insert_stop(output_trajectory_msg, stop_point); for (const auto & slowdown_interval : planning_result.slowdown_intervals) insert_slowdown(output_trajectory_msg, slowdown_interval); - if (planning_result.velocity_factor) - velocity_factors.factors.push_back(*planning_result.velocity_factor); } - velocity_factor_publisher_->publish(velocity_factors); return output_trajectory_msg; } diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp index 18d41f5d7fe5d..4235971e76fca 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp @@ -93,8 +93,6 @@ class MotionVelocityPlannerNode : public rclcpp::Node // publishers rclcpp::Publisher::SharedPtr trajectory_pub_; rclcpp::Publisher::SharedPtr debug_viz_pub_; - rclcpp::Publisher::SharedPtr - velocity_factor_publisher_; autoware::universe_utils::ProcessingTimePublisher processing_diag_publisher_{ this, "~/debug/processing_time_ms_diag"}; rclcpp::Publisher::SharedPtr diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.cpp index b08798cbef772..5bdf386479283 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.cpp @@ -102,6 +102,8 @@ std::vector MotionVelocityPlannerManager::plan_velocitie VelocityPlanningResult res = plugin->plan(ego_trajectory_points, planner_data); results.push_back(res); + plugin->publish_planning_factor(); + if (res.stop_points.size() > 0) { const auto stop_decision_metric = make_decision_metric(plugin->get_module_name(), "stop"); metrics_.push_back(stop_decision_metric); diff --git a/system/autoware_default_adapi/package.xml b/system/autoware_default_adapi/package.xml index a24d0c8a30b62..e0d3fc0f9e21b 100644 --- a/system/autoware_default_adapi/package.xml +++ b/system/autoware_default_adapi/package.xml @@ -32,6 +32,7 @@ std_srvs tier4_api_msgs tier4_control_msgs + tier4_planning_msgs tier4_system_msgs python3-flask diff --git a/system/autoware_default_adapi/src/planning.cpp b/system/autoware_default_adapi/src/planning.cpp index d89ef6c221666..e11b01115caad 100644 --- a/system/autoware_default_adapi/src/planning.cpp +++ b/system/autoware_default_adapi/src/planning.cpp @@ -18,6 +18,7 @@ #include +#include #include #include #include @@ -25,6 +26,34 @@ namespace autoware::default_adapi { +const std::map direction_map = { + {PlanningFactor::SHIFT_RIGHT, SteeringFactor::RIGHT}, + {PlanningFactor::SHIFT_LEFT, SteeringFactor::LEFT}, + {PlanningFactor::TURN_RIGHT, SteeringFactor::RIGHT}, + {PlanningFactor::TURN_LEFT, SteeringFactor::LEFT}}; + +const std::map conversion_map = { + {"behavior_path_planner", PlanningBehavior::INTERSECTION}, + {"static_obstacle_avoidance", PlanningBehavior::AVOIDANCE}, + {"crosswalk", PlanningBehavior::CROSSWALK}, + {"goal_planner", PlanningBehavior::GOAL_PLANNER}, + {"intersection", PlanningBehavior::INTERSECTION}, + {"lane_change_left", PlanningBehavior::LANE_CHANGE}, + {"lane_change_right", PlanningBehavior::LANE_CHANGE}, + {"merge_from_private", PlanningBehavior::MERGE}, + {"no_stopping_area", PlanningBehavior::NO_STOPPING_AREA}, + {"blind_spot", PlanningBehavior::REAR_CHECK}, + {"obstacle_cruise_planner", PlanningBehavior::ROUTE_OBSTACLE}, + {"motion_velocity_planner", PlanningBehavior::ROUTE_OBSTACLE}, + {"walkway", PlanningBehavior::SIDEWALK}, + {"start_planner", PlanningBehavior::START_PLANNER}, + {"stop_line", PlanningBehavior::STOP_SIGN}, + {"surround_obstacle_checker", PlanningBehavior::SURROUNDING_OBSTACLE}, + {"traffic_light", PlanningBehavior::TRAFFIC_SIGNAL}, + {"detection_area", PlanningBehavior::USER_DEFINED_DETECTION_AREA}, + {"virtual_traffic_light", PlanningBehavior::VIRTUAL_TRAFFIC_LIGHT}, + {"run_out", PlanningBehavior::RUN_OUT}}; + template void concat(std::vector & v1, const std::vector & v2) { @@ -49,16 +78,122 @@ std::vector::SharedPtr> init_factors( } template -T merge_factors(const rclcpp::Time stamp, const std::vector & factors) +std::vector convert([[maybe_unused]] const std::vector & factors) +{ + static_assert(sizeof(T) == 0, "Only specializations of convert can be used."); + throw std::logic_error("Only specializations of convert can be used."); +} + +template <> +std::vector convert(const std::vector & factors) +{ + std::vector velocity_factors; + + for (const auto & factor : factors) { + if (factor.behavior != PlanningFactor::SLOW_DOWN && factor.behavior != PlanningFactor::STOP) { + continue; + } + + if (factor.control_points.empty()) { + continue; + } + + if (conversion_map.count(factor.module) == 0) { + continue; + } + + VelocityFactor velocity_factor; + velocity_factor.behavior = conversion_map.at(factor.module); + velocity_factor.pose = factor.control_points.front().pose; + velocity_factor.distance = factor.control_points.front().distance; + + velocity_factors.push_back(velocity_factor); + } + + return velocity_factors; +} + +template <> +std::vector convert(const std::vector & factors) { - T message; + std::vector steering_factors; + + for (const auto & factor : factors) { + if ( + factor.behavior != PlanningFactor::SHIFT_RIGHT && + factor.behavior != PlanningFactor::SHIFT_LEFT && + factor.behavior != PlanningFactor::TURN_RIGHT && + factor.behavior != PlanningFactor::TURN_LEFT) { + continue; + } + + if (factor.control_points.size() < 2) { + continue; + } + + if (conversion_map.count(factor.module) == 0) { + continue; + } + + if (direction_map.count(factor.behavior) == 0) { + continue; + } + + SteeringFactor steering_factor; + steering_factor.behavior = conversion_map.at(factor.module); + steering_factor.direction = direction_map.at(factor.behavior); + steering_factor.pose = std::array{ + factor.control_points.front().pose, factor.control_points.back().pose}; + steering_factor.distance = std::array{ + factor.control_points.front().distance, factor.control_points.back().distance}; + + steering_factors.push_back(steering_factor); + } + + return steering_factors; +} + +template +T merge_factors( + [[maybe_unused]] const rclcpp::Time stamp, + [[maybe_unused]] const std::vector & factors) +{ + static_assert(sizeof(T) == 0, "Only specializations of merge_factors can be used."); + throw std::logic_error("Only specializations of merge_factors can be used."); +} + +template <> +VelocityFactorArray merge_factors( + const rclcpp::Time stamp, const std::vector & factors) +{ + VelocityFactorArray message; message.header.stamp = stamp; message.header.frame_id = "map"; for (const auto & factor : factors) { - if (factor) { - concat(message.factors, factor->factors); + if (!factor) { + continue; } + + concat(message.factors, convert(factor->factors)); + } + return message; +} + +template <> +SteeringFactorArray merge_factors( + const rclcpp::Time stamp, const std::vector & factors) +{ + SteeringFactorArray message; + message.header.stamp = stamp; + message.header.frame_id = "map"; + + for (const auto & factor : factors) { + if (!factor) { + continue; + } + + concat(message.factors, convert(factor->factors)); } return message; } @@ -70,46 +205,33 @@ PlanningNode::PlanningNode(const rclcpp::NodeOptions & options) : Node("planning stop_duration_ = declare_parameter("stop_duration", 1.0); stop_checker_ = std::make_unique(this, stop_duration_ + 1.0); - std::vector velocity_factor_topics = { - "/planning/velocity_factors/blind_spot", - "/planning/velocity_factors/crosswalk", - "/planning/velocity_factors/detection_area", - "/planning/velocity_factors/dynamic_obstacle_stop", - "/planning/velocity_factors/intersection", - "/planning/velocity_factors/merge_from_private", - "/planning/velocity_factors/no_stopping_area", - "/planning/velocity_factors/obstacle_stop", - "/planning/velocity_factors/obstacle_cruise", - "/planning/velocity_factors/occlusion_spot", - "/planning/velocity_factors/run_out", - "/planning/velocity_factors/stop_line", - "/planning/velocity_factors/surround_obstacle", - "/planning/velocity_factors/traffic_light", - "/planning/velocity_factors/virtual_traffic_light", - "/planning/velocity_factors/walkway", - "/planning/velocity_factors/motion_velocity_planner", - "/planning/velocity_factors/static_obstacle_avoidance", - "/planning/velocity_factors/dynamic_obstacle_avoidance", - "/planning/velocity_factors/avoidance_by_lane_change", - "/planning/velocity_factors/lane_change_left", - "/planning/velocity_factors/lane_change_right", - "/planning/velocity_factors/start_planner", - "/planning/velocity_factors/goal_planner"}; - - std::vector steering_factor_topics = { - "/planning/steering_factor/static_obstacle_avoidance", - "/planning/steering_factor/dynamic_obstacle_avoidance", - "/planning/steering_factor/avoidance_by_lane_change", - "/planning/steering_factor/intersection", - "/planning/steering_factor/lane_change_left", - "/planning/steering_factor/lane_change_right", - "/planning/steering_factor/start_planner", - "/planning/steering_factor/goal_planner"}; - - sub_velocity_factors_ = - init_factors(this, velocity_factors_, velocity_factor_topics); - sub_steering_factors_ = - init_factors(this, steering_factors_, steering_factor_topics); + std::vector factor_topics = { + "/planning/planning_factors/behavior_path_planner", + "/planning/planning_factors/blind_spot", + "/planning/planning_factors/crosswalk", + "/planning/planning_factors/detection_area", + "/planning/planning_factors/dynamic_obstacle_stop", + "/planning/planning_factors/intersection", + "/planning/planning_factors/merge_from_private", + "/planning/planning_factors/no_stopping_area", + "/planning/planning_factors/obstacle_cruise_planner", + "/planning/planning_factors/occlusion_spot", + "/planning/planning_factors/run_out", + "/planning/planning_factors/stop_line", + "/planning/planning_factors/surround_obstacle_checker", + "/planning/planning_factors/traffic_light", + "/planning/planning_factors/virtual_traffic_light", + "/planning/planning_factors/walkway", + "/planning/planning_factors/motion_velocity_planner", + "/planning/planning_factors/static_obstacle_avoidance", + "/planning/planning_factors/dynamic_obstacle_avoidance", + "/planning/planning_factors/avoidance_by_lane_change", + "/planning/planning_factors/lane_change_left", + "/planning/planning_factors/lane_change_right", + "/planning/planning_factors/start_planner", + "/planning/planning_factors/goal_planner"}; + + sub_factors_ = init_factors(this, factors_, factor_topics); const auto adaptor = autoware::component_interface_utils::NodeAdaptor(this); adaptor.init_pub(pub_velocity_factors_); @@ -139,8 +261,8 @@ void PlanningNode::on_kinematic_state(const KinematicState::ConstSharedPtr msg) void PlanningNode::on_timer() { using autoware_adapi_v1_msgs::msg::VelocityFactor; - auto velocity = merge_factors(now(), velocity_factors_); - auto steering = merge_factors(now(), steering_factors_); + auto velocity = merge_factors(now(), factors_); + auto steering = merge_factors(now(), factors_); // Set the distance if it is nan. if (trajectory_ && kinematic_state_) { @@ -164,6 +286,13 @@ void PlanningNode::on_timer() } } + for (auto & factor : steering.factors) { + if ((factor.status == SteeringFactor::UNKNOWN) && (!std::isnan(factor.distance.front()))) { + const auto is_turning = factor.distance.front() < 0.0; + factor.status = is_turning ? SteeringFactor::TURNING : SteeringFactor::APPROACHING; + } + } + pub_velocity_factors_->publish(velocity); pub_steering_factors_->publish(steering); } diff --git a/system/autoware_default_adapi/src/planning.hpp b/system/autoware_default_adapi/src/planning.hpp index 3a9b99e33a997..49584475734f6 100644 --- a/system/autoware_default_adapi/src/planning.hpp +++ b/system/autoware_default_adapi/src/planning.hpp @@ -21,7 +21,11 @@ #include #include +#include +#include + #include +#include #include // This file should be included after messages. @@ -30,22 +34,26 @@ namespace autoware::default_adapi { +using autoware_adapi_v1_msgs::msg::PlanningBehavior; +using autoware_adapi_v1_msgs::msg::SteeringFactor; +using autoware_adapi_v1_msgs::msg::SteeringFactorArray; +using autoware_adapi_v1_msgs::msg::VelocityFactor; +using autoware_adapi_v1_msgs::msg::VelocityFactorArray; +using tier4_planning_msgs::msg::PlanningFactor; +using tier4_planning_msgs::msg::PlanningFactorArray; + class PlanningNode : public rclcpp::Node { public: explicit PlanningNode(const rclcpp::NodeOptions & options); private: - using VelocityFactorArray = autoware_adapi_v1_msgs::msg::VelocityFactorArray; - using SteeringFactorArray = autoware_adapi_v1_msgs::msg::SteeringFactorArray; Pub pub_velocity_factors_; Pub pub_steering_factors_; Sub sub_trajectory_; Sub sub_kinematic_state_; - std::vector::SharedPtr> sub_velocity_factors_; - std::vector::SharedPtr> sub_steering_factors_; - std::vector velocity_factors_; - std::vector steering_factors_; + std::vector::SharedPtr> sub_factors_; + std::vector factors_; rclcpp::TimerBase::SharedPtr timer_; using VehicleStopChecker = autoware::motion_utils::VehicleStopCheckerBase; From dd632fc2a2bec57796ea1c0bfbfa9b7dafc93749 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 16 Jan 2025 22:45:07 +0900 Subject: [PATCH 229/334] feat(motion_utils): add detail and pass type to VirtualWall (#9940) Signed-off-by: Mamoru Sobue --- .../motion_utils/marker/marker_helper.hpp | 5 ++ .../marker/virtual_wall_marker_creator.hpp | 3 +- .../src/marker/marker_helper.cpp | 49 ++++++++++++++++++- .../marker/virtual_wall_marker_creator.cpp | 10 +++- 4 files changed, 63 insertions(+), 4 deletions(-) diff --git a/common/autoware_motion_utils/include/autoware/motion_utils/marker/marker_helper.hpp b/common/autoware_motion_utils/include/autoware/motion_utils/marker/marker_helper.hpp index ee642c93a378f..2b89fc19d1878 100644 --- a/common/autoware_motion_utils/include/autoware/motion_utils/marker/marker_helper.hpp +++ b/common/autoware_motion_utils/include/autoware/motion_utils/marker/marker_helper.hpp @@ -40,6 +40,11 @@ visualization_msgs::msg::MarkerArray createDeadLineVirtualWallMarker( const double longitudinal_offset = 0.0, const std::string & ns_prefix = "", const bool is_driving_forward = true); +visualization_msgs::msg::MarkerArray createIntendedPassVirtualMarker( + const geometry_msgs::msg::Pose & pose, const std::string & module_name, const rclcpp::Time & now, + const int32_t id, const double longitudinal_offset, const std::string & ns_prefix, + const bool is_driving_forward); + visualization_msgs::msg::MarkerArray createDeletedStopVirtualWallMarker( const rclcpp::Time & now, const int32_t id); diff --git a/common/autoware_motion_utils/include/autoware/motion_utils/marker/virtual_wall_marker_creator.hpp b/common/autoware_motion_utils/include/autoware/motion_utils/marker/virtual_wall_marker_creator.hpp index 07fcbd9840c88..fd86c54d65be9 100644 --- a/common/autoware_motion_utils/include/autoware/motion_utils/marker/virtual_wall_marker_creator.hpp +++ b/common/autoware_motion_utils/include/autoware/motion_utils/marker/virtual_wall_marker_creator.hpp @@ -29,12 +29,13 @@ namespace autoware::motion_utils { /// @brief type of virtual wall associated with different marker styles and namespace -enum VirtualWallType { stop, slowdown, deadline }; +enum VirtualWallType { stop, slowdown, deadline, pass }; /// @brief virtual wall to be visualized in rviz struct VirtualWall { geometry_msgs::msg::Pose pose{}; std::string text{}; + std::string detail{}; std::string ns{}; VirtualWallType style = stop; double longitudinal_offset{}; diff --git a/common/autoware_motion_utils/src/marker/marker_helper.cpp b/common/autoware_motion_utils/src/marker/marker_helper.cpp index 91ad1c41eecc3..44b621a53c5f1 100644 --- a/common/autoware_motion_utils/src/marker/marker_helper.cpp +++ b/common/autoware_motion_utils/src/marker/marker_helper.cpp @@ -54,7 +54,7 @@ inline visualization_msgs::msg::MarkerArray createVirtualWallMarkerArray( { auto marker = createDefaultMarker( "map", now, ns_prefix + "factor_text", id, visualization_msgs::msg::Marker::TEXT_VIEW_FACING, - createMarkerScale(0.0, 0.0, 1.0), createMarkerColor(1.0, 1.0, 1.0, 1.0)); + createMarkerScale(0.0, 0.0, 1.0 /*font size*/), createMarkerColor(1.0, 1.0, 1.0, 1.0)); marker.pose = vehicle_front_pose; marker.pose.position.z += 2.0; @@ -85,6 +85,41 @@ inline visualization_msgs::msg::MarkerArray createDeletedVirtualWallMarkerArray( return marker_array; } + +inline visualization_msgs::msg::MarkerArray createIntendedPassArrowMarkerArray( + const geometry_msgs::msg::Pose & vehicle_front_pose, const std::string & module_name, + const std::string & ns_prefix, const rclcpp::Time & now, const int32_t id, + const std_msgs::msg::ColorRGBA & color) +{ + visualization_msgs::msg::MarkerArray marker_array; + + // Arrow + { + auto marker = createDefaultMarker( + "map", now, ns_prefix + "direction", id, visualization_msgs::msg::Marker::ARROW, + createMarkerScale(2.5 /*length*/, 0.15 /*width*/, 1.0 /*height*/), color); + + marker.pose = vehicle_front_pose; + + marker_array.markers.push_back(marker); + } + + // Factor Text + { + auto marker = createDefaultMarker( + "map", now, ns_prefix + "factor_text", id, visualization_msgs::msg::Marker::TEXT_VIEW_FACING, + createMarkerScale(0.0, 0.0, 0.4 /*font size*/), createMarkerColor(1.0, 1.0, 1.0, 1.0)); + + marker.pose = vehicle_front_pose; + marker.pose.position.z += 2.0; + marker.text = module_name; + + marker_array.markers.push_back(marker); + } + + return marker_array; +} + } // namespace namespace autoware::motion_utils @@ -125,6 +160,18 @@ visualization_msgs::msg::MarkerArray createDeadLineVirtualWallMarker( createMarkerColor(0.0, 1.0, 0.0, 0.5)); } +visualization_msgs::msg::MarkerArray createIntendedPassVirtualMarker( + const geometry_msgs::msg::Pose & pose, const std::string & module_name, const rclcpp::Time & now, + const int32_t id, const double longitudinal_offset, const std::string & ns_prefix, + const bool is_driving_forward) +{ + const auto pose_with_offset = autoware::universe_utils::calcOffsetPose( + pose, longitudinal_offset * (is_driving_forward ? 1.0 : -1.0), 0.0, 0.0); + return createIntendedPassArrowMarkerArray( + pose_with_offset, module_name, ns_prefix + "intended_pass_", now, id, + createMarkerColor(0.77, 0.77, 0.77, 0.5)); +} + visualization_msgs::msg::MarkerArray createDeletedStopVirtualWallMarker( const rclcpp::Time & now, const int32_t id) { diff --git a/common/autoware_motion_utils/src/marker/virtual_wall_marker_creator.cpp b/common/autoware_motion_utils/src/marker/virtual_wall_marker_creator.cpp index 4fecaea1bb838..fb8708b5b7baa 100644 --- a/common/autoware_motion_utils/src/marker/virtual_wall_marker_creator.cpp +++ b/common/autoware_motion_utils/src/marker/virtual_wall_marker_creator.cpp @@ -63,10 +63,16 @@ visualization_msgs::msg::MarkerArray VirtualWallMarkerCreator::create_markers( case deadline: create_fn = autoware::motion_utils::createDeadLineVirtualWallMarker; break; + case pass: + create_fn = autoware::motion_utils::createIntendedPassVirtualMarker; + break; } + const auto wall_text = virtual_wall.detail.empty() + ? virtual_wall.text + : virtual_wall.text + "(" + virtual_wall.detail + ")"; auto markers = create_fn( - virtual_wall.pose, virtual_wall.text, now, 0, virtual_wall.longitudinal_offset, - virtual_wall.ns, virtual_wall.is_driving_forward); + virtual_wall.pose, wall_text, now, 0, virtual_wall.longitudinal_offset, virtual_wall.ns, + virtual_wall.is_driving_forward); for (auto & marker : markers.markers) { marker.id = static_cast(marker_count_per_namespace_[marker.ns].current++); marker_array.markers.push_back(marker); From 62e07a18c6c54f3a0213bceae320bb9e56e8af2a Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> Date: Thu, 16 Jan 2025 23:12:30 +0900 Subject: [PATCH 230/334] fix(start_planner, goal_planner): refactor lane departure checker initialization (#9944) --- .../src/pull_over_planner/geometric_pull_over.cpp | 8 ++++++-- .../src/pull_over_planner/shift_pull_over.cpp | 8 ++++++-- .../src/geometric_pull_out.cpp | 6 ++++-- .../src/shift_pull_out.cpp | 6 ++++-- 4 files changed, 20 insertions(+), 8 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp index 44dca13ccfd66..b7b4ad83de362 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp @@ -29,8 +29,12 @@ GeometricPullOver::GeometricPullOver( rclcpp::Node & node, const GoalPlannerParameters & parameters, const bool is_forward) : PullOverPlannerBase{node, parameters}, parallel_parking_parameters_{parameters.parallel_parking_parameters}, - lane_departure_checker_{ - lane_departure_checker::Param{parameters.lane_departure_check_expansion_margin}, vehicle_info_}, + lane_departure_checker_{[&]() { + auto lane_departure_checker_params = lane_departure_checker::Param{}; + lane_departure_checker_params.footprint_extra_margin = + parameters.lane_departure_check_expansion_margin; + return LaneDepartureChecker{lane_departure_checker_params, vehicle_info_}; + }()}, is_forward_{is_forward}, left_side_parking_{parameters.parking_policy == ParkingPolicy::LEFT_SIDE} { diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp index 8350252369cc6..c8e0788e39b6f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp @@ -32,8 +32,12 @@ namespace autoware::behavior_path_planner { ShiftPullOver::ShiftPullOver(rclcpp::Node & node, const GoalPlannerParameters & parameters) : PullOverPlannerBase{node, parameters}, - lane_departure_checker_{ - lane_departure_checker::Param{parameters.lane_departure_check_expansion_margin}, vehicle_info_}, + lane_departure_checker_{[&]() { + auto lane_departure_checker_params = lane_departure_checker::Param{}; + lane_departure_checker_params.footprint_extra_margin = + parameters.lane_departure_check_expansion_margin; + return LaneDepartureChecker{lane_departure_checker_params, vehicle_info_}; + }()}, left_side_parking_{parameters.parking_policy == ParkingPolicy::LEFT_SIDE} { } diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/geometric_pull_out.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/geometric_pull_out.cpp index 69c5c41405932..ed09e0c0a33d6 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/geometric_pull_out.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/geometric_pull_out.cpp @@ -40,10 +40,12 @@ GeometricPullOut::GeometricPullOut( : PullOutPlannerBase{node, parameters, time_keeper}, parallel_parking_parameters_{parameters.parallel_parking_parameters} { + auto lane_departure_checker_params = autoware::lane_departure_checker::Param{}; + lane_departure_checker_params.footprint_extra_margin = + parameters.lane_departure_check_expansion_margin; lane_departure_checker_ = std::make_shared( - autoware::lane_departure_checker::Param{parameters.lane_departure_check_expansion_margin}, - vehicle_info_, time_keeper_); + lane_departure_checker_params, vehicle_info_); planner_.setParameters(parallel_parking_parameters_); } diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/shift_pull_out.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/shift_pull_out.cpp index 8f4de1d3636de..16a3d4ffd842a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/shift_pull_out.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/shift_pull_out.cpp @@ -44,10 +44,12 @@ ShiftPullOut::ShiftPullOut( std::shared_ptr time_keeper) : PullOutPlannerBase{node, parameters, time_keeper} { + autoware::lane_departure_checker::Param lane_departure_checker_params; + lane_departure_checker_params.footprint_extra_margin = + parameters.lane_departure_check_expansion_margin; lane_departure_checker_ = std::make_shared( - autoware::lane_departure_checker::Param{parameters.lane_departure_check_expansion_margin}, - vehicle_info_, time_keeper_); + lane_departure_checker_params, vehicle_info_, time_keeper_); } std::optional ShiftPullOut::plan( From 0bf689c2dc5a39dbe8749f270d5c21ec4733e56a Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 16 Jan 2025 23:39:33 +0900 Subject: [PATCH 231/334] refactor(lane_change): add missing safety check parameter (#9928) * refactor(lane_change): parameterize incoming object yaw threshold Signed-off-by: Zulfaqar Azmi * Readme Signed-off-by: Zulfaqar Azmi * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> * Add missing parameters Signed-off-by: Zulfaqar Azmi * missing dot Signed-off-by: Zulfaqar Azmi * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> * update readme Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Zulfaqar Azmi Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> --- .../README.md | 7 +++- .../config/lane_change.param.yaml | 7 +++- .../structs/parameters.hpp | 1 + .../src/manager.cpp | 32 ++++++++++++++++++- .../src/scene.cpp | 8 +++-- 5 files changed, 49 insertions(+), 6 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md index 20fd564049133..601fb893f82c6 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md @@ -1149,7 +1149,8 @@ The following parameters are used to configure terminal lane change path feature | `collision_check.check_other_lanes` | [-] | boolean | If true, the lane change module includes objects in other lanes when performing collision assessment. | false | | `collision_check.use_all_predicted_paths` | [-] | boolean | If false, use only the predicted path that has the maximum confidence. | true | | `collision_check.prediction_time_resolution` | [s] | double | Time resolution for object's path interpolation and collision check. | 0.5 | -| `collision_check.yaw_diff_threshold` | [rad] | double | Maximum yaw difference between ego and object when executing rss-based collision checking | 3.1416 | +| `collision_check.yaw_diff_threshold` | [rad] | double | Maximum yaw difference between predicted ego pose and predicted object pose when executing rss-based collision checking | 3.1416 | +| `collision_check.th_incoming_object_yaw` | [rad] | double | Maximum yaw difference between current ego pose and current object pose. Objects with a yaw difference exceeding this value are excluded from the safety check. | 2.3562 | #### safety constraints during lane change path is computed @@ -1162,6 +1163,7 @@ The following parameters are used to configure terminal lane change path feature | `safety_check.execution.lateral_distance_max_threshold` | [m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 2.0 | | `safety_check.execution.longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 | | `safety_check.execution.longitudinal_velocity_delta_time` | [m] | double | The time multiplier that is used to compute the actual gap between vehicle at each predicted points (not RSS distance) | 0.8 | +| `safety_check.execution.extended_polygon_policy` | [-] | string | Policy used to determine the polygon shape for the safety check. Available options are: `rectangle` or `along-path`. | `rectangle` | #### safety constraints specifically for stopped or parked vehicles @@ -1174,6 +1176,7 @@ The following parameters are used to configure terminal lane change path feature | `safety_check.parked.lateral_distance_max_threshold` | [m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 1.0 | | `safety_check.parked.longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 | | `safety_check.parked.longitudinal_velocity_delta_time` | [m] | double | The time multiplier that is used to compute the actual gap between vehicle at each predicted points (not RSS distance) | 0.8 | +| `safety_check.parked.extended_polygon_policy` | [-] | string | Policy used to determine the polygon shape for the safety check. Available options are: `rectangle` or `along-path`. | `rectangle` | ##### safety constraints to cancel lane change path @@ -1186,6 +1189,7 @@ The following parameters are used to configure terminal lane change path feature | `safety_check.cancel.lateral_distance_max_threshold` | [m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 1.0 | | `safety_check.cancel.longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 2.5 | | `safety_check.cancel.longitudinal_velocity_delta_time` | [m] | double | The time multiplier that is used to compute the actual gap between vehicle at each predicted points (not RSS distance) | 0.6 | +| `safety_check.cancel.extended_polygon_policy` | [-] | string | Policy used to determine the polygon shape for the safety check. Available options are: `rectangle` or `along-path`. | `rectangle` | ##### safety constraints used during lane change path is computed when ego is stuck @@ -1198,6 +1202,7 @@ The following parameters are used to configure terminal lane change path feature | `safety_check.stuck.lateral_distance_max_threshold` | [m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 2.0 | | `safety_check.stuck.longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 | | `safety_check.stuck.longitudinal_velocity_delta_time` | [m] | double | The time multiplier that is used to compute the actual gap between vehicle at each predicted points (not RSS distance) | 0.8 | +| `safety_check.stuck.extended_polygon_policy` | [-] | string | Policy used to determine the polygon shape for the safety check. Available options are: `rectangle` or `along-path`. | `rectangle` | (\*1) the value must be negative. diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml index 15eb23daecf95..71fac1246598f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml @@ -58,6 +58,7 @@ lateral_distance_max_threshold: 2.0 longitudinal_distance_min_threshold: 3.0 longitudinal_velocity_delta_time: 0.0 + extended_polygon_policy: "rectangle" parked: expected_front_deceleration: -1.0 expected_rear_deceleration: -2.0 @@ -66,6 +67,7 @@ lateral_distance_max_threshold: 1.0 longitudinal_distance_min_threshold: 3.0 longitudinal_velocity_delta_time: 0.0 + extended_polygon_policy: "rectangle" cancel: expected_front_deceleration: -1.0 expected_rear_deceleration: -2.0 @@ -74,6 +76,7 @@ lateral_distance_max_threshold: 1.0 longitudinal_distance_min_threshold: 2.5 longitudinal_velocity_delta_time: 0.0 + extended_polygon_policy: "rectangle" stuck: expected_front_deceleration: -1.0 expected_rear_deceleration: -1.0 @@ -82,6 +85,7 @@ lateral_distance_max_threshold: 2.0 longitudinal_distance_min_threshold: 3.0 longitudinal_velocity_delta_time: 0.0 + extended_polygon_policy: "rectangle" # lane expansion for object filtering lane_expansion: @@ -123,7 +127,8 @@ intersection: true turns: true prediction_time_resolution: 0.5 - yaw_diff_threshold: 3.1416 + th_incoming_object_yaw: 2.3562 # [rad] + yaw_diff_threshold: 3.1416 # [rad] check_current_lanes: false check_other_lanes: false use_all_predicted_paths: false diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp index 60386f535fc64..358f60f3193d5 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/structs/parameters.hpp @@ -94,6 +94,7 @@ struct CollisionCheckParameters bool check_current_lane{true}; bool check_other_lanes{true}; bool use_all_predicted_paths{false}; + double th_incoming_object_yaw{2.3562}; double th_yaw_diff{3.1416}; double prediction_time_resolution{0.5}; }; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp index 450497fb2ca29..589338d7b3ace 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp @@ -152,6 +152,8 @@ LCParamPtr LaneChangeModuleManager::set_params(rclcpp::Node * node, const std::s getOrDeclareParameter(*node, parameter("collision_check.prediction_time_resolution")); p.safety.collision_check.th_yaw_diff = getOrDeclareParameter(*node, parameter("collision_check.yaw_diff_threshold")); + p.safety.collision_check.th_incoming_object_yaw = + getOrDeclareParameter(*node, parameter("collision_check.th_incoming_object_yaw")); // rss check auto set_rss_params = [&](auto & params, const std::string & prefix) { @@ -169,6 +171,8 @@ LCParamPtr LaneChangeModuleManager::set_params(rclcpp::Node * node, const std::s *node, parameter(prefix + ".rear_vehicle_safety_time_margin")); params.lateral_distance_max_threshold = getOrDeclareParameter(*node, parameter(prefix + ".lateral_distance_max_threshold")); + params.extended_polygon_policy = + getOrDeclareParameter(*node, parameter(prefix + ".extended_polygon_policy")); }; set_rss_params(p.safety.rss_params, "safety_check.execution"); set_rss_params(p.safety.rss_params_for_parked, "safety_check.parked"); @@ -454,6 +458,19 @@ void LaneChangeModuleManager::updateModuleParams(const std::vectorsafety.collision_check.prediction_time_resolution); updateParam( parameters, ns + "yaw_diff_threshold", p->safety.collision_check.th_yaw_diff); + + auto th_incoming_object_yaw = p->safety.collision_check.th_incoming_object_yaw; + updateParam(parameters, ns + "th_incoming_object_yaw", th_incoming_object_yaw); + if (th_incoming_object_yaw >= M_PI_2) { + p->safety.collision_check.th_incoming_object_yaw = th_incoming_object_yaw; + } else { + RCLCPP_WARN_THROTTLE( + node_->get_logger(), *node_->get_clock(), 5000, + "The value of th_incoming_object_yaw (%.3f rad) is less than the minimum possible value " + "(%.3f " + "rad).", + th_incoming_object_yaw, M_PI_2); + } } { @@ -483,7 +500,7 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector(parameters, ns + "stop_time", p->th_stop_time); } - auto update_rss_params = [¶meters](const std::string & prefix, auto & params) { + auto update_rss_params = [¶meters, this](const std::string & prefix, auto & params) { using autoware::universe_utils::updateParam; updateParam( parameters, prefix + "longitudinal_distance_min_threshold", @@ -502,6 +519,19 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector( parameters, prefix + "lateral_distance_max_threshold", params.lateral_distance_max_threshold); + + auto extended_polygon_policy = params.extended_polygon_policy; + updateParam( + parameters, prefix + "extended_polygon_policy", extended_polygon_policy); + if (extended_polygon_policy == "rectangle" || extended_polygon_policy == "along_path") { + params.extended_polygon_policy = extended_polygon_policy; + } else { + RCLCPP_WARN_THROTTLE( + node_->get_logger(), *node_->get_clock(), 1000, + "Policy %s not supported or there's typo. Make sure you choose either 'rectangle' or " + "'along_path'", + extended_polygon_policy.c_str()); + } }; update_rss_params("lane_change.safety_check.execution.", p->safety.rss_params); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index 45fcd6fa99086..611a0b60a4366 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -1051,7 +1051,9 @@ void NormalLaneChange::filterOncomingObjects(PredictedObjects & objects) const const auto is_same_direction = [&](const PredictedObject & object) { const auto & object_pose = object.kinematics.initial_pose_with_covariance.pose; - return !utils::path_safety_checker::isTargetObjectOncoming(current_pose, object_pose); + return !utils::path_safety_checker::isTargetObjectOncoming( + current_pose, object_pose, + common_data_ptr_->lc_param_ptr->safety.collision_check.th_incoming_object_yaw); }; // Perception noise could make stationary objects seem opposite the ego vehicle; check the @@ -1792,7 +1794,6 @@ bool NormalLaneChange::is_colliding( constexpr auto is_safe{true}; auto current_debug_data = utils::path_safety_checker::createObjectDebug(obj); - constexpr auto collision_check_yaw_diff_threshold{M_PI}; constexpr auto hysteresis_factor{1.0}; const auto obj_predicted_paths = utils::path_safety_checker::getPredictedPathFromObj( obj, lane_change_parameters_->safety.collision_check.use_all_predicted_paths); @@ -1817,7 +1818,8 @@ bool NormalLaneChange::is_colliding( const auto collided_polygons = utils::path_safety_checker::get_collided_polygons( lane_change_path.path, ego_predicted_path, obj, predicted_obj_path, bpp_param.vehicle_info, selected_rss_param, hysteresis_factor, safety_check_max_vel, - collision_check_yaw_diff_threshold, current_debug_data.second); + common_data_ptr_->lc_param_ptr->safety.collision_check.th_yaw_diff, + current_debug_data.second); if (collided_polygons.empty()) { utils::path_safety_checker::updateCollisionCheckDebugMap( From 67ab350f6e1af0c14bee74d6913c99165c2e9262 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Fri, 17 Jan 2025 00:05:32 +0900 Subject: [PATCH 232/334] feat(behavior_velocity_planner)!: remove velocity_factor completely (#9943) * feat(behavior_velocity_planner)!: remove velocity_factor completely Signed-off-by: Mamoru Sobue * minimize diff Signed-off-by: Mamoru Sobue --------- Signed-off-by: Mamoru Sobue --- .../src/scene.cpp | 8 +++--- .../src/scene_intersection.cpp | 2 -- .../src/scene.cpp | 19 +++++++++----- .../src/scene_no_stopping_area.cpp | 9 ++++--- .../src/scene_occlusion_spot.cpp | 2 -- .../scene_module_interface.hpp | 22 ---------------- .../src/scene.cpp | 26 +++++-------------- .../src/scene.hpp | 5 ---- .../src/manager.cpp | 12 --------- .../src/scene.cpp | 7 ++--- .../src/scene.cpp | 15 ++++++----- .../src/scene.hpp | 4 --- 12 files changed, 39 insertions(+), 92 deletions(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp index 59f6f20937f41..7e6a320f3ddad 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp @@ -46,7 +46,6 @@ DetectionAreaModule::DetectionAreaModule( planner_param_(planner_param), debug_data_() { - velocity_factor_.init(PlanningBehavior::USER_DEFINED_DETECTION_AREA); } bool DetectionAreaModule::modifyPathVelocity(PathWithLaneId * path) @@ -180,9 +179,10 @@ bool DetectionAreaModule::modifyPathVelocity(PathWithLaneId * path) // Create StopReason { - velocity_factor_.set( - path->points, planner_data_->current_odometry->pose, stop_point->second, - VelocityFactor::UNKNOWN); + planning_factor_interface_->add( + path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose, + tier4_planning_msgs::msg::PlanningFactor::STOP, tier4_planning_msgs::msg::SafetyFactorArray{}, + true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, ""); } return true; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp index 2d5da0f070ed9..5b8aca1c8ec9d 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -44,8 +44,6 @@ namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; -using autoware::motion_utils::VelocityFactorInterface; - IntersectionModule::IntersectionModule( const int64_t module_id, const int64_t lane_id, [[maybe_unused]] std::shared_ptr planner_data, diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp index f32210bc502bf..0e646e92035cf 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp @@ -38,7 +38,6 @@ NoDrivableLaneModule::NoDrivableLaneModule( debug_data_(), state_(State::INIT) { - velocity_factor_.init(PlanningBehavior::NO_DRIVABLE_LANE); } bool NoDrivableLaneModule::modifyPathVelocity(PathWithLaneId * path) @@ -166,8 +165,10 @@ void NoDrivableLaneModule::handle_approaching_state(PathWithLaneId * path) // Get stop point and stop factor { const auto & stop_pose = op_stop_pose.value(); - velocity_factor_.set( - path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::APPROACHING); + planning_factor_interface_->add( + path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose, + tier4_planning_msgs::msg::PlanningFactor::STOP, tier4_planning_msgs::msg::SafetyFactorArray{}, + true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, ""); const auto virtual_wall_pose = autoware::motion_utils::calcLongitudinalOffsetPose( path->points, stop_pose.position, debug_data_.base_link2front); @@ -214,8 +215,10 @@ void NoDrivableLaneModule::handle_inside_no_drivable_lane_state(PathWithLaneId * // Get stop point and stop factor { const auto & stop_pose = autoware::universe_utils::getPose(path->points.at(0)); - velocity_factor_.set( - path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::APPROACHING); + planning_factor_interface_->add( + path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose, + tier4_planning_msgs::msg::PlanningFactor::STOP, tier4_planning_msgs::msg::SafetyFactorArray{}, + true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, ""); const auto & virtual_wall_pose = autoware::motion_utils::calcLongitudinalOffsetPose( path->points, stop_pose.position, debug_data_.base_link2front); @@ -252,8 +255,10 @@ void NoDrivableLaneModule::handle_stopped_state(PathWithLaneId * path) // Get stop point and stop factor { const auto & stop_pose = ego_pos_on_path.pose; - velocity_factor_.set( - path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::STOPPED); + planning_factor_interface_->add( + path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose, + tier4_planning_msgs::msg::PlanningFactor::STOP, tier4_planning_msgs::msg::SafetyFactorArray{}, + true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, ""); const auto virtual_wall_pose = autoware::motion_utils::calcLongitudinalOffsetPose( path->points, stop_pose.position, debug_data_.base_link2front); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp index bcb8b365f6205..c788a54073ed6 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp @@ -50,7 +50,6 @@ NoStoppingAreaModule::NoStoppingAreaModule( planner_param_(planner_param), debug_data_() { - velocity_factor_.init(PlanningBehavior::NO_STOPPING_AREA); state_machine_.setState(StateMachine::State::GO); state_machine_.setMarginTime(planner_param_.state_clear_time); } @@ -144,9 +143,11 @@ bool NoStoppingAreaModule::modifyPathVelocity(PathWithLaneId * path) // Create StopReason { - velocity_factor_.set( - path->points, planner_data_->current_odometry->pose, stop_point->second, - VelocityFactor::UNKNOWN); + planning_factor_interface_->add( + path->points, planner_data_->current_odometry->pose, stop_point->second, stop_point->second, + tier4_planning_msgs::msg::PlanningFactor::STOP, + tier4_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0, + 0.0 /*shift distance*/, ""); } } else if (state_machine_.getState() == StateMachine::State::GO) { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp index 1163b00e08ccb..fa259b2bea9aa 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp @@ -70,8 +70,6 @@ OcclusionSpotModule::OcclusionSpotModule( : SceneModuleInterface(module_id, logger, clock, time_keeper, planning_factor_interface), param_(planner_param) { - velocity_factor_.init(PlanningBehavior::UNKNOWN); - if (param_.detection_method == utils::DETECTION_METHOD::OCCUPANCY_GRID) { debug_data_.detection_type = "occupancy"; //! occupancy grid limitation( 100 * 100 ) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp index ad1ae1d47664a..5bff3ca343e72 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp @@ -18,7 +18,6 @@ #include #include #include -#include #include #include #include @@ -28,8 +27,6 @@ #include #include -#include -#include #include #include #include @@ -51,8 +48,6 @@ namespace autoware::behavior_velocity_planner { -using autoware::motion_utils::PlanningBehavior; -using autoware::motion_utils::VelocityFactor; using autoware::objects_of_interest_marker_interface::ColorName; using autoware::objects_of_interest_marker_interface::ObjectsOfInterestMarkerInterface; using autoware::universe_utils::DebugPublisher; @@ -97,8 +92,6 @@ class SceneModuleInterface planner_data_ = planner_data; } - void resetVelocityFactor() { velocity_factor_.reset(); } - VelocityFactor getVelocityFactor() const { return velocity_factor_.get(); } std::vector getObjectsOfInterestData() const { return objects_of_interest_; } void clearObjectsOfInterestData() { objects_of_interest_.clear(); } @@ -107,7 +100,6 @@ class SceneModuleInterface rclcpp::Logger logger_; rclcpp::Clock::SharedPtr clock_; std::shared_ptr planner_data_; - autoware::motion_utils::VelocityFactorInterface velocity_factor_; // TODO(soblin): remove this std::vector objects_of_interest_; mutable std::shared_ptr time_keeper_; std::shared_ptr planning_factor_interface_; @@ -143,8 +135,6 @@ class SceneModuleManagerInterface } pub_virtual_wall_ = node.create_publisher( std::string("~/virtual_wall/") + module_name, 5); - pub_velocity_factor_ = node.create_publisher( - std::string("/planning/velocity_factors/") + module_name, 1); planning_factor_interface_ = std::make_shared(&node, module_name); @@ -180,21 +170,12 @@ class SceneModuleManagerInterface StopWatch stop_watch; stop_watch.tic("Total"); visualization_msgs::msg::MarkerArray debug_marker_array; - autoware_adapi_v1_msgs::msg::VelocityFactorArray velocity_factor_array; - velocity_factor_array.header.frame_id = "map"; - velocity_factor_array.header.stamp = clock_->now(); for (const auto & scene_module : scene_modules_) { - scene_module->resetVelocityFactor(); scene_module->setPlannerData(planner_data_); scene_module->modifyPathVelocity(path); // The velocity factor must be called after modifyPathVelocity. - // TODO(soblin): remove this - const auto velocity_factor = scene_module->getVelocityFactor(); - if (velocity_factor.behavior != PlanningBehavior::UNKNOWN) { - velocity_factor_array.factors.emplace_back(velocity_factor); - } for (const auto & marker : scene_module->createDebugMarkerArray().markers) { debug_marker_array.markers.push_back(marker); @@ -203,7 +184,6 @@ class SceneModuleManagerInterface virtual_wall_marker_creator_.add_virtual_walls(scene_module->createVirtualWalls()); } - pub_velocity_factor_->publish(velocity_factor_array); planning_factor_interface_->publish(); pub_debug_->publish(debug_marker_array); if (is_publish_debug_path_) { @@ -274,8 +254,6 @@ class SceneModuleManagerInterface rclcpp::Publisher::SharedPtr pub_virtual_wall_; rclcpp::Publisher::SharedPtr pub_debug_; rclcpp::Publisher::SharedPtr pub_debug_path_; - rclcpp::Publisher::SharedPtr - pub_velocity_factor_; std::shared_ptr processing_time_publisher_; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp index 71a5ea3b9e807..e2ddbc75c7b57 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp @@ -38,7 +38,6 @@ StopLineModule::StopLineModule( state_(State::APPROACH), debug_data_() { - velocity_factor_.init(PlanningBehavior::STOP_SIGN); } bool StopLineModule::modifyPathVelocity(PathWithLaneId * path) @@ -62,7 +61,12 @@ bool StopLineModule::modifyPathVelocity(PathWithLaneId * path) path->points = trajectory->restore(); - updateVelocityFactor(&velocity_factor_, state_, *stop_point - ego_s); + // TODO(soblin): PlanningFactorInterface use trajectory class + planning_factor_interface_->add( + path->points, trajectory->compute(*stop_point).point.pose, + planner_data_->current_odometry->pose, planner_data_->current_odometry->pose, + tier4_planning_msgs::msg::PlanningFactor::STOP, tier4_planning_msgs::msg::SafetyFactorArray{}, + true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, "stopline"); updateStateAndStoppedTime( &state_, &stopped_time_, clock_->now(), *stop_point - ego_s, planner_data_->isVehicleStopped()); @@ -152,24 +156,6 @@ void StopLineModule::updateStateAndStoppedTime( } } -void StopLineModule::updateVelocityFactor( - autoware::motion_utils::VelocityFactorInterface * velocity_factor, const State & state, - const double & distance_to_stop_point) -{ - switch (state) { - case State::APPROACH: { - velocity_factor->set(distance_to_stop_point, VelocityFactor::APPROACHING); - break; - } - case State::STOPPED: { - velocity_factor->set(distance_to_stop_point, VelocityFactor::STOPPED); - break; - } - case State::START: - break; - } -} - void StopLineModule::updateDebugData( DebugData * debug_data, const geometry_msgs::msg::Pose & stop_pose, const State & state) const { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.hpp index aac830b0e9f24..7d430463c18b9 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.hpp @@ -18,7 +18,6 @@ #include "autoware/behavior_velocity_planner_common/scene_module_interface.hpp" #include "autoware/behavior_velocity_planner_common/utilization/util.hpp" -#include "autoware/motion_utils/factor/velocity_factor_interface.hpp" #include "autoware/trajectory/path_point_with_lane_id.hpp" #include @@ -98,10 +97,6 @@ class StopLineModule : public SceneModuleInterface State * state, std::optional * stopped_time, const rclcpp::Time & now, const double & distance_to_stop_point, const bool & is_vehicle_stopped) const; - static void updateVelocityFactor( - autoware::motion_utils::VelocityFactorInterface * velocity_factor, const State & state, - const double & distance_to_stop_point); - void updateDebugData( DebugData * debug_data, const geometry_msgs::msg::Pose & stop_pose, const State & state) const; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.cpp index 9a402f31af0e4..1d1ee7fc996b2 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.cpp @@ -53,24 +53,13 @@ void TrafficLightModuleManager::modifyPathVelocity(tier4_planning_msgs::msg::Pat autoware_perception_msgs::msg::TrafficLightGroup tl_state; - autoware_adapi_v1_msgs::msg::VelocityFactorArray velocity_factor_array; - velocity_factor_array.header.frame_id = "map"; - velocity_factor_array.header.stamp = clock_->now(); - nearest_ref_stop_path_point_index_ = static_cast(path->points.size() - 1); for (const auto & scene_module : scene_modules_) { std::shared_ptr traffic_light_scene_module( std::dynamic_pointer_cast(scene_module)); - traffic_light_scene_module->resetVelocityFactor(); traffic_light_scene_module->setPlannerData(planner_data_); traffic_light_scene_module->modifyPathVelocity(path); - // The velocity factor must be called after modifyPathVelocity. - const auto velocity_factor = traffic_light_scene_module->getVelocityFactor(); - if (velocity_factor.behavior != PlanningBehavior::UNKNOWN) { - velocity_factor_array.factors.emplace_back(velocity_factor); - } - if ( traffic_light_scene_module->getFirstRefStopPathPointIndex() < nearest_ref_stop_path_point_index_) { @@ -88,7 +77,6 @@ void TrafficLightModuleManager::modifyPathVelocity(tier4_planning_msgs::msg::Pat virtual_wall_marker_creator_.add_virtual_walls( traffic_light_scene_module->createVirtualWalls()); } - pub_velocity_factor_->publish(velocity_factor_array); pub_debug_->publish(debug_marker_array); pub_virtual_wall_->publish(virtual_wall_marker_creator_.create_markers(clock_->now())); pub_tl_state_->publish(tl_state); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp index b051d5ff7eb76..becbaf5ee05f2 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp @@ -54,7 +54,6 @@ TrafficLightModule::TrafficLightModule( debug_data_(), is_prev_state_stop_(false) { - velocity_factor_.init(PlanningBehavior::TRAFFIC_SIGNAL); planner_param_ = planner_param; } @@ -293,9 +292,11 @@ tier4_planning_msgs::msg::PathWithLaneId TrafficLightModule::insertStopPose( size_t insert_index = insert_target_point_idx; planning_utils::insertVelocity(modified_path, target_point_with_lane_id, 0.0, insert_index); - velocity_factor_.set( + planning_factor_interface_->add( modified_path.points, planner_data_->current_odometry->pose, - target_point_with_lane_id.point.pose, VelocityFactor::UNKNOWN); + target_point_with_lane_id.point.pose, target_point_with_lane_id.point.pose, + tier4_planning_msgs::msg::PlanningFactor::STOP, tier4_planning_msgs::msg::SafetyFactorArray{}, + true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, ""); return modified_path; } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp index 9ba7b0bccf1b9..a5779cfc0712a 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp @@ -48,8 +48,6 @@ VirtualTrafficLightModule::VirtualTrafficLightModule( lane_(lane), planner_param_(planner_param) { - velocity_factor_.init(PlanningBehavior::VIRTUAL_TRAFFIC_LIGHT); - // Get map data const auto instrument = reg_elem_.getVirtualTrafficLight(); const auto instrument_bottom_line = toAutowarePoints(instrument); @@ -420,9 +418,10 @@ void VirtualTrafficLightModule::insertStopVelocityAtStopLine( } // Set StopReason - velocity_factor_.set( - path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::UNKNOWN, - command_.type); + planning_factor_interface_->add( + path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose, + tier4_planning_msgs::msg::PlanningFactor::STOP, tier4_planning_msgs::msg::SafetyFactorArray{}, + true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, ""); // Set data for visualization module_data_.stop_head_pose_at_stop_line = @@ -453,8 +452,10 @@ void VirtualTrafficLightModule::insertStopVelocityAtEndLine( } // Set StopReason - velocity_factor_.set( - path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::UNKNOWN); + planning_factor_interface_->add( + path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose, + tier4_planning_msgs::msg::PlanningFactor::STOP, tier4_planning_msgs::msg::SafetyFactorArray{}, + true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, ""); // Set data for visualization module_data_.stop_head_pose_at_end_line = diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp index 9e7a1192d9869..0661267b3d361 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp @@ -113,10 +113,6 @@ class VirtualTrafficLightModule : public SceneModuleInterface void updateInfrastructureCommand(); - void setVelocityFactor( - const geometry_msgs::msg::Pose & stop_pose, - autoware_adapi_v1_msgs::msg::VelocityFactor * velocity_factor); - std::optional getPathIndexOfFirstEndLine(); bool isBeforeStartLine(const size_t end_line_idx); From 08dd641f5ab051eba69d68329cc6c1c6d752de98 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 17 Jan 2025 09:15:18 +0900 Subject: [PATCH 233/334] fix(obstacle_stop_planner): migrate planning factor (#9939) * fix(obstacle_stop_planner): migrate planning factor Signed-off-by: satoshi-ota * fix(autoware_default_adapi): add coversion map Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../src/debug_marker.cpp | 35 ++++++------------- .../src/debug_marker.hpp | 10 ++---- .../autoware_default_adapi/src/planning.cpp | 2 ++ 3 files changed, 16 insertions(+), 31 deletions(-) diff --git a/planning/autoware_obstacle_stop_planner/src/debug_marker.cpp b/planning/autoware_obstacle_stop_planner/src/debug_marker.cpp index 93526518306af..62b9ae124f555 100644 --- a/planning/autoware_obstacle_stop_planner/src/debug_marker.cpp +++ b/planning/autoware_obstacle_stop_planner/src/debug_marker.cpp @@ -45,12 +45,13 @@ namespace autoware::motion_planning { ObstacleStopPlannerDebugNode::ObstacleStopPlannerDebugNode( rclcpp::Node * node, const double base_link2front) -: node_(node), base_link2front_(base_link2front) +: node_(node), + base_link2front_(base_link2front), + planning_factor_interface_{std::make_unique( + node, "obstacle_stop_planner")} { virtual_wall_pub_ = node_->create_publisher("~/virtual_wall", 1); debug_viz_pub_ = node_->create_publisher("~/debug/marker", 1); - velocity_factor_pub_ = - node_->create_publisher("/planning/velocity_factors/obstacle_stop", 1); pub_debug_values_ = node_->create_publisher("~/obstacle_stop/debug_values", 1); } @@ -189,8 +190,13 @@ void ObstacleStopPlannerDebugNode::publish() debug_viz_pub_->publish(visualization_msg); /* publish stop reason for autoware api */ - const auto velocity_factor_msg = makeVelocityFactorArray(); - velocity_factor_pub_->publish(velocity_factor_msg); + if (stop_pose_ptr_) { + planning_factor_interface_->add( + std::numeric_limits::quiet_NaN(), *stop_pose_ptr_, + tier4_planning_msgs::msg::PlanningFactor::STOP, tier4_planning_msgs::msg::SafetyFactorArray{}, + true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, ""); + } + planning_factor_interface_->publish(); // publish debug values Float32MultiArrayStamped debug_msg{}; @@ -492,23 +498,4 @@ MarkerArray ObstacleStopPlannerDebugNode::makeVisualizationMarker() return msg; } -VelocityFactorArray ObstacleStopPlannerDebugNode::makeVelocityFactorArray() -{ - VelocityFactorArray velocity_factor_array; - velocity_factor_array.header.frame_id = "map"; - velocity_factor_array.header.stamp = node_->now(); - - if (stop_pose_ptr_) { - using distance_type = VelocityFactor::_distance_type; - VelocityFactor velocity_factor; - velocity_factor.behavior = PlanningBehavior::ROUTE_OBSTACLE; - velocity_factor.pose = *stop_pose_ptr_; - velocity_factor.distance = std::numeric_limits::quiet_NaN(); - velocity_factor.status = VelocityFactor::UNKNOWN; - velocity_factor.detail = std::string(); - velocity_factor_array.factors.push_back(velocity_factor); - } - return velocity_factor_array; -} - } // namespace autoware::motion_planning diff --git a/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp b/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp index d13e775e3d683..dd9e5e3af1b3d 100644 --- a/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp +++ b/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp @@ -14,10 +14,9 @@ #ifndef DEBUG_MARKER_HPP_ #define DEBUG_MARKER_HPP_ +#include #include -#include -#include #include #include #include @@ -42,9 +41,6 @@ using std_msgs::msg::Header; using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; -using autoware_adapi_v1_msgs::msg::PlanningBehavior; -using autoware_adapi_v1_msgs::msg::VelocityFactor; -using autoware_adapi_v1_msgs::msg::VelocityFactorArray; using tier4_debug_msgs::msg::Float32MultiArrayStamped; enum class PolygonType : int8_t { Vehicle = 0, Collision, SlowDownRange, SlowDown, Obstacle }; @@ -109,7 +105,6 @@ class ObstacleStopPlannerDebugNode bool pushObstaclePoint(const pcl::PointXYZ & obstacle_point, const PointType & type); MarkerArray makeVirtualWallMarker(); MarkerArray makeVisualizationMarker(); - VelocityFactorArray makeVelocityFactorArray(); void setDebugValues(const DebugValues::TYPE type, const double val) { @@ -120,11 +115,12 @@ class ObstacleStopPlannerDebugNode private: rclcpp::Publisher::SharedPtr virtual_wall_pub_; rclcpp::Publisher::SharedPtr debug_viz_pub_; - rclcpp::Publisher::SharedPtr velocity_factor_pub_; rclcpp::Publisher::SharedPtr pub_debug_values_; rclcpp::Node * node_; double base_link2front_; + std::unique_ptr planning_factor_interface_; + std::shared_ptr stop_pose_ptr_; std::shared_ptr target_stop_pose_ptr_; std::shared_ptr slow_down_start_pose_ptr_; diff --git a/system/autoware_default_adapi/src/planning.cpp b/system/autoware_default_adapi/src/planning.cpp index e11b01115caad..98f1c846d202e 100644 --- a/system/autoware_default_adapi/src/planning.cpp +++ b/system/autoware_default_adapi/src/planning.cpp @@ -44,6 +44,7 @@ const std::map conversion_map = { {"no_stopping_area", PlanningBehavior::NO_STOPPING_AREA}, {"blind_spot", PlanningBehavior::REAR_CHECK}, {"obstacle_cruise_planner", PlanningBehavior::ROUTE_OBSTACLE}, + {"obstacle_stop_planner", PlanningBehavior::ROUTE_OBSTACLE}, {"motion_velocity_planner", PlanningBehavior::ROUTE_OBSTACLE}, {"walkway", PlanningBehavior::SIDEWALK}, {"start_planner", PlanningBehavior::START_PLANNER}, @@ -215,6 +216,7 @@ PlanningNode::PlanningNode(const rclcpp::NodeOptions & options) : Node("planning "/planning/planning_factors/merge_from_private", "/planning/planning_factors/no_stopping_area", "/planning/planning_factors/obstacle_cruise_planner", + "/planning/planning_factors/obstacle_stop_planner", "/planning/planning_factors/occlusion_spot", "/planning/planning_factors/run_out", "/planning/planning_factors/stop_line", From 7bc6a4e109cfaafc44ec3cae2cf5ab44ed7190a4 Mon Sep 17 00:00:00 2001 From: Masaki Baba Date: Fri, 17 Jan 2025 13:53:12 +0900 Subject: [PATCH 234/334] fix(map_based_prediction): fix unintentional accumulation of lanelets (#9950) add clear before insert Signed-off-by: a-maumau --- perception/autoware_map_based_prediction/src/predictor_vru.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/perception/autoware_map_based_prediction/src/predictor_vru.cpp b/perception/autoware_map_based_prediction/src/predictor_vru.cpp index 0eea665cbd8a2..ffbdbd97b50a2 100644 --- a/perception/autoware_map_based_prediction/src/predictor_vru.cpp +++ b/perception/autoware_map_based_prediction/src/predictor_vru.cpp @@ -269,6 +269,7 @@ void PredictorVru::setLaneletMap(std::shared_ptr lanelet_ma const auto all_lanelets = lanelet::utils::query::laneletLayer(lanelet_map_ptr_); const auto crosswalks = lanelet::utils::query::crosswalkLanelets(all_lanelets); const auto walkways = lanelet::utils::query::walkwayLanelets(all_lanelets); + crosswalks_.clear(); crosswalks_.insert(crosswalks_.end(), crosswalks.begin(), crosswalks.end()); crosswalks_.insert(crosswalks_.end(), walkways.begin(), walkways.end()); From 74f677936177bc49c6af13032e00ee8e1b49eef5 Mon Sep 17 00:00:00 2001 From: Masato Saeki <78376491+MasatoSaeki@users.noreply.github.com> Date: Fri, 17 Jan 2025 15:55:15 +0900 Subject: [PATCH 235/334] chore(autoware_traffic_light_map_based_detector): modify docs (#9817) * modify docs Signed-off-by: MasatoSaeki * fix title Signed-off-by: MasatoSaeki * fix docs Signed-off-by: MasatoSaeki * fix word Signed-off-by: MasatoSaeki * add comment about debug markers Signed-off-by: MasatoSaeki * fix docs Signed-off-by: MasatoSaeki --------- Signed-off-by: MasatoSaeki --- .../README.md | 48 ++++++++++--------- 1 file changed, 25 insertions(+), 23 deletions(-) diff --git a/perception/autoware_traffic_light_map_based_detector/README.md b/perception/autoware_traffic_light_map_based_detector/README.md index 8a59db19ae64d..6ef54d448b415 100644 --- a/perception/autoware_traffic_light_map_based_detector/README.md +++ b/perception/autoware_traffic_light_map_based_detector/README.md @@ -1,4 +1,4 @@ -# The `autoware_traffic_light_map_based_detector` Package +# autoware_traffic_light_map_based_detector ## Overview @@ -9,34 +9,36 @@ Calibration and vibration errors can be entered as parameters, and the size of t ![traffic_light_map_based_detector_result](./docs/traffic_light_map_based_detector_result.svg) If the node receives route information, it only looks at traffic lights on that route. -If the node receives no route information, it looks at a radius of 200 meters and the angle between the traffic light and the camera is less than 40 degrees. +If the node receives no route information, it looks at them within a radius of `max_detection_range` and the angle between the traffic light and the camera is less than `car_traffic_light_max_angle_range` or `pedestrian_traffic_light_max_angle_range`. ## Input topics -| Name | Type | Description | -| -------------------- | ------------------------------------- | ----------------------- | -| `~input/vector_map` | autoware_map_msgs::msg::LaneletMapBin | vector map | -| `~input/camera_info` | sensor_msgs::CameraInfo | target camera parameter | -| `~input/route` | autoware_planning_msgs::LaneletRoute | optional: route | +| Name | Type | Description | +| --------------------- | ----------------------------------------- | ----------------------- | +| `~/input/vector_map` | autoware_map_msgs::msg::LaneletMapBin | vector map | +| `~/input/camera_info` | sensor_msgs::msg::CameraInfo | target camera parameter | +| `~/input/route` | autoware_planning_msgs::msg::LaneletRoute | optional: route | ## Output topics -| Name | Type | Description | -| ---------------- | ------------------------------------------- | -------------------------------------------------------------------- | -| `~output/rois` | tier4_perception_msgs::TrafficLightRoiArray | location of traffic lights in image corresponding to the camera info | -| `~expect/rois` | tier4_perception_msgs::TrafficLightRoiArray | location of traffic lights in image without any offset | -| `~debug/markers` | visualization_msgs::MarkerArray | visualization to debug | +| Name | Type | Description | +| ----------------- | ------------------------------------------------ | ------------------------------------------------------------------------- | +| `~/output/rois` | tier4_perception_msgs::msg::TrafficLightRoiArray | location of traffic lights in image corresponding to the camera info | +| `~/expect/rois` | tier4_perception_msgs::msg::TrafficLightRoiArray | location of traffic lights in image without any offset | +| `~/debug/markers` | visualization_msgs::msg::MarkerArray | markers which show a line that combines from camera to each traffic light | ## Node parameters -| Parameter | Type | Description | -| ---------------------- | ------ | --------------------------------------------------------------------- | -| `max_vibration_pitch` | double | Maximum error in pitch direction. If -5~+5, it will be 10. | -| `max_vibration_yaw` | double | Maximum error in yaw direction. If -5~+5, it will be 10. | -| `max_vibration_height` | double | Maximum error in height direction. If -5~+5, it will be 10. | -| `max_vibration_width` | double | Maximum error in width direction. If -5~+5, it will be 10. | -| `max_vibration_depth` | double | Maximum error in depth direction. If -5~+5, it will be 10. | -| `max_detection_range` | double | Maximum detection range in meters. Must be positive | -| `min_timestamp_offset` | double | Minimum timestamp offset when searching for corresponding tf | -| `max_timestamp_offset` | double | Maximum timestamp offset when searching for corresponding tf | -| `timestamp_sample_len` | double | sampling length between min_timestamp_offset and max_timestamp_offset | +| Parameter | Type | Description | +| ------------------------------------------ | ------ | ----------------------------------------------------------------------------------------------- | +| `max_vibration_pitch` | double | Maximum error in pitch direction. If -5~+5, it will be 10. | +| `max_vibration_yaw` | double | Maximum error in yaw direction. If -5~+5, it will be 10. | +| `max_vibration_height` | double | Maximum error in height direction. If -5~+5, it will be 10. | +| `max_vibration_width` | double | Maximum error in width direction. If -5~+5, it will be 10. | +| `max_vibration_depth` | double | Maximum error in depth direction. If -5~+5, it will be 10. | +| `max_detection_range` | double | Maximum detection range in meters. Must be positive. | +| `min_timestamp_offset` | double | Minimum timestamp offset when searching for corresponding tf. | +| `max_timestamp_offset` | double | Maximum timestamp offset when searching for corresponding tf. | +| `timestamp_sample_len` | double | Sampling length between min_timestamp_offset and max_timestamp_offset. | +| `car_traffic_light_max_angle_range` | double | Maximum angle between the vehicular traffic light and the camera in degrees. Must be positive. | +| `pedestrian_traffic_light_max_angle_range` | double | Maximum angle between the pedestrian traffic light and the camera in degrees. Must be positive. | From 849892ec367b052b07550413269c38667204510b Mon Sep 17 00:00:00 2001 From: Masato Saeki <78376491+MasatoSaeki@users.noreply.github.com> Date: Fri, 17 Jan 2025 15:55:32 +0900 Subject: [PATCH 236/334] chore(autoware_traffic_light_fine_detector): modify docs and related params (#9818) * modify readme and related params Signed-off-by: MasatoSaeki * fix typo Signed-off-by: MasatoSaeki * fix Signed-off-by: MasatoSaeki --------- Signed-off-by: MasatoSaeki --- .../README.md | 19 ++++++++++--------- .../traffic_light_fine_detector.param.yaml | 1 + .../src/traffic_light_fine_detector_node.cpp | 2 +- 3 files changed, 12 insertions(+), 10 deletions(-) diff --git a/perception/autoware_traffic_light_fine_detector/README.md b/perception/autoware_traffic_light_fine_detector/README.md index 35b55c84aa087..df9f297422fce 100644 --- a/perception/autoware_traffic_light_fine_detector/README.md +++ b/perception/autoware_traffic_light_fine_detector/README.md @@ -1,8 +1,8 @@ -# traffic_light_fine_detector +# autoware_traffic_light_fine_detector ## Purpose -It is a package for traffic light detection using YoloX-s. +It is a package for traffic light detection using YOLOX-s. ## Training Information @@ -21,17 +21,18 @@ Please visit [autoware-documentation](https://github.com/autowarefoundation/auto ## Inner-workings / Algorithms -Based on the camera image and the global ROI array detected by `map_based_detection` node, a CNN-based detection method enables highly accurate traffic light detection. +Based on the camera image and the global ROI array detected by `map_based_detector` node, a CNN-based detection method enables highly accurate traffic light detection. If can not detect traffic light, x_offset, y_offset, height and width of output ROI become `0`. +ROIs detected from YOLOX will be selected by a combination of `expect/rois`. At this time, evaluate the whole as ROIs, not just the ROI alone. ## Inputs / Outputs ### Input -| Name | Type | Description | -| --------------- | -------------------------------------------------- | ------------------------------------------------------------------- | -| `~/input/image` | `sensor_msgs/Image` | The full size camera image | -| `~/input/rois` | `tier4_perception_msgs::msg::TrafficLightRoiArray` | The array of ROIs detected by map_based_detector | -| `~/expect/rois` | `tier4_perception_msgs::msg::TrafficLightRoiArray` | The array of ROIs detected by map_based_detector without any offset | +| Name | Type | Description | +| --------------- | -------------------------------------------------- | -------------------------------------------------------------------------------------------------------------- | +| `~/input/image` | `sensor_msgs::msg::Image` | The full size camera image | +| `~/input/rois` | `tier4_perception_msgs::msg::TrafficLightRoiArray` | The array of ROIs detected by map_based_detector | +| `~/expect/rois` | `tier4_perception_msgs::msg::TrafficLightRoiArray` | The array of ROIs detected by map_based_detector without any offset, used to select the best detection results | ### Output @@ -56,7 +57,7 @@ Based on the camera image and the global ROI array detected by `map_based_detect | `data_path` | string | "$(env HOME)/autoware_data" | packages data and artifacts directory path | | `fine_detector_model_path` | string | "" | The onnx file name for yolo model | | `fine_detector_label_path` | string | "" | The label file with label names for detected objects written on it | -| `fine_detector_precision` | string | "fp32" | The inference mode: "fp32", "fp16" | +| `fine_detector_precision` | string | "fp16" | The inference mode: "fp32", "fp16" | | `approximate_sync` | bool | false | Flag for whether to ues approximate sync policy | | `gpu_id` | integer | 0 | ID for the selecting CUDA GPU device | diff --git a/perception/autoware_traffic_light_fine_detector/config/traffic_light_fine_detector.param.yaml b/perception/autoware_traffic_light_fine_detector/config/traffic_light_fine_detector.param.yaml index 36d4413472a0b..b647729a27de5 100644 --- a/perception/autoware_traffic_light_fine_detector/config/traffic_light_fine_detector.param.yaml +++ b/perception/autoware_traffic_light_fine_detector/config/traffic_light_fine_detector.param.yaml @@ -5,4 +5,5 @@ fine_detector_precision: fp16 fine_detector_score_thresh: 0.3 fine_detector_nms_thresh: 0.65 + approximate_sync: false gpu_id: 0 diff --git a/perception/autoware_traffic_light_fine_detector/src/traffic_light_fine_detector_node.cpp b/perception/autoware_traffic_light_fine_detector/src/traffic_light_fine_detector_node.cpp index d9e0471a43d62..bc3d29ce456a8 100644 --- a/perception/autoware_traffic_light_fine_detector/src/traffic_light_fine_detector_node.cpp +++ b/perception/autoware_traffic_light_fine_detector/src/traffic_light_fine_detector_node.cpp @@ -61,7 +61,7 @@ TrafficLightFineDetectorNode::TrafficLightFineDetectorNode(const rclcpp::NodeOpt std::string model_path = declare_parameter("fine_detector_model_path", ""); std::string label_path = declare_parameter("fine_detector_label_path", ""); - std::string precision = declare_parameter("fine_detector_precision", "fp32"); + std::string precision = declare_parameter("fine_detector_precision", "fp16"); const uint8_t gpu_id = declare_parameter("gpu_id", 0); // Objects with a score lower than this value will be ignored. // This threshold will be ignored if specified model contains EfficientNMS_TRT module in it From bce4c44a7416f076071fa62bde37b1d21cc8e42d Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Fri, 17 Jan 2025 16:33:32 +0900 Subject: [PATCH 237/334] =?UTF-8?q?feat:=20tier4=5Fdebug=5Fmsgs=20changed?= =?UTF-8?q?=20to=20autoware=5Finternal=5Fdebug=5Fmsgs=20in=20fil=E2=80=A6?= =?UTF-8?q?=20(#9853)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files control/autoware_trajectory_follower_node Signed-off-by: vish0012 --- control/autoware_trajectory_follower_node/README.md | 2 +- .../autoware/trajectory_follower_node/controller_node.hpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/control/autoware_trajectory_follower_node/README.md b/control/autoware_trajectory_follower_node/README.md index ac05dd67f18e6..c56154f909d1a 100644 --- a/control/autoware_trajectory_follower_node/README.md +++ b/control/autoware_trajectory_follower_node/README.md @@ -151,7 +151,7 @@ Giving the longitudinal controller information about steer convergence allows it ## Debugging -Debug information are published by the lateral and longitudinal controller using `tier4_debug_msgs/Float32MultiArrayStamped` messages. +Debug information are published by the lateral and longitudinal controller using `autoware_internal_debug_msgs/Float32MultiArrayStamped` messages. A configuration file for [PlotJuggler](https://github.com/facontidavide/PlotJuggler) is provided in the `config` folder which, when loaded, allow to automatically subscribe and visualize information useful for debugging. diff --git a/control/autoware_trajectory_follower_node/include/autoware/trajectory_follower_node/controller_node.hpp b/control/autoware_trajectory_follower_node/include/autoware/trajectory_follower_node/controller_node.hpp index 1733b4bcbbb7d..c84355cc202fa 100644 --- a/control/autoware_trajectory_follower_node/include/autoware/trajectory_follower_node/controller_node.hpp +++ b/control/autoware_trajectory_follower_node/include/autoware/trajectory_follower_node/controller_node.hpp @@ -44,7 +44,7 @@ #include "tf2_msgs/msg/tf_message.hpp" #include "visualization_msgs/msg/marker_array.hpp" #include -#include +#include #include #include @@ -63,7 +63,7 @@ namespace trajectory_follower_node using autoware::universe_utils::StopWatch; using autoware_adapi_v1_msgs::msg::OperationModeState; using autoware_control_msgs::msg::ControlHorizon; -using tier4_debug_msgs::msg::Float64Stamped; +using autoware_internal_debug_msgs::msg::Float64Stamped; namespace trajectory_follower = ::autoware::motion::control::trajectory_follower; From dc75c7ff53ce2e5e1aaafd289a19e8d1e11c559b Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Fri, 17 Jan 2025 16:36:27 +0900 Subject: [PATCH 238/334] =?UTF-8?q?feat:=20tier4=5Fdebug=5Fmsgs=20changed?= =?UTF-8?q?=20to=20autoware=5Finternal=5Fdebug=5Fmsgs=20in=20fil=E2=80=A6?= =?UTF-8?q?=20(#9851)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../training_and_data_check/rosbag2.bash | 32 +++++++++---------- .../scripts/pympc_trajectory_follower.py | 6 ++-- 2 files changed, 19 insertions(+), 19 deletions(-) diff --git a/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/training_and_data_check/rosbag2.bash b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/training_and_data_check/rosbag2.bash index d2687b352a17d..7a50a7e118298 100644 --- a/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/training_and_data_check/rosbag2.bash +++ b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/training_and_data_check/rosbag2.bash @@ -7,27 +7,27 @@ gnome-terminal -- bash -c 'ros2 topic echo /vehicle/status/steering_status autow gnome-terminal -- bash -c 'ros2 topic echo /control/command/control_cmd autoware_control_msgs/msg/Control --csv --qos-history keep_all --qos-reliability reliable > control_cmd.csv' gnome-terminal -- bash -c 'ros2 topic echo /control/trajectory_follower/control_cmd autoware_control_msgs/msg/Control --csv --qos-history keep_all --qos-reliability reliable > control_cmd_orig.csv' -gnome-terminal -- bash -c 'ros2 topic echo /control/trajectory_follower/lane_departure_checker_node/debug/deviation/lateral tier4_debug_msgs/msg/Float64Stamped --csv --qos-history keep_all --qos-reliability reliable > lateral_error.csv' -gnome-terminal -- bash -c 'ros2 topic echo /control/trajectory_follower/lane_departure_checker_node/debug/deviation/yaw tier4_debug_msgs/msg/Float64Stamped --csv --qos-history keep_all --qos-reliability reliable > yaw_error.csv' +gnome-terminal -- bash -c 'ros2 topic echo /control/trajectory_follower/lane_departure_checker_node/debug/deviation/lateral autoware_internal_debug_msgs/msg/Float64Stamped --csv --qos-history keep_all --qos-reliability reliable > lateral_error.csv' +gnome-terminal -- bash -c 'ros2 topic echo /control/trajectory_follower/lane_departure_checker_node/debug/deviation/yaw autoware_internal_debug_msgs/msg/Float64Stamped --csv --qos-history keep_all --qos-reliability reliable > yaw_error.csv' gnome-terminal -- bash -c 'ros2 topic echo /system/operation_mode/state autoware_adapi_v1_msgs/msg/OperationModeState --csv --qos-history keep_all --qos-reliability reliable > system_operation_mode_state.csv' gnome-terminal -- bash -c 'ros2 topic echo /vehicle/status/control_mode autoware_vehicle_msgs/msg/ControlModeReport --csv --qos-history keep_all --qos-reliability reliable > vehicle_status_control_mode.csv' gnome-terminal -- bash -c 'ros2 topic echo /sensing/imu/imu_data sensor_msgs/msg/Imu --csv --qos-history keep_all --qos-reliability reliable > imu.csv' -gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_x_des tier4_debug_msgs/msg/Float32MultiArrayStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_x_des.csv' -gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_y_des tier4_debug_msgs/msg/Float32MultiArrayStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_y_des.csv' -gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_v_des tier4_debug_msgs/msg/Float32MultiArrayStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_v_des.csv' -gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_yaw_des tier4_debug_msgs/msg/Float32MultiArrayStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_yaw_des.csv' -gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_acc_des tier4_debug_msgs/msg/Float32MultiArrayStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_acc_des.csv' -gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_steer_des tier4_debug_msgs/msg/Float32MultiArrayStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_steer_des.csv' -gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_X_des_converted tier4_debug_msgs/msg/Float32MultiArrayStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_X_des_converted.csv' -gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_x_current tier4_debug_msgs/msg/Float32MultiArrayStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_x_current.csv' -gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_error_prediction tier4_debug_msgs/msg/Float32MultiArrayStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_error_prediction.csv' -gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_max_trajectory_err tier4_debug_msgs/msg/Float32Stamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_max_trajectory_err.csv' -gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_emergency_stop_mode tier4_debug_msgs/msg/BoolStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_emergency_stop_mode.csv' -gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_goal_stop_mode tier4_debug_msgs/msg/BoolStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_goal_stop_mode.csv' -gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_total_ctrl_time tier4_debug_msgs/msg/Float32Stamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_total_ctrl_time.csv' -gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_calc_u_opt_time tier4_debug_msgs/msg/Float32Stamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_calc_u_opt_time.csv' +gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_x_des autoware_internal_debug_msgs/msg/Float32MultiArrayStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_x_des.csv' +gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_y_des autoware_internal_debug_msgs/msg/Float32MultiArrayStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_y_des.csv' +gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_v_des autoware_internal_debug_msgs/msg/Float32MultiArrayStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_v_des.csv' +gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_yaw_des autoware_internal_debug_msgs/msg/Float32MultiArrayStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_yaw_des.csv' +gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_acc_des autoware_internal_debug_msgs/msg/Float32MultiArrayStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_acc_des.csv' +gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_steer_des autoware_internal_debug_msgs/msg/Float32MultiArrayStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_steer_des.csv' +gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_X_des_converted autoware_internal_debug_msgs/msg/Float32MultiArrayStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_X_des_converted.csv' +gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_x_current autoware_internal_debug_msgs/msg/Float32MultiArrayStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_x_current.csv' +gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_error_prediction autoware_internal_debug_msgs/msg/Float32MultiArrayStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_error_prediction.csv' +gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_max_trajectory_err autoware_internal_debug_msgs/msg/Float32Stamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_max_trajectory_err.csv' +gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_emergency_stop_mode autoware_internal_debug_msgs/msg/BoolStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_emergency_stop_mode.csv' +gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_goal_stop_mode autoware_internal_debug_msgs/msg/BoolStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_goal_stop_mode.csv' +gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_total_ctrl_time autoware_internal_debug_msgs/msg/Float32Stamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_total_ctrl_time.csv' +gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_calc_u_opt_time autoware_internal_debug_msgs/msg/Float32Stamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_calc_u_opt_time.csv' # wait a moment to open new terminals converting rosbag2 to csv sleep 8 diff --git a/control/autoware_smart_mpc_trajectory_follower/scripts/pympc_trajectory_follower.py b/control/autoware_smart_mpc_trajectory_follower/scripts/pympc_trajectory_follower.py index f767dad223f0d..104261866cf98 100755 --- a/control/autoware_smart_mpc_trajectory_follower/scripts/pympc_trajectory_follower.py +++ b/control/autoware_smart_mpc_trajectory_follower/scripts/pympc_trajectory_follower.py @@ -21,6 +21,9 @@ from autoware_adapi_v1_msgs.msg import OperationModeState from autoware_control_msgs.msg import Control +from autoware_internal_debug_msgs.msg import BoolStamped +from autoware_internal_debug_msgs.msg import Float32MultiArrayStamped +from autoware_internal_debug_msgs.msg import Float32Stamped from autoware_planning_msgs.msg import Trajectory from autoware_planning_msgs.msg import TrajectoryPoint from autoware_smart_mpc_trajectory_follower.scripts import drive_controller @@ -43,9 +46,6 @@ from scipy.spatial.transform import Rotation as R from scipy.spatial.transform import Slerp from std_msgs.msg import String -from tier4_debug_msgs.msg import BoolStamped -from tier4_debug_msgs.msg import Float32MultiArrayStamped -from tier4_debug_msgs.msg import Float32Stamped from visualization_msgs.msg import Marker from visualization_msgs.msg import MarkerArray From 2a6663b27472695357628bdc106494ae3ad85a4f Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Fri, 17 Jan 2025 16:36:46 +0900 Subject: [PATCH 239/334] =?UTF-8?q?feat(autoware=5Fdetected=5Fobject=5Fval?= =?UTF-8?q?idation):=20tier4=5Fdebug=5Fmsgs=20changed=20to=20autoware=5Fin?= =?UTF-8?q?ternal=5Fdebug=5Fmsgs=20in=20fil=E2=80=A6=20(#9871)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files perception/autoware_detected_object_validation Signed-off-by: vish0012 Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> --- .../src/lanelet_filter/lanelet_filter.cpp | 4 ++-- .../src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp b/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp index f91c4e2036227..f1c25e8573e85 100644 --- a/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp +++ b/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp @@ -180,9 +180,9 @@ void ObjectLaneletFilterNode::objectCallback( std::chrono::nanoseconds( (this->get_clock()->now() - output_object_msg.header.stamp).nanoseconds())) .count(); - debug_publisher_->publish( + debug_publisher_->publish( "debug/pipeline_latency_ms", pipeline_latency); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", stop_watch_ptr_->toc("processing_time", true)); } diff --git a/perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp b/perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp index 979cdd3909f14..0c69b45291281 100644 --- a/perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp +++ b/perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp @@ -386,7 +386,7 @@ void ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud( std::chrono::duration( std::chrono::nanoseconds((this->get_clock()->now() - output.header.stamp).nanoseconds())) .count(); - debug_publisher_->publish( + debug_publisher_->publish( "debug/pipeline_latency_ms", pipeline_latency); } From aa95f2a4f27f847532006e16ceee4d458a32d515 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 17 Jan 2025 17:07:04 +0900 Subject: [PATCH 240/334] chore(planning): move package directory for planning factor interface (#9948) * chore: add new package for planning factor interface Signed-off-by: satoshi-ota * chore(surround_obstacle_checker): update include file Signed-off-by: satoshi-ota * chore(obstacle_stop_planner): update include file Signed-off-by: satoshi-ota * chore(obstacle_cruise_planner): update include file Signed-off-by: satoshi-ota * chore(motion_velocity_planner): update include file Signed-off-by: satoshi-ota * chore(bpp): update include file Signed-off-by: satoshi-ota * chore(bvp-common): update include file Signed-off-by: satoshi-ota * chore(blind_spot): update include file Signed-off-by: satoshi-ota * chore(crosswalk): update include file Signed-off-by: satoshi-ota * chore(detection_area): update include file Signed-off-by: satoshi-ota * chore(intersection): update include file Signed-off-by: satoshi-ota * chore(no_drivable_area): update include file Signed-off-by: satoshi-ota * chore(no_stopping_area): update include file Signed-off-by: satoshi-ota * chore(occlusion_spot): update include file Signed-off-by: satoshi-ota * chore(run_out): update include file Signed-off-by: satoshi-ota * chore(speed_bump): update include file Signed-off-by: satoshi-ota * chore(stop_line): update include file Signed-off-by: satoshi-ota * chore(template_module): update include file Signed-off-by: satoshi-ota * chore(traffic_light): update include file Signed-off-by: satoshi-ota * chore(vtl): update include file Signed-off-by: satoshi-ota * chore(walkway): update include file Signed-off-by: satoshi-ota * chore(motion_utils): remove factor interface Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../factor/steering_factor_interface.hpp | 51 ---------------- .../factor/velocity_factor_interface.hpp | 57 ----------------- .../src/factor/steering_factor_interface.cpp | 34 ----------- .../src/factor/velocity_factor_interface.cpp | 61 ------------------- .../planner_interface.hpp | 8 ++- .../package.xml | 1 + .../package.xml | 1 + .../src/debug_marker.cpp | 5 +- .../src/debug_marker.hpp | 5 +- .../CMakeLists.txt | 11 ++++ .../README.md | 1 + .../planning_factor_interface.hpp | 10 +-- .../package.xml | 29 +++++++++ .../src}/planing_factor_interface.cpp | 6 +- .../package.xml | 1 + .../src/debug_marker.cpp | 3 +- .../src/debug_marker.hpp | 5 +- .../behavior_path_planner_node.hpp | 4 +- .../package.xml | 1 + .../interface/scene_module_interface.hpp | 4 +- .../package.xml | 1 + .../scene.hpp | 3 +- .../src/scene.cpp | 3 +- .../src/scene_crosswalk.cpp | 3 +- .../src/scene_crosswalk.hpp | 3 +- .../src/scene.cpp | 3 +- .../src/scene.hpp | 3 +- .../src/scene_intersection.cpp | 27 ++++---- .../src/scene_intersection.hpp | 3 +- .../src/scene_merge_from_private_road.cpp | 3 +- .../src/scene_merge_from_private_road.hpp | 3 +- .../src/scene.cpp | 3 +- .../src/scene.hpp | 3 +- .../src/scene_no_stopping_area.cpp | 3 +- .../src/scene_no_stopping_area.hpp | 3 +- .../src/scene_occlusion_spot.cpp | 3 +- .../src/scene_occlusion_spot.hpp | 3 +- .../scene_module_interface.hpp | 11 ++-- .../package.xml | 1 + .../src/scene_module_interface.cpp | 3 +- .../scene_module_interface_with_rtc.hpp | 3 +- .../package.xml | 1 + .../src/scene_module_interface_with_rtc.cpp | 3 +- .../src/scene.cpp | 3 +- .../src/scene.hpp | 3 +- .../src/scene.cpp | 3 +- .../src/scene.hpp | 3 +- .../src/scene.cpp | 3 +- .../src/scene.hpp | 3 +- .../test/test_scene.cpp | 2 +- .../src/scene.cpp | 3 +- .../src/scene.hpp | 3 +- .../src/scene.cpp | 3 +- .../src/scene.hpp | 3 +- .../src/scene.cpp | 3 +- .../src/scene.hpp | 3 +- .../src/scene_walkway.cpp | 3 +- .../src/scene_walkway.hpp | 3 +- .../src/dynamic_obstacle_stop_module.cpp | 5 +- .../src/out_of_lane_module.cpp | 3 +- .../plugin_module_interface.hpp | 5 +- .../package.xml | 1 + 62 files changed, 170 insertions(+), 281 deletions(-) delete mode 100644 common/autoware_motion_utils/include/autoware/motion_utils/factor/steering_factor_interface.hpp delete mode 100644 common/autoware_motion_utils/include/autoware/motion_utils/factor/velocity_factor_interface.hpp delete mode 100644 common/autoware_motion_utils/src/factor/steering_factor_interface.cpp delete mode 100644 common/autoware_motion_utils/src/factor/velocity_factor_interface.cpp create mode 100644 planning/autoware_planning_factor_interface/CMakeLists.txt create mode 100644 planning/autoware_planning_factor_interface/README.md rename {common/autoware_motion_utils/include/autoware/motion_utils/factor => planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface}/planning_factor_interface.hpp (96%) create mode 100644 planning/autoware_planning_factor_interface/package.xml rename {common/autoware_motion_utils/src/factor => planning/autoware_planning_factor_interface/src}/planing_factor_interface.cpp (93%) diff --git a/common/autoware_motion_utils/include/autoware/motion_utils/factor/steering_factor_interface.hpp b/common/autoware_motion_utils/include/autoware/motion_utils/factor/steering_factor_interface.hpp deleted file mode 100644 index 5b701a73ac543..0000000000000 --- a/common/autoware_motion_utils/include/autoware/motion_utils/factor/steering_factor_interface.hpp +++ /dev/null @@ -1,51 +0,0 @@ -// Copyright 2022 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__MOTION_UTILS__FACTOR__STEERING_FACTOR_INTERFACE_HPP_ -#define AUTOWARE__MOTION_UTILS__FACTOR__STEERING_FACTOR_INTERFACE_HPP_ - -#include -#include -#include - -#include - -namespace autoware::motion_utils -{ - -using autoware_adapi_v1_msgs::msg::PlanningBehavior; -using autoware_adapi_v1_msgs::msg::SteeringFactor; -using SteeringFactorBehavior = SteeringFactor::_behavior_type; -using SteeringFactorStatus = SteeringFactor::_status_type; -using geometry_msgs::msg::Pose; - -class SteeringFactorInterface -{ -public: - [[nodiscard]] SteeringFactor get() const { return steering_factor_; } - void init(const SteeringFactorBehavior & behavior) { behavior_ = behavior; } - void reset() { steering_factor_.behavior = PlanningBehavior::UNKNOWN; } - - void set( - const std::array & pose, const std::array distance, - const uint16_t direction, const uint16_t status, const std::string & detail = ""); - -private: - SteeringFactorBehavior behavior_{SteeringFactor::UNKNOWN}; - SteeringFactor steering_factor_{}; -}; - -} // namespace autoware::motion_utils - -#endif // AUTOWARE__MOTION_UTILS__FACTOR__STEERING_FACTOR_INTERFACE_HPP_ diff --git a/common/autoware_motion_utils/include/autoware/motion_utils/factor/velocity_factor_interface.hpp b/common/autoware_motion_utils/include/autoware/motion_utils/factor/velocity_factor_interface.hpp deleted file mode 100644 index 2fcde52ec7c81..0000000000000 --- a/common/autoware_motion_utils/include/autoware/motion_utils/factor/velocity_factor_interface.hpp +++ /dev/null @@ -1,57 +0,0 @@ - -// Copyright 2022-2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__MOTION_UTILS__FACTOR__VELOCITY_FACTOR_INTERFACE_HPP_ -#define AUTOWARE__MOTION_UTILS__FACTOR__VELOCITY_FACTOR_INTERFACE_HPP_ - -#include -#include -#include -#include - -#include -#include - -namespace autoware::motion_utils -{ -using autoware_adapi_v1_msgs::msg::PlanningBehavior; -using autoware_adapi_v1_msgs::msg::VelocityFactor; -using VelocityFactorBehavior = VelocityFactor::_behavior_type; -using VelocityFactorStatus = VelocityFactor::_status_type; -using geometry_msgs::msg::Pose; - -class VelocityFactorInterface -{ -public: - [[nodiscard]] VelocityFactor get() const { return velocity_factor_; } - void init(const VelocityFactorBehavior & behavior) { behavior_ = behavior; } - void reset() { velocity_factor_.behavior = PlanningBehavior::UNKNOWN; } - - template - void set( - const std::vector & points, const Pose & curr_pose, const Pose & stop_pose, - const VelocityFactorStatus status, const std::string & detail = ""); - - void set( - const double & distance, const VelocityFactorStatus & status, const std::string & detail = ""); - -private: - VelocityFactorBehavior behavior_{VelocityFactor::UNKNOWN}; - VelocityFactor velocity_factor_{}; -}; - -} // namespace autoware::motion_utils - -#endif // AUTOWARE__MOTION_UTILS__FACTOR__VELOCITY_FACTOR_INTERFACE_HPP_ diff --git a/common/autoware_motion_utils/src/factor/steering_factor_interface.cpp b/common/autoware_motion_utils/src/factor/steering_factor_interface.cpp deleted file mode 100644 index 7f12e2972ec86..0000000000000 --- a/common/autoware_motion_utils/src/factor/steering_factor_interface.cpp +++ /dev/null @@ -1,34 +0,0 @@ -// Copyright 2022 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include - -#include - -namespace autoware::motion_utils -{ -void SteeringFactorInterface::set( - const std::array & pose, const std::array distance, const uint16_t direction, - const uint16_t status, const std::string & detail) -{ - steering_factor_.pose = pose; - std::array converted_distance{0.0, 0.0}; - for (int i = 0; i < 2; ++i) converted_distance[i] = static_cast(distance[i]); - steering_factor_.distance = converted_distance; - steering_factor_.behavior = behavior_; - steering_factor_.direction = direction; - steering_factor_.status = status; - steering_factor_.detail = detail; -} -} // namespace autoware::motion_utils diff --git a/common/autoware_motion_utils/src/factor/velocity_factor_interface.cpp b/common/autoware_motion_utils/src/factor/velocity_factor_interface.cpp deleted file mode 100644 index cfa3c91eac43e..0000000000000 --- a/common/autoware_motion_utils/src/factor/velocity_factor_interface.cpp +++ /dev/null @@ -1,61 +0,0 @@ -// Copyright 2023-2024 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include -#include - -#include -#include -#include - -#include -#include - -namespace autoware::motion_utils -{ -template -void VelocityFactorInterface::set( - const std::vector & points, const Pose & curr_pose, const Pose & stop_pose, - const VelocityFactorStatus status, const std::string & detail) -{ - const auto & curr_point = curr_pose.position; - const auto & stop_point = stop_pose.position; - velocity_factor_.behavior = behavior_; - velocity_factor_.pose = stop_pose; - velocity_factor_.distance = - static_cast(autoware::motion_utils::calcSignedArcLength(points, curr_point, stop_point)); - velocity_factor_.status = status; - velocity_factor_.detail = detail; -} - -void VelocityFactorInterface::set( - const double & distance, const VelocityFactorStatus & status, const std::string & detail) -{ - velocity_factor_.behavior = behavior_; - velocity_factor_.distance = static_cast(distance); - velocity_factor_.status = status; - velocity_factor_.detail = detail; -} - -template void VelocityFactorInterface::set( - const std::vector &, const Pose &, const Pose &, - const VelocityFactorStatus, const std::string &); -template void VelocityFactorInterface::set( - const std::vector &, const Pose &, const Pose &, - const VelocityFactorStatus, const std::string &); -template void VelocityFactorInterface::set( - const std::vector &, const Pose &, const Pose &, - const VelocityFactorStatus, const std::string &); - -} // namespace autoware::motion_utils diff --git a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/planner_interface.hpp b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/planner_interface.hpp index 823771e173c48..f5e183afd12bd 100644 --- a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/planner_interface.hpp +++ b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/planner_interface.hpp @@ -15,12 +15,12 @@ #ifndef AUTOWARE__OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_ #define AUTOWARE__OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_ -#include "autoware/motion_utils/factor/planning_factor_interface.hpp" #include "autoware/motion_utils/trajectory/trajectory.hpp" #include "autoware/obstacle_cruise_planner/common_structs.hpp" #include "autoware/obstacle_cruise_planner/stop_planning_debug_info.hpp" #include "autoware/obstacle_cruise_planner/type_alias.hpp" #include "autoware/obstacle_cruise_planner/utils.hpp" +#include "autoware/planning_factor_interface/planning_factor_interface.hpp" #include "autoware/universe_utils/ros/update_param.hpp" #include "autoware/universe_utils/system/stop_watch.hpp" @@ -48,7 +48,8 @@ class PlannerInterface rclcpp::Node & node, const LongitudinalInfo & longitudinal_info, const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const EgoNearestParam & ego_nearest_param, const std::shared_ptr debug_data_ptr) - : planning_factor_interface_{std::make_unique( + : planning_factor_interface_{std::make_unique< + autoware::planning_factor_interface::PlanningFactorInterface>( &node, "obstacle_cruise_planner")}, longitudinal_info_(longitudinal_info), vehicle_info_(vehicle_info), @@ -130,7 +131,8 @@ class PlannerInterface double getSafeDistanceMargin() const { return longitudinal_info_.safe_distance_margin; } protected: - std::unique_ptr planning_factor_interface_; + std::unique_ptr + planning_factor_interface_; // Parameters bool enable_debug_info_{false}; diff --git a/planning/autoware_obstacle_cruise_planner/package.xml b/planning/autoware_obstacle_cruise_planner/package.xml index 7c6d0b286c9b0..71c3b1fb1e0d5 100644 --- a/planning/autoware_obstacle_cruise_planner/package.xml +++ b/planning/autoware_obstacle_cruise_planner/package.xml @@ -25,6 +25,7 @@ autoware_objects_of_interest_marker_interface autoware_osqp_interface autoware_perception_msgs + autoware_planning_factor_interface autoware_planning_msgs autoware_planning_test_manager autoware_signal_processing diff --git a/planning/autoware_obstacle_stop_planner/package.xml b/planning/autoware_obstacle_stop_planner/package.xml index c9c78b3e87c3b..ba6364a2b59ee 100644 --- a/planning/autoware_obstacle_stop_planner/package.xml +++ b/planning/autoware_obstacle_stop_planner/package.xml @@ -23,6 +23,7 @@ autoware_adapi_v1_msgs autoware_motion_utils autoware_perception_msgs + autoware_planning_factor_interface autoware_planning_msgs autoware_planning_test_manager autoware_signal_processing diff --git a/planning/autoware_obstacle_stop_planner/src/debug_marker.cpp b/planning/autoware_obstacle_stop_planner/src/debug_marker.cpp index 62b9ae124f555..a3337c5dd2524 100644 --- a/planning/autoware_obstacle_stop_planner/src/debug_marker.cpp +++ b/planning/autoware_obstacle_stop_planner/src/debug_marker.cpp @@ -47,8 +47,9 @@ ObstacleStopPlannerDebugNode::ObstacleStopPlannerDebugNode( rclcpp::Node * node, const double base_link2front) : node_(node), base_link2front_(base_link2front), - planning_factor_interface_{std::make_unique( - node, "obstacle_stop_planner")} + planning_factor_interface_{ + std::make_unique( + node, "obstacle_stop_planner")} { virtual_wall_pub_ = node_->create_publisher("~/virtual_wall", 1); debug_viz_pub_ = node_->create_publisher("~/debug/marker", 1); diff --git a/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp b/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp index dd9e5e3af1b3d..72e2b52c287f1 100644 --- a/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp +++ b/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp @@ -14,7 +14,7 @@ #ifndef DEBUG_MARKER_HPP_ #define DEBUG_MARKER_HPP_ -#include +#include #include #include @@ -119,7 +119,8 @@ class ObstacleStopPlannerDebugNode rclcpp::Node * node_; double base_link2front_; - std::unique_ptr planning_factor_interface_; + std::unique_ptr + planning_factor_interface_; std::shared_ptr stop_pose_ptr_; std::shared_ptr target_stop_pose_ptr_; diff --git a/planning/autoware_planning_factor_interface/CMakeLists.txt b/planning/autoware_planning_factor_interface/CMakeLists.txt new file mode 100644 index 0000000000000..0c25a2c21fa19 --- /dev/null +++ b/planning/autoware_planning_factor_interface/CMakeLists.txt @@ -0,0 +1,11 @@ +cmake_minimum_required(VERSION 3.14) +project(autoware_planning_factor_interface) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_library(autoware_planning_factor_interface SHARED + DIRECTORY src +) + +ament_auto_package() diff --git a/planning/autoware_planning_factor_interface/README.md b/planning/autoware_planning_factor_interface/README.md new file mode 100644 index 0000000000000..7f715790995ba --- /dev/null +++ b/planning/autoware_planning_factor_interface/README.md @@ -0,0 +1 @@ +# planning factor interface diff --git a/common/autoware_motion_utils/include/autoware/motion_utils/factor/planning_factor_interface.hpp b/planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp similarity index 96% rename from common/autoware_motion_utils/include/autoware/motion_utils/factor/planning_factor_interface.hpp rename to planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp index 7b720c69c6701..a2325b197853d 100644 --- a/common/autoware_motion_utils/include/autoware/motion_utils/factor/planning_factor_interface.hpp +++ b/planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__MOTION_UTILS__FACTOR__PLANNING_FACTOR_INTERFACE_HPP_ -#define AUTOWARE__MOTION_UTILS__FACTOR__PLANNING_FACTOR_INTERFACE_HPP_ +#ifndef AUTOWARE__PLANNING_FACTOR_INTERFACE__PLANNING_FACTOR_INTERFACE_HPP_ +#define AUTOWARE__PLANNING_FACTOR_INTERFACE__PLANNING_FACTOR_INTERFACE_HPP_ #include #include @@ -30,7 +30,7 @@ #include #include -namespace autoware::motion_utils +namespace autoware::planning_factor_interface { using geometry_msgs::msg::Pose; @@ -235,6 +235,6 @@ extern template void PlanningFactorInterface::add + + + autoware_planning_factor_interface + 0.40.0 + The autoware_planning_factor_interface package + Satoshi Ota + Mamoru Sobue + Apache License 2.0 + + Satoshi Ota + + ament_cmake_auto + autoware_cmake + + autoware_motion_utils + autoware_planning_msgs + autoware_universe_utils + rclcpp + tier4_planning_msgs + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/common/autoware_motion_utils/src/factor/planing_factor_interface.cpp b/planning/autoware_planning_factor_interface/src/planing_factor_interface.cpp similarity index 93% rename from common/autoware_motion_utils/src/factor/planing_factor_interface.cpp rename to planning/autoware_planning_factor_interface/src/planing_factor_interface.cpp index d09355b4003ae..6578776dddc4f 100644 --- a/common/autoware_motion_utils/src/factor/planing_factor_interface.cpp +++ b/planning/autoware_planning_factor_interface/src/planing_factor_interface.cpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include #include #include -namespace autoware::motion_utils +namespace autoware::planning_factor_interface { template void PlanningFactorInterface::add( const std::vector &, const Pose &, const Pose &, @@ -44,4 +44,4 @@ template void PlanningFactorInterface::add &, const Pose &, const Pose &, const Pose &, const uint16_t behavior, const SafetyFactorArray &, const bool, const double, const double, const std::string &); -} // namespace autoware::motion_utils +} // namespace autoware::planning_factor_interface diff --git a/planning/autoware_surround_obstacle_checker/package.xml b/planning/autoware_surround_obstacle_checker/package.xml index 8bbc0b6bf4e02..d92223fb2ea5d 100644 --- a/planning/autoware_surround_obstacle_checker/package.xml +++ b/planning/autoware_surround_obstacle_checker/package.xml @@ -16,6 +16,7 @@ autoware_motion_utils autoware_perception_msgs + autoware_planning_factor_interface autoware_planning_msgs autoware_planning_test_manager autoware_universe_utils diff --git a/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp b/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp index 2acf6ba1c92f5..e34315ad986a5 100644 --- a/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp +++ b/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp @@ -67,7 +67,8 @@ SurroundObstacleCheckerDebugNode::SurroundObstacleCheckerDebugNode( const double & surround_check_back_distance, const double & surround_check_hysteresis_distance, const geometry_msgs::msg::Pose & self_pose, const rclcpp::Clock::SharedPtr clock, rclcpp::Node & node) -: planning_factor_interface_{std::make_unique( +: planning_factor_interface_{std::make_unique< + autoware::planning_factor_interface::PlanningFactorInterface>( &node, "surround_obstacle_checker")}, vehicle_info_(vehicle_info), object_label_(object_label), diff --git a/planning/autoware_surround_obstacle_checker/src/debug_marker.hpp b/planning/autoware_surround_obstacle_checker/src/debug_marker.hpp index c49e277f2dc6c..0569c6815a252 100644 --- a/planning/autoware_surround_obstacle_checker/src/debug_marker.hpp +++ b/planning/autoware_surround_obstacle_checker/src/debug_marker.hpp @@ -15,7 +15,7 @@ #ifndef DEBUG_MARKER_HPP_ #define DEBUG_MARKER_HPP_ -#include +#include #include #include @@ -70,7 +70,8 @@ class SurroundObstacleCheckerDebugNode rclcpp::Publisher::SharedPtr vehicle_footprint_offset_pub_; rclcpp::Publisher::SharedPtr vehicle_footprint_recover_offset_pub_; - std::unique_ptr planning_factor_interface_; + std::unique_ptr + planning_factor_interface_; autoware::vehicle_info_utils::VehicleInfo vehicle_info_; std::string object_label_; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/behavior_path_planner_node.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/behavior_path_planner_node.hpp index 7f7ecd7326b08..ba3d3d5d7a4d4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/behavior_path_planner_node.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/behavior_path_planner_node.hpp @@ -20,7 +20,7 @@ #include "autoware/universe_utils/ros/logger_level_configure.hpp" #include "planner_manager.hpp" -#include +#include #include #include @@ -51,7 +51,7 @@ namespace autoware::behavior_path_planner { -using autoware::motion_utils::PlanningFactorInterface; +using autoware::planning_factor_interface::PlanningFactorInterface; using autoware_adapi_v1_msgs::msg::OperationModeState; using autoware_map_msgs::msg::LaneletMapBin; using autoware_perception_msgs::msg::PredictedObject; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/package.xml b/planning/behavior_path_planner/autoware_behavior_path_planner/package.xml index f9c736b9d5dde..3f41ebe74c86d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/package.xml @@ -48,6 +48,7 @@ autoware_object_recognition_utils autoware_path_sampler autoware_perception_msgs + autoware_planning_factor_interface autoware_planning_msgs autoware_planning_test_manager autoware_signal_processing diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp index c96bc601b6403..741d4552d8558 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp @@ -21,11 +21,11 @@ #include "autoware/behavior_path_planner_common/utils/utils.hpp" #include -#include #include #include #include #include +#include #include #include #include @@ -52,9 +52,9 @@ namespace autoware::behavior_path_planner { -using autoware::motion_utils::PlanningFactorInterface; using autoware::objects_of_interest_marker_interface::ColorName; using autoware::objects_of_interest_marker_interface::ObjectsOfInterestMarkerInterface; +using autoware::planning_factor_interface::PlanningFactorInterface; using autoware::rtc_interface::RTCInterface; using autoware::universe_utils::calcOffsetPose; using autoware::universe_utils::generateUUID; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml b/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml index f23a9980f1237..22237a5a1d3a4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml @@ -52,6 +52,7 @@ autoware_object_recognition_utils autoware_objects_of_interest_marker_interface autoware_perception_msgs + autoware_planning_factor_interface autoware_planning_msgs autoware_route_handler autoware_rtc_interface diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/scene.hpp index 91eff0b01346a..2d7b79357b602 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/scene.hpp @@ -76,7 +76,8 @@ class BlindSpotModule : public SceneModuleInterfaceWithRTC const std::shared_ptr planner_data, const PlannerParam & planner_param, const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface); + const std::shared_ptr + planning_factor_interface); /** * @brief plan go-stop velocity at traffic crossing with collision check between reference path diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp index 4fca5f821f934..12943912f04cd 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp @@ -42,7 +42,8 @@ BlindSpotModule::BlindSpotModule( const std::shared_ptr planner_data, const PlannerParam & planner_param, const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface) + const std::shared_ptr + planning_factor_interface) : SceneModuleInterfaceWithRTC(module_id, logger, clock, time_keeper, planning_factor_interface), lane_id_(lane_id), planner_param_{planner_param}, diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 844647e33f8c0..754c14df9fac7 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -177,7 +177,8 @@ CrosswalkModule::CrosswalkModule( const PlannerParam & planner_param, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface) + const std::shared_ptr + planning_factor_interface) : SceneModuleInterfaceWithRTC(module_id, logger, clock, time_keeper, planning_factor_interface), module_id_(module_id), planner_param_(planner_param), diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index f32ee96623822..b9803207a1a31 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -336,7 +336,8 @@ class CrosswalkModule : public SceneModuleInterfaceWithRTC const PlannerParam & planner_param, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface); + const std::shared_ptr + planning_factor_interface); bool modifyPathVelocity(PathWithLaneId * path) override; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp index 7e6a320f3ddad..8641ce19e4ae5 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp @@ -38,7 +38,8 @@ DetectionAreaModule::DetectionAreaModule( const PlannerParam & planner_param, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface) + const std::shared_ptr + planning_factor_interface) : SceneModuleInterface(module_id, logger, clock, time_keeper, planning_factor_interface), lane_id_(lane_id), detection_area_reg_elem_(detection_area_reg_elem), diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.hpp index 1d3e5f3540ff3..42cc0461cd59d 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.hpp @@ -70,7 +70,8 @@ class DetectionAreaModule : public SceneModuleInterface const PlannerParam & planner_param, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface); + const std::shared_ptr + planning_factor_interface); bool modifyPathVelocity(PathWithLaneId * path) override; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp index 5b8aca1c8ec9d..daebfbed3d12a 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -51,7 +51,8 @@ IntersectionModule::IntersectionModule( const std::string & turn_direction, const bool has_traffic_light, rclcpp::Node & node, const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface) + const std::shared_ptr + planning_factor_interface) : SceneModuleInterfaceWithRTC(module_id, logger, clock, time_keeper, planning_factor_interface), planner_param_(planner_param), lane_id_(lane_id), @@ -702,7 +703,7 @@ void reactRTCApprovalByDecisionResult( [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, [[maybe_unused]] const double baselink2front, [[maybe_unused]] tier4_planning_msgs::msg::PathWithLaneId * path, - [[maybe_unused]] motion_utils::PlanningFactorInterface * planning_factor_interface, + [[maybe_unused]] planning_factor_interface::PlanningFactorInterface * planning_factor_interface, [[maybe_unused]] IntersectionModule::DebugData * debug_data) { static_assert("Unsupported type passed to reactRTCByDecisionResult"); @@ -717,7 +718,7 @@ void reactRTCApprovalByDecisionResult( [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, [[maybe_unused]] const double baselink2front, [[maybe_unused]] tier4_planning_msgs::msg::PathWithLaneId * path, - [[maybe_unused]] motion_utils::PlanningFactorInterface * planning_factor_interface, + [[maybe_unused]] planning_factor_interface::PlanningFactorInterface * planning_factor_interface, [[maybe_unused]] IntersectionModule::DebugData * debug_data) { return; @@ -731,7 +732,7 @@ void reactRTCApprovalByDecisionResult( [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, [[maybe_unused]] const double baselink2front, [[maybe_unused]] tier4_planning_msgs::msg::PathWithLaneId * path, - [[maybe_unused]] motion_utils::PlanningFactorInterface * planning_factor_interface, + [[maybe_unused]] planning_factor_interface::PlanningFactorInterface * planning_factor_interface, [[maybe_unused]] IntersectionModule::DebugData * debug_data) { return; @@ -743,7 +744,7 @@ void reactRTCApprovalByDecisionResult( const StuckStop & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, - motion_utils::PlanningFactorInterface * planning_factor_interface, + planning_factor_interface::PlanningFactorInterface * planning_factor_interface, IntersectionModule::DebugData * debug_data) { RCLCPP_DEBUG( @@ -790,7 +791,7 @@ void reactRTCApprovalByDecisionResult( const YieldStuckStop & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, - motion_utils::PlanningFactorInterface * planning_factor_interface, + planning_factor_interface::PlanningFactorInterface * planning_factor_interface, IntersectionModule::DebugData * debug_data) { RCLCPP_DEBUG( @@ -822,7 +823,7 @@ void reactRTCApprovalByDecisionResult( const NonOccludedCollisionStop & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, - motion_utils::PlanningFactorInterface * planning_factor_interface, + planning_factor_interface::PlanningFactorInterface * planning_factor_interface, IntersectionModule::DebugData * debug_data) { RCLCPP_DEBUG( @@ -866,7 +867,7 @@ void reactRTCApprovalByDecisionResult( const FirstWaitBeforeOcclusion & decision_result, const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, - motion_utils::PlanningFactorInterface * planning_factor_interface, + planning_factor_interface::PlanningFactorInterface * planning_factor_interface, IntersectionModule::DebugData * debug_data) { RCLCPP_DEBUG( @@ -918,7 +919,7 @@ void reactRTCApprovalByDecisionResult( const PeekingTowardOcclusion & decision_result, const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, - motion_utils::PlanningFactorInterface * planning_factor_interface, + planning_factor_interface::PlanningFactorInterface * planning_factor_interface, IntersectionModule::DebugData * debug_data) { RCLCPP_DEBUG( @@ -976,7 +977,7 @@ void reactRTCApprovalByDecisionResult( const OccludedCollisionStop & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, - motion_utils::PlanningFactorInterface * planning_factor_interface, + planning_factor_interface::PlanningFactorInterface * planning_factor_interface, IntersectionModule::DebugData * debug_data) { RCLCPP_DEBUG( @@ -1024,7 +1025,7 @@ void reactRTCApprovalByDecisionResult( const OccludedAbsenceTrafficLight & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, - motion_utils::PlanningFactorInterface * planning_factor_interface, + planning_factor_interface::PlanningFactorInterface * planning_factor_interface, IntersectionModule::DebugData * debug_data) { RCLCPP_DEBUG( @@ -1078,7 +1079,7 @@ void reactRTCApprovalByDecisionResult( const bool rtc_default_approved, const bool rtc_occlusion_approved, const Safe & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, - motion_utils::PlanningFactorInterface * planning_factor_interface, + planning_factor_interface::PlanningFactorInterface * planning_factor_interface, IntersectionModule::DebugData * debug_data) { RCLCPP_DEBUG( @@ -1121,7 +1122,7 @@ void reactRTCApprovalByDecisionResult( const FullyPrioritized & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, - motion_utils::PlanningFactorInterface * planning_factor_interface, + planning_factor_interface::PlanningFactorInterface * planning_factor_interface, IntersectionModule::DebugData * debug_data) { RCLCPP_DEBUG( diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp index db0cfbe98d53c..39a56977b301e 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -306,7 +306,8 @@ class IntersectionModule : public SceneModuleInterfaceWithRTC const std::string & turn_direction, const bool has_traffic_light, rclcpp::Node & node, const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface); + const std::shared_ptr + planning_factor_interface); /** *********************************************************** diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp index fc442337198af..d12b58a63e531 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp @@ -43,7 +43,8 @@ MergeFromPrivateRoadModule::MergeFromPrivateRoadModule( const PlannerParam & planner_param, const std::set & associative_ids, const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface) + const std::shared_ptr + planning_factor_interface) : SceneModuleInterface(module_id, logger, clock, time_keeper, planning_factor_interface), lane_id_(lane_id), associative_ids_(associative_ids) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp index fe446d304d9e0..4b9c0a9c5547e 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp @@ -63,7 +63,8 @@ class MergeFromPrivateRoadModule : public SceneModuleInterface const PlannerParam & planner_param, const std::set & associative_ids, const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface); + const std::shared_ptr + planning_factor_interface); /** * @brief plan go-stop velocity at traffic crossing with collision check between reference path diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp index 0e646e92035cf..bbca1bf2d6481 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp @@ -31,7 +31,8 @@ NoDrivableLaneModule::NoDrivableLaneModule( const int64_t module_id, const int64_t lane_id, const PlannerParam & planner_param, const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface) + const std::shared_ptr + planning_factor_interface) : SceneModuleInterface(module_id, logger, clock, time_keeper, planning_factor_interface), lane_id_(lane_id), planner_param_(planner_param), diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.hpp index 835e946443e90..5490a37c7ec79 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.hpp @@ -57,7 +57,8 @@ class NoDrivableLaneModule : public SceneModuleInterface const int64_t module_id, const int64_t lane_id, const PlannerParam & planner_param, const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface); + const std::shared_ptr + planning_factor_interface); bool modifyPathVelocity(PathWithLaneId * path) override; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp index c788a54073ed6..14f4f7b62c1f7 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp @@ -43,7 +43,8 @@ NoStoppingAreaModule::NoStoppingAreaModule( const PlannerParam & planner_param, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface) + const std::shared_ptr + planning_factor_interface) : SceneModuleInterfaceWithRTC(module_id, logger, clock, time_keeper, planning_factor_interface), lane_id_(lane_id), no_stopping_area_reg_elem_(no_stopping_area_reg_elem), diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.hpp index 0d53441924805..036b6e30509c4 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.hpp @@ -59,7 +59,8 @@ class NoStoppingAreaModule : public SceneModuleInterfaceWithRTC const PlannerParam & planner_param, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface); + const std::shared_ptr + planning_factor_interface); bool modifyPathVelocity(PathWithLaneId * path) override; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp index fa259b2bea9aa..935b1ec125024 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp @@ -66,7 +66,8 @@ OcclusionSpotModule::OcclusionSpotModule( const PlannerParam & planner_param, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface) + const std::shared_ptr + planning_factor_interface) : SceneModuleInterface(module_id, logger, clock, time_keeper, planning_factor_interface), param_(planner_param) { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp index 22b2a91be66b0..c744cdcb22b84 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp @@ -50,7 +50,8 @@ class OcclusionSpotModule : public SceneModuleInterface const PlannerParam & planner_param, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface); + const std::shared_ptr + planning_factor_interface); /** * @brief plan occlusion spot velocity at unknown area in occupancy grid diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp index 5bff3ca343e72..743fd0e31e387 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp @@ -17,10 +17,10 @@ #include #include -#include #include #include #include +#include #include #include #include @@ -77,7 +77,8 @@ class SceneModuleInterface explicit SceneModuleInterface( const int64_t module_id, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface); + const std::shared_ptr + planning_factor_interface); virtual ~SceneModuleInterface() = default; virtual bool modifyPathVelocity(PathWithLaneId * path) = 0; @@ -102,7 +103,7 @@ class SceneModuleInterface std::shared_ptr planner_data_; std::vector objects_of_interest_; mutable std::shared_ptr time_keeper_; - std::shared_ptr planning_factor_interface_; + std::shared_ptr planning_factor_interface_; void setObjectsOfInterestData( const geometry_msgs::msg::Pose & pose, const autoware_perception_msgs::msg::Shape & shape, @@ -136,7 +137,7 @@ class SceneModuleManagerInterface pub_virtual_wall_ = node.create_publisher( std::string("~/virtual_wall/") + module_name, 5); planning_factor_interface_ = - std::make_shared(&node, module_name); + std::make_shared(&node, module_name); processing_time_publisher_ = std::make_shared(&node, "~/debug"); @@ -261,7 +262,7 @@ class SceneModuleManagerInterface std::shared_ptr time_keeper_; - std::shared_ptr planning_factor_interface_; + std::shared_ptr planning_factor_interface_; }; extern template SceneModuleManagerInterface::SceneModuleManagerInterface( rclcpp::Node & node, [[maybe_unused]] const char * module_name); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml index 9f920dff8f166..bf2a9dfc5e32e 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml @@ -27,6 +27,7 @@ autoware_motion_utils autoware_objects_of_interest_marker_interface autoware_perception_msgs + autoware_planning_factor_interface autoware_planning_msgs autoware_route_handler autoware_universe_utils diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp index db2a274272f9f..1849c05085ac4 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp @@ -27,7 +27,8 @@ namespace autoware::behavior_velocity_planner SceneModuleInterface::SceneModuleInterface( const int64_t module_id, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface) + const std::shared_ptr + planning_factor_interface) : module_id_(module_id), logger_(logger), clock_(clock), diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp index a955538f4f9fe..0cf1e343fb646 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp @@ -54,7 +54,8 @@ class SceneModuleInterfaceWithRTC : public SceneModuleInterface explicit SceneModuleInterfaceWithRTC( const int64_t module_id, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface); + const std::shared_ptr + planning_factor_interface); virtual ~SceneModuleInterfaceWithRTC() = default; void setActivation(const bool activated) { activated_ = activated; } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/package.xml index 88b252106a90a..3c2a229cca95a 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/package.xml @@ -21,6 +21,7 @@ autoware_behavior_velocity_planner_common autoware_motion_utils + autoware_planning_factor_interface autoware_planning_msgs autoware_rtc_interface autoware_universe_utils diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/src/scene_module_interface_with_rtc.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/src/scene_module_interface_with_rtc.cpp index 2e73b35e20ed9..34c7a30e73acf 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/src/scene_module_interface_with_rtc.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/src/scene_module_interface_with_rtc.cpp @@ -29,7 +29,8 @@ namespace autoware::behavior_velocity_planner SceneModuleInterfaceWithRTC::SceneModuleInterfaceWithRTC( const int64_t module_id, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface) + const std::shared_ptr + planning_factor_interface) : SceneModuleInterface(module_id, logger, clock, time_keeper, planning_factor_interface), activated_(false), safe_(false), diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp index 193ba5eab0553..a300e8f5f9284 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp @@ -47,7 +47,8 @@ RunOutModule::RunOutModule( std::unique_ptr dynamic_obstacle_creator, const std::shared_ptr & debug_ptr, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface) + const std::shared_ptr + planning_factor_interface) : SceneModuleInterface(module_id, logger, clock, time_keeper, planning_factor_interface), planner_param_(planner_param), dynamic_obstacle_creator_(std::move(dynamic_obstacle_creator)), diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.hpp index 49de16753a869..1879d724f98b3 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.hpp @@ -49,7 +49,8 @@ class RunOutModule : public SceneModuleInterface std::unique_ptr dynamic_obstacle_creator, const std::shared_ptr & debug_ptr, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface); + const std::shared_ptr + planning_factor_interface); bool modifyPathVelocity(PathWithLaneId * path) override; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/scene.cpp index 4af7801e50ba3..a5099eedce027 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/scene.cpp @@ -36,7 +36,8 @@ SpeedBumpModule::SpeedBumpModule( const lanelet::autoware::SpeedBump & speed_bump_reg_elem, const PlannerParam & planner_param, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface) + const std::shared_ptr + planning_factor_interface) : SceneModuleInterface(module_id, logger, clock, time_keeper, planning_factor_interface), module_id_(module_id), lane_id_(lane_id), diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/scene.hpp index e3ee2c0566381..5b908f90bf9c2 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/scene.hpp @@ -57,7 +57,8 @@ class SpeedBumpModule : public SceneModuleInterface const lanelet::autoware::SpeedBump & speed_bump_reg_elem, const PlannerParam & planner_param, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface); + const std::shared_ptr + planning_factor_interface); bool modifyPathVelocity(PathWithLaneId * path) override; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp index e2ddbc75c7b57..2115a0a7eca6e 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp @@ -31,7 +31,8 @@ StopLineModule::StopLineModule( const int64_t module_id, lanelet::ConstLineString3d stop_line, const PlannerParam & planner_param, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface) + const std::shared_ptr + planning_factor_interface) : SceneModuleInterface(module_id, logger, clock, time_keeper, planning_factor_interface), stop_line_(std::move(stop_line)), planner_param_(planner_param), diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.hpp index 7d430463c18b9..d2c999a377ab4 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.hpp @@ -70,7 +70,8 @@ class StopLineModule : public SceneModuleInterface const PlannerParam & planner_param, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface); + const std::shared_ptr + planning_factor_interface); bool modifyPathVelocity(PathWithLaneId * path) override; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/test/test_scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/test/test_scene.cpp index e304b479a005d..2b176a64c597d 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/test/test_scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/test/test_scene.cpp @@ -76,7 +76,7 @@ class StopLineModuleTest : public ::testing::Test module_ = std::make_shared( 1, stop_line_, planner_param_, rclcpp::get_logger("test_logger"), clock_, std::make_shared(), - std::make_shared( + std::make_shared( node_.get(), "test_stopline")); module_->setPlannerData(planner_data_); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.cpp index d8eea337e7186..7dc8ca9b2e43b 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.cpp @@ -28,7 +28,8 @@ namespace autoware::behavior_velocity_planner TemplateModule::TemplateModule( const int64_t module_id, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface) + const std::shared_ptr + planning_factor_interface) : SceneModuleInterface(module_id, logger, clock, time_keeper, planning_factor_interface) { } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.hpp index ba078f3fd6421..d204e589f0416 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.hpp @@ -31,7 +31,8 @@ class TemplateModule : public SceneModuleInterface TemplateModule( const int64_t module_id, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface); + const std::shared_ptr + planning_factor_interface); /** * @brief Modify the velocity of path points. diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp index becbaf5ee05f2..3a8692e9c53dd 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp @@ -45,7 +45,8 @@ TrafficLightModule::TrafficLightModule( lanelet::ConstLanelet lane, const PlannerParam & planner_param, const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface) + const std::shared_ptr + planning_factor_interface) : SceneModuleInterfaceWithRTC(lane_id, logger, clock, time_keeper, planning_factor_interface), lane_id_(lane_id), traffic_light_reg_elem_(traffic_light_reg_elem), diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.hpp index c30cbbdfc1477..71f0855a4af6f 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.hpp @@ -71,7 +71,8 @@ class TrafficLightModule : public SceneModuleInterfaceWithRTC lanelet::ConstLanelet lane, const PlannerParam & planner_param, const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface); + const std::shared_ptr + planning_factor_interface); bool modifyPathVelocity(PathWithLaneId * path) override; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp index a5779cfc0712a..a42e3520ea3c1 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp @@ -41,7 +41,8 @@ VirtualTrafficLightModule::VirtualTrafficLightModule( const PlannerParam & planner_param, const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface) + const std::shared_ptr + planning_factor_interface) : SceneModuleInterface(module_id, logger, clock, time_keeper, planning_factor_interface), lane_id_(lane_id), reg_elem_(reg_elem), diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp index 0661267b3d361..24e77cfaea157 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp @@ -84,7 +84,8 @@ class VirtualTrafficLightModule : public SceneModuleInterface const PlannerParam & planner_param, const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface); + const std::shared_ptr + planning_factor_interface); bool modifyPathVelocity(PathWithLaneId * path) override; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.cpp index 94421ae27e077..91ed11a7467d5 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.cpp @@ -35,7 +35,8 @@ WalkwayModule::WalkwayModule( const PlannerParam & planner_param, const bool use_regulatory_element, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface) + const std::shared_ptr + planning_factor_interface) : SceneModuleInterface(module_id, logger, clock, time_keeper, planning_factor_interface), module_id_(module_id), state_(State::APPROACH), diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.hpp index 1bd5003498d34..3e06bf2d878c6 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.hpp @@ -46,7 +46,8 @@ class WalkwayModule : public SceneModuleInterface const PlannerParam & planner_param, const bool use_regulatory_element, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock, const std::shared_ptr time_keeper, - const std::shared_ptr planning_factor_interface); + const std::shared_ptr + planning_factor_interface); bool modifyPathVelocity(PathWithLaneId * path) override; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp index 2000615b51e2c..c7a103e0269ca 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp @@ -44,8 +44,9 @@ void DynamicObstacleStopModule::init(rclcpp::Node & node, const std::string & mo logger_ = node.get_logger().get_child(ns_); clock_ = node.get_clock(); - planning_factor_interface_ = std::make_unique( - &node, "dynamic_obstacle_stop"); + planning_factor_interface_ = + std::make_unique( + &node, "dynamic_obstacle_stop"); debug_publisher_ = node.create_publisher("~/" + ns_ + "/debug_markers", 1); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp index 532cc1e8c7d51..ab69218ea9668 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp @@ -60,7 +60,8 @@ void OutOfLaneModule::init(rclcpp::Node & node, const std::string & module_name) init_parameters(node); planning_factor_interface_ = - std::make_unique(&node, "out_of_lane"); + std::make_unique( + &node, "out_of_lane"); debug_publisher_ = node.create_publisher("~/" + ns_ + "/debug_markers", 1); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp index 6d683acff667f..c650e324de16a 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp @@ -18,7 +18,7 @@ #include "planner_data.hpp" #include "velocity_planning_result.hpp" -#include +#include #include #include @@ -55,7 +55,8 @@ class PluginModuleInterface autoware::motion_utils::VirtualWallMarkerCreator virtual_wall_marker_creator{}; protected: - std::unique_ptr planning_factor_interface_; + std::unique_ptr + planning_factor_interface_; }; } // namespace autoware::motion_velocity_planner diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml index 07b719689f51f..5f4c15e0f8ab9 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml @@ -23,6 +23,7 @@ autoware_motion_utils autoware_motion_velocity_planner_common autoware_perception_msgs + autoware_planning_factor_interface autoware_planning_msgs autoware_universe_utils autoware_velocity_smoother From 62fa8ce18643ba44caaf5016fc4f4ff1e8365cd7 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Fri, 17 Jan 2025 17:16:01 +0900 Subject: [PATCH 241/334] feat(autoware_planning_validator)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_planning_validator (#9911) feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files planning/autoware_planning_validator Signed-off-by: vish0012 --- .../autoware/planning_validator/planning_validator.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/autoware_planning_validator/include/autoware/planning_validator/planning_validator.hpp b/planning/autoware_planning_validator/include/autoware/planning_validator/planning_validator.hpp index e996855b9b4da..298e7f74c289b 100644 --- a/planning/autoware_planning_validator/include/autoware/planning_validator/planning_validator.hpp +++ b/planning/autoware_planning_validator/include/autoware/planning_validator/planning_validator.hpp @@ -26,10 +26,10 @@ #include #include +#include #include #include #include -#include #include #include @@ -37,13 +37,13 @@ namespace autoware::planning_validator { using autoware::universe_utils::StopWatch; +using autoware_internal_debug_msgs::msg::Float64Stamped; using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; using autoware_planning_validator::msg::PlanningValidatorStatus; using diagnostic_updater::DiagnosticStatusWrapper; using diagnostic_updater::Updater; using nav_msgs::msg::Odometry; -using tier4_debug_msgs::msg::Float64Stamped; struct ValidationParams { From c926e46aaefbb37c1738cd7b20269a8e4dd602b8 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Fri, 17 Jan 2025 17:16:57 +0900 Subject: [PATCH 242/334] =?UTF-8?q?feat:=20tier4=5Fdebug=5Fmsgs=20changed?= =?UTF-8?q?=20to=20autoware=5Finternal=5Fdebug=5Fmsgs=20in=20fil=E2=80=A6?= =?UTF-8?q?=20(#9904)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files planning/autoware_mission_planner Signed-off-by: vish0012 --- .../src/mission_planner/mission_planner.cpp | 6 +++--- .../src/mission_planner/mission_planner.hpp | 5 +++-- .../src/mission_planner/route_selector.cpp | 6 +++--- .../src/mission_planner/route_selector.hpp | 5 +++-- 4 files changed, 12 insertions(+), 10 deletions(-) diff --git a/planning/autoware_mission_planner/src/mission_planner/mission_planner.cpp b/planning/autoware_mission_planner/src/mission_planner/mission_planner.cpp index cbbcfb84d2cbb..b806feded9802 100644 --- a/planning/autoware_mission_planner/src/mission_planner/mission_planner.cpp +++ b/planning/autoware_mission_planner/src/mission_planner/mission_planner.cpp @@ -87,14 +87,14 @@ MissionPlanner::MissionPlanner(const rclcpp::NodeOptions & options) is_mission_planner_ready_ = false; logger_configure_ = std::make_unique(this); - pub_processing_time_ = - this->create_publisher("~/debug/processing_time_ms", 1); + pub_processing_time_ = this->create_publisher( + "~/debug/processing_time_ms", 1); } void MissionPlanner::publish_processing_time( autoware::universe_utils::StopWatch stop_watch) { - tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg; processing_time_msg.stamp = get_clock()->now(); processing_time_msg.data = stop_watch.toc(); pub_processing_time_->publish(processing_time_msg); diff --git a/planning/autoware_mission_planner/src/mission_planner/mission_planner.hpp b/planning/autoware_mission_planner/src/mission_planner/mission_planner.hpp index 987ca6482ec11..18f0d3a9c259d 100644 --- a/planning/autoware_mission_planner/src/mission_planner/mission_planner.hpp +++ b/planning/autoware_mission_planner/src/mission_planner/mission_planner.hpp @@ -28,9 +28,9 @@ #include #include #include +#include #include #include -#include #include #include #include @@ -146,7 +146,8 @@ class MissionPlanner : public rclcpp::Node bool check_reroute_safety(const LaneletRoute & original_route, const LaneletRoute & target_route); std::unique_ptr logger_configure_; - rclcpp::Publisher::SharedPtr pub_processing_time_; + rclcpp::Publisher::SharedPtr + pub_processing_time_; }; } // namespace autoware::mission_planner diff --git a/planning/autoware_mission_planner/src/mission_planner/route_selector.cpp b/planning/autoware_mission_planner/src/mission_planner/route_selector.cpp index 5ee565af00423..ad7daba18dece 100644 --- a/planning/autoware_mission_planner/src/mission_planner/route_selector.cpp +++ b/planning/autoware_mission_planner/src/mission_planner/route_selector.cpp @@ -138,14 +138,14 @@ RouteSelector::RouteSelector(const rclcpp::NodeOptions & options) main_request_ = std::monostate{}; // Processing time - pub_processing_time_ = - this->create_publisher("~/debug/processing_time_ms", 1); + pub_processing_time_ = this->create_publisher( + "~/debug/processing_time_ms", 1); } void RouteSelector::publish_processing_time( autoware::universe_utils::StopWatch stop_watch) { - tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg; processing_time_msg.stamp = get_clock()->now(); processing_time_msg.data = stop_watch.toc(); pub_processing_time_->publish(processing_time_msg); diff --git a/planning/autoware_mission_planner/src/mission_planner/route_selector.hpp b/planning/autoware_mission_planner/src/mission_planner/route_selector.hpp index 5c8f81aaf216e..3e52f6962c47e 100644 --- a/planning/autoware_mission_planner/src/mission_planner/route_selector.hpp +++ b/planning/autoware_mission_planner/src/mission_planner/route_selector.hpp @@ -18,8 +18,8 @@ #include #include +#include #include -#include #include #include #include @@ -82,7 +82,8 @@ class RouteSelector : public rclcpp::Node rclcpp::Client::SharedPtr cli_set_lanelet_route_; rclcpp::Subscription::SharedPtr sub_state_; rclcpp::Subscription::SharedPtr sub_route_; - rclcpp::Publisher::SharedPtr pub_processing_time_; + rclcpp::Publisher::SharedPtr + pub_processing_time_; bool initialized_; bool mrm_operating_; From b466796bbe9464e191f31e1e3a885f7025fad11f Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Fri, 17 Jan 2025 17:17:26 +0900 Subject: [PATCH 243/334] =?UTF-8?q?feat:=20tier4=5Fdebug=5Fmsgs=20changed?= =?UTF-8?q?=20to=20autoware=5Finternal=5Fdebug=5Fmsgs=20in=20fil=E2=80=A6?= =?UTF-8?q?=20(#9902)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files planning/autoware_external_velocity_limit_selector Signed-off-by: vish0012 --- .../external_velocity_limit_selector_node.hpp | 4 ++-- .../autoware_external_velocity_limit_selector/package.xml | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/planning/autoware_external_velocity_limit_selector/include/autoware/external_velocity_limit_selector/external_velocity_limit_selector_node.hpp b/planning/autoware_external_velocity_limit_selector/include/autoware/external_velocity_limit_selector/external_velocity_limit_selector_node.hpp index 6a8fae3bf394c..be4893d5a49c6 100644 --- a/planning/autoware_external_velocity_limit_selector/include/autoware/external_velocity_limit_selector/external_velocity_limit_selector_node.hpp +++ b/planning/autoware_external_velocity_limit_selector/include/autoware/external_velocity_limit_selector/external_velocity_limit_selector_node.hpp @@ -18,7 +18,7 @@ #include #include -#include +#include #include #include @@ -29,7 +29,7 @@ namespace autoware::external_velocity_limit_selector { -using tier4_debug_msgs::msg::StringStamped; +using autoware_internal_debug_msgs::msg::StringStamped; using tier4_planning_msgs::msg::VelocityLimit; using tier4_planning_msgs::msg::VelocityLimitClearCommand; using tier4_planning_msgs::msg::VelocityLimitConstraints; diff --git a/planning/autoware_external_velocity_limit_selector/package.xml b/planning/autoware_external_velocity_limit_selector/package.xml index 5bfd3fa936d50..4a4fac40bd8a5 100644 --- a/planning/autoware_external_velocity_limit_selector/package.xml +++ b/planning/autoware_external_velocity_limit_selector/package.xml @@ -17,10 +17,10 @@ ament_cmake_auto autoware_cmake + autoware_internal_debug_msgs generate_parameter_library rclcpp rclcpp_components - tier4_debug_msgs tier4_planning_msgs ros2cli From f9c0aa69cba891f88d7b9afdf5e9d7cd89c0bd17 Mon Sep 17 00:00:00 2001 From: interimadd Date: Fri, 17 Jan 2025 17:35:29 +0900 Subject: [PATCH 244/334] fix(imu_corrector): remove non-periodic publish to /diagnostics topic (#9951) fix(imu_corrector): remove force_update() in timer callback Signed-off-by: Takahisa.Ishikawa Co-authored-by: Takahisa.Ishikawa --- sensing/autoware_imu_corrector/src/gyro_bias_estimator.cpp | 3 --- 1 file changed, 3 deletions(-) diff --git a/sensing/autoware_imu_corrector/src/gyro_bias_estimator.cpp b/sensing/autoware_imu_corrector/src/gyro_bias_estimator.cpp index 8dcc024ffc2b4..17194ac1b0459 100644 --- a/sensing/autoware_imu_corrector/src/gyro_bias_estimator.cpp +++ b/sensing/autoware_imu_corrector/src/gyro_bias_estimator.cpp @@ -40,7 +40,6 @@ GyroBiasEstimator::GyroBiasEstimator(const rclcpp::NodeOptions & options) { updater_.setHardwareID(get_name()); updater_.add("gyro_bias_validator", this, &GyroBiasEstimator::update_diagnostics); - // diagnostic_updater is designed to be updated at the same rate as the timer updater_.setPeriod(diagnostics_updater_interval_sec_); gyro_bias_estimation_module_ = std::make_unique(); @@ -182,8 +181,6 @@ void GyroBiasEstimator::timer_callback() transform_vector3(gyro_bias_estimation_module_->get_bias_base_link(), *tf_base2imu_ptr); validate_gyro_bias(); - updater_.force_update(); - updater_.setPeriod(diagnostics_updater_interval_sec_); // to reset timer inside the updater } void GyroBiasEstimator::validate_gyro_bias() From 18da07da01719ad948b5131c79e730aa36a7bae2 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Fri, 17 Jan 2025 21:23:09 +0900 Subject: [PATCH 245/334] feat(autoware_processing_time_checker)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_processing_time_checker (#9921) Signed-off-by: vish0012 Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> --- system/autoware_processing_time_checker/README.md | 6 +++--- system/autoware_processing_time_checker/package.xml | 2 +- .../src/processing_time_checker.hpp | 4 ++-- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/system/autoware_processing_time_checker/README.md b/system/autoware_processing_time_checker/README.md index 1cb6a289bc54f..e7d70f9378f10 100644 --- a/system/autoware_processing_time_checker/README.md +++ b/system/autoware_processing_time_checker/README.md @@ -17,9 +17,9 @@ ros2 launch autoware_processing_time_checker processing_time_checker.launch.xml ### Input -| Name | Type | Description | -| ------------------------- | --------------------------------- | ------------------------------ | -| `/.../processing_time_ms` | `tier4_debug_msgs/Float64Stamped` | processing time of each module | +| Name | Type | Description | +| ------------------------- | --------------------------------------------- | ------------------------------ | +| `/.../processing_time_ms` | `autoware_internal_debug_msgs/Float64Stamped` | processing time of each module | ### Output diff --git a/system/autoware_processing_time_checker/package.xml b/system/autoware_processing_time_checker/package.xml index 4a18857663cc1..37f53c94de0d1 100644 --- a/system/autoware_processing_time_checker/package.xml +++ b/system/autoware_processing_time_checker/package.xml @@ -12,11 +12,11 @@ ament_cmake autoware_cmake + autoware_internal_debug_msgs autoware_universe_utils nlohmann-json-dev rclcpp rclcpp_components - tier4_debug_msgs tier4_metric_msgs ament_lint_auto diff --git a/system/autoware_processing_time_checker/src/processing_time_checker.hpp b/system/autoware_processing_time_checker/src/processing_time_checker.hpp index 77450923509f2..f6664b901f890 100644 --- a/system/autoware_processing_time_checker/src/processing_time_checker.hpp +++ b/system/autoware_processing_time_checker/src/processing_time_checker.hpp @@ -19,7 +19,7 @@ #include -#include +#include #include #include @@ -32,7 +32,7 @@ namespace autoware::processing_time_checker using autoware::universe_utils::Accumulator; using MetricMsg = tier4_metric_msgs::msg::Metric; using MetricArrayMsg = tier4_metric_msgs::msg::MetricArray; -using tier4_debug_msgs::msg::Float64Stamped; +using autoware_internal_debug_msgs::msg::Float64Stamped; class ProcessingTimeChecker : public rclcpp::Node { From b92eb33c95b91fad1883c337b215f0dc002645eb Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Fri, 17 Jan 2025 21:25:28 +0900 Subject: [PATCH 246/334] feat(autoware_steer_offset_estimator)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_steer_offset_estimator (#9926) feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files vehicle/autoware_steer_offset_estimator Signed-off-by: vish0012 Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> --- vehicle/autoware_steer_offset_estimator/Readme.md | 8 ++++---- .../steer_offset_estimator_node.hpp | 4 ++-- vehicle/autoware_steer_offset_estimator/package.xml | 2 +- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/vehicle/autoware_steer_offset_estimator/Readme.md b/vehicle/autoware_steer_offset_estimator/Readme.md index 2cd6bd2aabe2a..a7e9b6722a648 100644 --- a/vehicle/autoware_steer_offset_estimator/Readme.md +++ b/vehicle/autoware_steer_offset_estimator/Readme.md @@ -24,10 +24,10 @@ Calculate yaw rate error and then calculate steering error recursively by least ### Output -| Name | Type | Description | -| ------------------------------------- | --------------------------------------- | ----------------------------- | -| `~/output/steering_offset` | `tier4_debug_msgs::msg::Float32Stamped` | steering offset | -| `~/output/steering_offset_covariance` | `tier4_debug_msgs::msg::Float32Stamped` | covariance of steering offset | +| Name | Type | Description | +| ------------------------------------- | --------------------------------------------------- | ----------------------------- | +| `~/output/steering_offset` | `autoware_internal_debug_msgs::msg::Float32Stamped` | steering offset | +| `~/output/steering_offset_covariance` | `autoware_internal_debug_msgs::msg::Float32Stamped` | covariance of steering offset | ## Launch Calibrator diff --git a/vehicle/autoware_steer_offset_estimator/include/autoware_steer_offset_estimator/steer_offset_estimator_node.hpp b/vehicle/autoware_steer_offset_estimator/include/autoware_steer_offset_estimator/steer_offset_estimator_node.hpp index 4e03cbe0162fe..0d7896d53a705 100644 --- a/vehicle/autoware_steer_offset_estimator/include/autoware_steer_offset_estimator/steer_offset_estimator_node.hpp +++ b/vehicle/autoware_steer_offset_estimator/include/autoware_steer_offset_estimator/steer_offset_estimator_node.hpp @@ -18,16 +18,16 @@ #include "diagnostic_updater/diagnostic_updater.hpp" #include "rclcpp/rclcpp.hpp" +#include "autoware_internal_debug_msgs/msg/float32_stamped.hpp" #include "autoware_vehicle_msgs/msg/steering_report.hpp" #include "geometry_msgs/msg/twist_stamped.hpp" -#include "tier4_debug_msgs/msg/float32_stamped.hpp" #include namespace autoware::steer_offset_estimator { +using autoware_internal_debug_msgs::msg::Float32Stamped; using geometry_msgs::msg::TwistStamped; -using tier4_debug_msgs::msg::Float32Stamped; using Steering = autoware_vehicle_msgs::msg::SteeringReport; using diagnostic_updater::DiagnosticStatusWrapper; using diagnostic_updater::Updater; diff --git a/vehicle/autoware_steer_offset_estimator/package.xml b/vehicle/autoware_steer_offset_estimator/package.xml index 715d80504dafe..e098fbdee6f28 100644 --- a/vehicle/autoware_steer_offset_estimator/package.xml +++ b/vehicle/autoware_steer_offset_estimator/package.xml @@ -9,6 +9,7 @@ ament_cmake_auto autoware_cmake + autoware_internal_debug_msgs autoware_universe_utils autoware_vehicle_info_utils autoware_vehicle_msgs @@ -17,7 +18,6 @@ rclcpp rclcpp_components std_msgs - tier4_debug_msgs autoware_global_parameter_loader autoware_pose2twist From e3e7fdb72b21f490e19152b97e12fe3cfcd4a1f0 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Fri, 17 Jan 2025 21:30:41 +0900 Subject: [PATCH 247/334] feat(autoware_accel_brake_map_calibrator)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_accel_brake_map_calibrator (#9923) Signed-off-by: vish0012 Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> --- .../accel_brake_map_calibrator_node.hpp | 8 ++++---- vehicle/autoware_accel_brake_map_calibrator/package.xml | 2 +- .../scripts/accel_tester.py | 2 +- .../scripts/actuation_cmd_publisher.py | 2 +- .../scripts/brake_tester.py | 2 +- 5 files changed, 8 insertions(+), 8 deletions(-) diff --git a/vehicle/autoware_accel_brake_map_calibrator/include/autoware_accel_brake_map_calibrator/accel_brake_map_calibrator_node.hpp b/vehicle/autoware_accel_brake_map_calibrator/include/autoware_accel_brake_map_calibrator/accel_brake_map_calibrator_node.hpp index 2a0ad4f987dad..cd05bed5ce476 100644 --- a/vehicle/autoware_accel_brake_map_calibrator/include/autoware_accel_brake_map_calibrator/accel_brake_map_calibrator_node.hpp +++ b/vehicle/autoware_accel_brake_map_calibrator/include/autoware_accel_brake_map_calibrator/accel_brake_map_calibrator_node.hpp @@ -28,6 +28,8 @@ #include +#include "autoware_internal_debug_msgs/msg/float32_multi_array_stamped.hpp" +#include "autoware_internal_debug_msgs/msg/float32_stamped.hpp" #include "autoware_vehicle_msgs/msg/steering_report.hpp" #include "autoware_vehicle_msgs/msg/velocity_report.hpp" #include "geometry_msgs/msg/twist_stamped.hpp" @@ -37,8 +39,6 @@ #include "std_msgs/msg/multi_array_dimension.hpp" #include "std_msgs/msg/string.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" -#include "tier4_debug_msgs/msg/float32_multi_array_stamped.hpp" -#include "tier4_debug_msgs/msg/float32_stamped.hpp" #include "tier4_external_api_msgs/msg/calibration_status.hpp" #include "tier4_external_api_msgs/msg/calibration_status_array.hpp" #include "tier4_external_api_msgs/srv/get_accel_brake_map_calibration_data.hpp" @@ -57,6 +57,8 @@ namespace autoware::accel_brake_map_calibrator { +using autoware_internal_debug_msgs::msg::Float32MultiArrayStamped; +using autoware_internal_debug_msgs::msg::Float32Stamped; using autoware_vehicle_msgs::msg::SteeringReport; using autoware_vehicle_msgs::msg::VelocityReport; using geometry_msgs::msg::TwistStamped; @@ -64,8 +66,6 @@ using nav_msgs::msg::OccupancyGrid; using raw_vehicle_cmd_converter::AccelMap; using raw_vehicle_cmd_converter::BrakeMap; using std_msgs::msg::Float32MultiArray; -using tier4_debug_msgs::msg::Float32MultiArrayStamped; -using tier4_debug_msgs::msg::Float32Stamped; using tier4_external_api_msgs::msg::CalibrationStatus; using tier4_vehicle_msgs::msg::ActuationCommandStamped; using tier4_vehicle_msgs::msg::ActuationStatusStamped; diff --git a/vehicle/autoware_accel_brake_map_calibrator/package.xml b/vehicle/autoware_accel_brake_map_calibrator/package.xml index de2dcf2d8e440..f166bd119ed6a 100644 --- a/vehicle/autoware_accel_brake_map_calibrator/package.xml +++ b/vehicle/autoware_accel_brake_map_calibrator/package.xml @@ -14,6 +14,7 @@ ament_cmake_auto autoware_cmake + autoware_internal_debug_msgs autoware_motion_utils autoware_raw_vehicle_cmd_converter autoware_universe_utils @@ -25,7 +26,6 @@ std_srvs tf2_geometry_msgs tf2_ros - tier4_debug_msgs tier4_external_api_msgs tier4_vehicle_msgs visualization_msgs diff --git a/vehicle/autoware_accel_brake_map_calibrator/scripts/accel_tester.py b/vehicle/autoware_accel_brake_map_calibrator/scripts/accel_tester.py index f73718f7ea7bc..8aef30f9ee251 100755 --- a/vehicle/autoware_accel_brake_map_calibrator/scripts/accel_tester.py +++ b/vehicle/autoware_accel_brake_map_calibrator/scripts/accel_tester.py @@ -15,9 +15,9 @@ # See the License for the specific language governing permissions and # limitations under the License. +from autoware_internal_debug_msgs.msg import Float32Stamped import rclpy from rclpy.node import Node -from tier4_debug_msgs.msg import Float32Stamped MAX_ACCEL = 1.0 # [-] MIN_ACCEL = 0.0 # [-] diff --git a/vehicle/autoware_accel_brake_map_calibrator/scripts/actuation_cmd_publisher.py b/vehicle/autoware_accel_brake_map_calibrator/scripts/actuation_cmd_publisher.py index 3a029e193f41f..334b5652dc8b6 100755 --- a/vehicle/autoware_accel_brake_map_calibrator/scripts/actuation_cmd_publisher.py +++ b/vehicle/autoware_accel_brake_map_calibrator/scripts/actuation_cmd_publisher.py @@ -15,10 +15,10 @@ # See the License for the specific language governing permissions and # limitations under the License. +from autoware_internal_debug_msgs.msg import Float32Stamped from autoware_vehicle_msgs.msg import GearCommand import rclpy from rclpy.node import Node -from tier4_debug_msgs.msg import Float32Stamped from tier4_vehicle_msgs.msg import ActuationCommandStamped diff --git a/vehicle/autoware_accel_brake_map_calibrator/scripts/brake_tester.py b/vehicle/autoware_accel_brake_map_calibrator/scripts/brake_tester.py index 050f232334afd..fe067494a0c39 100755 --- a/vehicle/autoware_accel_brake_map_calibrator/scripts/brake_tester.py +++ b/vehicle/autoware_accel_brake_map_calibrator/scripts/brake_tester.py @@ -16,9 +16,9 @@ # limitations under the License. +from autoware_internal_debug_msgs.msg import Float32Stamped import rclpy from rclpy.node import Node -from tier4_debug_msgs.msg import Float32Stamped MAX_BRAKE = 1.0 # [-] MIN_BRAKE = 0.0 # [-] From fc763acd1f1cdcda1358976a963da5f367e61bb6 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Fri, 17 Jan 2025 21:32:20 +0900 Subject: [PATCH 248/334] feat(autoware_raw_vehicle_cmd_converter)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_raw_vehicle_cmd_converter (#9924) feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files vehicle/autoware_raw_vehicle_cmd_converter Signed-off-by: vish0012 Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> --- .../include/autoware_raw_vehicle_cmd_converter/node.hpp | 4 ++-- vehicle/autoware_raw_vehicle_cmd_converter/package.xml | 2 +- vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/node.hpp b/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/node.hpp index 8f8e543dc680e..eaf39cf729971 100644 --- a/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/node.hpp +++ b/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/node.hpp @@ -28,10 +28,10 @@ #include #include +#include #include #include #include -#include #include #include @@ -42,7 +42,7 @@ namespace autoware::raw_vehicle_cmd_converter { using Control = autoware_control_msgs::msg::Control; -using tier4_debug_msgs::msg::Float32MultiArrayStamped; +using autoware_internal_debug_msgs::msg::Float32MultiArrayStamped; using tier4_vehicle_msgs::msg::ActuationCommandStamped; using tier4_vehicle_msgs::msg::ActuationStatusStamped; using TwistStamped = geometry_msgs::msg::TwistStamped; diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/package.xml b/vehicle/autoware_raw_vehicle_cmd_converter/package.xml index ff00f09a7efd8..0abb77644920a 100644 --- a/vehicle/autoware_raw_vehicle_cmd_converter/package.xml +++ b/vehicle/autoware_raw_vehicle_cmd_converter/package.xml @@ -23,13 +23,13 @@ autoware_adapi_v1_msgs autoware_control_msgs + autoware_internal_debug_msgs autoware_interpolation autoware_vehicle_msgs geometry_msgs nav_msgs rclcpp rclcpp_components - tier4_debug_msgs tier4_vehicle_msgs rclpy diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp b/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp index 7624705b15b37..8d05e4faa69ad 100644 --- a/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp +++ b/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp @@ -245,7 +245,7 @@ double RawVehicleCommandConverterNode::calculateSteerFromMap( debug_steer_.setValues(DebugValues::TYPE::ERROR_P, pid_errors.at(0)); debug_steer_.setValues(DebugValues::TYPE::ERROR_I, pid_errors.at(1)); debug_steer_.setValues(DebugValues::TYPE::ERROR_D, pid_errors.at(2)); - tier4_debug_msgs::msg::Float32MultiArrayStamped msg{}; + autoware_internal_debug_msgs::msg::Float32MultiArrayStamped msg{}; for (const auto & v : debug_steer_.getValues()) { msg.data.push_back(v); } From 64e4e21512ec6538532cac3d2417fd94d2467416 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Fri, 17 Jan 2025 21:48:00 +0900 Subject: [PATCH 249/334] =?UTF-8?q?feat:=20tier4=5Fdebug=5Fmsgs=20changed?= =?UTF-8?q?=20to=20autoware=5Finternal=5Fdebug=5Fmsgs=20in=20fil=E2=80=A6?= =?UTF-8?q?=20(#9896)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files perception/autoware_raindrop_cluster_filter Signed-off-by: vish0012 --- .../src/low_intensity_cluster_filter_node.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/autoware_raindrop_cluster_filter/src/low_intensity_cluster_filter_node.cpp b/perception/autoware_raindrop_cluster_filter/src/low_intensity_cluster_filter_node.cpp index e52fc57a5a20c..70ddeadf00b8e 100644 --- a/perception/autoware_raindrop_cluster_filter/src/low_intensity_cluster_filter_node.cpp +++ b/perception/autoware_raindrop_cluster_filter/src/low_intensity_cluster_filter_node.cpp @@ -114,9 +114,9 @@ void LowIntensityClusterFilter::objectCallback( if (debug_publisher_ptr_ && stop_watch_ptr_) { const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_ptr_->publish( + debug_publisher_ptr_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_ptr_->publish( + debug_publisher_ptr_->publish( "debug/processing_time_ms", processing_time_ms); } } From 4b166614d1dc6e372498f52e2fba14f4f79a03fa Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sun, 19 Jan 2025 17:40:26 +0900 Subject: [PATCH 250/334] feat(autoware_planning_test_manager): remove dependency of VirtualTrafficLightState and ExpandStopRange (#9953) * feat(autoware_planning_test_manager): remove dependency of virtual traffic light Signed-off-by: Takayuki Murooka * modify obstacle_stop test code Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- ...e_obstacle_stop_planner_node_interface.cpp | 18 +++++++++++++-- .../autoware_planning_test_manager.hpp | 13 +---------- .../package.xml | 1 - .../src/autoware_planning_test_manager.cpp | 20 ++++------------ .../test/test_node_interface.cpp | 23 +++++++++++++++---- 5 files changed, 41 insertions(+), 34 deletions(-) diff --git a/planning/autoware_obstacle_stop_planner/test/test_autoware_obstacle_stop_planner_node_interface.cpp b/planning/autoware_obstacle_stop_planner/test/test_autoware_obstacle_stop_planner_node_interface.cpp index 9f840586a1959..9da8409c6c2ae 100644 --- a/planning/autoware_obstacle_stop_planner/test/test_autoware_obstacle_stop_planner_node_interface.cpp +++ b/planning/autoware_obstacle_stop_planner/test/test_autoware_obstacle_stop_planner_node_interface.cpp @@ -18,6 +18,8 @@ #include #include +#include + #include #include @@ -25,6 +27,7 @@ using autoware::motion_planning::ObstacleStopPlannerNode; using autoware::planning_test_manager::PlanningInterfaceTestManager; +using tier4_planning_msgs::msg::ExpandStopRange; std::shared_ptr generateTestManager() { @@ -66,8 +69,17 @@ void publishMandatoryTopics( test_manager->publishPointCloud(test_target_node, "obstacle_stop_planner/input/pointcloud"); test_manager->publishAcceleration(test_target_node, "obstacle_stop_planner/input/acceleration"); test_manager->publishPredictedObjects(test_target_node, "obstacle_stop_planner/input/objects"); - test_manager->publishExpandStopRange( - test_target_node, "obstacle_stop_planner/input/expand_stop_range"); +} + +void publishExpandStopRange( + std::shared_ptr test_manager, + std::shared_ptr test_target_node) +{ + auto test_node = test_manager->getTestNode(); + const auto expand_stop_range = test_manager->getTestNode()->create_publisher( + "obstacle_stop_planner/input/expand_stop_range", 1); + expand_stop_range->publish(ExpandStopRange{}); + autoware::test_utils::spinSomeNodes(test_node, test_target_node, 3); } TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) @@ -78,6 +90,7 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) auto test_target_node = generateNode(); publishMandatoryTopics(test_manager, test_target_node); + publishExpandStopRange(test_manager, test_target_node); // test for normal trajectory ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalTrajectory(test_target_node)); @@ -97,6 +110,7 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) auto test_target_node = generateNode(); publishMandatoryTopics(test_manager, test_target_node); + publishExpandStopRange(test_manager, test_target_node); // test for normal trajectory ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalTrajectory(test_target_node)); diff --git a/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager.hpp b/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager.hpp index 2c9a935c2077b..aa7836bc66b88 100644 --- a/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager.hpp +++ b/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager.hpp @@ -52,14 +52,10 @@ #include #include #include -#include -#include -#include #include #include #include #include -#include #include #include @@ -87,14 +83,10 @@ using nav_msgs::msg::OccupancyGrid; using nav_msgs::msg::Odometry; using sensor_msgs::msg::PointCloud2; using tf2_msgs::msg::TFMessage; -using tier4_api_msgs::msg::CrosswalkStatus; -using tier4_api_msgs::msg::IntersectionStatus; -using tier4_planning_msgs::msg::ExpandStopRange; using tier4_planning_msgs::msg::LateralOffset; using tier4_planning_msgs::msg::PathWithLaneId; using tier4_planning_msgs::msg::Scenario; using tier4_planning_msgs::msg::VelocityLimit; -using tier4_v2x_msgs::msg::VirtualTrafficLightStateArray; enum class ModuleName { UNKNOWN = 0, @@ -117,7 +109,6 @@ class PlanningInterfaceTestManager void publishPointCloud(rclcpp::Node::SharedPtr target_node, std::string topic_name); void publishAcceleration(rclcpp::Node::SharedPtr target_node, std::string topic_name); void publishPredictedObjects(rclcpp::Node::SharedPtr target_node, std::string topic_name); - void publishExpandStopRange(rclcpp::Node::SharedPtr target_node, std::string topic_name); void publishOccupancyGrid(rclcpp::Node::SharedPtr target_node, std::string topic_name); void publishCostMap(rclcpp::Node::SharedPtr target_node, std::string topic_name); void publishMap(rclcpp::Node::SharedPtr target_node, std::string topic_name); @@ -131,7 +122,6 @@ class PlanningInterfaceTestManager void publishLateralOffset(rclcpp::Node::SharedPtr target_node, std::string topic_name); void publishOperationModeState(rclcpp::Node::SharedPtr target_node, std::string topic_name); void publishTrafficSignals(rclcpp::Node::SharedPtr target_node, std::string topic_name); - void publishVirtualTrafficLightState(rclcpp::Node::SharedPtr target_node, std::string topic_name); void setTrajectoryInputTopicName(std::string topic_name); void setParkingTrajectoryInputTopicName(std::string topic_name); @@ -178,6 +168,7 @@ class PlanningInterfaceTestManager void testOffTrackFromTrajectory(rclcpp::Node::SharedPtr target_node); int getReceivedTopicNum(); + rclcpp::Node::SharedPtr getTestNode() const; private: // Publisher (necessary for node running) @@ -187,7 +178,6 @@ class PlanningInterfaceTestManager rclcpp::Publisher::SharedPtr point_cloud_pub_; rclcpp::Publisher::SharedPtr acceleration_pub_; rclcpp::Publisher::SharedPtr predicted_objects_pub_; - rclcpp::Publisher::SharedPtr expand_stop_range_pub_; rclcpp::Publisher::SharedPtr occupancy_grid_pub_; rclcpp::Publisher::SharedPtr cost_map_pub_; rclcpp::Publisher::SharedPtr map_pub_; @@ -202,7 +192,6 @@ class PlanningInterfaceTestManager rclcpp::Publisher::SharedPtr lateral_offset_pub_; rclcpp::Publisher::SharedPtr operation_mode_state_pub_; rclcpp::Publisher::SharedPtr traffic_signals_pub_; - rclcpp::Publisher::SharedPtr virtual_traffic_light_states_pub_; // Subscriber rclcpp::Subscription::SharedPtr traj_sub_; diff --git a/planning/autoware_planning_test_manager/package.xml b/planning/autoware_planning_test_manager/package.xml index 80801a8102453..d3395a6c518f3 100644 --- a/planning/autoware_planning_test_manager/package.xml +++ b/planning/autoware_planning_test_manager/package.xml @@ -31,7 +31,6 @@ rclcpp tf2_msgs tf2_ros - tier4_api_msgs tier4_planning_msgs tier4_v2x_msgs unique_identifier_msgs diff --git a/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp b/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp index 62f89cab44e7b..9bc73f3455821 100644 --- a/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp +++ b/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp @@ -71,13 +71,6 @@ void PlanningInterfaceTestManager::publishPredictedObjects( test_node_, target_node, topic_name, predicted_objects_pub_, PredictedObjects{}); } -void PlanningInterfaceTestManager::publishExpandStopRange( - rclcpp::Node::SharedPtr target_node, std::string topic_name) -{ - autoware::test_utils::publishToTargetNode( - test_node_, target_node, topic_name, expand_stop_range_pub_, ExpandStopRange{}); -} - void PlanningInterfaceTestManager::publishOccupancyGrid( rclcpp::Node::SharedPtr target_node, std::string topic_name) { @@ -181,14 +174,6 @@ void PlanningInterfaceTestManager::publishTrafficSignals( test_node_, target_node, topic_name, traffic_signals_pub_, TrafficLightGroupArray{}); } -void PlanningInterfaceTestManager::publishVirtualTrafficLightState( - rclcpp::Node::SharedPtr target_node, std::string topic_name) -{ - autoware::test_utils::publishToTargetNode( - test_node_, target_node, topic_name, virtual_traffic_light_states_pub_, - VirtualTrafficLightStateArray{}); -} - void PlanningInterfaceTestManager::publishInitialPoseTF( rclcpp::Node::SharedPtr target_node, std::string topic_name) { @@ -471,4 +456,9 @@ int PlanningInterfaceTestManager::getReceivedTopicNum() return count_; } +rclcpp::Node::SharedPtr PlanningInterfaceTestManager::getTestNode() const +{ + return test_node_; +} + } // namespace autoware::planning_test_manager diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/test/test_node_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/test/test_node_interface.cpp index ab2fd5847c5be..0e22413c0c8ec 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/test/test_node_interface.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/test/test_node_interface.cpp @@ -13,6 +13,9 @@ // limitations under the License. #include +#include + +#include #include @@ -23,6 +26,19 @@ namespace autoware::behavior_velocity_planner { +using tier4_v2x_msgs::msg::VirtualTrafficLightStateArray; + +void publishVirtualTrafficLightState( + std::shared_ptr test_manager, rclcpp::Node::SharedPtr target_node) +{ + auto test_node = test_manager->getTestNode(); + const auto pub_virtual_traffic_light = + test_manager->getTestNode()->create_publisher( + "behavior_velocity_planner_node/input/virtual_traffic_light_states", 1); + pub_virtual_traffic_light->publish(VirtualTrafficLightStateArray{}); + autoware::test_utils::spinSomeNodes(test_node, target_node, 3); +} + TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID) { rclcpp::init(0, nullptr); @@ -35,8 +51,7 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID) auto test_target_node = autoware::behavior_velocity_planner::generateNode(plugin_info_vec); autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); - test_manager->publishVirtualTrafficLightState( - test_target_node, "behavior_velocity_planner_node/input/virtual_traffic_light_states"); + publishVirtualTrafficLightState(test_manager, test_target_node); // test with nominal path_with_lane_id ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); @@ -57,9 +72,9 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) auto test_manager = autoware::behavior_velocity_planner::generateTestManager(); auto test_target_node = autoware::behavior_velocity_planner::generateNode(plugin_info_vec); + autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); - test_manager->publishVirtualTrafficLightState( - test_target_node, "behavior_velocity_planner_node/input/virtual_traffic_light_states"); + publishVirtualTrafficLightState(test_manager, test_target_node); // test for normal trajectory ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); From 37fc242731cdc0e3e805cc377665eee60eb23b26 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sun, 19 Jan 2025 21:47:27 +0900 Subject: [PATCH 251/334] refactor(behavior_path_planner): common test functions (#9963) * feat: common test code in behavior_path_planner Signed-off-by: Takayuki Murooka * deal with other modules Signed-off-by: Takayuki Murooka * fix typo Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- ...t_behavior_path_planner_node_interface.cpp | 90 ++-------------- ...t_behavior_path_planner_node_interface.cpp | 82 ++------------ ...t_behavior_path_planner_node_interface.cpp | 90 +++------------- ...t_behavior_path_planner_node_interface.cpp | 83 ++------------ .../CMakeLists.txt | 1 + .../behavior_path_planner/test_utils.hpp | 42 ++++++++ .../src/test_utils.cpp | 101 ++++++++++++++++++ ...e_behavior_path_planner_node_interface.cpp | 73 ++----------- ...t_behavior_path_planner_node_interface.cpp | 80 ++------------ ...t_behavior_path_planner_node_interface.cpp | 85 ++------------- 10 files changed, 214 insertions(+), 513 deletions(-) create mode 100644 planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/test_utils.hpp create mode 100644 planning/behavior_path_planner/autoware_behavior_path_planner/src/test_utils.cpp diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp index f679efacb6a44..349d92377d091 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp @@ -12,11 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware/behavior_path_planner/behavior_path_planner_node.hpp" - -#include -#include -#include +#include "autoware/behavior_path_planner/test_utils.hpp" #include @@ -25,84 +21,18 @@ #include #include -using autoware::behavior_path_planner::BehaviorPathPlannerNode; -using autoware::planning_test_manager::PlanningInterfaceTestManager; - -std::shared_ptr generateTestManager() -{ - auto test_manager = std::make_shared(); - - // set subscriber with topic name: behavior_path_planner → test_node_ - test_manager->setPathWithLaneIdSubscriber("behavior_path_planner/output/path"); - - // set behavior_path_planner's input topic name(this topic is changed to test node) - test_manager->setRouteInputTopicName("behavior_path_planner/input/route"); - - test_manager->setInitialPoseTopicName("behavior_path_planner/input/odometry"); - - return test_manager; -} - -std::shared_ptr generateNode() -{ - auto node_options = rclcpp::NodeOptions{}; - const auto autoware_test_utils_dir = - ament_index_cpp::get_package_share_directory("autoware_test_utils"); - const auto behavior_path_planner_dir = - ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner"); - const auto behavior_path_lane_change_module_dir = - ament_index_cpp::get_package_share_directory("autoware_behavior_path_lane_change_module"); - - std::vector module_names; - module_names.emplace_back("autoware::behavior_path_planner::AvoidanceByLaneChangeModuleManager"); - - std::vector params; - params.emplace_back("launch_modules", module_names); - node_options.parameter_overrides(params); - - autoware::test_utils::updateNodeOptions( - node_options, {autoware_test_utils_dir + "/config/test_common.param.yaml", - autoware_test_utils_dir + "/config/test_nearest_search.param.yaml", - autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", - behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", - behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", - behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", - behavior_path_lane_change_module_dir + "/config/lane_change.param.yaml", - ament_index_cpp::get_package_share_directory( - "autoware_behavior_path_static_obstacle_avoidance_module") + - "/config/static_obstacle_avoidance.param.yaml", - ament_index_cpp::get_package_share_directory( - "autoware_behavior_path_avoidance_by_lane_change_module") + - "/config/avoidance_by_lane_change.param.yaml"}); - - return std::make_shared(node_options); -} - -void publishMandatoryTopics( - std::shared_ptr test_manager, - std::shared_ptr test_target_node) -{ - // publish necessary topics from test_manager - test_manager->publishInitialPose(test_target_node, "behavior_path_planner/input/odometry"); - test_manager->publishAcceleration(test_target_node, "behavior_path_planner/input/accel"); - test_manager->publishPredictedObjects(test_target_node, "behavior_path_planner/input/perception"); - test_manager->publishOccupancyGrid( - test_target_node, "behavior_path_planner/input/occupancy_grid_map"); - test_manager->publishLaneDrivingScenario( - test_target_node, "behavior_path_planner/input/scenario"); - test_manager->publishMap(test_target_node, "behavior_path_planner/input/vector_map"); - test_manager->publishCostMap(test_target_node, "behavior_path_planner/input/costmap"); - test_manager->publishOperationModeState(test_target_node, "system/operation_mode/state"); - test_manager->publishLateralOffset( - test_target_node, "behavior_path_planner/input/lateral_offset"); -} +using autoware::behavior_path_planner::generateNode; +using autoware::behavior_path_planner::generateTestManager; +using autoware::behavior_path_planner::publishMandatoryTopics; TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionRoute) { rclcpp::init(0, nullptr); - auto test_manager = generateTestManager(); - auto test_target_node = generateNode(); + auto test_manager = generateTestManager(); + auto test_target_node = generateNode( + {"lane_change", "static_obstacle_avoidance", "avoidance_by_lane_change"}, + {"autoware::behavior_path_planner::AvoidanceByLaneChangeModuleManager"}); publishMandatoryTopics(test_manager, test_target_node); // test for normal trajectory @@ -119,7 +49,9 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) rclcpp::init(0, nullptr); auto test_manager = generateTestManager(); - auto test_target_node = generateNode(); + auto test_target_node = generateNode( + {"lane_change", "static_obstacle_avoidance", "avoidance_by_lane_change"}, + {"autoware::behavior_path_planner::AvoidanceByLaneChangeModuleManager"}); publishMandatoryTopics(test_manager, test_target_node); // test for normal trajectory diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp index a18a2440dcb3a..488475079613f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp @@ -12,87 +12,23 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware/behavior_path_planner/behavior_path_planner_node.hpp" - -#include -#include -#include +#include "autoware/behavior_path_planner/test_utils.hpp" #include #include #include -using autoware::behavior_path_planner::BehaviorPathPlannerNode; -using autoware::planning_test_manager::PlanningInterfaceTestManager; - -std::shared_ptr generateTestManager() -{ - auto test_manager = std::make_shared(); - - // set subscriber with topic name: behavior_path_planner → test_node_ - test_manager->setPathWithLaneIdSubscriber("behavior_path_planner/output/path"); - - // set behavior_path_planner's input topic name(this topic is changed to test node) - test_manager->setRouteInputTopicName("behavior_path_planner/input/route"); - - test_manager->setInitialPoseTopicName("behavior_path_planner/input/odometry"); - - return test_manager; -} - -std::shared_ptr generateNode() -{ - auto node_options = rclcpp::NodeOptions{}; - const auto autoware_test_utils_dir = - ament_index_cpp::get_package_share_directory("autoware_test_utils"); - const auto behavior_path_planner_dir = - ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner"); - - std::vector module_names; - module_names.emplace_back("autoware::behavior_path_planner::DynamicAvoidanceModuleManager"); - - std::vector params; - params.emplace_back("launch_modules", module_names); - node_options.parameter_overrides(params); - - autoware::test_utils::updateNodeOptions( - node_options, {autoware_test_utils_dir + "/config/test_common.param.yaml", - autoware_test_utils_dir + "/config/test_nearest_search.param.yaml", - autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", - behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", - behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", - behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", - ament_index_cpp::get_package_share_directory( - "autoware_behavior_path_dynamic_obstacle_avoidance_module") + - "/config/dynamic_obstacle_avoidance.param.yaml"}); - - return std::make_shared(node_options); -} - -void publishMandatoryTopics( - std::shared_ptr test_manager, - std::shared_ptr test_target_node) -{ - // publish necessary topics from test_manager - test_manager->publishInitialPose(test_target_node, "behavior_path_planner/input/odometry"); - test_manager->publishAcceleration(test_target_node, "behavior_path_planner/input/accel"); - test_manager->publishPredictedObjects(test_target_node, "behavior_path_planner/input/perception"); - test_manager->publishOccupancyGrid( - test_target_node, "behavior_path_planner/input/occupancy_grid_map"); - test_manager->publishLaneDrivingScenario( - test_target_node, "behavior_path_planner/input/scenario"); - test_manager->publishMap(test_target_node, "behavior_path_planner/input/vector_map"); - test_manager->publishCostMap(test_target_node, "behavior_path_planner/input/costmap"); - test_manager->publishOperationModeState(test_target_node, "system/operation_mode/state"); - test_manager->publishLateralOffset( - test_target_node, "behavior_path_planner/input/lateral_offset"); -} +using autoware::behavior_path_planner::generateNode; +using autoware::behavior_path_planner::generateTestManager; +using autoware::behavior_path_planner::publishMandatoryTopics; TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionRoute) { rclcpp::init(0, nullptr); auto test_manager = generateTestManager(); - auto test_target_node = generateNode(); + auto test_target_node = generateNode( + {"dynamic_obstacle_avoidance"}, + {"autoware::behavior_path_planner::DynamicObstacleAvoidanceModuleManager"}); publishMandatoryTopics(test_manager, test_target_node); @@ -110,7 +46,9 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) rclcpp::init(0, nullptr); auto test_manager = generateTestManager(); - auto test_target_node = generateNode(); + auto test_target_node = generateNode( + {"dynamic_obstacle_avoidance"}, + {"autoware::behavior_path_planner::DynamicObstacleAvoidanceModuleManager"}); publishMandatoryTopics(test_manager, test_target_node); // test for normal trajectory diff --git a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp index ad37a90605233..506e43a94de1d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp @@ -12,10 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ament_index_cpp/get_package_share_directory.hpp" -#include "autoware/behavior_path_planner/behavior_path_planner_node.hpp" -#include "autoware_planning_test_manager/autoware_planning_test_manager.hpp" -#include "autoware_test_utils/autoware_test_utils.hpp" +#include "autoware/behavior_path_planner/test_utils.hpp" #include @@ -24,83 +21,19 @@ #include #include -using autoware::behavior_path_planner::BehaviorPathPlannerNode; -using autoware::planning_test_manager::PlanningInterfaceTestManager; - -std::shared_ptr generateTestManager() -{ - auto test_manager = std::make_shared(); - - // set subscriber with topic name: behavior_path_planner → test_node_ - test_manager->setPathWithLaneIdSubscriber("behavior_path_planner/output/path"); - - // set behavior_path_planner's input topic name(this topic is changed to test node) - test_manager->setRouteInputTopicName("behavior_path_planner/input/route"); - - test_manager->setInitialPoseTopicName("behavior_path_planner/input/odometry"); - - return test_manager; -} - -std::shared_ptr generateNode() -{ - auto node_options = rclcpp::NodeOptions{}; - const auto autoware_test_utils_dir = - ament_index_cpp::get_package_share_directory("autoware_test_utils"); - const auto behavior_path_planner_dir = - ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner"); - const auto behavior_path_lane_change_module_dir = - ament_index_cpp::get_package_share_directory("autoware_behavior_path_lane_change_module"); - - std::vector module_names; - module_names.emplace_back( - "autoware::behavior_path_planner::ExternalRequestLaneChangeRightModuleManager"); - module_names.emplace_back( - "autoware::behavior_path_planner::ExternalRequestLaneChangeLeftModuleManager"); - - std::vector params; - params.emplace_back("launch_modules", module_names); - node_options.parameter_overrides(params); - - autoware::test_utils::updateNodeOptions( - node_options, { - autoware_test_utils_dir + "/config/test_common.param.yaml", - autoware_test_utils_dir + "/config/test_nearest_search.param.yaml", - autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", - behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", - behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", - behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", - behavior_path_lane_change_module_dir + "/config/lane_change.param.yaml", - }); - - return std::make_shared(node_options); -} - -void publishMandatoryTopics( - std::shared_ptr test_manager, - std::shared_ptr test_target_node) -{ - // publish necessary topics from test_manager - test_manager->publishInitialPose(test_target_node, "behavior_path_planner/input/odometry"); - test_manager->publishAcceleration(test_target_node, "behavior_path_planner/input/accel"); - test_manager->publishPredictedObjects(test_target_node, "behavior_path_planner/input/perception"); - test_manager->publishOccupancyGrid( - test_target_node, "behavior_path_planner/input/occupancy_grid_map"); - test_manager->publishLaneDrivingScenario( - test_target_node, "behavior_path_planner/input/scenario"); - test_manager->publishMap(test_target_node, "behavior_path_planner/input/vector_map"); - test_manager->publishCostMap(test_target_node, "behavior_path_planner/input/costmap"); - test_manager->publishOperationModeState(test_target_node, "system/operation_mode/state"); - test_manager->publishLateralOffset( - test_target_node, "behavior_path_planner/input/lateral_offset"); -} +using autoware::behavior_path_planner::generateNode; +using autoware::behavior_path_planner::generateTestManager; +using autoware::behavior_path_planner::publishMandatoryTopics; TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionRoute) { rclcpp::init(0, nullptr); - auto test_manager = generateTestManager(); - auto test_target_node = generateNode(); + auto test_manager = generateTestManager(); + auto test_target_node = generateNode( + {"lane_change"}, + {"autoware::behavior_path_planner::ExternalRequestLaneChangeRightModuleManager", + "autoware::behavior_path_planner::ExternalRequestLaneChangeLeftModuleManager"}); publishMandatoryTopics(test_manager, test_target_node); // test for normal trajectory @@ -117,7 +50,10 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) rclcpp::init(0, nullptr); auto test_manager = generateTestManager(); - auto test_target_node = generateNode(); + auto test_target_node = generateNode( + {"lane_change"}, + {"autoware::behavior_path_planner::ExternalRequestLaneChangeRightModuleManager", + "autoware::behavior_path_planner::ExternalRequestLaneChangeLeftModuleManager"}); publishMandatoryTopics(test_manager, test_target_node); // test for normal trajectory diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp index 555657fe34af9..f6b3e9eeaf715 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp @@ -12,10 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ament_index_cpp/get_package_share_directory.hpp" -#include "autoware/behavior_path_planner/behavior_path_planner_node.hpp" -#include "autoware_planning_test_manager/autoware_planning_test_manager.hpp" -#include "autoware_test_utils/autoware_test_utils.hpp" +#include "autoware/behavior_path_planner/test_utils.hpp" #include @@ -24,78 +21,18 @@ #include #include -using autoware::behavior_path_planner::BehaviorPathPlannerNode; -using autoware::planning_test_manager::PlanningInterfaceTestManager; - -std::shared_ptr generateTestManager() -{ - auto test_manager = std::make_shared(); - - // set subscriber with topic name: behavior_path_planner → test_node_ - test_manager->setPathWithLaneIdSubscriber("behavior_path_planner/output/path"); - - // set behavior_path_planner's input topic name(this topic is changed to test node) - test_manager->setRouteInputTopicName("behavior_path_planner/input/route"); - - test_manager->setInitialPoseTopicName("behavior_path_planner/input/odometry"); - - return test_manager; -} - -std::shared_ptr generateNode() -{ - auto node_options = rclcpp::NodeOptions{}; - const auto autoware_test_utils_dir = - ament_index_cpp::get_package_share_directory("autoware_test_utils"); - const auto behavior_path_planner_dir = - ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner"); - const auto behavior_path_lane_change_module_dir = - ament_index_cpp::get_package_share_directory("autoware_behavior_path_lane_change_module"); - - std::vector module_names; - module_names.emplace_back("autoware::behavior_path_planner::LaneChangeRightModuleManager"); - module_names.emplace_back("autoware::behavior_path_planner::LaneChangeLeftModuleManager"); - - std::vector params; - params.emplace_back("launch_modules", module_names); - node_options.parameter_overrides(params); - - autoware::test_utils::updateNodeOptions( - node_options, {autoware_test_utils_dir + "/config/test_common.param.yaml", - autoware_test_utils_dir + "/config/test_nearest_search.param.yaml", - autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", - behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", - behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", - behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", - behavior_path_lane_change_module_dir + "/config/lane_change.param.yaml"}); - - return std::make_shared(node_options); -} - -void publishMandatoryTopics( - std::shared_ptr test_manager, - std::shared_ptr test_target_node) -{ - // publish necessary topics from test_manager - test_manager->publishInitialPose(test_target_node, "behavior_path_planner/input/odometry"); - test_manager->publishAcceleration(test_target_node, "behavior_path_planner/input/accel"); - test_manager->publishPredictedObjects(test_target_node, "behavior_path_planner/input/perception"); - test_manager->publishOccupancyGrid( - test_target_node, "behavior_path_planner/input/occupancy_grid_map"); - test_manager->publishLaneDrivingScenario( - test_target_node, "behavior_path_planner/input/scenario"); - test_manager->publishMap(test_target_node, "behavior_path_planner/input/vector_map"); - test_manager->publishCostMap(test_target_node, "behavior_path_planner/input/costmap"); - test_manager->publishOperationModeState(test_target_node, "system/operation_mode/state"); - test_manager->publishLateralOffset( - test_target_node, "behavior_path_planner/input/lateral_offset"); -} +using autoware::behavior_path_planner::generateNode; +using autoware::behavior_path_planner::generateTestManager; +using autoware::behavior_path_planner::publishMandatoryTopics; TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionRoute) { rclcpp::init(0, nullptr); + auto test_manager = generateTestManager(); - auto test_target_node = generateNode(); + auto test_target_node = generateNode( + {"lane_change"}, {"autoware::behavior_path_planner::LaneChangeRightModuleManager", + "autoware::behavior_path_planner::LaneChangeLeftModuleManager"}); publishMandatoryTopics(test_manager, test_target_node); @@ -113,7 +50,9 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) rclcpp::init(0, nullptr); auto test_manager = generateTestManager(); - auto test_target_node = generateNode(); + auto test_target_node = generateNode( + {"lane_change"}, {"autoware::behavior_path_planner::LaneChangeRightModuleManager", + "autoware::behavior_path_planner::LaneChangeLeftModuleManager"}); publishMandatoryTopics(test_manager, test_target_node); // test for normal trajectory diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/CMakeLists.txt b/planning/behavior_path_planner/autoware_behavior_path_planner/CMakeLists.txt index cadaacd01d9c9..f43b454cfb100 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/CMakeLists.txt +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/CMakeLists.txt @@ -10,6 +10,7 @@ find_package(magic_enum CONFIG REQUIRED) ament_auto_add_library(${PROJECT_NAME}_lib SHARED src/planner_manager.cpp src/behavior_path_planner_node.cpp + src/test_utils.cpp ) target_include_directories(${PROJECT_NAME}_lib SYSTEM PUBLIC diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/test_utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/test_utils.hpp new file mode 100644 index 0000000000000..5e1718419f139 --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/test_utils.hpp @@ -0,0 +1,42 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__BEHAVIOR_PATH_PLANNER__TEST_UTILS_HPP_ +#define AUTOWARE__BEHAVIOR_PATH_PLANNER__TEST_UTILS_HPP_ + +#include "autoware/behavior_path_planner/behavior_path_planner_node.hpp" + +#include + +#include +#include +#include + +namespace autoware::behavior_path_planner +{ +using autoware::behavior_path_planner::BehaviorPathPlannerNode; +using autoware::planning_test_manager::PlanningInterfaceTestManager; + +std::shared_ptr generateTestManager(); + +std::shared_ptr generateNode( + const std::vector & module_name_vec, + const std::vector & plugin_name_vec); + +void publishMandatoryTopics( + std::shared_ptr test_manager, + std::shared_ptr test_target_node); +} // namespace autoware::behavior_path_planner + +#endif // AUTOWARE__BEHAVIOR_PATH_PLANNER__TEST_UTILS_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/src/test_utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner/src/test_utils.cpp new file mode 100644 index 0000000000000..2ce6f5bee9a50 --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/src/test_utils.cpp @@ -0,0 +1,101 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/behavior_path_planner/test_utils.hpp" + +#include +#include +#include + +#include +#include +#include + +namespace autoware::behavior_path_planner +{ +std::shared_ptr generateTestManager() +{ + auto test_manager = std::make_shared(); + + // set subscriber with topic name: behavior_path_planner → test_node_ + test_manager->setPathWithLaneIdSubscriber("behavior_path_planner/output/path"); + + // set behavior_path_planner's input topic name(this topic is changed to test node) + test_manager->setRouteInputTopicName("behavior_path_planner/input/route"); + + test_manager->setInitialPoseTopicName("behavior_path_planner/input/odometry"); + + return test_manager; +} + +std::shared_ptr generateNode( + const std::vector & module_name_vec, + const std::vector & plugin_name_vec) +{ + auto node_options = rclcpp::NodeOptions{}; + const auto autoware_test_utils_dir = + ament_index_cpp::get_package_share_directory("autoware_test_utils"); + const auto behavior_path_planner_dir = + ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner"); + + std::vector plugin_names; + for (const auto & plugin_name : plugin_name_vec) { + plugin_names.emplace_back(plugin_name); + } + + std::vector params; + params.emplace_back("launch_modules", plugin_names); + node_options.parameter_overrides(params); + + const auto get_behavior_path_module_config = [](const std::string & module) { + const auto package_name = "autoware_behavior_path_" + module + "_module"; + const auto package_path = ament_index_cpp::get_package_share_directory(package_name); + return package_path + "/config/" + module + ".param.yaml"; + }; + + auto yaml_files = std::vector{ + autoware_test_utils_dir + "/config/test_common.param.yaml", + autoware_test_utils_dir + "/config/test_nearest_search.param.yaml", + autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", + behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", + behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", + behavior_path_planner_dir + "/config/scene_module_manager.param.yaml"}; + for (const auto & module_name : module_name_vec) { + yaml_files.push_back(get_behavior_path_module_config(module_name)); + } + + autoware::test_utils::updateNodeOptions(node_options, yaml_files); + + return std::make_shared(node_options); +} + +void publishMandatoryTopics( + std::shared_ptr test_manager, + std::shared_ptr test_target_node) +{ + // publish necessary topics from test_manager + test_manager->publishInitialPose(test_target_node, "behavior_path_planner/input/odometry"); + test_manager->publishAcceleration(test_target_node, "behavior_path_planner/input/accel"); + test_manager->publishPredictedObjects(test_target_node, "behavior_path_planner/input/perception"); + test_manager->publishOccupancyGrid( + test_target_node, "behavior_path_planner/input/occupancy_grid_map"); + test_manager->publishLaneDrivingScenario( + test_target_node, "behavior_path_planner/input/scenario"); + test_manager->publishMap(test_target_node, "behavior_path_planner/input/vector_map"); + test_manager->publishCostMap(test_target_node, "behavior_path_planner/input/costmap"); + test_manager->publishOperationModeState(test_target_node, "system/operation_mode/state"); + test_manager->publishLateralOffset( + test_target_node, "behavior_path_planner/input/lateral_offset"); +} +} // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/test/test_autoware_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner/test/test_autoware_behavior_path_planner_node_interface.cpp index 63b7ccf3fff12..0c933345e7647 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/test/test_autoware_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/test/test_autoware_behavior_path_planner_node_interface.cpp @@ -13,10 +13,7 @@ // limitations under the License. #include "autoware/behavior_path_planner/behavior_path_planner_node.hpp" - -#include -#include -#include +#include "autoware/behavior_path_planner/test_utils.hpp" #include @@ -25,73 +22,15 @@ #include #include -using autoware::behavior_path_planner::BehaviorPathPlannerNode; -using autoware::planning_test_manager::PlanningInterfaceTestManager; - -std::shared_ptr generateTestManager() -{ - auto test_manager = std::make_shared(); - - // set subscriber with topic name: behavior_path_planner → test_node_ - test_manager->setPathWithLaneIdSubscriber("behavior_path_planner/output/path"); - - // set behavior_path_planner's input topic name(this topic is changed to test node) - test_manager->setRouteInputTopicName("behavior_path_planner/input/route"); - - test_manager->setInitialPoseTopicName("behavior_path_planner/input/odometry"); - - return test_manager; -} - -std::shared_ptr generateNode() -{ - auto node_options = rclcpp::NodeOptions{}; - const auto autoware_test_utils_dir = - ament_index_cpp::get_package_share_directory("autoware_test_utils"); - const auto behavior_path_planner_dir = - ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner"); - - std::vector module_names; - - std::vector params; - params.emplace_back("launch_modules", module_names); - node_options.parameter_overrides(params); - - autoware::test_utils::updateNodeOptions( - node_options, {autoware_test_utils_dir + "/config/test_common.param.yaml", - autoware_test_utils_dir + "/config/test_nearest_search.param.yaml", - autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", - behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", - behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", - behavior_path_planner_dir + "/config/scene_module_manager.param.yaml"}); - - return std::make_shared(node_options); -} - -void publishMandatoryTopics( - std::shared_ptr test_manager, - std::shared_ptr test_target_node) -{ - // publish necessary topics from test_manager - test_manager->publishInitialPose(test_target_node, "behavior_path_planner/input/odometry"); - test_manager->publishAcceleration(test_target_node, "behavior_path_planner/input/accel"); - test_manager->publishPredictedObjects(test_target_node, "behavior_path_planner/input/perception"); - test_manager->publishOccupancyGrid( - test_target_node, "behavior_path_planner/input/occupancy_grid_map"); - test_manager->publishLaneDrivingScenario( - test_target_node, "behavior_path_planner/input/scenario"); - test_manager->publishMap(test_target_node, "behavior_path_planner/input/vector_map"); - test_manager->publishCostMap(test_target_node, "behavior_path_planner/input/costmap"); - test_manager->publishOperationModeState(test_target_node, "system/operation_mode/state"); - test_manager->publishLateralOffset( - test_target_node, "behavior_path_planner/input/lateral_offset"); -} +using autoware::behavior_path_planner::generateNode; +using autoware::behavior_path_planner::generateTestManager; +using autoware::behavior_path_planner::publishMandatoryTopics; TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionRoute) { rclcpp::init(0, nullptr); auto test_manager = generateTestManager(); - auto test_target_node = generateNode(); + auto test_target_node = generateNode({}, {}); publishMandatoryTopics(test_manager, test_target_node); @@ -109,7 +48,7 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) rclcpp::init(0, nullptr); auto test_manager = generateTestManager(); - auto test_target_node = generateNode(); + auto test_target_node = generateNode({}, {}); publishMandatoryTopics(test_manager, test_target_node); // test for normal trajectory diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp index c8661cdf1d912..c248a40eb151a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp @@ -12,11 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware/behavior_path_planner/behavior_path_planner_node.hpp" - -#include -#include -#include +#include "autoware/behavior_path_planner/test_utils.hpp" #include @@ -25,77 +21,16 @@ #include #include -using autoware::behavior_path_planner::BehaviorPathPlannerNode; -using autoware::planning_test_manager::PlanningInterfaceTestManager; - -std::shared_ptr generateTestManager() -{ - auto test_manager = std::make_shared(); - - // set subscriber with topic name: behavior_path_planner → test_node_ - test_manager->setPathWithLaneIdSubscriber("behavior_path_planner/output/path"); - - // set behavior_path_planner's input topic name(this topic is changed to test node) - test_manager->setRouteInputTopicName("behavior_path_planner/input/route"); - - test_manager->setInitialPoseTopicName("behavior_path_planner/input/odometry"); - - return test_manager; -} - -std::shared_ptr generateNode() -{ - auto node_options = rclcpp::NodeOptions{}; - const auto autoware_test_utils_dir = - ament_index_cpp::get_package_share_directory("autoware_test_utils"); - const auto behavior_path_planner_dir = - ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner"); - - std::vector module_names; - module_names.emplace_back("autoware::behavior_path_planner::SideShiftModuleManager"); - - std::vector params; - params.emplace_back("launch_modules", module_names); - node_options.parameter_overrides(params); - - autoware::test_utils::updateNodeOptions( - node_options, - {autoware_test_utils_dir + "/config/test_common.param.yaml", - autoware_test_utils_dir + "/config/test_nearest_search.param.yaml", - autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", - behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", - behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", - behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", - ament_index_cpp::get_package_share_directory("autoware_behavior_path_side_shift_module") + - "/config/side_shift.param.yaml"}); - - return std::make_shared(node_options); -} - -void publishMandatoryTopics( - std::shared_ptr test_manager, - std::shared_ptr test_target_node) -{ - // publish necessary topics from test_manager - test_manager->publishInitialPose(test_target_node, "behavior_path_planner/input/odometry"); - test_manager->publishAcceleration(test_target_node, "behavior_path_planner/input/accel"); - test_manager->publishPredictedObjects(test_target_node, "behavior_path_planner/input/perception"); - test_manager->publishOccupancyGrid( - test_target_node, "behavior_path_planner/input/occupancy_grid_map"); - test_manager->publishLaneDrivingScenario( - test_target_node, "behavior_path_planner/input/scenario"); - test_manager->publishMap(test_target_node, "behavior_path_planner/input/vector_map"); - test_manager->publishCostMap(test_target_node, "behavior_path_planner/input/costmap"); - test_manager->publishOperationModeState(test_target_node, "system/operation_mode/state"); - test_manager->publishLateralOffset( - test_target_node, "behavior_path_planner/input/lateral_offset"); -} +using autoware::behavior_path_planner::generateNode; +using autoware::behavior_path_planner::generateTestManager; +using autoware::behavior_path_planner::publishMandatoryTopics; TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionRoute) { rclcpp::init(0, nullptr); auto test_manager = generateTestManager(); - auto test_target_node = generateNode(); + auto test_target_node = + generateNode({"side_shift"}, {"autoware::behavior_path_planner::SideShiftModuleManager"}); publishMandatoryTopics(test_manager, test_target_node); @@ -113,7 +48,8 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) rclcpp::init(0, nullptr); auto test_manager = generateTestManager(); - auto test_target_node = generateNode(); + auto test_target_node = + generateNode({"side_shift"}, {"autoware::behavior_path_planner::SideShiftModuleManager"}); publishMandatoryTopics(test_manager, test_target_node); // test for normal trajectory diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp index b6a8fd04f93db..c2531e5f2bb9f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp @@ -12,89 +12,24 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware/behavior_path_planner/behavior_path_planner_node.hpp" - -#include -#include -#include +#include "autoware/behavior_path_planner/test_utils.hpp" #include #include #include -using autoware::behavior_path_planner::BehaviorPathPlannerNode; -using autoware::planning_test_manager::PlanningInterfaceTestManager; - -std::shared_ptr generateTestManager() -{ - auto test_manager = std::make_shared(); - - // set subscriber with topic name: behavior_path_planner → test_node_ - test_manager->setPathWithLaneIdSubscriber("behavior_path_planner/output/path"); - - // set behavior_path_planner's input topic name(this topic is changed to test node) - test_manager->setRouteInputTopicName("behavior_path_planner/input/route"); - - test_manager->setInitialPoseTopicName("behavior_path_planner/input/odometry"); - - return test_manager; -} - -std::shared_ptr generateNode() -{ - auto node_options = rclcpp::NodeOptions{}; - const auto autoware_test_utils_dir = - ament_index_cpp::get_package_share_directory("autoware_test_utils"); - const auto behavior_path_planner_dir = - ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner"); - - std::vector module_names; - module_names.emplace_back( - "autoware::behavior_path_planner::StaticObstacleAvoidanceModuleManager"); - - std::vector params; - params.emplace_back("launch_modules", module_names); - node_options.parameter_overrides(params); - - autoware::test_utils::updateNodeOptions( - node_options, {autoware_test_utils_dir + "/config/test_common.param.yaml", - autoware_test_utils_dir + "/config/test_nearest_search.param.yaml", - autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", - behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", - behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", - behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", - ament_index_cpp::get_package_share_directory( - "autoware_behavior_path_static_obstacle_avoidance_module") + - "/config/static_obstacle_avoidance.param.yaml"}); - - return std::make_shared(node_options); -} - -void publishMandatoryTopics( - std::shared_ptr test_manager, - std::shared_ptr test_target_node) -{ - // publish necessary topics from test_manager - test_manager->publishInitialPose(test_target_node, "behavior_path_planner/input/odometry"); - test_manager->publishAcceleration(test_target_node, "behavior_path_planner/input/accel"); - test_manager->publishPredictedObjects(test_target_node, "behavior_path_planner/input/perception"); - test_manager->publishOccupancyGrid( - test_target_node, "behavior_path_planner/input/occupancy_grid_map"); - test_manager->publishLaneDrivingScenario( - test_target_node, "behavior_path_planner/input/scenario"); - test_manager->publishMap(test_target_node, "behavior_path_planner/input/vector_map"); - test_manager->publishCostMap(test_target_node, "behavior_path_planner/input/costmap"); - test_manager->publishOperationModeState(test_target_node, "system/operation_mode/state"); - test_manager->publishLateralOffset( - test_target_node, "behavior_path_planner/input/lateral_offset"); -} +using autoware::behavior_path_planner::generateNode; +using autoware::behavior_path_planner::generateTestManager; +using autoware::behavior_path_planner::publishMandatoryTopics; TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionRoute) { rclcpp::init(0, nullptr); - auto test_manager = generateTestManager(); - auto test_target_node = generateNode(); + auto test_manager = generateTestManager(); + auto test_target_node = generateNode( + {"static_obstacle_avoidance"}, + {"autoware::behavior_path_planner::StaticObstacleAvoidanceModuleManager"}); publishMandatoryTopics(test_manager, test_target_node); // test for normal trajectory @@ -111,7 +46,9 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) rclcpp::init(0, nullptr); auto test_manager = generateTestManager(); - auto test_target_node = generateNode(); + auto test_target_node = generateNode( + {"static_obstacle_avoidance"}, + {"autoware::behavior_path_planner::StaticObstacleAvoidanceModuleManager"}); publishMandatoryTopics(test_manager, test_target_node); // test for normal trajectory From 80eb07ccf960a290e8d96ebfa0f351e1fbb2a032 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sun, 19 Jan 2025 23:47:56 +0900 Subject: [PATCH 252/334] feat(autoware_planning_test_manager): remove dependency of tier4_planning_msgs::msg::LateralOffset (#9967) * feat(autoware_planning_test_manager): remove dependency of tier4_planning_msgs::msg::LateralOffset Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- common/autoware_test_utils/package.xml | 2 -- .../autoware_planning_test_manager.hpp | 4 ---- .../package.xml | 1 - .../src/autoware_planning_test_manager.cpp | 7 ------- .../src/test_utils.cpp | 21 +++++++++++++++++-- 5 files changed, 19 insertions(+), 16 deletions(-) diff --git a/common/autoware_test_utils/package.xml b/common/autoware_test_utils/package.xml index 740e7f840141d..f67b366480b00 100644 --- a/common/autoware_test_utils/package.xml +++ b/common/autoware_test_utils/package.xml @@ -33,9 +33,7 @@ std_srvs tf2_msgs tf2_ros - tier4_api_msgs tier4_planning_msgs - tier4_v2x_msgs unique_identifier_msgs yaml_cpp_vendor diff --git a/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager.hpp b/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager.hpp index aa7836bc66b88..bb808484e10be 100644 --- a/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager.hpp +++ b/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager.hpp @@ -52,7 +52,6 @@ #include #include #include -#include #include #include #include @@ -83,7 +82,6 @@ using nav_msgs::msg::OccupancyGrid; using nav_msgs::msg::Odometry; using sensor_msgs::msg::PointCloud2; using tf2_msgs::msg::TFMessage; -using tier4_planning_msgs::msg::LateralOffset; using tier4_planning_msgs::msg::PathWithLaneId; using tier4_planning_msgs::msg::Scenario; using tier4_planning_msgs::msg::VelocityLimit; @@ -119,7 +117,6 @@ class PlanningInterfaceTestManager void publishRoute(rclcpp::Node::SharedPtr target_node, std::string topic_name); void publishTF(rclcpp::Node::SharedPtr target_node, std::string topic_name); void publishInitialPoseTF(rclcpp::Node::SharedPtr target_node, std::string topic_name); - void publishLateralOffset(rclcpp::Node::SharedPtr target_node, std::string topic_name); void publishOperationModeState(rclcpp::Node::SharedPtr target_node, std::string topic_name); void publishTrafficSignals(rclcpp::Node::SharedPtr target_node, std::string topic_name); @@ -189,7 +186,6 @@ class PlanningInterfaceTestManager rclcpp::Publisher::SharedPtr route_pub_; rclcpp::Publisher::SharedPtr TF_pub_; rclcpp::Publisher::SharedPtr initial_pose_tf_pub_; - rclcpp::Publisher::SharedPtr lateral_offset_pub_; rclcpp::Publisher::SharedPtr operation_mode_state_pub_; rclcpp::Publisher::SharedPtr traffic_signals_pub_; diff --git a/planning/autoware_planning_test_manager/package.xml b/planning/autoware_planning_test_manager/package.xml index d3395a6c518f3..d5f8383913274 100644 --- a/planning/autoware_planning_test_manager/package.xml +++ b/planning/autoware_planning_test_manager/package.xml @@ -32,7 +32,6 @@ tf2_msgs tf2_ros tier4_planning_msgs - tier4_v2x_msgs unique_identifier_msgs yaml_cpp_vendor diff --git a/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp b/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp index 9bc73f3455821..f07efd0cda116 100644 --- a/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp +++ b/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp @@ -153,13 +153,6 @@ void PlanningInterfaceTestManager::publishTF( autoware::test_utils::makeTFMsg(target_node, "base_link", "map")); } -void PlanningInterfaceTestManager::publishLateralOffset( - rclcpp::Node::SharedPtr target_node, std::string topic_name) -{ - autoware::test_utils::publishToTargetNode( - test_node_, target_node, topic_name, lateral_offset_pub_, LateralOffset{}); -} - void PlanningInterfaceTestManager::publishOperationModeState( rclcpp::Node::SharedPtr target_node, std::string topic_name) { diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/src/test_utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner/src/test_utils.cpp index 2ce6f5bee9a50..4930ead6d355d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/src/test_utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/src/test_utils.cpp @@ -18,12 +18,30 @@ #include #include +#include + #include #include #include namespace autoware::behavior_path_planner { +namespace +{ +using tier4_planning_msgs::msg::LateralOffset; + +void publishLateralOffset( + std::shared_ptr test_manager, + std::shared_ptr test_target_node) +{ + auto test_node = test_manager->getTestNode(); + const auto pub_lateral_offset = test_manager->getTestNode()->create_publisher( + "behavior_path_planner/input/lateral_offset", 1); + pub_lateral_offset->publish(LateralOffset{}); + autoware::test_utils::spinSomeNodes(test_node, test_target_node, 3); +} +} // namespace + std::shared_ptr generateTestManager() { auto test_manager = std::make_shared(); @@ -95,7 +113,6 @@ void publishMandatoryTopics( test_manager->publishMap(test_target_node, "behavior_path_planner/input/vector_map"); test_manager->publishCostMap(test_target_node, "behavior_path_planner/input/costmap"); test_manager->publishOperationModeState(test_target_node, "system/operation_mode/state"); - test_manager->publishLateralOffset( - test_target_node, "behavior_path_planner/input/lateral_offset"); + publishLateralOffset(test_manager, test_target_node); } } // namespace autoware::behavior_path_planner From 3edd7b51097b012db40162a391e7e3052b071848 Mon Sep 17 00:00:00 2001 From: Junya Sasaki Date: Mon, 20 Jan 2025 14:10:19 +0900 Subject: [PATCH 253/334] feat: apply `autoware_` prefix for `evaluator/localization_evaluator` (#9954) * feat(localization_evaluator): apply `autoware_` prefix (see below): * In this commit, I did not organize a folder structure. The folder structure will be organized in the next some commits. * The changes will follow the Autoware's guideline as below: - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder Signed-off-by: Junya Sasaki * rename(localization_evaluator): move headers under `include/autoware`: * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit Signed-off-by: Junya Sasaki * fix(localization_evaluator): fix include paths * To follow the previous commit Signed-off-by: Junya Sasaki * rename: `localization_evaluator` => `autoware_localization_evaluator` Signed-off-by: Junya Sasaki * style(pre-commit): autofix --------- Signed-off-by: Junya Sasaki Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../CHANGELOG.rst | 0 .../CMakeLists.txt | 17 ++++++++--------- .../README.md | 0 .../config/localization_evaluator.param.yaml | 0 .../localization_evaluator_node.hpp | 14 +++++++------- .../metrics/localization_metrics.hpp | 12 ++++++------ .../localization_evaluator/metrics/metric.hpp | 12 ++++++------ .../metrics_calculator.hpp | 16 ++++++++-------- .../localization_evaluator/parameters.hpp | 14 +++++++------- .../launch/localization_evaluator.launch.xml | 4 ++-- .../package.xml | 3 ++- .../schema/localization_evaluator.schema.json | 0 .../src/localization_evaluator_node.cpp | 10 +++++----- .../src/metrics/localization_metrics.cpp | 8 ++++---- .../src/metrics_calculator.cpp | 10 +++++----- .../test/test_localization_evaluator_node.cpp | 17 +++++++++-------- 16 files changed, 69 insertions(+), 68 deletions(-) rename evaluator/{localization_evaluator => autoware_localization_evaluator}/CHANGELOG.rst (100%) rename evaluator/{localization_evaluator => autoware_localization_evaluator}/CMakeLists.txt (67%) rename evaluator/{localization_evaluator => autoware_localization_evaluator}/README.md (100%) rename evaluator/{localization_evaluator => autoware_localization_evaluator}/config/localization_evaluator.param.yaml (100%) rename evaluator/{localization_evaluator/include => autoware_localization_evaluator/include/autoware}/localization_evaluator/localization_evaluator_node.hpp (87%) rename evaluator/{localization_evaluator/include => autoware_localization_evaluator/include/autoware}/localization_evaluator/metrics/localization_metrics.hpp (80%) rename evaluator/{localization_evaluator/include => autoware_localization_evaluator/include/autoware}/localization_evaluator/metrics/metric.hpp (85%) rename evaluator/{localization_evaluator/include => autoware_localization_evaluator/include/autoware}/localization_evaluator/metrics_calculator.hpp (74%) rename evaluator/{localization_evaluator/include => autoware_localization_evaluator/include/autoware}/localization_evaluator/parameters.hpp (67%) rename evaluator/{localization_evaluator => autoware_localization_evaluator}/launch/localization_evaluator.launch.xml (61%) rename evaluator/{localization_evaluator => autoware_localization_evaluator}/package.xml (92%) rename evaluator/{localization_evaluator => autoware_localization_evaluator}/schema/localization_evaluator.schema.json (100%) rename evaluator/{localization_evaluator => autoware_localization_evaluator}/src/localization_evaluator_node.cpp (94%) rename evaluator/{localization_evaluator => autoware_localization_evaluator}/src/metrics/localization_metrics.cpp (86%) rename evaluator/{localization_evaluator => autoware_localization_evaluator}/src/metrics_calculator.cpp (82%) rename evaluator/{localization_evaluator => autoware_localization_evaluator}/test/test_localization_evaluator_node.cpp (89%) diff --git a/evaluator/localization_evaluator/CHANGELOG.rst b/evaluator/autoware_localization_evaluator/CHANGELOG.rst similarity index 100% rename from evaluator/localization_evaluator/CHANGELOG.rst rename to evaluator/autoware_localization_evaluator/CHANGELOG.rst diff --git a/evaluator/localization_evaluator/CMakeLists.txt b/evaluator/autoware_localization_evaluator/CMakeLists.txt similarity index 67% rename from evaluator/localization_evaluator/CMakeLists.txt rename to evaluator/autoware_localization_evaluator/CMakeLists.txt index 0cdcc420eb797..f926353708e90 100644 --- a/evaluator/localization_evaluator/CMakeLists.txt +++ b/evaluator/autoware_localization_evaluator/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -project(localization_evaluator) +project(autoware_localization_evaluator) if(NOT CMAKE_CXX_STANDARD) set(CMAKE_CXX_STANDARD 14) @@ -15,26 +15,25 @@ autoware_package() find_package(ament_cmake_auto REQUIRED) ament_auto_find_build_dependencies() -ament_auto_add_library(${PROJECT_NAME}_node SHARED +ament_auto_add_library(${PROJECT_NAME} SHARED src/metrics_calculator.cpp - src/${PROJECT_NAME}_node.cpp src/localization_evaluator_node.cpp src/metrics/localization_metrics.cpp ) -rclcpp_components_register_node(${PROJECT_NAME}_node - PLUGIN "localization_diagnostics::LocalizationEvaluatorNode" - EXECUTABLE ${PROJECT_NAME} +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "autoware::localization_diagnostics::LocalizationEvaluatorNode" + EXECUTABLE ${PROJECT_NAME}_node ) if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() - ament_add_gtest(test_${PROJECT_NAME} + ament_add_gtest(test_localization_evaluator test/test_localization_evaluator_node.cpp ) - target_link_libraries(test_${PROJECT_NAME} - ${PROJECT_NAME}_node + target_link_libraries(test_localization_evaluator + ${PROJECT_NAME} ) endif() diff --git a/evaluator/localization_evaluator/README.md b/evaluator/autoware_localization_evaluator/README.md similarity index 100% rename from evaluator/localization_evaluator/README.md rename to evaluator/autoware_localization_evaluator/README.md diff --git a/evaluator/localization_evaluator/config/localization_evaluator.param.yaml b/evaluator/autoware_localization_evaluator/config/localization_evaluator.param.yaml similarity index 100% rename from evaluator/localization_evaluator/config/localization_evaluator.param.yaml rename to evaluator/autoware_localization_evaluator/config/localization_evaluator.param.yaml diff --git a/evaluator/localization_evaluator/include/localization_evaluator/localization_evaluator_node.hpp b/evaluator/autoware_localization_evaluator/include/autoware/localization_evaluator/localization_evaluator_node.hpp similarity index 87% rename from evaluator/localization_evaluator/include/localization_evaluator/localization_evaluator_node.hpp rename to evaluator/autoware_localization_evaluator/include/autoware/localization_evaluator/localization_evaluator_node.hpp index feb61dd3cacbe..99f38df4d35e1 100644 --- a/evaluator/localization_evaluator/include/localization_evaluator/localization_evaluator_node.hpp +++ b/evaluator/autoware_localization_evaluator/include/autoware/localization_evaluator/localization_evaluator_node.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2025 Tier IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef LOCALIZATION_EVALUATOR__LOCALIZATION_EVALUATOR_NODE_HPP_ -#define LOCALIZATION_EVALUATOR__LOCALIZATION_EVALUATOR_NODE_HPP_ +#ifndef AUTOWARE__LOCALIZATION_EVALUATOR__LOCALIZATION_EVALUATOR_NODE_HPP_ +#define AUTOWARE__LOCALIZATION_EVALUATOR__LOCALIZATION_EVALUATOR_NODE_HPP_ +#include "autoware/localization_evaluator/metrics_calculator.hpp" #include "autoware/universe_utils/math/accumulator.hpp" -#include "localization_evaluator/metrics_calculator.hpp" #include "rclcpp/rclcpp.hpp" #include "tf2_ros/buffer.h" #include "tf2_ros/transform_listener.h" @@ -36,7 +36,7 @@ #include #include -namespace localization_diagnostics +namespace autoware::localization_diagnostics { using autoware::universe_utils::Accumulator; using diagnostic_msgs::msg::DiagnosticArray; @@ -97,6 +97,6 @@ class LocalizationEvaluatorNode : public rclcpp::Node std::array>, static_cast(Metric::SIZE)> metric_stats_; std::unordered_map> metrics_dict_; }; -} // namespace localization_diagnostics +} // namespace autoware::localization_diagnostics -#endif // LOCALIZATION_EVALUATOR__LOCALIZATION_EVALUATOR_NODE_HPP_ +#endif // AUTOWARE__LOCALIZATION_EVALUATOR__LOCALIZATION_EVALUATOR_NODE_HPP_ diff --git a/evaluator/localization_evaluator/include/localization_evaluator/metrics/localization_metrics.hpp b/evaluator/autoware_localization_evaluator/include/autoware/localization_evaluator/metrics/localization_metrics.hpp similarity index 80% rename from evaluator/localization_evaluator/include/localization_evaluator/metrics/localization_metrics.hpp rename to evaluator/autoware_localization_evaluator/include/autoware/localization_evaluator/metrics/localization_metrics.hpp index 82119efca6082..78b9e446f7cce 100644 --- a/evaluator/localization_evaluator/include/localization_evaluator/metrics/localization_metrics.hpp +++ b/evaluator/autoware_localization_evaluator/include/autoware/localization_evaluator/metrics/localization_metrics.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2025 Tier IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef LOCALIZATION_EVALUATOR__METRICS__LOCALIZATION_METRICS_HPP_ -#define LOCALIZATION_EVALUATOR__METRICS__LOCALIZATION_METRICS_HPP_ +#ifndef AUTOWARE__LOCALIZATION_EVALUATOR__METRICS__LOCALIZATION_METRICS_HPP_ +#define AUTOWARE__LOCALIZATION_EVALUATOR__METRICS__LOCALIZATION_METRICS_HPP_ #include "autoware/universe_utils/math/accumulator.hpp" #include -namespace localization_diagnostics +namespace autoware::localization_diagnostics { using autoware::universe_utils::Accumulator; namespace metrics @@ -46,6 +46,6 @@ Accumulator updateAbsoluteStats( const geometry_msgs::msg::Point & pos_ref); } // namespace metrics -} // namespace localization_diagnostics +} // namespace autoware::localization_diagnostics -#endif // LOCALIZATION_EVALUATOR__METRICS__LOCALIZATION_METRICS_HPP_ +#endif // AUTOWARE__LOCALIZATION_EVALUATOR__METRICS__LOCALIZATION_METRICS_HPP_ diff --git a/evaluator/localization_evaluator/include/localization_evaluator/metrics/metric.hpp b/evaluator/autoware_localization_evaluator/include/autoware/localization_evaluator/metrics/metric.hpp similarity index 85% rename from evaluator/localization_evaluator/include/localization_evaluator/metrics/metric.hpp rename to evaluator/autoware_localization_evaluator/include/autoware/localization_evaluator/metrics/metric.hpp index dfe1a538a3488..0d791d6e2365a 100644 --- a/evaluator/localization_evaluator/include/localization_evaluator/metrics/metric.hpp +++ b/evaluator/autoware_localization_evaluator/include/autoware/localization_evaluator/metrics/metric.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2025 Tier IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef LOCALIZATION_EVALUATOR__METRICS__METRIC_HPP_ -#define LOCALIZATION_EVALUATOR__METRICS__METRIC_HPP_ +#ifndef AUTOWARE__LOCALIZATION_EVALUATOR__METRICS__METRIC_HPP_ +#define AUTOWARE__LOCALIZATION_EVALUATOR__METRICS__METRIC_HPP_ #include #include #include #include -namespace localization_diagnostics +namespace autoware::localization_diagnostics { /** * @brief Enumeration of localization metrics @@ -58,6 +58,6 @@ static struct CheckCorrectMaps } check; } // namespace details -} // namespace localization_diagnostics +} // namespace autoware::localization_diagnostics -#endif // LOCALIZATION_EVALUATOR__METRICS__METRIC_HPP_ +#endif // AUTOWARE__LOCALIZATION_EVALUATOR__METRICS__METRIC_HPP_ diff --git a/evaluator/localization_evaluator/include/localization_evaluator/metrics_calculator.hpp b/evaluator/autoware_localization_evaluator/include/autoware/localization_evaluator/metrics_calculator.hpp similarity index 74% rename from evaluator/localization_evaluator/include/localization_evaluator/metrics_calculator.hpp rename to evaluator/autoware_localization_evaluator/include/autoware/localization_evaluator/metrics_calculator.hpp index 310d1b25e92f1..6fb86dc9e8d7b 100644 --- a/evaluator/localization_evaluator/include/localization_evaluator/metrics_calculator.hpp +++ b/evaluator/autoware_localization_evaluator/include/autoware/localization_evaluator/metrics_calculator.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2025 Tier IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,17 +12,17 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef LOCALIZATION_EVALUATOR__METRICS_CALCULATOR_HPP_ -#define LOCALIZATION_EVALUATOR__METRICS_CALCULATOR_HPP_ +#ifndef AUTOWARE__LOCALIZATION_EVALUATOR__METRICS_CALCULATOR_HPP_ +#define AUTOWARE__LOCALIZATION_EVALUATOR__METRICS_CALCULATOR_HPP_ +#include "autoware/localization_evaluator/metrics/metric.hpp" +#include "autoware/localization_evaluator/parameters.hpp" #include "autoware/universe_utils/math/accumulator.hpp" -#include "localization_evaluator/metrics/metric.hpp" -#include "localization_evaluator/parameters.hpp" #include "geometry_msgs/msg/pose.hpp" #include -namespace localization_diagnostics +namespace autoware::localization_diagnostics { using autoware::universe_utils::Accumulator; class MetricsCalculator @@ -44,6 +44,6 @@ class MetricsCalculator const geometry_msgs::msg::Point & pos_ref) const; }; // class MetricsCalculator -} // namespace localization_diagnostics +} // namespace autoware::localization_diagnostics -#endif // LOCALIZATION_EVALUATOR__METRICS_CALCULATOR_HPP_ +#endif // AUTOWARE__LOCALIZATION_EVALUATOR__METRICS_CALCULATOR_HPP_ diff --git a/evaluator/localization_evaluator/include/localization_evaluator/parameters.hpp b/evaluator/autoware_localization_evaluator/include/autoware/localization_evaluator/parameters.hpp similarity index 67% rename from evaluator/localization_evaluator/include/localization_evaluator/parameters.hpp rename to evaluator/autoware_localization_evaluator/include/autoware/localization_evaluator/parameters.hpp index d8328fe62b3ed..20b530ea272e6 100644 --- a/evaluator/localization_evaluator/include/localization_evaluator/parameters.hpp +++ b/evaluator/autoware_localization_evaluator/include/autoware/localization_evaluator/parameters.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2025 Tier IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef LOCALIZATION_EVALUATOR__PARAMETERS_HPP_ -#define LOCALIZATION_EVALUATOR__PARAMETERS_HPP_ +#ifndef AUTOWARE__LOCALIZATION_EVALUATOR__PARAMETERS_HPP_ +#define AUTOWARE__LOCALIZATION_EVALUATOR__PARAMETERS_HPP_ -#include "localization_evaluator/metrics/metric.hpp" +#include "autoware/localization_evaluator/metrics/metric.hpp" #include -namespace localization_diagnostics +namespace autoware::localization_diagnostics { /** * @brief Enumeration of trajectory metrics @@ -29,6 +29,6 @@ struct Parameters std::array(Metric::SIZE)> metrics{}; // default values to false }; // struct Parameters -} // namespace localization_diagnostics +} // namespace autoware::localization_diagnostics -#endif // LOCALIZATION_EVALUATOR__PARAMETERS_HPP_ +#endif // AUTOWARE__LOCALIZATION_EVALUATOR__PARAMETERS_HPP_ diff --git a/evaluator/localization_evaluator/launch/localization_evaluator.launch.xml b/evaluator/autoware_localization_evaluator/launch/localization_evaluator.launch.xml similarity index 61% rename from evaluator/localization_evaluator/launch/localization_evaluator.launch.xml rename to evaluator/autoware_localization_evaluator/launch/localization_evaluator.launch.xml index f8595f9d23c37..6a20c6ddc8583 100644 --- a/evaluator/localization_evaluator/launch/localization_evaluator.launch.xml +++ b/evaluator/autoware_localization_evaluator/launch/localization_evaluator.launch.xml @@ -2,8 +2,8 @@ - - + + diff --git a/evaluator/localization_evaluator/package.xml b/evaluator/autoware_localization_evaluator/package.xml similarity index 92% rename from evaluator/localization_evaluator/package.xml rename to evaluator/autoware_localization_evaluator/package.xml index 7058064f17b72..e5b0f3f7ffe20 100644 --- a/evaluator/localization_evaluator/package.xml +++ b/evaluator/autoware_localization_evaluator/package.xml @@ -1,6 +1,6 @@ - localization_evaluator + autoware_localization_evaluator 0.40.0 localization evaluator ROS 2 node @@ -11,6 +11,7 @@ Shintaro Sakoda Taiki Yamada Yamato Ando + Junya Sasaki Apache License 2.0 diff --git a/evaluator/localization_evaluator/schema/localization_evaluator.schema.json b/evaluator/autoware_localization_evaluator/schema/localization_evaluator.schema.json similarity index 100% rename from evaluator/localization_evaluator/schema/localization_evaluator.schema.json rename to evaluator/autoware_localization_evaluator/schema/localization_evaluator.schema.json diff --git a/evaluator/localization_evaluator/src/localization_evaluator_node.cpp b/evaluator/autoware_localization_evaluator/src/localization_evaluator_node.cpp similarity index 94% rename from evaluator/localization_evaluator/src/localization_evaluator_node.cpp rename to evaluator/autoware_localization_evaluator/src/localization_evaluator_node.cpp index 8a9352d2a73e8..eedfd6f955b88 100644 --- a/evaluator/localization_evaluator/src/localization_evaluator_node.cpp +++ b/evaluator/autoware_localization_evaluator/src/localization_evaluator_node.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2025 Tier IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "localization_evaluator/localization_evaluator_node.hpp" +#include "autoware/localization_evaluator/localization_evaluator_node.hpp" #include "boost/lexical_cast.hpp" @@ -23,7 +23,7 @@ #include #include -namespace localization_diagnostics +namespace autoware::localization_diagnostics { LocalizationEvaluatorNode::LocalizationEvaluatorNode(const rclcpp::NodeOptions & node_options) : Node("localization_evaluator", node_options), @@ -134,7 +134,7 @@ void LocalizationEvaluatorNode::syncCallback( metrics_pub_->publish(metrics_msg); } } -} // namespace localization_diagnostics +} // namespace autoware::localization_diagnostics #include "rclcpp_components/register_node_macro.hpp" -RCLCPP_COMPONENTS_REGISTER_NODE(localization_diagnostics::LocalizationEvaluatorNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::localization_diagnostics::LocalizationEvaluatorNode) diff --git a/evaluator/localization_evaluator/src/metrics/localization_metrics.cpp b/evaluator/autoware_localization_evaluator/src/metrics/localization_metrics.cpp similarity index 86% rename from evaluator/localization_evaluator/src/metrics/localization_metrics.cpp rename to evaluator/autoware_localization_evaluator/src/metrics/localization_metrics.cpp index 97fd8e326cca7..00673f5883069 100644 --- a/evaluator/localization_evaluator/src/metrics/localization_metrics.cpp +++ b/evaluator/autoware_localization_evaluator/src/metrics/localization_metrics.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2025 Tier IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "localization_evaluator/metrics/localization_metrics.hpp" +#include "autoware/localization_evaluator/metrics/localization_metrics.hpp" #include -namespace localization_diagnostics +namespace autoware::localization_diagnostics { namespace metrics { @@ -43,4 +43,4 @@ Accumulator updateAbsoluteStats( } } // namespace metrics -} // namespace localization_diagnostics +} // namespace autoware::localization_diagnostics diff --git a/evaluator/localization_evaluator/src/metrics_calculator.cpp b/evaluator/autoware_localization_evaluator/src/metrics_calculator.cpp similarity index 82% rename from evaluator/localization_evaluator/src/metrics_calculator.cpp rename to evaluator/autoware_localization_evaluator/src/metrics_calculator.cpp index 864fb4a5ddbd2..887a042a22403 100644 --- a/evaluator/localization_evaluator/src/metrics_calculator.cpp +++ b/evaluator/autoware_localization_evaluator/src/metrics_calculator.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2025 Tier IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "localization_evaluator/metrics_calculator.hpp" +#include "autoware/localization_evaluator/metrics_calculator.hpp" -#include "localization_evaluator/metrics/localization_metrics.hpp" +#include "autoware/localization_evaluator/metrics/localization_metrics.hpp" -namespace localization_diagnostics +namespace autoware::localization_diagnostics { Accumulator MetricsCalculator::updateStat( const Accumulator stat_prev, const Metric metric, const geometry_msgs::msg::Point & pos, @@ -39,4 +39,4 @@ Accumulator MetricsCalculator::updateStat( } } -} // namespace localization_diagnostics +} // namespace autoware::localization_diagnostics diff --git a/evaluator/localization_evaluator/test/test_localization_evaluator_node.cpp b/evaluator/autoware_localization_evaluator/test/test_localization_evaluator_node.cpp similarity index 89% rename from evaluator/localization_evaluator/test/test_localization_evaluator_node.cpp rename to evaluator/autoware_localization_evaluator/test/test_localization_evaluator_node.cpp index 6ab428c6fb578..43367ff4ee6f1 100644 --- a/evaluator/localization_evaluator/test/test_localization_evaluator_node.cpp +++ b/evaluator/autoware_localization_evaluator/test/test_localization_evaluator_node.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2025 Tier IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -18,7 +18,7 @@ #include "rclcpp/time.hpp" #include "tf2_ros/transform_broadcaster.h" -#include +#include #include "diagnostic_msgs/msg/diagnostic_array.hpp" #include "geometry_msgs/msg/pose_with_covariance_stamped.hpp" @@ -33,7 +33,7 @@ #include #include -using EvalNode = localization_diagnostics::LocalizationEvaluatorNode; +using EvalNode = autoware::localization_diagnostics::LocalizationEvaluatorNode; using diagnostic_msgs::msg::DiagnosticArray; using geometry_msgs::msg::PoseWithCovarianceStamped; using nav_msgs::msg::Odometry; @@ -46,7 +46,8 @@ class EvalTest : public ::testing::Test rclcpp::init(0, nullptr); rclcpp::NodeOptions options; - const auto share_dir = ament_index_cpp::get_package_share_directory("localization_evaluator"); + const auto share_dir = + ament_index_cpp::get_package_share_directory("autoware_localization_evaluator"); options.arguments( {"--ros-args", "--params-file", share_dir + "/config/localization_evaluator.param.yaml"}); @@ -74,9 +75,9 @@ class EvalTest : public ::testing::Test ~EvalTest() override { rclcpp::shutdown(); } - void setTargetMetric(localization_diagnostics::Metric metric) + void setTargetMetric(autoware::localization_diagnostics::Metric metric) { - const auto metric_str = localization_diagnostics::metric_to_str.at(metric); + const auto metric_str = autoware::localization_diagnostics::metric_to_str.at(metric); const auto is_target_metric = [metric_str](const auto & status) { return status.name == metric_str; }; @@ -141,7 +142,7 @@ class EvalTest : public ::testing::Test TEST_F(EvalTest, TestLateralErrorStats) { - setTargetMetric(localization_diagnostics::Metric::lateral_error); + setTargetMetric(autoware::localization_diagnostics::Metric::lateral_error); Odometry odom = makeOdometry(1.0, 1.0, 0.0); PoseWithCovarianceStamped pos_ref = makePos(4.0, 5.0, 0.0); EXPECT_DOUBLE_EQ(publishOdometryAndGetMetric(odom, pos_ref), 3.0); @@ -152,7 +153,7 @@ TEST_F(EvalTest, TestLateralErrorStats) TEST_F(EvalTest, TestAbsoluteErrorStats) { - setTargetMetric(localization_diagnostics::Metric::absolute_error); + setTargetMetric(autoware::localization_diagnostics::Metric::absolute_error); Odometry odom = makeOdometry(1.0, 1.0, 0.0); PoseWithCovarianceStamped pos_ref = makePos(4.0, 5.0, 0.0); EXPECT_DOUBLE_EQ(publishOdometryAndGetMetric(odom, pos_ref), 5.0); From ae436b380914dd6c7cd60b28a35c0026a79e000f Mon Sep 17 00:00:00 2001 From: TetsuKawa <70682030+TetsuKawa@users.noreply.github.com> Date: Mon, 20 Jan 2025 14:34:48 +0900 Subject: [PATCH 254/334] feat(dummy_diag_publisher): update param setting (#9946) * feat: update param setting Signed-off-by: TetsuKawa * style(pre-commit): autofix * modify: delete unnecessary include Signed-off-by: TetsuKawa --------- Signed-off-by: TetsuKawa Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../dummy_diag_publisher_core.hpp | 6 +- system/dummy_diag_publisher/package.xml | 3 +- .../src/dummy_diag_publisher_core.cpp | 63 ++++++++++++++++++- 3 files changed, 68 insertions(+), 4 deletions(-) diff --git a/system/dummy_diag_publisher/include/dummy_diag_publisher/dummy_diag_publisher_core.hpp b/system/dummy_diag_publisher/include/dummy_diag_publisher/dummy_diag_publisher_core.hpp index bbca397fb47ec..64e2e0426046d 100644 --- a/system/dummy_diag_publisher/include/dummy_diag_publisher/dummy_diag_publisher_core.hpp +++ b/system/dummy_diag_publisher/include/dummy_diag_publisher/dummy_diag_publisher_core.hpp @@ -60,9 +60,13 @@ class DummyDiagPublisher : public rclcpp::Node DummyDiagConfig config_; RequiredDiags required_diags_; + rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr param_callback_handle_; + void loadRequiredDiags(); + rcl_interfaces::msg::SetParametersResult onSetParams( + const std::vector & parameters); - std::optional convertStrToStatus(std::string & status_str); + std::optional convertStrToStatus(const std::string & status_str); std::string convertStatusToStr(const Status & status); diagnostic_msgs::msg::DiagnosticStatus::_level_type convertStatusToLevel(const Status & status); diff --git a/system/dummy_diag_publisher/package.xml b/system/dummy_diag_publisher/package.xml index 56faf31413e77..e6b0302216e14 100644 --- a/system/dummy_diag_publisher/package.xml +++ b/system/dummy_diag_publisher/package.xml @@ -11,8 +11,7 @@ ament_cmake_auto autoware_cmake - autoware_universe_utils - diagnostic_updater + diagnostic_msgs fmt rclcpp rclcpp_components diff --git a/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp b/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp index 6bc1378507a37..5d0e4ee0316cf 100644 --- a/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp +++ b/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp @@ -22,6 +22,8 @@ #define FMT_HEADER_ONLY #include +#include + namespace { std::vector split(const std::string & str, const char delim) @@ -37,7 +39,7 @@ std::vector split(const std::string & str, const char delim) } // namespace std::optional DummyDiagPublisher::convertStrToStatus( - std::string & status_str) + const std::string & status_str) { static std::unordered_map const table = { {"OK", Status::OK}, {"Warn", Status::WARN}, {"Error", Status::ERROR}, {"Stale", Status::STALE}}; @@ -144,6 +146,61 @@ rclcpp::NodeOptions override_options(rclcpp::NodeOptions options) true); } +rcl_interfaces::msg::SetParametersResult DummyDiagPublisher::onSetParams( + const std::vector & parameters) +{ + rcl_interfaces::msg::SetParametersResult result; + result.successful = true; + + for (const auto & parameter : parameters) { + bool param_found = false; + const auto & param_name = parameter.get_name(); + + for (auto & diag : required_diags_) { + if (param_name == diag.name + std::string(".status")) { + param_found = true; + auto new_status = convertStrToStatus(parameter.as_string()); + if (new_status) { + diag.status = *new_status; + RCLCPP_INFO( + this->get_logger(), "Updated %s status to: %s", diag.name.c_str(), + parameter.as_string().c_str()); + } else { + result.successful = false; + result.reason = "Invalid status value for: " + parameter.as_string(); + RCLCPP_WARN( + this->get_logger(), "Invalid status value for %s: %s", diag.name.c_str(), + parameter.as_string().c_str()); + } + } else if (param_name == diag.name + std::string(".is_active")) { + param_found = true; + try { + diag.is_active = parameter.as_bool(); + RCLCPP_INFO( + this->get_logger(), "Updated %s is_active to: %s", diag.name.c_str(), + diag.is_active ? "true" : "false"); + } catch (const rclcpp::ParameterTypeException & e) { + result.successful = false; + result.reason = "Invalid is_active value for: " + parameter.as_string(); + RCLCPP_WARN( + this->get_logger(), "Invalid is_active value for %s: %s", diag.name.c_str(), + parameter.as_string().c_str()); + } + } + } + + if (!param_found) { + result.successful = false; + result.reason = "Parameter not registered: " + parameter.get_name(); + RCLCPP_WARN( + this->get_logger(), "Attempted to set unregistered parameter: %s", + parameter.get_name().c_str()); + } + } + + return result; +} + DummyDiagPublisher::DummyDiagPublisher(const rclcpp::NodeOptions & options) : Node("dummy_diag_publisher", override_options(options)) @@ -164,6 +221,10 @@ DummyDiagPublisher::DummyDiagPublisher(const rclcpp::NodeOptions & options) // Publisher pub_ = create_publisher("/diagnostics", rclcpp::QoS(1)); + + // Parameter Callback Handle + param_callback_handle_ = this->add_on_set_parameters_callback( + std::bind(&DummyDiagPublisher::onSetParams, this, std::placeholders::_1)); } #include From 51c7ffc95762280a98e38528396557f2c418251b Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Mon, 20 Jan 2025 17:50:31 +0900 Subject: [PATCH 255/334] fix(autoware_lidar_marker_localization): fix segmentation fault (#8943) * fix segmentation fault Signed-off-by: Yamato Ando * style(pre-commit): autofix --------- Signed-off-by: Yamato Ando Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../src/lidar_marker_localizer.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.cpp b/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.cpp index 34fc61797231b..5a43253964154 100644 --- a/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.cpp +++ b/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.cpp @@ -362,6 +362,12 @@ std::vector LidarMarkerLocalizer::detect_landmarks( // Check that the leaf size is not too small, given the size of the data const int bin_num = static_cast((max_x - min_x) / param_.resolution + 1); + if (bin_num < static_cast(param_.intensity_pattern.size())) { + RCLCPP_WARN_STREAM_THROTTLE( + this->get_logger(), *this->get_clock(), 1000, "bin_num is too small!"); + return std::vector{}; + } + // initialize variables std::vector vote(bin_num, 0); std::vector min_y(bin_num, std::numeric_limits::max()); From 037c315fbee69bb5923ec10bb8e8e70f890725ea Mon Sep 17 00:00:00 2001 From: Motz Date: Mon, 20 Jan 2025 20:58:35 +0900 Subject: [PATCH 256/334] feat(autoware_ekf_localizer)!: porting from universe to core (#9978) * feat: delete ekf_localizer files Signed-off-by: Motsu-san * doc: Modify ekf_localizer directory links Signed-off-by: Motsu-san * ci: remove ekf_localizer from the codecov target list Signed-off-by: Motsu-san --------- Signed-off-by: Motsu-san --- codecov.yaml | 1 - .../autoware_ekf_localizer/CHANGELOG.rst | 63 --- .../autoware_ekf_localizer/CMakeLists.txt | 82 ---- localization/autoware_ekf_localizer/README.md | 211 -------- .../config/ekf_localizer.param.yaml | 50 -- .../ekf_localizer/aged_object_queue.hpp | 71 --- .../autoware/ekf_localizer/covariance.hpp | 28 -- .../autoware/ekf_localizer/diagnostics.hpp | 49 -- .../autoware/ekf_localizer/ekf_localizer.hpp | 199 -------- .../autoware/ekf_localizer/ekf_module.hpp | 156 ------ .../ekf_localizer/hyper_parameters.hpp | 108 ---- .../autoware/ekf_localizer/mahalanobis.hpp | 31 -- .../autoware/ekf_localizer/matrix_types.hpp | 28 -- .../autoware/ekf_localizer/measurement.hpp | 32 -- .../autoware/ekf_localizer/numeric.hpp | 37 -- .../autoware/ekf_localizer/state_index.hpp | 32 -- .../ekf_localizer/state_transition.hpp | 31 -- .../include/autoware/ekf_localizer/string.hpp | 34 -- .../autoware/ekf_localizer/warning.hpp | 48 -- .../ekf_localizer/warning_message.hpp | 33 -- .../launch/ekf_localizer.launch.xml | 40 -- .../media/calculation_delta_from_pitch.png | Bin 56991 -> 0 bytes .../media/delay_model_eq.png | Bin 4906 -> 0 bytes .../media/ekf_autoware_res.png | Bin 69064 -> 0 bytes .../media/ekf_delay_comp.png | Bin 147442 -> 0 bytes .../media/ekf_diagnostics.png | Bin 145097 -> 0 bytes .../media/ekf_diagnostics_callback_pose.png | Bin 17825 -> 0 bytes .../media/ekf_diagnostics_callback_twist.png | Bin 17945 -> 0 bytes .../media/ekf_dynamics.png | Bin 5346 -> 0 bytes .../media/ekf_flowchart.png | Bin 146302 -> 0 bytes .../media/ekf_smooth_update.png | Bin 146470 -> 0 bytes .../autoware_ekf_localizer/package.xml | 47 -- .../schema/ekf_localizer.schema.json | 52 -- .../schema/sub/diagnostics.sub_schema.json | 63 --- .../schema/sub/misc.sub_schema.json | 23 - .../schema/sub/node.sub_schema.json | 44 -- .../sub/pose_measurement.sub_schema.json | 38 -- .../schema/sub/process_noise.sub_schema.json | 28 -- ...imple_1d_filter_parameters.sub_schema.json | 28 -- .../sub/twist_measurement.sub_schema.json | 28 -- .../autoware_ekf_localizer/src/covariance.cpp | 56 --- .../src/diagnostics.cpp | 226 --------- .../src/ekf_localizer.cpp | 463 ------------------ .../autoware_ekf_localizer/src/ekf_module.cpp | 459 ----------------- .../src/mahalanobis.cpp | 32 -- .../src/measurement.cpp | 61 --- .../src/state_transition.cpp | 102 ---- .../src/warning_message.cpp | 60 --- .../test/test_aged_object_queue.cpp | 108 ---- .../test/test_covariance.cpp | 84 ---- .../test/test_diagnostics.cpp | 213 -------- .../test/test_ekf_localizer_launch.py | 170 ------- .../test/test_ekf_localizer_mahalanobis.py | 229 --------- .../test/test_mahalanobis.cpp | 66 --- .../test/test_measurement.cpp | 86 ---- .../test/test_numeric.cpp | 54 -- .../test/test_state_transition.cpp | 101 ---- .../test/test_string.cpp | 31 -- .../test/test_warning_message.cpp | 67 --- .../README.md | 4 +- 60 files changed, 2 insertions(+), 4385 deletions(-) delete mode 100644 localization/autoware_ekf_localizer/CHANGELOG.rst delete mode 100644 localization/autoware_ekf_localizer/CMakeLists.txt delete mode 100644 localization/autoware_ekf_localizer/README.md delete mode 100644 localization/autoware_ekf_localizer/config/ekf_localizer.param.yaml delete mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/aged_object_queue.hpp delete mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/covariance.hpp delete mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/diagnostics.hpp delete mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_localizer.hpp delete mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_module.hpp delete mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/hyper_parameters.hpp delete mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/mahalanobis.hpp delete mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/matrix_types.hpp delete mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/measurement.hpp delete mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/numeric.hpp delete mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/state_index.hpp delete mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/state_transition.hpp delete mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/string.hpp delete mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/warning.hpp delete mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/warning_message.hpp delete mode 100644 localization/autoware_ekf_localizer/launch/ekf_localizer.launch.xml delete mode 100644 localization/autoware_ekf_localizer/media/calculation_delta_from_pitch.png delete mode 100644 localization/autoware_ekf_localizer/media/delay_model_eq.png delete mode 100644 localization/autoware_ekf_localizer/media/ekf_autoware_res.png delete mode 100644 localization/autoware_ekf_localizer/media/ekf_delay_comp.png delete mode 100644 localization/autoware_ekf_localizer/media/ekf_diagnostics.png delete mode 100644 localization/autoware_ekf_localizer/media/ekf_diagnostics_callback_pose.png delete mode 100644 localization/autoware_ekf_localizer/media/ekf_diagnostics_callback_twist.png delete mode 100644 localization/autoware_ekf_localizer/media/ekf_dynamics.png delete mode 100644 localization/autoware_ekf_localizer/media/ekf_flowchart.png delete mode 100644 localization/autoware_ekf_localizer/media/ekf_smooth_update.png delete mode 100644 localization/autoware_ekf_localizer/package.xml delete mode 100644 localization/autoware_ekf_localizer/schema/ekf_localizer.schema.json delete mode 100644 localization/autoware_ekf_localizer/schema/sub/diagnostics.sub_schema.json delete mode 100644 localization/autoware_ekf_localizer/schema/sub/misc.sub_schema.json delete mode 100644 localization/autoware_ekf_localizer/schema/sub/node.sub_schema.json delete mode 100644 localization/autoware_ekf_localizer/schema/sub/pose_measurement.sub_schema.json delete mode 100644 localization/autoware_ekf_localizer/schema/sub/process_noise.sub_schema.json delete mode 100644 localization/autoware_ekf_localizer/schema/sub/simple_1d_filter_parameters.sub_schema.json delete mode 100644 localization/autoware_ekf_localizer/schema/sub/twist_measurement.sub_schema.json delete mode 100644 localization/autoware_ekf_localizer/src/covariance.cpp delete mode 100644 localization/autoware_ekf_localizer/src/diagnostics.cpp delete mode 100644 localization/autoware_ekf_localizer/src/ekf_localizer.cpp delete mode 100644 localization/autoware_ekf_localizer/src/ekf_module.cpp delete mode 100644 localization/autoware_ekf_localizer/src/mahalanobis.cpp delete mode 100644 localization/autoware_ekf_localizer/src/measurement.cpp delete mode 100644 localization/autoware_ekf_localizer/src/state_transition.cpp delete mode 100644 localization/autoware_ekf_localizer/src/warning_message.cpp delete mode 100644 localization/autoware_ekf_localizer/test/test_aged_object_queue.cpp delete mode 100644 localization/autoware_ekf_localizer/test/test_covariance.cpp delete mode 100644 localization/autoware_ekf_localizer/test/test_diagnostics.cpp delete mode 100644 localization/autoware_ekf_localizer/test/test_ekf_localizer_launch.py delete mode 100644 localization/autoware_ekf_localizer/test/test_ekf_localizer_mahalanobis.py delete mode 100644 localization/autoware_ekf_localizer/test/test_mahalanobis.cpp delete mode 100644 localization/autoware_ekf_localizer/test/test_measurement.cpp delete mode 100644 localization/autoware_ekf_localizer/test/test_numeric.cpp delete mode 100644 localization/autoware_ekf_localizer/test/test_state_transition.cpp delete mode 100644 localization/autoware_ekf_localizer/test/test_string.cpp delete mode 100644 localization/autoware_ekf_localizer/test/test_warning_message.cpp diff --git a/codecov.yaml b/codecov.yaml index 7bec89dd5a552..726b675d7ff1d 100644 --- a/codecov.yaml +++ b/codecov.yaml @@ -122,7 +122,6 @@ component_management: - component_id: localization-tier-iv-maintained-packages name: Localization TIER IV Maintained Packages paths: - - localization/autoware_ekf_localizer/** - localization/autoware_gyro_odometer/** - localization/autoware_localization_error_monitor/** - localization/autoware_localization_util/** diff --git a/localization/autoware_ekf_localizer/CHANGELOG.rst b/localization/autoware_ekf_localizer/CHANGELOG.rst deleted file mode 100644 index b8e74c530e059..0000000000000 --- a/localization/autoware_ekf_localizer/CHANGELOG.rst +++ /dev/null @@ -1,63 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package autoware_ekf_localizer -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -0.40.0 (2024-12-12) -------------------- -* Merge branch 'main' into release-0.40.0 -* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" - This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. -* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) -* chore(package.xml): bump version to 0.39.0 (`#9587 `_) - * chore(package.xml): bump version to 0.39.0 - * fix: fix ticket links in CHANGELOG.rst - * fix: remove unnecessary diff - --------- - Co-authored-by: Yutaka Kondo -* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) -* fix(cpplint): include what you use - localization (`#9567 `_) -* fix(autoware_ekf_localizer): publish `processing_time_ms` (`#9443 `_) - Fixed to publish processing_time_ms -* 0.39.0 -* update changelog -* Merge commit '6a1ddbd08bd' into release-0.39.0 -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) - * unify package.xml version to 0.37.0 - * remove system_monitor/CHANGELOG.rst - * add changelog - * 0.38.0 - --------- -* fix(autoware_ekf_localizer): remove `timer_tf\_` (`#9244 `_) - Removed timer_tf\_ -* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, SakodaShintaro, Yutaka Kondo - -0.39.0 (2024-11-25) -------------------- -* Merge commit '6a1ddbd08bd' into release-0.39.0 -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) -* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) - * unify package.xml version to 0.37.0 - * remove system_monitor/CHANGELOG.rst - * add changelog - * 0.38.0 - --------- -* fix(autoware_ekf_localizer): remove `timer_tf\_` (`#9244 `_) - Removed timer_tf\_ -* Contributors: Esteve Fernandez, SakodaShintaro, Yutaka Kondo - -0.38.0 (2024-11-08) -------------------- -* unify package.xml version to 0.37.0 -* refactor(localization_util)!: prefix package and namespace with autoware (`#8922 `_) - add autoware prefix to localization_util -* refactor(ekf_localizer)!: prefix package and namespace with autoware (`#8888 `_) - * import lanelet2_map_preprocessor - * move headers to include/autoware/efk_localier - --------- -* Contributors: Masaki Baba, Yutaka Kondo - -0.26.0 (2024-04-03) -------------------- diff --git a/localization/autoware_ekf_localizer/CMakeLists.txt b/localization/autoware_ekf_localizer/CMakeLists.txt deleted file mode 100644 index 6ace0b413d7a6..0000000000000 --- a/localization/autoware_ekf_localizer/CMakeLists.txt +++ /dev/null @@ -1,82 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(autoware_ekf_localizer) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -find_package(Eigen3 REQUIRED) - -include_directories( - SYSTEM - ${EIGEN3_INCLUDE_DIR} -) - -ament_auto_find_build_dependencies() - -ament_auto_add_library(${PROJECT_NAME} SHARED - src/ekf_localizer.cpp - src/covariance.cpp - src/diagnostics.cpp - src/mahalanobis.cpp - src/measurement.cpp - src/state_transition.cpp - src/warning_message.cpp - src/ekf_module.cpp -) - -rclcpp_components_register_node(${PROJECT_NAME} - PLUGIN "autoware::ekf_localizer::EKFLocalizer" - EXECUTABLE ${PROJECT_NAME}_node - EXECUTOR SingleThreadedExecutor -) - -target_link_libraries(${PROJECT_NAME} Eigen3::Eigen) - -function(add_testcase filepath) - get_filename_component(filename ${filepath} NAME) - string(REGEX REPLACE ".cpp" "" test_name ${filename}) - - ament_add_gtest(${test_name} ${filepath}) - target_link_libraries("${test_name}" ${PROJECT_NAME}) - ament_target_dependencies(${test_name} ${${PROJECT_NAME}_FOUND_BUILD_DEPENDS}) -endfunction() - -if(BUILD_TESTING) - add_launch_test( - test/test_ekf_localizer_launch.py - TIMEOUT "30" - ) - add_launch_test( - test/test_ekf_localizer_mahalanobis.py - TIMEOUT "30" - ) - find_package(ament_cmake_gtest REQUIRED) - - file(GLOB_RECURSE TEST_FILES test/*.cpp) - - foreach(filepath ${TEST_FILES}) - add_testcase(${filepath}) - endforeach() -endif() - - -# if(BUILD_TESTING) -# 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 -# src/kalman_filter/time_delay_kalman_filter.cpp -# ) -# target_include_directories(ekf_localizer-test -# PRIVATE -# include -# ) -# ament_target_dependencies(ekf_localizer-test geometry_msgs rclcpp tf2 tf2_ros) -# endif() - -ament_auto_package( - INSTALL_TO_SHARE - config - launch -) diff --git a/localization/autoware_ekf_localizer/README.md b/localization/autoware_ekf_localizer/README.md deleted file mode 100644 index a46ea7181315f..0000000000000 --- a/localization/autoware_ekf_localizer/README.md +++ /dev/null @@ -1,211 +0,0 @@ -# Overview - -The **Extend Kalman Filter Localizer** estimates robust and less noisy robot pose and twist by integrating the 2D vehicle dynamics model with input ego-pose and ego-twist messages. The algorithm is designed especially for fast-moving robots such as autonomous driving systems. - -## Flowchart - -The overall flowchart of the autoware_ekf_localizer is described below. - -

- -

- -## Features - -This package includes the following features: - -- **Time delay compensation** for input messages, which enables proper integration of input information with varying time delays. This is important especially for high-speed moving robots, such as autonomous driving vehicles. (see the following figure). -- **Automatic estimation of yaw bias** prevents modeling errors caused by sensor mounting angle errors, which can improve estimation accuracy. -- **Mahalanobis distance gate** enables probabilistic outlier detection to determine which inputs should be used or ignored. -- **Smooth update**, the Kalman Filter measurement update is typically performed when a measurement is obtained, but it can cause large changes in the estimated value, especially for low-frequency measurements. Since the algorithm can consider the measurement time, the measurement data can be divided into multiple pieces and integrated smoothly while maintaining consistency (see the following figure). -- **Calculation of vertical correction amount from pitch** mitigates localization instability on slopes. For example, when going uphill, it behaves as if it is buried in the ground (see the left side of the "Calculate delta from pitch" figure) because EKF only considers 3DoF(x,y,yaw). Therefore, EKF corrects the z-coordinate according to the formula (see the right side of the "Calculate delta from pitch" figure). - -

- -

- -

- -

- -

- -

- -## Node - -### Subscribed Topics - -| Name | Type | Description | -| -------------------------------- | ------------------------------------------------ | ---------------------------------------------------------------------------------------------------------------------------------------- | -| `measured_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Input pose source with the measurement covariance matrix. | -| `measured_twist_with_covariance` | `geometry_msgs::msg::TwistWithCovarianceStamped` | Input twist source with the measurement covariance matrix. | -| `initialpose` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Initial pose for EKF. The estimated pose is initialized with zeros at the start. It is initialized with this message whenever published. | - -### Published Topics - -| Name | Type | Description | -| --------------------------------- | --------------------------------------------------- | ----------------------------------------------------- | -| `ekf_odom` | `nav_msgs::msg::Odometry` | Estimated odometry. | -| `ekf_pose` | `geometry_msgs::msg::PoseStamped` | Estimated pose. | -| `ekf_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Estimated pose with covariance. | -| `ekf_biased_pose` | `geometry_msgs::msg::PoseStamped` | Estimated pose including the yaw bias | -| `ekf_biased_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Estimated pose with covariance including the yaw bias | -| `ekf_twist` | `geometry_msgs::msg::TwistStamped` | Estimated twist. | -| `ekf_twist_with_covariance` | `geometry_msgs::msg::TwistWithCovarianceStamped` | The estimated twist with covariance. | -| `diagnostics` | `diagnostics_msgs::msg::DiagnosticArray` | The diagnostic information. | -| `debug/processing_time_ms` | `autoware_internal_debug_msgs::msg::Float64Stamped` | The processing time [ms]. | - -### Published TF - -- base_link - TF from `map` coordinate to estimated pose. - -## Functions - -### Predict - -The current robot state is predicted from previously estimated data using a given prediction model. This calculation is called at a constant interval (`predict_frequency [Hz]`). The prediction equation is described at the end of this page. - -### Measurement Update - -Before the update, the Mahalanobis distance is calculated between the measured input and the predicted state, the measurement update is not performed for inputs where the Mahalanobis distance exceeds the given threshold. - -The predicted state is updated with the latest measured inputs, measured_pose, and measured_twist. The updates are performed with the same frequency as prediction, usually at a high frequency, in order to enable smooth state estimation. - -## Parameter description - -The parameters are set in `launch/ekf_localizer.launch` . - -### For Node - -{{ json_to_markdown("localization/autoware_ekf_localizer/schema/sub/node.sub_schema.json") }} - -### For pose measurement - -{{ json_to_markdown("localization/autoware_ekf_localizer/schema/sub/pose_measurement.sub_schema.json") }} - -### For twist measurement - -{{ json_to_markdown("localization/autoware_ekf_localizer/schema/sub/twist_measurement.sub_schema.json") }} - -### For process noise - -{{ json_to_markdown("localization/autoware_ekf_localizer/schema/sub/process_noise.sub_schema.json") }} - -note: process noise for positions x & y are calculated automatically from nonlinear dynamics. - -### Simple 1D Filter Parameters - -{{ json_to_markdown("localization/autoware_ekf_localizer/schema/sub/simple_1d_filter_parameters.sub_schema.json") }} - -### For diagnostics - -{{ json_to_markdown("localization/autoware_ekf_localizer/schema/sub/diagnostics.sub_schema.json") }} - -### Misc - -{{ json_to_markdown("localization/autoware_ekf_localizer/schema/sub/misc.sub_schema.json") }} - -## How to tune EKF parameters - -### 0. Preliminaries - -- Check header time in pose and twist message is set to sensor time appropriately, because time delay is calculated from this value. If it is difficult to set an appropriate time due to the timer synchronization problem, use `twist_additional_delay` and `pose_additional_delay` to correct the time. -- Check if the relation between measurement pose and twist is appropriate (whether the derivative of the pose has a similar value to twist). This discrepancy is caused mainly by unit error (such as confusing radian/degree) or bias noise, and it causes large estimation errors. - -### 1. Tune sensor parameters - -Set standard deviation for each sensor. The `pose_measure_uncertainty_time` is for the uncertainty of the header timestamp data. -You can also tune a number of steps for smoothing for each observed sensor data by tuning `*_smoothing_steps`. -Increasing the number will improve the smoothness of the estimation, but may have an adverse effect on the estimation performance. - -- `pose_measure_uncertainty_time` -- `pose_smoothing_steps` -- `twist_smoothing_steps` - -### 2. Tune process model parameters - -- `proc_stddev_vx_c` : set to maximum linear acceleration -- `proc_stddev_wz_c` : set to maximum angular acceleration -- `proc_stddev_yaw_c` : This parameter describes the correlation between the yaw and yaw rate. A large value means the change in yaw does not correlate to the estimated yaw rate. If this is set to 0, it means the change in estimated yaw is equal to yaw rate. Usually, this should be set to 0. -- `proc_stddev_yaw_bias_c` : This parameter is the standard deviation for the rate of change in yaw bias. In most cases, yaw bias is constant, so it can be very small, but must be non-zero. - -### 3. Tune gate parameters - -EKF performs gating using Mahalanobis distance before updating by observation. The gate size is determined by the `pose_gate_dist` parameter and the `twist_gate_dist`. If the Mahalanobis distance is larger than this value, the observation is ignored. - -This gating process is based on a statistical test using the chi-square distribution. As modeled, we assume that the Mahalanobis distance follows a chi-square distribution with 3 degrees of freedom for pose and 2 degrees of freedom for twist. - -Currently, the accuracy of covariance estimation itself is not very good, so it is recommended to set the significance level to a very small value to reduce rejection due to false positives. - -| Significance level | Threshold for 2 dof | Threshold for 3 dof | -| ------------------ | ------------------- | ------------------- | -| $10 ^ {-2}$ | 9.21 | 11.3 | -| $10 ^ {-3}$ | 13.8 | 16.3 | -| $10 ^ {-4}$ | 18.4 | 21.1 | -| $10 ^ {-5}$ | 23.0 | 25.9 | -| $10 ^ {-6}$ | 27.6 | 30.7 | -| $10 ^ {-7}$ | 32.2 | 35.4 | -| $10 ^ {-8}$ | 36.8 | 40.1 | -| $10 ^ {-9}$ | 41.4 | 44.8 | -| $10 ^ {-10}$ | 46.1 | 49.5 | - -## Kalman Filter Model - -### kinematics model in update function - - - -where, $\theta_k$ represents the vehicle's heading angle, including the mounting angle bias. -$b_k$ is a correction term for the yaw bias, and it is modeled so that $(\theta_k+b_k)$ becomes the heading angle of the base_link. -The pose_estimator is expected to publish the base_link in the map coordinate system. However, the yaw angle may be offset due to calibration errors. This model compensates this error and improves estimation accuracy. - -### time delay model - -The measurement time delay is handled by an augmented state [1] (See, Section 7.3 FIXED-LAG SMOOTHING). - - - -Note that, although the dimension gets larger since the analytical expansion can be applied based on the specific structures of the augmented states, the computational complexity does not significantly change. - -## Test Result with Autoware NDT - -

- -

- -## Diagnostics - -

- -

- -

- -

-

- -

- -### The conditions that result in a WARN state - -- The node is not in the activate state. -- The initial pose is not set. -- The number of consecutive no measurement update via the Pose/Twist topic exceeds the `pose_no_update_count_threshold_warn`/`twist_no_update_count_threshold_warn`. -- The timestamp of the Pose/Twist topic is beyond the delay compensation range. -- The Pose/Twist topic is beyond the range of Mahalanobis distance for covariance estimation. -- The covariance ellipse is bigger than threshold `warn_ellipse_size` for long axis or `warn_ellipse_size_lateral_direction` for lateral_direction. - -### The conditions that result in an ERROR state - -- The number of consecutive no measurement update via the Pose/Twist topic exceeds the `pose_no_update_count_threshold_error`/`twist_no_update_count_threshold_error`. -- The covariance ellipse is bigger than threshold `error_ellipse_size` for long axis or `error_ellipse_size_lateral_direction` for lateral_direction. - -## Known issues - -- If multiple pose_estimators are used, the input to the EKF will include multiple yaw biases corresponding to each source. However, the current EKF assumes the existence of only one yaw bias. Therefore, yaw bias `b_k` in the current EKF state would not make any sense and cannot correctly handle these multiple yaw biases. Thus, future work includes introducing yaw bias for each sensor with yaw estimation. - -## reference - -[1] Anderson, B. D. O., & Moore, J. B. (1979). Optimal filtering. Englewood Cliffs, NJ: Prentice-Hall. diff --git a/localization/autoware_ekf_localizer/config/ekf_localizer.param.yaml b/localization/autoware_ekf_localizer/config/ekf_localizer.param.yaml deleted file mode 100644 index e00d5e1c10ae2..0000000000000 --- a/localization/autoware_ekf_localizer/config/ekf_localizer.param.yaml +++ /dev/null @@ -1,50 +0,0 @@ -/**: - ros__parameters: - node: - show_debug_info: false - enable_yaw_bias_estimation: true - predict_frequency: 50.0 - tf_rate: 50.0 - extend_state_step: 50 - - pose_measurement: - # for Pose measurement - pose_additional_delay: 0.0 - pose_measure_uncertainty_time: 0.01 - pose_smoothing_steps: 5 - pose_gate_dist: 49.5 # corresponds to significance level = 10^-10 - - twist_measurement: - # for twist measurement - twist_additional_delay: 0.0 - twist_smoothing_steps: 2 - twist_gate_dist: 46.1 # corresponds to significance level = 10^-10 - - process_noise: - # for process model - proc_stddev_yaw_c: 0.005 - proc_stddev_vx_c: 10.0 - proc_stddev_wz_c: 5.0 - - simple_1d_filter_parameters: - #Simple1DFilter parameters - z_filter_proc_dev: 1.0 - roll_filter_proc_dev: 0.1 - pitch_filter_proc_dev: 0.1 - - diagnostics: - # for diagnostics - pose_no_update_count_threshold_warn: 50 - pose_no_update_count_threshold_error: 100 - twist_no_update_count_threshold_warn: 50 - twist_no_update_count_threshold_error: 100 - ellipse_scale: 3.0 - error_ellipse_size: 1.5 - warn_ellipse_size: 1.2 - error_ellipse_size_lateral_direction: 0.3 - warn_ellipse_size_lateral_direction: 0.25 - - misc: - # for velocity measurement limitation (Set 0.0 if you want to ignore) - threshold_observable_velocity_mps: 0.0 # [m/s] - pose_frame_id: "map" diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/aged_object_queue.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/aged_object_queue.hpp deleted file mode 100644 index 2b6f209c7121e..0000000000000 --- a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/aged_object_queue.hpp +++ /dev/null @@ -1,71 +0,0 @@ -// Copyright 2023 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__EKF_LOCALIZER__AGED_OBJECT_QUEUE_HPP_ -#define AUTOWARE__EKF_LOCALIZER__AGED_OBJECT_QUEUE_HPP_ - -#include -#include - -namespace autoware::ekf_localizer -{ - -template -class AgedObjectQueue -{ -public: - explicit AgedObjectQueue(const size_t max_age) : max_age_(max_age) {} - - [[nodiscard]] bool empty() const { return this->size() == 0; } - - [[nodiscard]] size_t size() const { return objects_.size(); } - - Object back() const { return objects_.back(); } - - void push(const Object & object) - { - objects_.push(object); - ages_.push(0); - } - - Object pop_increment_age() - { - const Object object = objects_.front(); - const size_t age = ages_.front() + 1; - objects_.pop(); - ages_.pop(); - - if (age < max_age_) { - objects_.push(object); - ages_.push(age); - } - - return object; - } - - void clear() - { - objects_ = std::queue(); - ages_ = std::queue(); - } - -private: - const size_t max_age_; - std::queue objects_; - std::queue ages_; -}; - -} // namespace autoware::ekf_localizer - -#endif // AUTOWARE__EKF_LOCALIZER__AGED_OBJECT_QUEUE_HPP_ diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/covariance.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/covariance.hpp deleted file mode 100644 index 018b93f86d816..0000000000000 --- a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/covariance.hpp +++ /dev/null @@ -1,28 +0,0 @@ -// Copyright 2022 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__EKF_LOCALIZER__COVARIANCE_HPP_ -#define AUTOWARE__EKF_LOCALIZER__COVARIANCE_HPP_ - -#include "autoware/ekf_localizer/matrix_types.hpp" - -namespace autoware::ekf_localizer -{ - -std::array ekf_covariance_to_pose_message_covariance(const Matrix6d & P); -std::array ekf_covariance_to_twist_message_covariance(const Matrix6d & P); - -} // namespace autoware::ekf_localizer - -#endif // AUTOWARE__EKF_LOCALIZER__COVARIANCE_HPP_ diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/diagnostics.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/diagnostics.hpp deleted file mode 100644 index b194c3e956341..0000000000000 --- a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/diagnostics.hpp +++ /dev/null @@ -1,49 +0,0 @@ -// Copyright 2023 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__EKF_LOCALIZER__DIAGNOSTICS_HPP_ -#define AUTOWARE__EKF_LOCALIZER__DIAGNOSTICS_HPP_ - -#include - -#include -#include - -namespace autoware::ekf_localizer -{ - -diagnostic_msgs::msg::DiagnosticStatus check_process_activated(const bool is_activated); -diagnostic_msgs::msg::DiagnosticStatus check_set_initialpose(const bool is_set_initialpose); - -diagnostic_msgs::msg::DiagnosticStatus check_measurement_updated( - const std::string & measurement_type, const size_t no_update_count, - const size_t no_update_count_threshold_warn, const size_t no_update_count_threshold_error); -diagnostic_msgs::msg::DiagnosticStatus check_measurement_queue_size( - const std::string & measurement_type, const size_t queue_size); -diagnostic_msgs::msg::DiagnosticStatus check_measurement_delay_gate( - const std::string & measurement_type, const bool is_passed_delay_gate, const double delay_time, - const double delay_time_threshold); -diagnostic_msgs::msg::DiagnosticStatus check_measurement_mahalanobis_gate( - const std::string & measurement_type, const bool is_passed_mahalanobis_gate, - const double mahalanobis_distance, const double mahalanobis_distance_threshold); -diagnostic_msgs::msg::DiagnosticStatus check_covariance_ellipse( - const std::string & name, const double curr_size, const double warn_threshold, - const double error_threshold); - -diagnostic_msgs::msg::DiagnosticStatus merge_diagnostic_status( - const std::vector & stat_array); - -} // namespace autoware::ekf_localizer - -#endif // AUTOWARE__EKF_LOCALIZER__DIAGNOSTICS_HPP_ diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_localizer.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_localizer.hpp deleted file mode 100644 index 84018c043cc14..0000000000000 --- a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_localizer.hpp +++ /dev/null @@ -1,199 +0,0 @@ -// Copyright 2018-2019 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__EKF_LOCALIZER__EKF_LOCALIZER_HPP_ -#define AUTOWARE__EKF_LOCALIZER__EKF_LOCALIZER_HPP_ - -#include "autoware/ekf_localizer/aged_object_queue.hpp" -#include "autoware/ekf_localizer/ekf_module.hpp" -#include "autoware/ekf_localizer/hyper_parameters.hpp" -#include "autoware/ekf_localizer/warning.hpp" - -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include - -namespace autoware::ekf_localizer -{ - -class EKFLocalizer : public rclcpp::Node -{ -public: - explicit EKFLocalizer(const rclcpp::NodeOptions & options); - - // This function is only used in static tools to know when timer callbacks are triggered. - std::chrono::nanoseconds time_until_trigger() const - { - return timer_control_->time_until_trigger(); - } - -private: - const std::shared_ptr warning_; - - //!< @brief ekf estimated pose publisher - rclcpp::Publisher::SharedPtr pub_pose_; - //!< @brief estimated ekf pose with covariance publisher - rclcpp::Publisher::SharedPtr pub_pose_cov_; - //!< @brief estimated ekf odometry publisher - rclcpp::Publisher::SharedPtr pub_odom_; - //!< @brief ekf estimated twist publisher - rclcpp::Publisher::SharedPtr pub_twist_; - //!< @brief ekf estimated twist with covariance publisher - rclcpp::Publisher::SharedPtr pub_twist_cov_; - //!< @brief ekf estimated yaw bias publisher - rclcpp::Publisher::SharedPtr pub_yaw_bias_; - //!< @brief ekf estimated yaw bias publisher - rclcpp::Publisher::SharedPtr pub_biased_pose_; - //!< @brief ekf estimated yaw bias publisher - rclcpp::Publisher::SharedPtr pub_biased_pose_cov_; - //!< @brief diagnostics publisher - rclcpp::Publisher::SharedPtr pub_diag_; - //!< @brief processing_time publisher - rclcpp::Publisher::SharedPtr - pub_processing_time_; - //!< @brief initial pose subscriber - rclcpp::Subscription::SharedPtr sub_initialpose_; - //!< @brief measurement pose with covariance subscriber - rclcpp::Subscription::SharedPtr sub_pose_with_cov_; - //!< @brief measurement twist with covariance subscriber - rclcpp::Subscription::SharedPtr - sub_twist_with_cov_; - //!< @brief time for ekf calculation callback - rclcpp::TimerBase::SharedPtr timer_control_; - //!< @brief last predict time - std::shared_ptr last_predict_time_; - //!< @brief trigger_node service - rclcpp::Service::SharedPtr service_trigger_node_; - - //!< @brief tf broadcaster - std::shared_ptr tf_br_; - //!< @brief tf buffer - tf2_ros::Buffer tf2_buffer_; - //!< @brief tf listener - tf2_ros::TransformListener tf2_listener_; - - //!< @brief logger configure module - std::unique_ptr logger_configure_; - - //!< @brief extended kalman filter instance. - std::unique_ptr ekf_module_; - - const HyperParameters params_; - - double ekf_dt_; - - bool is_activated_; - bool is_set_initialpose_; - - EKFDiagnosticInfo pose_diag_info_; - EKFDiagnosticInfo twist_diag_info_; - - AgedObjectQueue pose_queue_; - AgedObjectQueue twist_queue_; - - /** - * @brief computes update & prediction of EKF for each ekf_dt_[s] time - */ - void timer_callback(); - - /** - * @brief set pose with covariance measurement - */ - void callback_pose_with_covariance(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg); - - /** - * @brief set twist with covariance measurement - */ - void callback_twist_with_covariance( - geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg); - - /** - * @brief set initial_pose to current EKF pose - */ - void callback_initial_pose(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg); - - /** - * @brief update predict frequency - */ - void update_predict_frequency(const rclcpp::Time & current_time); - - /** - * @brief get transform from frame_id - */ - bool get_transform_from_tf( - std::string parent_frame, std::string child_frame, - geometry_msgs::msg::TransformStamped & transform); - - /** - * @brief publish current EKF estimation result - */ - void publish_estimate_result( - const geometry_msgs::msg::PoseStamped & current_ekf_pose, - const geometry_msgs::msg::PoseStamped & current_biased_ekf_pose, - const geometry_msgs::msg::TwistStamped & current_ekf_twist); - - /** - * @brief publish diagnostics message - */ - void publish_diagnostics( - const geometry_msgs::msg::PoseStamped & current_ekf_pose, const rclcpp::Time & current_time); - - /** - * @brief publish diagnostics message for return - */ - void publish_callback_return_diagnostics( - const std::string & callback_name, const rclcpp::Time & current_time); - - /** - * @brief trigger node - */ - void service_trigger_node( - const std_srvs::srv::SetBool::Request::SharedPtr req, - std_srvs::srv::SetBool::Response::SharedPtr res); - - autoware::universe_utils::StopWatch stop_watch_; - autoware::universe_utils::StopWatch stop_watch_timer_cb_; - - friend class EKFLocalizerTestSuite; // for test code -}; - -} // namespace autoware::ekf_localizer - -#endif // AUTOWARE__EKF_LOCALIZER__EKF_LOCALIZER_HPP_ diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_module.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_module.hpp deleted file mode 100644 index 36fc9053ef4d6..0000000000000 --- a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_module.hpp +++ /dev/null @@ -1,156 +0,0 @@ -// Copyright 2018-2019 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__EKF_LOCALIZER__EKF_MODULE_HPP_ -#define AUTOWARE__EKF_LOCALIZER__EKF_MODULE_HPP_ - -#include "autoware/ekf_localizer/hyper_parameters.hpp" -#include "autoware/ekf_localizer/state_index.hpp" -#include "autoware/ekf_localizer/warning.hpp" - -#include -#include -#include - -#include -#include -#include -#include -#include - -#include - -#include -#include - -namespace autoware::ekf_localizer -{ -using autoware::kalman_filter::TimeDelayKalmanFilter; - -struct EKFDiagnosticInfo -{ - size_t no_update_count{0}; - size_t queue_size{0}; - bool is_passed_delay_gate{true}; - double delay_time{0.0}; - double delay_time_threshold{0.0}; - bool is_passed_mahalanobis_gate{true}; - double mahalanobis_distance{0.0}; -}; - -class Simple1DFilter -{ -public: - Simple1DFilter() - { - initialized_ = false; - x_ = 0; - var_ = 1e9; - proc_var_x_c_ = 0.0; - }; - void init(const double init_obs, const double obs_var) - { - x_ = init_obs; - var_ = obs_var; - initialized_ = true; - }; - void update(const double obs, const double obs_var, const double dt) - { - if (!initialized_) { - init(obs, obs_var); - return; - } - - // Prediction step (current variance) - double proc_var_x_d = proc_var_x_c_ * dt * dt; - var_ = var_ + proc_var_x_d; - - // Update step - double kalman_gain = var_ / (var_ + obs_var); - x_ = x_ + kalman_gain * (obs - x_); - var_ = (1 - kalman_gain) * var_; - }; - void set_proc_var(const double proc_var) { proc_var_x_c_ = proc_var; } - [[nodiscard]] double get_x() const { return x_; } - [[nodiscard]] double get_var() const { return var_; } - -private: - bool initialized_; - double x_; - double var_; - double proc_var_x_c_; -}; - -class EKFModule -{ -private: - using PoseWithCovariance = geometry_msgs::msg::PoseWithCovarianceStamped; - using TwistWithCovariance = geometry_msgs::msg::TwistWithCovarianceStamped; - using Pose = geometry_msgs::msg::PoseStamped; - using Twist = geometry_msgs::msg::TwistStamped; - -public: - EKFModule(std::shared_ptr warning, const HyperParameters & params); - - void initialize( - const PoseWithCovariance & initial_pose, - const geometry_msgs::msg::TransformStamped & transform); - - [[nodiscard]] geometry_msgs::msg::PoseStamped get_current_pose( - const rclcpp::Time & current_time, bool get_biased_yaw) const; - [[nodiscard]] geometry_msgs::msg::TwistStamped get_current_twist( - const rclcpp::Time & current_time) const; - [[nodiscard]] double get_yaw_bias() const; - [[nodiscard]] std::array get_current_pose_covariance() const; - [[nodiscard]] std::array get_current_twist_covariance() const; - - [[nodiscard]] size_t find_closest_delay_time_index(double target_value) const; - void accumulate_delay_time(const double dt); - - void predict_with_delay(const double dt); - bool measurement_update_pose( - const PoseWithCovariance & pose, const rclcpp::Time & t_curr, - EKFDiagnosticInfo & pose_diag_info); - bool measurement_update_twist( - const TwistWithCovariance & twist, const rclcpp::Time & t_curr, - EKFDiagnosticInfo & twist_diag_info); - geometry_msgs::msg::PoseWithCovarianceStamped compensate_rph_with_delay( - const PoseWithCovariance & pose, tf2::Vector3 last_angular_velocity, const double delay_time); - -private: - void update_simple_1d_filters( - const geometry_msgs::msg::PoseWithCovarianceStamped & pose, const size_t smoothing_step); - - TimeDelayKalmanFilter kalman_filter_; - - std::shared_ptr warning_; - const int dim_x_; - std::vector accumulated_delay_times_; - const HyperParameters params_; - - Simple1DFilter z_filter_; - Simple1DFilter roll_filter_; - Simple1DFilter pitch_filter_; - - /** - * @brief last angular velocity for compensating rph with delay - */ - tf2::Vector3 last_angular_velocity_; - - double ekf_dt_; -}; - -} // namespace autoware::ekf_localizer - -#endif // AUTOWARE__EKF_LOCALIZER__EKF_MODULE_HPP_ diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/hyper_parameters.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/hyper_parameters.hpp deleted file mode 100644 index 02958199cf2a1..0000000000000 --- a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/hyper_parameters.hpp +++ /dev/null @@ -1,108 +0,0 @@ -// Copyright 2022 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__EKF_LOCALIZER__HYPER_PARAMETERS_HPP_ -#define AUTOWARE__EKF_LOCALIZER__HYPER_PARAMETERS_HPP_ - -#include - -#include -#include - -namespace autoware::ekf_localizer -{ - -class HyperParameters -{ -public: - explicit HyperParameters(rclcpp::Node * node) - : show_debug_info(node->declare_parameter("node.show_debug_info")), - ekf_rate(node->declare_parameter("node.predict_frequency")), - ekf_dt(1.0 / std::max(ekf_rate, 0.1)), - tf_rate_(node->declare_parameter("node.tf_rate")), - enable_yaw_bias_estimation(node->declare_parameter("node.enable_yaw_bias_estimation")), - extend_state_step(node->declare_parameter("node.extend_state_step")), - pose_frame_id(node->declare_parameter("misc.pose_frame_id")), - pose_additional_delay( - node->declare_parameter("pose_measurement.pose_additional_delay")), - pose_gate_dist(node->declare_parameter("pose_measurement.pose_gate_dist")), - pose_smoothing_steps(node->declare_parameter("pose_measurement.pose_smoothing_steps")), - twist_additional_delay( - node->declare_parameter("twist_measurement.twist_additional_delay")), - twist_gate_dist(node->declare_parameter("twist_measurement.twist_gate_dist")), - twist_smoothing_steps(node->declare_parameter("twist_measurement.twist_smoothing_steps")), - proc_stddev_vx_c(node->declare_parameter("process_noise.proc_stddev_vx_c")), - proc_stddev_wz_c(node->declare_parameter("process_noise.proc_stddev_wz_c")), - proc_stddev_yaw_c(node->declare_parameter("process_noise.proc_stddev_yaw_c")), - z_filter_proc_dev( - node->declare_parameter("simple_1d_filter_parameters.z_filter_proc_dev")), - roll_filter_proc_dev( - node->declare_parameter("simple_1d_filter_parameters.roll_filter_proc_dev")), - pitch_filter_proc_dev( - node->declare_parameter("simple_1d_filter_parameters.pitch_filter_proc_dev")), - pose_no_update_count_threshold_warn( - node->declare_parameter("diagnostics.pose_no_update_count_threshold_warn")), - pose_no_update_count_threshold_error( - node->declare_parameter("diagnostics.pose_no_update_count_threshold_error")), - twist_no_update_count_threshold_warn( - node->declare_parameter("diagnostics.twist_no_update_count_threshold_warn")), - twist_no_update_count_threshold_error( - node->declare_parameter("diagnostics.twist_no_update_count_threshold_error")), - ellipse_scale(node->declare_parameter("diagnostics.ellipse_scale")), - error_ellipse_size(node->declare_parameter("diagnostics.error_ellipse_size")), - warn_ellipse_size(node->declare_parameter("diagnostics.warn_ellipse_size")), - error_ellipse_size_lateral_direction( - node->declare_parameter("diagnostics.error_ellipse_size_lateral_direction")), - warn_ellipse_size_lateral_direction( - node->declare_parameter("diagnostics.warn_ellipse_size_lateral_direction")), - threshold_observable_velocity_mps( - node->declare_parameter("misc.threshold_observable_velocity_mps")) - { - } - - const bool show_debug_info; - const double ekf_rate; - const double ekf_dt; - const double tf_rate_; - const bool enable_yaw_bias_estimation; - const size_t extend_state_step; - const std::string pose_frame_id; - const double pose_additional_delay; - const double pose_gate_dist; - const size_t pose_smoothing_steps; - const double twist_additional_delay; - const double twist_gate_dist; - const size_t twist_smoothing_steps; - const double proc_stddev_vx_c; //!< @brief vx process noise - const double proc_stddev_wz_c; //!< @brief wz process noise - const double proc_stddev_yaw_c; //!< @brief yaw process noise - const double z_filter_proc_dev; - const double roll_filter_proc_dev; - const double pitch_filter_proc_dev; - const size_t pose_no_update_count_threshold_warn; - const size_t pose_no_update_count_threshold_error; - const size_t twist_no_update_count_threshold_warn; - const size_t twist_no_update_count_threshold_error; - double ellipse_scale; - double error_ellipse_size; - double warn_ellipse_size; - double error_ellipse_size_lateral_direction; - double warn_ellipse_size_lateral_direction; - - const double threshold_observable_velocity_mps; -}; - -} // namespace autoware::ekf_localizer - -#endif // AUTOWARE__EKF_LOCALIZER__HYPER_PARAMETERS_HPP_ diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/mahalanobis.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/mahalanobis.hpp deleted file mode 100644 index c1538a72f56b6..0000000000000 --- a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/mahalanobis.hpp +++ /dev/null @@ -1,31 +0,0 @@ -// Copyright 2022 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__EKF_LOCALIZER__MAHALANOBIS_HPP_ -#define AUTOWARE__EKF_LOCALIZER__MAHALANOBIS_HPP_ - -#include -#include - -namespace autoware::ekf_localizer -{ - -double squared_mahalanobis( - const Eigen::VectorXd & x, const Eigen::VectorXd & y, const Eigen::MatrixXd & C); - -double mahalanobis(const Eigen::VectorXd & x, const Eigen::VectorXd & y, const Eigen::MatrixXd & C); - -} // namespace autoware::ekf_localizer - -#endif // AUTOWARE__EKF_LOCALIZER__MAHALANOBIS_HPP_ diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/matrix_types.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/matrix_types.hpp deleted file mode 100644 index fc75dfe72bb9d..0000000000000 --- a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/matrix_types.hpp +++ /dev/null @@ -1,28 +0,0 @@ -// Copyright 2022 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__EKF_LOCALIZER__MATRIX_TYPES_HPP_ -#define AUTOWARE__EKF_LOCALIZER__MATRIX_TYPES_HPP_ - -#include - -namespace autoware::ekf_localizer -{ - -using Vector6d = Eigen::Matrix; -using Matrix6d = Eigen::Matrix; - -} // namespace autoware::ekf_localizer - -#endif // AUTOWARE__EKF_LOCALIZER__MATRIX_TYPES_HPP_ diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/measurement.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/measurement.hpp deleted file mode 100644 index b8db07015ec46..0000000000000 --- a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/measurement.hpp +++ /dev/null @@ -1,32 +0,0 @@ -// Copyright 2022 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__EKF_LOCALIZER__MEASUREMENT_HPP_ -#define AUTOWARE__EKF_LOCALIZER__MEASUREMENT_HPP_ - -#include - -namespace autoware::ekf_localizer -{ - -Eigen::Matrix pose_measurement_matrix(); -Eigen::Matrix twist_measurement_matrix(); -Eigen::Matrix3d pose_measurement_covariance( - const std::array & covariance, const size_t smoothing_step); -Eigen::Matrix2d twist_measurement_covariance( - const std::array & covariance, const size_t smoothing_step); - -} // namespace autoware::ekf_localizer - -#endif // AUTOWARE__EKF_LOCALIZER__MEASUREMENT_HPP_ diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/numeric.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/numeric.hpp deleted file mode 100644 index 253da4eb7f6dc..0000000000000 --- a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/numeric.hpp +++ /dev/null @@ -1,37 +0,0 @@ -// Copyright 2022 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__EKF_LOCALIZER__NUMERIC_HPP_ -#define AUTOWARE__EKF_LOCALIZER__NUMERIC_HPP_ - -#include - -#include - -namespace autoware::ekf_localizer -{ - -inline bool has_inf(const Eigen::MatrixXd & v) -{ - return v.array().isInf().any(); -} - -inline bool has_nan(const Eigen::MatrixXd & v) -{ - return v.array().isNaN().any(); -} - -} // namespace autoware::ekf_localizer - -#endif // AUTOWARE__EKF_LOCALIZER__NUMERIC_HPP_ diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/state_index.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/state_index.hpp deleted file mode 100644 index 86fe83ec4aa8b..0000000000000 --- a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/state_index.hpp +++ /dev/null @@ -1,32 +0,0 @@ -// Copyright 2022 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__EKF_LOCALIZER__STATE_INDEX_HPP_ -#define AUTOWARE__EKF_LOCALIZER__STATE_INDEX_HPP_ - -namespace autoware::ekf_localizer -{ - -enum IDX { - X = 0, - Y = 1, - YAW = 2, - YAWB = 3, - VX = 4, - WZ = 5, -}; - -} // namespace autoware::ekf_localizer - -#endif // AUTOWARE__EKF_LOCALIZER__STATE_INDEX_HPP_ diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/state_transition.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/state_transition.hpp deleted file mode 100644 index e6ce18e76a3a4..0000000000000 --- a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/state_transition.hpp +++ /dev/null @@ -1,31 +0,0 @@ -// Copyright 2022 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__EKF_LOCALIZER__STATE_TRANSITION_HPP_ -#define AUTOWARE__EKF_LOCALIZER__STATE_TRANSITION_HPP_ - -#include "autoware/ekf_localizer/matrix_types.hpp" - -namespace autoware::ekf_localizer -{ - -double normalize_yaw(const double & yaw); -Vector6d predict_next_state(const Vector6d & X_curr, const double dt); -Matrix6d create_state_transition_matrix(const Vector6d & X_curr, const double dt); -Matrix6d process_noise_covariance( - const double proc_cov_yaw_d, const double proc_cov_vx_d, const double proc_cov_wz_d); - -} // namespace autoware::ekf_localizer - -#endif // AUTOWARE__EKF_LOCALIZER__STATE_TRANSITION_HPP_ diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/string.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/string.hpp deleted file mode 100644 index 0146176b7ddc1..0000000000000 --- a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/string.hpp +++ /dev/null @@ -1,34 +0,0 @@ -// Copyright 2023 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__EKF_LOCALIZER__STRING_HPP_ -#define AUTOWARE__EKF_LOCALIZER__STRING_HPP_ - -#include - -namespace autoware::ekf_localizer -{ - -inline std::string erase_leading_slash(const std::string & s) -{ - std::string a = s; - if (a.front() == '/') { - a.erase(0, 1); - } - return a; -} - -} // namespace autoware::ekf_localizer - -#endif // AUTOWARE__EKF_LOCALIZER__STRING_HPP_ diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/warning.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/warning.hpp deleted file mode 100644 index f43c5e3413213..0000000000000 --- a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/warning.hpp +++ /dev/null @@ -1,48 +0,0 @@ -// Copyright 2022 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__EKF_LOCALIZER__WARNING_HPP_ -#define AUTOWARE__EKF_LOCALIZER__WARNING_HPP_ - -#include - -#include - -namespace autoware::ekf_localizer -{ - -class Warning -{ -public: - explicit Warning(rclcpp::Node * node) : node_(node) {} - - void warn(const std::string & message) const - { - RCLCPP_WARN(node_->get_logger(), "%s", message.c_str()); - } - - void warn_throttle(const std::string & message, const int duration_milliseconds) const - { - RCLCPP_WARN_THROTTLE( - node_->get_logger(), *(node_->get_clock()), - std::chrono::milliseconds(duration_milliseconds).count(), "%s", message.c_str()); - } - -private: - rclcpp::Node * node_; -}; - -} // namespace autoware::ekf_localizer - -#endif // AUTOWARE__EKF_LOCALIZER__WARNING_HPP_ diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/warning_message.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/warning_message.hpp deleted file mode 100644 index b379e35763f54..0000000000000 --- a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/warning_message.hpp +++ /dev/null @@ -1,33 +0,0 @@ -// Copyright 2023 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE__EKF_LOCALIZER__WARNING_MESSAGE_HPP_ -#define AUTOWARE__EKF_LOCALIZER__WARNING_MESSAGE_HPP_ - -#include - -namespace autoware::ekf_localizer -{ - -std::string pose_delay_step_warning_message( - const double delay_time, const double delay_time_threshold); -std::string twist_delay_step_warning_message( - const double delay_time, const double delay_time_threshold); -std::string pose_delay_time_warning_message(const double delay_time); -std::string twist_delay_time_warning_message(const double delay_time); -std::string mahalanobis_warning_message(const double distance, const double max_distance); - -} // namespace autoware::ekf_localizer - -#endif // AUTOWARE__EKF_LOCALIZER__WARNING_MESSAGE_HPP_ diff --git a/localization/autoware_ekf_localizer/launch/ekf_localizer.launch.xml b/localization/autoware_ekf_localizer/launch/ekf_localizer.launch.xml deleted file mode 100644 index 76ac35bcba38e..0000000000000 --- a/localization/autoware_ekf_localizer/launch/ekf_localizer.launch.xml +++ /dev/null @@ -1,40 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/localization/autoware_ekf_localizer/media/calculation_delta_from_pitch.png b/localization/autoware_ekf_localizer/media/calculation_delta_from_pitch.png deleted file mode 100644 index 0fa459f96dd7113388f9aabb59fa36ec5de9946b..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 56991 zcmdSAWmp_d*R~5GK!6}Yf8Qk5SP2T6epLg#+ z`}gy;j2&I{?2RBytZl4}s2vRKjf|`vOl=&`pgMTo|HNpf zsOl(SZ=~mFW@G(L(ag%|y$}L|fsTQ3r@4-fZ8trHo@F3aCZ@fj zScrXFeh7$f5MqLSimvI$t6r{(JMCw0jff}Wd_UJ0yWyTjGzSJlVvAQ9bAt!Fwgk;Z z6^OpWkRi*#Egv zb@4|>gvfv*eVGwb2f+A)TQXM+oZs!!V-XRfMTJL&)A-EIpqI}XE{%4Z>ldOx6#h^D zv$$YA)5u$e_}>CMtKZq8|JnDq5CRn)?!P-jP~gJ;dnD1vZ+tQTo`xv!Q_TOFhd~%r zK7N7XNe?!!B5;q6)}(d?UFT8YkV-TBrrYwK`kEidq!xNiAFcBH3YQb#VARk`vL6Lw zaTPfXEPPN%kuFKHQ-UY&_+`a~H>mh@endfKoT8&V2C2Wt^uxfIsB}g(5Ecvs|ea$#sk%xH>yOK)%|xj-RMX#etEC@Q778q3sTTw z;ejsoTtIMDR^)=TSqZh_puhgH-zo4uBY455D)A-KdPWrATG7>ZW=5Y|HQ?k*G(9vc zv0F(MS$WcR3jFe8R>I&yoWQe^=tDoYr9|s==-Ru4*FPR15v;TKZaOGw$m&CsU<^yRVOgBZ{m@?2E zxPFPzXE#hqp+7}WJ5DPUT(5%85;JO|JppB zgqm5hH^Zn>P3;4%cyk!tZqB)d5Op6W@$*S6T+#*J#2E7IO@!|ZtRs8SH1Rb5Z?jdd z49IXJG?Bd+VN*luUdlV49%7?9<@8inW%~wkKoHI)QJ7+1z`)bH(*!BtAmYG<{%d9t zHD3tj@Ntaorq}hVbp+y#eiq_4lh%&y~CQ$26>&w99gG zAt|QcHV6>Ru42WK>1LE4&Db>sc8GAP-wyI#XeT9^u;_~lYi$cFHM9(56rks}yqk8dWKTC=%ZO!Z`%jPhV#7EP+1k^kH4UaT7S0b0DX+)(JQn zPy+;svSiEtQVnCSW-bDEE5rDo2l96nv_}3hy*M=jI@{ z>Q-=U{xGm+#NX4g9yp>EFw@LTyw1cS9s|q!ou?!`M9$sScByvsYHx=Qd7oC9K-xh! zP?(u-2=tGxRM9j>8|?uLGqatqP)Wau;kaSbc}APq+1={t_I=(7M>=1Ru1>b)Nrh}n&XvCc(dFZJ-LUO1?`)ITmfsf9W! zH}h)Y8(#$&5C~-YXMWf!$*@+x@j^9hX)i5thJe(9yW$0x@*G;)&n_=07v6FRPp%!m zredfgsZf{)HwiZ00$ ztH(e~?QovvDvtHIIqz(~!mAvlm=+Jr7C?kFz`r zpXRA|U6Hu^8PU^be9NSpqHLv4yxEk>t^gB^>7%Yy$+hdU0g z$Wq_Q^Hts|6qbn|DsuaAZW*iq zzyscPt@qSNU4Sox)soNUhd24M^G*yZ?xT1&E-p*Sj`FD&r;hjO}~YKVW@!Mm5hWor@EB8 z=(#IlH%Q7+b>3bFTVkPLfeI`WqSm_j3>ln&w@h84#=7{+sS2tzuFegly&4iqEL5|I zgY6`BwLN>u(6V-k zI|`dve;%?bb!SU;Me`*y1guLE@7vknIb&Ib?a!3 zVHI~!#RBqiYe|gN+#H`}_&J)WcaL4l*HCvMl}hSJxw(<=a56S?q9+QqoMC^pENp9w z|KpY;OH7mT=Td%XSYj|^m3i*!%Gi!5(wiEtc3O>Xod3^EbH1AY{4&T0dRV7s1Az={ zx7@(Qh+8BL*Ui8MlG4O{qYd{6Ky7exv_b2?S8p=Nx&2dbjiVt!MP5ry{55y|6H`Y; zveK2xd2N6G|r+|2na@>CO2@QOiG2sqk&Y$I|tB}rJ#t|&$@oZ#l^ zs046ScwvRv+;`8H-Y&j%i_i4rH+XPdPW7#XQF5jr&I1T%C5!{zutuL@PDy&^M4SC% zM@89rtQD`))PRwkDQ$vARXDWFFLx8hTQ+{>?$d8LI}-Ix*(3h9%w*o!-l-eiFJ~S@ zhQwlVIXkX)=a{K%sMM=P%}(0HZ%G_q6V=J zrUYiu=vrk&KaQqVj~%WC&tCmLkK7C<) z=L&Z8!CI(eetFm7mHb;n_{u@R!PYAK zmnQmSP@S-WX^WyqRfAl|lY?G`17x;NU8RJmV~XCSIRn+#sa=xn2Y0r}v;G;w8fBx{ zixCb2B$aIqdOi5jZZp6#Pq{!z1BJH>PDq%6k#rNe0Q|51OI2*-^&J;rJDM>`LSnEA zO*rcCtAcGX!5OcBEB{zWKz$c18Of{b>dxo|_G9f|W-mMM~2d$V!m;Hbb>f8diB2vYd%dTyS3dQ445m8X2g)^mIkP;Vpj(_gXWG>&=n& zul=0~Hzn8mPd!vIuN0M5+vQW~NQpPiD*`g(oKtIeS9HjgZ_hV|}NH%75A- zvv0oevFyhd?VDjn4`V>dLZP9Uq?1ESM-uwx+6wy_22gMC#^EY?#qC8Ep=wQhC?8u9Qv-swgX zkA6l7HF#QJoAcip^GpROKJ=Uh3MHNbk2b|VG0uo%mqB{cEuy3=&kKw+O{^k*ehIJ= zg=e*g{}$DQ%@L-l%|*C;p?kdL1$CkS#)cJ!ZJhkH5S&=&FF*CC9o?uCt09`wlr*q1 zycDT28sR^q*d8Zi!+=~eZVu`R96UFa^iK?u8D#;B>2>MOTNkbut}g=PIqL0okb(yj zT8q=Bf)A@wZEAN&NJ(kqTm)QM9v2zW$Mjq#{KVq=TP>KSr+mP9DC_fjXrP>mf%W%7 zAiHMLEqhaIPUgkOZVaJdZ+V@knY?L8t$poV~)@6&^(G4K40)&rcZ9o>UyqOjpQa#9H6aEO@jA-9zA+0 zJ>98yB2@5rLOz}pdBMA$2R-%+zF>H6MKp)*LmrhlefH}3*BJ4!-i=ZHbEDaM6Csb& zx!SjO@J=zU-0BRWBjZITcJd|-p!xydsQkrje6|anDQ-)wZ8+lKD{=xY^XJOn_3-8p zA@Z`q_Y~J8pY7f^|zThpjD(KKX7^dceD#7>S`|$T3O^M^@Uv<{~hG^U*I+ zKDkG08%IUQ^I(MTQ1Gjy$X@)sU!@eG@C_&5KOqU>$q*Ut)+Z3QskTk$S?%PuZ_fdg zO@X&;-&M2Hy{ssOd7)<}j3?srF(HE4wO?-S@0gURolMu$kZCO>)F@1Y)k(Uh!bm0l zjlj1s^P%fItmQA(DVIEKF6DYB+L#pYqXDBDs@aiMxC<C8Qz}{{FaF02|j1ABB){Bc@K?1D}v;y7v)^pk|{Q@p%^jp4H6Q^g) zzr_Ektsvmt-kD8LWr)o__$Iv=)qieFZioiAyOZ66s*R1uKl5z69XiXML7@{b0^?(! zR2f1qTCDS=W*R0G3%e$;{d>)!w9~V0Z?aDcnTSJS_e^AM+3qv<$G*UO&Gc?a(1N!QC_15KF`Ot4!61tEBrUa?XJrQ8FE?p;rvH;)-LWbIzFbWd%wJl zBF|H>mjuq+Q4Tbf&md7y$v>l+?}j}A-US!=35FEaZ+ErfjjqF$ zb=2WT=GAme_&>lk1}@LZ7>s)49B3SNcKI3$nsc$hsg+;3HYB|ZU8Hw+Qy#`X?*qhlluKn@3Y0XZ3N064kM z2bW^5h5jMKHHzE7N}oSoUKk&uP%?tzTOmB#9^3^MP$pGWgdBkCQeFPbUGsOBt#jwC zcgI@en-S1l*DuV+1U>wgT1Dhe?PKpg!k3)irp*AXXEusrE`nEu9e`qQnl=P}sFyNb zM+=t|v)(DWZA;jY0Yx^E*<1u)pn8(XsuS(E${!b?_2x(9`3cvCJ!jv;Y|vOx|4z15 z#4gUKiGQL9n@e<;d|z}`K`B&uAMVZ8>U@K1!m0_*2oQ=ZkZu8u5f9_c8?f;uDd?3Q zZRpL~K;+kBi_PB^d$w4B+YGhma+bPr-!P8#VghP_Di0=gHUXuvRdt?6Y3l0E4BqIYmk;Vx1JiQ7)~dlrGr6q)qoA9@yXn}=$FxB461Z4 zTZ`O&7+}$3N&9k0*}z@^J zqx-0F7rk&MR8?7Q@}HXjePIJCr3aONWR`0c6a&U`w*>&yPMoS5jRExr_4`gZ=pE6C zbHm8%Lo)@IPg2s2KRW6i60goX78lNLYCMeKvq;8CFTNs{0)wKX+5=Y0ax+pQ4z^&9 zy$LfJDX^Xhe`Z&2S6L;*DRF8o=%{ykF&m?vO@7IHyx&(vqc-t_Gqz_n(ciaRzEk=A z13nO9Y<|2`fbIBAaijs(Se)sP>V|AoenB z;E^jFH8^~gGR}3{l=OmyI^C-4wGwLFP1ll(^390RtXn(RS~qnO_hGMJv)p}F>M9X> z#iahXW71bp73{bUnhbwAg2}j?K=r}1Lri!tpd!0huJ1A*N0QORwu~k9cA6#CYE5?? zD`~8uZJST2WD@t9%vEmHXr!a{Gde=hXaNOz9Q{tzoqN*M}Uon3akhSQPAL1W#Zn= zbaGlx{2uysiU(V&!N(IkZ#msOBP$H*;48O%5Im|$>ICJ9E01gR?zDHvRO}@`0fK?Z zec*q?F7`^o=#X?>lD9TTCEj}EVhRG$CwpG5(k-+>g5u>dbtd9&!>Jlc+i|L8X7jV@|w31F~TXF)KAW5>4g|FZfEgL#so!7qu64F^Q;EB zH+PIDi!@XAviGP~%@r>>wnD2VDu&E$C2EZ^^ili045z7OjousH=Mwhg<+y-{j?X+K zbW~uW2gX6HKL0mEv?rZ4zQJJ(Rq#!YjF!m58RgjgxWR3LDu_(Eef39I}vLmOZ#@i=}A9mR7-IVwORFbo~+El4aCKxr) zF@h8e_}o@^Wj`Q=IC}vHVUBP*Q5^Tzcx5*k7d5oRoz1yY5qQ$2v?~2bqw;s46*Umt zeKLh(yv4rk0IKOO$^#w)l#YS58xQIMdbj4z1Y|}=&))z5IpLa1270G8u&;R9vd6)a zg$br?J8g8(bUm5LD$~4j_1g_hs?5`5&yP4QbE7@HRnhd^e=WJuy23C#q zuK*|gJ|a|yk8j50rg_&@L707QriM+p0OxwmS;q3?g{xP#X-Y9Je|v&2Vf1k1-djVr z&!ofAHd|d@Gp}N2^!UkcEx;M&Yr>#-yE1;6bPV?gA{OSB&al&-+ zZeeiXy8RRTS?|H+#4SdTDSreHq{0fbBlzD}2@Zq#d)jByMlAWi`JNu; zy+bK(w10!$fhhA#|9^QR93lRYvOi}|)6N9wR(Owad8;`8W|%faWl8>xe19T>NO33q z-z|O;GSvUQgzrb8|K0d5=>PrSQ}BO+{QsQf|Bl1@BAlWAr>d`s&6<^y*8YEcU8TXr z#l@FZ@Bpk3=9t}PyD?r?#-`*EJ4au{Pi59nau*)nP5iA;f(w{WL_Gs+cY|M|@BqEo zHk5lbf{Z-Qs0!B1v1|r7TR(nb@_(MXJy~Y=xIH#y75M91&X*wKvIsI!;Z%#HM2$yR zy{HH&5(bm+3ZfQC=?wuS4W5G>(l0YN2Y^ZE!)W+Dq(Hsy7LjD``rWSr|6bTfL2?i`RJ|{@h`G6GM4?{~V^^jwbH zP_>x|zFC9|_}l*HLOsmX41AM&MwT@N@-<@%t$h=FPpWoc9~1wzp4gR>_>;xqnDHl9 zMI6SUk&2Y`#mnzV55uh}`gK~ivULxiQ#2S;rkqL_gOm?5vx4Z^!*iDu9QUP?ts{3O z4X|;)l3aG~X8Or8^*Q~>Ut*D+vv-pDcL4Y6`**$=tA0q*m;C+!#UlEx6owPXT|kW3 zA$~w|?U&Z%qO;nIO+IWTl0Yo2J@ZC~ZBUWgibM8xP;L4{H#RBta?r~Nwx)>p_!;hT zy1NV7?!Lo)v2s(ogLl6{a)Ijk+g3!ZkanCmyM6CGMn({-;E0DKE(fjq1 z#<{&M{P+n*rFq~!PjL*tJnqjNe~6r86fx}h??+;Tv!vYjW<2<#of%p^Jg8I`XSa36KQEey5ItBS{H$hObx)Ed z`^99lp8m{DK?_3{%0QHWId^{rAJ!l<0k|#z&=}l`Z|gyEb@u5k@m?d3{U+rz`9Bh= znf41GJ%e+;>;57jO`gSdvS;nnp5bZAdkcCxA@%j&(oBGp5Q@k&Izox@6;z*}r?H+s zCHK9px{eJd{S$54#9==jZvdWEl%#qVE0Bar4e8QmKp z#!EE=tSax)^XZaB_WH=3%a6zs4I{u!hybBTxDd`9BEFcW;}hG$%Q3;R;4K@mICOlO z3*A%M!|^MY{z%F;00%Q=)%h0sGu1*>s-V>V-OsXtWurWNH0-n_{jft9TH6)GDE)s&rC#H2G&2mc^5cR1fYs=r51$j1~W zCzD@g!Y?nt#z#vU6u30KA_V5@8c?^4whrPP?oPx!a6%nqNZn3+a3a3_%Asl5xM>nta1^ zjj-d>1A9Dzn}KpOZDx?ecaO62(;}_p{F?X`80G4}Wv+r;YeZV9yIC&59;^J{SMeH7 z7MDas3wxPtSX?6Tb%PD+l1V?e<8Ri4L@b8BOip9%S?3;$cnluX)`w^ES{}P#gU5AN z$J?7jy?h#f9WE13G7tq~{aR)mjLH}!&j&;J)&poEn%`4Udy?P}68Rv6E$TrU{rO@1;0tETpw^@?3wjUZ z+n|m<$GJm<*GE2NOD8*H3&4{ZIk5wRp~|h!XXST)CF+9fJUmOG@mpMt*{mTBf5&TU z?=g41>v`*e?fLLeWR$mX^O2hMl>aE*sz7du#NurlmpsYG7E-}-c-iagEQQ-1_(Vg? zz1~Y^tYFoUmOLXuHJQ1K&M0$vV#T9(FzJ`oGgRCC5!#54Jv4Y#?$73OaPqb1j_%WC zksbB&@EUe3>iZ**^_tANJbrsk_Ic5n4sF@^HEBIYSK=BqE9+Jax94+jdgi+y%7Gdo zmOqjfP$B{M9b656%elhjgZ2*D3Wf9BkU0{hN+9E`O|}Gs`-+ zt}m#xw#r_ctF$a}wWFf{m5^uY-P1Q=z)m?xirN7zcAj$2NdUo*$b(d_Tw|Z?6NVz_Bzs4a^BEJWQ0>5Qc;_?jEu^T`t99o~rUOP2nHeXL}3%yazb$_RE64KdkxOs^}iy%G05-*W-i zyx3=6df4aD^a(y5*I?r9&UK{ZfXj03M$6*4EonEE!rYRE%j6xqNU6IfxNBR!_~j}i z(sH(0v}21nC%}^ahP`6Ex$QbKctBMb$bRRGdo&z;j?z-(jX5`8TKv{2wXA~jj(1F# zJANID6v1_R!1{|#yao^}eq0JZY2;ito*2^{;x_Oz+Tx%V- zUzjD1XmxGsw2SUucSRr^t_#k>WUjeI{ouT1nQj)KMlCs^V}-Y){uMQ z1cZ8yd8zhIH$P#$#kC)25c?2(;SZs_7)&}j=GZ8_d1gKKIrm|39x+vfi}Llwd`|#x znZUMl!`E<_@+e9i02^!1Ra(g;5lMM63mL+O+LP9H*foVG^<<6B29wc(cl{BLfZ-)7 z^;AsGaADHSvhtciJ{(x;2yWhGh&o9J7S0-IbE%~8l#TXxoJVS)>YU|L;rFs99h=-L zcTR*>sW(|Ow-+^KtMY;!&*Uo$bKSRLPEmI~yrUMc# z<7UO;xid0@6Pa+cYv&GzTLVPZVP{?Unm`|~K1ra-z#Pn_a=A%k*^x6+DzZ}b)4DkU zf#<=p_1*#1_-5#+R6B5ajbe%*9JynD9G8r`@=p;-p3d42vPdNmTk&~Hwa3(!qD6zGAt{pd!mIF^a>skU;=29jh1kFs}bYX>pmEw_^ zxT-wN&c@-_0g5Bz4NN(GG)8Bae5?k7j)|yW-U(D)?S#tg6+iP!WMT{PKVflJXv*IGSzC|UR>OLIum(Sbup(K>xP#eRL|9U z-br99kS?DiOzp;!ntBi8x^}+W%I2MbNOS9$99q+3jGOhc3o<^x%azudT8=5m2zghOo5>Oyx>x~9ZDT_3K@Br zyWRgDEBB9yz;wRqn-q=$$>C_K4K@Ua4nFF3bedqHv98%--N}tIOPUl#_}b z^*-94pd=#P8H|n_H%bVla0IVRtv9!W@m6&7sfyQNE;B2#e~ip!&LfbUUdEl963mJK zHj#hwY*tJ;ksR6wB4?r285ft!{xD!aMY3 zoxg8;rz^s(J%U!|PZUGS^D@PbS8x53lNss9dY;`h&Lz?lt&L;BU7bSU6U`nzI#)FV z7OE6o>;*r$4W8BROP=!3UpfQjb9bhy+*j`)+8ge$nlQ6I(Y{|N#}$?NEp5K#YF%=o z-Wv4d9fwHmYX5;g5(qvc{G~o*#oqxIfDHbSEjHl|t;z=@*x{LUwuUZs9fUOIeTBHf6x2gF^3&mNoPL-w9%a+rc8lpN zrebZ=Y?ohYyQONIpMsD7nYYV_Ndu1k`)O9ss}s1Mamk&So7v}Q!u+LF6n)3%i)YsO zmKCUu3y#a84$bxUw=;y@wg(#E_-oel{8>~VA(j{3Vr*Az60Ccczq2#aa-t*6;Avhp z(f#kl^R0?)+LkuOR^>G5*GkhRP)FutEejI$+P%ea~v)m;%9sl8z`!Py)|fYrg^wO|(X} zg=uQ|RH}F3C3~egRmHm%Nny`ixLW;sJeeMQjtMl&7!lq>ieIJb)kEY{j56qb-VEOtd)~B@{7Ua^-I^G?8EtYn2tO zC#p!Ovy5G!J3Ot(XNRA3pjKR}(!uo~a1b7VmPQ)|*7-tZ;ly3#0$y|htJ;L4ESMt< zzqIdaI;uVw;hesb#3|_uwlV~zcWZm!*)W%<)T6)9ogVBQeH{cLP#fWrJC$V9$LTbu zMM(5d$JUWW3&ut5Ai$fwRwetFHpkN*KCoYHsl+ZSw`bHzBrSyu>I=7$1aYN>y_}G8 z$@Jxj@Y&R5&$p06@&>%atYQk-9FZx{URq1IExW(63ad-!M7%DLQWdU56?qvcGYCy_ z7tS1XE3RTM45N8AxCM7$DFl0~*JE;|hufyk+B07x_H22EIaOGpW_cc+Me<=Z3U~QNqr&`7B3kdZHNZ!tYp10EJ=kH17GbSpD<0_iciU4jmHIjwsPJU;JdF*m?vLPfAFs2dbtc> zfq;j*!;%|nFWz@$V{D&CPxz?dd45B?YEbOg@xCO=Ct9)HbO*i)>K7q8gM5iIJe6u#cDH)ov*qa%j}n@ zt56ddvaqPiJZT^2VK*-ZAPV-zRa;A+9dK4V40wBD-e_nBtmNRR*N@3agku)E__(T! zl#v6q!*Zu{kdq+IV+XxSM?TdIN(^SI2w##T`w(>Om8+2Ch|tR4P2=- zJ?itz$9oi2LRK{dcB=7EO~|v8Q_@Ne-rjGHnYoUu8Al+gg3C#1L8&uYdI=*?S>?8U zKEoV56wAR%fWZ{!WV;j&mK#~3HeOrM#T#LTS?_mif;925Nio;mVH~v07?TGnN0`da z3`cIkD$Tz~R4XYbCu`*MQ1~@}?9pm=x;11F&f)Ly4oQAaElZiAB;jgFjVFidP;fAr z?`Ogf-DSI=sQllt`eTGF9siq_qrqB zCSy^6kV#pIK8;(%1Xi7)CtJE$PK|ED_a&|dCchnl{x=ir{pfDT(p-PxpEcB1?q5&T zSPd;!+gG148_%a$?3v!K%;+|eZjiI&+X>6ym|61*sPw_whFGF)zX!p{CSxtnV@zki*{FZB>`FX8VMlYf zDQ_62Q0A7L$_eg*7TO=U7b0jdYMyC)G&3vB%`XW< z-NNpi-AG1!cnf0T;=z*azi3T!tv$uZqhZZ*<8tM>+dL}jlhY`pb@i!3n~cVFeWQ!; zSh{f+sX24^e}W}^Qdt{)^;^n&^q;R?-X}t&Pv!BiA>-ee;pHTFr>R=RyxI!|Sii8r zSyfo^l6`4$pfPJa$sX7#1oa6yd+y)$mleA}8H|qL%V*?EtGu?)$FbD=dI=q1q0?2eRI2VqD>CW6L#b)PXn@mk^o#>E+5!reR@YVj{gh}1*d(|#|zC!v{zkmt^IKG%NJM-SUfs;Bt`8}J0{Q|nUhWSF90?8p zR&Va)UnKLbU^t%NilKu{v>#Lh9}V=|tECiOXlHt!QMQ{E`zNVZDUo*CjxY?C!8~AFEtZyZl!z}0-GD|<#qk;w6WOC6O}Q* zrcuH0u=M5?nCjy`_9V@SKd@Up+PwFw3o4{XbS6#Zp`p3wb?qZ4B}U5}H_Cfx!X00n z$n5Wp$wnY}r;#n30EAiTc*mE9IkzhW=Hq+P>0U;X)HFP}$1iaA7a5KdmJT`ugL#vB zsTtC92nB7Es)Iu%5EO*W?E7w_Z$(|HG#jo_oB_Q-KYJbeM_=l@`ZB}T4{er2!WUHP zQiEzEwD`Y65L)>hd(GFyIdxTyfcYhK81Frm%EiSua(*t&~DQvW`VR z!69jAG5PH07C4!1Y=*!!*<~GWEv37BIlhJewd_u!v$Xh5!~5-}Ik7ww&e-?B_KX>y zj#$upPyW6iF;7HqDt5>|b1GFb|xjS9t!?23%4EpJYj6g2A;>TNcgiwevSAQq% zT*u^7cmVB~OR?YXm;!<$K*VTd2X>|sNVZE7+xGzyHUT5*95SvWG#3M#N=!oUb$4Cd zYjJZrOB^v+B)55pEnP`j~ky{9U+kuQW1x;)IX@f z<3ev#r!N-TjO#uRzw5(Vx3gPaBFD@ZQ;2(Z`|}L#4I*D)Aq88n0=-`Kbz2^eJONS^ z-evoA=cz!~?9jEtUaTwit{{X#q@m3q2@(4K$=I6c%LIcq{RhLt6cnE=MWvndjcz<1 z&tyiEF*=`D&)xAXz|!dB^5ra~GS>XLhqvhBg;u`y=nhc_M=#u&ONzZmdAaxl>pHE^ z0|M)cEtJpeRn~iMnQE&qax0t`w7%IJE+`~)v3lm6glp3lW8?F*EGY8kbQ>}^ryPaH z{%6^yLrO#h_UZNn_k=Vur0u}vH|tB(q_wah(@S+^ekyU&>kIJBf&&nB=3$f(Q!sVv zydHtQjh6I2kIE3ylzN1jl8N=98k8(EbO$ebpdN8k9uNy&@=r@1U0HotCoISg47>F< zc3Ib95LcMGhPjqo|J+pa)*haq&?iycxl>QTXW?-KnoLevPy5VF*Kcz>vE#|jI@3t)PQR1qa(HtY*6D8znQix4+v6>G z=%qg?T|sQFV8nxAf5^!N%8nvpf&M>)MGB947(62MWtnNBZfof@WvLH#p!CtJVE;QJ zyWXkSfW|JIA`~c;^Nr^Pgo_rxhW%cZ)|h%yd``kv&zI*0{nzR$IKcZXuJjK@ zM}nvdqsGRt*Z>MaXbViOX3FO^+z&frPL>)bTRHr&<`&d|Vdgm5RBvd?x=_*g>B1o$ za#`MwFpGPN(tnL+Yl+ zVLR=2u|))zLGD!It(A_owIIvB(|NZq4E9LxEmP+Ui|-&tZ!Y)Dqkb&KL~z%&Z5Zo_ z$kgIbspF)@B5pGQn?&G}ME`cmAWMbLl2jv`r>owWuo6c}W_l@~mDbm8WQ-cgq5px0 zhuygQKmkr#W^rh!k`d8h`e6^#azsZbyoe?#n5X!go$&{>*@>HHb%{TU7<+>`k_K{g z6=3lO18gBA%mQrknKYB%Y-%~94+NwAUUbX^?aQ-!@m1FEJnkOJbo#0)@Iu$f}4aXC*f*N+1#HbXFJk+ znjpp`-9Z>f1mh{4DgeERv1R`HP%`#SAM4IB(A0S690)Mm2u;GPYir1aMLvUHgDrp> z??0QsJ0xD38AYeTanDA3&4#&-g8*jrt&kLQ6=jdFbWf(gWwm=mhu4g}0bczfPdC;f z4pGQH^|*dO=4JS(fxE!UC?N$$&8$Ie#XZC7fV}fKy7casD3mFASQ@`Hl&_Ll%}Nd9 zbqZ`I@)1A?q3Frl!mxiX!cNxn_JJTKga1IUo>2TR3*aAo^bq}LWM!V2v61*LZTzO0 z18ZTx6As(_+e75wN*0!YV-;%Hw5arGuP&s}g8rJCbHZ<_F#XGqIy?`>C<=%uU&rf+ zwA>gnURGLpN&_2JTWoNK6%etQ%3OEyYc%Cf`2!N`rtb8xvpS<5n(xmBMTO)vl zh1GC1WJx2ZrR}$5$(ui#G_RkTnUPge>V3Cg`n1uR+1bU!RAyKO2qh&Yi1>sAIW;vg zQPEG{-i@bcSJ&?CCycy`AW>=(soFRR$~=;1edFqDy{q6-4kV)f#)? z^NJofTvomo6MC!r9T%BpHUHCh=hreSEw(RaS4^>t)02cNBB|tI=Y?geJMk*2?zTjf zF3hL*LFB)ix%4h~3Jtqd(Y-(wlS8MB8I+_rD#s z@0Lng0y4!eRiuuJxB^mMlb9trZtxg^lw`SfE-f;R>vwAu$~Mw`X)VFD@{lCY1eznI zM&dkp9q3lDNoWsJYTe3a)WdJ7qW0dTgPa=WKjJ(?Gn;)2IwEZ}ogJEgLwj;5j32VH zIGC#Bo_NYdr4OutK|?D~91Yx=hl|J$1J@M8^JhdqIfH0x6mV>QlYdI7O8!Cn6GfvX zQK!(7-{VjNG^k};a!`vtvJ$y`v3&lu?5#RDo!Dc7zzifMc0bbld@<|FuWqdZ4!XPU zlSKjDD>NXjb`I62iH)@%d!2tazH|Vd2fN9UwU#|JP(=t0qp?*xqM5mO>hmXQg!ok< z!H{`NYSd!QbqozWpP?cu-Ni6TrXXZC&xGK~vR8>8{(;Mo0HUgO#3EfHy6Km?mwRc;x@A}#Y z@OqtdJ_-ADb#bz|vhqo%fSR2h%V2h-;knz%vbtt zq{WE0wY{DD3QuP5}=;|Ki-7NScsWBqa(rH}{v6l)b~lmg#9?7Z(>f zIXN(ml4oUQ!8@Ygzay0yRbAb-?by2#t~Wk5K0d#&ASNPmD~3j?ZE$ce?g!)fUOVY{ zjSEYA1ZjI`CrX)47(5N_+8^B0^`RWM)f5-o;4BLc^B%+TpJsO-%+iM?`WLdt;zm2N z=aih4hT#7&YCJ6~b&O4~e5CihlEF*)cx6P=%-{4&kElho{mH)g^S}6#(kz7!-G8}b z(|$gso2)+NNbm1kIy^&_uUy0>_&ZO<_~}yK;TK zvicMOBzboScE^FZq$lm9PyF_u7&YTE-v5|) z%2s;hA`||Qs5Yu8O&q|-Q!!GWTP~0o3{ve-`ywk99*$at|6|VZl5anC*>q`_I&XH_YUIV9pS$O4FuZ&B4uS=CzqqutR2@q; z+OMXj#wItZ(eSq^yRw17?7ZRkf~rvfz?UyYbab9%N=LMfk5?rdr0=}jTacWz&^I%q zLPA24PZJ_8)A5=-*2S{bi_T#oQ?B=W)oy|_Q(sqIR;EC+Vw?H0e1>it6|0NPh?c)Z zUTU6HzS4&~pnzFUjUv`bQ<~A=j&;61B_UJ(gMpUXXr34))sJFk0n)_V4N*p;yb*|1 zm&=(AP>gzcet$6bi_|^__0+}rN^*(G146u)0tEdO&@C$6C8S z*;ZPkbv1#?@#qT0X$k82UFyc^N3aW0l5|C%tr8^z{P zmP2#Qs2O!l&GtkNi#L!P`_n4?`C*Ikb}Fl?$YMI}-@R)c9>(S8=hsbR_3-dOz(7$^ zyK%`&J-x6_(~R2MFV)q2R@Tua?E3C`x?OfYunm8&UAY|i zRpyZ`BH)gb4=*o0KcN#g36}4VQqNF7gN8@q0%3R z&1Kh=6}h%LEO6doCqo~{ahXoYNHibBMiW#}Gg`Wq&KcSnpoKLt^Skv;GIv}esfE!N zX`3JKAi4`j^gBa_8ZKtzH~VBxMIkIh{zR{O;XzZEfwPr6ogF0$LW9obqx!#Io}& z&CUJ(D*EvyeJmjEP=%er)YMe5PJyed>q`RzyF8p9d3oZ|ls|s_D6XhzH)Ms4QSkN_ zs;a62L%u|INdEq{6b>({H#`H8iB0ow=BqnJa5*T=vvANS2qE%lm8h z_Z@EEzKtONR%PeeMV?r9MIZUu<|r*?@g@&;$uF6%8nb>NH%IE147wH)Tm5f$jNIJZ zpni#tj<$DphU^m!XuY`WgT{SPOV>$wp+@u}t#EZfQhn zys5lJ>lZW1SXT}saV*_c%nJ2A#F`_OPu48nY%OW2yWvH{52dowyd5?u&z5#$i!#~Qg`#`;T-Lhn&#MYkfs)k90K5|G zWh{+$(gn=si6?J)IA$(F2|t&<{==+-wk*MPoi75mUdr`9m`;j{inm$BCet=3yu#|U70GmFKKb=Ch}+n1&PC?!~rBRFfhtD$YOs~l*{2G_9Xdz z6LFt;w8qeB7AIw@a1qXAH(CmfFS%&tJt``y^g+vx?r!lc6*iMLbaDy`n@J0_X(bZ= zm|Uby?Ud@U0)I5^vD(Y6C1&T8TW42qV zb*7b;vCjW_%WTnSJmfJ++n($fYiEEObc?7qv3TFce8=;%!fb*0P}E(GP^3Ovv!OoY ze~N~!q%h-iYyUBtHk*rJ&GqNL(VBzP=HfoJtB%Bfe=}Wg9I@98Y^bivinEt3q%gMS zGsYNctTxnkKD%c?$?CAsf)Y+DY^(cZWQyi{qDn3$Ik|7+#|IR$e{dULN{ht<35N_b zumyF@87@Td+LI%hOA>h0_0x2*gH9)5fUN+_7T#3)-SO9&Nhr!U zf#*TuQjyYOR1@1>0e*Ft&l6R{=C+5%HIdx5&=)+pORkr=%CBpEi`m}urs&NsfAD1F z$eFrkQ$A412kPYj8JC`c;X@m0+6sv{lpm0~>FMeJ?e8~1u&!yb{>`tfBuG&VP|R7p zJUduBa^Kk4m_T>b`B_@pJUAF7`tkm_^EvyIFklCe`yuu^Oxc$lc*O%SsGdE0f3Vu` z2uCM4ICug*9bVbd+iSMe5jA?C@~*SQq(!#TGZzcc!Np zs0s)p+5H?Vr$Eb`)H0WU&3s0eQ(2768hx$9(^sUoZMpn8mSEoMA|7`|+4O#u-Lnri zGm?sihR+;S=tl7FeE5uuk2JTqsgPXoQ}8z7jIF^pXHI|7%~A6b8(ltzHowNGf-OF@ z{juDZdro_&+-#-ep^7;a6cis3$98D_O--zuyZgfGYWsVnJAmM;e{)sAQ>3b|-xoz8 zUAda-QMp-IGeHcrDP!1*j*(F!XDEGila7I*`3=`(d8J)MX(@-xtQWUQTWGr7Z2jlB zxajzJMBqMu{v4nO5@ujPz=JyvFid~HM?!zXi41rGzy#zZtGc>+m~C?t@n(x4LPGMM zE?%~PEv2NQDskD>hx38}DJui=ffgxmL!%8t#AP62>UteGIp%xVI zo&EjNdBYi_n^hor0XTDVa=seHgL?`vTs=InpFHV;wdZkMK~GFf#KFadS~_UZvIXk! zyy0L6c$SaSwJv6ks^uxmya1aoD^5XsNocy`wvy@Q9^NYFpTWw9`!9A?CVM?0< zHf&N$t{0rlR0nT#R5a97`kq_GRx@*kCsNFqjtAMi5yT2O*kQC!{{1(o!a`n6TN`nX zc%0TE3;sYE^%xe?*Vh*r4b5cWt7!R!hnpK4Odj>6@CU#e7_vsDq$u26U+LZ>)yTum z90ZucI6FIoC_~_Ym6cVo7UO7LYaP&eRDWNi=1*@&^<3TpyefX-5w*2thD=p{@tkzj zl5=9kf-AWM)(e94?t=%a>gtlOU*~SK+1lEoKjq5TO_lJS@oRGpoj)zsDDMGCN*xVX4#YHBcRB`q%A{JbKs0WVR$?e~W}DCp?lK*BL;4}W`p zxbE!n1U^Uk<;(Z4m@Rq|*kH**0gP3Yl|P838y>C=h7z#dwy;>W)!t8vjrEtxoF7OR zhmv{R*_w#Y$ud5I3Bi|rpE;!<2j5MP_q@3}0R{%=MD~9LH9`ZZy8JZ!0ePD2SvcXz z&8Kg>8l_MEdAn0%Gg}i86Quq2i!@Q

2ekEU zJtvLFe(u)M(UHia3Wtx6k5o8OP(#BFE}1e1C<;;$B)y2bgg+xi&?62Za)90d+!odu zbTXq7EhsWKokaf1M^k>5qXOw|X?Ypebzr_;>i)+MkbYEERD2^MFe#)$4O;>qPl3|c zvFrc|>iGCLB{g}_l9HD1N0AEFj=O@3ujqdV9l1^lGS9$ANMTSM z!PopgY=y_7KUL7p>-V%bxiW|PU-I-MtqU^cPHu@N^WJ`Hq8^ zYV<=Es}5OfDX_Hm{{DO6qO4%Ha@8$!)rWl5uCJl~&bm~mAVHqm!O^j^r{@<_w*!#% zXU}c{&w1{OMsS(;{pP#q;O5`1ts`H|cRE&XSH!$9cPTg=CapI+{9Gfq~9DcDgx_nQ4Uj~!pU zz`~HgxAk*Rn$c*}g@n=LOo7X*ES0;#>au)_JJ|0;x>N}~-z3OmfWo4ty z2&n4be-vN!mVi`Os*ah$?-Ksu&I9&$8)_i&!i(1bvfYCW4QxM^0>SJ>L4GmJBLT7n zF{tmpPIVuXWD4N28t%nNTQBe&>6@$`uJYqO;_#E_zJw72cSoqG{y7g-Rz45+F#Cqv5&cak?$^7> zYZL7fnuysiy%a@qieERnQl-qOBV-Edi>eEyu3zS$u^B6 zM_rwrqM3umcC$jaCT+u-12FAYqyAsM=#@a6!rtqP*_(_(OP;q2cR${LxDX{xB3hsk zqUX6|xPScteRsC?BaiExV9#Rp`K@Z}CDXPxf00$v-`8VzY3>8kGZJy<*SmeCCsCmj4y%cR*VqCBOu zNs_LZ^`rlX@lSzy>mI#?uLsf-zJaIm)&j*;YFFvl@r2k&n%{g8^{c_23k|a}9Xe*_ z6=0ozM@A;%93PShB-HHIUj!33^q6x1SAs$_IxS5J5Y)`fEJf#dSRK+A{4AuNMj+r& z4E+Wc5!3m1-ijJR97tJY=futH>z+i8@_vE$fq}@>ieF^xiz{E^?ch*j*vxxYu4rNf*}u_wF>$0$iztRDJbQ>Gv*6;YXU>z_(KYI_ za4|x|_~g&ReLcRKhN&QZ_Qw}Ak3qOB_z!RI316R507^i@oCh{7jwwj#y!Y7FM7x#{ zx9?|j7+Iia3)aXL^N;w|zk*MmJYgk3M<73Jnz;C#Xi7H2-?u=>&^g*fh*B9Dw?8(D zh>Cu&c~A;P2*xh^$TSoyz-AEKTtnkid_4Z0`{>WOxhurG`%T#iAZs6h;>FA(SEXf?4D?)83HQ{hoC_uD@KCpTfBY6^p(f(rG4qcHC3r;)Th#EF z^kn{Smu!TB{`yOY3CuoZm78AP?H;<|kGDjM76s~0;` z!%XT_Z=s{jK=tqU8buF8_WqSJCJwClTBURJP={(>>@L^GUfP?RMJP%?^4mc`-r85_ zk)wo3HTMhO^Z<(r3JZhutb&Mr(b~lG)K9r}f?>Ai5cE*<9Ig)mku@&Ud24U~ySqCC zu++Fji^pY$2&z(e=wCVoHkzeFPQ~z5dm{+YQ(k2t&13 z$CGse*n%|;69GssXD)6$x#*ZO4{HP$Nq$d&@SCBDA5QPI$BV!0ivi2TJwWo1#|0E6D4qNNo$ zX!)(Yd}Ku6+qYK+Sf-(WFDAlp4HRN7jpw|y(|PRk?W?5dDRya~?PBGp#URh;5EetK1ZMj!RLIq}N~VWWEI+?+kk19Aven#Is!6B^i%R}F|HmGAN6zE0LY z;Wn^;iFIWvFt3THTwahJDb9~I9+ebS{{435s~`h=oR~$L$4{MN+ti3tEn+SO-%Ldf zxq8d1>~(O*Tx3I_NM@s8H}W?tCCNG>7Igw;?1e<{ zG`k@;(`Vb=y+nM8;Ul-d(j28d{mMeSo7{THdJiYNcrQ<09)rHE|7pO+zM1!^N4<{2 z_;q82@bLUe$Ui- zAljQVGc%w~m&avHGb^SE_44o5Hm|1n%uK2pwS^Kg>Xzs0#vjz}wLPu9KHr>nuARwN zqaWmEA_a!K0_DZZuFs7}Q4iIsU5uNh4fScCvGu+~liAlR%O{uxGVR|8+W9*-6Q@Rm zQ$A;fdUHK)PH3$q^+*^U`Iga8OFQU6lvkcVpX$YOu(j!t#N4F>dZ%OiiwMNs?Wu&{gyv9q z{VtoWZ+!8BJ4RzVWpAHLxGr=*znGuVJ- z{O@rBJ5@=McgIEl{R&jBLc3Ijdap#I0~h09ogRL1=YJPIzg!ihnOADI(O7FAznBt6 zRqoa8Tq2z{e0QFuIlVj1v}J&IKcVAnG_S{?B<4#}`6o>C z5fsS_-0MvW1%P^Zh6G`47*};?{RUSXnjnIGuSgRs`cYJrQ(2j?*d9><;xuR(w6wIp zXJ+c#U0652zkh!Vhye;JYEx(D`VWQg%MQE%s#z+pJ;DJ2qoc8ox5ht8WkN46s)VF>F?Uko| zxukBxuA@#dZ59$5SMFG{n5aayi>vw&AD-|sG_m!MLD(V*>A+QGVyyMaSEiZfuGMU^ zWpgpL+j*&O35{N1ma0O=M-S*Mk36)l^id;jvLuI9<`wnb-RWl6kalTT>Q5PCGSz5% z+}SzPexBE*EPb<`8|S4Kn%zg8XP!QBu)H~N( ze7`+GI^^WZ;(|kZw+1%m2yZ+Yt3X+pTQe?Q*1L?t{8xSeSOWSUrWGJ#9yNXzH4%zOF(WBT7`L0`piUQ zz93Z1)SR3+pn-h(@&!}KTk^z5ntmk4>m>lf}W!*wlfPWJIUs(hOooS#@!{xZC|qD4|a zcwb-NLqaI&H1}#j<6Fkn{zDC=poK76l;sWr7_IJ%wrS5k9wy$=J?;g-j zHg{DVe|>OiUbraiQ;j1*7rUtSYe!!!PH|=22Y0_U_@R8wE^bpYMr7%0rnIFy!L&1{ zm)Pc$4tP}FA>3FCd|~YxSuqDim}e_zNAegUjY^5#e7A5QRR@W)P$@7_)42I;WG>%tjP&R<`y3Y(Pa zBntZob;mI+&Igd(u8L zUCj7IL_MK|90>w$?Bbu$8+&^Tn#l&w4pz^$O8Z@p$1SuQyahoayF4FlSScITH@Q6B z1ABw5EFd7l#4I=#(kZd8$v<$%Pr=wB&-dQF#TDJfTMx>Js!*{Ue`y1R_qd9NUy+L}B_NJC>F;C)8 zb?JkK7dVb-Xf+vWp*VZD=236msa`0LW78v5wK7%}!Ec$;oIrg^sn*YEVaqB48#r3e z5Z|O%)MPh)EpEc{qut=ufD~0+bbFf8GcI$Yh=3ZCpH8C!xS>AIBkJNAZOsyUPEU(! zt|xmbql2I5JR#rCHt5epG__%BCt=;_!|#?M+l*J?+OdRI;gtJN*?Dx0{e(Z%WfX zaH$nQYBoFArnGU_F%enCmfRXf^)(f35qi|J(enzu{ZB`6XerafE%c!hPIkukI8tg7 zleuA>=18PoPV1Xrb`o+J{r)L$bB^u7zyyQ73pR~+k0pBQCqHcRMAow5%nmBQM+Q8f z^Hy^f{U2f9&3gSU<=)FjUc2h$+o~1rON8^d+O{|S(HnIk{t&t zpH1=YY%$!Q4}YnuYO*P)_Ue^9lspaBM@59ZKf?;ceC^Q!gMz9GztYmv2jlCz&fo7_ zTN#~-p@AX@Bwes&O#Pr4>}_jo{4g-^5|{wE)M^Xge+Prx|3n8jC*rfbQYik%-GZ$sN>*nH6y{tLu)9PZ2sc z%Bm6cyI;HMOLPtn4(>RJ&Sq@{H!{(Dcx*kN+7qI{m)9%6+qg zp5#f%kLk0GUpmi_gVCO@k{z_3+%Fv6NId}lzChoY5}M6gR%6bH?7|FEN<~3vC^`f! z1X^2ncXxS+QiJ!EyN8wU02Qi##xRD+D7*8PRw~qgBniX4d2UtO=H}FdgoGf9xbRRy zgI63Zt*>Vr8<9dilgrz~`*i*Rd;r4T0|ockm=-7$trj!H zTh6ad9}Yl~2}PuhL4PuLQGkme!_w@eN^%?uVaLE0<)V%Ych=A4yjSM^b~XE=8`){U z74V*{QpOZ|$;Cu6Vh|DL%Z)joAUwbQX*7(Cp`g^T zxgW00q$WLc8VCH8Ra9JoW*~9(O=g5p7sy<8|MG2ZLEr_yfV(>%h$+x#C>yUlcYuxo z_+WGRx7-DlfS*oQv2`rE;#@D6`yfLF}2^qk?8k;8_t$Bt4!|Y z`uIR;L1yxT{PltU`k(!rV;Lxh?qg(Q(WCz!rjPAH4~r#YM`>LimcuL5KQgK3HKx+N zC+nYzTAAUaS_=0jv>7%I*NOAz>Us2JClP=A5R4(5y}Ifa1VFY7+{uHM7t)x`%@ z4*Xm?Pd39f_ZPW&8*vBfkNil;5DOO>8!M@zf;H=NBPf>@4ccF-&$Zk6$?hzO&VJ0$ z4WOiL{|%Yc}G#>xX70pQQu8c5F{NI>=peeygw zGV&2d0UOGONi<;?ub^aI{xj?9*C{Yl4v7Jv^5J()* zYvpl2q=j$ufW-AZtS=}$5;Bxyhg!R-PxH-6H>h63{X3qtJ2@r#Q@;JI{kE&nZ%39k zY>%*z(X}MO%ZnQow&mTqn9r?#!mh-)bfdDUYU$CUpQr*3(Xoeitvwj8N}PV-{iZ@z zKZqs`c=7ycb{?nGpw(p2t8El-dR#1b`6@zF0+C_!YGd+6OWQ?*tD?HYJc`fP^|VNJ zWC35q0&T3TQiY<m}yrS3e#5gC*8Aw7-M z8(v8DThm|8_e+u(yCR{XsV;WE+2Ypfn98>FmhU@8uYczhh0G~MzRwP6OEwejyP-E@ za6$D}*3!!ro*K1}f%ce*caP5e`1j z+1WHO6WK$oW~k(X(W}0&%FV;$;9oQ5!Qqe+_T$GNpnKHU*EfnDbm%T<;C)5~%{PnQ zr02JwbO#AK8Mc`H?Se$P-K@8s<6}SF)<0P4X3G2L4C07=W2|5 z%f0?gbBOshx7cq7i0VCMw2e|@=K};iwDS6!ap{3Gb4h@Ca{aYm3m3rCc6w;A4h&k zd(kFKfojImTk7vY68JjbxJzMa=yTrZ`^2*?m*b^DPlZ!wci&V;Ea)3IJ;iS(o+xP^ zvCfN~vKvp;kx{J1JLgK1U}|a$&tKc=I-^Gxi@*|%vhU`Fcn4pDP{a9f(O8`aH#8pS zjz$eEW@_C41dfjn@20=-K3}Jq@xHL}KB<{4u^wfHGk_FH83brlYBfxc_}|Bm9}im5 zNtJ?OBpd~s`tb0VogC1)G;avl)0eTi^G>=SAzl&w;;c z9mksZKX-VZ9hjZh%Erfu%QpI)G`{2_3c^_ns#9oqcN?b(Q=bI(GMi}ypzsy4{<&G)~rR-%d2IEHcm6Um9jFr zgj?#DLt*OXb!`23-!8Bdo>C*Z*K1V=hONifHTiqEE-x#D4Zp456W~tg^;h2SC=FZv zv_7Y!uj4W9VIpHOZJpdv{2qrZBHoE$31>j;2DY+G@0-kW(kso4u^M<0)}x<56FXG?O|o?EZ=&o!9?M*5`cm_odJVwNxL<3nf17-YKTd2%t}A4ES|t z-O~D2yx~gy1zt=IogT8=+lMbAgnPR_hM7=DxV^WJy3AR+f~-$#&mZdR)_mlwOAY;t z!+xuiKXlx#t~L5Saf?@3&eK(Tw(I55#MBEu1JftJZ)cZQEooUcXhx6+Q>EFFE!C;# zUo-lDIm9XF7FI}%jzrmG)Tw>HCptZbEr)8p)3$wT;~Fx2GbY{_C1@GJIh#%Cxng{M zY9&C%6i;#7CZM~Y*1@mqg>tj0n?IQtUcUS#>R$~@Dpj|>(SBriyXK>-Nv1dI1!iXx zy+mC~%gL8`5h0-3EyDoSPtBPBKl41+oa;N62Zu!OMga9{b_7$Y!g*nDOI4e7_OT3 zNUEp>D{-3Vevl1{fiAd=!O$gMpaG*}<6waF_xC5B=LOxa{&0_ zED#$^BA5g!QQq|X@A>&X8iGz>?Luhvrlw2JKQ)EraC z!&d*bAB}qJA^YxV(*HNoA|fn&|Kfq(4O^jRH`{bA0TEH?&pP5Ncav16#KR@im9I?C zKZM|WH~YSHbKde~U0QJv%WGbO9?^iIT9>t8pI?1(Bx=ZQ7CWk73=6{)L4$jumg`cN zL}c{Ae#veB8&NtVbAY>*_oZ1r7Aj%*v;`p@XM0&E@*faB}}=-y<^RNq|U1 z*9%;Fkg8UHoWxLe9`j}nTS51acxHd*4OdKZa!6VlDb(}`+(u+OM7tCpKb|2Dt=wsA zj16qwgm_(-X+&pF+o<9=wrN$v{=r*P$QTd!WDSMwx#2a6>{ky)PA5-IOIb;oS8ck6wbm z4*HD(SBFC&;$&CkP$5r~g8>o>RA`0Rx7wV{`UnFekgrvJ0QL+DPnFe6gke)G{rC8I zB8*_b)Rv5%-t@aLgkuk3;@#UbI{i04HaWRCH*oAz1fD5K>7-#&9~E;+0%E5&0Dm0v(U6^aWz(AxS z>%hQ({V??~RE;#y*9M!%;`(~fe}ilL)$s)SBv?ngvp2!0WqH$F7JWou$>tYG{eKQ3 z3*cA-nL7Fc&|Ts{c-zUz-92=C2bh9GLZA;#2JhF^)umApM!@C^za zEn;*4PWu@Ik&c%EbCM%9H8F`L zxrUOOn)+Rh-urT|U1OFzxfd*BP;tC{_inkcW+wyqMzg50V*~{p5jYt#a&ik(RgQjs zeyotdbSq|)s(df=J?VSi->JlW;@{x0imCZ_h2RWV!Qk+~;_p{xBKiMJ$D)<#JC%qH znK)PCyqPvGff+-c=@DY^s6dtj%P+(W;>3Zs2Bs($!1VlzxnU)ory`@NNen)B4A?D{ zC}ldmpXpTp9UZ|$5{g&_G<=HhNyG=BoJ=`l0y|C7*ZHdsmAqxX17ctad@bPC25+m4 zY;0YfS4HUX<=OqP-Y;+yLx^HdGr%cSokn0EaCY8_E2$O-hJ=EQJh#*tqsfStUs$-( zTX4Fp|+H!k@A0z^bamX?-tP&tFu z2Rzb-c07Q_3*?8uNGM>8{R?7Ga_57XV9XK3-5FsWU!7l-U z!F7R~*lP~f28acOa{;EiS9%h~O-)Ue1d0ELZ=#h(ws~LIV3>i2mlxsMb#P$EXMXkd z+c&?zf7Kviz+$h$9)j@$Y`g)$#$n)9RrO8gnVO$EvY^4yffr`2?bq zg6RURWChIm;l%t>V4>kl!T8_c4wS@*8e2`xNz&vmHjU!g_0G~#%cqA=U7?glh?dLF zB78pA0)SqC^0#1IPD0{t47CDmZ&5|gh_#MJE&xNw*DX9vZSB|Azx6@O+$e`paBya( zB8w$GWz$qsEA}|C1!E^f#R6RbWNvxc zALexjJ9iDeyf>GsjQ%O@8@81fFq(U-9AueqCGRM{qXULso(Id)R-o zp2HfQfB#%xU7W3DMrc*qlL59^fa9F|^0`%nN-n~7^hL-kX<}kR<6va-2tpCzoB6Js z$(kq+g0~7hN*)md9bNj@ukT^357G<)sN)erhUl7N|K|lbr-j2*q4&)ggitK42_n7Arqvg0u2QF?TI(=mIYz-TG+#a1Yf=G=4SQxEsm}4&nn+n7U$AZ zi)(2_JIDONs=&g1QHpcmtheD&v@-qcJZ_{e`>dPOuIjKZsS-Dik~Y%x>$8k!^c_N5 z9QhoqtPR5NDZY2?sH~p3o(5R-oqajcUSUleb!#xNlb4r=tOVzr-FAwn@Ku!G0kYLZi@TdsP;6*(1cFDotlrOxFpFq)$`urI&R)$ayQT-P_ zbUdkyhj}s>K#7#g0x&o3*BN<%{fF%=FSjTj{%2x=6dEVQw5fByVITu_1)bT>%i z&qAVe#i}lhg~Ei!o2kku0Cl0uf6XKUs@u&21Cap3FashkCUzSR92mEN|Jpk`n!vz| zn07H(^}w#ZvN4<|Aua8Awr>WR9}Hh};}&VlUIr%BrJ2feg0J}cKVn{Kil zx)dFpcP7-mDWYT$PCXFxARd6;c7R1TZ&(HJNG_|XrN!^(PxhXk9#&4yZ$KIl^FZL4 zH)Yq3Agz%ZMNkevn8(+4u+*lQM{p|IPe}3c+XpkHgMx!$)aETbNTX)X`q_O}&0%l>kv~2F&KaiENFl)V0{Kr0@@1*KMqZrr*C2+p?h5_ z951r$5%z$cPx?hUaJ0eFjL`h3|%}`GucT23xYeJ_$%m zFwF}K|0GOm%s`b<;Y4PrMZZ8JCM6|IBM&I}9W=C%3&#wJiC$GDK}mUebeP4FPhkB3 zvf^ya)y_m&$aIZMOj42@pgK4rn=H!9%c1Txw6f}gtARRB_ZFjMC=piXbnyU4)_$wW z@U|^260Y^H5#~uIQ1Ky?MMg%7yn00h6J)Qd93;o2V;;c_(s)6;I>-#!3dsbJiowUQ zGg87IEJ5BlHbwx7BRENc*NAbMDkwaJAsWAcfS9d)z+^kR}Q50YqtgaenJ zJmcZ1l@H zYb;efW|MIzrHKt|yo0GekoXf>Rt$pKdhTs+alR){HsfPs48JKzXR*4New zAXuSQ8O)WMn43$zdsk-IlsB{vp^}}QEmb)Ke?thF*xH5%1);>n#Q|tTQ6>(@7B1cZ zDF?!hj-Fl&=H&)0-+y|Ob!@7|86*t~;5RVflai**>Lt!Jw*hNFWSTyxcicSwKvOwyn8`0A74XjyCVAltt&bMX-igv4Rg-&Q51<2mLSEn}=H}+KIH>0Rsb0Dj zZ7ZuDJ5yEQFRs7be-X#1?OR%UAQ;x*K|42=?DK4`fsh+t9WT<=6uVSO+em$M!dVBa zqSs=?pqbXvJI`wP+x0$EvNx}k*4F6OjUkq^%Xkg_>g}MtjX1Or4jIP#oM#WIUaQca z?%0?!jf*ZYoo8`zM-{VRqwr(3CD~nfca>lkY5koR-ub_TQQdTh2}cr=%-nCJrsn3( zt}d~H`m>LJpilrWHq_U*)`s)&(eN05kBs1b9U^3bUs#6V&7`FL(Cat_IGe1qiIEN%b^{37EdVaER0V z{QOFXWz;8O*{ugv&oM}aLZKo6mwZZa13&03FgJrz?+lo9_x}Cz8eO<}9OYo8_rELi zgm2C;Vd%SlRd2UC_`E|$gY*qGmNxJF_VQg`{J^>&*<}nru3tYF?Uf+M=EwIGNcrA( z8atL}CGuh+-tOlFe{@lH1vBo^Q9{#a{Qb^A6pE6sZ__imRcp7>(-<^VzMkr86jjq< zX;tsJCk<@zj-&9JI4d{~g-x;8^oRm{g>kNm$~m*DHaLx&R!6Ok|@;=DB`DlZ>8 z*KTBK83_F?IID=<1T@|rs(Qru8l+gnFbYfkDLDi)@q_`4>gFh>EWr7Jq~$o@bPvul zALl1v+Yr-65a6&!MsME87wOkQt@RD6I>_~+epShaIMDEP>=$(D_k;V_$jLmu|NM#N zFV^@&J&)vj#UivkVN@32ABdtapdrB;nI`<yQu&V`!ChT)ja!;|!>H36JEkvZw3FCFnDwgt5)-vU&>uz3VnSYr;4N`n zRYb&kXXj%fM`vgAt+A5Or`+K{eh|?C_5etVo?s=a1*a`B9t8|jAj*t}%YC$XW<7E? zHsGb7F~Z>adZ4@Kwj8Tj{OcFc+WXMx1u~nPpT879>itYW;0tirY4w+&cf-%v!+b9pA*9KPqhh8}Cq<~+B* z!>5(E70_RlZlDYtF$>mh2Pn@h(=S{?GJff^S(sjw%lP*)~`0Sj{L;qEMHmP#kE zE~K$i3rwi3RzXLz8m;%fI?}Aax%MzNHilao7AMNAZOpHxx+2NMwSJnSG&VMh@xm-F z{ijc#0Ke~}6Z{4*DuJ-K08}>l`gKWm4Oivyll${^7g96ISghAy1KgomVJ3BV>(&c*_+zhr2aqEefM9FZU4WSRidaA zrJJpUN~LH?dub>kEfr1LX%W&M8nlO|*7tc{_kDftzv27-!Q*my z&+|OS>-Aj6Od71?m2GWAS@O|ZF8wP2J5-woJH5y4L>XgWWX!W7ePrg4SFCZnBc(se z7$4HKv}@0b?eBY$kUt&&k;Mn}4V5UNYJ(bQ zClT8M>4T5M#1{0ECIBT7y;iKfTI4WEdoh@P7#IuoHxvbJ$&`k!1ZIe(!JwzeUQJyc zt0pGOA<H!D)b#YeJ0+-si9!@SNKRg{rt-C=Yr48hAUuhg z_$izd=)+vA0&mh)cG|T%JF{y_?h1ysXEmfbk4n`3X-rX^H2cyEv5Jn{tZac*&!>(& z6D;MUvxB2lCk^}qN;$SWlkk`y^561$W`CT2%ZM72^^JfxzIT2mtEyRln!6FmbnxCW z6`lC|4W7cGFU=2FdvL4yD^T;~*YE4P#M|CGlc?#DbH+KSN{6=NxW@O4I$jc)B)R`C zIH?Wdr=*mfokgG()5EW>s;MbBa7|o7LjAq%3H;qWrwQAw;<&g##D z+hqPSURd+7IsuDf4wv^?j|dOn<8eteekzD5Oec$4{ukbhd9Q3aB`O{f`1gsvp6~~2 zJbZ$;FIi~Qp?V5B~b)Cza%M zoYW{5d2-klp1@2CBOsSp-# zAR+aho2$C`9!T@BX1rie-~^C)Hew&!{Q={wz06&#eB-bABSi~DH__105Ln#Ce7a=L zt?Io1`r%A7fC`3N^ny?*t{k2d{C7pbi2MW_+u+Zi6#yFH87=huu{S8krPoaH-Rt4n zl#jyv2DX(>j$dw#w1j~_pe^ZAZkm7%5&|F0%N?jcCKe6G98LNCb1w{(V+fXC(vi{Dht$Vj>pz&{wlN$SOS_-)sM|SN$+7FLc z|KEl2bCs#xsN)D3k$RqSkG<5F>wgcUnHGr3x9TanaZ2ARrXRqso~dd3RAXp?6MWm~ zqMrdb!dbf6&VP)P)?SEQVXceg)inl8i^g(>P*Z}VK|NtT{vz$iI7oyO+}weZ=5U>}?J#f0F0c7az)7lnlMaj@P0QB1$a~#~)!7UUVNj{xtQVlH)8eSzgDs|>>McL>YiaWmFWW?yMF{Sz z9qiO3@z;zhHB`!LB;eP79-&kHWqV~snt+Z$@ckl|2yyWeS+;~J3V$vxE+SeCj259wg8Lz#L+G6M?L|;( z*2KS|Zo(RE#&}3wO%2Y>x>s3cL{%huSQA(v7LpNE)xfwOvL!feV_;wyvUN_c8NY<9 zN$6s5B~c(F3Nz%rfwgrDuIDL!{uGQ4p!#?Us49w1^TJ31EdY&O0uTG~JB_dcEU&H>a=6ga(3~=?I}pLGSp%j3 zmQq6_qtlL4S|2N4`A@l&MMp)=_(`ta2l_>{$#5k}qxp;NLO+sgP`e*MHX-9fC-MFY zdkg>wq7s6H%doI&FPXY3vDV@;Ah+etRw5-K5D-0x9Ni91{`>2;O@i_o*L^wM+W!sHj z1G?Y&J^396vr)x^Jz6DB$}_$q=x~Fpy1(5R#~?yS3>DlPs<8Zmhrz)_WYXohGoiT2 zUIZbBdkKmWOdL^D0^)Kw=1MfgM16AjuxFct5j${AAtEq-XKZp3B zjD|mWeyXR~+eC3l|2W1R@mo3$Ch5;v;Y3Q8qbhs63ukSr@gG=v&-zuJfSjz@7_v>W#{J`Va(&c z%zmT}aN%^S=y{NRhWpv@#O5U9;&(wOVY9PGl$BGvN7wy+u&|0)8C|4(#@YYj;&}AH zx>ADaA`R!m&Z_Q-f;6X82S1{$TW+RX{bc3iZR9m#UO_HYzsOz^d15W8)a`dKM%SBHOlmU?haV*tT2MC*#|Gz_^o{+=U{tOfx?^K?|)Kl)@O{}_qL;r>Sv%tPj z6Sc`sBOSA6Vs6(f1+j369?oxmAd_)e(&LnWvAKn++Cs!uG7_0imGS7M&aB6|bB0s9 z9@*I6@wq_FVp(y4systKt?=+z)pUEFFh%}>lr%;$(4qf%q&9R@C%piYkyXAC1724@ z8f}Ml>4Iu369FEe&joTuppD3?`to(4;2daMUEN?%QkeAMyz(mz;v_xk>FDSzEG)8f zbH_dpWh5s{)zPCbmQK1lQ!BY~kUDbl(1mW@7*TI@K%vpmm(alUZ=z1~0_`LuBvcqr zj`joHtQ5>Ww1FgvFf`m5LpU`X|;0J{>q@Wp<2EYKwGOh=J zwF6?D%x5AAP&3H-S2wea!QE=p-qg&v5GbhX`1Mz&ky_G)@An-KfYc^rz!+Pn z0EY2Yw|_m;w8Hjk|K_LSbXxhh-|O`!E?G6I^5<22k_r5~zjjJsQ>8#Rq59{fKN*wC zd8XR3vg%e1GoLUO-A=1$y$VW7HhssLE)sqDo98AzN>phy>8lo1(d&Dq`(|WtK&WK(y%3O@ z7w644Hj|x#_)nq-5e={ZdJIi3koDu3-6$4oK7D$5Wwu`xoD!xWRG4pFDNupR7#gww zp(hkKgM;2uNxyBVTGs*I`Mr3-j#3f53aa|guWs@}MIC^~stq3O1cFFHiKhrg41gRE zS)0WP^~aAN6S@OTc)X74*sr1hj6Ohf$*3_x;VbCvvwu zILA{3?Uq~H3g%Xhp^zm|0jxc{bl9cFq-NeQN4?f=s% zwv%D(UoF5tOF)0ZK3NdZ7M*YXA+XX{4=bYdw4?(rvhPIuT`ZZWW0Iq+rJ zB0yE!y{s;I{@m!*WKXOL@`#+A-W`8~Eq4a0_1^EXzs{#-aJB-OLb-A->jzMYoVRZc zfv5ozC~&5KevJe24e(q(n5dYSaEYM>x{3&EW7pLnrf~VwfX^x_h`t3u9b(tZR8>@< z{S-lv3evBLAhY}T@3#+32rHtKApk4jTwX7JkBrpxZ7d2C3b9)~;J$&w%7BUf+$dCv%`TrXU_0Tx@4}Y`__zTc>&|acl!&>>l#F&Yd@(93w$*C zOIsFGMq+t~L5gP<$^>842FWrybD7z5i6t!m@$}c#IcF9_LB=<+t9ZAE z46AqgOv}28nr6ty@S}o!oNRFS27H2ol9B)_B{$djp}ct)so#4T!7~;XT!1_YdaMzKu}TAwv!uIr`Kd~lyRGm6 z8wT$31(HK7SlC++uQ|~RLFxyXhqAHe1Q2l7C1av=fB!yzhPj9mmke{C$o7$8x~>0O z6S_#|)8h*+NdlK4iB?hh%1CKp`mRrqmJH+M7#|z8^O=l{3`PNgr@&3F9eB&l&F#E0 z90`BL)9hXh5aN^-ILHWL5Vt5puQiGX5GCF3?s%ixCTi4h&YPmwD@L(ZWM*3WEn=Hd zz`8;lG=ZgEe03rZqfXDlqWg>VZyMIHcDE^W`PE{66J><^ldl-QKN|#LmcgpCGuEl^MARb19MR ziG>XnV-V&C;9>j#-6>OAw{ld2>AAUt9vK+Whh*7DICAFVBZDG3u!rJ*8u`KX7pfsD z-v8ml<0zL~JGew!6vz13LSkApF+KQMJH1N525CGiE_W~-^W6Ep!} znv8wRfZLD~{URhVckbMYL&)FTw{KTzEXM_m_#i2HihhEEfgxD_`$q3I9I<46v$h&o zHe=XJggSv80lIrc+{xxoU7b0w<l*5p;)C~!y`JtZ7#E7+ zdx?(be@L~=P*O^*Nj7SBY_u~#GiRHG`?^O?+$Fd}dI@RzI> zE{txaK74pjhcrar7-j*7IkAD(m7a+c*)-xf;isyoiqdWrP ziAafaIDPfs!FDjzRUvqvEbvWY#A9Ra{-T76EInQNw@_nKlX|w^*7N7jW0||m9vgE? ze_L09BZ(0j|LT+ z2Dr8=h+H)_yQtEdF|>$qGic(_sQ~KoI%g+I^fK2^Cf!vB`N+=0V|7zC3{57a3ZPl+ z-%Gr!^Tr)@tHgD)qV#|EF?~#*!r!sHZfF*^4Dw+m{tAx^8sLkV3<${Rfyv90U|=72Ju94Q4usZcN2r34bY$pz{Lbs7`b&j z$+K%2KyVxn?T87HV}a6+7_WAAhf4iDQqVpTvE*l0C-@27EF*d1u0ZJ0C=MN}!qp@g zE-by=8lM%OUjz7B8zX2Qg~p5^QTh2Pu@HdAMUu@gxHqZWcsV!@=K7&}#3fuCRr0)r ziM2F1Gv&4Kk5__TLk#zX+8QZmsfNeR@971(%ryZVo7Q{dXO&blu9w$GZu!4Wx!m1F zh8l;E?e`u%+J_B+*gZi@6Ro#Bc5pzwxP}DZ3HAkS?}3J9kCfEs&u4KF5F-9% zmsI-%DRGbqCe7sparFZqrX9-Vkr%y^_H`5yn&ylTSm9^@CHw5;Rc)D?9Y9K@Med`&qv(CJH1>VGpm5w#8j-0751t1#dGn3d0Q8FbxbUzF z<@%*~*qDAgB(J2DUQ%+jREKvrJFW**tuUx4KthCN2v<_dW^{L-3H7P><=i9^EHx+! zyTL=z1H z5DT+ydFALS3`S7xh+k%*`Q*qlo_R^`iTrakAOK6T4iQpbY`U0TM892Jlpt|HPCII~ zTG?>Aw8{4ey^(ZS%e!#Ouo3HDGrFRYSFUSlbe?*Aj-nPJ@eWM;u{l9s|g}Y z=Q&!n_L)r2+Qp@FS6P23?c4PB;&Wlx6_z=h_$&C&_N&Spn$OakGe$0uCLR2B>E`|X zQn5kSl>wf;UzsdFXG(=$%NW8@BZP>VJYG%!azvo^L>x-jf`015E`mB#HC6P~GB|ESKc5WPFml7Cw8? z(ZsMxervJU^^?`GbRh1X03b1Kt{P({*_o9LwKQ_z711By&e9w?q7OM2z+`BHrXtj2 z=((UMYDZcCtkc8NY!rcTaUr_}$kkD(O078)C)uH~!grk|&P@TBWe_ak3y3#AY+!p} z^ge!}qsBEw+xS|azR0P#olU8#{esr=r0m4#6q-%moMNv3zyQei^bZ}v9bI(PZJlL z&;(+D9ph7%fH@lD3C%T*aiSS%iiK&wB)EF@87x_sl$2lxIs%8)&peb2Nu}-=H5v>3 zJlWFos_YL$T!=4^AGUpe`~a#alttghWHe5O6Ke_dy11V3v*@GniBaA31!>Diu$K@P zOg{Z^TTkyCKsj~}j*tJ5%i<=wmc;gB76ipAJJUN>BRL>L5x-a_!ysg}!$D2q}87X)@}zsbQiLDN{skE?(oJe=NM2 zrtkDyr%$gI5B{dV%x<8@VE?2);qA!R=XuuE8m%UlMooj3mltlFwoogh{$;Nj^))oA zBI2}DvyS|(os{%>^jRa4c}7!@|KzffX?Zhzn|J7??+T65=6Glf8QN z0Pq7UR;6pVR~2O~#%}Zm{|!fMbLxc)^V5 z6aX1N875TOsDE~D#R)4kXd8KS%Nnsx5fR~-g*{gDl1O01n2JJ367Uo3?hYIc+#DR2 z>Z0rrl!fAC*u>m5H!!gN%~p@}mXhKm@l{US^p9)PrDud~RbG_c^{dm|=}O$r$2F27 zF>g-jJ+kBEbKAV*+v?f9q5@q)z!-g*@ky!3v$YkxPrkUNJdoa{N&V>h>DTc;TYOCq z=hBe1ofez1wyqCVl)fFhH$30B%lOtcM=zzJgWWzU?-Em|_f}au@0KrP3%1!`aFU8+ zkM>l{ywczox6sEE%SYNId!>2r7p=sZCI84XyD3V0SGSE}pGi}D&Aap_{l9giPNlR` z%aU!m)5G442OB=iOr47~d4~o7OMwjxi2#y2^8+FN!Z!F?BY!VsHvfq;mDT}Xe!9$p+9%V3SJ%`nOE)6-}!Mlyjy`Fp?_PG4R=k83CW;I;W2lXWN8Sfhu+vwW; zD(wlHZJr=!RNuAuRrR2oLiZwXmeD{hqlMgVqv_Kp?&=)$6n@yP7-?>V?HRu7_vQ^V zBZTf6dYwr7@wS1nu}@G0qqHRlW~2}5@U>cw7x0ZIadDRs7)6|f*Iwex5ArTPz#7#% ztOdSkNDC~xYLHC(fa~+bbM^Oqg=BiEaHkwb$s6&X>UftDd9Z&Jd*I`fI0^W|BxwE?$uFo zr|g~+L@-!M5ER#=M+%SZ zr&sfSZCy7BPkhw*&FiSaSJ&KfP3Pgpok4~iV)l~2E(ER}s%(4SGN8|SktyHE_Fm@MNlu>6y(W zNrRHwnfcYzO{#4n^acJ#Dz&HDF9fCLh-FpQrK`_-?5#$&8M?YRpBJMsfYd%bgVLYRf081P#hy}wDySehccQ+9U3%~f1J0_ z1J>8WkN1DB%DXcX6+3>&C%e&+)Sx8MSb9F*>uT=w_XvXmpM}BkJrZw8`p%wHK4YFP zxL4{*HxtE5=Dy+n;>kZL{_0Bt_;sg@SI%GG(&4J!erS_7kaP5Bhd{o5N9XSmzuaKi zG6NcZ5AFfk`iWJA%KQ+T`p`Pd87Jd|u}rirw;j&JQb`8-Wv-2gBo+n4@5$6y&N zxN_{PQ#?!EF>xoCS=NfYF8fZaThlEOgS+<7b8nA-^7*ib*YR)f(j%C@Jmr2cO>CZ?=}=t+#S#S-YH^P`4s;p?(6Gj9ieftdv)W%8R-xnt|mqhIX9-g}r3Q^z4tx{-_G;3%o=!0VX# zqp>kpR0U=0A9x(9i$2>{7}+n7q+tAO?U&l(6_-c$0x#`u?YCqaaoRo5rIhQ~+e2!0 zW9UTffkfMeR=U}$zAdiPX8NTw<;(o*DKyucHVuCZu!mK2tVG%@PU+S!>C?@c^Lw*I zhj>m6UDlkI=BhckX0;{rqIFYLs8FgWg*+c43$MDg!Y@iPlf`Lfah_wpgoS_h&a)|e zb?V)pni8rpDBel!_>_gMI@`L(uEL<;fQP{H$Y007&a>OnxeRp!NE#>acz&Zc4}3C| zYU5CLtodV#`EH2<`aY^WW7JY&`M737B(Tq<_e$GZ@sz zHo5fZ_JK!3%SxIGmz7D)(^pj7*`F>jKk4{hIFUZiO_-c{GJ z6`%d_`pDO{-Y-v|BpgsGQLKJ>Nz-3xo2#%%$%PkkN|)F~EZAP%Y7Q$D37NNlwOd(Z zaAG7V(w%;kL;h#5$w0SCeWYMZ@dGX7$%K>a_k8V8h zi#M_UrZZxfx=%Yrt!ikLELxUxEn1O%SD)SS5>1(8C!s3~1~;Pi8ZN$*9P``mtc7&$ z`L9L~7$hs3AC8at8~Daz8jPy@Wq%<5}g+*mRw+CliKVIYp~=%Uej4$8rMUydu$C zfZEYh>;ZFuunJ;FE)q!F{j|R6l5J5rQ>+iv3%T+-@3NF1J`{g!x_h%Wmx?LW;vV&2 zx6zRHV>b1U&c3Z=r^mNxK9p&*Dtml4B8=YC*YG)s!03c#*~2?!j;BQ;ItNd4+}pAw z{xi5br1uO*A;Wmf8IvPI%ygtyg8Js_EDvS);@G$io1M%B>XRnK4+P8aig|E_%hg&m zQqqc`#-Gk@b6mXxWBxx=LE~>amGvLYW&G79?b`AxsIhy z?PxTkkQb<0V-7Le)%wwLzu5js!z9f?HV!fMGtLKBgR-yyk6Ok$kN@mAm35vaH}P#k zhRycIQ`Y%jO& z>u|lpTy`v4aIE!G1j*e~&dgh->9R)i52!Yg8k$Rq$La)L6uQOeT3K)^eKbb5t2US8 z{>0@yCSOekc33Y``l=k$t(h->kn+^|;M&4@A;r5^@BB_;KW#|7QM;5g$NP15Q}mgE zcFELns+D88jAxnNn=>5@*{D9*=9{7S`{<(Yq*3#;8uDCeH6f9Z%uB0k?|DM*@ve8> z?0ME|(e0{rK;1y0bncs~XFOv@` zvs1i}x5{`jffRyk8BaTlX=uog@I62vo*w8ah%T3x$~SwYSc)it;KK=+qWWs(=Of|h z{yQ8w@9H==?ov`xLT?Qpo7K|#aVA?%Ol(Wz%Nm-Rd3qnW(K`AVhc`e)VQI}ZcU4cH zrMjhze43QOwj4x|^YT@n>_4%wEqddZ=tS*9R>Aa{2bFR@0e`Se&hkt9fHG3fxLur>Fko3E}iRCP6-X znJBD2PLNr~RAt>FZQkMW^|g)OwU!!P0X<2-E4qD${Ap`qDua4P=S$G)XhXyEf7&-FUzuxY&OS)HfuaLmg(S!ds~DynD2RK`9AZPkZ%3baCFO-V=phs zoWEYuT<-ou+pHz7iP0ji1CEmA90%tunkh?30g{!@JxAA41!xAww_J}~vE5E*F?~wM zHYGdLT%ggjeZ5JhD4wT}0xfCDOvOGo1p8#ZG0@Zd0NW!WKE;8#=%@ogf4((egZi8x z*;LSW0%@gAlleb7*BcKx zpE0HIcL=1j|7Uib!PRzBX$|=n{o#8Pt3RKk*DnMx&W3b-YI&;9C|tKR(DedpB=(NWFTGQD_}yY0){H>dj^Hj(Swlu5br?-{9~v*7EC63RR^`L??I z{iVw>tlf4`K3_IZ4T}vG$a!)*?v20Nsm#M+v^TG?np?@K?RqMh{HCa4DR}3Ott*TH ztXZ{>4QldS7vqc^E1f4-|9GfGefeY7oh#rca^disQo(Nm_cL3J>^!tIwU)P->oAIx z?%bKTk3-}7rr236xFiWh2i>-u}__s~CX;4XaF#Ojz4 z{Yld0g-Z&_X7b|8msHf6g{vP7*-U)g>xzZbMRV9_-^Fz5#`^{~$`*v~@!xX!OV!d` zTy&=D&nx|>`R?#ctnddb?e49gHs7t<7=3ShxJAz|zdDP(o}U}UOkDOiTvK?_qwW2w zO=)0`kwq**#4ufxqpOSlP;6r=*QW~6q2BK#vpKW(b}22Wnz={!M2OQi2!F|T3n>UKo11f%ul7tk&DFCJWF~~p!^M5;Jd~`LKUfHnFLx~gMv&7+KkX2;E*z~zC5h830Avy@b zx@{`Sq(!Fyx7h{dZ$ch@=gd*?*tD^ewmeE+F6PNx%nFR5b;Ez?7qxz`806{~l20rt zw3K&iSEP`jKGw_Ft-Fi~W0S)Xyu=EU!5^-pI{pm2EmpP8Qg-y#1qxy!Yg$ zc--R?D?_YLRod)V)SpE(S-XCyV-cQ~qWO7eSMYb!jHHPq!P1E)>Fwv9ZB>%^eDmrd zo4ne|?W7aY>h4^FIj2k#$a>#Y=CuTpiy3FpIa2D$f9$>3@zA+mBSDw%b6)u&ei7#m zHJz;A1#6Avr6+0l(ng-dc1|n0{OEn>QaRQC@NDJGpmm1P`kaMRN23(_qF(FL?AsFgJN3I5?+tR}u+?j)Solb{ zm-qRN*LDoWxWxJjor)%>3j6c-0$Hp^IMe`L~MuTepO#Pe&9H&a;O0y;@f3UdW=5y^a`D3t0ztvB|xM_ zpSSbHhfEOqK=`X&7cFp%SsfrY5x3=2@coFSGhMjz^Fd-kfe;gOrGJo6l)&w4s}wap z1am*pTN(?uqz13D`n>M0&B*La!Uu21HwKJ`Ig3jKW*@X-;?yOQ*}6SeC*4V8Gcz;Q zGF73$zHMgq6LxvJc>_13X*r40r(KSgQda(AB&fAH6s9El$`6_vzsiCBvel_U&Az{F zA&ZVV)^jHP`6FVU83VdylzaVUeCtOec*+xLjeqWPa_^ZKw=Jgxsi)<` zRjqdI1E0dq;rND@5BWx%z4z|B%Qioc+`afba@3fY_fF1O5QWy2kJ+a4bT(y-U(T42|F^Ltkt&h_Gz;0%@_P3`a7fx@7+JaA3M<@Vg1wmq;+{ll95U4 zD}85m@D_Kl%Hqt89`oJbkTTP8xqZ?BhXA|OZ|T2fX=!;mM!+A3QJ=OS`?ghk1}3%5 zXE=uyyCu{=pO(s&B)~!mzxeZH3T};B5YJ~^7h9WNA$;Z`5K1`1z%)nu`jQaQx`Y`F z=u7cJuG#I|NjW*_9D|^}mH|U36dO1)V*KAD8C*+Lt=h#dtN)$L=zp)LFs*RlfFvRIEva(EY_Oi6bejJSZzWLnRe+;g7 z;Y38tHs5de`UP36JTpfu?T*}|m>K-Def#Ki-vZsb99^@lP^0_0uVqZ-=dzb2AJz>& z`h?VFKUq(?*4BHQ?JR{jFIDzLw1Vzs$6rZ{3$`c!S{fg_vhj8Ms|TO7LW3vYFW}a$ zS>G7gPjlv`mVjX9x^v!;gwk;E>dPH_dwI&TNczuZ2axPu?(+8PT^gF+y^SoTw6o&) zGNmd)qDPZj`3U60tLlRR|=zC=Y2y3ezGST?hXVt z{jgU1HoFm{Qn@r+ag!j^^f+_7 zmBp%fQb@;jGM~N+K-jF4IF|WS7z54qlHOlhTPxn(DYgGu^bE81&#h5#f$$NlXlXS* z*h5LO?$oLRy7bq>X$9^~pvrpiY7jXp2rCIdkfhB_|3@82#8`VEVX&Wa#Sv75)1MHY zCx~|(xs3cVG%4rdFY(p4X)gBmGiJ%-nS4?%@ldNEsHL#iD;Y7{B|5xVCfY58kQyWS zd)*UsGzQx8$#^g(Z}a*z?Cb>g`*{;dzDTk;KdtaaiC7APMHtUq;!v~vX}q~rZ%f~4 zlG@9zU9VhU50$@rzv){ft^JYCMrB1ZKR#S0BD^JUB~m+$HISbtuJT+|uG;Ef-TLXQ zln*bQMo8yh>g(``WQ?nqTl0sz=82S6lZAE+{jx7VUZ5DTt7O?tFW!XV@3#|ShhKfa z=kC$HX)CQ`UFzZX?fcHiEgE5&A1~M4s;1quEbg>_dugC5`SR@Q`>RQJ)Jfx3MAURU z@0lo^cq2yoa?Dj#gG?@wQ8`2;C8{Z&?2Yyhdo@GF-HZLRPD%zWT{+|p9P`I0w(8Z7 zWN^pMIx0#RKhEC$AzM%PNwE8+v$Ew}&mH0^e|fekuPl>jEuCesI42QznWH_8#-_bC zp_E?D_72T(?Rr+wlJuv#h1@6Rou5Th7Ks=FP3zM9AC@3j7+F{zKq7J4d2WbNkS2l8 zNItRe+cd&WOcLEA;NgrSY}Bihg?S$9E>mTzRz5P7>;eLB`^?@1nI)&DvcPV!0wxUu zXr1TA_T{lxSvJKz0zyKB#SJkyNWaiWo$dBZtdEhGHyEyEtVB(ShB@=s)B2_y%S~B4 z3B=a4ef?O5O8Raxvg%)dpl%`-fnBAWP#Y|2X8afcF;}uWRlGKKvm77#0HJ@j0Fz*x zYJ74+;Shzpcgd1x?jZ_)Qf6j}u-8F*lkdd_P`@e?@LTxVsrtiwi-Bg*M8!^Hg~N1h zH-1i1?O1u?YIXQk0$t~|oUhuE1z*ldM+W78$@!wqqvh@--h2M6?~yJqy}qXk8|tSX z*3_|z?c|)G@eqz>;C()~B`R_##8sKXP;;otY@6o->!+oKoGez|LXuMVc<;Nnvzaoc z7Os3-T-@=^+W4ywLloDUNW-0*O?4ITKOePN*8J{zSaq^UC%rRl=i)fsJD=Ua{mzxJ~K=42WBe3mTJv|#I2-W$O~*K*zOO}|OAwXK!q zchRDvbK!a=5Vm5yvz_e2_{XoC``mVOouTeHJ)^RudP0J#vf$l|?h#8*NzzjPBDYd9 z&8vnqB;cCZn3+>*ah{?oa>%4<>F9FQxVqi`G(Jc2!m41!-P?M0ckN5IR365F+>z@&wqaI#}Ts%t#jJrRZCmdH>W zO^fAmE(RX?hp-8PCj0|)b~J`oE-`>{kObDA(=Tcd9Sqe`v*pn8U~HNxd8*K6`AY3i z9jz^OXTAIL;78xSG07KQZ+NF$Uma2Q_(rh!rxfzcThToi+N6h{O6ESUkX+0Ow)$Co z`SF~}s@>N2n`OR&N<}k{*Z10qw<*XTT6_I?j=Js7?|Aj0vTsJ49-9vZ3krr0>j|%Y zE7kEA)2oS&?BX}oxLVaIYdrJgn#**`b?vunP347gUY9x5H&xGjw#3*EYwQiXzuoB2 z`n#8|SASf)*x`NR`pSnor>FS}q6w1xB9dGm%(gA$SB>UmG?pyRmt zBCdAPTPiN6zi;7Cu*1F#_jewu6=^PdE?a%JOR%lf9BGp(M2u#fqDfW*f3Mr0EAR|N z3z}0w5lu|~xB2-C#Vt4*gNjS-1N5edd^P~vOQ_h93fp9CQ2*q_nWOuCcHKNLC$}4! zx-i?`=|9(}y-Tddi2<2*7{=r;8E)Vo5vEYy*8&1pY?aCX@mqW-6}Lte+_aqrU5JdP zE?fS&50MXQ;Nc1C3+Ni%XAhj!P`#a8{IhwrAygs1T63{7@>}m(g+#Tac@Fgl3;fNz#mCEDy>MsGg`wly z@4w}m2sLtwImxc|+aRy$@+a?DcAZlX21_q5+Q&MXWrYc9YCYx3&2b*(%YD-Hc___T z^RT_n_VG_#7Teu3>4XAKE~(UQi8!Q@>s;2!|LoV_ZJe@7Pp{^`-SLC-eX2#?pw?5L z?-S|ziH}}R(yy`Z6B!SvE4db!O1am0!~Z1Jrt66t=JnDIiX!fI{rIQ1vVtsKM_y zb&Zh8P_i--i&6`syq9B)2SYizPbXfnwoWz;&2NxRx^I8`bZj5biC0;VMDMaz-*9dJ z>vT5SpIY1b2-O6qLWjn9vfY<+pLUVPm3LREI8!70e$)C-a=Oiph$ms4M!KxqyN*>` zxW8Jin16ka?9CWw?i-^muZKoNPH$;w-Ilv5I$7l=Wa&7&wyyZvL-Ep|ksile) zI%>_tW;Xt|i#>G1PbF?DRtpKUnB)~Cll&NTzd51h){Hy+B;KMwD=TFz`0%^#(#tN2 zO-XtMTWQYxvGwbXy?x+g^)qRvd+l!WiOsdf`$-ZHd%iZ@lnbXig7ISRHO>1dxQH8X zop(Ps@W#8Gu+1t}vyG5o`%_7vD&5mb4pZba%$3|KuyT#gSFoh%6@4ibp}eRi65d63 zs--z;+0(4uZu+pPVUN#3@0GRu+^D$gHrB6ppWWbL7gWu5+JU zNIs4)5T}PzDv5ver(`3}`$06zAkw0VBMz}hq1?IOHA$Q}H|RsHLm2mZUJ@Zw#Q8z2 ztbABvz|H$M88hRYS-;9JlV0*~%FuDaZuk+AB(4^87)>aKQCry{iEU%0#dH6=++=AK zR>)pEE~38f_ojfT<{;xn2JXebSKnMBvUISj5$*%DW&br!zlR)v5G6rC2!lR0(+afT z&LAccVP#m@QW!KG4TYun%!lpBB63{Z=zM>dP0V3J56LHpfS~rPL^|Y{T>P85AD!?S zH)eURn?thsw>-y8= zXBy05)pWV6^5>Yt;O#jB#ccg!-%jgzubmZ7bedWDn5~v`LaRphb<3kwo9!N7^%6WK zdzHEc1o9<4ejZ?u><8B4P0rsos@h1sskSX&+^pf2w{UEvWN)YE;GfX8pVjWqwt5>+EC4+o#MhqI{S|@ee!_g z?P16+IQtWx7`789d~lRKO!R#zIr9h(UqL{K6QLvO>f7+ev6YzPK*qoaRYPosKK8?a z&CH~=r|Ua%72n^eY6*H5!GTNd#xx`_Tr|cAK7x>)$j2z@-O5A5`fi>JXf;?Vd_?8gj}2?+QnT;M=w+B3IJ;r)(^+C3y>4^W$GbnQQI+fYarw_Hl-pFkr z{+E#SLibC^lVJ7Mv39H^6DHD4vG6ds&mTnPO;5B_l3hSreicwfFHYi_s_kwg!9=kjkj`M+|Jj^L+=nRa+ehv$}&Up zOps=$fIGp?*^JAIq|-s@952TTk=;YGtB(7^4Wje};7|!m6HGD1G3kVG|E5aVqbG@$ z6_3IzT=$^^s1qCyI6P*rHMDe?Vk?|dc0y*BW@b!)z7jXreyuBRhK5p8Qc8mv$U3jA zps-ITD-uU?v0jO(!X?^u^bkyIr*F5WHa|bZ^dmWFIBWZ8k`WDw??J9v2?V)il`hg^ z$RnWbD2BU^PQpt+bi!pd;#se6eXo&l8XKEg{$P9YbhV@DO7KIi;tPhdzaVQyK!!1# zZitbvS3Qt%XLi8=J`3P%@O9M!Bq_2qx3VJa&i}Fg-L|k8!i@!;Qq*$E5r+@qxC3A0 zjKZ4s?CkZq{9K%fL`;52$8x$R3GEvOMbNxHTJgFY{aJn9=B~%08r$dO**$YYIJ;`p zWQOLn@}CidFW&tO?l0oeaGWvYCMyZeWqmy3%Omjfz%xReIv7-C?Y(2^}k zEHYK=XdG4JRLvBo3?2V)m^@%Vy?7lKvv#Z;!aa7BX#8piY_x1I#b`0Wm5g8;0yRoY z!{|P9AFw*G9$d58Ol$W?=utzFtO~yu2C*BI5=2TdUQfAu2aT8m7ev!)TvS#?qpavF zF8+Nh!_&~Wx#37$rUVJs?5;_qT7b5F9eS1v%k2>kR{jXX6EaM;>+hJ(hxScRud$Yv zmC^fEev~GckhylPHQedUk@GmUDE;dt6%|TA5fGN^(;)v?8lTh{ClZF%7igBk-Mjoa zX$qz3K}yOLdTv{7F#>Hhp}z;zlDd4^$4luStIqo=QrD~VSRo<^#2>er82SRYDUk0+ z#CBD#U$qUym8Scanu{K5fvKp*w6(h*!*`~Uzop-ymzB|)Z0i^B@+${&sivIJy zp&#iMpZx|r18~Ioog*jH&3d%T7yll3LuXYOi&`1}g$sYL${6mpdOsWydX~s;4K-Jk z)6_M1fr0zaV~9?6+~eQB?6`WBV jKGflVul)b)i*GWpwT^l1*{K}01&>RziZXAc^t}EbGE6Cp diff --git a/localization/autoware_ekf_localizer/media/delay_model_eq.png b/localization/autoware_ekf_localizer/media/delay_model_eq.png deleted file mode 100644 index 41777d756b9745cb874eed3d5175470e76ecc8b9..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 4906 zcma)A2UJsAvjzcypeW4BO(NEVhO^UU!$I~(&EA*t-o{JDZKFxK7Q-)9d0|Cih_$&aah!V_tPVo4r8S#$OL zvyQ@_UUtShd7l^yOcA#S%=|G63vc7W&H6%?_Y4aQe;8ax%h)INN1E$Xaj0;!bGiG7 zy>~1d2mtZp4)-CwyO`Q)Jv7}emFQx&Ex5+&JnQm|INuRyss6bcV(9AniNnI2D=q8tWztznyYGQ@Bc3R&Z?`x^ao z^`rjmrWXk4?-l*SX#%7XTRw*nf{35#H^q+#cO|ld(7L+01FJGGa@7C9O6TKFc043c z=jYqE9D=2Sdg?(bJ+8{z!qvW4J>~aA@LQ+T2%U->r$JvC(g`fNJ1?smZKdQJ7Z)ln zp|(_316-c%Eska`5Ok7kTQ|t`J`vJ;Hs&g>-3-s%PvBKDR?r-rd}~An(+d0nHV&mA z7fze+B|H@6r}vh1jO3=oH~n_zqPMNkURQRay8@rQCK^Nugo-*j_X$Q;YgPOnR4T>7 z@@J(7SEfo_78GgTWU8$RrZw`eIGYv7@;$}S!{sy4$|bQqLhH)TrlQb*80C(BPO?(GZH)e6>KJK443)PxipLVdC`}dm z$v@FwC@xJeUs7>@F!+^jU-NF+xFgIk!4ZjK370=%=rm2&Zv9eU$PTd@mfayL+eewr zN>iQ4k43%{(vTd5+R|k03cW7+D2*d?(W#&{iyL>K;X<2*JERz+-n)h`Ro=j-%#jgB zFN35o&!TZJ+@^>%jzr3+5?lnx7739tGdDU;_-0dP^_Rdf)|nq3kUWCo^z8kd|Ei@s z>reOCtBi#XUloaWQ=)WNPiljrJ!-U6GLDuv{}Z&GUnZ6-aa-~TSudc>vB=x()r z`v9Fa;#sKQk`X=xpHeVewHmc zt2w0Y#EXxoGh}*P?au>Kw_EcyT_j5cI(2Nw8y_nzS9`XE_)sd4K91p&iUu5o^>Nb+ z*`95y^~cWt7+c}FYe-vR^cVzJSM`7P@~HBllXI(1NwHmey6`yvOwJ$jjG=&vq?ClT z`7^X7K8NsAXC9XVHbR7TwC$41{n&|}h9}gE-ywD}AU?kLa>&njI~XQk9*0Y`P`(G?NxpyX`Wxxo=0R zX3(ihEuOYMZ&jscR2IDDBrK&iObqI!6WEh%S}_M zJjaH;eq_pvs4y^Q?k4ls?PKz2g?BJ2Z{EF8FYp*HbHXn7xoX?V{_dGFS7W3yA^=8{ zqXWAa<HIdhh<;KT1vmNw-ujp-ly(*^fS-3`~+=cNbcU*en+{zqM#k^XL55 z2P`{ME;XHeCfaLUSTDmTEr0|>m%oHsz6}BE(J}td(7$E3e|7G9u8PIS?D|i(XfNn@ zn>@kxl3P^et_||*?JfxrN18SK?Vq{r+CDD{*em=Un8Y74Anr2wU4`(qZr3rI(Dm)GzUSPoc}sa|KHhIS zxA?S1zik#qNqpO!Se&Ov_f9PLN+6SzIkl)O8qSGP>+8KV33}=S`@B)c?s2VvaW#rt zJlIbUb;7isy=F*J(mzNC@zaPfpu1A0PNqZ@mb>w*-lH~eK-sYh2qEQFL%&wC+fbR1 z@$-u)mHS$y-L+r$q3jIxnSoA=$=5xZ={BxjA4bw`=~aatwEcRq&HenHPy@LJcG))C zO(vkME6sGuR*}I1Ms=~ZI?!45ek8<#<8sqO6&d0=6e*CQI=3So4ny76PQmf_&=Ls$ zh)&FXoDZW3G|WN?GK^DGlwhI{2)wDQwSledialpS-*(Sli@+pw5&?4J5_QrZp{(0G zT*%lfqE8p}^=b)%J6RuS^%|OZBIOL#z5xH?l$|j)43Kv1q7c{<`b&?i*Xs|y-tls;@Svm1qj36G;eTYTb6@(`M`A6gct2CDO zLsCb?EpNvG`3K|xTB38S7ho@{cQ#eyW#q)mFoL;Vd^4*TI!Q3gJqsoHi+|JlzQGfJ zJohsX_ZaX6Mj-ERo5mEm8=d|=lVO5$KnVx8Td8AYqhaJO7R-kI%; z37s`AmIJRbUkSd~uaXZXtzUaa$ik0O?(A!Qc>KpMp1H7k0t5r+PK^6n7hG7KvmFqY z%c-yH#+dNW0H>Ye%j_EGhpflm^R6>PNxvxV&1$a~1w@u$h@?RJ7#G{YG>m#w|0rrA zOmG4y0ecP^VlqC@xcb^zLIMo~1>V8a@;@H~h}P#^j=rj{PfeP4+@jOATI8<%*;XnV0Dv^NcF>Q zGr@JW)R{YjSkK?s*5!_Tf@AJEY4Og_jVOLWRtAD;<9qhVPoRYK5qc(bpG%?CQD#(k zpTAdqM$A75ck5Y3V4bunHdb}ob~m)07p9p={J-)X;ZKVlPxlL6Xd8>bw#Iff8%KbY zegm`e=|#gc@6#l7_xs|;41{{nt(GK)4EvV^z3#mEN08K~w7dSMD#gRV# z@8u(v*_MIB%zWD~iO4;hre=bs*~7~{L%9?Gsjq)PrA2Aa6P||I6RT7C)-UI<8E+jk zyDd!Rfp>EG0g*tP?vyV9mYrN@thLqO)wW7wuV1*xn5cG1!#~L03sW+fx6aYF?3^oY zw~p=%uSF>8L3u-v7BpwUxpNA&ida({2X7Z!N4okY^z)*qtkRq6xmq0Cw}e7pwjE<6 z9Ti#>GdX$hvI1>V*tlDv;9Qx7U4FAdKFQu#%c1HuBGwV1)s>I${?k13Y%d9)eupD- zx>Q>|U5kU74bX104a2F00B}$ynm#Avcd?VzQ6Zf*yzc>g)X##W;ShR3H~`yD!Y84x z9OB5(rlU(}HgyHT!p0|id1izUtY0uyx)K6-fU8%#uyUi#cB`)bL z@%1Uwi=PKx%zw5m(ZmGO%O0Ok65IJqG6!EN!XI^K` z24%K2a;)qj10pqagi}bT?SSRb7-r7I#Ik7tR(<}M2STgtZ#?m$o18+60wnLxhoQKe zUwBN0Yff|}T88UVq7Yps1aJfw@waMNbt?(~WCV1`YMyj9X#Ze>Fp{}<5TmO-b!Yqk z6|es}9wgy+553O`N^4Zkw;DZQCOnV1o!k@mk(5K>grQFSN0R(6@8^H==RZV5QM#2} zPLe@_*ANe-?I`A()rMJ$2+pQ)F)UQcP-Zn#;&MwQsFq;-$TxrXHmbVgB`(}8J@rHi zcR>=BP?8J(bg9sDvcne+jt0id6a{m=a~Uqe4Brcp6NkzBfyNCJWcrTRWH$JMDB~g| z4cFlum9LE#C2lO^K;R@vL$-9?4}Xi&vxkJIuQ-8OBl~&a^@@%{-TV`^1e(WjMAu_z zX#CEI>5~bDHu8#LL7TcV0S$AiJgU$v;U%?P4|97MbGU{AstXWZ2+Ij|CTz*5>$Q$G zKfWnc4CMc$*b=X0+l3#e5{Mqhk;UDsQ{Vh=JW74Q&~8YQ{4T;VMKfczC5sSRq34B- z%YQO`_{zg=lk!lO)2EyLZ$Rc>j#FBa4SzP#!*Z;yUD2LyQSak{b0^-`G>E!2eMY3v zJ{({5>Bu=tsGnW_*h;1b@cV_Gw}&LLtn-io9ymwh2}aK^<{6r4mPx~j_2P0j8YWZe zpFgS#x;%aI5IKd$x+7l(j0arK=v(^|vjAM9Yhc_sMyM?#M`Me2?)`k+I)MvrU3|c; zQN-qP3954USd8Oyx%O&loL zgDT(3w%tE0S4(Sq-Bmiimfm*+`DS8??`{tLEP@&pcN4|w2g)=|s3sU$rvmwp^@AF2 zetfqCMAQ8weHku=&q?)~dU?P52LGDy=L2C&n0;80BC%Rw!_2;V4^fbsqJPtF!%gbv zH=@mHwWPySGw)?P|9HiL2c$>>6K`-aLo!{rHcYrN4{7D$ep={IzL8em4OmCXT{92-sFwkA-gwvOV^v}YHLF{B1VZS- zM3=%s6%7YCR5S2?AgxC)+JBVz!yPzu>0!O^JVQFrKH)u5XnPFS=npZoqXLDIRgB;M zVX6kMCBVJ?h&q=}}7W4;9cWuDLMwX4`W7Ma8vyT5-5%1G_R8b~?*^z2+=@ zzRM`)Ecf-zRiLqMfh73_Ca=yyO$rZu@A z5I$;o?|x9>D%bwn`f54)A?hL``FT8`Dg8>LgPy{BF@xEz-Tk?{%W!+5>rv zVo;lnQ2=?vQkr>OUg@%!w1hXcKmAq%`i0H!H?LL{u$VpJ0B2X&S2ENUi>Af08^|H7pQJijl2j0~GWSOt99@ z^uWkhTW_1IvU1Snr=FdTJ8l}tDQHXv71BTKX*Ofn%6^};#~*y|g6kUT6lq)G{|g*8 BgHr$i diff --git a/localization/autoware_ekf_localizer/media/ekf_autoware_res.png b/localization/autoware_ekf_localizer/media/ekf_autoware_res.png deleted file mode 100644 index c771e3620b1610a08b0a064a51bc762f7152347b..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 69064 zcmeFZWmH%1^Dazxw;(N`ba$hGfFRP1AOh0ejnX9z0wSf--6bjAUDDm1&;7yg@Bj1b zb6%Vm=hazfE!Xn1Znt~id+wQQX0DmpK`-T{&{2p{prD}8pG!Y|1qB6{4h02^i39^y zeDM_Zp`a+Bo<9{+c81=bMb#crxfQux>g??K+Ntt7C7p7HHcOciixpop%bsgmUr|@3Qx}*5Zky#_WZ`2~(xT225MmGwnJ&`sCJi{Xp$!#7#a2 zXGGzo5oy(|X}`F8>YR_i9`U6?{XQXO^n_|m}#(oTnYKPOYKe6?=eS{3iqG?|IY;mg6;@^-J&W2%0TeUCEgk5 zubTuO>_7PZ@c;RT1!0)LgPAp*#pi$BgrdF0_<#2L`*QCqB#L&sG^ZdspMSp$WW#^H z8szf-x8Z-J_kWLsoqfCs)r$?DJ%5gz=EwP$IiVHZTU<`sQyXdT7JKaIs3E4TVUw$8^ls#Cs~jPB^ei zcMSvx4Js`1(l%Jw!Xypr#p)A7ij(TUh15{~%YcxM^Pvpt8cy10|5DxKY_L8z@@)1W zOZ$(qU#dc}>CU?@S^l-|ssz@pHosW@=fZ#P=fU7jRA^Oi!}HgA{S&ax(~I$E~pSNfNj5IzF2`W#mbsQx97Q+TYU$+KpSzm{R2 zLmeF;3{8t`{dsN!OEAgY7W_7gaJk&v+>T4_Vg8XXlDTPUY2{P+W3gVTsGMB&750nV zePXF|Ia&?Er7JPpdBkloWq*5paW?0sK*e^(fscpx#@IL~D{GJ>h1W)$DhllZ`y)V__16dA9X-3l$Z0 zuXeA&bU1s^RWgkD8SeY{@6TrJFe#U>_8QZKJuaup&2kjd8eERvHWbNZ+3xRx3tU`W zYMu5xPbZC$DMv>~+uGW;CE3{6hI16GtgJ*FHb=H6OViwTtJl)JJV(E)l!@Bf9)3V4 zFW+r(TL;lygu*j z?DX~Zt=+8&F{1ia1^ib>{!5%cwB!b~Sf|#Jl;1uu8@#)0fD(@Q z>GmWpIe9;#vwvhu0Os9M+TA1n8K-%VIJUVYE;BjW=zL?BilQ%|c=3EqyAFr483n%m0WmEK&s?0@Q z6Y4s@-kvCy$r@7qwYj-jS6A1Y%ri~z?S2I_LEhhh*(d&AH4<%Ffs2!TznmAGH$kLU z%vNv)BX~K%*~36jui4;UO^pQanJl}C-A=9Hrnbp;a_)7}Ka>9cnBdz3A7J5)O&Zi#M1b@mD z%ezSwM>Lcta*kjM<c5xuDUd1JNu;e%E#Ch-tkKtlVoUWP|Mb@~ zYa|@j5_)Fk`-(pW4n$PM;$4rseYL>&C;rc9>kntYpp*ZkkNJRvq}FChQoJ+!MKTU9 zZjOA44AQsn-!DDZ#sNh15zYa?YYoDkEO*3#K&030wcB1jT~xwVA_@vhNoncu(9n9A z{3l+@DCrMq4{(TyYpj3$`1M-{}ak5 za9JPFZs&bW)U#gk zStHs-flGk4&el4KTy2;7M*`(tTr_aZ06?%YoKsm@na1z%4j6DhK&zvEk;ZqU^qLfW zd@d~?&^h->INqXpb;!muGij78PZS$2bwu1PM=L-qnrIIwt7e(WAVXo@VUEbnbNW~^ zVRz^G29LWFy}M^frk0kT2W^B>5o9Ux@f|SI0_dwG3%;hU&dlep1|I$Oiem)2-FnhU zQIBKhzCWs_9o02O>;ovfTO~d!E1UjHCoF6EFQp_3Fmtb@b0N+m$W= zYfM@dp{tA=*IzaouUA-tf`X#y6#9C4-msBTw#xfma93#(v!&+NW0xWRSM8hp;6lsa z?>M|SAg{_YC#-LM^VNKqoWPBbvXy~Cl9;H4+1%2yAU8K7U~X;>h&5wladB}pS8Z>u z-VM0by!~pswZp?hBuZ)k+9IBU-8n&|0*=~^o;OWCu)gl%(sFV=i5$kd9w(zfQ|AsD zyB~;ny1#kzMog?($7!~W-Gb)JmoLC^mb+gZiriiFS9D>C2L}g#&&`cz)G#RT(Xy(4 zc7@DE+`CoS*eCuHk;J^b&$H)g=y=3=71w{w#XASJY#hJDyO$3&I(;aJc$xS|hjXpt z4!`|6mPOM{wcUobjCg0NklW(Y(gjommhJieF9<^TM_%pL_OrKZmA(!8`KIKAk)`q4 zR$Kew7EYOpT)rwHA>lO2&+}Yv%Nggr`mr~5VEX>sHmwi z;GyKU@b-V=JDPQx7rI=}zzKT9&3(Gi?3Y&DxL>5*9@9CZYP~mw=6@f7 zPw=QcjD*K(t`3-Nd+W>?lvr`DT4BkBkFV18YZaBz)17HEGcy5xejFT}+x-9$b8w^m zUoGZTN+^t|a9$6Z_>a(e zp&DkWX}VpGABj@&v6oA0+R#f-%^B4M_P;s+1@{!mIrpQ7 z@$yAq=aE$X$wadisWoUPnyB&7sUhVv061rOkn%02*m zsXu5ZkqUqKfX$#aC(YA!Ij8XAXl-x4F|9G=2H}WC=TR6@|1({k#h~N)AA;Or{T2G=eEU-=srcB~6Dtyg z*4g{yfeh<~LzJYr+;)gJQEMwoAX7wt!ech;phYTwQ8a^7curz;&$TiI&X;|T7xchf ziw!$2&us=G#yb|ONdG(|3Me04NLmw8^_BR)I0P{XQF2s@_ANu}8H~TySx~_GGi_z` zKLv;+`Z)rm4<~HAmWY3?6T)jdVIC{x$m>*DQ!+C%v$96Q*xTE?pZ^M&cRvbKrcVJ` z!N@ly)7$ym)5`F03^LQPJdIc1V)`ll6Xddi6S~`P!6YRm1pz7kr#8wzw~r9)eGuI6 zL`_zUB(lWvGbhQ;HVHIg*ugt9v*F?4jRt?tb`Ih&2DO6i_4NcUGgULQExI)K9|m>c zu9fBGiiKTWT|kfT4&xikmfbe8;v3EvQOh-Nz>$%#rDkE;{*jU*__ZZ%c5aeZ+F5Q%J-zwYyA3IPEDCZ;f~5|D=A(#cCd`ba79!T-Yt zX6-6gdir22cH_Q>-P0BmMLsvdmM#Q*9<&Qz*yezSq`Gc?J3h8YH~`LEuhCP8gJals z_!1y>D!vv#PY@j-V3PINsxM-CowoqIi69fI0m)HZ5Zu3H5(#9I3h(TXWf+!<^{U=2 zpPgEk|JBNjA07b#FuI+&`m0IfG_G+~9UX0LxmzrcTtj^;6+5QS}IGi>J_hteJ`g()Cf@&Kuce zbKg%;Nl8i1bt4Oyt|o0XGIQfvs@vP11TiERpf1L}NnEdg_-AHjPL>)E8|dolf-G@6 zvJv21T8fC*?cH_%-N@)@{ZXI5e5gk`gn?3}9XdWRPy`Yoo_Y6ZFYoa1aDXc-%gfud zwQBjQ@i8%Zn&s~XzdUn)Al@lO?qR0OGKA`HN>E1WdYh6Y|iQd@33m z87i ziL9n8EP(68KtW+A4$G^ijSli;6h2>o{if`Cxcn2G#ib7-*~{F~JT%JXr3jH!5ijAi zrKdG{c|Ae7g8Mko4Tva#9&ZB0ot!?F|@; z&F8vV8Xpo8RvNUSbSt@sYvuz~$ga0=Zx}rWPHKO`Fk(;%Y==8h4#AI-mUa~!BuIFY z1YK;El}Fk_2y?%GmywkvcU?~h=Ecd$=?>gTadEM(E;HeGb&vKJDSE03*y7tx6q7aI zlP?P3)n2`_1@8gagoi?|G3^e30XRK4P|O|033{_TQ*B?j0>bqGOmffN8NS;b=V1&ZjQj-r`C@stx16RCx7X(`s5xC_v$WcqT|~Onf@6CqnY>=2|dHlr9FxmxPgioJN<#m5=ttd`c3&T_GsgOQqH5q@XWiDLa%!8 zpn0Iaz?ULXUcc;bZEdBN3RhNDZ8#az^6~M3XjMo^h||v0igfv7LzSj-gF4{8%F-n> zY(QiH!kkoI8!DaD6TnS;;;~BAX72Cq<{&}?BoB*QW?WpHg2;_M2+|lqZqbZLURGWX ze607|B)M#W^~8^dd_Jqcf4?UFhx^eNMUs~KzT0(~{zS?wZ&21x`7lsDM{NX8aF5h! zrr4k@7(`j}39Mq)!C0@9m1B~U{z-MaOHb|45MU|&3nJ4}Qf@%(S9}Pvw&^m{Xz_F+ zj<<5w*86|~GJE%~2od(khUyoPbPA&L^+88}nn+qg0;X)OAGzqTDB^OFoBxhz#;mTMgvtTMZ;-X#b8lyw$;;4BB3j{k6OW0uj4e zC%-tcKSFr$6ASRY3VB3bf6#G|SF_duw<)-?9AN+Jr42yf5`-_|^4D?!xJ|#qJh~>r zzXKZ4JU~Ab8$8DR_i~d1xJ~tLtyuRTF$3ghAfS`!RMA%cl4w-{xXri+kI94o3hJJ> zCYU(4g*HfuF|2uyzeW;ZAR8=k7p78CIA<%Jq>8||~%&qjYqxfMtam*K%JI60~$j;gJ*0#*Qt<8cd&Nc zZ_)H0#g~WJB@RaXy;+JjB9+AusMoWQ)R>+yvj1ZQsnp)ZNvTH#2bqvZ%!oCq8)h~3 zsb>@p@0xTCc2OIE4d_zG64h*Au#ois&Uxhly=NDUPWbz_X{ZAZs+(m3=ChN6mKLyD4WO_H2_Hj;ZT6Zzq{Ayx$d`#y7ya7KX$&GNB6A1?=m5$P;?KOJS( zyj7I0*np3(l@9(Z!@iYPnm0uw3o{CoU7P7t+1>$5Mg@qOanPV8|N+m&1GRbKNZWQ8fow!D6D%fy9x z`5&{`1{IW2KR>14`>BPAyP`TCT9Bh7^J{l|7pl9W@}RmnX=|X z+_`mQ>UZ3e`&)R|LNtGzCu9xMC9tpwbHl|u%ty$b$>Ds`m;Eqb-%nW6SSdWNkJ5gZ zprW9Q$x3>{&KK*;X*^T4$fKKdRxO&Sf4mBXKiWCb9>|IbnY9B$LQv7rGOfxoGL}G$ zbq!de%vT#_AiD(2^U>XDWut?={l1mQKUuTb??~!WR1}N)C$)iJ+9aR%+Y+E%>R|_= zT&p`%TV(>SMLe(6=4D_7?L>4vwm?DXo!8{hSFFpVfyQw}a9iT%rj!T?-2f zSJ%rd+4woE?lMjW zYC0Zfl8*3RggPEuB@)K*r2M(3@ofQDMg(feM$RGLgDf7JN)efN0jNiVM zd4v=992XR%1iLlSdOxyMFFL4xWzQ)L5~*&_FhKXT(p z*!wu5o{}QLwF9${6L9pTG$>gMV;(Lt)@F#9@IsNCJsG5~oYx#<>tWTGaYHaJPxFAh z0QV4;G<>JnEamjh>j7!>bEL^eeMZXV+(Stn4_QkW>fEr?bE7wE1AK1abb&Aj+dACu z1+kzA1IyKJW@0h{>Ym9~4L=+6|MzoT*RO*nd8@-c|4MRQj-1#rUFLR0Xj@x}#my;# zpBLz5_j02nzujq6)EjMZItlxbEF}N&wcn!?e@5l6ZXu{As?EUk<%xJIhb>Ass@F-BIT_(_xwj%ySWx*D1H^fKz;Iz4^ zHBUd%kF@df(thji{54-8t0RSG-?1UAWE`Y;9<;>8B_bfk8a6UAx~3eefP?#95loqeEE=lFo8X<`_cBjCEl6WWm*c)(VS*8dCu61ZQ9GKR z=+l!2+|mTh4+wJO=8f1N2xsy)(u=snBh z4f;7f#Z+7P+j#@Voe?Q7h?xK%eC;Wumu}nhiuUcKv*s&nsqR$Ch6L7p)#&HN%j3C8 zwq@o4^(5#jJ6^MlH;3LUUl>=*RZioIZuy&Wk}B`KdfXYxlgcm-vQiw}@5oZpJ9x57 zzTF&sZ;-Hm=B_qn^Dh#?3L-#cMKL7XMX zV)MFWl<107x}sq7?X7p{fsBlde5xRyao?v5sfeMf-Q$g6VPWBS<(gDcJt+e51#x^f zi><#}0@4JW!o5;xXlMXcUHZ0nllCDq#IY~T!BqNYO$WTxL=TYrAVa(`_&E24*ZC%) zRC0r0S72QWB4(Pwtw{LKmlsPx$;AW$vbeMoG_~JWo`_)xlsWwDjUy^ie=hu*UHS5p zyosO{87X}fgNC3fyK=<_rW<^#G_0YCOK!icLb29##7z%F;iF8VLVM=ckGVAdMc-UG zhqkmOSJ394#K#e>b|N6#pQcPH$alOMx^OlPdR@JO&Ul*fqPMev*Sd~gc*e@LYH#Rk zsd=4Q~$59apR^JJ}n~+ip~6 zUK4j$|E>Dds`LkRVzMG zx^2=h=w3FfZb8PafRtYAgP56THf&tnQ2WaUQG@US>4fRl$Ux_gkXsjnHM`!gtks2q zsMR}UN9&ZxvK5i{?|%e!03AYS$%1BMG{9^1EJM)!usYyX`b>jZ>Q<&DeIED5 zP{h+ij{7ufo{3!GWc7Acr#-U5Qp~E==>S{YwwnY4Pi?S3ocm$SZbgTYKVbjkt z@>i@}QH0d~b#|wR8Mow@Lfo18bs6O|Z{9Vq)zqJ=^}4)Kn_E#@^+_oydMTFBdx>eP z;_F1mE8D%V<1Tw6v5xhk*%PhiQdLJH1o!B8eMCUQ)Kk{fXJKO^-6boL!PPPFH+g-W z*z~!*U5kO`Y*Girj-WWAZr2u7nK8U^t`Q!tz4*(Bg7y>^s+bI~bm~`2P3FVuL2zb6 z-bBRd8jf8DxWy)CI(p#)rCjAbs-BiE5ev(D0X!S+5| zpru&fPggL`V=~AMEn3SO41CHq#X!+MVryoE*Ss#%u-5DRtWZJLK#0%Wnl`tz5|>dQ z7w)aEyB(pb1nMlqr`}h&=I=zTXX-LwXFZsyuTUs`%tdU#4uxkFc36&7X~-?=u2j#* zP2{{D_h`M=)%Jhy($>P$9&un%$h66-i~_@VB;7YHaDzlis0AxwRE}r7UnJ%ifKEmr z)ONfSmYcRQMbDg6izOgcPb}}y`GY1HdG$`IavZ;6Tw^V>KClcmD%=mh&b}d@1>oSF zZ!wyWu+@*bk2GfiMb`1NAM&H0J2?D35Q#id1by!-5@$kLdqnKSz}t>V#Is85Vms3aXwx&$;k%=e==QTK2@09bT3UR%(X(F{@72SsiJnms)b4Rs<3*zvo)q%EGMQWJq?E4D&1_|gh@!wu9F z1PH1ETkA=2_Eu1ycvR$X?OnF`cQB@kC1gQv4Kjj_^TQxjSZ+_E^c#6T*Wto0lJj1K z8gn}VK=qEf{g%e9cw8L9H@T>w zhK2?m=FdYh8C+xQSz`1+1Qy@(jWQ~%zBFFD(u?p8kCB;R zAlTXy6EXGh$4ppS**{7*;@DmrD2{heENf-uo|jXb@3JiOYF3Y9Ss(lot8HRJ#7(bR% zAbk*)Et6Ne3y!`@AScC#f}JN-ER@S1VR37Ug3dW9L!ph#d zy>&L9;FflBlwO-6D`~i@TY9>RnwJ?K4Y`@dT)d=5+y$f54vW&&&yibO0`DC?R!7qq z7d>9$*y1O~e7RH?71-j79p~R~mSbaMF+&?Q<~}{xl{&gWiXP(@nu#wA+vT&Y?&oEa zyX%z#WJx#o{(Fn8Nl8?uEO>`0(p4jRv*UJc52XTC;!J}Oi}ekarHC{1&|};!$?H1!bl%5j<&Gy+xMIjRg+OeNT+_K8!_n;> z#w9vp-1E*Nu}#H&n~;20s*-A<7H(sQp1U16sUzu^{txG8^RG0mxy}mnaAS8wJKK9@ z{FME%h_4a_j^7q3q)@{YC*W@^$eHK85ymVpFhC1z)a@pBrw2kGrCJ>ywhEX zJ34lK+0&3S{po$egc@?O57ijUjdS3E<&`r%=J5Fq7xohkAlfn8h`%d*~D@a4(1@ie`HLg6C;n#e% zL#KAt%_u>unUn7>wQG_i7vbKX*Y2s~_-M*hB|e9d&Eb-uY%6boHj5Lhp?!a+=4^KAp} zI?FkaC}iakN>(L((5|ed!wFuqII+FX3t>h)3tg*Jw`?<$bZQd#;#Qi%rn3Nf0o%2u zcOr=sZSv=-JXg@k`H??W8zzjGyU$LI^LVCurmQCM+vPQACr}fB%^fzF>tVv)rk#Twvx^MaZn&mzO2X!rex!FC=_xaTky!b#8Arugu{nD3{Bz zBX&+bdS*UestRzdoU#zfp2d{nb~1&bYC{h@Usg{@a4STl*{OpHc}zy^JrQB&UawkQDS2P1umtlZ{b72{Wayx@VG2!9R6Nn6 zuGLwYK(MaOZ^S;^p0rwY=>BUr)8Ql^*-d_cSn}4|;PMvVVTZ?Qy(;3LrU##~m_ZTZ7?qM1AxS?=$W`BkJ^g?#ulPwlg9I5JIx~=HvM>o6D#? zCcJ%n5uC9E;#!(;g4T7wk#%bc#8X2EO-`%ICMnl;?IXOW0ONI}Myiu+ z?n$|R&~UPrxJRl0QkdgXZ+$sh%GS-Ve9fCreCPX8+z_U)rKDyCxx_K>^l1GK*h6wBY#C3@9IqM4HwH(ICiuSq zzZQ7>F#hRtNC@_y8Jhu2nCk>NPf^<0hELok&NIzq$eZUKOC4`Y5*;$8%~W~TZh(U1 zE%Th+oF+eSlqFue(yU5LDQDP-gWaZobg4^WuAtcV{pYnu>;sLyFsozLM7N`=*PqNn z9p2lct^HV#aSeH?vGZf$+JbNuur&{Pb)Ur>{@RBJ*(G!R++fI(# z5x|H1(Dh86)~SNtdd$`HA1k*Eq~B^7wh(LhX|%N3HdGJ2ls+5s)~oykxsFIEhq7v| zR_UJpNleB`l2Jh4+c#?N#rBy~3czOT?T(3ZtSns8UBY_(@s{v!fY>*}u{np9&JfD# zQ26fCIZ-6B(0~YNNDQZow?H>r%+#$xTU(4dZq#v?+KUn>v!CK1yUSyBL2sfy8%`t zQT-;={pj6CwlrFmk-KK&+5KM>CQ1$2FW{B!Px9?`oZ=+cmKU^hjz>IP3k4)~xmqzYSsxwP-Eu!p znhTwF(n_pYoqC)u)Sn%n+cF*#Fb|A>=DKTlw z=qn~F%5-ur9Wmb*b$W;`{@tn2!4;l3CpiEWQW&c81=RgNZG^1e@aNEpbM!|t zG!~aFjGJ3oh`4B-J$a4!d(6T!Je74(b4du!*Y>ni-M^wEeVfhej~xYbrUaxSOgUz! zY<#dv#BK(GRROOSN6KDU|GW`S*NiCRd1waSAx;B9xA0Fc(tv!sGX zw{-_-VCvKG%`@HUG9Mqun70(~%GKc7e*ozG<~rlYVe?{(M^3=i;A>kz_LxuCfT+45 z9#(0OaU*i6%)65Q;^UhyQwom7T&&8f)9wZyCOVX1$Kl-XCJJ2Pxf%yXbI#6{g$Oo^ zU0kpIh|DYN9#oy%nt=d-NZg6YJ21>X{buWlmLT;!|9C)_>4C7QWQ5 zFqEaCth_~QmOqjHK}WfAxb-bg<)Za$qW~ukT@(X?1)iX0G|sYJ^#qQBbsz4WS-?)A zO##><3XQ<1A1u46cjflL10Osc%3)j4Yy1dks zzA>7b9c_h&{yR^;t8*n5J}1Ktfj4x)$^?4U51z5cw@0i1>QcNcO)PmosQ9@VqgUf{la`+%+KXPoR9H(m)p7o{j@TUHhA=MH_ID|yAkxEUN}h?8 zo2$Yb*Jp|mWitG)9Mr}zU+`&y3gT^TRvGAD3-K6o^CygjlsROf*yfsC^-P%HC zf!V^{1uIMDMJK|E6aX5)=m4KblY$Z650uaEfGOJL%^n9QH#c^^~$pa)Xrz3)MPYle5CY}Z?xB~p3>j@3TeUgd-J zoVmg*(tYX6`URx7;`hYCXD_((1H+U?kGC2K&a>tZ8nJx~8n{ZUWCm;Wc?5u(;87%DSO-W>Y6yTI8^jQ*ev5uJI;<5t)BDZIHw;VNZ@sAJoUOrp+}5${ zoi9cop1GMP6aVvcRV}6nIi#vUDDsA&Pe%)x|WJM`RmO%%R`4_%*_b74_(>U@69(aHOgVMDcu0CommiW|hrK-w-D$Vf83^Jt<*M|HK zT{n}}8yE~r|E8{Cf1n_o(ks!CIFTjtFVO<9h#te(Kc^&K9Sr)0_%nvi_=Z070x9`? zN=eqzpmkOBLiuwFz)wtoXs9WKpcYzD1^p~%Z z1?<omNa*i z!W;))16C23yQsUF2?vPB>Yy5nP#`lJZ`GF_2}X+jhk1%-w&izNGLCjlQhfC+c4mw-DB=K6*lS#4n=mRr9y-h8J<5Xzdl{LX&$lMzNe8HElXxb6+Pp2}@JRy5n47 zF@J(vDNT!hghbg+EYwKLG!F&AQ>3aesLO+yRh30CfZ)?`a9(>n59pH>@{G0SW>rTf zVJnJ)rxY3haC^>?=CT{BWKQX|W7Nv2&k{l_?bX;z`1m{)9e?=h>Zb!b6JjunF@YM$ zWA*q2zOgUv9JjKLDXrzpaF5|v=m_>Sc%>wN55P`_J&^F_28PfFY5M3xR|6df%uG!R zHGsNIM2k1UOnsUjgV0)Zc=oLRe|iDx$TZZSL1B~c)_OJb0>0TVdG;V4HGA%N5&Q}1 zx5aLN7*05!CE`bK*~`OuJ^@wK&bp;eXoK_DE z)sEx!6f6MDm%rA7%MSJrKmzsxMnKyl4ze;*?7B%>DwdBz@HO}czPSSIC)hxC-D6^j z3g^UhD;VDWOwC=)P(y^j`OCaN&P_w zZq4Nwh|-a|*7AaTG`OCdn@DBU0(c2liPrEA_~rzo_0TmOsDWNvJMZn4G-M96$^|Xw zcZ#G43R@PJd1e==BqC{3+5NU}DpD2Pg8?gxH58L;(KT3t5(NRM1$mhD4!fMnAY;&@ z(F4<7BM$8kYDXBQB-*Q@R5yObgihe<2DZm!Haw$iHL!p)|G?{pu@qvBU9V+c6!0ULB4=Rx5> z(yJL!AQFQMc{)U z99#laW4`$Ah2&*QLX?gTm;?r(u;GXb;(E^049b~{h56mFZ9^{qu6H6yMLP>CPo|j# zZSO-_Sp^+)bijAfz8w`jIO1yD&|di}Uz>4h90iiLHR4pyJcLJ(ek3$)U>>k%v*{~X z`}WY>GSOma5dx3VITgk?ZsV&Ft*nqq!hX`*Qx#;46U!Wd*0C(NBtvW3qo*)16>t+3 zC}1m~sbc+%dP_5Bt7LyZ9e&)aco@&?b5*dUeOljzr*dx^0Rnl-q82Usr-wt=JmMf5 zZ2HYy<>Xq;zEUU%ciuizn+J_)BF-BTci2UrFqX=uR7`TC?i<4vl7N%dKC1t$0{jFa zjQwWH=K=lquOgSufAyXa@t>7%eM9fvm}NS9*0dnkF^?)E?k(@ttHBqfcMuq{J91kB z$g!#B+l6{`b2FLf*NVx)3}xno8)*ATl<6f?@0%~wBnvv3tiV*dC#(79az*K2zOmQn zC$(jvQ&{$$rUUw^_ehSvyJCR<@b>gD5rh+b=It;!c;UcgB(PE7WS@fneITV=#hfYc zV;oW3?aKr^;6!p+d54vRGo1T$3BW)z7zsxDpfEfTK5yo;XKKt)vY(t2(DiOUiS61T z_u}eOw0O@eM(AcGtK2_wUeDt$!91@(_-lL`>?kA&T}K6n-2ywsihCd?EB z?+lb}pF=?9K>+r`q*IFq(gfk>EsGL%j9m??3BeS{+dF3ikKw`hv=T8Uc4}~r+F*0;NzJ3Ph12N2kPv3H_ zR*cV!w0OsDq@3zO4m}2XhQ1fs(q@Rlz|0crZ&?gIcg0Zcv`U?;mT*;-oh&%5`2k`c z;4{9Gm-4@zH*ucVen496@{=KOZ>~d=5raR22mmNQMETZqKGT565+52c<`nUk?sT2@ z`;km}IOMzWw-G4KGh~`UekrhVPIz+lAo-D{S{D6$1=Dwf`~iLKZS?Wf@v3yhZZ*5} z1Vx*F^9LnTKth$m*a?TtHQiYQwKHIf+im0>0k(Jy8TxJ*X|D%{i49}F(sMd(SeL4) z{*3j+@($)mnyKPpTA->ULAf@c-S3u9gDo*YEq=CwQ_t*(Gd#c`H?MPVQMWi0IT^IW z6s)peqJFJ)s9|W5CQ_lIPazG|hnX4V&TV>FNr=$>IQrBa^|>4*3gn-a_Ucrgm+gh$ z(99v@c`oBO7Rm4ss|#O>F;hElc$al-y^xet&^=gft^aGwyBF^+C0+x(R?n1*xBT%j znfY*W01Zjho6vgpuiizb-SzczFvZt+u}bnyncrfn3=Eo;&=uPS$5Q$)gF#R*-|dHp znJVD43r2A+lpvgl2W=Ap1Q#lMo0Vuv=jzD!+(+jpJ?rkjt3h|(@!RQ6r%@EXJ10l4#(pD=XYMmw>Y#~swXKnqR0kLb($vxtxmd;} zSeoQ(YfOiXNAH12PS5~3IXGAhzM#QnHrA6Wl+5A{bPDA3j9;T6Z3RTcBOqW&tMW_9 zO-v4ueva2go6=X^Uc{!neOT67w0nK|zBy422N`6t-u9XFAQ=XeJGkNnE0tFw-2NZ} zYaGyueKelANvsKn@n8~PFP3LpkF~EF8pe0Z8VPj00CWHwx0ozh`IeI^qo81{aQ;8@ zgGy9UMRG|+K+IqOa-z}ePL`z}Op4iy2S!Bnn-$i7Ad0x4fCg1|kc=e+h&%w}Mu3g1 zrj6zHei3R@Af!63szHpusBHnVBR(E&cxWCh&@l<0nU@Qcfos0Xv21oP3UO)+MXSpZ zR2I3uft(PZu{u#}E}^IrPS&!fIk$sav`Glg|KKBo;3$|RlR--4JF3Vx1&xvHpi>mg z41yUcFhg{>Q)UOgU%|j&W@Qx-9-hs2Ht*&2;ze)eyk|EGq`T+X2Z|)?=PsAvE(Pj+ z7Syx&y@=_edL^t+hq>xIh(-)XmjNA@#1avRKCR?mt^y~+>+em1dfu7?SOa8Aixtw3 zlo3C2JNVcuVGRl-OQD6I1O9Qw ztv*p31<`g62zUEv!Io_feAur-o(_`gW<|@ z(Bx>G>H_)~r_2gLqt&3mH4SN2kFEc)=AEV*>@a))8 zzl0BAY-n3~`4rV1Va1LcnL9rvj!ja$Q}Xpr?jL;)3`?O?)srsd^M;D%%9xHqqIGAwiS;fo?qSKsAx@E9gDCttjF@ z+6e?nF=0cTLgCv+MbPnF!iD+i+!^KcS)^3!cXo_vi_hIDWz?&-77k$uVsayH`*O@n z847w0_SsowP4?H(QFdOrfq@(kV!~$9a>2m_gdelBR6mzaef6MXWi^6UT-r$KYE8v& zxMRsHKHPIa@Q7peYk0XWR%x~YOJRH~w}aG}SCzyF@^^L;({?f!h;?{ltmUDr8h&q~mF;K<_h-Ivh*swvK7 z>i78i@v^mtJZ~_KD08@+p@9LW5h_4!g`w5DGhf^p`W+>1k6#lH=icmpIg|_(cFNe+ z(Q6mcmC50#tFG!&my~{gl+5NquR}HTHzWopNUf(>eQ0fCWog>L$>GebpGW#4o6_1~ zj^cT0k7?{pqc)gZv~cegw9f8Bl9}s>VTo+t+}OB)-3YCt^711h+yA%mki2ifE-5Jq z+?E?N?J#hp&Dwo4rrsMz>pdMz;+VgLK42q*A?CjR!)jpC+usD}Qt-<|uRxJ37#WnM z@W@pcX7L+lh+gobmo%s4-}7*CFbCWL>JXq$aW@5+uX6KoZyZ?`S2@7Qb1&%oW=F7S zM@-rkDkEue5L~RN7EhW)XfHg1#&MVp0qeSC@UZ|`DT`u zI>^hnH@v}5aQ@3CTH444fnOA18OEIH6V&zWoe~QOnwattBvP^J>TigyQN~hzC?M#G z>s!U5kgBW38p@dmrycmKWu^pl0k0{VNr`CDJW6JeAh8!7Rq-`u$6JVPRLM0&3G3Bc2^CzevT(6C*Qc*bx8q`mpn!^ zP5GfD$Mi!3prLh~gFIBgh3ye8}DXP&W*q}x%nJbyow?s7zFkk>}qZ-cPHrV}iayBBM z!Rfjg5FxY~SSVE?o{dgjtPd=Qz&~GHt00u3xIVQAP@v(eNQi)L&thMQx+j>Ku_Ovr z!fhzg;~AV;f#5}A&ig7#A$1H@UZ{S4Kmd=!q$F(F{K)k>%}*FMWkOp@wGvtQ@{y(i zB~8+Yk2;r1m=aD3m%4|yJRYw_GMovK!cd%cmj8m$MV@QPd~7XwqaNipBj2mO?H@|O z8(8P})e#F_@qdtS{!-oyJ)4EjNM~r`8l3DJ%`>vnmw3%j8Tzq^rQp)O?bQ;E?~|)~ z(h3LB)#ML(FJl#|W>J0Jod|9`l{l{E|F24}BM%Bw+qv zR!orGhDS=nf|=vdK~xqSBxwT-F#(}aY$&wJXkz`)f-_M1z*d;&@uis8mEZX@;3@7Y z9FT+)NkxwRQSKqr*t>H6(8(kv&YDm?S@6_#B>Gy0byh1#`IJ?tT#MTcT+!>N6cYBr zrut`xxz8r3c2gsCf`*nh(rDtS(>CR;&MTyzBa_@}CcEkmF814JO);ui-N7c|SW&b%MXTg-5^uszq~oRr*t{xk?}M7xuzo)C>#5PP0_gF< zWvJ5@gXj}k(6p^c%UOl4N0hNpOF-pv%7*NH-1{1X+u^M6d?XWDFqc-}bCr1m8+!Ta zglHI1FG#;GaZY2E;CxaVV(_V%QNW6!PIekA5Z+#?+%IyQU!)l!{|25 z#&{v0m})tg?M*A!vr;*>aZgjvwaj|tj(*W$XZ<&9OmAL{M+5W~i%F5*=5PvRu$qE~ zj?7vWZ*shJ0UaULQcZrC%kcR}sEo6exsQ|bQXkUey2uY*jsbQUqa|~m>u*rWg&Fuy zyHL%M!>d=73DGMN;x+Ef$Kg!Cq^{P;Lyfz=YX;J?(MWdCT@fJ?m*`QqP$6761reUp z7M2^Fz_>VLHEAzuH@sgCRVsb*z`-h$sAOhf)`eqYn*FRn%aarCaLKa|gy_l?Q-c~* zA~uIl--H0;i(K{zn!&~enX0o*mf+RcB`FRZ6KJq%jGtAi!q-N?wQzv(i?7BWGhDw@%9`~{frP?9WgmHiyX%@!$KlHddY1m`C+As&i87b z`)WjHPXq2IEh%}Ll;4)pG*Ac58wW$Igc}j#CbKIo={fj~`Wp;PNZiGOXyu&ncicjH z{KHCUr=FAtf!0a}#HEiw#MCfC%tgbr#7(@~6>(vMe#!=sH60{gu3h++6T9waoV

-1Yz)bkHS z6||^kQ?s^y-HEsnz|4okMz!d#N}eRTTu+gBM!PM^-ugY~{*a16t<>4HyMF_H>p1F+ zy?F>k(1U42BImDs){r_ybPP%g-k-9?T%g{50`v>iocP!#*RNTfd}d$`K0BAk>~u64 zD9vx=EzlVi5p$jIKaVo5BsaX=PPY}2q5};xl=ryCcxx` zw;)pE#R6}bNUE_);8_14RO9o5phrwIS=t}r2x(|bTYF`1V*W&(RzM44uEcaxeh7{T z-T|_cp<(Zq+~rwqI~k z9=pA-t?XB*@$4_s4*i=gS2Cu0J6l#!{(|8R+T(hQVr-O`B_3r844u3cKYj;m2x9tl zr&hQa-%A(k7cfFH07j%17=!wa&bF8%&4Tr%Uq{#XtN}?|Mv_N0l>f(rXm0L6GEqja zlZEW{&5SJC3b=dvtnIf^{h*#t(6h=7P|^5>2|6UhCq`3*lZ>vVV3Q&UIBa&p!Tmp+jfj zE$Y*?P`$J5gYVzH_EbbE2jL$;-z)0#1G=Zve&X`}MB$443O=RqH9U;?z%FJ($IsoXgP`J@C^5ZO(JVGhzPW20yhWoZQTci0Fii`e@H5}Z}aw_6vRIHxPu`kA{1&r*^}V_Mmyx%!KR^?3yP;>l4Picfitgr zVhC13m5@o9dEGMw(Hj&c3x!ff#W87e&_8nIp5nGGSq4uK22+5Fcs8~p5eExikzFum zxp5%4-i-auRGX+9{zc&8)yE$jZ?!_tErf; z8%OI``0O36eMB02GgFBC%39awvL8yLk$Ka; zN1PI5uZ*ec)4dkR{okK_)VEZ7OZ+q?`@+-yA=5`rroCYT9TmljP^k&u} z%6f;IsHv7NT~3n<3xY7-a+{Zi_2On$Gx0c*=lo}LOfmp!=2DK zUU#OhL%dP5d5VGPVXTW#qjL6W+>bu_)X;&uA>A1Caps2FcSeay&i0vwu^f`Qh*e?H zC0TV0h0bTBtSIE3i1>ZMY4&Ty&yC{Scb$(I7q%<~@7u}W)Y9FXMgK9>gaer-5%DS0 zPZ@#vS;e!D&4n<$_cVDiFOYqBS=qBC;a$c`e$`2-?N-#pE?cK^1&-syK-V8G^Rdlq zPhT3_xli!`%BFjPetBWWN;KlJs#0)T*Va)~^}@#C5w>4Y=g^;Y8Nwqp;G$7XI$&!F}CmbY{M ze_jB}g`S^IThbPIW$taQUkA$n(#kK_D@BVCqI{P>@Sf%v|Cn&TAQp|a#Qgk4qwR^! z+QalZ|mB*hXsNDB;q^ZtAa}(9ex!msO zEpG$2?)nMa;gXx3{H12BNVj&iR(*-17>RQaUSR}4$Zs3tEknr<>hybeXs;J9g!5@x zZRor^R(L(9ZEkcZOFqT_Wc=?fv(Os1xtz4z$zBcn%Kfc}75?`emXt|$cfOp>UGUP! zItt!G()S+m^ZjsPI_0m}lMC#UrE1ir0n?6`FW^Rso>IcNcXdw?e02;yP3hz;llGt7 zYh9k;mtM3FmL4}WQ>A(-SlqqM+rAMJ^VN#RIV`flBe`+GR1DuE_5D+!`0h**cin1b7sK~k zEqy1gOdT1)`1%y^I%(i_exAN%K$_29w-9#3hkF8Zqr@D;atm1fPp5)ZBW6;|re0F; zF9lzyz-Kq9Akrs6%|ty z96*G7Iv@ytnMBy3AqE-i2tiPGzg55K*!s7;oOW?PoXhD_ii(MGP8NyD_xtPj^L-go4E8)Ow^QDtc&yNh8;HzP@e$ z^CP8Te25PCR+H0clsVko?L_@DAptQ!;IL*aw&6tj zD0pHy8sZ81tN7#6yDRmK+5f)c^18Ip0Po^jng3J-oT6{^iL^(Y4G!2b=ccjC!FS;e6ojQo5--o>!-szEkX* zE)@7*g)2qY%g?Kru2s~prgTjya+kk9JtDXI=Mjs$E@p{9X*+H{Aa{u6h)egQRoqXW z5I!8UX$`yC8mZbbvG>!!CVEr!_7VL554j=s{k6V6ly} z_|ju{K2**tq$cK0{^lW=fLZK}_9GmjA+MOFolqa;qPX&0*+Q;N-b^t_!C(Y(HZW=!#RJwyxv!!>>BRVD*UFQc;k4!=%RmZ6Ymb6#Yi+PPH z_6gS;c0NNqyqkkI(c(Ym@-Du`r%rNFBs0w`=QEoU=g#RkF8LJOvyg=Gh#AhF@-%09 zombK#_Qt<|65CX0i`X+Gsy^*m>VH6GIAk|ZFju+RL*cuI%OO=|pQyyK@x0Wb?}ozP zfyOY16rFr(zxF#G&1H$YQH>jKX6tRQ7T37rUtEJXoR#-`#rrbq89Zc=WO*L%VISBi zWNKd85?HPj%SOyJJEW+2S}PuK`Qimk)WI!}e(2$UqwYQ#lCMr>SN*4WM3MroTAJzg zXT(?0;~|s62lq$i{Y|}ZBvp&5;3VrLyi$Z`GG;7tvub+{T(qA2<}t$=8L$ya^e7AGq<>K# zdN;H#t$+-venCODPS#&|revJHSdl*NE&s+wL+t z)?kQ9ecx9b?AC`{EA7b=ri^xg;&bSJAdH;Y#*%{tPjU`#Pye!vS;-H*C=-&)*dbrD z_~H|HP#-Gnu)t4eFbQP8T~{jE?bkW3Ji67Cy%L`Fwzd;5uC(!066&|2A$mAp?EWyr zj~}0p=gVFF9x_iWbPvbt6EV?>ZPm`s4h#TJOG#mbfw2?BmE$$mlQl3Z*YDeJ7;zdI z5mBHuV@P3f2Py2j_d-P_blfTd)D9T?`02xkx=H_=nD-ufcJw}TTa)N zpz%>D&d*-;?Tpmf@}V9U9ySl+(gG!|YTw0yu`~(Wj79XGqT11|Hm?Eu-lKlIDs^9` zgB8(xq$&u6TTpu6g1Nal3^;^QCJVaAD#jkxrIfq}u|J43LP1xXJ>*15R31!Fp3e()r=5i%e` z@`Yb#zj(xqOK11pIU}c5QFbe4A69@0$vkmZJ*uJ-r#>HWGj*ki#e(I&Kpv(eVnE?; zh^BmI@$2gHZ5a4hA}5m!9X=JQcIcX&gbS7$Vq!M>Nb=#9HOos;j>0+&Bt5LC5Uk}r z++EeHa?IDwm2lpghmlD~W8bVJqN2=hMwteFGw=%zu01(e+`stXZJjA@9v?1bDnL)_ z0<|i!s$!NV+K8&OuUcd`{Yp_I(SL=f&kOUa4d};(>pS&8K!WUv-<{&*LzJVHJX+Xd zb>-QeSD%VjxG&{Zv%)b$P!NsTih0-P!E|gG`o8vS>6MF`nwpAAAIu&n!~516$^vs! zBe-h*$)IIrLXiSPK6T&m^U%7w_;8Ef0dihR zBiH0=m$&-5QT!c`{;o>(hs6ORDS#c!9c)+k^?$!dg4Nz|qGP<0nr?i;+)TrZDP zzHa-?#xR%UsYDMGTq-*B`frXf-n9Yd@Amff2?rT6*a%(eOedn?;u8>f|Lu24NeLOd zD(tbK!F$ut!u3jsQ@iYi*DW*!1%)DYj=4^qZ9Ec-*o1_xwv{*VaJjTfepKHYFduRW z$ro5lY*|#~_|=f(gMZQIgO?xoHWjbm!{tNbkz3UCcSpN8o#xtb%7nBEHg82~E-y-s z#s>!V$>7ot&XA2nTCa}}IpEy0%oWVPv?$r6gEa7(xao_C%p1*BY$r-?^$?tM@<#i89ArXy$7*=s_r7J;es z?A<3m#npKRRd6y(ii=^@$LjZw41A8TL7@vaE0N;8xzAVu6U4t6+@McMOneF|Yl6o~ zxl|HN{n{+?C!BjB6c2;kQ8Rd9h%AGT*wI=eOhRGj;))k@x>-v_pOT#1n2H@kiv=Im z;{4c|WXit>mnT+N_{A@KsqbYW<2NOkO+-lIYA4zxY9*A{Vsn2Tca-1zD5MjAI7+zp z4!`OL1&N~?Rhg$joOEXvqj=R4E6MR}>^6|a<8MXsCk9|uocik^&eb)BlM@qPvnHerF zu8xk*$_?66)-ZY^0`y4jIe>I_%62Q(p70$^R~qYu&(aB9FV;%D@Uq%h^OuRQ-p*td zZ;l>Y2UPE~mwqg_ zA`oL1EgIU&_k4uUxv^>)w!MuNnh-u`_;~;3&6~GQ_6#eW{(QewI2;=pN#R|3KiHdkSLgR*iL%$}l2Ybm~U&r1jT9Mb~0v}cvSY82P+ zW64NL%;{AZEZLjyYXbY(lXL@BHmH*Te5(B27pXY3W)o?9X%>ge)nI?)UTezcY*6;+ zrdZ7V@Smdj&9B#`=%lcGsHY(v!HSDb4G;0H#$0`);L5#)Z6rO+Q1^gowZrtRl20FF z3RT}MTm0(6afIQkj>K_1z6; zpm%7tUvG)ikLTOdVBw-@fYO-e)Gtu$9N5m=#L!B_`Wy4f??BqLmUT)Bq z6&lFRy$va-B0X`^ZaX;O;GSh%5l`PyeUvS=+%+GCnii z$%OuOHhdc9Wyw(yrS!YKVibIqQj&Ry2Dcy<^_zAV5cRlusj4aanF}ct9-l>>IZ<^p z*+I|>l0L1E6TW7v4w404PN~rO{w)K=!~#}%`cT$KDdjQuOB8qiq&k#Yb$pXpia3_f zX-rAw4khdu)n@Ie-QbeUx};x4*!ZEal?YnRYaVQ#2>n|`k* z|0mi8u?L=>k^sVSx0(~R9@0t96$vS5Dy3i9EZ!vB!QB5WNs*MZ|D{l)UmnTU4viwF zuI*3b$R=+MoiEa9#Dg08Nms}7D_YLlzhkQx6rvrPnu8hw6z_QzpgfS7iZeiO4m$kOi^hRSjI-jR;;oncX6L(RMACuvMM%ebjWt zopO1*cr9ncCOtDfrI^i}f2&sfU{;JaF)xi7$rbA;G{3A(SSJ9o&mf-L*?SKYu7{&5gz^E%lbGs4z)~P5}dM3{`N;r(#jr(Qt z;XtDYo)I({L%5Kj@n1JX)tp%=x!B%iZg^_t7W^B`_}Oh za3rtdgk+F5O5qt5_Cv{eoo#t{P0!(CJ?>IgnFf6*Ur?N49sISrh}c_=ea>?1aWS~IQ*O4c0*%W%?d*o4q1R&l#O8fI zN|w;69BpFx%hWw_;!dg?r+gls|Kw*=q*oq3e4OYFE~0G&$DlC&S~IC7fx%CX@p6gW zUr|b>rkNBynSXu?K#_V|`_em9-3CYREg5UOy#6Xd_qLj;0M>Lq`Se46@z|V(n@btp zsJldk{-@vym5DZ!IhJ~kt%%e^gU(N{JJ72=f$bC--w)HT=BnBteI8m~z-43Jnzww0 zzEF|8NYdzGgcS3`l>3pZ!hKoS+LU>y*&zA&@YFZGvc#!KUcDYCoolZC_LNz(ejACztY- zSm^AkEogQxz-A&qDsXyu_u4PeK)j9Vx@4 zKWMZ*QXgwN+Hhb>U4zeJ3=onHz=J~ZyxxPc^7(Bo>a?%xzd2)S>4;R(BNX-L&2-J+j7lK~vlk9Jj3fBCvuNsC;r36$ z2f7|U<;D~Ph|7Ju=04CoWkyX1IS2QXe*PkMs7fzQIn}U#IolTIb?MTJ*0i;aJ**a{ zPO>DL=G*SQRhJgOOH6}u4ZAL~-t+u>W=Ta1Zj9%ESuG^=d;_^IlTw(s=`q>ua z#K~^nT6sBZ#lLi_(pL4&=4SSjzNh_szQne~fACZH)r^w^?6_^jkxeNO=sr~~Q`$`- zEMGE<^Od3HY8ZVg%ntXk*4bc;T@@UXHiC^914Y&8rvtJNUfu=aGX{($g#jH{D z?nvm6>GCX9a53Z9GY3kXcg|m!pK%*hJ*?H3msG$7j$L8g>VkkH3b@sa*W2Q*y;XDw zvR8dwt1ooE67b#wNS>L_R#s}RB8t&1_7(v$mT9jlGsdkR3foz`Jr^0j`FgxQm5yi; z#ibvUc&;BZ)ES!=c#W0h}dB^%IpMJw3ZI%~x8p<73)GX7g8s1H1{Q zr{1W=|K>7RXTpP^t&Sq7!YNqZ)xk`U@HCGv+qw-R>=V!P&Np!Ruu3*o7Ob5GPW^a&&yaFYPgOU^~a>t zsDCU}9;va>>Cnd29{z?ep)8!d>V|$Cnf1*t=L4<1@V{I%w(eTDbe@r1tVpyaz;&IP zr^Uo%f?@X$N->~80WID3#QQFiO07T(RZpJ&6eowy%!-zcgUQY(?AZO_ac#jz|+y zY|?hq@Mk&C8Tl8$O*7QlUajK&GwL2P+obZHaRMRMw?O`U`&wk9O8X$#oo>_vn1geV z)PvW&*sgdgTJ}rHT@Cm}vy+f^9j)x>YPd4>$C+&s^g!Wx5~5cH&tc$H8axIOLqtK7 zd`fmxjpe%z29Gr#*XqHiDeLqVxDWV=bF}lApo&ZnW}M`&`oW_QU8!_*E6FQfIU%9F1$3A+urJ zRllqb@EX0F8?{SkdlUMnS9PDS49OLCLL!Cxc6{m}aP3~8l9VJ8;TXi?Q|WmNd7o}x zdk$4qGk4+YI;bkJbw)T-GY&4(>wRdEvo?_wKaUlXpHLi>D0^C!n0viVE2-3dJ=^N_ zdBLnqg3y7l!|ehOA<;>}%jbR^BBacREHe>s$Xypwa`#lz2%G6`cF3`{sTfNY7x?#p z9-hImc{kpH^qfS7n@gvm(nco9jpyJ_iWNS`=abNr0K76xM+x?}3&;k$knRr8F1M{3Dpb}J=PMpvZoXZ=Lk`R@YW1l9>lj~pAB8%hFlMi~PWbkS`B=rC zERMDj;1@gP^;y>A7LShDE!5jEUm@uk(@Sp0dd<1G5}&_7y4P53CpY%XnuN_liGU5( z75Uy%4>1emIZVO}I`2H`u<~Z#(^=z-@LxvE28qPzE|{Es#da9Bqg~+{1n*{x#*6YP zwqaYtsEQrI9+l=C%(ltl5(i>bjDj7dFhUHti{I@*q9?2S!En{R+i^($N|D_WtI-J! z)IAu_7enM;$!yJcJ0X#Z;L+<|K_2jmAXF8-%MCLV$~*V{I?WvR(P^{SOWre6)8YeJ zx&g(&%e01=wpS?X76m_iucH^&E3|Av$`}?HztFBRogd*tZ6e3aSzvzo0H#5Dxbl9* z4ycEc35!R~_VK=rjXv^)$V^=~M+a0m-tBFg;(~&SNsiz_6rm0L_x3I^)#*N)f3Iw^ zn7hT_PdH)>!kehV$lZRGOZ;?pgsBv+>=ytVhET2qYH*CV`f<+3}+O3KE{?pDN#L4UfC&r)+)B6o*5kMfL4s;W;+r%NO@;0U;T&1O~PrtRr`VI@CmX3-% z(YmlOW6t6pQ9CLxr&}ElPKU7he5jdqZujFdJ28JJE81O=v-`jd5VKgH|4cAWvwI+9 zgq%x6?_}aV8#xJsT`qb&<|CW{`F_^YB6Sq&Hhh!tv)1*dbk}dTXY%)Dym444hcY}ONCo;sIsmDpOB^kvkpzzHI z>I~@0>UIm2grTnS&ei;$Oa5?;t#Z}wiefk8cy*)7gFuE(Vz%>Z%qI6kHhN}zorb!7 zL)=7N*cWkjt;*hC^iz?4Erd&Oz77C+x72gwDYFj*!`o`Em+70n7L2-_%(NY_KVNjM z<-Iz7ladA#bqOf=Xb1wt&@12Uef-Z0pp?$%V9DeYz&5m0xqGLOPgx+-dA|eE;oYM5 zOghYg{q!;GS%3q8FNym5U#TiAKw-x{dr2ywMRUn*7?Ko0Xi2USZX$3el2{+EazD6H z6#N)HVnsW;c4YTR!9JMDK?R>CU5Xi{Vn#$tAc@4j7sj4?dg=S*~4j zWww2ZnEu+mm+XK{-Iu?4sO!z~SeOaCx$&maRhW8~;P)1hFAs_$$fJI{g3Vc{+ZZ~V zyKX~V@qzg{@EK#}Nht-a?DJxd<)gv+@6!mMpOH-P_#b%vw#<-X-k+)Hw>u`w(b^o} zw19vnYGQ4E`2#y)0tph65yCtj7hjMVdd0@gQ+}~v!xzf0Az$=ACR@XlKM_TJrc)L9 z^?y+Z##JSLkagekzj*e6w(G?d3nXHh#@y*D&SIE=89Xb|X3Z;N5}BPbh2jbl1cN6> zEgUzJr9R*wWeU z3yfhJlhD2+^dc4yF~~*NeVQ?ER}mc@os*L@d3v(T*E}t>;>Qx7H@Xblx^ll6pxS3N z0_F@UuA-J!7iwk~-OKEE2TD@nctIJ2i=dn6(JNwSRny3H`!Gix;689LWx|O}M7@{K zOBmk2&Z=Ho~E;~T5TF6OE~*(u9sw5iy%Rs+hk#bX$&-@^_Yk<3chO=%4~ zx@*!H$fZ|PWiiP0@w>fyMzGG(3#sq$$FvJT=Sv1`<%a$2`IkvQDw3U8Fc2K} z%l#(KK>kXJ}gXNACh;Ou)nx#R5Z7n~+8_e#ha(ntCHi1do z@wj&~{-)9d&3y6aWbs>uUK1^Ae%1T4F-!X@iPd;2F8bdbS(M`~Ei7QaEowKV=^AQ5 zB&-r(BgOl8-wqbV_8IZu33Z$3E_UxluwRPkgxYz17Pp_Mv`&S_D$#_-1 zx8Cnp<32eEm6P&aSNFI3TYKqqk@@Aje#77wqb0n}glV86seVJZzMHU`$K?q z`UIAM`h0+U3ri_iVU6Smxl~xS2)iBO(kF9PqjZ)c&1~2TyfhHqF$=d3Hh7}$H_B<_ zM{GM};RwZ2H#)7u!@fanWw(&FwyxR=;I_Wl(nQuJOiAP1yob{4A$(KnK>RJRSy(!? zwc6&c8Edn*r~rg}+|wUfSpqmK?(`s?ysro^c~n-L1|da6q#7`H=TFi*+JnEDxwD;d zqV7kI$vt}@i5i)h^zBT%DlRRB)>-#}UC_4MpA}H?8t;`6y^@Yai%V^-SmrUKVa_fs z5(YupnA43^0p$YnH^l%ihFUqC zwy`|FF)<@W>3?JP=qKR@fK_yvUiXYmqbg~%Q%Z9wY|5xlk#mqBL^YY5{eUuZuSyf8 zLb0tFphpf2fIn>RyqCV2r$|ai6a%o;V6#T1|4ZPVK3)`_UlrkqnQYZeN~g0kb*I&TtAae-TXgkD;hU?__XT#VMi%-4tRFN$a6f|U z#@D{RuG1kC*YQ;s+E^c|0t*XD=9f1@I<&*A^ZzPlK%W3*lO;Gc6DnSxq0iExrF(NB zOB1sjcPnuKd}aa)(D~*S_?;NeKbT5@NYp^kNTDQ*?tLP-!cZU(cb7q3?_!zoc(#1P z(D3mY$Ut$ws_4@1i)@ybB3rl<^(O!*M}9#?VBA~!)qF|>=w5)gN%k&E?YiP#C=#aV z37O5E?dnRwL3!iI5f|6yANFSO>Tt!XjM8=1ZHiNnofo9w`&0DH$r=zU*(z(=H_B-g z`s6I26!yumkG+HDei*;`E*1qjYAh!G7}gd&rB@AuJoqAA&GQd8G}?D#pX{p7b0|to z)=%#y=4QmFLf^Gs4A9mNqc=Fp8d#*x9Y=ILfB%sQcHh!-m38U|^zvOl0{SrDc_}jU zWtWJ?6ATGRL5BuYKd@(0Bo41FF=s2T9*uKCCE5E60t9f2^&P!-#&Ts}girrocJBNU zZtwVNuEGDjI`i~=fjNJ;^PY4ecS3G|n^phpC=+bf5_LcU8=H+0XH z2Q)+jMIy;70j{{?(|FzWs*~M2RGUQw9oRI09cq1L0cqlefa7n#1({wzl4%QZsTV8;s4IwVdAQAh6Ew zD~MOuBuSEMkMt^7xT~iDNi8jgah6SdH6vm&uB`2&|8Ogrnh2R7scuju8_HY_x%!sK z^I}ct0#~|vF%KWU$}WPrb^?wEQwT8f?w&G}P1B`Y=|6OS&I5NF5yifqQzBvfAMPZ2 zkJ1&g4?j+Oh>1479Eei<<@aN=e2XvA$EYJ5<|XKhO2E2b z{n12p%zKZ(0MtYr&CnWTaaPfxSfLkc>zp{oVs{4h^1m*D!7MI+*yT$RR50YD7s7cv z8C+3sL2%rzufo2QY}xIIk&*Fe#i4ey2d$EBii=L}hu_r$+Mt!oY8!WYZ7ZA$4(U$@ z*G$X|a1~F-yU)2>I=U{`;vd*XgkpB{~dYiYIGbf zk0UHQ5gujH>L9)K9hjg!cA{oV<>Ve$SP~06qpO!oMw<-sYsJAZ>qty#YO9160XIE2 zRhGISU=B_cyMKWg&2lC|A)njA(|@~C=@3}%s$u0@rVGmh?2EadMwUBg%KBy|vvh>? z`{f zSMer0l`Z!h-?8Lz_rJxcbazo9iv89xVD7!R=?Z?}BpcY3Z7BGUoWViihR_dK2jk7* z;bC&{1%}J|=g>9O1!R|T?v8}ig&K#U%j8otKLsv~Ql3kPkX3z==oOS&CE25f*1&;^ z48&udC@?n9vL;G?ou_jx!+locFKI?Aa#|xn1Rn6Ai{`Kza#&F&&o*sr# zFjxR&?}%0ig4B7t=6foWN5m|EdM=lD*HpCa))CbaB>OK(r zMK^s>(ZbkFNqw96^w0k&0x*Kh+O`e%4j*0m#+1P0@Uy)3PnR|5BiA(P0&Yx{+s-{g zZ7|36kd)bCc}6O-%46oHU3{*r@Rv1fL<4R8DYcacMc<6Pkp2r{o4*YL`2XDNOVwE zlQR;A5$tRG|Cn%z-6UYbI~C@e>rWU2P<&QNQ1#K(5Q|@oL_|UGNW{vuZ@C}s!7eU5 zlcIUqyGWqW_N*sS9VGEvN1E8LHKGSUzcc)ghGYTTuIsNtYCYQ8MD|fAY%D-{kC>uV?M7M@Z8 z_+U`TY>sMu3VMipo(wWco?g$Nu-!2TzO}*kzi<7>1gHk$e)SUPhRvXg&xaH87|Z%? zJLDY?$E9zJP9N>>^k_{Y^j(8wkg^I2v3zDB3e564ppD z+1~wlZDtxY*z3XYzmO$&(cFi4!ON3v5K$C^j&7LeQJ}UOKP9@co4p#S%XR z<~1FQqL(ZtS5+AG@@luwjm_eCR8~{dnG@Jit2|x^j~6Reu`T zJ9EJ~qAnjQGIjb7qZ!C0E?o_c4C1UFcSgCDo)|^`@oS3ub!Ow?5Y6B z64*_F&Bd)_+lMGCm5P<-KVbR!o@dR_B&hVpmeHClL{dW4#C|==vs{LBJ|E5#y7cqs z+1A>b{RiI}g7>VvtMi$sTq0&ck!HKUJvJtpFr^=1oaGk5qkEoWp_~AfJB~~RNgrq^ zA1oh>)t6z7^PJc8I#%$zL}J88R-%aA^_ruN_IFp^g@}c_=N?{q@u}!l=s*ic2Z(PS zy;ad6NO9Z;^O#aJCAobF$(C!nMuiAFlH%TV%uA?O8RkmL1EanmKX^(yq9|l7 z<<3+K%a`Mq4e^1f%U=ke4XRkvCNg&B0V-$_M^gP|ON6Ty-dU14me>Pt7 zDn9%>tv*>f#G$zGGfG{)uas=(-;p!WK4uR9z|yFFRk1CJFXNc)mw6 zS0NZ#_a)?iS+czQDZiEVfiE5EbHOROTD_}lZvL0secfMlrOXiQp^%a<-Sy6Ss|?^U zY*tU>N85}hlnbf+AW+y@vEs5CA&ku`p8n^QLxa9A<{4#F;UvI|687r#32$Q{k*bi= zXz3Ywc{hs(bwyqG*1kT;B)B597MgJM2PW!>+0F($74FXecz=^5ZoUa1}O%f;E8Jv$M@KK(0v#d=O*b0_y??E)y0eXYFKnjL>~(bFe= z{`{L8mdEDkR9?WoV`MZF=PxDz8BH^+Wr0WrFPdVaZ6}%~y1P>A|l2(RUq555C$3 z3_`I78XCf{mWDXBO2jt4Gr$-+)W$(9*4JEbWX~Hb&ztJ(GRT4{G;8MC3@6gQN(EnZ zeY}BD)s(?>OVa?F#Qv4bFD?P1bY6_K|QJFr`Gn!Z>V#~uDjv;;)$$mSs*&ktA) zF{1TPc`Qdumch)QH*D!J;WP)85Wq8B`qb1^*z&u!G+daiY9S@{`h!<@=>y!YQV#ue z=)Q1_O&!j<$(QMjOAl^#^lI-jJlpJ#`0xAcal>X(Ssz*L7ah;_-E!-QB0K&flAkw} zrgm9tkf~#YW=zb9X~eEIQWB{zpZ$0;l==b74S8PB5&q#h$+{RY=e3>;wgkHkM%&~R=a%2n z|Bd2?P*Fg{gB)Y`mFCYoPZ_at-d9Sw=x01W04kG4%<;v^(LSW)>h6={!_-G+rrhrf zr9XRCw0vI42NNdv_OK6#f;)PDXluOFi2k@oC7JLKhcsLwGWpJu^)>leAKq3L>?uF9vwF6#1^ z2lJ8XD$vdeQvR5iguv^(CVB?gLSdcq&2Y^*R>=%31cSZLV5*of>mx)=O?yHrTjvKC zQO>hYm-C=22`Eqa@WAotqeGW$991to1uzurXwW4VLTtYW6D23^o43ptt9!Q4PToKk z*Z*j{P0AzBi{!g<&JqKqmw@2-0cFC0xCKyigWkfnnIWIJw9qDkUAKwX|>e& z9DWXO$)R}r)Gv_i+BQO>?w?Uc`Y|>5N5y=@gO)Xf_5V^kiY)oy3BExQL*8laMVYG$ z!}ZuXEQuXDZ@+Ubp zf;E&3g@HtzYX>wv%r&7r3$MFTpR*iv_ld_mM+fHqwOx&9J7L9&2xj_}jK8X<31Ao5 z+SdA!9xO7s9wS21O8oin9q;o zX-waLfXNB0Z|u+qrbXuxt^2LrI>zbYKnr!m*+>Pd&Kcww5sm^dGap$C)Tf|hkw2|5 zw{iRwxg2BSWpRK$T0$q*PXKw30?zh9u@0xyOF*YgwBv(lr9N%y@7`^#RX2(6;t{;v zRfJeR!0=Nvbz(+tw+&_cysFgi%>J)@am&wcM}9xF?P`>@e$LhLJoTS1GkpJ2z2Kzu z&)uc@`O46QKJ*TQ&(F+A`I)aREbOt#=e{9SBB?QN;8ve@Xun07 z>kL#epaUgJ(BU>Gd2_T#ac=wOXVY$-A%0sh5L6qDcL_8r^o!V&;@#pUb?F%$ z8#lHKw5o_FVPS32Dkipdw6|OKf4!GdO2Yeyc70%LuanWFczr{B@@8{J+iu2yYf;(B!2wy{7n?Qlmb5C9%z_ zm@RU{+5|CsQ{HdrhN%MJx-YMxDJb@hnz0*}0i9s>=3IV0P1f3L=$VrF#<(mCBC`yb6Z zH?EG-KY1LBxzcC|edA-r1Pv2TML)HGVc>YS)K4uWRNGF`TAU4HYOk*?lz*5CP)S_G z&1{#K$Wz*JOJ zpehuf(e2zfJ_*;1!?3xz$$f37@o%S2fF5at5#NgtF}LK20t0w$Fkx8YTlpL4ooU~J zQj5vZ?(0rrQJpWU#q$nkKZkPZcb>Xm94(y6-{yY3d79*V*3NQ(K~G%w#Wk6Y(C6y0 z>o^8P_{tYz*EYPctEF+g)!Y4Rc=m$l6ltad8VlyN3hif8Lig6*+b+%bhmj^9Z~??m z)7iVa)ndlu$8^KP=bN2cHrTx}nfVmj0qfuJc{sK5IYmUGMg{mDzo@!_Q}}2^!q6~I zozvRFLMzLl=Dbt?$GaDy`R#>}TH&h4DGy$WTQV{)Lj+WnCX(=hQi9mK zAjb~w-qeXW1*1^jR%gJhYd9yvl|A;tfV51w=Z$97PNtW$Z>%q$!8Ds-WPPKHTS!BM zzcMd=#=sj7tDTNM6Pk}WUh3=;8pXb-d$5f|s-$eTw-?I6%NKa2vAd){#2TRzULH<_ zTuQ$kHgD|X_e_@IP1|$XS+VCHB@Wf=Cz)+zbPP)~C(NN!C_62Ui-ThZT90nW^Cpg& z#JI1)B*(g%8b7H|+Y9A-oaCeuc!wo1QVF+NWZPc_!N6?^n1nV#?q%L-S!nKrKIGhz z97eB0bmYFcj)dWnx{6}#1vCytmc=x6&;IM@yGKzrgZxQEsVc7Ci~`6P#D#`BvH?j* zKtLiPx;gf)y1Lp=Qfx(o_B_eJ%ucuzbGU%*C#ZZ>ZvWBIJ^V1C-(n5-Yt|@L$@5{5P_cO zUfmY6ZKXU1^&hp%E0Q)R>ulkLam_q)l^ZuO7#{ys#CzJ=M#w($=s zi|%3kY<~%=;2AFq0(|75ZrIjN7b>t@AJa*vgcYbjVcQXgUe4qwx$sJhq#iT@^%vUJ z1=8DGrH*l(FPxpV>>cb&Ut4p0_oLcC*rw4<`&{u3@#XwYa)?Ho=4}4DZD{-2G`+=~}&Pd0kW6p=jzn&p_n8*ZgMm{O%bS2rd z3m5t+6*@oiFJ;8E+BYwckcOF2ezer7EaFB+hv;e`BUo6(5{L@%#8D<9{ z$3ky5f!jV&vtd_+%BjFrI*vkr>UEH-x0+?0hOP%NFhoxbI4gHzJhhQ-G|kZ2TP0IK zKivrZm@78S4EBWXzBeFFxq@hu}!VVRZcZ;2Dm|ACi5Xe4YBA+PdGl-2xKo{GAm zCQ)KTPrH1mPB*&E^KY;&K?FW-MoFzD8aiW_Z*JdtC{6Lr-EUkJ7>(n_^gG?sq0P&L z2|VP>@S0GuLZpT2Dv1QdKR}^_JPO)qY|W~M&`lchnrrIQgJ)pK!M|@m$VKA<09(md zl~_ikf3aBbr%1tJIBC^%4S(^ZcMt^-_?ITK9!u*=lz{8;3uHqmOGR=Al2Hfz>t8zI zJw<}XrpMb-;+3Kl7qhL3-ghb%OJRp)QR(nse|z&OCC}UWkVjkWe6+((#z6B5rSONw z1UWTz;2{ZF+RG?PdvYx)$~6GyI3IjWKc0|4gT#o5bX|b_je#ijnKK3@>cyiBltAoZ z)kZ{tQvGFng{I;*vR9>lk=Ha*%v zZZ|-E(8{jA`j0sW7d3*z+<1vU%6i%&y*YpSmms&jJm+`5ytBFK%WMtrAKmnhmO{TQ zbgTR+(|{*n1PN+_>CG!^DKE?0UoJ?ins#ks=-$^rkJ1UEBS}B~x2OsCB*FFuBn{dm zy3(jL4eh3L+Ij^_e?gT8%Eax?AB)d5VPQ1GfSu_c>^wT`?v$#DNE2Z`m>wFciRygb z0n;9GA`yQY2Ch&Y6sd@O@50=GNaOX!{OPFx`7H|Ng^$0=LRcmU+@j8Z(07(5M`b4zC|(I+QX+p$aJKH)d%1(tq+Qx($+H317gksy?G(w)_xQ&kAVBmtU1wo{q~E zi5^A`{GD=wMybrPy7h$8nTmE|x4XvEtuoJgTadyF*j65`9#{Whb^3AdCo+tUJZ@NB zUgmdyui?d}5UL2seS+y$=C^-k_!C%+YF_(9fv>*l(~hm&R!Fq}!S$0m_JsEv9B5X! zMH#ooymLbFec0&Sdg}~Z(=sklWy$`-Eq@Nh{3BKmOnx{AhD79bLt(9PpI~6|U0mrERa7#U*%0PIXQg8T+3ypl=c^RK=6YyGic|JWOh!{SUc^68L9Ijf(l|?Mw4Ofsgq|jKtmR{Zm#qITn&sy zOB`Sh6_+!Xz-SR;6&{AqoIE|dsPhca8Zez&6orjg(j4>A|8yuIM2-K-3NXrwQ)e)j z^z>`pJwIr0GY`^< z2s<&h9|#@M0H)=y1OdtPjG?zyZM$>L=1WQjZ5(Ogr#w|T1Fh);xM_hlPeIUe@j9D3 zgF28cwY=1p@3G0hyDP%q<^GaYtU`{RL&l4Og&zM5JP+}g2N#P49Fb`W&VuRYl2*}o z;|X}b9}3`LmO;X}`O9zI9UzHtB1H%!;+_`ONzfxne9eS7x7rj4cKb}^elxl>ONOaSY zfZ<`RgU(-jb1RAH{Y8SMKZ)(_05y$kXZcFs{+TEvg9q``jP1z*757z67@n1?kD;qz zb<*`m_o(yT1G*0|mgQldO0%}}`1ugetv(sc4Rj7)xitFo81}kY z*S?IWxVUlqu$l+Y=VI6vxw-#-8CV?6=mV8mB<`oLSzS;T0q&8uCIF;2aE7k~r|=#E zN34Pr;5RMvcnyc~Yr;1x94w&883+nQhqm9VA`{d6Y2n`zECBnX59+cWP8vkGuq4{0 z`+3nHfCB-~tIo4>c~Xi_JSq1;(w2``N>9HPOE)>N4C^=k5jWu25a+;G_h?*+x3#)^hmpo;{=85dJi8`9 zQL^@c&8kh=!6HA+^-)z6Ev9h7^Fy$a2D7hU9xL_9gJ-I(eAfCJ+BsvJlh=6Q#$!RCd zSbCCM;LaQ$NC^2IS~*aTk$2*z62d^s4{SZp@L9tMFy{tRp}Y?NB+dI8*Aq;UC;xR& zf{dg~KbX2VxV&)jb}|~@P?YZX-%cWD3Ta^_28vaiZ*)e z(UyhRPTmZ+3O(z1^$#2~Qqt=+S7}cX9)&IJP!Ih{xO>^~ozTMY zO4Btycji32=~dh8e=~`AV=DnattEHy@J$4u{KSIu?gG@M2t=F}tR#O$E_reL)E-)q z6PQ(a{UUa~-hDA2dHJ@rBK8-7-rV03XnZ+;nIOE^YNZHmLT)f3iHmVt zA2C!TS|3rIq(146w3$z`3(Fl0(FD8=l%B<>#96=XjK5uaf`HEJ6Fe784w2>)nBI6$ z7{cY4DMGg4F#I8n#hO$EG>WqrmWUXXbZ?yi778^TN^FR@9N{UAYq1$vUYbQ+YF}eZ}-W$I37^jGQ#es#?sr^2zO3(ZmcteZyMA!27 z%|?og@H<0bWI|V}7TN5rBc%r@k16(65Z~)4_u|!A=moQ{HAb#%TzM8DQl?EB%{`n- zj2`cWwE4Jy5^9(`wJRURcHQ*_2fmRE`L&JnJK7Z5CYix119N8nh8+9q2YqemYx>3z z%NK^rz!Ru^#Vuw&x| zDw{xv0u0qf`K!~OJKhH@#YKor{?*ArJ$z)*4V=ke7X9k6p^Tg1<1AwtsrzI4y?zm+ z0*w*6d^r1ji@K@hTQSg7;XsU*g?bv$6Tvc`W)U8(=fP)mt_1%p3~XgU5;6azYHPK? zzOf|eH)c9%C47f*V*wK4Kz|{d0vux5|vy(a~vu!p}`-Uem zBe-<$Zu}j4h<3dJ>1Yh~^NuXYdc0W5^iFE)99cT|L%3{-GNF&tG+O4*xIX_7%P6XQ zycc{ecLEqh&;~QI@NWp^ANT#h9_o;?t0GNQ5zq`>-ZmA`=!0KO%Q`pZct(vP6*!8O zgW*K>KlOiYfzu^|vNO7ci4b+BZIWrg8K>VC??Ck~5Z%Yvx@hD68_%V4k6f$7TurZm z1p3czWjuW+?FVt{#loQZs$u(j(BfS#Iny$%@cGE0JAVo+4k`;mxsRt91{-%y9dqM2 zI5))6vnN*_YZ7y)A`%?8@BSVwm6)R2x^NY}%VH*m8NyfdQ`28RrsC2m?vBNCT+tov z?xCYOCeGsG7ck-OYDgnJE3{M`{p+bF^lKButzX3!d83>ofOK5&+d@4P#vPLAj%K0(CRSt4FPi^Rh@P@&Mw1@iBVz`_GiRXC%B0+6H}v?5@NP;TzkUXlO9@G$G`?wa1*ygc{qxdO|a%*?yofxWatYbjkCP=)W? zbuTGPa7ovK>0+yKF;1eoPfi57^W8l#5+^VvNdLqN%s}g068XU^XzilAv`rO~(~m8) zaC%>Fi>YSba~d~of2#Qw9?sQTcvuD4U@)_%e1CVrETGP|pHxv;zn~9Yp7yU<0!CLh zWpf?3D7v?0aXK+(@NolI?ous{O#qTIkhL0!&_J49TPt@CSr^W8kw z+Og1^C&&CaO7FKJg-|59$4VT%Rd;4({C`_eJ3Ix`jBfv=Qu^A{H`Og!vRACisP}}Q z<;Ztqe8d%K8*gk(6S)Pgvk2XNS124U4(i1#y{F@4z)xGAYW|J`lfanlREE^9KN>#4 zFa~x03I0Cd+#_rJS6z0YTZBiaXl#-j@Z#^#+Yv}7vITty#qBaZ6ENUU;(Hio2C#*E zAXzf1WV*-acIIzGI$Gz5m{U83mj^sbs<%>?{n8-6}snY zJ%Li!gqdOPvo+jK7`}xO8|mI*HuUSIM0Wfros(CFM7don$1(q#WvzbB^4RRe6^b|d z{PZ8B_Lh|<tfW&J%THAUlRMfGsC3E$9 zjRC6Jb8k7Le6QCa>uavxihO?i%RtIBcPk1d`@R&*Nk&oH}8 zstE0Z1Xl`U%bQy|XXW>wtN*&7lHQ@G1%L9hq5K6==6U2F^}>oz|7` zz4Z@d7xjU5t2;P;Fm9}s73tU-uNrBCbk>6`$LLL7xy*|Y%`!e@tuMg=#sETj7o5_4 zAX&~-U*|JyL!=trxhDrxD2ZymdSynBlASwOva;Je(b&Wy2~5sB(^f`_?}szCa2bxe zKlq#b(rasP?pgkX=~8WL&{Wi$WmwmqtTe4unY4-3@&X}>DLiS{>NFUpf8GBD;+|dG z6{3Uf8)(G3SaUOc<`8uUM}lsKC|s;pf(X;r;meph>&wP0{F&>~fv$`HUqiK2b#w-X zhGO2lxeWgSx0*s1QCT<6Xc0QPpYO!Kcu&O%xnF+gzlj?-W4PaWd=z{Ka5(YuE)r#Z zWbb^L?XY>WNHb`!In`3zyb5V9MXFPJf@WPPWWVB(LS;inTvr~#y z!SA-+^J;6)$LsBHtL-=>88C4!c%6VhhypM}e5O{H>juj=7dtEYwYxkvXwsgo75(;1 zjTA(DVPT)sGyJcdG~nr{=1}ej{glm?d^0~Is3+TW#H{OP*WS;pxiBszitYZG%d6C# z(l&|T;J)_KxBDL5^X0@j8*V1QNeo}5f4|I2JQG))F6f0-HGtuYep6Yo?-a)5x+ty z_RY2ZuJ~AR=l0F zq(Poyt3}l8vL!?@kDtFlA0V9K2=kjL;&P8Yb>ie~7A|frN>>LTv&9Q0d>P~W-Rxh! z$v(;QfTLSSi7qh7l;YcOKc0AF7I9}@_eXK3qdE)9Q6{jIb6n0+cd+=P36b~-3@rG= z`vR%@DBT{BUT6)K%wR5E|nxRO`=#PYIz7d_?}YUiWCBde)hlIH`; zVUJ{_o70+AwshH0s)VI>!-5S_#Q#2rfrZHks~lSOtomXpTO3zM_tp4g@9mKdf6g>2 zqDN2pZwHtx;x4t9=4Y$8lw%c43pv=D%S0(4MYacuSCMkj;S;n+hkh4*jiLR>e(sFy z*0paREE<29G5)&$#zaJ&R(Uiw$Abu($4?@?u8w4OCNb;YnTVqk%v_nni>fYOe$kN4 zixg3wICu29MZ6^CXy0>rXZFTASAGK+Q1MBX@ezzmqmbX6? z*%i8)@9VCu+vJkJy!CSIvKsa;t^MXYe^y97E6(6Q5w7>SD^V|F_;(7ZPss|8DzJ%2 z{=It)tR42@@cM0yp6_2Xj8U)T%P~*iFsw%0xGY=bPhjy%*L-}*uX%bY`t-VuC?}(! zUtQUxh~LE<2R|*LBFc3J#2$f8u-N5&2_S6qo*rH=;~NnZcOUh z`haQkBg|^V^N6>Dg7!rl>4ORm9C}-h&wQu2NN*t>mPeQl?w4o@vxf?W&zhJtx0Jp& z+|-@I)XvXGv!wcbr<>{muvCOk!k#Q-Izst$JyM3S% z7+4ZovDvL5#fhq~vg$)}9Tv}S(L~7G>@nunHBB)x;81x#SxTU?SW6!1-|Ttu+lyKE z`%j*ehsWYZzEKc>Y$6Vl&xj!onh-1dZ7RaSSkgM0lUT{a90>9+*d?MgoAkZ)x$T^ zhq^6)G^Zdo1ZOG@bY4AuLks}_>*V%rmNUi4mq%XX5#pyWvg$tid9hUL;MOoN{WBw7 zLiYL5c_EI!NnCaEO4GNh{R6Y`{P}P{oHQsI4y$iobJvsNj@i&ISc#f1-BWp`fDCf$ z5}^HS(7_(*U(9^)`1al>Su#Zhns+WW$n0lpqyz;xT-cUL!{n^K_|AZFvMORDg8Y<( zKQDkfcHCNd9FCT+JbU6l)(8H;`RujDhTPg5{T0g3#uu~UbiJS;q%5)Yb=tYBH>YUd z)bVa<3#MM1>(G*7W?jBV=q^$|y;;bQLS|38B>lXEwqbt_*&=Z!vlLHQz3!l>6_5MMZA!bD)*xZ73mTdZfrRjXLn%5;br5C4`h9H#XM)#l=P;Y6$k5P z%t&TgKv1JA^RxB7oX9AMSCx{oa^Yrl@=#4WRTTk$qbzvrH;X&oEOAC?PEhFXmHQD! z*N3OA-6IML*%1!ur1izc9TxFJVfwoI$oFk~fAWx+vh245P z`Fs9%)yv}5M`wt^g1%A5+RMa029&nDzOpqk-I*Y6dK4RfA+WJUa+-mmmbc%scgBgY zoWFFlbehrN<@s^_WHMrnt=GJMPHA(OWreHcna@ic$XWnfrpKN@N3xBTjox~^z--idhNOH)dj!GufM6)%&a@RVJ5<% z^yI)~UhwiFziTt@_dQ!;8)Vf56%2>NS@tRT$riv~8wnX;o!p&mx0Vb#9Nr=-`Jb&& z9ti2>=i>M5CYoMzXt>o-=8P2RLXGCtFP^g>3}mEP6)TnJ4kV!fCq5`gIxRm?o^OLdm-y3nRBpa;e?Hp^RIgsZI zln^KM+VjiEbot)`O$Q4EOSOHn4h%qbyTo<5sgSa^Qu|%r554yiL)rqU#DbZlS&;_^ zPb6OP6eMhCYtyh;<#OQFtc~0J?}m481(?JZDq-k8M4ls@E}jiQJo#~H)1P&mCtTS`PE$Mou7hggQa8y!ca9Tkka$$5KgrWv;FwxEwMRso z)Z}@@<+W(UFh`%}Q8>IloUf!)^|S)-PDi{pk?&od-CGe0e~~y{qxQOdD|be4vn$|V9!d|y=jRbRcg2=lgO>~~5ew+r4?^Hz_w;vOEZDYkZjl;`+&ice*i zRoo5Rbk!R9`JOte`k_v_{BGx-v@$AJ#?XbLR+2RYteJuv8oQn;Pe1l7pK`(Kr$3Mi z@e97#qC+IRJdP&pHlKe8fBSISTuA-b+Zc-KllY_Q@9Jp2|0w8Mu=KET0Y})(h7xvP z&^V2lnGCeL^k~nSmo2fTF-+*q$>G5xyK;jY?22lGr7B-9otup*T-2&+wC|gG{9lDE zwKU)TKwCn~N+-|g8pUxrDW>^CfMk=gLGM6jgESL4bQBm^ZsaW-1r+c3cdyO=@U48R z?p9-Rhe`WZ0RMxW;mppjgIexpZF$wJ8+(l}+Up=L|E-twrrM4Lc_{MY75o@-5-aZS zl%zgqx8|cB_}GzE5VN)o-}sFdMP$V96S~p?{9YUGr4Bcom2Noa_&zi_6R}uct`hpn z?V*ZZMk3vTYX%*r!zRC@a4+KWC!Dcu8-yU3kf$#N*Wdj-yN4 zGD9053uu(1mhdWd^lc>V2X0YADs_`a+}ohPyIA*(E`jng{dz>4^kcYT>=}7Ul3ZmZ#rEMA=U>0N1hkzK%b(sMLKR)o3;IA3{Jw+lpi$&>N+S(z zOqfikqh&fg)eV^oLQEdJJ6T)O3I`{3AS-%`YK6gDv{kNALriM*wb!mb|+YG zvY-t9qhEcrFf^AeKbJH^KAg;TdzLL~sC(@6;o+XZ*vI1xi+o#ddcWpfTQ=`=m7cfc zpO9)_EARC`^-?vhlSq zT~gI^1y?&H!lxVjJB)FY&o?cIJ8j=XpDTY zPA(bUpPtw@^`6DIa%BS-7uChmIo}Y0*dkXOaE=jm6nW4?rgrxAv4n{M;<1>hD|e*u z>LdKaGXm~Jl0*?hQgDX89m(PS^^z65sz=$(6F^~8t$#ezhCJnowSUJKJSKXLjO@KSG&yIX8egK3(L zYf)SYeMIxL7O}dzdj0x!c$nahd}HB>AJzq8z=sraoTcQq*4EVQ1ZlP#?j4XU~%HM${8mNm2W;Wikqv|?jtOFR7V;z zCux)4UhXC(1uCk()vKd>?bf(BzI|XQrh9o=?mlpkuRFac-Zbv2hmD5u+vrM4O3KRq zNLEVRLe%Gl`+l`5)H+}8sVtWUKoFIqlK!{zWD}n+4OowaS1S$uV)pBLM*W{@uu~vXN#xQGeS6d;9tLmukVaQ!2lfzj$-C4t+e|ZH?7BK)mdj zO(gkK3&Un+Il!6aRH&LZ;}c4QK|F+3c}z^!_hvzR!W2tcj@N@Ig9)3sGDN>ig+~9z z{C=+X6|1{X?64K8_OKKzM{8g4l<#DJJZ1fr(x&Dm84T>PdHgtgz`E-`!HcR7IHI-& zus`D*=l#81LeY(3U^?4msS8K`3Qaj#z~z*}#0dDT2);Y_rsa@lzQ0s_qwL0{r)}S@ z`RLwo^2wMF5Zt7f|HfNo)s^2ACHA8dyEa!VG@xtbBjI0T;A4$-kDloNu@kYFtokL^ zAUiW$;!Ea^tkR692&p5aOCFmihx*aVPm-kb~)xvFBXfm`-xSZQc&LjFuq`*3AF#QwlkuUM~ zApPFttCnK%MaY9e^yc|6nXsQskr>!u0{XO9#&6cvkAAq5z>!h%xPg2!lm>b^I2fUQ zLf_JIHY}Y!I9n<1zKL}8!~dY&s&?*D7s}PNCokMHP^*|vBoMG3yC5=$xPFnm;8%Ra z8viZ#d*H6U>)^s}qU15&Q4VQaS+H-RKD6~-&6of%ph2lJoqOP;a+Brr;@0j7tSWRl z&7)&1ZBISZR7x9zu0ZOz0qf@add(693g$^jKkQ7^=*zc?fZ=KIPKdt##}4zT%lc2g z^zBa9U3pEuCa9j2aeV**i=~|eb>YeYmB2j$i2nbB7`DFiNYdhJ} zNQg;JG~zb`x&7bDHdu%IrSv`SY%L+#wSGZz!(+UsD)o~|K8y6G7NK&_%onYt)TLoK znS2Igvd`tLGlyZV;x$4=UW2ZxWX0N7sGr8mpvXFt$mw+YE)w^@Aa7B^a_CtRO-GTL zP(y(6+@D##4k4)tSvo1e}=+V9@1Hpvvv^sKU z^K1lv-^>?4f2ciCWN|@TrDC<3b~OuCG)bpaNSYxs5V7~;M+px;L!Iicer(}LqKVMW7amK!~?=3)9LVQf~hEtbaKmRZ*N&4OS>X`q1iUVTUp^67N zr;U|Z+MvSYZoR;U=#+25rBq=z1Zk}Y0M(ofNSRW|GhNVB&Vhx#;#)myEGJ?ACniHm zOR=HU6><_OS&nS-P0~l{Sv|o?;G_kO!%ZQ(&+I%CZGLaJz2OdJTA%(edIRBd`P?ea z(cX|M&9*eDsE&x}j2JQ1-O3hOVPXcqN%QYlj)dY0w)RlHma3`RQ1`5cZHRC+e_-I8q8)($~AUt~cCp>~u zLl|4f=kSVl&#{aOFwJY#9A3Ae5E!Sk@GEY4kRK48yu!ZPwP2yhI zk;x_Lo^23mhLA<~oOh1#wZB@LpeuTR`y$p?{HqJP5NwtD6UGDLMB5n-AYGL;`<<_G z-y*NZYcXMu%VUo>0s@l}apu@PKe<=I65O>@;c6@0_<_Kpv4>a7fjzKB?bJg}Kh#cb z`g--uhcc!0M-kO+%_6eG<&9WpkJ956e{q2S#xJ)!I{P<}3+mNcbYFKHS#RIfaEsTQ z__!_aiz@QpSSw7k48DzAy)%@2%7MhDa_rnLt1ei~(sWHJb%i#5$Mi$g1*A?qm@CneGnWeOA;{%Jvf8a4e%c8F|G5B`A&8A%gYLaG}Elv1+0nNd3x@}x(% zS4)I8-4P#W=9%f;Z=aVrLwEI|=I7hv)78(@Yj22SgDzFf>_|WJ?Io+WvMcXXN~sV1 zd8dnPB?q#;h)0L^?E;ZD+VGA68i5+ioej{Bi<{9AvY|73d7ECIy}9GF=W9O{cZUWG z>eH`@ukuJ0zFvs3Vr*PI_T)>x&K8FDo=lfH+Tep>EI=byMezn)t~^HJe;EVl(?O`F zt^yaht#8vnyczt|{-l8D{J2Bp7EH)56RU7VJdWXU$ds(l9v+S1*uN;77c~zQ*U@BTO+m<5`MXU8UBSa_Uh2<+T zj->lL+A4H4(`y;YeaU7KS)6YH0S03g=N_ssKJ9tx#m_gdt`ivu>rK=EN&*mGqW{AE z2D7z0$m>qtvsrIbi%4aK^{NX`9a=>IqTsA@c%S>-(w`eIW?B#mt&h0E4_5KM^Dduv zHKOb;*chE@(-hl2ACIz*o*n6T?OoRt$x6Q52Dwb5d3GcYl^n4YdSG8g7Ih;bs?J~7 zhSVkgR1K12_i|x1LYGM>l>*D532WsU%NJ=lF2~x;^qPmG9T5mXd8B;!Q6-L(n1_L^ z_XD(a=|S~svo!x^U&!kP!GiA=-Bec)L||_UdYEeQ&*cr0+Q8|$RFb_#cq0>Z4u2S< z3TJ9{47>*2A46}e<5sgd|Lcc&l|3JpkVL@b>SwSiXlySOjqOctBmQZA_JhYS2^LdN z`^zHD_>bW&Pz&KI`*h!#a3Lc3zB95Y@SCScB7+T!Tqf2O23TV1{8ATxO$EDd`DeIJ z%3lYzcAQ*ar#LP|2;UzP7pu1A?OxYTIWF)|FkNh4zB2Q zicXIF7hDa12%yff$53bQHx#fO&i$bgm3(H`sEByge)8ufcf?QM3Yf&sxQ&Ecu-ztz zHorJIw=7%off-ej8P9$s@>94|HEICIKs2sTEqrmM*0h3{c+~mIC3ZiGcbiEsEIiiL zCL<8$(((?mL)HEOl=7qA;~qPY3wN+qkQ`vRTd9bxWzL5-zV)%zcjIKPo#D{d>S2fd z+mY}%DO!P%mg;P#PwDHhK_*+#J6u1Or{VxCG=t<|B=MXy8h9?e6r?gSVm5%ciMRyV zrhCVX9EoB^K3aCnyF9Wr)6PqgWMs4edFMdQaJVo^H(vTmouPZb(wJ1K5tOAC(=Z*y zj<}ZlTxc z#94YmVNk0`7L@;##WHAeNCq6+yTrq)++Zm4;6l+_H5ewhH@gq>G*5>xN3$6<9XTeS zA}>uhqc&8kY;iP~dDFR|*IPPUDhVNOYYK~#(AP34yKIlr*~-1-`2NNCRj7IcfYEWE z1A-O@GFjoYx?^@J3_qzx&7QA$Ff-?Co^;~UH`==LDz@60jyC-?Tam=F+-XguOG*1c z2re^9+fU%;(ZQI&!Q2k!G6Sp(GWSv!xwZ}`UtjQgCNkeXeAhE%t6hHjxsQ1eMNu9X zP8TlHOt>C<2=u~do@iH)(8t}(L?-d(M!59Elnd~w1}{3ui#2gw(ai`;=)RY(H3B;R z$iVYsMI;;_Z*&=G z5L!0;I4A2l&I%c_1*l3+&V=u|0FvbroC_&{Y4;_@r)(l!7A!&A{Pe0Oq5W^uQ=q(X z?%1j>#G>KVA9`1Ryd_El1WRl!<*Vf+#n7xnhvlc(kKE&4lo@Iwd3qAcy^(`upOVv+ zWrYFwfF%uyzp0)f3q9tuN7y0Y%HX5nFmFoDX1ShvP144GVnv%jlt7JUKOh2vqc{a* zVcFZR9P`)3<5wL5>LL&#HAhupB60DBxL9)ZA~;I@Fq2E-`n$FncyZ`L<38kEdGaF<2L z74{^Go^oxgEcc)uud#Uu3j;Fw3@9$9t2WanflcJZO8sK(&QSt|nSwD}5G-}++-5;> zFSwWcKo+$!UK3;U;qr2S2rk#A^IDNPvHtbO`2@EksTZ$^^3r{vBn2t?%TmE7^5^=m zJFDFcaPsc5(sN7_K}R{-kB~br0D23!w%z1O0+%V;X@evlH6uOdlwe@Qu(q3#@z&Io ziwYZi71gNUcRvbxrPDi}^dMi{;@exHLekZeBnwY^8OL)NM-Htde#HcQeq-PLPQZqgw6+^kQ2uj>cedNFkBTi|rSGRGPN3$bTuH7JM z#=rgLm^?nxt#D|>53ctw`bL$QNx$XHu&@_O*^JKv7FgXu1A_RiIZPn4joeZ>wB{Hv zBL?EGu4Xaiq@MQ!hJmM zc;>{+n;ZReqa_-dKgXy#5DT>8Nx*S zs6es3ubG*P8>mrYVqzE<$v=pQ6Ln~PiZ)~p_9PlWb|mjjiVi1U6W&D!plE-fyZl3=~%oA!;#UHJb2|7J@?LS zSzbgKe*JmkOPrjR*4AYc;TAAENG(+zwX@t@9KHHTyT=p~77j+>qydJeED!97!RlqN z+GC|~EH|RN`(vux7c=RL2)!5$T7(Ce#vAAn!`_jRv?5>5((pxIw`1k!?|S%~F4RRJ zo`)g`M!>0i(()Sr{1q=(zFxX8O+tuf&U|hvVntCesebwPmC8;;yW#jRAzHls2f+}@ zgZ&E0Xm2(%iRQ;VO4@Ca9bXN~axH1EYrxc;ODh;82?9{LXO;W^h`r8ab(qU5C^&N2 zy292tF53Kxh)y}*EM0xguP$yPs806S&V3HZjTLi_g@#^UL)iB0HtW7w?7?UgBEzR0P+(B=(siMf|N8YF z>w+150a^m$>$b@1&NQt?<7F7K1ib6YnT+y5gDeCbY}aW(r~oYchJFfQcYB>)(0=Mm zO8T$Fl^e#!33lZ*-PJEMMC0(KAC5%!{p@@WxbWmq!m9-Vbw(Qah6Ic*kdu;37V#)%wEw$GaTLDgyaKI|0)c=#-VmLwyu_Ue zr;@z;t0z|iL^@X6v_h3JlM8Y%*!fihU<_t@$x=NG81wxOPkT#`RS}8>yn1!MZ8h$b zDE7yum%cw9Qu7)I^eNGOuMMDLVuXPzB8I{aDi9U*HLOM;u8bxwu|{h#;vMtqU+vMQ zWZ)t!47qJQzvr2wdtRT*!TM86(d4>l9U^ov{()Jg`jx@zbb2F`g1(&WY;qo5VOyjW z@rP>`onTswo1@Q@k}9dIo91b<-3f~|Uvo4E=zMN&Zh5jiYNU(`0xBRs>x zk~AHKRLoD;LWV3D0Yyl2868R8=+)uEF*Fx%K=;-mFBOe2Y)GTCd6#+0F>0{ zyfIT`)HR3!g-58*To}FWo5cNwcS~@$KYnUu{>8_uwO73Y~nQVb>`4c4DwXaVu)uwtE#cg{l z)MIluf-vP~d%|RCT3he^H%`;*pRkWPEutxT2)A>l5uJc!cx(>iE#sIhep-`UNE01z zVv)N$#d`OT>7CIg;9zh85NlEt&!J=B_ljzF4)t+Qdto@oOA`<1cR)YsHK9t}J3shV zF}>#9#Vfi_QQ$uAOSAj2F;0wK-jy(Rq82^EW-hdpqj`W^G2{F9mbrrKXXacTcl)l5 z4!)vXcv6_fx~Fuba2dM>FeLa_zqO&{NTDpa&%oX1zPY)44ADl19AEyiU;v;LBL7h0 zuxNkZnF5=ow%99aB*t1P214<9mro|_JdqUIw!tGu+zEJp2jAXkIa05E=h>WIdns7| zQ(Fm@eI6~dQ7wekDvc(B1|-rCVgFIpq-fID>TTV>*bw9#aQ^zmpNz%sU=BH!Ggm?@zhF$m{TBSVe^i2t^dh z^=8Kf1LrfOI&P2*?MH0H7U3of7j&Zowk9%7Lh_Vn8i4Uce|b!BJa)w7M8}SRHYki| z(HCji7zh_|PU5Z3zbv(i8J;#cmZ$==s~lUI-Db5#s7LA}zotRS;KRsqE^KE;5?&8> zjx~e<@{ni>8ozrH9b*^<$!?_yLw2v9HeI((v#VN-C~ay%r;$x4R^5!7k;e~z2wmRb zS1kR#+R!}r!eggAG4I?^hid+pAt8en8j{gf!7J>3CJG8neqAZVYzNdl*bOC)Hz>Ud zouX7~d=$X3uB#R&TZx$l-%&R2rcSZAKnimD)48K%cdMFGYadoLh$$Jn~Ir~{N;-qTzD;kG??1Ca^Ge+ui&g}bhs zsr&T^Rfo@Jbt$K&f*6V*p>e0SCkb?KE^b?-I$Avj6PmGY6SeD*xAC$xy~v??;Z=Jv z#tc4a?UoYuqz6U?#kK$OBTsRG&_TcPOCoRS_HqQr+0J6`X>^h?Ps+VuDFi+oaE?bK z$7S~>8Db)uMwz`?_1=JPX-(3=Y`F(e(jK@Qmgu;@j;M@4P<&s+IJPQ7ys#IE$qrX( z(@Y|UHlAG(>WL|3tlicw&e;oli2{toXlS`vN8kuR7q95XEEq&NbX2wp1-`9ksx2Ni z(@`Nk57K0V)baXu`j}(~Z~=$fVsjYV(1~xjl&N+*Qh@Q&YP0-AZhS^i^)~G@repv3 z$qn&IGflbI9)NvTwv3Cf22t|d&Cc})g*@cd?y^3hizesw_|i)_0Q`udd5a1f;!&zc z_oqmX{VN;jCUNtj1F#AT(9Q7%BMXRS+G8k}@Vm!Ym?tnR*<*EokP=&% zCHns15N34b+GEWiN*4I9M6VlbdmlfIn`Dm$2nRg+KYlA|ZC$-Nm$APs9Wd#sqF8M;A%5v&w#!=_*X_!(zY8h$wylhEFKwL>(@6*3 z(LA{TlalKnWsZ&?=fWd1OcybGt-`9o%w_ts*FrmWFYCw$P~6FphDP|KPsZ{9h3sRW zqN+^P_qhg@kM~|s@?4z=x_5Yy@XZQr^rtM$Or$K#HZ0%E1UOaNRUDTdBAl}rUArwn z^DGEX!+T|`V}B0aMDPjo_*G-Yc!4YwI!VlEXgLFdrxx~k$rtrxK|lT&Uj^qv3kCX9 zRcygB0bQXcPX&+fiO3CeU`-O(h}m5WXUg>dS7TQm4(0m(kCtOAOCqw5P!v%VSrVn} zJ7sNBDl*ExjG-dQAxVz}%s znfHC(=Y5{%zCZW<`P_Fv&jqB0;+q$-%v1eFD)WeW@gu+3*g|@*z9OsX0D5wtQhJ=1 zLnQOpnsy!JHudi3))cXTb<>2|Keo}GQh;^&`bP8UD9xXvbBSnk(BVwXu5G1yO!+dP zr`m=?T>AHmMmuH867WL_(eKhLP{t#OqvbeC=r_@m+APizAQ??^F9H zJa>=+jhnV^_@=`q@b{AwzCe~y&q6eN`g_qbg*Eu5`%d&E1pCCZUTk=dH*yE}N}ePn z<}T=pi#pN?L+(?rFgUD-bum}oVkjSJ-m_kaX+!X^@iV3un=RV;nTrvMq?MTo4UkC^ zP0M{ZnfEvkoAs|RroFxa**CYZaaIsTlT>v@;(1ccB5yIzrRSDO*?fDBIVwBs9{q`) zFO8yUSU2DEmqlR1HfbnxFb`m6&nLg)=j5@d$L59M&TSlT>`uh&iYYyn!MrMKkFf+h z`nGZQ2`m%{H~=I4jfyi>fax&Y62fa1EK9}Dt!@@y+`nyn2NIu|uB9HwJS_B%s1&8H zYlIl;X4v`T3s(09PVIg@02P1r+rl87)BFDbuPJ9eL znmr++c4LpWcFoI|a;mBe?#|0!J8Ye?rc5MGFv60G_p2}2Ha?wjxDz-ozfb7Qc4=vC z@k4HD?ty0F!iVE*ot-lh5&+}3wYR6*zXg5r|D{;no)%y;-s249^RszaLNJ#

E)5NI5OOd+(ksi^z-pY-TVlbT|$dvNXpk79b%jtFP?} z8qK5LBSxN{g>Tz673RGRoD~p2-4IrGjgkZT;c_b~)Vuc@uEJ)J$>9Uhh?9h8Q{UrR zOY0M;g<0h!F$HQV0?1YNAvwZDRg)#x9^5QG|XTaxS$xj)eauRVIhSk_p4XWRryikLa9<+ z&H1IJKe|gUKp{)$fJSF9Vc=$rn)EMk-mxq^P%hR>S+I3R`vL`}FoKEoDG_%3C)=Kn zXa_xr6Vu0!TC}ICsaLLfy=~LI@H29`a3q>vehQdW-@m(7^%ve1<+>9Eeck>SXUYFq zz<6HnjvYG$6dby-4ro9RKK6wi(-jasm?m`TMjTYj9!S`hFzZA+$or#{N2vkNKl56v z?XfM=E3i=-5hXc-4a3a`HYqqxdMsz^2qk=cG;LV$H6dxu=+S-y--n(G>Kf82P5Dhn zJo{e!Fm-YiEPvM&JB%LZ zZ3uc2prG@i)U>TMYX0!7*`_2`5nL{h_xo>IJWAY0JxwJ?9yRKo_gA`?J=~6Nrh5`_uuiin7? z$@i_h&HnNdDwh%4AriGPYa!Oxmga`F~Spq zGaO13mouHlaXZs|a^|8J(Db#+lZ$9IY4RhV412L|&Oi7`fyL#^Q&rll)GxqX8Tx88Rv9b&0+@NzN#+4^@jBG^Fs@p{NCKv2&`r26^=jnW=`@S>;fm)xpQ2SaK} zuVrEH#NE@lPHGu*>I51Ca5ThbfWvjwR<5XguWwQ7ioO0 z=qOWL2OZZBus^zh#JeQ#qupix-WtQa-g}=ej{x230_h{V;?^p77Ts?5*O*W)5TV%_ zTh|eFfYQF55{+-$dCUN_?I~!tB%bWAjNW)fvy{D2QLDE}e?H`|xxAVe_54*e(AU1x zQ?^#0MB;0Oy*Icd2VaMo43|yGRgP5_@vFEo+yVPB`KGC|Wl(-p_-8S}6_zb^`n9R4 zIgsu-X7>Q(sq%ALyvf3gR}bcZhf+tbxcHpeLJvCCYG{BdcPYyEeA{N32k9>@9lK4m-RRp_P2@LRg9?YRXe ztcbZ7MK4Uax#8W}81+L`PG-wTvz73S^nRwn3l#4|jWHH^c(wSN7ap(XQThsFo(%y> z4b6?r!{t%lR6@!fOSA>>XB(na_3qL4;!Zqn*;ME7sehU0aDI5hAY2pyG2B$)R#mdz z8lu>L-hHAWAawY-67!JRF0l~i3?TCFE{E#3x4(4}NArt_QTW%*(-I2HeUL;9l($~@f0nyeuh@U=|^TneczVdm2)7QLfwNdlyXU@m@dIK+$_jOkF8G-tA5`QyL+x_BXb2kEdq)5s=;Q zXJ2=mR962AV{HidJ#}a0KcZOh2{!M~R5d?Mc|jj;+00=01e1z80U#7gN2<#-9cuUa zw80-ccsq=!H?$x{PpBC+j2yKbP}hm+IwE_O`R2!uG9EK;t188}Ln_6T!L8Axy_eN= zix!2XA_X$ymk*u5FyZy%wLF`Gh8fB*^DEvUb}kvTim2eElM)sAmQIo-{;p}*s`qG;8gRzWjTwF6tQ^W{V20M6GrWSXFV53IYSe3)_-tcdEWg_^ zwiY4LjS(2~nM(Bk;_GaghhLDpHT6IrF3i0h$Haj8jYW#{MTg4C=aQ&w(CswjTM>QJ zY7SkJixX^XiQ_~6!%Sd+E6@@Zy%ODTo`;WcPIhQd9V_k>^kytVmQZB5CNokIbU2P; zIO?DWJxLini%^!G+XcMCXTItGGSha9-Idp9`<3g_i*(1?M#ybFs6Y3EIHfI=UxWZn zSW5ihXd49EZ#{b!IVO!Hnrz(|%QV#cFH3vArkk9y*XKa7n#_DO{!suPyo!E&_W2(tK!*7aQE<^RkQ$D$w1YvKKZek|F2WCy!nN&X_l`@E{w9Qo4@J zO;2V#7?!mavW;?yvIwB7NFu;)0mpD)wX9QOqKJniL{oaoOb?K7;b9@%Jpn1s<+oQE zs{g#zPnekq%J1wmw^eMn&6R)J&U~mGtPV36W^jEu=77Ja=X$;8MB+PPQOD`a`AT&> zEhM4y0;9}v6t*qlVQOlvsi`su$U{Ro6qIQld3bb}=HL5yvldj`Wy#p2&IptL_c7i` z4mt#0jP!oLrEKoqFPY%Q?edlce>?ZD`Od;K@jRsMKX-m&UYtB^yIIOAbD~~=&vSa| zL)ipS((2V~2fFt(d8hF*iD4K!(Uh^|fwR(it1VPhqo3I_|Ja2mT$n_`cq&hP zeBO{DN^4XM{d3vU@hMj|HCu7D3$tpAt2>SXjm)cq6lQ}9aYNZ!f0gC7C&!pi7%257 z07|BR`7#8_Fr9tu8|UE_^h?N$xWdH7g3m{_S&;a((h(EpafThw1b*bE14hdm|Ci3L zw=jS$x13?yDIhRHCj0yO0iakA9{736%Iaa%QIXg& z&W&QbAV>lWqUx{KgHY<7QHKfIIbZtlcs8*pq;cNrs7SE< z$kMEC0r?R8#TlrC5-sxt`)L!BN%>90mFLoXxFgncnvjO#K`F()S5G$*2U;X z4(Y1<$;nF%e5NzG7V%m$wVPoEx*WWXU0oTuwH2rADSOqGHixt<^)s2jdxEEH)sHp{l z#H3A|9lXo>I0pLgp5p+CoZLRIoigvlIOCN4T~>MnP)mJk)#ukF>WBt{PO4y>f5rG3dYrT4Uj<~%S* z5#~F`JMtY#Lj5;hh*4$yXw)%4W-rWPwrbYCWUNtX6Gi!P&}IE`BhtJ^?SPyd?Jq#N zP>%=})NMI)-1Q}i&R$X%cGzrn^w#4$&5Blu)bfzQ&t1_iy{H<3&)Da0-;iB(nOa=W zoF{&t*O+%BgDB-n*|`qUYpV7z>3}O_5a~6;^B`!t+X5w>`Z63Jbd__mN@2E<%eE+ z?`)%InQL+lg&H6PA3=&W1O>0uZNcKS6U7=dQaJ(-i6ZC*6`18-t9;%QIzx?)r^sdzd7c4Emd@XbD!rGJR#4Wn_w4&~w*3r?qc8vn< z0TO@!fjy@ZL>+Yz%*W71v3CDcRn@FbV2`xH^LvYaS)lYb#|S~2AlpiT$dwXqq?W@D zgBT*0wv?2v9+$Y*O12{UjA+zpOH0eW$pK>TPc}~aEyKosi6J0Md(_p{sm}8<3Hwx4 zUze42{BS%mR)9lh9rhb&y0H)0FQz@9&f{Ra)Z{z*DT|?kdHovL2OaA5@5v1eD zJ+dNg=|``h7(Ro%Z~r^OR)^Wz=y@$utvSNE0#2*P8g2aV_5zI{7_ zbJxpLfZ+3$gDYEGT26QE&rsm**oHX^UvYd3J9gPV5N5edPj@CiI-Kp`Q{X_0s9fJPvMX z;Wb7h_CJJ=tPOEvqGDoJ7`u>y!W>gpc33mNZeEg`5n5SY9SZY8yLXTyx1hkNrie%+ zit+LBImAV`5$1J1kb@(dB9aiDKV~_%^Kn0$NtQ30&_AF__(gZv=V}uv8%G`rXK%KI zw0g-otdxGN)h$y41BiC0gTj!N^Y19h7%dR8`+AJyvaia&=#Jruv4`Bq{z%No2O-|S z=v6jhu@3!QFMqts~Gf2nv7YUz(Vh z05b)>&ouj_ADS#l2pH5ap5L!^uL8XiGJ4$0@!O#!v7C2CJpIiw`I{_vnxr z;jl#&?BA%+wlyd;23!YW?a+{)__I?f-34b$A?ykigdA0+(sNio8KZ-rZ}HSt|CEtI zfRGE0SR27m^DnGQ+(}!!u5SPG>JH;nsyP>Mc6HYfP_e*9tiVEPomp~BWG#V0e+)uR z#4e|(*jT?+fCGJgz1M_~czU2vyW;!$`tl1a4QkTe9=l1JiOw2-s3+}u5xYCbaiBp% zBQ#Rz>~ZyP!bxk*jMD@Tc6j@~Pc$V6lLM!Ej%8s8w}w2y`CyngkcmceiGJ!751PQ{nr6gCN7E)t+X}%Rx}^uo6c8^_ zb&T{v=MpmT5J&nYSwllSul_2p?Lfoa+?=XMcQL$cm!J2V+t5^oHD2jE^h~v@cSdui zwI*nO93r49a&j-RSPC?Er7dFU{?E7+Bv!|bjfzxWP6hQ`Od9KtgwqS8if1h>lmli4 z!7$-x>Nvr+v5cik3d4%7C%Lsq(kd*q7&dvOPmQEP-rNPf{{rW}pP5hU22LEKPajmw z6GFLaEr8TUzx;kpL3MRCM7w}7H&h{-%>82m`?%jz8+ z*SD+@$==rdnYBa$t-8{2O}rtbyuq2Ea^e_~Yrqp{Yh~r?>U!Js_oCjzf$}m4m?+OH zSJ?AMKk~P-Ds{cDpAl3llIgcssOooea!OB67vtw2?)W3dIa#pnr?(zAGqn6IyqaT1 z%gH$#S|Kob_iTdBfQtX^%K(0@qk}d$qhYh)qQ+?JQ+YOcxuf~u<^KOKthZ2xnE!>r z*)D{GHwwiGqg$+P9aWGGY(;w*op;8^ukxNTHr}4C=|?z`smvJf@fuL;%nPd=Sx?)t zA;WE*0<#MWJRp)ORT+xk{gy!&11n2`ZctxeT>*K?U*_wn>RMKiB#3`1-@+KPgveGI z<0lUj5=iwesA*c@WJz;K`6I($qnWV@Tb#x7Khs*j-zZzE7CLBgs^8eyIOz2D?c3p0 ze%<3y`5bo(POcCr>xi(hu$Tj;kd3u<-V^XT0-@g(9ab6+$GPtp_?F0oT56l#8Isng zF;YNK*|i0QS?+~C+6DHwkFLsPIGi?gc7$%3T~5K2lgotj^^xEqq-mjPMqQ@RY4Tm7 zJU4_-VX3#bw-bUF!T2nLjnd_a>?+4-}*gnS`R(}j~2E$hQ2%ilQXae$27T` zTS`U6+O~S~&-Xx|%je%W&yxS45itUUJ-CEBy zj~cr`!%}$VPS9bCvC+W+@SW(S5D8VdcMpF7MVAm*S)?{z&GlcfJ**vATfjN5j@!cf z;fBoF0R#*x;|PjqX{tF~dBG`j%DC#+e%f-%#mw8=+vQx&-xS~z`h(!Y=olG&VA$bx zQ(iT2-_OraT_koI=H>0%x29T4uA`X;e`N!7IRX})_vvzl|6O;7#|!L#ls0{-4fv=n zZEcGSm-20}Pn0e+F@OnpDyX9D^<@o>fjRCs|FDUn{Tj*NFhA`2RtOmQdyWb*pA8a& zSa|(7Wc!9t(v}$c<1uc16(1yG%TL9dSj1`>UaGJ4@;0pgX;9B}-Y=U~B;ML2N-{8-glO}qFCtPm+ E2Ti?D7XSbN diff --git a/localization/autoware_ekf_localizer/media/ekf_delay_comp.png b/localization/autoware_ekf_localizer/media/ekf_delay_comp.png deleted file mode 100644 index 54d934caecc921be967da733cb2287ae2208e8d6..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 147442 zcmeFZXH-*L_b=>oI0ugfkwX&@P*gzb0qGE;NRuiZLQ{H4=sgq_kq#mP(gmc38b~N1 zAR@g<377;3y(M%)=)6(SdG7o5e!1h`G5+gAlD)^?tIW3M{LQ%%{ZvPd?lSx33l}cX zJyBQIzi{DV`h^R>TmAVP^^Q&Pbx-OSjknSh!$1H06F;jvL%n44Q8D!~aCh+Wf9_>} z!O_hfVlV7%>t%26=I!L}vq{scc;UjW3s00E83tsLrouc%DcPIH_5LaQu*%g#mwA!~ z-K2^TmWN(8R>6a1^-FqRS|0Rm+6IqxQ>^b3O=YjhC=cE0J}n!*2Wc@rZ*ZUZYLeyY zUX3pFV&4dgakvD!-RPsd=ZfYsjm7@WqRrpi_*NaFUI7W7cMtdTJ+CIW1Ml|JUz}Cs zP6k%*4O5N}&#r4(5$XxKO~Hzy)cOBxW7Px{p7GzS8QO06fBv~ZBnWZ*^Ybb3e{TOI z#s4vyT=j?k5WF94NoC&3W@+S^9kYoTFvO>?rqqk#F-<>N>~qIDHl8 zX;p4;r9n>z9^y-Fo#d%fbKJuv!_Bq{#v{%gmJNX2zrDTMNv7<%pKjrxt-aCRJHVsU z0m0Vlz(v-xFD?h|z!Ju!hhUO9@MMMY)Eb!Evr_z9n`Vq}gb|SOYF29mon1jy-LZ9| z{pLZxN7e1V7Uv@l;m)Q@o$*z68~Z*lpilP6BNN4kH_mB)ilE1GNd7r-m&T0YklHsM z#&%vGuR76g?EyH6IJd9ZX$?E2KP#@9=HvN69EtryLr2HAeV%Rqd(o=)P>d;uEu7Xgg#Q9KIzhpJSPwakHM9+ zG&E+u;i$mcF0_(<*KxjWZQRHZ#TO~ZA#*?so;qU+99wf%J^m4i-o3JYK?tNK$je^FSY zko=*gV;_SFnE3dM(y!hW7VgoK#j;96l%S6%u09HAh)Dt8xKH z-c&kV#1I&hx+As^b98se55Za(Wc>#^KV6t*&+Fg#ii!iVF9Cz(oNyX5qC=H?eV6l% zYb5+i@F&qb`IYWOxo<8HqRO4ft&^j>7PSL^cL5yR6Xi20`<-5XLmLSR#lab}%z@9- zymue5yAx1LLEEk>Iul)c{iag8q2ivr?25cR`ISC_T;xM8Z|vIU{@x3MZ%?>uhTPC< zZ&PK`C}f74sxBJH2N!;On0Q1X^Iio_tezoLVxrUsCx~7fveV;@ z?ICuxeI~h=frK>B+}_51I-jCgnx!>qJ?Kth)fPE-W0+UGJ*#R0)8JSFBO01}T*>(kmb2u z@E%COS1etIBmUYw{fKMwM;Ir6*n=Rs>p{biiq-btSSpomJ`hHKs>;lU*{8AS?gMf# z`T2bAqROYUSm~%{cU`Gqq4x~t<}hRR(g9(-KY+C;Gc zG1!vm=Du8}jkoA#CWHO7_OdEt^^_;NE{Sd!Npc zfVkh`$)SJ${WgVJQ5Rd~1TzPScsFduKU|RQQm*maFNhPd(bx75KF50h=X@7En`bAW z8GwE`Hi=7=E}kx1-(b`F8l+L7vbP{swH&cvna#3=y3Y~Ici8ol5HCLoU%7c$ z1@`IL&V|lv$9x%TL=V554BS0by(Pu#HT!Hd#P?n-=t!K$boxA6VFkajMDoW}`<-mP31Qh6vG{`XZS(|GXLerFM9@q2ETFow&B~fStQq$h@{@ zaeHt&xyOu>6!g5HW((ss$(q|2`qz*ov*Po~1En< z+{*gI1re{DTdid!*H@`N`whg+kMW`DOoxnnP2BC}@A~tMnMwNm4r}=Auv^X>dsmhayCopbEXB z2P3Z>dr+8Z*GgYb@2g2k0qn%sesCj0s4t@~6+oaHTCMvjwjP@SV`ic}=R-qPt&~1& zn%@a^=H72jME*p)T(RGg2# zGrjhJAt@;H_^_>)((Od*7}s!Yk-3B)ul#b4pDh@^M)wicojbU8m`|4bHirljZvJGJ%lMtH&_#v4 zyxnh9hX@hYypuT>cD|)sKnRe0ust3YNO{vXTEP+4=PDJ|WRI+N;ThDwd1j}WJCxYE z{(wU{UC!&Ij(~pR-71qcw7gr&rG5Vdc=i=FYpn9M8Co3-OQV-(Vz77hkjTxwdXY)Z zq%64G$s<#MXW#KklI>SmjA?ELoO2BR$9wzb-Ff$84VYrt#!TE-Vd?;UK^C#aZ*1s{ z@h*`eDFe8_B}t$)#hpPR>s1a1Y}zrXxXXcD7FddD8Y>^y4MDff0_7pB1$mqirr$my zTg(6&1It5x-!Dg&yIq-f+7nWH5UifbmBY?tuSzPeB;Lq^5LfGi_e(DpN|-`mqy&r< zEO5K{KkPuF!jOWp zxbsgTN8e~`eH$@N0iBJO7%AaFuFx9l2Dpf`6P?nelY-RtNp2I2!@wJ6`_Q&=XIO6Zu=;F*E4P{ zE#Df5>vel;U!2gOQJU{U7{;9IU_~kutrEDlD+HNq1YmM+iX93Uqnn$^v?=3-f7cz5 zTi8}T%y`Oipj`USX^!mgy$5P{!qwz0G&S>b1EEewcGIgP8ik)@AelfPzuv=}A;qn( zP%}lCi{)njhp&8({BIv3Ha1+$3!~b~0ls%r1;DEXv)@MTU!rU%Y6%SkJhZj8{zK2; z9ucZ)N4frKA~|iOcrD=VdHY9Y$Xblcb-i+&ff_A=P55edD1DTTt304Dnlm1W?cHAt z*y)~u8n_kCN}q0|*thcky-Ql$ZP#TL$(>u1S&-sTHq1PJSnWfaP*a=UNZ0p3=L<^- z7qlwQS(|@PdW6^{t?9nEjyMSjYB*P^DhL>5E1#|}B8(Tzj*qZa);H3>epB@xGN0^I z?%q4_YzlziylO#@U~wobr^Gd+f54R=FT?01Wl*cXc!+51Po44H`{j&S+hiA`_H>_CCz0bK@ zPrA-4hc*)o03dX?jeA(3^M?1V9IBNla6bgcsG~78Q_Ij1BB(Sb%Gcau=lrni zVo0nC)$U%i#wS~b=Pv9{MDm65;hT{d%6bBF$_<4j1+{1!#F+UhhKyCPE1Q)aUi0zg zT-$;mOZ(7y>XB2o;HIwfH{(K-Q$se*OsUTSPs-6uI_o)pcM|qDh3b5+cbtutV@eN$ zLp1`+*H>5V8!@${Sw~36B~$-54up;akJ6`O&)n#Ar`pM;X87wBd`5>(Rb9ALR#ldk z6Y1IHQ0wjavUcv=^<5LCiViVabMw03{>2>ajyR(lpsZ^ISTUDdSTrnW(L}Qs4lcCP zyE={?=@~xjikZ+cG-3`nlUGo%?VNAdO^b=uq{qg%r&UgUJp)fmJ8D|+<(wI%?*^1Z z?49pagw%E-4^N!R3*L*Hqmx!0OGti3?}Hd>VXi^hp;Y_3Jo?E0el!x%QQVTbQq5|! z5>s!X2+SdQGE3!ybNrMGw@j{<5ic@dsaGA!SD8~p|1UE=|jn4ZVm)JyT_^Dm`jP`*8DDsNcd$yDsJQMnouSm-W3 ztV#9*Mz=-mSd2k0H zu4PGN(A!}FOeV@ zf~KS_u1ON+Bb4_*cYQQ+ch4Z4+uPfTBWVP-1T^PlZP}cRueL#rv24iwlO=Mo+r%{VX*9iw+_6+1MejYE|eXu zdaSslBthlsjV+pMdh`^604W*p>Z;1Lsazv>qvQJH$ocTo5VfFd4aHe#TKDsn1E-@M zbsnjJ{DPfrejPOfXZAFGjGy1`o4gn2JP8}741AF?n@1g zT;5~@UxUv2^%WY_qo0ZYB=&`+A*DWep_L@_V;6wDRnQ$~P66eTnA*U{hyy)kFh`w| zerkM|t+eDHg>7I*q_#3q2U@S7j{eT705Df7?fSyU*RE_|QS7@Y z^th}?wZQR8re&pb?Q$0nPkvKkvwz@1_N=K-_4(qs5^Y9Y=arsZn^CC&E+JN|v`lP| zEe}_pF?+E~rAA(Z4f4Il1~u-|sHy7ECz&V~C7Rs0%LD(iSeB70H_pl}ZI`_Hei4av z^4Tek;&-*c=wwGlnc)|NUSp}C4s*N1u|rzL4qZWpaO&LSjGFtD*rqX1fFMU;jl809 zh$8b1CJY!+;pGG?7PXMGx2EgBu#!m!leyddPv(3S%md`+Cd-Zb$$Y9Z5^8y=7C;W} zN(t6*ETY3~F-k~NC^@XxzN>3vi{WQrd12-n$b+h>?512=i|?ZSF9Su9puP-Hznh9} zsoRkfTm!Q#EPkUe^h5f`(v584WW4|p=HNSW-mgQOs-7;uoDvQB^(*J*JmA-Z1nA8w zjBF@ot364v5l=AESXjgt9v+)o)^N}%+77PNSO=d3$v%-3=&0{Uc4|B+ex&!FL!sou zM@3TkJI>fBduL~nQi?&LriZ7D*})?-7xZj;ePwlNM7eBWp1yFc4Ya|=xw-p&K`z%f zd4&z7D`_NMd4%M^dX;K2GdJsG&dxDXW8k==JI+E#fm6&BLQj}scsYh=Ph-{T`K}Jv zZ$sq`JHY&a{ABz3K2AlRUqUqbM4IFIxB|MIsov`TAMO()r8elbrC z+>R!mHqDV3|EiU3&!_Z1u^r$XgCld1>>%$g`R;R;6PtxonsRF}=4J z11pg>62xWWQ{X}fL!e8CP0bBExc&i1PEg!4wNKY_|Fu8X**1cXX{8{-%l3)&lj#0b zGY&(8$C%X{0H04G-)zMd8 z0Lggp%uk!Km?o;U^YO)Y3}gZ}GIfc2;MJ@Az40U8)8W|Rxxh+M`61@}8t86BPe|e# zPYNiy|M_yv?Ea>ON<~IwY}8n$M)ILDx3B}&zE}sIzB(`n>vgDQzIM7K`iRZgk909PMin$&Y8P81(v)0_5fx;%X(fbV|JVATpr!K`+0WwFW&(6P!Tpds4tjw$| zV;T0g?~ZV{kbC8zn+CeAL(6xA!Pu@y0o_got}} zN%wgB;bzUV6(4c)&^KhQ9V$*y`nl~?iqcY9>5g)c@ET68s&j(gS=6*I(_BYJ3Z>Fw z3`6t9Yi1sL!G&+->MS zb2zvIi5_hwEL%yMU!r`j{MKxbEi}l=)Fir~Nr7?tjQ&jjYzm`aK*wSnm$C(X)c-ck zCiby2!dz+?Y88#wtb-j36MQdAeufxLjPSC08nxW-x+ejvsHqER*?|Jd?U|&A7 z%ilBi3_uPc-_G3R*DOy}x{-~}7&PQmh^2LPmTiNT?$Hf7@){wH?VKn46LVVLwG2o3 zY&S5~7T%~6&@3OHD}@4mM~gRh3x#|e{Ex%8$2@YY0v;DxZC-1!zLBSPtjqdtp4Md9 z8SO8Qc%H(LItXY4L~SE?V*SX=;F_gwN35=(npZMEwr=<~So#qnoG_16EMR}9c#FI;lZCpWmGM~ZXp4+t0(d0tQ z5~M1AY6yN0DwbX*ck48C)eFQe0IRZ|Hne!8r~5V1^&^FHlOMSbXgiIll((%}!G3A3 zD$$88yDlW~2k55aLFx0}}oEF}_EEsNtSa>Sv z|GDVh)1B#g>QdtF#G`9$i8t?;mTng(XCRCI?$EmHRn!ZfKhy4Ghs4JtJ3GnQ5kjM7 z5Psgoo->1kZHbf{G;#|3_0D+iH5P+&*2du(vIIMImWrOSc94`;&Y!oo=?R}J1zCB zuGYLfTYHXF9J7wYV8|c?It9*O{QTSux^Cvj8?;5N+|N_$E&3iDDbM-f2>Km~V1f$W zO*}j)TC-5@~b zV^<(;aSHZXCKVmAe6}0&0nG3%u32nt?6&v-z9Laq2VOhLw zlgtZ?=*F&ib8w`65ZaH=ar|PWHvKO4KZ&;K&PmScmag)l;UCRfQ$@-hN=rI6#_TH= z77Mf%I|WNWPY>=$;org7zb(53sp#3GQTEQy%Zh_&Frk4w%mIbfriE=JoN(;?%b%Ok1GPRoL+Ol=X_I%guM;Qovvrx_pm0p>sHGg6AbP#S@W^H}=QIgBx@A%3 z?hX~ZU%%nBJEkH3Cm_^GmvU&vIH7fr9^NrI-i#sU1ksn^acIFS=4@+w3XBzRd5CNY zFUtO{1?VwBqpY-}SJHQfyYEf;boE81fwa>Njahr_k8-xjXzRdFIiwK8-$O@5`t&!w zlhGb*J#&E`=_cwQg#LV6>|(hx6npFS6;2md7_$#ke1It4Xs8vAIM8<-`8~m zEck18ehk`4VOi(6*v{HZuRN5sN<2AIb+6%vHr6jc)Rwrxpm)>UatT})Qj1*1IF*6N zsX4RFI~mJl{o8@Zp%Z(uf(e7HcyPyeGIT)OdXpq?F#TS2DC-J$@YmH~9)-h?N|=+2 zpv_>FrhLS@pyJxfZn@{ik(>3&$Qa&PC|L%Ja!ocqnfil>g!5gdh4zhqxtt&LrPbDC zCK%i0ja}&3uuLdQHTmo4vh`5kvWf6 zgAZShOih-XdJ1}SWLIztt6b_SVUKIm@?WAekX29LTe?%wW6s5GfBt0M=gn8a@oa%D zYZ=ig_hS(W^&*J`r{no(k%_vdXDW!wYOFD?oX&s(e#$v?En#p{DHrv(4mE$E8@PF- zJ~Z~u!@hK?=FzB>47ek1=$S7!nhJVH<|0$#4Io4bNH(QA1?vcCfVv!S8lBA&>-}C8 zyUXqe*F5n&tkDg7WQiB+YwTWDE8t8hRjKKeITY4R`$Hjw7VSHkEG8=v472PZE z2h<$!Pkw+bRN(3I6-xow=^f_86|ae=FQKf*w8c4vJFd%eayKWfWMH(I<}Ys6#OkWQ z1r1WKN}@uadYYtJyCQS|$|{n0V;oqpe93tTxVGL>Kk}gdZz>vAeFr8A+J3u3O$dP1 zYHs097G}mCc*{0S$(@=TRAr=rAbl0ayL*G{Yir2Wv>lCV#EItfr~QJQI9_dY*LoJw zN;9HH-12T3O6omC7a=F*gd4A%o4O&`3hUE}L%HvaB(@lbUUER;Oq8Zm42sJ^5ZFyB zwvL~3uFt3-Bl>Ey%YAgW^E5+TOV*?pcV_3TWi*JH(kI71F{cX`{I#_w?1z%z--m;4 zNt_IR4C{+ic3+w?f}CzYIyW}=WKbBcEsgD2h_G7&m6jWul_AI-`4`>b^i^$3#4En# zf<}b3O}@Fu!z)jNZOB0T(s2f^tLt?!QK#F;9v4@J;o6>D)q-VJcx}D?(>k?Dq<&|a z49I-*sc_j`Kof9$qDVM9XsH*PbHk9D0m?5vsm;0K8x9PTTQPSO3AJj?(8`MC8{{+S z2p9XAW*R+hF+%7i18zGy1904v5ED9{M(~mik0)m&K~l-hZ?&wn>^0V1nRev}NqJ5~C%%`YP0g)i$-qryiuK1D@Y1Q_j=n(3 zeN-`1?fyd2_oowknvD$zN5bh?84a2PoH?oikK^1B{b;VVyHM7<+F%jENH-+#)K zOanH0tOrfjj1X-$A>HE*y`>PZMydCIjC$9Y68}s*5K(^R{-yxPsneXMVcoYTtG70g zT4o) z9DFVH2F4e)2kAs8ceo~ET#{PgaKv&Q3c^3>pAYntN@{+u;pjW{v4qZ;_!wE_n{mv+ zHPM?vbShs~W-=%CwO4kvznoA?8r@FPT5 z{4p2{73+8PD)*Ok_m*WDQe^don1_8~4n;`IT-R<+*0A>#D_JTW@084dW=_-=zE6gk z)0|eB$$G%_nuQnu@1uSW;P_q9;7QXnf4BjmNEFJ?1Z({4{nK{H;Z%-MsxAL5~X_Q2^;3 z<8P@YYhm@vFJ!y#$*pT&6s3k3_*bRU=B^?fEvzfi}p-#DOhw8N1<&@4eB-CzWFk%|CZaj+`tsa>PUj6= zt*uR(>ABi=*KJ&BCGAxH7IVPu_r1|k{DSBfZHa#t_Rwg#MbsUVMj_-}g{v&o61pQD z7tYVD7h6Le;rdWTtT7e?%lrIU2-a?Y@l{ee#tH!w{+rQkA8>0o2o>gJgOSG|CZLhV zA-{su&%cq!2|bPHcX@UefvKHU(YBE?e(LiR3uizEhQQ^LW<*F!@kben3Pr}iJ6YLh zI=p+T5-3w|oWs}2MyRj5Of+nNQ?rV2 z&IczEdKS-l@3{AM-SOHuh93b32|{~81Bmk-qFdLSDue7cr3nP_GRShRoCNuN z5@nf`61zJ}i5m4*aJ5|CSHwDr#}$bxhgXrJb2Rq5pmnk=uLM;)Zi#1XZC>kSZB&rg z-oL1&}GQjF5`?r$F=RFrNvZApHCQX7GxXZ-1`i z)zo~(MTSy!aRH@5|wYJ0uA)=sP~;S$j0wWGzPUt()2($r5FN% zOfuiwp{VcEDjt@48x+o+v3C9MNz!Kf-ZS~?l>Y6S#M*R z$!kSinQZA=T_XcAM8zow#w6G0=d%IGHeb6E0?JTXIR~=oih$}wj}cBTeZ9JOqg3|D zGm(nznQEzO+U}kyy@fnQEYqC%`t;KNl!b@(6RK1Vii#@7>3jC)oS`Ez={2j}a|Gil^u>9R6&O{xF9VZ+I zi9WIk$!hDOC*4p-J1m-Tmrpg$Ud@|_98(G&MHbU`b&a;k(qdJbD(tIZ2W%ny*PHp* zQU?dM3)f3B7cTJo?Xp2!} z{-cMe{qDAwJUc&^s`bnQDO_4ws75yT;1Uy_{di1yl4Jp42FRWyi11JylX8A36r{J* z8f)j6)F=O12(>?!Sx!fVa~|oX;Vk7(^J?$heg*!ehm+qT9hG@ec80s|XQp;%wP1#> zI~9IUen0+;5y(4z_1;yTAu0TxCw918#7p>Fu=NxZuWo?W-DI}x8%4!D1TwhJERKR< z)8fx|4uW{RujC=iQd#|rN6jqv4$eAD zcVVtaZu-jb^u4c-qN1F8mzA%wTru0{RC);=(37IX1&?{xJJ$StAOCoMw?+L|q4Vdd z-4w*m?2v|UZ%S|mGsEGRwB-;*n1V12C7*b4{vzpG^ufjA227M`+W|ZV^ zoOH)`J2Ca=mR)g8O^EgC@w)H%V}cqY!^Z(o8FO}6xzlMey^gk-gHgn)9`5=!Kk$8#3J!rS=AV+ z@}}u#M zd#<_dapiar;>d8pP9lgW%f)HiExkexMlZzNTRP#f00pius)rf_8#lN)tYg-h?y7lZoVJp+)-y7ph#&uczm&@)W#xP_%=P)J9h zI`1%R5OdFJff+;6f`2v(YV_EpEO->Vpbq*9|DGSE9*)7?^19D1?1vpsMqm7`l*6xz zS`AwDmh_@^*U&5@L>SjHZ3ADAj*E^eAzFgacDnntF&snpXb4w|9Ng&YU;me^zwH1O z`M7hE5|h0)8cffX`onlB=h0E!z;pf3!`+^sby1;rbe6djuMH{tsmS@4QQvVOghsYP zzkE{@?O&*bP0z~c0Hlm?=k^%Z!|7IO)fNI$9~~v5u)+LtBTvV~6*vF)s>z#ULR2r~ zqp-()mGi^Xrx(c(H-c^U^aSWPXePTZvcWiAoA!xyjGB(>1G>r_zMDKew8hZO3Q9!4 z@=|=eIj8YsUa{*MmClsP6;egZ^`f@nLmRcRkZKB1yB$9{AT>%YKpAG7JuotoU+~uc zeJ>UON%U2-jv|?D#zDM6bl9&?oxaa)SCZ%~{_08Um=+oQCoxi8eGc%Zykr) zY=PE0dPZjLeOOydU5}k!51f46T~O3?oVw1|gx_tTu>G&)O$M4&S{!aChMjDnHbakA ziy5ng%;0vIGNUlENtk4-{9putzHZN6kpA!QIGseFitN!&aVmPq=7_(B65p=1sS&9c z;GO6E;OH9!-;9WALJuH(ru`#idH$soOGYxE?%6>XFlT=*MUXmLqu1HVp?m0Vre>;8 zI)Uv*f5L!HA8ECqqiE1m5W6C{epVy0c?}gf7olz0zUe!a&SvbdxB|TX%{bY9;`+Z- zfA;8bI5CtdURC9*o%rdZ_1U6H%T5aLq#bxN6HYH;(cp2kw@MxErebhIK|w)Y-g7R# zJQ+OUYGVo>ukI$}XUvMvP9N6p$%-%b@_*i1@+$P-qZVJbcXQ8!dAhC8LB8hZ_zX!` zuHdal1;Y)&hdZr@nXTA*_uL-4qrFkxu!DB)>GkxOsBVlCg>hgoQs`%8t}`}c$&wKJ z$%i4SUyvi70wJLVj!FTkO-*vH>UT z!qdkGot+osI#r77iT>oAbllzoNTIr_!&z|Me@JtVrJ=S+AmP@ zg3wLI+vFdFTgTTA1ykBCa-X1Dk5ML8fs0fA1kRf`CmTHHmlfN@vE4b^!ss-^-I-0bfI$=9r!9_Uo z*$c2fKnY_nDpe*=TRHmy9VSGTU(vh-;J+RXGE6ADC)YR~7cFh<+TcmskOzXc=?6W} zHm98=Fu-6_gRAj5Gyt#iT7UJr;**U?CL+6$@?A!3ZD}Fpm8o=KaE0;wiu(EXGZYMX z)fL@c3&aR;I!1>BR(8TsSi49Er3Ta}im{p~L9*lz1{ zvb70&EtSI`5*VEAm8=9PAqKFp+8QIjao6+im#kr@fKcP&zt4evYS}GMgiF<+1|Ih-u2RS z58D&LFTYO?yqVMDC`V(iWK|pWDX4Wcv)|18*ru(5kz-@4WsEeL$sE2qnA<}5Uk8VN z^CYifqJcuzEzP~v7rBGCCL6sw+IE$6eE@Tp22vF>q?NQEV-Tcj0k0L(Qwkbv2%SvU#SHy)0#zI`3edM)|e5yFjEFNN&Y2* z`&aVl#UD03@9y#J#9E)^A63%>Po64ow4R>@W@(`1C313&j#MCC{V_-n>&)@Dm&5!g zIwOU7H4SzPvR~%Kg(jo)*D&{i9Lj6VgGh1_njh*~LZN75@E z%up4#T!Iu%ugK3G%$i>BL+7@kbuHox&G5>@yFsL93#R^*jc0rI{vEW~df`K*TJJDJ zY1f=(T-~CvkrC7IJi&GKX4wHl$E}#Cau*2RCi}2*`*vp33Qtp%_ydoDsm9WCxBu>a zEKzUXygA-%J)chmo<)WoMDpbX*o=#%iCD_{Z)8OUlVR4U!Hy;`A0Z$+e&8Lyo2jJ6 z7w*eBEhhL=yaj-xEY+AG4#0)TWJt=K(1ddeYF0TU8l8^Ou*5#n*R0#8u|ka8zpa1(%We_I^h;Jay_r>7aD(|`fc!TCV?r*`ecqZ?3@w?+@1PC0yW@KQk0NYbHIFO zd@g07h^_CgsMacfe&xO&aMsXkb)mzB6X>QXmD0isxA3mu&wV2CR}~It7cpuj8pOlJ zk$KdVGr-bUS%FjyU+I~(3%tE=DwNuQExP}K)9lw_qzly^KNg3P&{iJI0YDG7X0Nb{ zoE%NGvLtDyiJ(vS@saf0XXL6dhy;5pxx#&FF#^H&6v}{ z0(oKYwFzxfoMc`jhMrIQ9fopgmo_PCzA9cvE2daGuOlbqR>9g1Sh5fE@%*XTQg+|# zTqn4~x3NG~s>khu(@+tKfa)-%1&uL^`a~=Xr=D9rPGtBMLr}LyeCsJ*G-Op1c($Dg zJeUc$?JA-SHk_Xww;m3->y-Z`o498>Aq{%PJfdbF;<$AmMRB&CAx>p;uoswHCKR&t z#5)YCC>6h31BD$ss3?DGb8vmT62V0%a4vT71rUk`TF{w#Rn$QFIDvd9#Sz*1Tsr=q z?d(%1prARO%Wa^mv!{zigNRW8wBx zAH}`paEa>fmW1h!t z8(PLDhD54QTbrGI41zGC;mj55)$Re-x6V{=A-=$-($~NkvdxNm2$Zrt({}pEx6~3p z&Ji*Q;ix_OatFQqo2AXLpUZxB==s|T;Pp#4Yh5&hd3YQsNuy$2x5H-a!e$QR-2OH< zmcv`^BY;KBX{Cns`&akV@$?iGU7xP24)`G5XP?~xxG}*3Il+h1$Y1d4FVu#Sk+uM76 z7pj)67Y4JTLt1m~4>k|8hW_z5YX7_AUXYRhH}1Lc;{W2?TVdd-CNkBb*45O^l=XH9 z2xx%8h(+3&S83ayC0?PD{4?|M$?g!<3vDaZOylL_i;Rfqv4c~i5BmL&FJKFD-+zSY zgN3D~rHze^NF)*t*RPtma+_BtYh`0Y@%#LbgZUmE?Ck7@0!G@}+JS+MSTKu{R*pho z^~FCd?y+VLNPV}xaABs?PCUKep*AfoP0R08_%$30zQQ6T6MW!dVPWCm;9zKIxarN# z!NDDRFk4hqg#p_fX#s4i2V1OA8e;q4pDhLoC0nOh8dlQB-t@ zdPb2VySTWRsCZO@1&1E5*C)SwM;rR~vwzc>B8cXK2immWZ3=GR*W24m3%zAh(9&Wh z(3>M>`z9^TWRp>drEeMyZ9QD#DAYI8(-WJa`GGaij^W)~(E;0Yot>R+T-}(G($X4J zA*CpDx5f?(=27mO!NEZ^l)@$J^@&QEq9TXS7yq!G2cOh2%XnKvdN5a{XCTZq+$jhnzw3jrgu=75^aO!G~~ zF&AG4hob8|{QOb*U>V^b9nU<}(a~{rg;7~JR%!qM0HC?gYD`;B_s!F_Sgv3H+iRiw zCHHOW++Xzh%zeFtw%S}@$1hP|@oH3%kqP)-{hS78Po7mFN{HDJk8Q`rQzQxp(iLm6cVk;}F*Y!w(KOXsH%#Q#+syf8PH=?B&asXx(Zo zSRkdWxtZFdjI3i>hRguFtxMHLq>_oqL&7!*wH z?1BiMN)BozF~$W=9yjNdx-m>7W3gDJsE;2%I*%679b9Z7L*X#Z{ySON6+Zp$g>j#|nqAxWirO+7G(IFi=MkJe=nf>hPzCqE|y@MBh zOEW{P7u-Oq1vNi~7;7g^veH?kvP8@^5AdtumEna_r%GTCaNeO>sJnJ`Z zIeB^F+8Pdr150HV7Z>lHY0|IyH1+msR2btim_;IygPB> zm)6$-&%gYB+?hz78GC%EBCRvrwZ`-ZW-|NbkK3;!BfGvvGosPxJ2ZAJL@ z?W2AvRS{4qsHv%`vhr&b3U&R9lZ3H}Nqv1i)lt{g9qR7xj*5zEbiNM#NX2tYYG+^l#TN3?1|X<3;*4CB=pyz(ut zrltm<=nN7{g~Q=g6Hro8^8NdFO^aS9i88~or6q@K9lqqA-)Ly&=jIdu0NpH^VJvoa ze*S^yoN}XuNOo3sHiS@QRj9wXu%K>2eVf{@E2%GQp7&hPc}4Z6&NNF69UOnOiHQl0 zcq;g^GC%K4tf((4ENn!fxMe(UNlVuk7OE5sOGrv~batMdECada{mQjEe@hEB(bMxh z*m`~pmx)(pWMJ5y=ROahLQNWlUU(#Ac_??2L?W%MtdK}q4;%++=oOynHn}SZq^zwB z7Z5^^A>Q8JRJ*0F-ff@@kn~>a-@reRl8{i??SF8Qp34FW#zu07t}HJvZ|Pr-n4_|R zDqivN@k)RC`}&b&7!WnmbB*G>?Ku&AiN zuP>QQ4mn&*i?~je5IsG;uv4NnmY<4U%7jy6H}}?4DLy{6yr&TP5n+!ns;TkZTNxe#P$r`o?$AQVq$B3$=4`tXvSq!C(C8_LT4#w2 zs(}HXY_&&6M^hz|3O@=63R0Q;zQx(JIbb`6S@6@R<2Rq4^6zgFMAuPPW@fVB@72pW zP?7uhd(NJWI@D%Uu@*<*F?Myd*rWnPUdnX$%gy(n`1Z|%^u30P98zUiUGm}d^fXny zKPUuxJ%663Q=BR7Zbi|hqprix-oEhq7Z(IoGS=2ys6;|riE3}!i<>DaeX%}2nwXiH zISb=>@l(H*{u~}3Pfbcn%FYHj4rb+^?G-7Zp)nb6P40D`!L5o43wPRzuzZT*)gxB7lEcF4 z^6$Geh}cJu`rT$n@ZWP_R~24WR8pel)fMtxUq!UU(taE7vx3OHY15`FP$AqVZ-6r% z0eG42DIAISHH?uhTkNvABRR9)*4O8QC!?aGqzYqVW4p10K0i3@e6Ep;mv^nBe0^wo zdL2xy>eEx_*dy$^-j5}}eO`nBl$u$FyKYZON$Fo57XA72XLr8CMtA@EBFT3{f`emp zyY!#4@eevXM_q~(u3k$wD?LA{?YO2k}iw`S9SZ|$`L;jG->|hpm8O7+N zYNkI@Kg}X%Vlps4)}r?O%rY*%+d5ZjWA%6NA>O%}8EtHp#i{NEPjBo_Ev=3pp(W*< zkzYZm+&~yP6g))FKQu6~@5qr7ldAjNU$eWry81ju7!hSL68VVv%^%Eaqe7S@#RUa_ zQ~Umr_3&86)X?wW|N0__W~SlVRDS=qZQG)vqm2eF<1|%O8GjzRB ze|lix`s8bAmF}visTK;Zd&fg=A zS{w&39-hd#G$xqN-dMB1fPgOF-8SuMdu9Io`IDyoZeUx+?d=p49c&@;Io{;O@$qp5 zCXZ`adCeaV3z{p(2wD9eu6HPz4NyeZ`2TB8TeIu#S=()0Tuir*N1YBBk{PJ&eOJGaA7!tqB1HuH%)A7*gH z+-Qc&%9>f|Fp~COaRCC=Fn5v_2lBgm^{1NeO3SBDaRfdB5u||mZ_SBH+}zy#-b)6YInRkW zWRmt$Hc)XZNik8K>l@XcJtY$v#r8kAZuC%~UjFx)wD0=&ccxfbdD}bpAwU)C`^^0K zP|f7UgAiC*DZAsU5Ir_3r<>ES_t}9R>?r2^dZ;)7%u06ck)EmN49Qk zB+=J?zH{desc0etfh0!xjm?oq!NE!wFMf+WWJc;MEq?uaut|YAS0QO%a*Q$PFi>?q z%E}LDKAPt|Rc3c^AT_;KXnZR8w%Qe-BRDvifq@}$TA-$;=CyoC(ez4XQrmcMv3nS! zgxhf4Q}u}ASFc_n0`>796A@YTT_5oU@#&M(d1T+d=D{YUlZA;6-?^F-m*1*-Prj@6 zTva!(k2y#~V=P23Dx zQz>`tD*D_|wRi7cNIlO^nJF$M&5wV%mW{CAH?hHIhoRec=jXi>&qobU{zUQ`8%u7o z1Zl*;`Q?y|c6xh82A{Na`Mv!o7W?jJrKhWKofM@HVUMsv@a!10mj}W!@?L1elvjr` za#Ko)ifXNtbgl`}(nik?R!d_yLnUZT)E#5$;N<7`9f@;41(bLBGPBpD0PYJyT1@~Y z1J5BPOUqF#0xyU6Z2l+dL*A;!U3Yd4zJH(fOF#sQJja|C>)fYLpE5Es=J$Epgasbh zb@#pW=i6I%Pi`pq4%|C|E5CjFw$J=)=7pf;qM{-M$FkMATBOJJ*4Bi?#QHdirIhXL zcBecJs6G2{AhlU&eQIoU_<+wk#8VIzte=be!mc|nUHjdurA2o2HdLn- zM4Dy;$}T7OlIDK@Mm}pLI|r%0t!-@VFLbu>@hMYG^hB96I5@cd$MN~})zwvmbyOzj zy4C;^-eqN7eBG4r=FQ@CP#j)(^ytykr-zXv*9tV=ytnTa$BIL7vxaw!&B~2&A7PP0 zYOB&6Y-?}F_20O0qb^o7Gt3YY?!Wz(4i3_eKm6k3`yU(@^gN?sWR%%4fedMnT<=x= zlgJ4X>?-%~-ShbKGtldq!>OkUSNuFYJRpN1>MCBiP&m#*PI?x6x3~BCacg^q zlj$QYiEjJiDcuZ5-tmbEQHQ?OkGuKjE%mPE>S8|wG2l9Mbz@vk^6^b0()0210_K>L zIBhH}Mu-J6-Rre7ZEn_G`5Ao@Le?6!5x``uF@y>^nS3mkcc|u2aA8dK6R<6Bp3z-#_ z4lW<4(%X9tI6ouNegI0qc@>p7{Pn@oD3qaW3ZcMVAB;~XBqZpYMoAVRBco`2qx`hl z^lKt&X|6~b6QsSxlr2ax#nT8a#nabsa3+64AszYn@ps$2hYugx@FbyhGBYzn2@^eC zrmm@JE)q+9MC|BY5-nSFtwIQW+iSm9qUo9v7!+jI3(`!|J|!6$8K@vbC8kFW;#mBj zh}h{`Sy?TG?GlMiPfJsd*@B`(^7!#YcLRBZJ(QdCE`iYpW&W$XP!JVwVWOZgc1&&? z$EfdRlb_$AEFmubSTV8F_PLOiI!Y05Gd*kKky5F&{O1owquTf+Ml?wyWpvasP&hq$ ztaPbQ@4aP{yXtaLi=|LvVj{5i&5gCCwY4>*kcJ7*h$*lD9>0fGVuX?vdYu5$aUpNt zT9}x;(s<9}zhloHf|jk~JGghR(^9Ydgi8@(B8s<)iV7QjXB3keb)cRy>8Pp`de_ zOn#e~*eTkcm70|F(DS~^(^Esuf(IoKsBnqM64pX7L`*cgXA}-pIQpp>?ZJa! zUNV6lb8-anoq&LnDNdORs3*O!y8`zdZXW!DK$p0s(=c~7?$>n>7Z(>};}=bqNQINR z`BfLWBI9q)U67amoEUA9qQMoXy0lcjvDVygeZ#{80Kq4T1NL0FaA9^~VamI#%{orlMstY``&HfMMxnkGSOsFc`DkK9Wo7Tsm^3F`pzR(r zTbk~b*@4{1UJMqg)8F5pP&AiPa-BySa`W?dvmh_@k}m}&h|o7RHHpXZadC~)*UCZ2 zK8V4st;@!oQZtIT_Vs0Grsia4Tie)FhcWx|y1Q?y45aoQPk!t9m}VzSD6=%5|IFgz zw1Ka;0HTMJlM}AvP_P*?A+4Uujb$Qs*!L7*?}O}lyHl&Tm8w@$7|*y1LeC^L&D}hh$t_ zT{#cjZ*FeJzR7`M668C}+Ze_-&#+dNw zz8{^-G(Sm)YArT47Qo}s;lmywroU%rFQ}^K@vD?R0oODb|#yMMdn# zk9&`(6z6APiHSK6KhR7y$TB{Q)m(Y%cTZ1`*L2}qayZ}sik@982_#)lUo~Tq*v5G2 z{;n>1Yy%Jz?{-LWb1U&hQ!`7IEGa6hUzA3uIfs{7-rZ*HiY=g_@wifr@=)+`6wxc5 zFP01?{Bl^}cd5P~96T{G;qC2>Ov&$?o!T;{8ZVXJG6te+TQ-}s3GsL(B-{zaU9~t- zEIFvZ!k`M5LH>Yv_gW#$O*?M

DdA*J7GsW>`=Voz%@6<)K-{Ajmq&=Wuxj zgHd6s_Wfnvr=Ifg@YuE{U5egFyMO;a%5Fp%AWCZYco;8Xl*h-)aYe*tKdoLplo!Vfy4 zuRKvAwjLByM^DcY5RTg9W1F;y<3x{GVsg^b0Co1CP~AgGS-LuG)69Mh^eh4`)x_DA z3(|IPGuo_?TD;d+JtAscrnDly?$2<^{LKWK>*D3hrn$PPoqf)Qdt(Igkdyl)EF$i* z4~*EZyR7W&=Bs~ZsiYrFfjI;N*;|~9eg5VRdx$)n{|-t@*FP#1cqMUYN6QhT z@S-v7ki|Z}g9uKig@uH`r6Jp**x@{S^v9g&PFowB2=N19bOIlLmU*lt#J^dZnwr9w z(c*GkUYFGV0w-to^|6g@sX8cHEv=E^;i$)tUCxD<3ORxQ2?+`seVcD{)Xd!6&CM;8 zPQV1$S1Ro@zOa&(mPQP|(X`b`I%IWM@i-b2P_D@MlioVy>;8q#BjR=0yoYKLRsCrY z%xGUS|ck1|}pg^0;Q$<;MvhVxZ=B}=kCQB?(Pqo{LK5idAd|0$=DK08Ptqkm= zclq-ELx=LfPfPJPO-X~BdX1v2ANAdk)1lzz3oUCR&|(8uTClCpf6?a*BsBX5{7Nh0)+w7df!) zR4Rx<*RNkE(f36~9l|jgSm5ZUx}brGSEo%p>Ew_sK-a>$1<@g5&G&+*t;U&Ho0c`{2ua0yg#Oiavl zBlYr-Dop%F0*1Y3au#F1WZEtH(f9oI$^SAe&tH! zd*>#A3C0E;=j+!oaAD_e!*+ zKD zc=(Wpv!t)ww_M{Zn`8$7fVj(--d^vI{yTe3T_P289r~r>R28BqEo6z}KubddH~j|S z8k@)+9G}dNbWJ_zT3E$2G&HEbOnu8&R#wvW^7%kzF3E`8`S370+9Fq1R#uik>dnpB zfKHgg<4RFTe)gT&iAhP8*b~;dE1oskn>TMpY!c(h7kR3T${fH=@%(x1TWt zDkeAI#ZC+OY;t|=usM$lvy9DBDwvuMf<{BV{Z8tJ2gDhzT2RWE4Z!EQ*;yUpdf#J^ zQ7oluqyPaUR4jejg`7iBaZCp@AA#8T_)#Xd{tzAv4Bg+pWr2Kz)`n5}Lne<54Iz)Y z0fIu&!l+b!{OFl!e}rz^9TrK+HIRzHvDA|D59e7@6BCaM3SMT9xEmPQt)*tKKFmztUjYHIN)&rsyfd#>p@lwMI+SHE(_we(u&uDdeU z<8%iPw!Jn~+;R0JT^|(2YG&UOg@}iKeiX^d)!p6QKdICZA2KsC@^sS$&Fiw_XMP4U zORfJITohr)cL55ZoCl%P8&43k1j`K;+k1ZBEh%F0yfJ^LO~hW%n03~bB*1w&DKNdMcW4;to&GD)s1b~}vx`n6^2*2IK_^G)NR+ge&%ujO>g$jW;0&_N?P zuclT`o-Stec?hvHIVmX!Oq76$93Z#6ygXtP5+N=I)N9Q(PEJlN)>6a8x;<1>QJOnq z>djNzx(1s-JwZWU=zDSr1MlxICok^??ZckF<=eNJDq5pwl3toS_A)SVM|z2hhyZnf z(`sLDcpM$Av~fwrHS2%90Hb}z3F+x}9T^7ra_=i2sUb4EVqQQn=9pGfS)F@>@+~gga0lh{gZsl7ct zV8Mp#W8F(zllQ=K>b3@hF%JjF_k4%`rLrYS&f30rrV3tO#rk~Il$2B9KLL5-&v?us z&^l}TUs6|Z{`T#t9d$%R1g<6&)EU2Fi5QYVMn;2qPJO)ehImX&z}>qSjtjF#fKG7r z{c`P8x>30lJNuiZYz@RQ5R`Zw6bXjrvYsBf=0rR;)()1*-af=LjPo1SIBQ>=#a^lr zZReXI^YY8ruk@#{|AL%M{*(Am#{(XQ3YGNKRBj0gy+n1aaHXGd@~=-j{`ePZ5h}wa~gxld^; zZFfd#=~{?r-^1D==|3N+j~J!{Izk`j_{{9a5*$fZ6;SR~dChP{s3 zHv(WpgYVs|sjaQ8sVV&3AW=+fneg_lLtn`@s_@#YbHRCb-NO?TUJyaC#jjY0 zgHfGDM?g_=v5}Wo%L~cw+wyhG8<|pj57{EZ~bkY2U7_XTW@;EL2cX0A4}i{NC~s3g`FlUed_$MTap- zdKw$`(`Dpo(7(^c zU9CYifcZQXTMzmSsuI13?f0*d+|tmuz-hs>lBhR6Bybf>PJhjjBfgu%wf#utOrePXIthbIb50JM7WrC^%@uocdo>vV67s<}p( z6=okt8+vjI3g#&2+n+f2eYz_*bx9V3g)~htF&V`kV?zv3TfhPXGWwFc`xQwW=)=&= z(Dy)$AxcX;AMd@`iGcIAV*+7)ad{*@(BJ=jPETJnur*?xZn_A_hL;z6kUs?k1Qu7d z_#lS4J>J|1?H0-5CPbt%5Me-3Ycqk;fEm2p+}-c3B4l1_=a`3R9BtE6R<6TPqV5OD zc@i7~JWKR@0{oSLgUb!+o>Y)Z|` zm)RD+#DdYsCY2ANAIeIEm&pg zF&FW`&1BF8zTI~D^-x@vWPw5uX(2SER;pwWT$Xt~Jt#8dXJ= zFZ=TfwRm;)2`(<{vF1d`f7Db|z}1i*_#tMeYo;o*Lp~~oMsrzRoi8d8C2JZ4MktuI zQM^hpIW#nYhfq>hMkMup`uK5cF^d7S=lb$UN2ZZ4pyq`L_JyfP752+ugt326$D;PZ zBEwFDK<@$Pf!JzBRfDZabY$dIUnv+g5Kg@gVXZit)6+Or6i(ibuJV`U{q zMA~WK6ZcJ}XLohefd{HB;=SL%O|ZJk%Eks#mDCs`%#Eavnk9-eMn-Tb7(^s-12_;!4k|^0bbAOGpKB96-=sc%=uuRZ2tp}95aFA{X2fa* z6L##_uUp%h&MPTRtp9Aa&IM9RHz>w+bi?I?{M+>ETz;<`%98^vUScP}J%~yKSH05U zLRJLD(9_!sJrfm2;uWa(hRGV>ICRrBsj0(QWCONr+h#bqF$z^5O%6SX+!P=wUeCCTV4H@EK87VB=>T1oa$Sz*(zFEenTE_p3X9FFGa<# z#Acfg`MILMVFrd02(+o`rFyc9cpP@YdesOd7kme(X zscrw+xnQXp8#_!-Kc2-Kn~;~cctU#lf}vrbGd9b2(=dDwsi*Ka)>ZT&D)DFLf9*{- z-aR?a$~u51zd>*qePkBU@fh6T1-e3kY+Dw8&D1L#2QcvL5gwkNz}{U(*8xtPodL@b zu*=HI;5UdKwVy?Z-568z1)3ov^@(8_0KOr4FJoU~2g3s})?q!cUYmWFMl&@Ra%!>$ z{hn=*oW1`kefBi3%47_JjExNdm3ltpBpR|;s(P}no*pb%&{}{Yu~I?WUV6rxRS}_O(nfJkQTxsu~W$&{B0Uh-*Nx(bq4rYYJ&btQfM9`|h@8f4icwr<^e+BS7APHhh~|L=Pi z_EC4jIrXj@w6>!vW)8*2Y1XZf$$ z$S^-hr1-~=kJXR!hbt(ZIdjH-c&s!mtg%Y>r$N*Eyn=!P00Ee-u0j;FBp#zMW;w%p z21CY*R{2WgV>4i)MRYVXs^o;>`!`3_2a-gDU`$D}4p_}!YB%W17VeHkOmDMXpZvp2n<2GxqtsU%VHy?mZ1=YSo5 z|Bm3&Zj6(7tC>phu}N&DV?rV#NH?fS<$)~7QeL2#i;B=3b3R_yjnpS;-I}zX6kZ5) zx_|%v&I6c~A1lqBogOf%BH3N74Cstb1OIyAZd)_eLkM^fOs;McTTufS4D4|6;zgkP zQiA}P8}<3}NfgTf40SQW6V1YNS|f;bPsClh7#ID{$|cfK%;V(T>!aUT`1vz`{klf} z@a@|-m`q^X1b3&w1<~mMm{T~L))@ktEYp&cIXO5WoPi<-YV|BF+pu>xz-)4Ga>AZ8 zR`%Qp#y7xk;03(+>J_5@Am%hb+I9XVvVsrEtH1cZ$Wfp)Iyv7Xb`Wr!_TQ!p<=?v=@mbliWJ)f^`R;zw}z(l@u(A zz5L?EQ7hRvSPe4ER>tqr8jhA#UNr)V_>ov<%W>8e^QRHGM>hkfK{CL#68`747g(V{ z=g)ygfEQSWg|YALhQ3BNr{qhy!{`F&hpB<-0CjI3)CTZyu=_p5xCRH;g2CFgdpCKo ztO0C^9RLBM2vScjGq|tO@wQZ;3c&ezD1EE{kqx6^iC_)W;(Z2j|D)3X8H^##5$?FP z7v<#}`_<0OBEb|4?K&%+qb6I02q+A3eSJ_t$ux;@kEoeVZ$C z|L?v4&j-W{#N*ljX;Xtf`hR-e|Np1|8y$>EA=M&<{l5nf9>jJ>?nPLHQVh%uARw~? z+XPhO;-n6sH{9N^SpYs4!MVK%qz>P#c}^z?YSrgwk~O$M=s+idXAY_;V5wL_Yz zuGk=rXMQWgh@sCHk81!>J48>v@|nSbfd3FHxi!W&DD>%6)wSRL-5dyB4I( zzMG18tdFN=!g;oU4qa9r9_1ZC>`h%=);XO(*V`RR@IFzg?8&mL@3ehZTH@DnNn=j> zscql|iwX*koj8H?q9tBn-9{LRL0SMTF>jW_Z;?_^^rH_TO~3Gzq-1IJEJ7@Fq^HV+ z76wT|aXTCkHDHn9QHK#=&!6)cAA8noo!)G)X&{RuB9hO>)&t5zCj!O=_YQO1QAQ)= zJ`Bb-(8y#R4k}%gd#+cV#YVYjgMqg@uKInH?3t zjrGhY)lMsLMRK7Hrmam_Ts-C@!591}dUKJZ;o0fI;b9SzPdnV4;Qyq%ajkO=M@Yem z12L54=uzWOL3;s75k7yF9WpHAE*$vfCt0!60=SGuN+FZCcQ4}zQ~!4QJE74h1rz#Jg!F@>Ri09f8r zaS}YVBB2x6>*8V(y`titJo!G@1m7?4A$Hd~lRR2n?Cqy3l+$o`ehiV4wV}}P0}FuG`Jw%g_RA{=z}Z_csk#NS}r*SsZgF+a8eZ2_ZL z!OAyQ+GdRg25HyvRyY=Mpq61K$!89OjBrJ`PEiu9Gd(Fi63cfRZyc73>fH_k7Ha9` z%a^eexc#B5c>JyxC0Yp(q2O?S2TYDCm{x}4z$f}3819GQnZC3 zGa=y<#y%OW7noz+Y1o z9HL59htjg$hk#3Wf_TWEe>rADmF27_!d(VGvcy%}-sa|y^DqteXne_b_?JrSsN$1J zY+Z_uXr=jmSAn}I?76OWioQ^)vxF%OjMKL3C-E{xM%D3b+amnvv|sEloyCx06KzpRe9V#%K1Uc1w;%|pr>~`Y460eam$FVgw z9VRxMpUqs{C1HatnZVu8$oIa(iq}thxq%xQLQ93>&OApQOWIo>hqQmR)W* z81zUJR4DStaKG0L?e@~39JuJ2LID!iPuS^qjZmpce9|=04rF9z2!wuukp$E`T41B z<7csKdWtVg9*%DRd(H_3 zg$1Pi|DOH-pZ=e5`2TK9Rvvw}WSC?ju49xzneszjUji~v6r3`vA6}@InCPxMsF+H_%KEP~SKY#MPN~ZQ9(xwQ zIsVtJ-Eqx1)U6WO(SCtGgwX*1c;vomy~M=NOF94h8YA{Sg`>B2bX(zi!5i{k&>`>Z zZjdzMnH%TKJj4Dr7g1#N>1~(D`!()Q^FfMFFrYYOSHx}>*rRt%6n%{?4vjio8xzUE zwBu?S5pTrGX(6m~i|%51^^e)$Z3(tBt>&){2Swf&)R&hO+9+j+l(!eme)#r*iQV3i zSd%}vhT7;7k9vJ}>?nSF<3?fe`Dz8q$VO&fs>mnJzm;*p6JhS_H_ukQ2qk{Pq{99C zm4t}flZU5I@SY2#r(F5G;muLeV&m46##7sqZC+cH)}UZcrW_D+5`29g`AR=gnlw!# z^C_@~6hCG~ojo-i=B5_=gU|o_qtx0|0mEM2_qtQURQvvZw)JGz>fnp6-k#@4s~5fO zqnlok)|2orG2f%f%aZ)2Eh~dDpQ&n%L-vcFMo~>s(e@=(KqR@?pJu7CV3g`){_!H( zcAfF=^yS<)soy!!);WYjk5Dufzqv(h#Xo#z^@rjNrAx+~W8YoaA>jTw<^bx7qZAk9 z&T35epke}S#^6p&phpAdH=9eMR2}v__tvVKP7Qvw^1n~FWwmn?gv4EkmtnH}%0)jXO$n`dzI<|=xlxcp~2o;%nkF^|y~v_7oocn@Ku9>c`xrfl{h&JarL_D)=v&kLl?*e#mcg zfoTNkQTuG%*p0hqcU`FQfE9}?J z7K%D~t@pRk-Iyn`k=BoEkxqm8F}I60`Zqka!pEjLLzi56F1ti-h}M=36iq&Rc4Ukh zi5AEZCApTMK5mqP_G)e?RW!ZSs^;ZBlf!+T9P6SfW&Y5TS^P6st@A23W&EW*3V5Cl z1yHM5HVCih|6VBAk^hBadHr`l)%Sm29z&{9MG@eboQSkwKsCEhO%u4pa|d z?$@dTpw7&G+TS5^llZ=kHZ%PGK)bJtj9#yGc<7dZFd?HPYfH<5`TdFeU$M!ocnA5h z{oOI@MYJ~O6&}6nWmcY53H?nYlZ0PK)NMJ@`T3)#QrDKH(W8YlGKue=C+AOcof=d5 z*ikt&^xluVG`W;R?-ANIX!(&HC<;1tifoJT&of)t(2Ex(usO?no)N0;`2KjNL1H_+ zm-C*bP<1Lt#uq#}YeVndJ6y1Lb1wljD5^baZIr`YeQ!kdCs?|ZPiOk@k5<{)VagP{1r$I#d4X)z*&x2^3ibWmC@+sj$#J20d{Qi#o=$J_r zy=i5y*R!z^PI5;IORV#I#0u*N8y5S&c)j)9xDgc}KXTAPXv#6C8jJq#wNq%Fb;!1t zOeddFNNv_d-zn|88)+SzIm_OC*r417dscHxOPh5rm^etwsEng|beacQ6@XjZCZEul zpm1hknWy{kgD^f)Z1g7v3-g%|3B^aY+)Rndt)ko(r=$E}q5OV5)6^03POvk;h1Jy~ zDf~oi?6DP+pNRJ8;w|i=DplF>lbzOTu+&GWQuNeJdAKnkzo(}sRQmbXsC%nSaLW#0 zN(r*(;KAemNtv1asPBl5a#Y&=PSuQe=B+7+jds+(;DJd9>A*BUwM%sEwT-Y+FG`zn zjm1liNV#=@Lr z-9N@u-P=2*(PiBfy6csncGK;xya)DPPX6cqu1%-6UC4g)u#$Y0MSaT|js4#?Nc(jr zbhsNo8dk<_^ms7646a?<-idl1Hkrfo8t4k0?93sN8;IGa2n%C)c05PFnDiiOV=>|N zlLHaQQ_a7W#GPC9L&afcVG%Fw``q_19o-WYbo=)^gOG)F4Axvcs0z>w!+P5`i~lc# z2`grJX68HOSWlk^H^6Ki%|G_qu6W?OWd0Lo~TAd^{Sxp$XB!@quHA!S@?mK`^ zLRN0>RG4;spZ_~B7SsQj%8b^ z(`ufV(@b5!K~Xr7W1P%%4b~%wdBh^_IRP&_$fCC`h_3glOf-I+y#9Ah-8e$Y;q2hh zo)ru=1Z6d);ETU1X|MTjBI{Go9n`RHv3M)IEbS<1&dRE#nPnRzB&o~gyl-DP77e^_ z)J$i-=i8o#s^#gq0_HieoVPaHMBt+=-PxIVHiYm&vwxpTywIsETOqAHdHArRTpuk; z@F$YD{k;Mp5$D9p$Cpx;i(&-z?%BWj-l!Il9V){L*DMbFfG}liWyQjJ>t7lMhFFNQ z_B~=`RfZqy|6Tq84Sit^L&4`-hu?3rnHPKH^~8LuU_+hSz}VT^o-*^0@D~oZ!Xb0{ zu66hhRzj6X#}q%Va;G$Pyr0)d-J`qtTo~=@$7;?~ z6;A(p71NXH6~`=4}qd&=Ga54N3)IAiagY;ycS z{>@*5lW02JWbt?GnGOr{O2+73hAaV!h6Kb^<{XWsuL_NcvF#QjKnon$ab`vtt8EC+v{%1h3zS{0NrG}_| zdn-@EJO^=CEWZfHFaqy%0ZNbxrU_2bq$@OFvEyl|8*XT^5xW{{Gm^j z)f6DjVUUu7V~n+lu}F`C>GfEqv zqD%8V{Yp>x&eH+kiAK-j&)F02U%shQmLstjE*A~(OA+7bx0dS?TP~JfbNa1dOi<8~ zs)Q#zI>NGxjg9E?3)q?MftiOvJD{lYkn>hLkN?KYzo=A)ZEWXawBR)#`%>SsxWhl= z)qDCI##`yq;tx!$_1?wme5>*On-$L93UzDVZ!5FIG~eRy9a6Beswb<&$F=|3s91PH zBqN)FYfS3+g%>h8UeYUSu;8b|_3BL&VW7wH2DXNa_4IuWo0mAkm`2_^=XMO2WC(UV zpp1(OP-Pugd1t12+dZO(=D*)~`Q8ypby+@nc*45D_W1vc7m!CzJtYt)8pHO5D<;yf zYp(i%0u7Y1^4q)fZ)DtY>V=Lek|>9f)@*;2m!`h(vqJNduFnRfJozx^mAm}=5B?af zGnOUFYYK|uWSgl@os`o~mmJ>h+gtN&OQXC}v`R!#7E&sG2xwxk*5jk2H2388-SZzT zK!Y#x<5?0&TeNnGv%8AZdNw0?D`8lo%QEGfBm#keDg+Jm|g#2;(At+?M0?}nx3Tz&hQ)P ze8{$Hp0`Y{yKr6(vOlzVQPCxMD&>wH3WhB7$;1iLIAjf+H=@tS>{toG33Ut2B^U=# zsM*DDGfw!IsKAUZHpd8Wdt7*uONhBQ@AYY)O8(cL(JohSZoaemu>0c6@^@vPOM!*< z{I=(xe^La?#u|6HGE((e57!VAAY6dB1ch{!f>ym&RdS+B%-C_}}!C!DS&+H8A9zpqaz zZ{Oe9+qRO?mj$qq_foWq>HkjbqZlOO)Kwf*vb@G{IKTta3b^&jfq{=<(dUoBcsGXz zCkA?YG@PMFWp9+3PSn)s=#TALJjF0RA_#h&IZ_eiM`V*9x0>j9Mq=xD>0?fno%qy! z^-1{uTbNmgDk4t{If9`K4tE;Ku|7Z<9JZ&aEc^ri2sm+m4Z~dWQYS=fVG2y z2F0ZQu)l)zoS~B=&l-Marg{tAxo?Z86lW+7w2jjGw3hrbT_8~(&VPO~qsG!}t~{o% zVSKb*Z`*^_jJ}z#(Nmc>I~%rln#SENj~mHe>gdBN-+Qe)*s##|ckplatpzze6Vnn_ zeZjFy8%Y~AK>;6mGkNY)&zk9MnwXRlaBEW9i1gA?lWQ&UW|}zZptpG}tZbZ{X2(a- zsFWss`xiKXm&N$D=#<#n+_0cLT% zCmKAhx;Yor`ts9Vsu{*+f9CfswQca(4p-V-{+W8~pZ<$6XI-Z-^)W0)%iC>GI+Q;Di0I7Fn$d2D zJsc!nO`D%v?H3x_`x!@n-I?6^d_ekGv00gryudluLp#w1;x_qxmN+wKWCYGTNJ2QI z#~c1J;tZ{+vu@0Auj6#Ya-1TBE}xedOR#K-W1F}$OKu-!pztPQr?gUj-<(fbQPO8e za`G$s%BQKk|BH*wDYIzTYC`VauTS)hFBoaJ+v843F!T=nr*X|F zn_=%>t6lxi$}N?S-#wA8zwwOvwH04|XYN$)$B(sv++9cMQ`mjcC$Fl`vQLhhDv>JpNHSqx;hSCnX{RCwrzg zt^Ov^;i|^v=&`kujQcj9%h=L3J4wpPd6jn@>KO0W8KswOsIh&=ls+sakyzT?MBdog z9=130UPL{Wng2hV_6m!N;@G$s(C`S@R$NSmTbsbn#r+AAu)jivloL`Or<^G`O9bhe zoRYXUkKvf`pf_L6Ie$DN`}uxQl7VTmwa`$UpxfV4qwG|7;g2&~-CcUasxt@5#bg&< z#Mt(+R^^F$kA037jUKNQJ;JkWEEOM8Ry=!GYcL|;Ze=R({Q%`px$zQ437=Ml(rCTe z>M~>Z!O-_fT4B>&TID9*a&w-YLu({b*%6xZ>7fNF+0yW2kBzs{(i|Du%*t{JS_Nu~ zeVTs)=iksSURmXjHz+?Gd1$@)mNz+gBPz`}C}}yBx0`E0ihq*3Gp;?ht1R*fQ||SR z6MAl?kp&IaC#It(3Y%5B?{l89T3cDZBW3XOvuNIx*jIg$y4hCdq`b!rS|x|2eQQHS zMbe*aoMn|gW*&6jsK`!XJoHia!CNM*tZVl}nsP+qJ4;D*-Ip%i(F}H<^_nQnxvo{S zyO?XeFSaqlC+ki^-$p|~?}Gh3J*CjKJooe{_x|%>tQ~X$8TmScjQNCJu@FRAKmEwLb(vlWkY*8I5yNnn<3GKwou1}Yh z*q6oAo^yI}73BAT_9M<&gIbiX$-Nid^021DkRv9xCtqDY zIX|%_iaL8t)1xt)DnUSd<847KbvD}?qx8*&!H6q{Hy;`p8I>a<_ODI59y(+wV=jN4fm)Z4&TgLd8kL+D8*x@VD zn477ySw5&X@}Twp{RbHqTC&jrt@OEN)`mH0c&Xj1&Q4up#;$`}?2l>H zVM&3A!2#bD!=K?z_5*@#BPk09`n=?i(BbG#k^~lEMPn1{afN#ULBsy1>z;_6pPwZ0 z=?X_ICupn5-Fp7Y*Xy%giZAJ{AJk*Ck%14G<%eMaRE47&|_t?=Rvd+zi3LI| z`Pz{;wb7!4A3b}ZreUIfy^G(-;B?2x^YwFwJJs$OIgw<#WLva+;gIZiABi&3T?bjp478dqPU90%e@J4mN zfMMC@?)+Zwo_nq1?5_QCRrb@`$B8nSDfCUOO~5e)F+(vuP2Zn^ixVmKu7NqRfg{?| z<+EoaEb3wg_`#pF4O3w+8S|u^MAx zZNGKKtkPBQOYdEmrz?kQ1NPoMh!T)nB;j1&bFQ3Q?@I5bh7H^?y}*zfM(U2&(tZ-H z_h)RlM=jsh!$a$5e+!dggyTYB@IXITEBRQ)YGuHuAODJq2C#UK`6fD?S^w5Im(e>! z3JKaqnqXS}F%__z2VZVm>l4zuEiO&{+{Hj3W9tf|39RY8k2{le0z(3ca#=Kwhl?OXL`FXop7-CzgOEpx1Gm&p~g zzufoEoz0%{imxa2k|V=l<;BYu&ik9xVxGpvwtAZMly0+nQl_*t<5kQsT{dlEjaK%u zHV##}1d@hmlkr*?Zis^V)@Ng<$xFrU8)07)PQ3chS%_jJQnBs(cWty8^rdwz)dcpb zmCF4x@=mmy_>jJO7rX$Ja(Hbk`0r}FzA>$d0{sNLF|uX(^JSSNodvX^YcnY@0<+ooo0yOMWd zatMc*z%uQc#g!*|p491IZwW;7d`h%XRBAoYM;eRa=HlO|yZe?jzT~#V`s(#Hmt|$E zyXFSh%e@&>mAG5k+4;D3rT)gP`BDBU2pZzmxz;SWhxnZrnDKvCqwVA#2U;x9xt*w< z>szk&i_FlRyYJHfVQr^QJNQ-a)O-PhKmju-yjL-Olz*%z|h&p8iZDY*dz3=<%twWFuYWu4jPqimFO^&6D}K@eiBr&D-xs?mzGA()}hPe_K+R zeV1mM1#7eB`m-xXNUL7OwDvXJ2c=p|{vWE|JRHlm`yRifQc5VKghHew$xw)r$kaq; zQJFH&WUeSGNit7Krc9Yhh7uBzIkPB{slhD#)}{CJec#{x$8+>_9NqUdoaa9GUVH7e ztZHX|Xv08#<;{2FGfZW_i>MkG5JU+9zTnO&i!WDr)z8Ubo@;zl_9Da%^UT@>H(whP zbJzZJTW8u6^L#7geakc_MZ6Bi$!*3t*_+&w*l^bDw`aeLCHLpW24;_f^Mb?ugWDgt z4LVA1&{CA+vgxi0=sl>^_1Z$-zS8dc{kJ_uZGU{IWoq^v0 z6-p=1SFY|`wST!iDNcN4uu}TiOS!nWvt-!+ZFjnr<#k2HMTe{Ub6j_*XIJ(twKkn7 z_&gnXd2U2G?43V*dV{-17t?9`=|jx}lo}a{)+?bttxDa+D88NS-@3Z;ol-OFgth$u$_O0@J2n$v8rS?= z{&0cm`U)}Xg@8;`fp5J2GC~JFZ`7Re{U+k1B5yMlveKPDI`>dnZ$y5Gg{}Da?Xt3B z$&>=tu<*r`Uw-{m)^_^N)|Z!{nQq*@=5~BgUsvHTf5tC=%k~EqUKw4uC+hgbqiFE= zp|-t}VH4&BUjt^AV#n$a>Wz2)ZR0Q4c)_p1;=tciT7}%!OUr+{J~+9ZDD^Yj7T;#s zY46sP__~`lc0Kp{H1@Cj@}38dvE_|OIeqoWOFy4({CZ8iil~K)@u|*39uuCAoc@;d zu&gi^-=iGt>&xY|s!pVoTC~K2BAntf@{EmBhTfensZ@}8Cu#@+{boD)^XKX4{rDDa z9+P}nBA@#uaOxOJ2^oL|gGVhfA4?8Ij`!)Nt8EKZ-S1%ivO;w9*h37QaRj~xM|)<{ zGD`#Vi6>>y^5Dy_Sh@bZdE|j?JT|TB{=B7POhQdeSdyqLli$S4gS{0HCIe*LyjdFs5w$*0md%_Dhxp~C*eSN)TaUL{KE3Re< zY_1TXm3$i_|9@NnL2_2ecC!>yflI<+ zerJZb=DwFXiyz6?XovDrt!bVD*H*x`EU$YA%vM1S#77zhA(d?f;{i3gMhwTeFFHw3 z5NseJO(cX~=6FUG)#d)4 zy~XVXZa1s5(}IFnAFJGcQ*P5u$@g=Dk)2QC=R*GfYl4(LIkxdJPjUnM@*`iUlh8n4 ztu7Cw&VHyS_#7|i?SU8*Mr;C?Y#Ajr=%>bUzZylNcqKn~)Nj-SrBNXfBzwbkwTbf0 z@d<)Fv3o8gRI#t8I12 z(YN4~?b^s)SMCn+u6{Lhzd^d>;FBRY721_1mHj$woXY-BUZNd_Hi5mZtswJeFm98l z0Y7AA1+IL#B5Fuk{&W>--8`jRas`XiyyD!&vF}Op^MX$2OEU)iYb^gd39MUl6E7>B zn`{gd#HnnJbRPa6M-(u{Qc@i8z=0_vj9*15@TlK988ALE)d*eOul@bInK1Bo|Jt={ zceP$-J$>rs`*&%{Ld268rd`cR4pxYot$ts*$(4MK05!YV=%&jf!^&CzKUC;qiYibt zNZ&Kv_wj{j`MNbHv0N~a+L>o&Rdz*9O-)yqmHs%o?;>tnh{AQNUmYDu@}_~KV9c}(hR=Qpe;=kdL6!C2t&LQRQ{IFp9|d=9XY6}sRuaCdohyC zNbQpzOHEj=%J&4Mh>Mtc9fa~(^}Bc7-}><_kV`s~&~#U9FZuh-r;o;eJCVSjqtlf! zuAIg5pVBPsiyjm*P;j3}QT_ct>9J(x1k{f)Fa=!=@EXs`xStfM&Bj=w--8Fajem%8 zeR4sRb3Vh=g`D3|HFt)B;hq6E-P3z|2Q=R(*?Jq4zdso%tX5q!)QtzwB@XoowN!H2 zoK>!^y&WS?-+|S|&=`@#4PvIL#jta+WI`@D?geU|*eP$WJ>EM6F0QsSif3Idwi|y7 zkXaDVco?J{+yAZ%bl))yb)&8QzAWmf%~iCZ1^gLE{13!tG@8&mfjQ#9B>91a&riCT zt;7TkxmTPS0R8nfsGtk!E*J5tPFZ*8+0Iio>C4eRmLDHHns}y3IktDto-dHE*z@em z;20ibeWWNU2x*F8KP(n1*AIEIA@;Ody*%DWr-Nrjk184!Iri;H9~yf9`PW0U!RVv~ z@!yA_hyi6p$OXMC+q`L$qP%>#n8S~rI*fxT?hnR1|2-KFh@n!=I}_Grt4}hyAW3Jj z@fVBCJF!m>{I=}r8VKjWl?qEi2J6SjWhDcbOwW0C`FZW)_-pI-nb3J-H@rd zwo~lm&~5W{wa7=0^t(W%!eKl9H}9p{(I39hywtS(kT^yjKLdRP9?plCOp(y$?L+?`B!Pp+q~#Gpda$5L5h9< z$B9kZNy?FTf>%Ai*)B1v)3`l4ewr-SuCThc6JKi=kr6E(cz`zarP%y%tB~1q>yD-S zh5q8j5w!F8#B7d8= zs{phOFlmShnO8fE|77TuEkkJf*U5Ytj-tq=J>+}T7eYaHz4Qu`=F}I~V{#unhsAr- zCx+FWTJ+9ePTn6Guc7vBs5d!Z;)tL7p$>oF2eN~hfp^FFWS*9?3`ZbIU_W>eJoswM zb884%DsufZSE8Xh$DTMxJG)(Zg8zl7kf=krg&=RCCz_mYA<9bwW6-M}opxC^79yEZ zXc6Kc$S}Eo4qnOZNaK0-G!hcG2-kpcTysqOc-SAt=4S^=XY>i!?Q#OEAFGngB(~nK z#1}$U08^4P9t?!@zSVcN&yj@czFNNha@WWC{%_w$h5>HqurG;c-#~z&ztS#;pY)Q` zPzk-EqmuY3&6pWdnR_vwD#f;Imy!&=5{&%)!3wUHW$#y}|M(}iUtT=EGJgDjJ1IRe zprzAxuuA^L^*=B`6))40oWEHr?UdObj_~IG`;W@s?+I48E1!x9MsDQ@gMXYCuY(SH zyrH(!GP$T|N_Q6r=K9;|3`=+BXuQ24syY+S=&JbNRVl&z`gJ~ zwdK2aK7Mh@U}<4`wZpAqgJ|7;4h?;9?}`4#Hv6~-zEE@GhIsujfw2qdN7Dt~pOKSq zn1;d)DaeiyQEMBUtPvTC^0WV<0S?+P!H2r~YA^gb^yf)coNT@sU(%sjy2dp9D%qgh zv3t0=(bL%MvLDJkRYBxxA-axgrmjqHw_rW!FT+4jf4J^_Y0kayZJ>W8TueDQL`85? zwt?g2bz$iLj{nJwfCrQ#uE{UnxDDL0IU6?U^(Lxu!INh?D$q?wriMPPo@di6Cu%y3 z@07p6Ja@p3BUSvXtR1hr@2=*>6ec(9Yi-Go@ZI+oo!~E_)Q}(V_Y51z$bYk$LSJST zp^dNb5)Ad#`A=7FBvHq~CjE+@PgY`O6vLO{Nq!EFk0$A+LgT3d*0LPWoPu?<-(yPNhq3#NybK83j438&Ylay&oJPt$bJD5W(EI`nb+GxrUGOGV%um zCdw*k$nBv=CY68eoUV>pvZ;W&u(ixrUdCKA*U+YrV;e7@v-e~BZjd=&Q4#?WKllh? zK!4@-YAcdpqv6gGROH%_%noZlrVtZ$;OiZBNf&n@7Q$XxlzU$>h zXe(_eWLJw70o$I-Ll6Ha%Ww|=o6bcr_>!&R@c^ceGnycKAom8gYs) z-;{kjlTPD2{*JG9OI{5%*~jld-%<8i7s*JX$vPu2ym#XsC28Mt%JHxATf5`7`z&S+ zSLP?6bcJrmJd{{W^TY%M1cZd3inCHGrH>dn)sPKM9=1gLGqzC5(Wq>Z^( z!}tp`?_rb$8?r5Al9~+-3{=(BW>_!m50?2lGExL952zw77Ji3lJ!X24N&21P2&{`a zzId`86a|7Xm;Y}z(7xDOBVW2D)%ZgUwUO`pRgnx#jpEkArADDn(Ao+iZWu?s0;9LI zQWmEMs0s68c9_V=DC3OtPU7W})vLRRt6Psm>|s!SQAZjD=O-wZK$U-4E~%Lw#1Gq| zD8mj+fdjMY?JdR369_y9815|=+DS{Vi8YMpC3AIsp;vD-1#9ybKbp)N5+g~xP-oyp z+yz73#H7CgbFRk_!!W)GS!l2Tp+E{74g^vX3aYf(C1sAQGWoFH*?e`-WRaz`&WBzx zsrlDQkqQBjM4(<~+n0jmvaU`kSiu2ALP+s0nnYo0d>#r(8;d1ZSB?m))}K(rPRd}h zjHH6s0aH#otUQsDZ~T1gjGz^0{fT>)_4U{kZJPg=AVZA53HdHgC-r!j8F52&PweKtra!@{1XDzB@mb3 z({Tj zd3p4KCwAk-%R)6CljmNGYuB!QjT#O|ER++^r>J7El?K`n;0=s76Xm|Q$<%u6+MM8a z*-{8xz!73An4O!}ukCOTfn<$gEyPKk&?#EfxDGRl^d} zz@%GIZSQK|y6^IPZz2TlHaRM5igtkv#|4abV)7Q#_yV(2zklN>!z8@742O;VyXv*X zDmQ?(Gr{qGOJH~Rom~QM;hW-5_kFlikw!7_XYx$Dv(Yi}QVHTSCb-s2aM{^E*4JfoZc zDh7HD-OV{vRa52a>vtx;5tqe!%+|Y)r@OHchxUcI^M!Ev`Fow{r@u+Q5RZ&R{^rFS zx=R3B{Pm_BnyPb(uWB=bb_d6L(Pm$XIS{j{WFCvm>3aXw*0&==a48911DkD4yH4K5zb= zPt2BdhsjwyM3+nIlP(;TA9R>YF!|_rCgCEDR2r&YU(3D*;FJidPa{HNgm+l{Z9sET z`t@nHixkGs*XJFZjLPcLUo!jR-_v(pOE{!dF(#JVeUI9YaXyY`81e!&9H-^%)D#`i z7+ul~%x4o$VO=&Vg6;5oQbEJ`hIlI2dxosT?Kz(xWpOM&O?n_*bk@A#WIS5u9 z)f#fscbDlTOw~Krw1Ty`2@vt2-g!2s$D+&^vRH z`!df^+pVRdqFvyHcxTYy(GWwJikVB1=pRwYgQ_Vnotr~TG9@Q}?q|xV|9Jg=z)gRC z?i$@LB5c%J$Fm%jIr>TK`17~AX4Qot5}~H2+Olik!Gn1kd@^6Ze96L)IJ7|IGF#}$sE%A`>|n%z)K~T=mySd)KW@10-{zRUPIJbjJ@jfpe*RYMA}H_dsCQZjf56 zo(uGtpF`={(A!KdL@#lC?Jwk^V;Ni=P+h@zHVzQ-A%S+6kumYMLogsw)^>h7$HJhV zl$nHfx!&;TXtDiBQ&NnJ!ajyhn`PqX`_GbtTn*q)}jZO4x51u0}aEia*SR4sN;-+Dnw zNl8ILp^w8B4;Kdj5&=MttOs8ZD$BwFK2jnh(S9&IK#>kJsq5{2l;wl}RvFLj8ZlXJ z^HvR0t-69kAw7E6lEQu6bhFCe?>pjluZIVE-w<4c5Pgxy(gKcNKNG}sRQae=E1NiQ z2}JzqyIO;Nk59|s>5;lzLG^N!P&=dz6JBVafpq9no!$5sOcKmJp#_}Izb2P178qnFP%5T6-VS1FZSc=2}0)e>5@9?2k$bH^%$lIGYc%a9{=eL zkUg1My$9V9y`kT7x2k>Bt7`;Fj4e?&Y5Gw8)rI^UV|IUUWxZ%zr8#!ER9Oc+y1H7( zNs8qT9jeWx+V7xq&g#Y_=V2|eWGnx%xS#R`0lDAf&e0S7B4ifazXe$3|HFs&JR_Wb zrG}4>YmMstE}Al_*0%~QEA~C2#nKwmZC4e+bcDX1+7aryWAmE@_?~|zA5lO+h~=N{ zNy5jz+smp<2L6LZGGl%nZL$7ddkk#obLt}%QJh41|LVOwT7S?E*(C>M)IycFv-n@$ zN_V@<>VIhdlu{3li-t3fc_)t1Z{kH<0@MFgf{44LR?rG%yPaKG+=QTzv$lRE4cF3w;qJLmFjbkr|Hy{mA6iIv{xy)H@s zbt5k6dt`6v=Unpt(kcDc3Q0w|A3iJ6drCqv$x@C>pO6pA|h0sj81 z)~Uz}|Bt%p=Jq;076m66zNdDS)|Dtq@^fs@^7REbw2N{j_?#a3>Fa9v%?mKa(bZLa zPbCI^2YCgAejpzOp_}a`pv`$(_Pn#OF=Y z)EIi{^fL0NAg=_TCWyP)*}rE7F)NdrmZk&m80cSvpuU*&8T3$cY#{6quAh*Q>1$=d z4hyC!;T0L(ea8REYq|r|kH9i2EnSAfDMkd;QiFYAUkGo%DOeL8+1%_z1^p@-77J?8S-kY~ZTge3ONP`6YfHXra%*}CNK^6=vg0!H_(@L+rdUAFB2>fWlNQv%Y-Lflw;k&nl ziXT1lHcmDst<^ZHDaz`{7rhVvOVEWUL^#$Uaq8hdO!UI)p$>-b3GO>e;;zXWa2A?#1Zsk>DQjw7K8tJ zx*T|!M&BgMl> zt|f!}4)=GD;Av-{rhtRtA|$-wf!rN^aqasCGy%?{EURKFilv$QgCytsZiy~ad)`=Q0w zppW+2IaOZBm!mN-$pJUKVRnPrz*^F?5@>w!`F(D14Ex8een5>c6W5GpY+oonaU=D0 zW}%TzWaEt1GeukPcjj3hy6G!pxrwDEqLnlM%lF0DAvO_?{rMbZaFASghrJuU5@q?Y z51yxfOIK79e}*t!BSR6$Cp9W<+L3KKqMkNdeQ|jc`x>o}w@v<_aVP1~I?Vo1vn|im zEd)FjSA|Rqjlq4vAFxiUs;j%K9m&ON9Sa7lgkAj^8Dy(N-eOb1vzKTR51kz;rfI9c zp&QzzgqF-DU8Cg|RO9zX1S=W*f;3=6458xS=xFzE9~hU%pr{E|VW6515ea3*$p{*+ zeZe1KYV$MJ?{}6A@`@j2J?lI4#LY%QuhpbiH}MJOm!o(UU2ZYnU(0kK%KAse#fwu?{G?bI7@jP{;?2i zd-d}%#gO!f9m|b}ACB&!^|M~u^?m+J+L?XugqdHM6Ggzr)ZpKK;2D6>K|t>OvICu< zovV*hqoDU0Ni{ll_2*KxpRWT$-A21Qm7S+bSQ%8fM53a{@lV{QTh-n26=fjtgINa| zv}#G)5KYZ_h{Y;$1+?VA{R4u)WcF7P0QL9X&miuIB$HeM9(V4guJ?cQ!z2Epip%p; z4Zo;%+=0`WjKL>6xtWP5I;O)NRwGXBySV3%@wrJ~#eA9D(lq9j=GTOgASE34V4pZX z1Ex4F*)Z|Ckd~O>w7nXy{K}pA;!S?Z*>6nlAM5A_Py&4(U*9WXxL^=kmYo3#gQs4m zIt9Tjpac5t*ChqGgHm81+5hG?lzCQ10YJ9D@+v1-VJ|uE&}IFQyku*s2&=FJos!pk zYn^in;m^{){Rt!$5ANFsye+lt>67bx?^TXk>Qv?*sqhg=2yy~4Ssf3>qsUJi&HB|mcz zOhPPOoHB@#cW3NJzTl}90AiDfWZE)oXAgn)Gjyg@~ z;8D{nM~ex=)k9KcwL&O%DtQ|xS1(Y9rYF@w%k6v`=V6wiu1=!YQyypcF;rDnCL|^< z%+GgtWD`XGT`~aW{`eH3cxcC5Z0b&>Biv$}g|lZ~kvTZ~8@}S~?8m-VC;LJogLB-T#jZz_D6MT=Ni(r z5$7$A$`OP(S-c1==HW6Nq@gyt#X!is#Npn7lwpCsYnGhX z?5B^v80qMidQ7X{$3bM{q-ys}bhK2>j*}vUgyrhH<^C_Ebc7xtE!tMWdcr>*v;|NX z1s{p}+vC~frrWB&FpwML`)tjwAWpV7CxRNXC+DISXlZFt=h3pwub;Ylzj6TQankeW zKTAFrKm!{fC4vZSF5DZKckbK?({Gp1OXNay-la1l;I8%pR}`KuBO`r3h77KE%Rcn< zl;q?zSGx7AKeCo!zOZ_6TX1Up4}^2ybPDub5qm8Z$@MgLKOa&5?Kv&nUN3xbh|JK!bT9nWLh0Dj4JHHm$?|6HEHoZLScP@(@#qH>jcM7~ZyK%#Y{sK>P zOG_wIK^qA>J3s6&`9`}#fp0}8L~PqW&2)f1aCJDkz3X^OG%I)oa|0onjPOmdIC2TW zm6F`IXGEXYInXt}<@vmw1bAFlL?!lk&rce%MgDn($Pl16yu*4vO+N{VM%0ct|0D|* z)PQaw$LqpYVfcgE`AXq}K7AV+Q89CGdrgJb6rP^@fqU@6w1U_+r5ZyKXNVyNS~ld6 zm5>)z{C`*-8BX6>+D<;&$$JCP%^t?3rK?`Aa^eAL?%8uCxfUvR)hhz8)EX!W=iRGM zR0mJARP$Qv=J0|)<+{7j%|lHQoci^i+4O#ghG|Q)N1^-d)2>Nx2%`IK!W{`Qv$V7^ zSOLnwIRY*-LMD|BHr+ADUFUv5lNgS7u(sJv2c+((=jGQYMhq#S?y#Q||xDfiCNl}dvce2DZVL{)` z!9ocAZ4E3dlbVsC@T#UG<9MLSiSVv6&1=buXiH=>k7P4ncXBG|Fn6@Iz1ksXog??3 zVQ5TlnOa(MV~bW^wIPEHjc*QVwQ%If{G}vMXwpNHA2d>Y0KCG35zki=T>Q{FNRYE1aWRTjAToVGX+|;e!?`u^RnF^WBNb3i@XH4>0_Rxc|0Q>kq zeZo)9aB&3sPF69~8P75n@YRyGtRkL(@)lQje)i^lc2q)U5u2sA}Sn!D+KS_wTtCm^csZ@0zzOm4%9TCUHo(gtKxEO^7cJiYqh}K?LM!uEWx8}+VSDf}k^vgB(w4nP zVK{-Txf+_jAM5KO$iS>ux@qk#h{VCN0FD(8eS1Aumf!-2HKT^=GWf&t_H1(4Dgp+c z%T%QKG(SM3tjn43vKxrZgQp&>5%7U%pA1L1#0|l|G1nqdM+=Mevq|Fa zC>@%U{7j(h=3d`<_1A7sQRD;=n8KRy8boia3rEN68-JLfG#+?nj$sj3;HGlyBCtYq zl^=IpU3#Up(s5nc-4y`H_x&z5iF_j))%doe4ZG{O3kMHRQhK_-6bl{QBjlAZUM-zm z=W^qQ1ympLK5}!XaI(4`k%Q3}lH@ywEWtRtLB7Yap&7vf&zw8%-$l0Syt3y#a9|WO zdzv|$F!+JV6&Z79c3I)MkSd48RLsTT@s{nWV2f5-dL?Ug#sk5(pOL4+l|TV9;E3e=AUl zI-{K8V)6gnb7YNq{o+mZPGwsShXNkV(v=-m5tE8y+_(;^($>q3P=}s97%KXIbnvi~ zlT7IUu(O|&LB@u{)=-m&ho?(o1DY;mdfk8W!=)emA}oi5Sorg_rK=)Ny=KL^woQ8d zofrS!y}9HlJ%ZN}L||BeaITO-(b#NIGlf@J-kaiDgKTK`pa_c1)!;*xK;H7lC^*7W zSKDAc;3M;Oa*|Xn#LgiZwK6a$DZm(WsaK?72bjj_q923sMPcFGit*$}$_TNXJ2zv! z=`7E9t$oBQ|Kv0sBi;7oXIC$spucIF-eRgK-ptf>w)I!!^^v;8e3QN#awAIGog-aY z>3J7JZ*8JZW@Jcudg}zE{7Je;?i<%;_jvR5v2W+Rx`E$(V16mMd$HR!R*~V{!|ySq zrzERmN4zwS zF=^+MZLl$@X4ld@1VA(_DEW6W{IOVw$5WtU^$Pgp@5 z7S<&w-1wNx;BFFDDZ2r;=W?;ze6%NgZ)rzjn-y<{`h~{jR~=*Ow~nbgXP&^zl9iqTkYZ;EM6vtGA@rweM{4ziQE|{H;F!;UT@3k_WgJ?-niH7p}5jxOOf@ z6^fs5X8{NFf;Ji}YMGZ=w{8{8-`0#SwAO311uE}T^ka5amFn@wk7o%OOTrO z_fs~*FVeK*;$;_#1Vq=_4E?Sro?;U1AMXc%yH#dvA6x=NVdZnUh|`-cf>|KcpH4bJ zQQFkW&`I%$n3>3UnJO%;2^DfOBc6IbPc3+N|9VBDr+eUYj-F$d zb@eBANvZ4PuY=McwjlQOy5JX?hikFb(f>uHmdxMgYRx6Tru`XD!1(HrrKIF z)gd2T@g8rso{xN4GAY->--hh|Ju|KM;+^hR8y@25uO!>FG)|*+*B zgv#zUYZ&pVsfkn_g(<@6_(p<=J_}794<)4sP(ump#dj+23agdf5LX?nnMin9>kTdW znSW5)UZrFlWahu~kZYAxTgQWmFl^%EMP|q2N4_b z*KjvU>J?;ufasrgxuo;Wn=4a8Vs1J*I=JX-*Wv>YFGM1&vIfhqUU8h9x|{Y!;#Sq9 z7DFE3^Iu@c0_#HPQg`BW$J2aA&o}xP((zw z<$JH&<6T8Z2B+by^F5~t{g=L>*P_8K;RyyQvp$?uu6w#-i%7i-92%p+dn3 z79IbK#dURcFvr6&YGG(7%zZ>|LtN4u?+-}`M03@L;{&D{?sPx}y8Y89f&kd3mvz<0 zqge8jl-t}-v;nZhQ^t2~fuNB&oP*6pT+NLn+-}{zjUyJ^7t&}CFe&XBV|4$>-*$9d zQx4#?+UOn`IHiZLnCw+{jQ&ockKKl(XUEI-o}MN6wspfBRepbzc0iA#4lRLbi*_XJ zrUtB!#!Fp6#C@U9k08ai>54-9>RVt8%ykq=ir6 za9J%JEnyGT=dozv;E<=opVVj~!FEVc&=%H1O5Ao2hQ$AhSabrNL6eirr7>;^i-+IN z5|6o9R`XyGdr}>-_I;lv_I(nC|DHrH9_dBd#3`3{%iG$0*w9yWeDx>&drZxfFGo z6mQn}?0M*Z<-G?FkX4OnDATT9X3bs(YWP7g9n=yM3th}RIc-t;JbplgMIR@RtSm~^ zT~Z#qh?rmc)m0Chrm%J>$d!9e3>F?ZDu5Hmo!=K!0|qnyBD#x^t=)v4<>t+9fA3Rk ztM+|UTv17X-n%vN#LU~g^~#n$rhcI}?+xZ&O*oTC={0A}$F}lg5Dr}Hra8E{3|=0_ zbHd~$7O%aS`@r68UUW*Kb9_=(c6}>*RHq4=3IhY#mOWy?)U%@5$UyjMn+$s|+>9s) zNWF&DLKprNSRQB2KpebbP;W{h-B#~rZtlr-MCm;(!Ww*h58t356*3-aa+V9Ym7Tz5 z@FLF}ms@B)fXg$&a+uN!RuQhQt}EX(iKj~s!A^(9Jj?|#n{d37G3BcNTQSDzwtJ_w zMI)DV2ytE&w=9M5%V{r6n_nLd&_BGmGr;$GCuL}`XqOQ2Q$e7*;^S0fhPdQ~p3}|} zyJFF@Jk?bG`(>s=28tnVRw5n`|#UW8ys+(6zO$ zbw8J-E`2RkZ2CQP`A0fU9U zMF@c3U0!|yDmb_e3NO|D<5JEr4lRRq)9Uo!5A4vgmF2}v+xg9VUIp*`>$R}m3}b1L zrIL?W$BjQ;ZKCL3vYvA$s_IU>8Ab}vwwxC8Y zz2W%!IzvwHm^0A4W@H?3adn05%;+hj1hkMKT=op&2k3HuNec)DET~EFtd?%)?%Hua zEsoZ%o>^##dDE@sd6&pjr?aho@4c9CmaEy%V5jN!>IXBwc3v(w$dP;9YV%+r|GciQ zg_{Os;0R|ImxonRB)!gj~f{NZgM+2XCJbW6;N4cclTxjD+95Dd2FNtrjb8< zLPOgtdU=thRNq9-_i5X8z?bmNg3*{;^7;T)3W=m8`WWWU%aphk!M22NnAB&jKvRGI(K`c+icN_VrO&pB znpG+O>8O3J`QvhHQEY>Ou`yU9O(QU-w)2s;0d`HgGA;jsM-G(E*AqBZ*q3F=cgXbb z9R_hLFMx-~KCXe~is9O$$Byk-ubKOE`6`Wjn3=R_RApPv?&0MOCE6HjA}#H+P$%7B z>``o6G-5gC!>? zr={^hV;QH%lJ*Y-4puTsVnrr@yNGq+&%Js#va0)a5X*;CoIJDcNY*8sD@>a@)o7Xr zTRa>-D8*Ztppv&^$H>G)3_R#MI_AHH>XH7x_?4vqG53YsQj>M;I}bPa z+h}fQ7wX^{la#;ufl6GXwO1F9Mp#BPX!f7QAdts=WeQO3>q72*nTQJSD+nJfQlvN69n}A=t_(9gp*+lQt2$g5z>(>IeHsuO7KEs!bdReH0Qt zK>EF|4(ixR`J|(ftnA0I!?#_EK?X%v6}>5L9-hU81*mxaaefWoHCSxEP|1gZ4w#Qp zMxtJ;dn9HJW%lQb2_oqlj{gdQ{5qR!mRknuY_CAN(tYkq$nwckDk{xnOPqt_ndiCJ zaPaJf*($n*9D&I>IYHEBykO1%#|?Xr6!q}xMhJ?7y3hM{Z0z+*l{-E7>y%GM75&}# z`TIf~MoF>Zfp;i!Z6%X)a0&b$K17ynyK)7fAT%RYpX#lGZf%~EklVvUkcenrt<$6j z`<4REY}uZ2aq(K*Skl#S)sE20%L1+Db^^xK=bTW`rPq)mmMxC_p~bMtfb@LZ+qVPD zf1GdJ*vrk0v~82mTf{)NfbX~jQfd8%*jDnZr*^NNF>9bn>4|b3rV^+Zs^ogjN9*}i zRE2`dM6Mq-dY%;hwl8?cM6GSE;Lp*I`dL-AZDVSZ0i2;;LQVPFnWmQJ9mH6A#X9PMkM#7l%g`LupZjtXp=qyR0 zgK(;^zdw9Dj!0(D4qSy*#kX&J={9_|Jw{j;b<4d*3MO4amO*hm zCt!82#9eIt<<>8qnO;4vzORbYRtXBaHYG0#FFVY=7#lxdyP>Z*fMUxAI|}_bsyV{V z?{~9DUWo!uWudDZ?c-AkH0SQGT+SB|O#Ym84bn-QT16jKUOf(LZWQW3euX?phz#f{ zFtryKQ(~$#^g1X{uXx{!ty4YjG&*nL)*nt=etntw<0dlgG1>LX`PVZg?gNlMdR!aw zsMG3q0xH%i?S;FulRkE*Bql^C$DUmG;CsS)F!+EA4lU{1hP`QdIVMWM!!2*vF%KoZ zuE1XGI9T5j61zfeNx*@D%!~%3mAG+KQxb!IV+W~D@15RHyfkVa+Nh-KZ11Dcj`Fy) z^}vN6jz$iB=A-UBEv6^J6dBEAZtVXpShhHp#4!t$=9hRlh_i9$HLxkVx;7E#6gU=9 zPW%%heQ`F4lHd;(z9WNYGKu;c+O>m0}-t*&DWP z<-zGlnLibV*Q*?g6aYnTh2LEp0bV1AJJ~_j`S{@*e#UZ8Cn?lj*il zFD9NSy^4x%=LkJ9T{*v7dgujh;W8YdQaw=oOp!>NdbTV9%W~XwyW#nrBpSX z?eFKdg(jbq!#&4M<{5AJTzJ!;<$dL+X6oP@_)mKo#U)z4`Ngo0TUX!sYslkM5|~cl z{IVoE|2WdZ^zykBGj;d`J{fk(?M3dAvsKk5zO?4Bc%-gP{5TrXr|&b-ziTc{7Dw4kge9HW;P0f`Doft;{R-esDQz69X?f6$)`rp8 z?+lkLB3?%-6sn~CYLa-kZFXW3CY9w#NbtE^Z+Ia112Pk2Dd@i}$>N{{fN$FP=dM_n zNt0|9EUt8^DK*B1+Kw>(Qpgzz5hY>=qabr^YDv$Cwh-#YnlU}9pqZ)K@ZXr~3k1UA#B zedRhL(k8FtfB5*TS{Q`z66F!f_kXh5*H>--9=@c0XBQzYQP-<$YG`~#P@f2{Z8LUY zml;R*>R#tt1HpN>W&C_f@F%RMxqf3;H&}h*o}qV#d*a1JWBb5zjM1Y3S zX8}GN|KH>2nh=i!z0Tr#8EJwjYjxVzv81fG<#_t;7q`2mu97t%f*z5)jv0Uj6^nJ& zygu6(qlb5_&>mQF{$d%u{Uh6a zW{JCU7GOQ-qwUyo*A9Il5C)VC;;T=p1Z~cX$~dy_CG%*}Zf}AN@;kpzDf+XFAeT$0 zAhz>ISMCxzoA>2YdPnZr@Q?0~M*yr4FZ1#eE@OfJo_FI^!MzsV_+tc6UdDFzikzsZ zsATN9^gZ!vsRkn1hGb=$e=+b`Own3`(>?Wo zRl&I*60`(RtV4HRMHOHs7sucb z1$|-=DFI)ltcd)Y!yp?nbQoU&PzuWC*y3U!mbdj4%gr$n%BL}ZTWeU}JXxpqQRs-0 zDW_1#>T_zJ@@cZPygfv%?IJ|<*ByBjH_;HGJo)5$^1IokshaNPk^be)`4#zDS-;Ry zn3@tg!t%MxK*$~Dr^xUR5I>zIuvLJl6UjIn@yX0Qr=S3KY7lBaV5e{d0y0B{MMR*d zC4km`Z|`~G!!9SD*%E{z)wOGNMec{VXh_rxkK-A0jiHk&qix>vAR3;t=PSgDN0%vN zdTO|=X4*xMD-_4k8|6^Uxp_D{J45QwqjI}DZ{4GW{in!02vf^btm{(rS(Np~e3)NZ z-kvD6dRRg|oZOVfb2EX`|KYrlch&mko>LqA%@*o@>(^&bGnBldIu;k-O2<1%QDlC5 z{N=G-TVfkx4_{l~s`#!DbJ7=&Q^;+({bpE?McS~dNGHSN8fLOJHFpqb!=95;N^ND6 z@^F*k5!rJ?c!w{By8n3utcp_?PWnHmCpJ56A8Dwfk#X3)zgmQoyhWD}7nUfe8)SAG zq@+=LsV8ozPxXd4ux0;_H6b(l3SK&!4+ftPuRdSf8+I{bN}I0d-tvqYdv{-!!TXEB zdoBcAQ&UwP7N>rebn`6l&5seKqTXASykx1Ox16AP`s^mtiMB07xxb$KKs647t| z`Xtxd3(;9@oW$-I2yt(o0qaJIFb+p0co+Il(XJ)7-T1?oDx#i8N0c8~D{*RK;>h>6 zPm22cH=dSznlwGlo4|7;P*%%IYRwOuI)G-&tn1L+i*3lv%$!_#z#ZXiuO;kj3MFd- zawC}zJ88-p%2kt8h~(?L&DyilUUqDdzP5%;UTiE-Da*1+t@T<_4eStQAkMcY7InP% z^-?tI#mDsF1BpLh9ufAaq^MU)&ds}+@?0S&C58uG7<`zRnA{}$!2fa9-Pr2=ZtgTY zlqd1IiF}46m5kciqLf3LN?8sY=DNXOvL@Uvn3>^{C;F|Aa=IV9{nfTeEfr!BN<&Z0 zZc09MEp^c>ocfmS|7o&v{l7Q*V+ZYIo>X&A?v(eXvB$O>rQf-)*Coif zJSFY5oz3%V%U~Efrby)%{P9PaQpY!s5T80b7v{E04{DuL)H9F z=;{}6e`0)>Zp~^Lb6z#9IP-*7Yet)ugmt*vfhUF)akR|cpAzH`sZo@_>KKx>?EqE9 zwy0bGnkBsDkZgchw5*%6cWVvCq%!r&&N|c&{h42XAnza_pKL}FTi)6PG@RilNX2r^ z%4!8%Mv4dQEP;+}JmZIhq}}_4!+LehH+onQvh1 zWyyR%LA)?Z$j-i4=2K&U@C&Q>{myOG1ttTdmk1*4hY4kw%1lKIg*>IdLeiyc?dIOH z?91t=HXOgQaJQ(13H9xd@HDGU&pE;;tdhRbm)2EYc3)RS9X#Q7+R7-Ln%Kpse0ihD z3`1Bz!zaTWtO1~l1N|CvXj7vLUB`=YdzjkxoAfIJBu zcEed)*6{Kq93Kt9U#gd_goV^Np6Wao3rVShCS!q zJmov>jRPIGtDWnU987)uvXD5DOl7ffMdG#S=Ph0J_5KatU2o7_jQ8S}2xfqCx3)qA z@9-I{|4T&vj*})WtHs~DLa923*ms{9-f51>f4VNj!+*^FG^=6_bU3&wQ71sSLZEAH&_V(WR_ zW6iZjb?d&*wEQ{c4%{!(PBhZ|woI<0^kF9St7`j&JkxmY;ePfAJ$!EZEO=SMTf7MHC-KmuuCpXX>A=hzLF@U_uvc5x;tqvbu$}Tl+A6ocN>FiP9 zC*w=?Wzw|Zh$67Ojl@#uEgjLWztQJY=_A-K-R~)j%a=?!F0J0O?S3VsTZo-3cYXU) z@(##lSj?)_zg?%s?%h4Ud#iLs=BJ;dhCaR9!)9PSl9Vd2QFI=xyYS$eWdHbkG z#`-nNz_z3s+qPbGP0vWmjcfl9^<~hUP2h%*bkj0To>kAQOBXKeVY)9jVT-C37)l|^ zB0oR0Jzv`l${HI3EXaHFrsZt_(T_^jR>kE-$3l6h(!K?%mMDtAmsXt3Yodlu^|M>o z$dT)DPf4QVuZC|;4<9;uIVPMw@G`2t*h(WW%Ap{kUK5JmQGLi3c04)$bG(eA{PSZj zYhxda$h-IR%rTjG=<;R)zlJ!q6zXU!7>-f*YsI<6ClUUVnnBhJkJys+aOn(iL%2iR zi!H_M{UnERuyw?(-OLZ@<*)SQ7?kjCQoVSdl6hW!G_@e>4PrROY7AG1YhpVX%+B}N z&p?Ojqw10CdH26ciRbhEc4Qv#EIYVifzPvyon{pmiVX{%pP!>QG@L$`iTwPvXbevZWZto%MWgs#s*C z3vHOpyUSZX-ReEa_(_X`*v;(bekOh@K>ebhdEgnSrza=$Ae@3mQf+YE={6*U9K=}f zSMCh@U<3N&`F-$5L$y4t$4Vq~?7>OQZTEHbsixY~$G0L9RYpzjY&8;NCFCgyecR1r zvK#y*R<{Ui%Ed@EK5_d?ZRwvVi0Jhh&9}Sw)em%8WxwYpmVaK(fUi63kAYoOxN5Nl zRDb^i&7(!90oPp!^HShFfRK?~fRR12eGc#y|4TMY0E1vM6{t?BXY2$}&HaHE*REmq z=@?)0iBnBKUnln-THPw!?nuX(SX$1^&Uz-tV`2j2#VN%`f5C4IDHbo=o@^w9qC+ev zsiupJntlW<&+))Ew*UR!;x9?TPw6T$cL*G?)fdxNr7DB%!O?ok%(Z2y!N9mQA$Zc992RjYXUT4btKpF6~K2@M@AeHXj-Am4JJJ2NoZTBlt7=_W5hbAswA#rYmy zjV$};hhG+pNncy-ec8mRB+h4@cg$7I7;dHTO4;bGY+ND~F!*kKQFt1?Ok5<|%rLZ6 zNBP5=G3tRoVQzzXX){>$MeMsZTucE>AH_p6Gdqx13E#ZwAEXEAF68`z5NxpfKO7O= z4wW)YvzefUN+OBmrlcK3F@@$ZoPw7`f#2a18WLjJnOjpkYI(#g`m8##?tk60-rfu& zEhlk_1AoGmgYzSr9O#?tMWib7a)w7M@^LNjt$cyuLG%OKM>EST`+wi`Bog;BEK#a% zO|D}pY`@ON*FnQXS^VmPpShjgpU}%LBaIWCH8p=_5~xzL6)w!!o7wk_L>bd~|pqI^;*`C=lZ zrLV7VZ=V||4}KPS-KjVz1z?UdxUh)9od)g^zn>^u;ESKO=(fr?dzWJ z5eoTfwOiUG%rK35?$D`G|_KWzRb@KRqfNMi|&nHieXnNapHRJcEL zq)e)=brUTu2p9nM;`gVpH!m+Of+<7j!(I`}k^!D?uaK+)@J(Yqm%~kI-|7o6@oCU8 zG8!VW-F;VuVixO5c&C4O_znc;FZ2HxCmYFmC*;3GKgLQumR#Ib(F4Fo5@#fu;3C4p z;~hD2{Go~o?lq;CL*nc9zP>vcPq~w@t}|&^_cAuNKHs2`=JGelvw<0~jnwS^WX;b) z@agE+SQerAW};yl7(T9gJKjLB16Ta#_iti1>UE5fWKEQ@BS{Ad~ zlR5Tl2_Nak)Zw`B2q~k{Gv1%9-;hPzX8?v7<~F^`2_A~_r>x{pO@2wurlZZ7eOt&R zqsO4#p0Zqe!bL6l(=frdyRNkhTt4_0vE}TG{1K=eZ0_vp%Hr|drX?>w9}br~U{@9t zY$r7M)J#l<5d@2L+&osnhzJ6I(#LRA4&L^Veu;LyI2Qw7pntVSl%pFz=#5 zT)IZCLrw=C!7-y#-m{1Y5Qgw5|9QFkaCg?Ll9J=cj)j}97evETZi4^nF1TCoGzGpE zCl|j_Mp5*Lj=2xr&Q0VFq6vt!D6wK?kbfdZSPwNBzY@?;I-lIHb^FzYwEE%{zM`I) zac=D*g<0L3Q*L`xS}7!y!W6IMbOiM2djBY}tawMK2ciw0>Fqy!WMX%!HWMkE9zM7mYFTe<`l5d`U$ z7LYD!DM3mB0ZFBE(;ati&;7pf-7zl1KhANed+)W^df)jz^Lc&~`bEtt+fJ^o1|Z&m zZL_BGk>iwL*Kb7$0>r2#yNL9e>~VZqT*l=|UtqF>0*1isBw?;X{4hSgmIvn`uXg{F zS4ARkw^3xhdwzkpm(BFc_~``2t-u$D8g@D*Y99yNP^d+X#oRSgx_Mflun1fHWVw@g z$`l9*%ebT@sOQ=xQ=ieJeJ@bw-QeWRnEX9DTBuj!2z`9$Cp;Ct1n5RGm#8W?9>+*LIiMj#3W$HgX*I5+qbk}3_lo_3_eiM z1($Y=zpXOw6yG-dQ#jtIaMx*N`}$MS==Z9{Eo=uU0lJ@*cpn+})&GtsZwia`aam#5 zdg+`tGT)4Z&&>Y^^!DYKn{Apqp88s%yusDM%4W9|gW2k0|0N@lG*Z-|7fhLe!#JFx z;mgNr=LG>8wwl?mo^aV_@O-fD;}ZvV-^M|>_HNgUzgGf@AfC-g@3ZQdZa-Wnpt{WG7Cr(6mR5M=3l(Bp222|PX2o~R6J;>~p zKhihx;2svgeRXhR%Ap_!Z7m4H4p=;n)lOHTmN$EB6^$jaoS4G8^M?raQtImNS0i^{ zUmiLct~yz`B9s4aI3gX8=57v*jud@(fjRJ9U|9oLVHZb{>6w|RgajzA)S*n*)P&mL z(eC#Q7}2bXZ?m$pvcCpBRYTwNJ(zOwv#$?zxR81dtxeb?Amoemo0o(By|`#DmMZ?! z>Hgy8>)KW%XulNScg%C3cf6x>;f+(ncnZtJmBt@ae{L-ZTIvK{Cq@P+_81;*bx>b` z+9zlLpoj0@JM2A-27>8<$`Qs;H_W#Yb6L zS=|bP{$UQ44=EhzKmQ%`CVWx5@piYPAI05JNE9b>vXTY)0X1bNOmIm&$sdAS(>X>N zN&{%PJJ!%6@MMd*EUUY@xxunDGU7hp9S`g0&!0bGU>r=XM2K*oLUtW|UQhvN+!PE7 zeh^ztNF5NTZz1pB;-==};B%E=vc>JIY8o!W#JX8cEdg6TD zq{KmB_(zXvkzUOf=rE@fD4&qmtG8lyIl|j7oN3+Q8LNF>6P|$++LlOBXKeNe&+p6i zg_&w23>ZNu}S?t6TDHDHz z#Zq^X@W@B{nbNNmO=iq&MUxUOE?Ly{$d$b7r>t@eub=+V!eAt9%koaW64sVjdee4c zGzKq@Ogrj5H68!U4wDjAB?5!kI0Kiy4y&DQ%AEFM^8jukmWZ0MoPKlu&}wIwDQ&*< zv*j+K$L@pAPGTF5RKKWr>=)qZ=JYG(Sf48^^m;1fz{|$u3=(+@!Fpo;VH}M2C`gE$ zAN!u8z%&820l2B&8>e$u8YBI1@0}btc=M9igMtL35P|=1fUDV>EWY|0t(BVJ)Y5=j zO%F4%VTvWpq>$LGU!t-^A@zHTO5=;I?QO96V;Dj612@(KtRs04(c$ELS~d!2p^V2I z?}D3{@NwBci${

s-8aaUWOPX;0!P{I$b$#8+kcyUW#%Hd6Mol1J~8K1{VyFtpWP zh7r`u34_E6GvR||4df1XZNj$`LitEC>u3_R-I>l4;~IEqer_{L7agA5a}VjbUf{x% z$&EvUr#9K!nJ4rliT>dbIf1w?O`Sl9GilfuHS@Hjrjq>p578pix$@chM#clbEE()( zOqEb4vA0v6kI6P2bDI(gk^acTj&CDH-z7Iz2?-n?YwOSDyrUmsaNt-7O?q6kJ0u=e zGj?ASMSi=E`Hn52>vI=v==%DDWH!~*f*1)?=*3UdkUENdlAh5M*>&7s2 zl1t09^0KsME#bXeeal@S&w00h{}1uzp<|%I@rl!U(g)JVFV}C$+l4sNOrC)_a`U;% zVoaGy$l-jS{SJdp2V}y-Kq)W=II{K zgu$|7!CDRF+rN~)s-YojZcgA$+5PsxRps4tR&n1#EJQ-qKFLjQ`91fh|JZH9sDQf& zLckZ`T}hRh6T50ahK+C^SFzFO{gLrWak|@_*d^2$8$ofg?zyj&iSuG3a}9j;XW_nv zY-_1wslKyq4F${Z`nArhcZ&AuN62YWNE(mOhOdx`ZMT1@1)cS=Y2;3A>-2TcJ)hJ@ z?wdQ!k)vEjNW>vt7sYMDBU3`AUN7FW700;a$)z&iWV_C1m`%sJk7ok@s!b`3)5TMv z5JZ5TF$;evfH?0E?_(Z81LOH<*K}1|(=@S94NnQSABF(UYlq_jrwdlCO_T??vL`&Z zHlLq2M|S)zsQ2_`J{AAQb=H60TiIHF>rA(oK`wtHVw&!KQ=a@(w9X7I{ke>k;qqS9 zhoHvU@(sbvIfhpbOTsMcyy@wTYon!{l_$P|K%3-3$j;m)B9aVGGz`b%0 zoSBT}1C07>nfQFUe9o<3{PbEjOQPOXlUP05$t+SZ5!(pCJMhB!vq>=d?CA3#ZO1gR z-Hv|l{0jG2U*+8bQI*Iq&HhKH`wKz!D*=Y02_LG(*9WZzlgZPl%oxbo=I8Aaf9(^9 ze`91ruPiL)6~95;0r&eyn3nqc@7x?Hc5@30IVu*AVSryqT8~Fb{dFbH#4#{5fhCLN zF2TTCa~D14ryFdOe6etfZ0Ga31cl~}OB^=KluN(Qt&V5)l=Cx-rjJY$S*xU;+k5Gh zl&Tis_-O{P>HLwoe;*40^ARl#kgy@KfcSlymYKm`YB2WPNj}mX>o@Yn93(rbU2{`w zVbY@JFp_Y>8ludYZxW0*3HCiPTz|%Z;kWV5SMU+SZ6WKJYd|^v!1vzH%)TK?%T@5= z5*az2G{SyKLlsrqs)pc(kMUY4bt`kk+_3dN@_W51Jov1MPLBPXhuHA3mpI-0PWIL=t3Fr>M@WXZB?uPt`G}Hm+WuLUBh>q}#EzjVF_mm%Avu z<;D-soZGQ$_(M^(R#BT=i9>hM#KxbiyL$;?uKqJt)i>N1Lbq-DRxt2VN@pI1dsE-O zn7~rrAxn#}Pe-!!9ponVrd=BW_1`4soTFXQtH$zPU-?h-7}p%p3er)1ZZJ37L&b znRb5Um2bNV(K@)E!F90$;uNXur@?H>?yv*a)O;rW@Mza0{a$-2M$p&^S*picI z@o?|neE3G83xj?-yI6*}RaB5f0{ftksY$EW;`9F3xHy`3&2}udxlyY6aAenF=wFnl~-47%d)D=aj7xSh4y1KoB}bk$@3mu z|4M~lA2q{z5{PwV7zIf^)@c(ZC2l`%q5ypS3tw`6j|w&=BF5411~7NAyc@7~PxCfN z88%Y2&oIug2k{lUhV0ool&}wuFJh5;efy49vcex`sht7>6QpuTCBStb01yLcKmq_C zW_Y=`axUk?5hEXc54kDeU%XThJMSRYvsR;(rI=r?{kP&zmVlzRS=1XA?rIUrK+oyY zEz^2jWYWN7$=K{(`+hJu@ht+TqChbF^iKlKCUsIWFYZpRPXpJWj=Au4z{yuw`1Qu zTQhr{?fc9c9oOrqW=@OsudnOBeSb+%FyFu1Bec(R<*Y^8ZKULz<5NjDt~&BTsWqV`pAt=gWpW*JGU=Mb60D-nP2` z@d9+_@f9W7oOv;M64`;q(*O9Mf}QTt#V=0PwPXCbL96Ap=f2x39Le)k^OgS}_p{Gk z!Pc2SzuDfJQM_j14lKr?qARj)gElDB4kRy*xwXG0b1esf=@htJD%m)7uIH<0$amC@HR67<6uJ;35=$*i7r^9fsahF?dY) z7btEz!nl}L1b3Lj`PH~LkBDkqVoXYOR8(~Q_F8YZ-Tvx}8HwJ@!NYf0s1c%&{^7rY z>wSfZTLB>kqz<_`jO&dK?e)CDM_!B_qT+k+8`1R=01>0(<6o?g3q`VE_%Xc#Poa#o z^oD!go!6{~3+w-{=K4<^^fe|KOYj!-DP~$sEvgbyXF2At!b51+xn@ZadcNNsR_+&3 z{tEDH&M^8sk;11LVEu7oulh?rELwBZe4k%!p@T^%^C4t#qkosb;SU&vKMxF zjapZ)SO!PYU!hT%q1gK6$$Kv$kuN^@m-gINH4)5SF!A$o>G?a4xBS70@l^0B^HXX) z)bmXgZ>X<0P3r^Ciw2XCN4tBO738VBHRnvS>nzChVdIAn{Jy!Ip=~S@jgKSrO^|8F zFfJnkruAyUl}B%CGrh&5@Q%Dt9S*aO2)x|Tez3Zl10R9W_Zbo@Gtu93P;#c@!6Dxj zpd`>Rs?Z@u{!fIcR=(hDx%}>N@JCI+=HJQ?z1-yEb7w5_x%(|{4wzRHU+1WRi~Q$x ze|>2ZGKC(cXg%YZ)<1!(>&V zgA|vS18rWn!3*}t!^?(Vo1p50YdyGQ2CX(U`J-W1pF!M$_)_>;`H$lC-&Ypq7h2`!BB6YF`k&6im%#R{)vATDVAeUo78SF zlQ%w7Pap3skFAd%s`p9C4_H$kHn5>M>f)vfaGUuVTY6M8xxea=9Zas>_)7eCYTMNE zDDm*?RBQ3B?n@&7+OruO9tE(8_RNESRg?JC^loUOnPmT|o}#FGHe&R=E&CUaB)WQRB|A628k8dClDr)L==Jb{bw z+z9Z%%`-hZLak9y>5{~MONjt;+WB5pNP>Ir4qd=J46#QhHeikn6b5)EmU2;YK z{9S~lQPv;vuN0;eD`BL$&;|LkDv8L1uTa}vk#mr(xZiH)Jezq7F^MTr5S*1JW zP}y=EHDetD^e7aNiSV2mmxB?lr&ue7Vu0k4F=H#Vy%vT%~fy$rJNT zp;s?Lt`-ar0WRRps{J(P*~l4@Qp8e0s$FpFD$J~h#ub?2KYik`4E;aCu%{0b^zp%> z1Yl6W({X|P!O2Ny{|Riw4`gKC{jB@(%3-A1(@mo@U$zpvuk&pvk?S*d%L@Yor9rdh zK{mYZSctvUaM3*D$=SEPg;!GsaUD??wg(2b^rJ{t<@9R=*!W%?r@V`c8?LNpOxasL zyX$M*+Vyf0lfhYl(CM9NOhf>&?o2%fQccd=dY4|Q$4l7xxnxiyclo8PoQe)>-}LJa z;t}n%x);f7)$W{8RGp(#eXjGi1}V<%-nnd+m36rS{};n66zAFQBX?d~)R+3aBJ8SX zt=KgZ3aX|$VZJB76Fx8prjEGYSKG=9&{W%(b~odBjXz&@iMvh6OhIRmB)xWz6_@tR zqU~JB7_}_=TEWZlBXhvPyR>yn_AW(X&e>k&-wcm{Q0?J4CiQ4^fuM*V&k2XTw({j8 z1-ZkUd?vD%w1`r93z;CgLDrKhUQE7qvY%Auk(RML$7N z$HK;Q%`eB6N8Ev_;?ov z)X0}!F*!{Oe98R@wUu>rb2wPZkn!8QJwCHrsqI{qI)!JTT|+B5*NzY^e4~8}5JYVz zDfySK9D}z604lhn^1`^Nz5`7e9Rg+b3^2m~`*<6NFiK60Z$Rw3h3Z9;bqsRf@k(#2 zI$y&UGFz>!X64sc*gL{k#~p&c@002$MsCMa+vPD`try8MN7>qg6v%&O-!Nk){Fr1R z>F8eBOYF~uO~N*pfb zw)U@hq4N{Z<)wo9S{=FIzzn;MN?wY}Mprj~N!y);1+^=cY&rAv6H$Hk8wS)>f}HXj zN)i{GY2-f;-eLH5IcWXN*>1kA8>@!JcxCZQO2mj=?>=+PYH#Q6qlb@rxrn~IO?Coxc}^-zx@V@ zR${s5N+tD_XYIq<4#oq8#dXrhduK((G7s@F1y|4P`zmn)T~jo2F{nkF2|dM0m47!_ zq1H=jBbhgRud+J~ACn&iZTF`ZT_r*V?RYiA1yXa`TYt#rzp_YIw-&lKW=KeDQrPwX z-a3$4k^%My0@DozI5@gSN8^8kIJFCk7|?fsoR0L)(xh z(=w=6WzUzPC!4395ElpDfwyNv6*@M`%A|<>U3%Q7J7)uOQkIRKu`z?3c9px=vqV;@ z&pw+LVLNf*w`eb67_S#!vNGqVeJzcNKm+~hPhMS)=ubnItWg%3@oAC|v$o*Q{-0A` z#t%#^EPx(^k3KL}x==$?LxTeQDj9xzW@_5M4gu8b5RTp{`V6qZf8iXNG10eiDJcwv z8VY1Vo7V|sUjZ%c#wC8*9v~_&{$K_+gDyC(NGtbd@R{W!S>*2}+gex%sSSVgh`wAB zyT4we+nLVnLIA1GBA}V&7d2c!Af)SGwQnxoa!X^g5W+qyYinR`d0sY};p^h2S z&>dyk<8C45887%f=xose3^hfHtXK$8OK!cj>)>dj+dhc7umLTN_)+SDFY;|w%yiQ< z53WMw6FWnl>+S(f30pFRP zJG=0!jbp3+WbNDO$5n>eowT?ZTFZuY))zC`auwiIyyzs?}$^slHt}>%VG?ZjBoz+0B2g9sAYN zGWo0|XKDCyr%Z{fCip_jMbudaLTWA+X=OlWJ1s2@s3~8*Bv@*$EiXgS2O*6#44eD+ zTcF_M)&G+D!yIY)`SUhV03fwaIu`#gC6Ax}=c8ep>J;->8W{F5CA_^)+wFucA9(+% zPbGAE+>eIR%m9?8-9L48KN2m7;NJ+9RF_amr=&EzY;J+`sY0#lXM_G?d81?wU!k+9 zn78UwJcqY%^u59?6YjS|0oN`(;pEWj?=sEG#EfCeFU2Vh;c67;k$I*miQTtfG&{L4 zxgh`S#od&omc)hIB+)m}S56jrI*PA^n>z0*;Ib@7RaY5N{CBr-%B(G;u`=SIgY-h) z?_$xMsC#$WqXeL-34jG-F97TIJW$A7Pn+%_!OfuE%jVUmur2 zox7f81X{3xqvlk9z4BW#JAq$V9Xw6(^+MmA-_6{;bO~)uVxV~oUj)sEUls_Y?`nOS z5>47Nc=w(ye6T{8;Loy0EX?qaMhdv1CiS(o3D7GA(5RqC1ZxEtA$WO}(^crjysDwn z1||)_+`z{KGiwK*K*tD-D{v>fV~cu0UYuzspQJ@|rXC;Ok~tBLIP=KlB>I6Lx%o*` z2b?_46 z(P7i00rf1$u>; zzcs=n?+9UBbx}!RxaSORlH!GoOMY{W&EPM~b$!zSmgAlO=bM53R%86^V{G6dG~9nxoXh5EHr$fC0c zglA!T3?yBdb^mb)AngdPVDt!@^RxZNDo7-b77Pv$WU0kRM*ajmhuJf*IX!%M0m;4V zTE%_2cFd&XGJJgH3kA0V`h(bRnr+?XkN@4zGmJ$=oPGiR#q#_dbDr{!9UT`zp@LVsH3xE6p%oXyH3xm7Nt)=Jb9c*BEZiN z{0>|^ys@z{T^*e}{QMBSHmGsLLCh8ZW>4q{CU#a^ zv7gL@Z_D2)Jg3fTmk{vTaY+agHHOeH4gxpWebS6;6YA6dUDxyu$>-1K0OOxKYjr2F z-g4;Ei%_Yldn^|IG^I3&VEoHWz5>=R@6V+UNg9e`Ikz@$v7_&#i#YIzg|R{^gW@&p zQ_y<0F*g3OV6C7K8Wz@bMMH1a#zZ&?vD(j0K@AuNr?EKI+UqM>SST^L^&+wV19No=Do7>)j z(y6K+ZKD7Y7R@vut70?@0a$d90%BsavLO&If#Yd-xU!Mabjx@dIJd#Slbs!W!B~MM za?%WU83yV=6Gj#jQVOm0}G5U^ua1A|M z7+`GPHmKuElxX(g;&R;gEAQ;QiUw)EU^FFVDpeUrj}M;cby${fkP;K&>a=YD`EhkDIzy2<~`mwPksVcUTpScU=Y4}N1EUES~v4Q_7k_HQmwi2*7y6@#Bv ziHQunHShz}KZx8+RXb!r=CY^9ril(q8`ERq<9VyaBTvWctYgO%ftJBj)zP`TcDo~f~dU&62tN`a3 zbUw(cK{7{2Rdur&kI{Oh*cgnw%t@as^^cX(SKrFz@gd{2Jz2PQi+#I^U1$7N`Q?uW zj-?FQ_TXW7s{gPEn)&~x$sm4>jg7FP*4LlHRRP3D=$kjN1i}PLhRc@)wRCnMwdR3W z^!&DVDh2@mz2C~=Ekf=hH)eo=iil1!U_wcy) zL_NrPC#y%x>2nyd3ocSDXlAX|M3^jpn`Yk{1^JvORSA0q$vB9(eylUQ3klWgXm9q@ z^G6~EM6@^=y6uCXs6DcqjV^FSw$HxZ|A;ODNul!CnFclo>=~drgXs>n@)gp<0GS44 z={caJcsMvLEiAyjx8TS8peNx2=4cz8UV$Xf)WFpA+#L@sfpm2aH=Z+Q*t37^>hOyy7)F)3!a*aid{I10S*-4 zIB-Pc4tX_b-HHEe2RGUW^LyO#knZ{rTq28(<>?H5bfiq9KF&_RB8jb*;$a zs8%c%;`iNAYwMQ1N2!d59SZG(oemS6yg8}CLg5Xz2z6ERD^o2@UQ2?}H02n`UESM) zT+=)kBZ-bC*6P(c3gH736nuD?h3RhuBV>`A9sYSkn2D#aD)++)0yT)Q2udgWUXgI@~9Sp(~h}j$u^_SP{>^$AD@9iwMA0>(Bl2cN0!=esWfb zGP2RzCywcYHSNihXq`eR4mSh2myGr5Jt)y`vq|v?B?o(ZfbbbZG$8eoHOHTX3kHCP zJ2n0VQbZYGRd+rpA6E6=i|~&g?rne=~A$QxLtiLyZyOS-CHe^JhF& z!YRiwEt(IJ(B($_4)`+-0-_E5PBE8RD(WEz2RoNeqmQUdv70J+bY4g=_eV-=04GhG zwv1DM(_NM9w-6oktkBViZ~*{XIb^YEW^MXM5nTN~r(g_lbYLMW<$*e;#m-qJx1Ipx zEQJg90CSO-KtB!+-V-_~)ACMJ(a@N>*tXu-v!=umt(NsMkGn{MiF!p~KS$+8?q~>! z3}BZQ78VAUcA$P%ySi#IkR7)EP;t3*_+p5JeU(~`fbP;$AG&)K=`zUY@3L<9;Pb(X zU?IQai8-o>>Gid_cY8f=$~U-6q~E!jwCKKb!!2PtB==2#y`3s~)}dm}%tN8E6xx~V zMmBm)p1%w2RxX!lS&Mu%EdzS*In`}tl0X@Z$V5?PIjl9?#ji&FkO@s2kg%#~?jacevDfkw2xHb0V>6Nra0pvG=6t87JSSJ~X~tJC*Vym31%5=?QcQPGUi!A}u$;F$4x5I7 z0j${q3AKe+paTpq40Cp1;t2e7Y~YB^=StkU($w0|mKD;Di`9Z$prv;1ceq#}BP5Os z1=$P{6l4=2@GR9cb8xVSH9+0j zb8z?$Mfjg7cW^d?T&=6C=qopUAYTXD7rY~S5?2B2z&heD(Fh_vC2{9v zJA&1LSkmU+Bc{dCphZJE@Y+ksY1twE0L)Y^U0nb}POMpo;paW{EtF@|3@j_uFc)7G zOn78>pqhC!U#d9%>tY*;y{R3^?c|wn>wJ+MA>34<0KA0@3|BXo+s?sZ)4i<}n7es+ zushywErtF8h98SOl<2Ak{$B`tPYIBwE*eaYebMjNn2ZE2F$7iW+}&p@HtaukO8fVK zE_M$7{J90&Jy2xofnDWYwQmEqR*ha!0l1A82r`9k2upg=7SzK&4NR{HAO5oFq*3;h z(3qz5gUiuW1%-5zY6;;7~QwqNkWMN9(R(UtFsdWDbW&< zNO@=lv#c$|y1BboB}NH;dcc^k=Z+6us+?k17%QyBkelYkigLF2vov3ppV(AAik)12 zOfm)~#@LwW2unB=grM^y;1tIV^nU~+zjuy3lQWu)ZZ10CLyT^Bhy;U97kjLPg;0w` zOavMuSBRYx{JL1{^gKuGLy+qdJ^! zx-mLd-;N%<-z!^Yy#;l0U*Gn}68 zPvzwR+}i@!Hvb0ypob|Rhl>NP`pHuk5w8vVZ7e?4-nb3CD^I`TahjRuzpT6f`!RZ* zOFudBLKdf9UqL*!Sb|4%)wJl5-1D^s@#h}SqYWRQ#$zB+Be!D_O1M=T8U!qrSFUb>&B?0H*^RkB*H7R)RkJ(e6 ze6hu73jg%-3dtX&=_8#~z0w`L_}>Y8&o1%BcY`X{1DGNh*Vyji2PY?!k`Z_|fc7}T zLJ3Jufy5Udw@UpVNL5knv=9#sAc)qi7B2yMLBv9zP+!Th1PJfu;n7E&M18pMtWhMD z&zJVQ`}mK5KjzJGYu^rrwX+m$4wl(ykYeg$M^oie8B}6-f&gSB-!r|MEbN970t!S~ zif=xSC14%>@}z|*1Gl&YeW~F^q9FN&kIX}+%7{71Bf3Tyah?dU9crp)#E`g}ZZb+i z8P)dl!O^Bcik)R=eGX4>W1}yuI8azldGG62=)htG!6X1Uf_w{f;?MfErk0iuE4=6n z+|#0?DR*mR;uW)pEJv;P`f*4*_Ro`2&roC&Lk=ehii8 zS8m0C!mUh!mY%M`;mw|Hx4JR=(b_Q1Z3KVUbf4rIosiB=0|SZG@0u7A#li~{WKP0m z7+sB`yMvFRxd#S(K#^aF>V&EZ8)A#-A2^o19~^|t)CD3UY@|X5TERWfZXbJPZemaq z1;cwj1@l>Z!UV*hnwy(3{nO5;;hYAtS^m)SBp%SmGzzr-%+BsaaMBQ!sbW;*q^<1T zoPn?0ujISPzg5G-g#FS5utyrsnuHc+yps>O@aCPw^pU@vg8(7&oBtVJ$KgTZp6M*I z^b-n1;XddQ0iggY9{9;q*8zb2>5)skB5U+R(C**|2h$(U?Eqv9X`u-l7Hp2!3MjxK zx~GCcM3twp%kq5S?#P{s|8vF_BZ{lQK%P`p39Ui;=eJwV6eAxQVj4>q*2 zGADS{A!!Fsl#vnB&_PLFo_xj+7}pCw(8ls`cPIL_lGI}g8V!~ogP4@k+HG9RB=NtD#3r64w`)o5wxd<)1DYjIsHRK zJ;TktPSaO=hCNM2_XykFZ~eE?IJj-kDg$Zr|ZF5Tn(;kw9&PyAeO^`KtRnxo9$ND#3JP4e9ulmN6yo; zrVRsJTU~DM4G7!5*IS3M;lehA<}55NyNrm&{7%wGd6DBoC@4Og`j39V__A|@Mg1?) zNMFZ)4;HPX z>VCzmOtmMVmVlsmoCE}-oS!Pd{)Q?mFW|TO*@eU&hJxj97X#YM1ahCJEn{;N&l(v~ z`(YR%{aEHG?8=@i=Bp05)xcddr$=9hK@CVLLHyp6kzYU{ z8U1m!%V6Ein<$jYu&}Zc_B|6ps$olUcYpirlsWx}Ik3h(!4U&Pl+j>2Gza<3n~!^= z;YHVLr{$>4Gb7F^y9pZEgliA)>GcHIQWh&2cYfZ~z4qT@!lkl{WxSzP8BB(#(|-}z z?@Q+#ZCuTAQAj`I7@WFdWEB4?fP&=84P;T}R`8qW;hA*;(TyK9^79JCo~VpzO`%>t zC`&Mnm+K?$>dZR}#X>Cyg0>K?#Nvyq?e$SxYcP7u&+ zwM6fPoC3I!qUO0@mMck+ahs5?DNxV-oB5>Q=3etqm$dmr6JcS9nC3^I`!3 zqWo_}n37E_4N*HtBv;7Ejp6HFtq3O{o-^_#hYz|*<7c31jo54BD!5{FSl7jX0~0lqxUQ`^d(Q&-6^!3RbP-lcgs_%XuwcDln1@0xFT_O>VX4QAY9Xm|{9|vt2_-SvK z>F&+GC1k{^^1~g*axuLML0N~xO(})m@=4b%>rH+AcOI@y91TwyXw+BQPd^$P9p+zi z#6qxZNh?l|pc-m3*~F*2v&WOGBybzr3Yz$uyi=Tdi41NOB}b z>L^<2?(xzg3~5$ELqy5VMwwYzE-XDU+Q0>vcpmfc-2O}(5(cUCz-v^`(niZi9_I%5U_9-%k&J^Mk9Vpc^6Na#xzniQz3$;QWHaHVnVo@yg)9p@Hx91k zE?={~(;b)7{^`mKNy%n^EIb5!jNo>GAbWL9%@Yt$otYEddzg}%ghz!8|kCZl#l8kb~8U3Z|(`MFU2Hj!kE{I~se!j{^g z+;=y{Mq}rJp^s zR$3-)FevV)gIeTMG>(H{0qDtIEZ<&6v@eJnVfGyUC`gbq7_(ziE z&g6Ampuw!5d}YVQq>-X^JMo_SmHH6pgAL=CQj%oSD2YmP`ABf0!EkaFj%dK345Cwg zT)LH9A|gp0Ghq{-`WFYNY$EgL&4Vsc@>uZ8Sm~MISGA&H!AfULzvO84D53c&b11iwV(0^&`CDI* zk3^F#oEOQWI$@R%J|UrJ@fn}_HI>&+V#mX0C?BqTYg?RRssr5M2j^GCTs!Z#IVSe8 zTo=T%(MAay-|IL(vQX61VSh|rDWrJ!yUSOufBmPYGvGvKb9$6ooo!vFms_!eh2$v} zzt~=4PrfWZR-EwtN_pp-DfM^o>rsxC~n!Nw_Kg^ap1%fP|5V*jT~H#ErZB3?X;E(#$!&fcZ0^C}S09q^p!yRA4mq z>-PeLB^M8f{LK=3vsoMyG!*ppYx$wck55v<4H#)yS){e)?RfXY?rCk4RYlLPPbAnE zOWd|xp?CVUa_#+vRfFHrXLFzReeq|*_dU?77{7rJ2p-|$hpR*9qA5S`qGI%`V|wrq zU)fi_E<#A|hc_i7lQ829^kooT@C^PPB#v6@tb^9m2N%O**hwfm$7V$-rBYIQN71cY zcoxO@`9Tf>8zxxIfsu4+;dC}i`JY-#m362tg_Ol*yUq~ zzKh!GJE_+#3BJ$0jz0A#bq&~wZCUnznSC1`dBN~E<$;m-ZpC#RO?4*viHdi(3TY9p z0-U(_=xZw)4{8O7c%?pfJ(bpPR1ge}I$`+X2EQE8F5;P0t}@1G8k(L4c^P;I;FY<2 zIrc|_4o|Ev(Ea|y00GW>$b5ndtzgE*hN+Oo>!hmP2s_$x{fT3dsHdDG`HF3`hjqnQ zT1O4~zgjhpSx~VfUhwx#O5Dq{A1N#6+%BDRp9#bJ76)^=J~BYli1b#s`>!s`0v(li zFTd{BnHN~-@_w>>*DiZ_K`xRd`Q)S6x6eN?%c)pT_tkjmBKa%gDmR8Q74}&{+De|H zyG(gk$>?EZHq`)T$_r0B6ftcro~qx2t^#;^_rE_aV% z(uT3V<;^rms1({Ss|s-sahi&kd8*`joFwi1Y=y7E&A{}TmrR9aTr38X_Nntt_=O}> z$;ix}@-%_d&$K44YfEmXTA-X}W0I}yWc)Cn-O5byEuSCHbo&@Ep4Wz7M^-7ufe(f6oF-p5m*+TfVu?WgPM zl)mS`%Y5%@D7c5fawpSd&C&T#$pa?!JhW^celO~h@w`SiRobO}QOHU~ot?~dS0#*rG zi?4}!FSCt*ByxK}8$C_vc` zJL$m~Voa4gLrDtC-l+Jfth_9Xl>@@6)uV4bOBwv{$G!x)1sr&ZU%e=y8&zp*(fvN* z47G9SD{cj2vsp0G*39pH5m*+-3Fyy_doKN0Ri^#NnrfE7(#yQ}_hV2ovvu`5a-Xf- zwYsIG)MDOyJo6lkHqay%^Ms4V+AYNEb+Fl;`uO}ziALO6*Q?skp6Cyj-(7AGd1oEb zDZy*^_9!*gIN)pf;(cGH@!^;;~PL4X)(0Hh=r9(gixI#vD)96?hOegX21PIKdCM}tC_-NBRVpzu6$nuLAk)X8wLmBho zcsMsZ_NPKarpd6bH}lIP2Bp4lQx~ZoAx(wn)?*$8zeKn;^^O={st0W0mB_!Bv}1f5 z7LI?&kwl90$hxvc=dBt%@U5~l*jEOam9#fp-+i7u5;@`^Z^2Mgb za?-z1Edx(i5gk4X3c~BZj17~8X=X4Hgwa+>cY)3u*H7?o)g#tC_P$4FD>3}9^+y^j zgNW2@??*-@og{Ycx2#5nd!gtm%2V@u$-#J}EO?}WlkZx;`S7PZr zFj7c}V~o_Y-wPKVQmbrx&_H{jxW!gdI~;Aj4PmA@1WF&=1F$Ss*^E(LzAWo4rwSH8GqZC&o)|@K4!1Fr zv|AW{J$@Ubth{{-qY1Zh6G3%;4uUj5l>_tC}dZm@t% ze`cg+md@$i+N$I8B8fXLdi6^ZE5qXQVY0RgF0aL1WxQVquf5S5wK3wm+BH18VO8m? z-OP9`LTPhr3*BN05BH7BQtM#|^IrwQ0`Jw^bFd?wpDc)rA4~_r@iVX)j&J+x6Zz^K z$3)N$INnETazwMp188f>I7ZX}n_Smq{aMmQ|EvDke!m1+d#PzF3AGnx{XWSkMu+Ae zu1_yLnqLh=HS+Mw*bx|aGiK&+XlzS+`9bx#BO0|DEYgMMkdaEt`h$AcpXK;w>?HOC?QRctscqm`uQ+kAmHZO zmF3D%q47*>A)1xj)06^vhGq(J4Yz#5*3L;7mBgoNY4OFqtO^<(BJ^j4SArCCg`zlV z9S=|X3w1A37yXrOpk#mcNjk^LDmZcC05zs*(u}19V}tP1Lt-K$KdRio4;U%87>ME41(}qbj0|0F!wgsJ-{r5F@ZnS) z8Hwim0I%(IcZT;-g~uKI^J`@Zc4@Z=s0s+Dvm0&c_6_InW0$f6c?-Ts&zUem2Ga`1 zniFVL2;!EOe8ERAh*URu>692=Jo&UA?t&nl0XM|o1>#Kn2>8J|ASk!9bbZ;i=4y?E zDT1FY@8hJs*HYAFdjIwi(`O(zX59(N-#qI$&+1p zCBs_RFb@tgd=SDtVaNjXi`T}gz(Y6=1G!*ICCJJEMS?|5-Om%~wccXEfHRRYEUI zZ~!w5hY5eiriq*78LnzVnZUFA+rN6=8xy{4ITh@fJ}_vg&u`S@WRJ!u=^sW-N?REE ziVK@s$Xnp}>G#-OBOvo{`05$#etftk$sf7MKKw#*0}?g= zc3b&4Uf!yWjNIIJ+$Ae11Y4ENM&G7LKmCk!q}(_S@LCrd-zJHT)v%21TdzslAl#{E z+YoP2kn@w{`t;-Lw8M+9yf-&e^6O56uwQ+8AfRJEL?U!t5xMgFJYncu+|rkm{Rze` z&YO#q`+AEr9cD3aKEGDCUnn&Fa&)xEL4SKEw0?UI{e-9gfRor0Lqk#o4w~zRGIk&| zvdFJb)K&q8>^s(!z?fJDS?_J+3XDYlP3SXzdBL&g+wr$?kAt=P5*akD5Jr%1M7Z6D z)v4ca17*iAFZbl=iVy{2KRqy||M34|>aF9V+`9MSK?D>8lx|c?Nf8M_N|X-i29cDO zR9X>Gq*J;z1LoGt?P=irEwh(mZ|*% zu_HCihED#`QUWu`!U$u3Ou4albl7-2I!7eQNdaOo_yM0I&*uU#$=S&XASM{OSerOw z-_zZNzATMWS&T+g@S8X91sxbtlqvB8AkWn1biGNHdIa=mPS*r^FE@H_rzeO8RN=8M zE@)tVAd*gGq?-alJ((V+*ah*67t`|0DFSmTYO0BK7(#Pp$i3u`g>9j251@lXP{lBjke4BRJRUiTrL}-oQ#c zHvSbZbrbN)J11ZG4k?=O2n7w>5i%Ia`A!-4nZ{qa zHO3;wkffv}C=98pUJ0#=*`7!E-Ieov#x3|gymLCFd#^b&^M1yokXt{RpzQ&CT3{ms zFi+_B70h0tPz75F zVrq64IE?MAt??1I0!hkwfNmNa9^PSqGAVku)E6~$>I)h+At9GcmuaD;0#Z&m=g(8& zfxIn94^9I_9_rI=@=VNfQ1wt84q3swfBLvGv39e%HLR%lVgJh=(py-F2Wj_6cZ^ED zb2A^6>fawXIP`jj(EQ!5x;eiV#$r)4rcOm|9OHSLP2||c&0g8bOKYp7r#5GvIizZT zIz}-X1)7UAm4a z-iF-ihu~p&Sy1qVs2|9_U(Tm|c>e090b;}JOvU$I86ESh((kC0_Z%j;tTV}|Iq&@s zX1?f**D1a_A-+04g3=3k6g}8Hmitip;_tW*9V6aUYF&@Satt)c2$lHwnkFxzn6dQ| z1qs`8FTY$OIXsEdYwU6|%Z~)(PU7^hMmfIjoSPtZV=*u^ym-ToL=fd%EB4;&cg1_V z&L=f2ud;94b=w|$dR)U=L^M{JZ9Ja9c6kHwkz>pMb(s$vKMmnPR=%ZNu{&R?r_rlR zewMs0pW=Rm8entkaMMC1o7~lk>3E>*neyO#mXfR1C#3QE!$^GWG>LJLfjfN z`LOXGyJeoBIbU6n!e$ssUjT460viP)i;$}TUM|qh0?by%ql1rFv*6pq{)*vIg@VM- zpWCpXp%=2kaW9$eOGnLs#WP>4#RxL8nBBX5%k<68*?;6aL>118?`NO8 zzpy0yOK|zBc0GY%!alzz&xFq}Pa~&wDpixW4-_tVd*czRix0bC%!$VZd~X#a33SO^ z6OgW{6DxLc$#@eA2nc|L_X&n%Wc4(Jnh%h85V3#g0pXYn875E|Q^M6y6F@|)WCT*H z*W?r&-;i)Lt}|Eztf&A$U}1E{&o;v$umY!;(dXdzsa6*s)g@?mIqEb%i-I02b#-h6 zU`;~8!_m-GDgcGFa@}LIC;KM^on6&KE#rp|OJ&OnER3sqrOS5st{@OSuT&6shJI0f zi5#5^*(Y(*Ja45*f14cf#trwPm;aN!ft}{+2O53nuR4-lMm%0!vL<|#lB92!{2*pW z)v2p2?fLJZhcd&G-qxSRJp*#9yQm!wFWR2`;lV;|PzDBUNJPcP*f!Q{#hg5|?n2Ze zId0wVkAGx%x?dxjvi2|;on7wka%PxM%xS@;6aO3@7*-uE^+`Rl! zdp17kF)N8?xFJ8pe?HJt?U#`|o%|h}hIZ>gg|8_$drCx|nkULCT!;@Kd}KH~Q5fZ6 zy!!(Fa1a<+MIUR6F#riyBE3caGQpHw;@6DgGnptG^jrjEXRm>bp}L@D9@eLCG?sEK zw>L)MkFSMSf14#|zF*;dAMXUnsU!UPm3P8bj@0dkyMHnU9%hSGf9y#uwC3&-Ws5?H zo3)ov#bZ&LQf~X$ZaE{T8~{na?4j6Vi}D5JnHzEzjxv$mSpEL6koIW+BRAL-F{=FwvqY#0?k76$v1lB5P4g+ z_hm8-8q!$~zqqJqncMiwtDi~szY?8vkH7E_O!%9B%aY@yNb3=1VKc0g-%Q}M4E#0& zLX+4~@_2IMjDXdAKbp3!qR%Y-C+*4)sxHHZg0Y5?Fn=FS?a8&9TwBlW-F7`r0ZasR zvPp@FAD955%G0><3Yuc-N^G7yX(*a>w?6ur#_a1Wd|Ekf!DTW(N4b~Br9b_|%kz8F z#+S3$GjfOJHKzQrNrhSDL12;c_fwnfM{_hus*xHojRfbfCDnSz`VP9ws4XQ#cg!cU zNNmstNb<0(yl_x>PwPs0-Au-V-4^AVeRaC>+~+<)Gw-btVy_l->G|G*Us9#L+*^ew zuRi*+GFzr7PV^N$8NJx(U*pAq+~qg*m%KicR?lWv^VK&xsl4>^!RLqpWQ90>2cZh? zBf<%+s0$}I1bf&vr+t0njXl^`&s`ooH`zPXMK%^TO1C=idf&X} z(_VASRPS)A@>ox5$S(ux!v^t*>oiqN*Y2|2{rv&|`8gAb9q@))1Bp_Y#D4rW$u#7+ z{u$7a4|K!VBQIEm2<)Th*joXs2=NpoUcJzpKxC1%RZ$&wE!?>PAMC2I5I$LHhSwtzi1<$P@-}w2q5auyWSujw(Ga(0Jvg&fcHa0cEV)36~HcL-zE}XqGY1 zbq*}L&=FZ0;OEkMiU+%$$MH6(YHZ^10S>sp-U=Mnom&B zcc&6t0yGW)7RbwMQW?bAa7RD`6B=gzT(qz--PLt~{VWQo6}64M$q{0Jw$Ip5^%YoX z-mBfuK_W!}LnI=C%+K$Tu|ENzE1M?%?zIdoZKuUR2%REEl(D^un#5?zvwUuM_Z2asy*GUp*TcA7T7{)b3);eW zlQZ;xgkQAw6$zug$6j{J=vW_M@R$at!2JBhtTfc)TP|*HpQ+k410`@M-Yc?(w|nkX zGTpff?HQ!8{|8X4%5%E#4htnL+f)>m+OtU7tz~`bcuP~Ba6_odU5cTVX9|kHfq}R= zYIi~V0NA@fxg`TnJ@D$bhci0Z+2J5)LTes>dIi86kU*0ulf{IUz{LRy45A>h4#op8 zTbEpFY`>EPoT`!Ud@UL)qO3%+|xLlC9*O1X<2D+X2J4k6tJ&11AK)O=jlj!Jk{Ee%)`9^TR$;elptSaL1)P_o~r54fI)gwZ+yXodaXm zvIc;he|1wMb}nU3xM@CA-N z%PohFN8ZJaISVHtUFJ*N(~uLWV?BnT8m<_|6|q1@IZ$>NfwmGuLzN-%S65}DR-mll z2iqw~K-rJi^|iOlWc8hZA}Vk;r;D*e`!WT$0Tng%h)Dlm$iwU2YzXJNj==!QL9%(k+$YW@xON4C;PFL^j&Vm>eTgR)l6<~Lr$JZY6|ri zRNSHco00bxW>B1O^4zb%6h*gYJF(B512SwZiF^%cH=G3;X{hJ0u$Tio?tD*Lo;+cN zP7%bQqM&sOC^*yFTmMa`6y-dm%c2^HfP=6(Vqw_pJ%wA+a$(<3N#aX1oTO2-=U#Nj z?XL{`qb?e=jj1>z<(G2>-RmFWt^T0;q`cxT_2U*3rY`K!4~?9nYoq^fBHcTh|A>!e zVLk9YHu-}R)w;2Y^Mm1;uZ*;`D9FG0YYe2<)SVT5kdFPM3ZN&T0Z#njO6$@ zNnJ)2W*yEwqLwBmn->NHd+RQoSO)w~``0vkAyg2wZ2=(%uIbBBE}N0KOQi!{m)wg} zaXlXMKAu%{`r?%;>N_Q_taMR$V02Rpx#CgjQNqW|-PHAW%!NMc2zYp*;+C45I6E71 zd#$h@_nL)X`%wcO=i!;1ZV>F)+jAp0jhh?Yua14|?{@-{en^a5!ezR3%Mn_KU?zt@ zHo^Gc(7h86;AiMH0l1zjiiXet%Xw~8xHxM9k&Y)o`q?s}@m`vx&3CFjEzqy;wHOPx z!c;t7vvP!(XSJ(lJvi<%A0cjGN4g?zc~!L4Wm%h%Vu=2OKeYj<)ds>^fLTDV(V?e{XZK6$34H3-{E5hzUgne(RznC=qhgf`P6{LK2Udnp>>Pw6@F z3j8g;A8)*u#_c05tTFUVf3%l{X>I%H&1MrqxwIWcL_{P-Tv=P&0x~p!FK5yv!`vlw zE2l$e(6>k?$Rjin9~~Ur0|iiJW#uMfnoEIzJcIRof?+wmk~*EdwphrH{2_tm$QIn> zBi0l0Rc#1!iUtQ*t)>dO0wHC|sL;5znENA#^05<$TYXXd9~y0=n1dJuR{r6QUo&u6 z_N0nF`}6vK#)5MrRR1a}wni+|3>#c-B3#_v=OG(nX$j&Ns@S#xpA27-x42#I#leiL z(Z+PMQ2aa9f5K(AU~G9KPok@el-1Spun>q?B-c+=+-`T&Oa0JyiTpQlD&7hH`t|c| zU6-qq6Gk!`z>U3MU}UjAe*eA{$qAI#@MbfD)U>qR062oUdf^F>j6feF^cjOTFF5eu ze*6H-A>?&X1}uQ=v4Dt-1Ufn308E(^^L&TiiPge&0eP$FDoE{Roz&gye*Ld=bzu`) zSMPi;uy=RpiPS(1PIx}jchyfa&N;dY21=PK+_-pXg(t!&Kj;1gscRAlJ8_b{MWllo zZ&MQrCgMjE`JAX=^Zi3+)_*T3JOeb`vGIV(2?Ae1hY8!0HyJQF-~gfJa?^ImKLOV@ zcYNorhp6ObZUUo&l-Z;q{9b&-oqfp=$R9-@ zwha^3YAz{o(<6MI_8Ofv=@$qz`W8*6umH%&*_WbF9p7Ag*)wyP)FnwD2*`oU3y@7% z;IZWNSp^Z%dn^~%;?j8m3=d#ei1!dNG8wY`yYKyV$WGx0fRixs(v~TTS-V)zb-E37 zgNYb=Tt+{;&eDXd7kezNkf|Rvyl8|93mxlfBo7_t#Y9tplWZmbElzd-Hwveeiy4(S zUhKRo7EnIyUk#0`SNqnHH@XfrO%%sd)5pdk1)B?9!Q|x7q>Q+H;XHWF&>acO3YrYj zAPjeGyN`hfrlk=hKxnZD=KBFB&A$n71*xlzhrpeC*uB_( zO?OSdoHJTbjOutV`wv2c2yRmFHLO-+?q4-|k_yl~0{3S|gAkVZzS@845hzWmt1ffxZy!#3?j~GKhLqWoEwe5Vjkwdh_NDWPA1)>p?yFuJc^7 zsAml{#1<5Qup1p+QE@T!)RfQulR`Nd9lyhx;{8?{iOF;^@dZIXUt3 zLzo(_O#JP+WJS0yrE9rEGXc`Lbmn}qyj$C&Yn&LdB>^nU) zmK(%z{eMH90740nNc(jKt}#%kjYJ~DmmB`RpUWO(;G@@0`ar6BY;89+VMXwfJoI-O z0boZgpc1N^>X>HFoK$5XPVlm=-N#%uQ4xAkq$QCC`)M3bs_KFWgOWv~l}{Ca2$SO@ zy`g)@%_5}z)-$QnA!9Jfe0)EL7urCAB7oB9y@1{50r#bUBPWxUnfYXWq6wPsmD?{6 zw&(hMXCDfTfhrStEV$>-gGhdjdKz}pdiUGH{IljnO>q-;650> z+vTr~bygJF;47&#^WWg#75p{F#6U2#I#D6hS8eTq5IHUZ0hky1MgLsoN-btVkDs z?|Z~mHbZMVf%+PHb#@l85pXo|WbnS#OVTtPr{+~j2>V&^*MTqtr_Dnmlw?&f-dy~o zU}X>s(fhP)*#G_P$D=#idf-9p$KCrLK5g-(>`z}Tjnsghp>ln0vlKDHW-c-0=}`MW zn@xq}SA$JXz<%6nrOiJ3=OVPDgR%Bm9^}Hn&4FJ7ddQssI*KI!D`RtQN2eZ23Txgn zU+H`U9P6r-ygcPl=+S==%r8ZukY!30 zdIm*}ox2kt1o8fT9V}OX&p(o>(p#-}MyEB2goal%?u(zLuyiO=+}8Cw|C!{iELp&V z%cM9g8k`w*5)T9Z1di(U{$%>)tI|5S=a*WO&cKl)lat9%Ht%cfs?vdtA@)03P4|INy-Ng1OVY$k0hiD0uALH*ZFo2_(Tx zwg=ujG4G=);}?)%k_dtqyZwjOM(o~YtpU&6b=mZX(Ixn2pFZ>&nNY}yuEbFaviEGF z?#V^sKU)RDR9mkj?EDPQ?|_Z*k%|l5E~~9`({*cYM~?3rEsnL)?1$j5P7B?Q><_|a z+a)k4+tcaJNX+dCT{L;&bpJWBll>lLK!AieAk`JD89;nI_0~GwPgDwYvfRk-rVS=t{9cmGLOYR1Pw8X?a;3rR!7mStQ+Zsx&q{ zqw=?kXB5VBLyd8+PqtqMJ{;Ub{9OIwug^Islu~%4!yNGX{Q2`$4iQ{WM=H#LLPsE} z_+bQer6AYEybi!?2ohybk&yTZ%i96E+hGUU;|9h>#Db6*YTD;;y1!}GqT^bJo;Lrp zH~a0R+!qOjkI9kiTY$+dLlpwUqZOg9fb#P8=|E=%NAnK{*>Wj=#Yq*S`t79%ElL|I zkhj<92f|T3!V2%UaK;wfk=vCcC$LEb1_d3L3&WK@%I+Gi!{jKnOdD1=U`t@pwGJmH zxO=eEbW=6#QC1;5q!63gh*fKz=Xfc)@=wxdy-AcKad~=_^^sb`k=mustZq!ux7@X>m9 zpp&xxrn=$I$+y6D1BzSQZ2N()UsLHbzylp#?+pAk`XqG1WbWzEYvl%Zp>Ni=YigYP zKxJ?;6q-z-9+SFO1u^er=+t9@Lhz|2;x$({OU??cTj$ATlz$zEov#aj%{X#dzji+Z z&(a9Mq-}9{aJweoDv(HZN}HXFwd2lq3$Hm=v=rE6%V|M34*dC56mlOX-96M@&;7Ms zl+}-BIJIBNS50;FT1|ntLq2D*t!%mfc#tQV51H3Wp^Z$a$JEQoz`%ZbnDs7NW+R4! zY)I7IAZwz%G+lB!^yl~iMzVO8U4lf%0MQ?Vy z$&j#517{|x+D02D6ObPS648$iQzCDIs|;8g1$jBSP0vuw+kSXxR_i(4UBDDC_J>I6 zV3*BRYF~tBmHgK3QndGd_JU<}L-p1w4|{lhV>8pW)IU>FHvTEbu-lz&Y_{u$5h4)6 zA{8s#3$Kx9D!SwjzN$CnK5a%3Y2(sQ7@l^lErrl)swg{t4b;~&m}A|knn)t?n0}lz z@+(1Y1xj5&>nRAlIwd8_YL6eM4=o$k*p7JbqlT_`gNO(KPZBz3E5=r#1%&^D5!~%m zV~XRD__lAiikr5An$@dp|8_1s_d4eI^{r<2_p?3v?Ami0S{i}|6YaQ~&(XU>>07H& zCCx`mK@1)rpkcPH31+Wfjbt2ZAlY$f5-lzFyIfe#n|`kFPtmh0b0=Fz72l6~w(cRr zJ=Q#%zEWIuxBGG!-;O)(X}7R@QGn^4m~Rj&<)9B{AML z^r=E*4*?|}Aq^Qd^`cY#9>5}iW+%RrWwH5qElXDb9zyutXVcVUW1hRJtFbY?olZ}A z6o~hI@^aiw9!_cFxWcs=&L&Bs6)^ zdWkqTDFN+ED_Dt+=2OF+=e+SsgQK%)c?ypweYGfsmc1qSHtIfls^2fArZO`qr^FEC z0dRg47&LfV;nw!;YEc3nJ64q=oKGhjUv$QCb@ud3f>_L4S5lG~FVLS%c&<0CRCI>q zV+^>EFTo&#i0UdKFS3-^!O1t;^G2Zw-}Wt;86BAwqGP4jYNE-=NbGZ@OEuojdm#EF z(_d!th2h1_l{i!2&M0}!iB!N$x1Xuj`MMFP8{D6_9Hv)VPV{pMwfsGGDJSX8AB0lc zL;D4YLST%NmphQGdP1B9ou5Z)wrSuWV0uGgbDV${s|=|iFPn1U*SYt6V+u;v<(Rz! zk@C&BMq`ey;Nr7YMyHk2KfznM#3_z(@Lwy=YNe3<4SeKY1J;BePg>{q&S)|c5~ua1 zeM~tPR}&_4FBl+X3{2W65)WNvFp?`Tb8mJ?qK|cVOR`e6R2JR?KzP4fWZes(3C&1Q zDr;G-8IumBF&9>HUzdw!m4o(o}(PZ!Wqan^5vF z=Mker+IV4Xblxgz(A>G!f$f*UolQTX z;P_*!4*2ov8+dUe>MMOC6}Fz~H*bH{&{{-!|N0qOxdO;445tqiWOq>D7`(stVhc90 z&|=W(L~Mk^L^m>L#QP=80=|G@sH7Vc5(Ttc`yhAr0f@M3X3!R5M~tT2>t=@M!8CRg z=(IetsMF&r53;SBt{7n4N zp?#H2oS~Xp1w6W_=N^XO4xAOtzXWV`T6|8sPl^EjhM^h;XSo>((nw7}Kuk(XI#vqg zwup37{K^Eofrn9GTs;DR(wMHL=4SQlmej(d2=jwcob5LnOqSwjTrZ&Z)b$fB+x5OO zWM3LdMq}1cr7a;6TW<0t5Z)DXa}9PN=3=8J5AXo?Cp;aXBmLbrNS}#AN)y)nJ|z8{ znIJWXoDLJ=uAhl=D*%xs#KII!X=qO)o}%e`ByeN9m0pAac?6rrckFx<*cQnLCeWup zPW@GD)TdW^_6B@3AI*zYisFALD8Se$Xzykov8{ni6VcpR_y?x}>xS|6;3Ed#lg&1q zQ6N|bsy_g-`+(Lwb96^ca`HX%?=jE?RwIM)Mt8BI&Hsl5kg)7~-nHUX-|Yxp&ugK2EQu#V0t>>@91p@ohPlu_zGH z3-5q|!l2&j>U5$y%wR`Nxc9;dR@Z12W@e^GF9FAzkIxx^DS7L(zzC@yfCsM*}9hH+I&^y&bOW6VFn%)Ik|;RJbDrUb64|$ zsHf}IN+Mt?Nl8e+cjH-vbOStPjSi=2TZk^uIsvcS#R`mzL6NJRLIX-VPW5p0LAW$f zD0slS^KJ)jKkElC;r@JD8&*o7g&nJOa>#kVZ}dgaiF-iK{DMs>gZNVa%$ek>u$7Nb zb2bFHDT^QpArJ}2pt{zrSO`i~wt!aRo`^5c%Ijz0dXzuvcbeLyQ< zNJD;0OScir4M!&Ne&(pdBX|;ZuzTk5d-xYbBW<49(WBThn*3K_viJ9^$zf*|?d=ll zgxT63eVF}b(HYr=bv&`|`-PyHX~@u>UJ|p}I$FdVx{WY}->U#mcanXDB7Agp56m>M zn3bI3Z!{#ci{EfCoUYkobx5&h*HHgm%&z{xH@eyz-3!0AdJq>{^LtD{l)cw=L_1u6 ziJj%<8v8@SM`cpg_OT4T8KsK+?W@a-vTx}U4W(rO3WAtQzQibYl3-X%Tg| zny-#g>ZHBQ8Tq>%1#{9;c1~|L0xZ16!zrvwgGugF7+(tgW1BkFEhVHjj3Z*|vxc_p z{KkIf`s;>7w-Wf1#FKRygKQMi9eCq9p$CJFc%VVW*Mqb#zE)iheu3cD@-vKD>Tyfd zjxwvLa^{CWk?0C=Lohi29im_e7I!^ZLTUI5YAlr`HYwRf9V;Tg<;xS_8GrLPzCj4H z8^>|ISnhtWF~l!I4K~0q(tP^98B`Yz=aRq@MU&CfpMrR|k?Vlw=yTat;~Qv>R%7Q; zWhSIpWOi9I{#NJ2GUiUY(>iEo_;qKB)vL+IkM2$g=MOT=?K%2lLZk++3fttgKY#u} zI~+#5ItqBgUtc6`MxUMV^%s!JCjW8xhh5s}FJfCup~}wzg(Abn0LM zrXWY~%T!XY{E{-IT>8Se^gQymaetXU*+9#+K5o%;!?Zi+N30B0Nn2w7KFjBaJKBem_2K#5%-Ub1 z!`TuzgBKj|@%ggvfG0-?gU<=3;tU!GAVrb!464~{^=y#Ds8Xq0!fFj4YO5DMNyv_t zbki{oHT)KA3wNDfc`KnfxZ&%vQ^84kqiYuf!6i+w2fHzIOz`PyASbQmR*&!5HqgE~ z3a3O}XJUftNJ31E%U)hU>tdX^Lc#EEWX_2(R{58rrqU;sGMIDn-5#N@5Lptfj%}Cc z+~t3H?f2l%)g2h^-qddueGR#u_Y%A2E|Rjs4%TWRVlL9ox3xp_dy)S$4N0b--`-79 zIEkO}doEWB&y-dMDk^KJ7$MS=u6If+z?;GlJwQa_>I!Tq(-;$kIZobj(sr$k)vo)V z&HK{qKgVDq4mPLtNB-{{Z#ZcQL6RF<<>tf1j=t5lPebIg4(b(rtDBg0k2%in#}O{R z+J6p-g}+D3)y}mF7*kNO=(4Cp*<;e{T^7#3umSFpUh?3R@b-0|edHvNfcChDV;&xJ zSZRY(@)P_D%=TSSzz*za0!f%v2o#QL{UGw(yx+8rgNLV3P+Hpa?Hi{1(jmMZ3mf-j zBS@T1$T7V<7URRh@i8CV^K{_9gHqYC{r=)lHV|c>bs{Gtt3$03(hAs))vQL!Fyt2( z+cmUL)4PxJ`kXw6%US*Y_j^RIaK%cA1-MepS3SWAcSpHuo0*wSOJRV3z~&0v`=Gpi z2#w)o?U)x1hhO(A@P6;YRtGtwt53haxdI-U`#TwE;hK~5$K}$k$cD_pty{O4nO}=C zV9XU9F8Dh!3u*v2e59#Ke&x!uF}vDo4-jMe49RmA99&$WVu`qliB{l{$diae<;29r z$5FEhr#}YG`zWZ8p6G#<`+FFi$N0My zo!r|2zm^A!J;B*9u0Z~;Bdok3XImE@$ z;N^{!o63L(1x~{9-`E*kg{vKqT7)1J*nFh5F;NBPn8)~V7m0{`mh$sJ-|7_D&SIb` zAvP8x&$8L~$sZ5%6Hp+<)%xE|o`1)Qv`M`4R83x99+(-H1`1(QJKkC3bDH@EVI?7> z*!V*Kzq3P{p^pdI85|at3g3r%Icxx3f|K{)_FrLa1m;K~`y0z+{+XV|gvoCGJzQMO zM*jP!UsxC?CW|9OEOsyjlv(W%E7BTbZpZK4?yzY%W=}AfaDSndMF4-hB>@*KfOde8YH)%!?miV*8#< zGqQxjM{r>#>5y9u*D;SlX$2_(NW*{&U4OJx=v`maN1j0#VGgSiKxYN8&`;Ok$Dt*d z$NCrm^5nL*TtaYqC`LKIn9PsFe6uQZQIm%dXpInl%Efhc?*m5-5tzaIn9%zOvji4y zTYW&~Co~$B_VG{MgWRF`=2uc_?Pn!tu=-^&kqU&|r{YJLT!qic0fcAw_Q##i7)9^g z*#URDI2#xm)zU9RH*|Tyq!9icRkIR6j zwl{DoLgjM{=9i}0MO^H{T4I|orP&~hlCp- zth`}$oxsCT8a=-T(2&Lc9O(QDK+B*f_M78VQ+;4cO`gmN!kf5pV*%Q&<9DD8wK7`W z2{->@K1Fcc@e78a^!er!boiR!onLDPKcq39U~k9srU@v&e*Z3?MSz*yj;eKK>jpaU zs1C5=+j=v{Ft17)8jfnl>}iEvtd2EZg#i{8siCK*XK1*J?(^JPxI#k%|2EXqTSE82 z2BfGMk_|2qRLanlQ;tFqeSr0O@uD6rQ>#}D>Mc<&Gv6YC;2BMMnVR}(ljzG^zf7j_NI!ghdjl4-+P|yZ20y--QC`!T7*VGI~@R%i+9&XR4t*hf+qMFhV zQ?e9A*yUtq{uv(<0y=5*ntMz19a!qH+f`W_7Ec}3h!{`e;^2Ux&PN(eLbL*}=jiAt zGxIt+oIBrreS+d$>xbnrAS2n>a13vE-dRwE4{izw44U1BiBS)maySFrF-Y+O-ce2M z54ul@Ro&LMC>wOerJ6~uKqoH=$sac);i1^~!-lEOW3V*6rrD&|I@kVKbSFdB5+;i) zBy0|SUGje3yvfYWeD&%_bQaQ}WNFFzT`LI%1q>Wm&v1ZV+`Mz=mo~kahs}gVuc{ zY7N~7wCi3ensh`#Xqk8yh`NuCJd(iC7&#I50RN_Q_I83IutT0P8ukPFqtOVHD1p2& zTE-oTvacPp71&?s`-09&D}`cy%5(y30L{7ASDq7n1Rq`#>~MN^UaAK>FK=H@7OjuB zK4doZ^=%Gz?O*}_u)uDfv|ZVS9+zUChx~g-gC7X)eJOSDrhM*(gbDr)opoH|K-l;Z zRCuHfCuwLopEnszwrfkzvNu2eWL=F(HTmvryEez~gCqAiK;H5z@Zcd3#TST(7&f`G ztT72COr~u+W&L3AK4yD`u;%aJ8vv7GAQ?bf2TP5Ofj3B7>xSE~Wwm)H1wd_`W@M#m9e#vIr;R4Lg11*_R z_6>`ySvDARAlv{L*?|R;?wPD`v4X-v0%GD8ATkXt$#LeRHN>14OV}xbYY{Bp-t&7= zZK1T5e{T@M{T&c5EMRzJV#wg`#&s|e&*MgDCZHE_`?0)xv<4{1@|qegH7lzHNMSMS zazeS6syPC)eYto63=F)K(D;3DV4}@#Cji%=SNuNcU;w?p1>bT=53w&1+#l6C)DVx- z(1&S2{U>K%i-Z<9z$6O`ABjvJhONJbmgONM&*Ch*N0|3BrO^VB85(qO8&LLg-0_9! z=^t$chJO7z;9gf^{RuYP$aA$Ckg!=Ct7Z@lgh3l43-#_5b(q&LlgtykEGEZlbvOgb zE|ZawQBhd|P?@@EbCq@%-Hfu|_h^!C@&@`A&tqxw$F*aGbSUfUqlso!Fo5Rc;{b=g zwbbIlXgqld+jpbF`rwsPlE7*ptvzG_qrhR>1*>1t*yy#lGBSBQv5y%JFgCEwWObhJ z^``dmwy7L}L8xoyH`^g{^0xUU-u!#0w#{e?^U;d0hoqz=E-nE?Y9e?9DJau$Q33Ps zWRny^;D;Z8&^#I(UErb=e6N)y?W03FPk&u-Vf%b3*E5j59Uq@JVE}Q_Fa;rCh zcX}S@U~8H9!CBz0rSz>jGl~tjPbHl#Z%IjAAQeE9K9a=nVd@5B=^>0|n98)BXsj}&P=;RGQiIq$AwoY#dLHTEby0IxzSsg+zC^pD!6!J~v!d(F!L%$gK31`k%; z05tTh7NDk+$S{d?Ux&hlm4;>t&EE%+`Q2Fo>0{VkCZ3lS6f8mZ584uW%WlEQL@;s0 zqJ!lJ3(SfO+zPF0mkL5kE+X{c7cx*esT`ppj*E#oS#|L3?CRn#E9>sGcEPeTt{r!J z*FL>CRGQWo07F*^kGR3#$sp$S{L!OF)4&w~(BOD+@C9)PanqT=&Zgcr4`vn!zwb^d zDv4*T(W=cAj`x85s=Ni#_E{8J@>MxWZ}W?L?g5CatCKA)(7gu@%P>#uJiGwUg8|h5 zLOqndNF9m=f9#ufwXzi8$>+0SeM8f0KP2I4D{X7Xn#?+)XzlAvAcq;Kg_kb1VLl?^ zZh27)-R`pSP?PeGh>?Eo=xw=qGUwwkgai^I$49VtWzWpawE4rXj!BDx7cOM>?eetz zGFZ^Q)TIIq!}KYI&=PD^l!!5fNPONci2-|`wcnq2)+Z;2^uF4Pjo_@sY8#C}b3Vk@ z?$b->5O>_oa+m|ctz{pYy!qKWlILvw1BK>2(?Rr>kdTn9xFNIKLLFhN#T2W76-f-R zt$}faZ*^0Bj-F=ONDR6DA<(qd9@dl|dTF2U(sZxgJY2AW$VL3H^u`B4Uz*?NpfUsy zrun(K27{925@ZR$RV~GjM?kx@9B_TPToB#k5-b&GwtP4-r9W1zHm}%=s1EAmcU71} z?8<7HmnqaGlBG-#@ne0I1AhQAd=T|G00m}yD6RWKZw73~1rRiJM6tYl`BGYY zNcUeDkiIN@Fj+8~rQj>&d7J9-5NX9Q|AIE=PIGHCJkzueZnU0#Tu|%PT?Hml2wI`w zcH@Q>yby4hL;J|F5X!1GsxsOsjkK5Zdkb~)?LtP?W>2MeOSV1XH62{1N1zWN`%r5; zqNb}$O+s=TLKeu;QX8tyOUH$}O%u2ENR9oJqw$f*7R{O*eb!P*;Nr`h(z%0dL zV_svk;SkCVi@qwa5pA7=#L1|+Hhw64@aM(Xkxv(w&R??*7VZD#4uMh71F5*%@Y#&9_uAb(E6~%~5uA93m z)CleRDq0-Zr>eMLK`d0kWU>D)ZeOQbtzVrZt@Uaxw`9rewNf0RuhYEX%FS%nw0Y3& z<-U2K77#AHn)Q0r$8GId4gagP>)V4( zWtiGK#bl$F4B1b`S3UJ)CbbQ7CJV3;2Fw+5=$^yC!-c@!^gF8R^r7>zASyXengPYvs=CN zi7G#;6mE$Mxpdj<? zPe%7P8y7D06!qaEuwmV;CM%>f!BB-eKQ&fge{z(unxeq57rg2ff`^c(?R`S}t(Sv5 zWx`S9sv0(fwoV0e%5VX8PoEf)^ukiH7@tcAkDgqWOHf-?0+DUP~L^|?{*lw*TDNI0kj~cm=!Iko&y)QS+d!if4OMXOI`(!u|*!S=V z>8teL(B=75nq5>i%pu~^8o_ND3L+q(%6X4eW*sdUD({i4!ur@Ve0;@j=Bu`_Pj}ZF z%$b)lXKv;8vXW|DFPvMro1*J(kfEJ2*(?SAOmxM0c*p0mls)f1j`3i|xCUW`PI(34 zH+Jw7IDI&;P=0@+z3?a?JgQcDAV4jpfI#Eyt+fLAui9M|9za$ExsF&d%?~uZ+&g$TDn_fT_LooVzQ68nLa|Zy2K<+iH9&u=vdyR zF~n|o9ThT2R1%xbpv_UH-5K;*=H}GSGMS&Vw)TL0-0EHKd2!~OPl`Be;=%>iK4Ke$ zjP`5&c{(Ji>BCj26ltn2Ms_)W!{$_-2HwD(?*a=8li41+_kYb}1zZwnxSGt?^DMR` znonUuPcBN%L@roa`;mh`0k&TWB;Z${&SyoD?Mnp^@i&mU@U2OWqV?rycGB=2sSF7l zqPJ9BXLu@vV>bTn6T)x58w#JW4QR?+>^3}%oDSi>FyG^BU`{(bo_%C3$2us~u45M1>-cqtd`UHRGQe|7siF4$QtotTe z@8E{~F+L_7QZVyu%3i|?Rh^6-nTW7j_tiS&iMGO)Nc!t7g2QR`|4gsmzl*z%|6Xf6 zRDS+x1pI!bbN`p~ljsNf1;ffX?0eUYLY>8Cz;}}hYn%6PmflqN2%9?H8j{ zt&YDHDekJdbf|NYuKJ@<^y0OT_09Px^Jz=sz)XqGRg_aInCcoNc~9T|xGvK_L+xy_r(v>JFx!%pTJE!)7)tPy z4)^4X3qK5RAct+8vaNbYP(io0Ycsx)=A-1ymclX<=^=L-tt2Hi;1+!9oDhc?4WzUZ zudi%^|JZ714e=Tnhdu=^YOCA3++48uF7U$H($l?%uK`o3T&$l+wTQOm)2cahT>DIx zbjRy#P_MMMWb}CV%c5kI=4S1}8@-&W$WqR%jiw99 zxLZV|qwePw7wvj989CSuCZF$!yCXhtc1=G`zCvyjojTx{?zS8)mDAh7VW<>*F_t8^ z_@2v_uC7YXaQ4?Uix+)!$}1alT($?%Z08|iZN5rW)Hv;sS=={X zlfj*rp*Eq4ta0+R*fEVPIF8Ir{B zuFX`cF{Fv!)vI4G`eDY?EI{cIfZMG)9&Sc^Bi|&{ZK6`R`Qe0zzm3hq{vT|)tzMo% zPcKeA`JW+Uc@Qc`O_JFlPp?;0K^VpK%qnx{%t9q2yD_C+d4wdI#7-&g_MN-=Pb+Z> znV#7m&5T7qVSX{*O=1ardy)DAg)`66EKHj+i^sOiLRDy}Cs)dtSYEtQdU&_~q1`d- zW--NEH>F6TmWeB*s|zzR8A|JXTv!G|NB@~Jmaj$>yc^HRn~Ijs(R-_u_!9+vVXZ}u z-|Wy`iy`~{#%hnu#c{jv&!#-D?J{_bJzK&o{@78y)70l*PK0OzBzRXyKY=5i7UqJ2ZM5N)hxWxDa0q9C70jKySLPR%-X}$+V)jIbcvHQ-i%0N z@_3f6h{@MAPOIKLw2U#*jKEbkV7A*SU+x&Uwz6?%rm3-(f(x}6*5dnOFpV|s-c$X( zMm|lN<%OF!uP>$^ZkINt*9O;++>?c9qo9fX^iga*Y)l_%9-@jiY(|;;nm3+~>`2s) zap}MQat(%N`xjQT?cW_7p(iV^@a$WY`D`$Ko|snEN%f^XTe+;CbX`OaT_fmKyLQ(l zU*ok2Ctd$Po<&-6(kBtmlg8`EoRjvf93A#nKMq~x;pySh?;p0{Nvh@L+gGHWy&EON z`aL>67UdLLH1;AZ_9@{bC`R(`&L(1SN(oCsgCon?xPWT)LRM6v9BJz%GOTPjF&UXHC(JbBlAQ z7GjOYvhiobDJ`p2XHBIU3ds_O*_(TGqmc_dcjtk`BvM#(NvfIPPoRKulO;6IHnRtq;q@)c)Vh%*v1jpNtJ zGDZMH0RLwQ9-1m%cMkx^!KB|#kMGE{ZQ+4b_ATOTxZRvo3@QRhx6Kh=M>W z^J3!s-mB|lp%+9=HZc9v1J}G;>$!EG1s8U`kJ(NI7ehB{J^N$DI&OJAdKto$TK16{ z5>DHz`4GlvQ;pSwiTKR^e$>HP=*GkZviK8ZGi+)jep#F9?&xc`XyOPm(ByhOB|f;f z*J$@weVH^uELm_e(S1~rS9VDEW-sE5SyPENrR5~*Y+W021s~ElG~Luu%e*-@y(XmW zhZ#BG4|;1qr!6vuyv;F)%PvY=mrLk(L_ud|CQfEfDdq#al(SBMwRi>3 z(a@;<_R=(PES56k$hInh#L?~Ku07__>w^KXuKrdc7pS3Mz!)|CmXbu`Yv$9fN*z0% zx8vrwA8k5AH|~z$H=%Aw3`!c15;>J!O+QI|GHSb2ZxF%J3M=^4KM3M$Rs9HTr87OE zw$*_>j4-~veC0qxC?YMX@VU%_?N})9GADp`R~$f9C}~V;21t_5)(e6}5N7P@!gMSW z^8j>Ag%Ljv&+2e&83f(Q36WOZ1EW;I@LW7!wgaC5y^GKWnA1n-l)%JzVg090-U-#9 zE^ZF=^n^b#0Ci#R-uzV&WB2X5?6(WM&v|LXsSyy1>p>428tV-c^(`AB6WYE{V$In{ z-L>Hq=36E(Mgw|+dyA6g9J(FuR_}My$>q!UH*qDMXva~@3gh4I)cw|MEwbLD zRvnT?Mk3PU6I!@8CZW~t)muyjoC6?;6(UH-fs|jR2ZMlUIU>2vep%6E^hy}=lB8`- z6gKz9qcEFu&@B8FLAZU896&6}G!5ciX+>>X80RH&mL=NKF=2 zZDi}z>6UoSO$22o8mg!EKH9gn>RuppsK)!+%BoZPIZ0#dWi!*I!G9xMR(9akHMI%` zu+1ScZdlL*;mWzzx2HR zd_LU3UeTv>ec83{Ljdq`0uGB`I!5iy?CJ_%oFZzNqgom1hfJ#%Ot_RYPA6Q-Dj$g$bs#d)a^XD-3Z%fctXFB7+z zHKLeS`)q+a-m!PcBa~pHg;%SM7d$XObY(LmCj40jzC;XYJzDxeY{|D-Al|#;nviJG z!--JMA_wB|IZtY28IZkrEBAgmmO*3lS?(T&A5#R(i_jny?6gj_uyFKTP>h0MZrq5| z_I&I_GJhd2Syqs5aWr`+#?&RR<5GD|7-^{D2E?(*aS13;$)@?Gd5^YPiw{aLQja_d zoXjs3XDiq?$*lyx0eoiD=^!xT-NiHp&ys+}%%AZRW>)t!x+1Zr$)mfI_Q071 z#<`%8`CmegS3$x6Mm<#KQW50TGjAH1RljR$x7?Zxj{&|X%pGA)4~4|qTKUe-xT{<> z>l|y&Rb(u4r`a?}2&-dfv{pOpHdk-rCfJ5LO(zI?YvyRw?~!KSfYA<0Y~uw1zZ=nd zK^&$i1|(pBtVDc zac(a{_$9pG#0{^FEX2Ase{_Orry6`zgxI3i8+%OZzxG;yqBP;6Y`k-1q0)TdHmP=XrJfBHWxxlVpK2)IT^yEU3bzni~g^ic7 zaZMuavAlehGUbsF;RKUXrk8gsV^hXopFUR4wg131qhiBmY}(GFx`#P30_-{)8zZCBAk+v0kpkTz13Z9FLudo$RHj&B8U(U>2 zk6~<>*kK1Kpg0coll1z*Pq6xOm1qtJQ`J*U0iI%p)s2y*=8TK3CCWc*q&DngPDtZb zfTyp~mrSNH%wJ=_xF`*>7?=t?f{epI$+5a+#;6-Qzo`~6)^mosN(q&*+B$x3GTXVa zAc4*&r)`P#uIINFX`iffD)4ZKoWHjD_%ZgW+b+g7VOdqx*l@Iz5Iv)Xbdz3OP3t0q zUQzBwt?ltsH^ZLOQyleX!%^AS8woQ#8B6+PpTg8eKxP`!O znR@lfK2^&2%^4~UlZ;XhNutk%sR*pKleQfa8y*>l;iRz-xK?=DJE#OQ+-{Wd<7ZIS zT8^ebca5pVpGz|?@%p0bwk|h+(FOMO%raUSW~zytn}o)-wi2?`UXA;JnkMGFmb{y4 z^y3(Q(#=s3JT6UFDO9sQVYK)tAAj1=%6GR!kCzc&yEG z_>Kj~phe`*WLajL?sWO!n?KIza5;?+EzhjyA7^z4egkR2EkhYbZ%;6o> zASKGa!45QP9A46dBww0$mAN1dDIoTsPZh~zqPI$Stp=HO!JbP6MQQ5SvFT~*hpIbw z#a_8oxy0ug6HN1VFF9HO7xfe8c2cAY6Y6@>z0^?)I#edKQ5C15xI7%sFX7@`L%TMT zUY1^z)X=`LkM?CL8ZK=Pa8fLTB9U;$jB7l0MyYdp4xkW_uG~&6}t(t6|S-h+~7jy+H1X z>!yf!7)Y*GJ`B{l$m#~4UM!fX25OLOt#^H*9T+@)!StL1sA&;om!e}~TSFsBFFd_F zGCX46Bvb!ccxK~|=ky9^I%L-W__!*nXZcQgkCe-ucdONRC39Y4;mTn%u1QVCh=%f` z;M@VhaX%5QVNBK5s!x22la^S^3zIwPHcZ?PSnr{F0Bss}T`}bPACBuPFshw-^jLEQ zTxvD<88UUot!A^omZ;w~q7Hz4yw3(@m`x}}Ek?A1T{(S@{JZCrNpPDHrbB5WHakAu zN~ydJ-6GrKgGQcP>xVTtZX{5aI6G(0)VFbQ%z46P@S!BqtQ(iq4rA1yvTu`2*V$Jw zX^$4l=%!P{v^wqurv4pvu#kBIqgz$Y(E{U(ov0m_Z1_IuR(T&-bt~}!(HaA1O8w_@ zTG8m_6v+&7u#5SP*Y%>?sfr42H1Afzj+#%#LH+Y#PcP3?C~!)xp<(jGr9-$VWGAb7 zar*M?j8UE@Nxf|{SAfx z601jQ8Nl6npF9zs8OdsB@3%=X9igVCj1>}Hn~e7T6$3Y>c}6?YY>E+w#w~4pU9dGaDF_8?q~#izHBrpu_TF5IkAI89Ym_3$ zW44+TK1b)caB|gQm|TUVH$=y*4k+5{iVv-CkTIjIMOaZ^*$hgx*cF=PhB+3>hAF0a zA!@CLQG&u8E0gW6TM<@R&X{LpuM3GJ_dtqH%)|OOBm0wer|~jOy`t-4Ut3)CGADAA zt3aH-9_Hbj497&{VKgA>1|LUV;{Y4C&9H`-;kNQ1R4d(vgHoy}Vm`tHaGezAL~aYD z^rY>lca@eT*ftWnh4Hwa@E%7w_g-r#(q%^SGKQ|pq ztC=e)hN>t9h8+)5nw3{}h%g;0?xhOr`K-uA0y(&Zvl|Y1v|uHCHAJS0f8gk%p!_ z^~LEVMRY&y$qAIP&Q73^tJC|sj|}#e?};)qrn|fJLEYO~I`pYS)EJ3-ww`0hy3KnV zDNYZT>=iBRtnCR=xl(Ui8B*fgIZe%R>ydWjQt|9b78k!y#f?`Bd6gfp=WM;j&xpygyu#i4#=KzpW>EQo9MM zXxb|^5H~6XWjKqL#CVEQDQv^+LZbwGJU{WZ*fd9F*tvMb4L?qE;Fv~yd6c>PSX1D@ zlVRN9cSzOn!9q@nQKAE#=YFU`sBX6S7~EjZ(wpar1MSYGf`M%sq{e&@Mi!R7P2I>T zYIM|8aOWbS8$y;SC8ekiC#mqk$-2gPafeBK!zVj2*qyV5=augAke#&zKhJRfm*<6d zlaKfMl;pHl6nj=isMy-#&4Juepy9F&9KuFbFoMrmfLx*1eL++E;mX`=K6FUffdu+7ME_;^#u6EV1ZR? zClpDgaWC$jwYT?9m4DDeYh<%7OTZJyI`|?vuEEgAEqb14K;X@@U zS0?sBfQF`)s5o*S$q5ok>$KZ@5Kzj?v*N`)6gE0r%hM zKOBj)bLV-wxH4H{N*7S1el7#nb5G`RySo7p0Wc3&11zfz5M4-OI;D56yh_gS%@Wt3 zI0b8p==(c`ZvzWi2%i)h7AokO?5V^#qmcvFqpd;tQ<*}=S7lg_Q_N4yEMEIVnVz(n zq!xOI-8XYH5|~@A@66W3ew1D2dIbrRSXK7emV}?8Xnki4g8(^^JFx)m^M`s<;Fmyep1PLgteu3Ocb&o7DoQK_N z=Oag&La}q*K7Hg=^`HP6YZBpPbvUmkpD9VD>C&>UtHYmF65ba~o7!=y$J;&=(U5%S z{N3xWcZ23hf?Peg@SZ$A?xuLPp8u0KLi3y;F|v8Ox7$A&Q;hh4DYcQ@A7lL1L*&)e z*2bJFAR8XE8|4SpoTg|)eL-J-91K)*IF~lRCUUyI4xO!Dewg~QRa1}>(LN1dc!5#vWCTGDW_UYH@G0}oZIu%H zy`yaP@BHywB05*$m8w28VrD65ej4jhAsEUDb@p^c-XdEoD9HWBXC=gj<&-9dWNuQ? z%2I7W&)oU8mn+!VmS8=fb3R_^f2YHEGOa zVzpvqD5q1}EOvQq8LyK2E=JCpxfa@-uV1dI0Ca05(59CM>$7h-*>LK%+y>w1d-BIXo~Oi8gBp6k+9%tb37e%%)^FqDiJiC&<)mm* zfp^5$zW2nE^5lg%Yy~$@ck+R@t8h@(!^~v7nD!sW_ijAlCK`knI?+)-JN(ZRSO3*>XFqL8Kf}W3ZI;3~Xg*H$D6e z$d&p}E&POOrM`Ry5p~VQ3M!tc%31!$wZ+h`bocw;}{3|8{&!zkBCgay0 z4)(I<922?@gXmh2#(70K=ZuU&0xUe>;TNu~5d6B82Fa|PV)d>0qGwYZc8f0ik^Z5c z>#|Q5xq2|cZ^a5gp3kpSMWkOEe|hVXQ5sdJ;6qtguaX#(UIF(I&g^?FrdhagXfU}G zt-R0TK$qB$WmnEgYFj)BegCn`gtV|Eav-&4?7$GH-4WZrIFzT#fu{s(tK057c+g+4RA=>Xwy?DzxSjpz5BThcwh_o;t27%Ge%$WeEGMm-1y@jN!s>K1MM{$=)^=4UDg%ktQc|^O z;zw9sKFktG4RyIjCk#oePRPU}h8#|8o~S@cBSoa)gAY=p(vceT28qU>P1K;Of<(Y*+dTN0{nvP>!~ZYohSYe(SOr1ORV*LiAG~mdWL*^vp;ns z889TkzR~jmv6l_crLkMZH0^e&9oEA$`PPEiouuSp_m`#sg!c4SnK37@sEXIlH4*Zp zHm?Zfq~qK4@U?o#M|r8*qB((A>MIr*eQm*RM$#Af$0?F;9!PF;V4hP_pD4DCos#>y z(2K;xQlB^9uhN|PML^B%rT35lgS={fN8KE5&51R2t92)Qf$t)VvJtCAD7NDpz24~P zITQp=D9nk}K(vvZ($GB0+Q-SlLS!5qT)qeQhF8?b)7|Z|geAWDj8-|nwwwdIE!!B> z{c&eOw1oKqZ56KU=y9uv_Ra3NrI0L5+Q23)XQ4qi15Xw+yV(^JNckh z4^MRaD-M(gC=FI<19_hDXI0OWiBVEJ5!i)Gh-IAhsIS-xZn@IFtj}KbSXO#}&`GZ?x?_4bU6U zyv5F(Xhos)^BiVRPIIAE46S!}&TVM#*2+r72+7I#Xu@TnZu9hZzB7N; zh4Oodk$r=roY?N7@2qI&Qg)Lw6UI6RTZA(c-m7}$rtBEI>HsCCc=Qtr(>Ot9RPHRX ze_rbkQm^_xlaw8C7>~Q2Ya8Lgg7~qusup|vd?+SJO+%|U<=th0?A`%&!0v*?@c0l; zZ(HyN#^AF%bXLFM-Df(nifhx)d}uHL!zK(w;5u?|*^zz6yzHbV+T(FQ`DOm@3?U>! zJBXtq{Q5|=4>$Ki!K;EvfbF`TWtB~&qY23j@A@_+`V{Sn%Sau)@Dp;XkjINK?10#GsjUOSs z!H&sql-ukBd4!&{8C*8T_A6Ouh4+q-mSM*>J{?{ERxw$?*;72viX|gPGJ3e>$|oXp z95%`C;@TgAkE>*8x9V!1nnj?*M2H!%Y1;?&HK(^QiC@66IMpOhk=r(HL`DjgEDckV z_zWMd1?QhV_uAn)nuETfXlc5frffuES4(o(-!Fz?qzMYAif|H3q=!mj;yqF>P4VOn z+9>*CkG}qoJv!15^BZkGZptXq4#J0Zf)l;I4b%JdLftV<*WYL1l8ZVApo_ z;3wWNoWfM)f!^r4xF>J5@0X>5x&Y=W9`x@8><=A_yEcx0P=p>{&12s8Q)0?ko?JP$ zRAut2%|~L_+9^kMA1z%rJsQNP39!RxKO>FNijr_a()*ln=%7YKdc=RwSzr0%!4(l1$Qn zJmR6p=+c{faG6%t;jXwnD@^oc>Y#eP34od3Q{mDgg1u{S7}AA z&z3metECB;YtNkHZeIZxLPT&kY^qN`LWVOBR|lU8vBU5-Ztpn8+j;C_5Bj^R`BiT9 z9&*@ovCiX5!F-HL4+HbhFG0H=J)+e;l_lkbA!j~q#b&P(X0AUk@Xw4rK78dgBbZ(a zvvvi)vvZ59Qp<)lsO{FsmQ5H#nJsKHZuHDmyoub%shB=PXko#- zseO+ae8eV;38I>V7NokmQ!x-v@edD|M%T7y$jLV&N~0hmSf?ZUK^vW}XqW4>#&aBt zO`!;`m0QKjDK2xe@BWYP$Y)~XIb5P$S_I0f<#)Q88fO0yV ztANAZ#mJiB{wKTx8?YmUEO+`*&U`mMNt}pxmZ4Wu!hqLpXwQKV0$fO|!P}nJi<#V= zUkSco)WsGM`Ye^|(Se?$t%ynJAAR$h`64J{aL-uzljXku%8YjuE4uuPy7u;3tIP`) z!u2KZ2e-`g8TSC+w^F!Gv>!$4UBO>s`ye2u)Mabr!;8$eQk@>9+DK`G%0tN;Bj7h< z;+TLk%c%193%Qqv&!raXt*iZFG-i&g=$1oVB=%enLriSUp}FPgs35nuZG=Kc?#Z9HbHBwr)%<0xo>ti#!yWq$v9Z%5oX7s3 z)oOkx(6dY4d{@Fx)L`gC4*4-yNkxrV#ZlCK$*MHL4(7=qsZoTWf7=CpEa&(mcAkorT^zKdeDH@kT*=AT zd`aVyKS%Fq zQOVF?2~oE;<|sSux;r}yi=0u>?!&WT05we206{N)zH>HW@hx<6;Fj!y-ii8Lyn6i=lZ?Yf^n4k1$I>i@CM9IlJot-C-ZzH7O z^{e{l_Q~nky!S@K_ohJuHf0+wI)q_UuT*%3el(XD-VTA6+y7H{Z$l0G{S&)iYuP$b+@OauL{>G=WuzBp>P z{g1aHec%sLD!V!Q0lC~UqVuj;G|A~!xfb_29zC*RMqBiGsAc4LT;mwMBk^)IJ1NQ~ zU16T`CY#s59(Lnv z_4FMUajROqW%2JRmH&9(d=bE4`z6u*^hiIQKe&ODZqN{MxJFN|g!`}~`G!Q@5s=Gn zEEFcoQtmONRgnYwYHZo+ZkU*{J#>HSC4MN0IA@k}KDX*v#XQD)ya{+p;0 z^37H@FaRG<|ITLdQg521xVF(tAYr}`g=Tcg>$Nia@rsb!a14cWbHWGoiu3s2-Ct!Z zdPy^TszDe`fYH&1gw{#3asVPl{9x_~;6iyAN+Z1&g@kp-P|x(>KM3Ae{nM(PHzY2r znsa}baGxQ^X^f@A+R2==uaeeS`&e(7z}V;Sx&nV~6~U6(x~9&83|e3Q@kGZ@=rSuJ z*|O^I#SvPylKJT0gLQ6BI-)dculS$lctrkJhV-cl{}k@w{UNHjB{>wc*JX<%emDvL zp8*a71C-7BNt%_RKZfdF=H3n23i3E~6zx0ojuMc+n~w&dT{%4)H9J1l zUfGp7w|Y0bhcayQO^Cl*7V)pwYdL&x5~D?Y8xFLa3j;vS{xc2Mz%;;XirMCUL$mHk zHETmRiT|fFCVbs@=Y>Viz=L$WE(s2geAh3o8q6hu(J#>Kby0o?1<``Vm?;By`{ z?!#xd_+%2Q@Q(yz0oW6KgW{OFtuMjo-wRO>*=rIYFKWBIjwI|2?)%B^9(`vX5U0>p z@IgA65&^U9o>%c_yP;=|MEFLy8Fg==OwZubIjYFt-Z%Ri>S7@!lG5E@HfZoT$a`8E zuNoS?2~O_rZ7hF<@JaE7{d>aHNPM3!4<&WruYVDq`ujhW1|n6(=wnVAuSbJE9gAzv za^C-2a({hAuio?ju7$tARlCU_5b)pMrszL0{QvI9ZIpb*j?l^N>)gf8Z_inHkJ=ch zEz~w>Fge6!TDPuDR!V{IfUmu1;v;R=b(H(^qbF#iM^|9XJ3iFQ!uJR{rqtB?S}~U3 zz>{;ehr^BFyTs?!j(D1yvKom1(scoA55%|?z@+a9oZWiv+> zik5z$Nx2MKx%C0@NA&bLsvrK(Zp?ahFI4$HebDHxCPw<2GOE-H?6`(^8++7N>@e8y=j(1 zZe7D(TFGuywR>zJtMVKhW)dlNd1a7xMqD4vK}-^UJ9wU!1rLev<=?gLWl{_@>#X|h z;}n}H%f`Cj@{@sgv)^1VFdud0z8ab6Ib~kOe;$E1;a-U7>w|HSq|3UV&HkZ5dUl7dA@t z{#>QKuj@VGpZVj)#L0T5FD9aNg(35LEOW*lcK7A753aU6XR1?Qye1OC%W(l5=uqzR zA#?;4YC_3QT)$Zv8z#1_51nTRo})^cV>z1A&mp_CyKVqg*=?-%{%(pP_9xfS@Fz#~ z?{ev4)qBUy#Dg5fgY5OPT6QP37p-cuo1W{lYH52Nwhh{>?Dz|sWlODldMn3h{64=- zi;J{fK79KSk5le4$jT0{dXXk@6NVQzBx=AB9o?oh8r!G*EXj?p7U(#f^s#49W-oMm za?YeBz0?+84`@tF95#M_A;*wAV^aJp8h4ZXGO`(Xf`#~%oY5J2$HOFFf~q7%X+!I| zR@cCTm9SW=@|~25A3t|^Pc>&y(CMw=$l-FZQu=nE+68c1h1!EOM#Fj2;>t;1h_eWl zySemVE%_QI)?n4`7`|~FB?W_}QL*jg>&fIaZ-`!j@{yie!J-jNSXsj zVvrz9ltEOK-iIGNL8k%oilF_N$MVNiXFD3r5a@EpOfDN*z^S{@f{gUi_Brhtvfi@# zzPbl;+$8Ne(yQ*?6YDR6pM=O3w;a^5Zq{YZ&Zu*Q&?&PI3_N!iIM$!9#X!PTWGs`#3mwlabJv0qxW&golX{{ z4)@g@j9jFMji2+d#(!+)xfRN34QjKQDGS~1L~m1dfge41eBFkZiuTR@jUXV)V31q= z!Q_K)wpg_ti!gHeRK;K7hN$i?Ly=lw@U8O)5P>H`+lVr)`_HByn3yP6W1uf#t6Ntr zp}wzt_yFzI;ds_RLMrPv*&&N=3U2(+*U2UFAYkos+nG!>@3pEJQmiDW#r4`t78wW7 zq2zE_0rsm3m#fE^UxH;;6^caPt`%O)jTD| zUb-L=){fx^ME%`$_8{VSJ2ZnK zHQu66UkMpyzK|*eA=R;r4L&)$Qn6@&ZAZB@@TuLfv)w(%iSW#e%#cs9-e@jCH`**L za#6akEKw64;MaxTsrRee?VJziVio|R`H8h9npO05iwCICx`|!cdj*Fm+=P8yEicwUbJl3RWo`{xV zJeh7K@+=+I!_zj%04ACpz77k$*1Gow|8bOHf6wEcd+!jDnFY?#dT7_#+9-FC2G*SM zsZ8!+V@VrjVxO8vajm01g3aOyevIob{;~MB1y+w~-PWU57JKW~^LbqRU@IjAWVL(L9LT6&2_4P8GavWee0M zidZ7I;XZxHLH)!rp_D^n40NK=fcrvkp1B}%{~aV3SN^y?Wn|$~y%WmT6V*4nx19S* z)vK^jgawH51mP?lskvwE0aqG4hd-YWLc`<_Q;br~S=7p!NfE zPSzVxgXzJ}!fYS)DJX8MhYyrQ9%=`2fEnl8QMLkeZ3aEIWC`%wg@n+%%!A$b`yN0= z@=hs9$G4^6Ty7W~?#=8w;dzL@rOi<1^97U4F?U%@^m?Ex_4-ZR7JlQFmdEi*&>)6pLa-H1#qgX-CkoMNx^jLf_5~(*6NlV*3 z$L)Blf=WG#6KommD4JDU`~iEn-Qu$~D<6>8OyLsCOL!PT<;%cJ2uW<6Ep>M3shK-P zH%Ohj#IrrSw(dd7J9kiw$TcJO+Cz(FEn(intg6|9^jFK~8B6JsX_@2@DXG)W{gcur zg+s+8BjPMr5@(08r%^3oo;HHNE$gds0%w~=82^^S(GJR|03n=f4;gf?{mR|OWj{i@ z;?+FGFF`)2lJxdjlAM0p@E-jic0Gwbd#9ACpfXl|wpl?>cl6~hPD?r=>Q{XfGJ~+04mRZuDsV&#p0Gfp~DcNhRgs_?FdtjdPVT(cAL29 z!qTKx->}CM&Fi*R(pUVKUp(EsVQsUgmk+WfzW2skX%J#2Fo#VRgpO7`8+e~l!$>st z2ZrB%Q7M5OUeD>KSN05PE4cqBQzY%{0fx!u8=~_{Ta182-#2D+tUaTz-!p5))kSh5 zG!4*WcwY+g7OS(Gy^?!npGWzE(x7>YOlWcPOkZm~W71M-s3K120vr1$nB+A*sqG6} z%~z`Y9ES-ycGdUE=5&Ixv^R=IJ4DQMFh4A=;{SY_y0l@Wzu*5qR493&jny!%hs3J}t4(qS$}6Ud)WOPzPb)yjmmfYL(<-nJxlgHZ^2 zzT#nc>Zxo{-qaR8)|>i)zDR>MsnhS`X5_Um9@%`{e1`re#EOD4#q{OFwRKLt?h2M> zg?!vsXxxM=;07892Vq;>%agsyHDB|mQNJk-dQ^O85PE4H%h;tQU}pilQ;&wd0roHN zBU)3U<(YUfBm6N+SsyEn3B)VhGXZOkeBwIJnLQk2k5e8-5V z<;6j6LRRYrb-(gX<4EzlGZ)qK){d$w;$uTijq|!MJFIWo#QQf3MLn~Yr;uU+Iii#X zaB7ZW%7nShlAlLu8ZnEvSJ{wlo%)xsFm7PE%+3zBE)k2(k3j@7`;;eX$N{8VZsZaM%1&FIe37ZqQ zw~B|)=Mp846WH6hTt^;0!{TA_(-F$^2%?jhCLp};H$`(tat^oPFq%d~E6!xzOry^t8U*8@+RSvA~*)Ui;q516K{cUY$^Oia4z_(b~)iM=}FG+qmb4B1$cf}*d4ZQZ> zKyr143AU?;Fj^W)io4NXMYJG?*vXMdQfS(x|DBtwtdR>SU^~!%x+P7adipmWpF2ix ztVhdWLrwlx3-Zf?{sCoSXyrnWk|KQ~ryQA&nWogfnP;>cE-cXiDur|fF{T%@sV(8s zmyR6xY`IFtgm#SWdRONnUfCQ@!$V^@^j-TKGulhT-)OchVSh+KHhr_P2QRW1i~@Ty zXvoe}67feM-TOX;h#KW81yV*pBxT9GEpmUhU9X%6pZCnv9ISU;*dl)TZy)^ZjU2j6 zo$0BQqJP-E;=JxlxABHC^^WbHFvGcuSb|`7IBW1-rB+hJWp|_h7*{u0it`WEc~avq z@fQ$M7v&6tm#Y{U@e`{H6J9Ju+Kx-Qcui8yA5Nle$!Kd#Sao@r1!LvNo?Q2QPD2t| zFdW~!YR(9YhUPv*iG z0Q78O%9F$NKBN`_i~K__{JMf1qX05K|`NXWfNV8 zq;g4_#6Oyvr}A37`>Q9J$)$f5-e0k_=OYlwzy>7;eCY64xW)noaOg@32LKb*sph6y zHGZ7Kf8$^f#e+Ggkm?!U9tL}QXwOX34E|&p(Koe`TZ#XQ|LUI}JA(G==E}3h@bK3D zho~%*#Mk@#8m{QyR5jTA*<$+=stP0BdsiyDB8=!}f9+Si-c+wVSAvNS4ELe%T+^lr zQDmp>?d5YH`7sS`51J&7za3x14wu*k7BchS2F1&xeOT-pN^YDml}^`3I(m#BdQy@` z)wPN+D!vkl$MjPV)-%}nL-0$mK_QDH_-Vs@lw2DCe+^XM7k2QDk3$biZ zN&DjqPQCf#1ulgn6JX0WVH(Y6K5$j`pk;BE)gjLDv-S{SUy@{)nvO#x0c+eR>Vu=l zd~V*IO}pjh2+S#0W^z&DU2oBR`@M@OFY(?nplpYTYyH%Qynv`}Po4HMKD~R1sPsYR7OBknx`IDKU7>MB19;3zVE-lnXf$?hv?8EF_ zid3zS)L*o_b~F^!tzFALe&<-*P8QM_?d+A$SwGySQ)33kl~y@>te=#@b*Vprx=JFngq*>&?tf6u`J z%$J=_jgRxE-+`OMJLWUFa)uFS=}Ij|d+)Mrcijt1&-WZ_7WTxq_pS%3rXx$~^$en{ zMICo07gm0yG`4a!cDzS>Wv6z!Yf=uTbpk61*uCpMa9@|2MAbr3M^)Rh(Vr?l=b4J* zXsA8!>gedeQb9Ue?9q`XeP$mRsw(_{L)~7`ehR>+S}2n>hy<{%AZOzv+ZSHw^Af)C z_t17pqEGi?j}U1YDdrZDw))WlquQ+ygJW=jq^I9NRDHeLmll|1u@R*`OcmT)y|*9*%f%dikNfZXeruMJ4%!&I^W0z z>rpRGClUVA|AS~Xg)z+y(%oqq0BO)=6%JQMk@?EJqEDR5zXocIU7TAePbgh998w?L zf78e2G6VmxywUo@G`JbjbjAv#`&PI%;s*xR{K=U%1zDOJ{mDJ{04mCHaX|j>xz6r6 zd$xUc53Dh&T6yqk-5vq?%l)mn1n1EEtZm*z!_}QD0^r;VO`z_yez~X{=3CO!9+oUJ9MoBt#s6>(l`mAZ49fjUqrS0Ew$@Q=;Caf;o> zv7MMwK&N9XH9*Y-Rqxn0_*w2#+40+55)(5HWTIM?$CvaTFp9hL99Frfy?tf7GekLw zD;{k)1|<$qukYnRJDA(PT-g!bRyTXqH-9mb*L1ds+>kWc&;Q>r(6*`OuG{B+g|D^P z9xy)A8Jljog-V@{>WGYQ>OcoH(Mxmq-4`B?&sAy#eWIeKu;Shb6;PgNjo{r!x9uWHvH%>(G0It9mOss!eaKzI?uK;q%_*uk{~91Y=Z|7H=C) z5_<aE3Z@fcSYWT%K-fSQ2 zX!b4zrq-m9T%ZGY6!{N9^B3lqUGe-c)Axt(<6Hhm3IApPPO1M9M*pAx=$zFZEyPZo zIBZZ%c(^rQ<*675K#;13!6b2M25B6`iFLB8&tafV2=JZQW%dnv;%(SP7>gN53? ze1G}TiBkdHeavj75%iqcYYN~!tvxOF z25p-9^4VWr>q-M?!;%aZcWeg5Zq2DP^Bg3Q!Ia}d^C(jhMf*TMW*@)9t1n(~DkXRVuyUQytE zf`q^DGN%0T{%KJde17MY`am(Yz{8>ulE#YGG`%7E2O4hD8uWYT78JLp2P3xztD|L? zAucbjyhYPXh-0Yz{r?a4-ZQGHuX`5-QBWz0fGAZ%6A+M&RFwcqReA^Mz4t02T|m0D zfK=(dgc77l38D8EdJR2<7T|1t@B9AmId_bEznpWv{rSLP5cX#6wbzlIzVXhF4(VSUT$vS)6kGh63|(EB34@dT<{0pLcVPgS zYbM|}Tk!r(?(RJ0T{_~^S___M>K7Ly%Q{4Lf^0bPu5{OnhWnWlTG>Kw9xk{;gZh(# z33Cn?(zr$N7L7P-J%||W%|N;3W3tzI$s3qr@*m{BMHAP>$eG_gj{rve-rtR*DQDae zqPv|H?ewBl=slN0^~~X?q7siY{!J6==0ilh)dOS$BostkGc6i-OirvV0oX3v#I`OTvz1s z%2)h^>du#jX786o;Xm`{0e*Z#8IljN!p@2N`y%U3dm}HoF5X?4nN=g1gve8VTuuH7 z$eVqO!4^FY^@iq19>y_B)}gnIpsX{?6zmod<@A*$);q1?S2DZYL@%;8n=K}j*2}b3`4g%fQ%TqNDkh+Qm2|u7PF(3BD<#_ zYpWkbN+i-+*~dR;ofnj0K>?$B`q3Q|*)o#fF0SxZ6DeSml9#+YQ-IUvC?qhn_ixyh zU2}b`Qh~QY>CU(9G3-}o;cC6$oO4CstmRv_C1EcgCTkFwe?~2~^6(1=wV@*=fKp=& zJ#Gz)$-nUB$I*mCLSlD_Z^ahd5P|I@B{bz%awJ8_--lm}Eml09ntZN@Gu`_0W8O|tvDDUX}GfCy9MWg%ztjUDDTSM`iNQsn; zSbd_cM;(7LS?j}#wUM`Cw>Hx~_$9d-Ouo3Elp-?4j=> zg)O}8>HWesMM{r++21C5UGRguecYLrHIS8X3u5@`Ul|_SJT%Dm^A!RGb-S(#z>IvT zs<$kBHpL&8u5+7_L!vr3YU@_pnNwx=r{sz0^rcdE(9B-Z5&;J&i^-x8y9GpGH|y71 zp<>PQ2KB&AX2XQvO9f1nxxq>Im!|Bp%$~C^%)sHx_jCfTUkOexjX1b|8d%{@)a`m) zL`YpyGI588()fVJkmxTyvF0{91-{SMwE|!sQQ*@mnZxi>r=r|4wL)vzA&%nPW!NH zBVQxKyOZdgtp=V0q!DO6Jx0J)`^r*H_lk1*mIy7+kNSu3m2b7`T%mX`j;&Rn987ky zCTfn>3T(DL5q(N$kZZGGVt*^#I#o{Eky46N+~rPr>9G2mV2rCCyALa$eRmNW8>a?F zF>w-^I=zEuyuz)RpTN8uoX8{>R8Yv`vvuu-dYmFEI^{|Cb|R_O^UaHtSAIJH@`*WD zsZild?qE97A!UBn7B&^H0jyP6if=f-(ujASCZXbI6a|^U5pT1SZn*ig>JMakwsSce z@4yT85}c;*Y89|7as5yJAW9K%w)>MQ-u8F}s$NYBrdMWnzRU9@2Rb?>m6S){*U(@K zk+&+Ow~3)a=e9fi9r=(B8LU@QvH3FPx=?%CmOI4xzrDptp2f*3Rv={EN2orh?GYOg z;H==kVE+lQjo8b>@d!zlo13uAbw!X67#GBolVwPcq z82QI;syy-T{D!~+XW=H%E?t62hVI5Q(3de-uG~rnHpX8=xXC-McTR!B)y=Y4VRtv5 zMVK5%-5aYj+L%$}qm}B!KDRRtb7l15F|u)vxC!5gtb7pGhxn{F7+TldR6CDO^I?o+ zir;U(GIEO747Pa^`H%16RCD;9Y&F`al>fHQ?^9K+YlI!k4DA=h+t+=qd)KV-3xyFX zc{0WDYD9|L7Nu~|6SWrdb-%t&%i1ZrQ(h%bwIPLSWj^lLe(o3jh|@4w{qx3J!5*pT zUYzeAMo#bc1K>Pgmd#D-IoA@yI^HC|mu$rG=FXy{(r0Il=+*ao`7!)Yyut2(kPQdt z|G|(N%9ONrDk{>1kL8fn~)J;XQI zpJF`>-2AOGcRU~kV!2RmYz~{BzpaX_Js)Dv{2kH8%=j$s1EqMHeBRk->(4Jh7?VcO z5Ba>M%}Eu_056c0wTP7rUihv#O6#{Ic9zS+bv0bMNQTg!QRQahsq zLPHL6nW0GMf~>zk{8BMi#XGbS^g-!K z^31Yr^?BEAy9d(9e)}IAo>oW96Ib)8Z~h|>5Q9ed$zVA?4X4fu+hL9&aIm7Za_oGy z8ojq-sZP=Jq)-w@W?K`JzbaZ%MTs$TM1Kjxrw;0}=xbC`G{VEurW;}eDzE~{`+gI7 z3QBHFIR6EoUHuN2Nsd0BRGC|ufA-yZ@x9eE7q$Q^_oLv7j@sW5@5TxPW+V^T&xnXzs)!!2RJ+>DO7R+@AWWSt?I`TSgRHV+gOxQHJEhU2ZBjhh-(U_K~JZV^TpJUqEV zHJ}{<1*zI5+-9JQSXXkX%N}~`*9Y_m#4%L>(3+t(;JXor!@o9zngYeECCcTqi&ye?2rnn)`$C+shHVUHVt5_@Yrc_c-Mr+MN#-4ao)U2O( z1pb|o5h$vqfIwnSAPv&_FQ3L}2s1zWzAe_O@zd@lO(!@CWi_AmY>XC*IZfurZ*eYO zR%K)@Q^vKiaGQAM%r@!8%w-RKI@Qu@H=^AZ7aM#}c4XYkQDpjL?&He+>JkMK*1dwK zT=ze?3;ceC-=H7%eUIOndD1azsO}9pskc#JqbJjM-mdBXsPq-xtP2nCy{YFqHNi`H z1qE(9Hda3(j}{@2eM7~mCXPK!rcr6AReqKFf~@^T*n!xSK&0JvdRi?Ism7}Py>Y!` z>m2?u$9klnc_l`?JpymP6ws-u1cK0$w+bH5+Re%X&>%R4Bv?cQuDKU zw|-db!2(+s7QeVhFv~pz=<3wVw!za>COC&yN$zC>bqIj{;C8#;REC;Sa-ItJ?hU1a z=Eg0bc!4u&JJ+7g5&U)gHXr~`ZrS^_K!vN7$OO>gZ60_3jS``__tE8K{vYphq(Ga{ z-HYY1t^^NT-5x-ch@SbxB!W4oxdn)oEr*+8Z{P_afR3Ysa68HK4(*iUKeHyLL+WSb zzomE)I^e>X34{T(BLBF=fT&mdjdEI7h_ue^hReNB{?=buJ%eo*t>B)P(3z5P#ik<3DOzv z{D#Nhn2)8at8XG!1wFU`5USj0yS>v3H34*KR9K8a#8~kDj7f-Oh*&?B)cc1Cg~q8Z z-sR;P)D`{ab5T@Mj~}W_>8)d0W;4<}+>>`Ulq*SX-rQ6ePdjq%0KboOW$?Vc`i`<069mWFv6En)Ay92iw{6c#*wu% z1!_I-9s$Jwrf29lz7L>)cq&AtC^qO}mhu>Nv+d$ym}WB1jVBg)3rC&6D9+9NvFj%j z0+CA{7q!Pgae{s_B9^MpWuUhrPf~Y=emzRr4NTNhMdcDq`|7yVD8IRzJHF}rSvfEn zSn#oWN9x_#IA0p_{lif%YoAO*3?9@^6jV~YQ%7@L4X)atGJ!A=0y$m;=>I`B=h!Xr ze@7-sMhN)L344p%7ln8zkZ0LHfW87|@psp!?7O(XEJ~ZxE6@%zUbsb#7vret2SZD0 zpHs}j_OSnwuKvSUKi90+|2KK|2Ae^+|Gx;C|6$htAOCRZdSL!Cq*iS&n%@5oj|YLU zP{4hbSHJRAH(1Hsdhz9w{a+eW_Wdl6zbE(el?a!`de9V`MUlUUPSBj)*Nky4i=xb& zudyWY(jQYU7jr4%r5*V2xpwz{`txri}|nqi`BwT|J8p{U54{t<;;QV#arF~ zs(A}spiK+?PZP&CMGXJ+#J#!Af8YGSr{$mJ^xv!H|K=v5xNi%zDE?Pn0G$7u|LDJO z{{LeksW3+td*UI+2J5-hGrDilo^|bu4risz?lrm|6@|?7-cejPEH> zj4(IZy(`}?=cIwgHP`rBQ2eS#*{lqXi}NQiKKX$1-IY`6rQHBoGYbSNgw2@BMLK!w zy~k3l_(5o|PsTQOnmGwD{RS-$UNz!k;+@L~zo!LuT9GVL3*3@cfxv%>_$%0u9{)TX3DGURX`k$a`4| z(6oq}*$#3!Aw$gV!>lG$ncLN1GCj?whYEJpt&k5_O=((W?yDi^LvI!~=Hv6<`MlP5 zcKA(VkZJs&_ZH3{Ja-3+#lIHzi}X-kGya6{Tvz2!00F;!?sA6ip)Y+ZR#JlE?pH6dTnOcAK5aBH20dl&?8BjF~+2OS^Dg%Umma8$>i(bOD`9myU>gB zC7CczZ-x!-%T&0eCzvl8L>UmFkDu5j!57Ojwohg^`XXJ<3gh;Up#ok%PW(eePF~Yo zc**#4`YC&GMQ)F>JpIu1H)H3xUaz!^OA3B1(9Cx+-l-xZEM}L~zUm|~KXQWFA9e33 zyzKFD>RojZf;`dJj+;eH4VhmE(>p_TIS0smFYWs%q@mtnQ+4lHK=$Ta~Xym-gbraPbnlxO2 z-#7hozJWJ~@PX&-hV66U8aiO}ZFrhmZX+%qr+P8Cv~8h*hrERJGvsq#nsa{Qn#+K3 z^PbO!&9jIC&ss6C>erOd<*>OWIOdxPg|Q49CUGVRo*~8-&6OqzXYRmG$8E57=~5#S zec#3X3nw3Po-B*`4(QTczl2zdW?Gh$3DiO-+0#ivM9`*+;75BH;OV+xkVSg%R`V?j z$_Kf@id++toFUmq1{G=VcmF!%1Jlt7K!*E4PbWkz`JIq?biXTk8=KO``S@G2^A_Iafs8HRw&i*IE?!C*iRg*QfRSqs z^1f9kA>A9hlnjCeSA`Sk5)6uu-;d2yw$4musYgg8oza?^iSs!#hpX+B}zi!Mq zAs%Agl0PCmblnSBJK?dJH>zn*B$k{|BHVG0wd4k{H%68wTCX}^gSz>G+g(KXSoS)M zW#?zf6Z!Gl(Ve0jJ3J=hr^1+&=6$ksuV`ck82PT^c1P#+X!^VH-@Yftp1CEt#(R3A z2RU6kPW7{pd4JuMbNjsdJ(VQL=8g~WtWYr}$lYdYg+zNh4!0haidYr(eD9X_&s^BO zEv>)fL#oW&CmC{=N)+e8+ZFwg{By2mN)8<*ueGP%W_;TIW-jiv$Q@vu&Grcr&(P2N zSOvE6?kIi&C1;og{S2t1KZst|X2(jWRg&m@$GTz1lAzazDkmN=43$Oc# ziJQ%c8qmG&Xiw-u&i9JwGi607y!7YK6p=z3n$+|g6=mS_k-FL#twv-%BIS4jHMsJ1 zJG=by8Ckxg>Xl^aw%zNe{vq`#)+5)-wqPSu4LcSyOq>lL3?FbD&wyz5CvtdQ_oJuU z!lf*|l0I)}e?}-GPWp{3r$i=zVuOhT>qlpMAw>D1BUE8Y>W!jKAHnf^mz|pPD`IL|Jvx^7jSi4e4uYiU?Hh%Xp^0jHY=6l)0{L+AqvSrLgMM z3G-F&n~P@*tY3!`(VloU@;5g0W$W*8m+g(6+4%9gi<3O*q#AFGP$;-yF_(D>4ED)) z+p5iVE(=grl+rBgMR{v~xiIx0xWkf!V~o|=jq|sNRN7j1bn32-c*c35jkE2vS1v70 zC?lLwSI=iApJMB+C2jD~uOwl}38M2bJEsRWVUg4i%mqsJ^sAO;J&^uVsLK9m;`&G8 z!1%0kYL#8Qx$sYC^N5mCsm=UW?O&14#y~dv@jhJ@%2>u#bKY2g?_gnt>&!=-{&iWQ zaJwC?Y$QbAhyiA-KO)}8-!8m%Om{@=lhV6>RPf+Z7Ce1xQ35{R*dXLq>7qP{2vjfN z09OUW*hJX*{Jz=!3JWay=uLpX-a^ZUd9vzj&IC+OT%0)5QnfTJlE{S|zK=#*Rb3gN5ibXp7J& z6UYb#(}f-XZ7W2zMFfY2ioY_j&(v+Q2@Q22;M41c#9K?#Jfj{4ebba)eTZGp1-za>eKY$(PE*!tSITfrXenvli$>2(zF>2Y<^ zZEa|tjpjYPPJ`&ztH1bVWniG`a&403q>=LbjJZ8p)nsA8>y4GmQ!nlwx#(OG<#cq!44tw$f2A8qa%X1xksaPNH=v8SXd)i3b z_miQbvtoJryq`j6s{SMQ+oHWBZn-d_;{bbWc3WR--5q3XA(=u+U2B#9l?)q9Z&4FnDya^?eq3W8UNWgKb69PxI{C zuTz%Z+u%#+>T}p0M6ZU@x)&ZFH1_x`^-ew~{WN}-Ic9chkPf+a`@A@_+ICOm^^QFy z=}`28goOS6Hj0+!RG9TPQ{QyYr2yPr^#n$vUqNZ0$N7z?_kLPUwItq%MCs#kql`d^Kn?z*#jW))5W45p3c(9XCf>GPF{y&wxc_H-hI=K zQMNDK%SOX6>J00|q%pPO!9WSNpws#}iS(C6 zJ!VmZk$kQW6jn+{1Opb+iveL%XF-!~MxfMzq&$D=g(jsHAE4JgQtQ4WNnl%wRSPYd~a`N)2ZQlF&WErQi0jozx_ zKZ>~^#H2*RBgPEWWPPay(?N=JCtf+P-kYir2Ep5Vy{b^^KObDCh>a%RiuMt|?mDba zKX%?~g&rG`M;jd3d zy7@{$;iN^(U~=PfY&DutOV8D(@+Grn;aci_iSQ(1VJun2aQIPC*jYusD``yWF(JN! zROea8w>mb1w1M^QwaR7Vc>(V>ex7S80gruv)_XDV*5vM&_1r&||HiXRr3 zsYC?b5`iDqQWwO*In`1oHtv%bfl|Xsrc6f^@h=;8y}hp#7sY>d-t%_0z1mdPdwkL4 zH#j=eENSqPk_|nO(7pN&p<`c4Pm(I7;?GGmHCMp!ah!8XWau4VY1HFrq(obQ8!74b z&h*rP)#-O;(3WOFE&XnqQJ}ctdS&j+_L%G5szU{rsfHN=M`P_k&_r}y9y2qwXMI(w zFcj6&hss0U-WYL37R6MqvBztP7@Q=&UkG@X6sgSVZNrpd;5SE3dW<$X{$q$7&%cwW za^_>p+34`LaX!=u*b=`Vk?x?+9WpN2G~b8$=_JH8@p|fpg$g(Lt#Rnqi)*RmVAFxN zXvob4&4bc_HK(bwgo<`qu&R!f(KM&w^ICTLQ8@!W0Vyy^{2YgoMrbGo?b7+jE_w+x zyq5mEzTJr5M_MhIvNJWRDE11YVL-ks#7Rg-7(|&*msV2zbE&&9J)&497qL>AgscXG zr+vuO>LRb9uO>M_2~ZSsD$LEqHjme2hqSuCM7Su%urc%nvIZepgu>p@1LriJmrfcn zmF;OS{-x)5Sh|JR`KLm(&ElUOB}b~JK#5q78}Tavxv}bE>bo480~sz~hJy{n~6)z4vAH_^RfK_{>R8>Q(rB)U`N|h&Y%!Yi@r*K<%4*E-|*6!+d<|>!t)HbY&5Tx)U_se2)z4c|R zd%-c|diLWcK?JbMiPtMN7}ohnWAIwvA4?se+TeMi?^FHHPnOJs45h(GYS*>=+-4`5 zNCKTs<{BvKSe7@$C?V4QmqSaTrW$6_l}3h7Tf49wkBhI|rMyQTZLK_J>~;DE6Z<)Wr2Htbf8Z6qZ@mY#|p zczSTNOppBXYo5=zB!@JzF7dr9yIs`co`N@U5&wQox*ARL)K$1C1yRaO*%ejPn;SXb z9vr%ImGn|9u+Q(K%5JnOf|}@ifD$Do?0&RpbG8QK`ZP9>OBFUCOqtpYA^$XfBzXns z50FRC<-&5-*9$X1zt6b7eLsBA&_{Ri4y%IqYd4$;VJ8W8a#!hG*D(cU$nb);P8V{s z)m%Z-$pIfjy0t;)YE4`0oA>pEb+lF$izbvov2yv!sVGcvYz6f_;Fx>!yXY`g0QpC& z$m;-D&+5GCZ_glvDT*;JCTrW_{ARES@LqWJ*;jMoDKMwNiGnt`uj;vhPN(4X=3t2)xg*&7jHnJ_~7o&wmK*lTXJ47MQqh1$5IwTxffPVP}ul8)a4t# zqBRJ5D#(3N5g3#|S(dB9KhRXgDf74`@*9_T(S>@@n($(jU|m=`jVvNvpDL-IE^Hk< zeU8sLN^^(yS3q1!C}T_5OSKYD7MTqUNhyB?q)5zh%IQ$mby=X<022+G5Dn14--^P= z`64rq+wKtlo>PUUAm#r1Eh|v5lXmNRlPsgVvB06uSr)W&duS!)x8$$EMFse^3Zs`! zN5M%(8P$V?z1*-ccCt8)bHdMmhjr0{q(fLPB2}3mitJBNDj;aadUnDH=#%fSBZ}ip zG0Ufbzo71r2|E9jXUazUA=mn^Pd;~Oj(z`_GJG=!OdDU zP*^INTf<5kV`C>G*`p0|WM=_E0?lkc$is`baAqvewTa#FU(?*DRR$$*n8%>cza~!} zTS$XNo^DB$ZwA|SChdiXnrZQK6csOQOGr z&TRRe$k9sbZJtAr`@nuSY5<6JwB-$SqUwXm@NAOMEb8mnupjJMz z#n&#X zj4eb42S>Cat+&6%ln_tN8Mh~xilpd!6&_3=#yf)IC}wtPcH#r+7$uP%U;oswqc_e@ zO=0`JnB6~vMUsJ(w=i+$aS|-b)}X?=z4z%v369<9Ny#0q1QEACTP0L{GrB34ccTK; zSRL!E$Vhuut?(}~^RVfIW;o9bFxgmFDR8ac5pfW`;)wg~!?n4iAWAI1KvajMVF9M`LC>{GLg>k;k) zI;f2*_xZpDU(6}0@0_WgzRg)sO88xC%65Bgj<1-6Af=PYmJkm_lT1raU6<7W-XTHX zf<^&An21<3R2GhDQuB3G6Y+LkGnI2*i$#7nK)W{3Z=(oxX)ar)a#J+6?V^Xp#?1Fr zg`ogg{M5gBt^x^v2}SR1_DZmWKh^NLBj)DRu3;MW*i?_YvU%pYAorU5ST#Xv3vF9@ zt)|hIX7F}%-ZuGcX6*rWbcZI6!1><(1%?ngy~c~+Ux8U zX`!=nxv0C@#t!F!xK#>Hg6q&kcxe6{1E?}lRs%xe=Jd_(Xu)X<(j};yzy4;-u^DmsXiml56X%aXYx8$s z|EwZJzly-qA2vA$-eanlKcwJE_KoVAY0g#(azy zLk^p1=|oE5+QJzBBt_9px2FK~Mh!dHD)w`8n8;pI6|P}kLVKXS64uZj(}Z$r*N@bT z$e4FG1U{3JI$9TA$)=?=GGA{`Kf8ZOGq_D&+B_J;liZt95}C&nl!x}%lJ5Y!xO*S0 zd0o_79Nkgc20=SCoVR;WXzXlcn(u^L#j6MIiWRvHYCFYP8^CJPmVBF1NG3MNO<60| zn}!}qKC~c-`=mNDKy+#l(LWC%L_Rr!r~>#oO4mpMI8~9->n|?eWvXlvh?Wv-6zj&a zr={(6mH{n%k-1XfX_qSaR>dslXX1q`VBOEBGp?tdK(Bbu7E!Z;6&-Uc!^g?F+q}zV z7HgZW74Fh_b0Wg7h10Fo9&bO55TE?r9#5O{ zl<>9ObyEbZHh!k7p0%rU0uI_^6tpULi!=!!+zs>Qy&7EE1qKSeWAp~!~0vG+g zKA%@)Fgl%cj<|a6q_?5R9R~|2 zOZOPA{=x}?xGVDdU7e=`RGkt^_;{}v9NV@nC66DW(Qovt^PfP&N@#!TD-UQ^+uzKztd7b(SbAig?8F?7#T=qN#v4EbX_DZjUWd!B=|~LYY5(^ z$~ntwe;-7p_biKOIxkP(=dM00n>w^Qrq&2(soH@b6MfAqg>|))` z0{Y17lT zii}Kb(g^hy?5*8>e`$VeMK)E{RA=4~Vc%1rwJx1E5ZT?lG90OiYTUpI4&~1DOnOuL zO5_|)N_EOYQ4dW5%bPSQqDL8Ii zdeb#JHgj-RM#eCg_g?tW^d(DH2Fclkx%7=4VRtii>qD85_1)SJU4F{&I~O}}M?OEN zg+zuo_Dq=OL&Rb5*E#B|fOW^{M=>=ng)#6$>xilh7BE;skkoHZWh#`nU)ejMte*A3vDU5@9_u~Dn#2h*4*bfj8xW1hdd@UqZt0~>zG zR%$u7d`7ww1;F@9Y@xh&PfW(P@26UyYtL*FrCj^mIFGL>&$L$T_zv}?)6AaLFAm`M zhHoDTNsTKPT-%OSO31WHtb*gO)Au!{x;a5b$z#(JlXl3NVmWUjy|7DAY92jVS#=<6 z0d71pw7S9-(<+H}dhz%_Tmaee*s4AGzk*r=QNo{(QoY}}IeAUVFV;b*Yorbc%ISPh zmS)oFbR%t77WXJ|GILiG^ThRg!`>&gwCuk^rr%}+RYsNr_#b|M3J{BU*>ST#shy83 zNt*-c7sEX01W~wr&@r4sd-2i7`XeQx#}MiYNhsQ?xmUL) zMNB8y>LA>}U3RU7%y@zqG-Cym_CUYW)OT-7keiA$qS+UHms~y8$j>!Q9`pV3kwmWT zR19BxIX#bx1QnNys@j#qqx`z-@2s&A{uBz~-Pa&zxz~{C{Nmv)+8J-vTNvfUt03as1{?<*6l#_NTQ>PHrz6{uDDmi^)^DQ3uf6f+}Nacv8= zr&iVrsL;U5g6&uyr8c#jBnf}c23~6ISTlW%o&$7dw4p;WFtj(L_<*7JHNM*NtINyeLdV}-=231yP zyy~69^(xrO$jk&&KR^B=Lk+bVU9SE*;5nwv?B;88B`rOT_lq}GKU!pze&cbBJUXyo z%OwB(QZpG{cG-0ewC#g3ls`XoMZIVbi|D)tLMHeX(q^$he-kPvBRsbYJ4kgE&^cX& z`ysBH6Z5uZ!Q+n(3hN^C*O|rTMzP0#UsaY&)=O!d5t$nPv3serX>-E-N}{vAGuxj)v2#mm-`A2=5+C(&^!q3uiNJIg zlc`^mRw$kbjy|BSZVxQt_AWQT`7&Oe7}e~`wx8jl2o@0+K5O%8C{F&817U72{2JJb zTNYb`#>!;#B6FxONg<&$yC?2I)Nwu}ulDZM)mg{rdQ}xNR~OT_X5pV%Zc;Ct*~5YG zX^1ELq;v;M8);MX0ou9WHO63%g})bN$ts5B-{&n$AICD!T-#Oe-K*Q~S=3CQO{48) zwQYH12|JVhgk1ZjmdfR#O&PP2#LGV<&wPFWID|QK6aI%WvN>}pHOBcoA1;2;JN;Ro zIo0TwIxnaaR{-1f%d3^i3>zp)?S>0QUh(=;5VZZe8hjfwYlLn*#R^8eCOwkx)_DpQ zn|&?S?rX@~$RlFrR`t{j*CQteF75kw3fCYtrzI^}F2YZkd{Q*rLA%|afH;4}@5%N9 z{m4soQQNiHij(sTWN5B`L_UU6pPs>19ZAXrIvDtCW=E0K*I{lTvf2_$+l0~pIdN6k zn4i1AXES*hGB(LAU4+zN6VlinApYJ@9vpp;8^e`^^=i6Cd0_2$Vurq#%ty|X@1QpJxtXjt zr;=_ZiAR`+d#9Xvx}CaMY^e*!JXGou*t`D;Gt)Pbn2ltV67WjY2{?iNs8d+cw?Sd| zbq~}YC1{I6o99dylktwbRY_Q#OI;8C7 zs~syhUoU*B$j6c;G1qcNUY@Kt*|(OKqN4(eZQ`~^KC7`Lm`z^uj@NOHc)zR8=f%$A z3b|)6DkkJL|FEaC?AyDHVx)Bj^tJcF?8dNIOw__gi-1qTA2-zgg4JLN^zgnVut+Z^TTq=1_1Pr zhKLW%AWG`!6=FaLNF?W;>|C$+#nN`K56fM1kvBXV2;<=*BAAYlgOLuV$DY|$UmKWS zxVl?zoehpEkeZUf#LIi4RqB*Za;~^s4&s#S6Xf(;_#BuZWJ8K1MDei@k>az+0v2!4 z6CS9J1{Z!;wjkUI5ZqOj5g}$De_AWZSBP0lRT`NEfs#Azvo`rJD4bm*GS3XE+7G9G zt&cC8_W}8@E3dR*{yo%4q_J50XC-@zlyFo6zL|0E9y9-=DWjQ>`4$b5wF}n zcFx8uzs&2MV1TYnv=F;z4qMC(xi)-^rCm9wt2>O+2>YFF%uYdH7Cc}D0x255 zN-Q}w!o*-{8RK`Yg|}|-U2iykoT=_Tgd7=S`;xQEc+Y$@`CcKEH8<7Nnmgu zIGz-XRute~thp|nD~}@n=0C9RpHAXNAyXiL*x-pI@%2Tl_fDkg`HZn~7V_y$%p`>V zmJB>P_>l3)F@-^H`$Ei3Gc5G#@ZFr1R%E0{L~GnI@lmGMH2u#0pig1myLf+LHE8%n zgrpt_G(MA{mO6lhE~$Zrx$8gbhqTDxKd{UlP9;!Sese(eb(i|Wucm28fE9}+Oi|^x zV551l6QMjT{>r}vvo~Jkct)F{PE@PfsQ-Hx@2bb1#YeWI;K5(EB>VdR;uC01=i&hu9E6a5nGXayPv_Z=f$Bbgc_{(X2aDfF@~2@t~LH zEkp3vsSEM|MgecCj?dgnj)M3@eQ4akI>Wk}n)zgcWWf|&LL|vX?tCdY9iop|SD`;o z2(7-;=AUSb8dwb*@j9q~RotF9rDjuycNIntABa<+`$cWFw7@nFu|GUX8OzB7fJ@c= z2pfdE!j6XDV&!v?lZB0EmGfPk%sVBD63wd&Bz)U#D~DFiEq0>MSfi%bw&A%Fc09#w z6t9)#P1*Jm@PiSRExI0aI-zFivNhI)r%mL`=oP10ryjuwx!TRO=Wt;Qi_XjYeoe}- zVzIl0?feY&w1z^Fy?0+{43sHmr~^y^DcNmS{C49-K>!-I66|YF)FP@=)$kOu($H_` zN1B|*q)=DOes*ZIb4mRhU?lb0_4+&|)fSczW}KU;$!bc%v3lf+*K$}sTd+yMvHe4f zh?#%8^SxAB)rVKk{*F01;Ewtx&BkR4zo%94K(6Jqwqf`?d@P~%yn>ck9pQO&c5#Ha z1IqHDC&wFC&hU4gCW)>g84)(2+6nR+%z(Vy`=A3>3EMPucO0MktR2FUefr&GXR^DE z-t{`?$x`_5Y_j7A2_eGyzmWt2QwL*8ctKik&PW8fMdl|Z)8m_-hONF z**0sMc-zEbqdiDM5DScqQ%KfqUllyda*3zn}b~Km=O;7cUqqI}{<8xtD2lS%} zD)D)#EG)IXlBODKfAJMl8uB^{s!8D2Z5=*5sRqOZ@u3!YLt7FS<(t+(*3L{sa4P#BtPf#110HSj=sJtSe%Z3v!gDYJrBQ5lsBp*x$j4)UInaH9x0ss9t(26 zHIB=q_^Dyj*Y|njr|Kkt2UP^GGRDg%wEe|5C%Q%NA)?E>gDlZ?6GxtUy3PQpQ%nRP z*AQ(G=r$Dr7*XX>1o+4_NEtB)8{gv}qdlhUsSk?o>!kU=r6jdHQeaMrh^-vG+4wu3@`!3m!!u*ZIVx*af$t(#!+mbaWDKwdwNFqdcY zctJ#v@61*q?Fb;37#Q@M@AVn5_uq}rqdz3pO)i^GF3B#C*h&6sS;W zr-b9kw410u?>OMBqq-%45*LuPEX2e{G!Hv3HRrf7r~M?{MOSE-JU?%`00^nBK1NIe z=r<7kuOarfmXoMPFP*-LB#rsS9vhtfKL<@VIMG=veb=dSWnrFvKfr(}=8wTgFT1U( z9HHYY%3J=CH@}*E4aj2X#CisTSzrSnQtkIMW-kD-!~R5E7)(sSU1PL0pf&Co5_Jm) z=PD79%6Q}yn=WPOqOK=&y%dtUqKI8kuAaaJ<&8XHPz@{|JyVC}w|TnSG@a`^I5?-N z&p2`RLr;N*r(-{)m;v3+LRkmvlsxnL==b)kU(v=D?BYCtvL`c* zA!A_A_36Kr8aR_gC;uD5p1;gaRRaw)Bq7`MDx1xmy~uV&cG06A)};2uNu-3geUhBI z#(8!~15}Lie`dA=k8C(I{zzrOgN8(7KyIjyIU?6w5enRg9c{Y%i^A4e1oCsX0U-Da zVLUng>KgCN6eLFdwvRfgHOc)2tC`I00vNp6C&)1A$4Y);(|bEEd+q=SvwwX}K!kcB zrs{to+G9xk#hko9!=6B(hAVc8L6B6hZ{e2{K(;UX%WO1nwtb|cZ_@Pk*UYas{C6qF!-I0A z9oJ7(k}|-O@pn$P59Ycu5Y0c6mY}MTeXh$aaQt^;(mbNbTdTSS)=*&~Co@VL5T?Ws zGgZ*aa?-#!X&Yw0M)sQ2l(aiL|DX8Ry@}n7Ygf(%*9CL{ZG7?{7W$Fub?!-4*x&xZpd==7?xt#HXlhmV0LE2( z%?YXtVL3lX{$#(Mdh)2sK1lH=T@rlNtGG(=mFSU5bAx3eBe90ZTQ5sYNko2>i`Oh? z2>gaTzBjd4uopWM73^->wcS#%_W#LYo-L*Plh{a`?!^SK(t(}u8en`!yJF7YwbOSF zo9el2N4ap3`r6lD7eM;EbOH58^wh+4uPUm}ivmT?6nkcACNwy)=?KLDBkhNo3vN&V z)`0_5$9MesC5sWHamAj?&qHj*Nl5sb0v@(vN8}Dr(L;*%Bzm@5^yH+G%^pi1fSGWp zp9NUv5qr|x(pkx=&dXfKC&@RjpnVnd(>GtADx+~sesJ0*ElsXVoQmW!yKZFJZO0i( zw~e}#u{h1nbqSn0tC7c69YhSEk41NZ&&YeR0|(Gbk=xFK!8b|+688=G`JE3g&__=y>%Y_Xfwl-_<_a&}Pz{V@YD@fESi z^Iv=?X*WM-MD%Jq?MAAI0laMgy$vN(|1o*v)&J4nd4Dyvb^YFRJct#HGzAd_=@3+^ zL_i^c(t9T$y+?Wnk%I;hI7pLb04Y)e(g}ee0@4#&fY3s(0i-9?yLp~_-{-yeFStLv zdt{7c?6I@5v-aF;%{ljHepg5|>}07B*0O$XA~@`iyuvey!@K*Vsz9wl{{iq!etyvp zC^7hA~Z&2z9;_S=L^=}G*UbBwcABAG-~>p0VF)oOn=}iwLg`k$kcU> z=bO<=4>0_@+dM1h@qmM?LL2$l8jjq3+48o&!n==u@C0h}QHSjv$K5huQJZ(@a0?Gp z>SSTdmyXQbz8(z8mHi4So>Z`&&U?F<2qfKFys>TJ@w5gk@99{;?L|H<&m36SRiMTq z$~<@hkTx%`Zkz3<*^U6H|6Tl%_!>2&<4u$lD&CLyftd80rtG&UxEpGszx>{A`vpBK!5T`n^(n`->{j-LQ^02CNUL zV8Gj)iKFo=GCKFv>@Flf65%xBjq>ZSpOiC3Z!fA0s6_xiE@AYurihC%#4?Tc21Xt# z2E+($pE!>G9Wu#&WY-Kfszd|mv8DTn*yQq)-ThgT)3BD8_lUDB6MI!uQdrtL#(ALQFO||oVT<VB+t>sKh5n17Cw_{& zQg+LI^&%;m#ou<@>oLwCZOZm`z~c%RQQ9T}x7E|_ju#*RMD$t!j~o1=69o0+-W#q3 zrQ_kO(ZfnZ7$#mx?Wb&1+n%DLsw3ZgJnPy_NXqNP`oDE|8Y}B;#TtI+fH_yy{HSwp zH-I=}_@KG)97|SLJKU4cHNQ$G^p`Jm=}XEg0z5l)KA_6tb1q|TVg0*7roCiy?CjvR zz}zajmgPRxTJTx{uc1mC#l6)FNcv@OI{R#gJp2}k*lrB94{o>UQ-o&T5W&s~Z@`Hp zi9sV{jP+=@595LPoo3AfT7dI4g2R34ge|rLRHbifapn|=gVPni0`8dSWuU#- zea%$!TiWX1F^1%T)D#w2bz-81f18G%gG07Uaw99-mO+m~cfGUkqYNRD*43ZIuwG*! zXsx3UTSTa|H)%Y2VJSv9Evt(oK6?%ZueIC6_Q?RF3OC@mROoO)v9m2l#LeZlh};|n@J=g_(UnERz-gAjAA~}(mQiu}3F!POld%u8(p>QCDYuR0qr=0N8UsM)Yti`(;iQB{M=Wq=la|ZFB7K$1oHe zDCyI{vyB5cH~?h>l&zE385{!ZEr#0Hp2{!+uYwIAiE1BxKStj@$O@ zsS-OsM#=-o_DJ8(5MmD8OX=u)3=9PHe}{?)Is6x%`+J+CttOqlY7AJb*^^Df5||A4 zhktgzM|3pDk6rdZeFspz6lj~!1kM&BzWG>njZUL=gK@TQ=w0SmsY-Mi?#5_;;oi?( z4}OJ2lZt0_N+dIc^9(&6H)f<&f%nUH|(;ts}r6A?M10~LP z6-F2Wxe%aEp{%Q@HkDro7#w6#k%+1zrLN-H;s+2GWB16}kyjS!qbZsOD)GS*)s(Hb z1OQz>c(KLjD3Rj2N%_BFaxzz5;jj887YhhzQf@1_sET}?F575cTN#wTRN)$(vX*i4 zYViMqtLHpYh{})zNMQjJxpV~Mr?&Oe6`R6;1g$?PLVM<5UyH?*arrq4u)ry=C(9#% z)$jO{-OiL}-lbMi*I*(7BT!zKQY%&4{X6T!)9r1Z^82`k$t#Lfxe_$iJILmAL%w*%p=fn7kGsF?3e`%$2mWG!*V>TN~s${1=ibAJ92>5GUM@tjbnRXYlp-|9^JxaTyVQPXVbcfZ5- zY#sGJe4P{EdUy1BI{>hjd<`~^w`EZX>$2no`h2I;v5AL3{8cY;`Di0(T93BT`fbFPjCl#t9`r4|34B{pdc z$YI_Pg)*?w1xLR;iI|ExLcFg#w05dgjrn{Q`rr8QLv%V#M+nnU29R9+J-%9>@vIaI zWfxBW>j;mIs@*2Ki@Kh*#{ecmbSo_%%~=Szt05y(Va_oP=;- zDN^V=UPQZq`hy6P$IO39EF5JCReFBok<_CU)vX*#il;bwSXD?n7gVjWi@yGm&71xL)E`Bi(yyEvvKotJ~@vv9JpZE+mX!ZKjxf)b{F99cdUJl)0(LfNsg zD9KSC_3vQ-PmUSn>%AM?J5MX|(pJnfc`9>I_4V^A<(wkpv+cFym%aG(?ejT0fK&j5 zI^SmspZu{?akk;1T5hD&>PW#e(Qk6jO}vHMZ;ENa=tZU&9O`JY z+`Mq%9{LsZh2BG!GoG5}7NkT#U*>jgAyC$aKOSJW25OM$ zjS1`|EuN$z@ITC-KMMEYHHI4Uf|Y5s3R;SZWG4^zlKRE}gKtl)raGrm*UCR40085I zK-0?Q7<0CCzfh0gMhjhpGx#Q*!no8xdz>7tz{lnY@w)GSa`;8lH#CQpyt@BnJ^I@` zt#-!?8;_fj_o`IrHxe0j3c`lnEao##A9(B3jmbEmE}6{BhqEugreWo5>UhAUllxrW zrcR6I)<0Q)h-5ThW1^hNf3jAs5GH!$m|>BIN+#<#Tu-e1m(0w)zo$@qe6}W-M8qh% zKKaUDKskCBv*^KwG-nZMwT%4TO-W9Ian<-pJB|R{{|SMg1%tOey%tLm-IuW}eS#sI zPZZ#RNeCI1XgDPx{t_+E{;uz1Qz-joJ>zk9{GpsuyHbx^2r*gy8(pOPF?RiGYJ4_jw1MD7Q>GYs%+ zZ8#GqQ_~|Arl&{W8a8MBnYPhIZSknV!AOpRuLUxuLQAtzH)v|l8vDkabIX6K;M*!` z;(bWd@lmSkJB{KFb-7orTAiSuz(oxU24i0yJzqw3xd>UXe`=J-Ectdj@Ll%E2=mg0 zxeCWMRZumBHPQBoaLD{=6)1B7NJHxhnroikL~5rVY+;s545!JLOvZUb7Fci=u)6n!fn=rF#kSIY;bfB;PE=cb~KD5<6xhC<`uO~sW@c}}dMWLE8!K!5i77YBO2O9>} z4c=q8NJG!msf+IsHceOALwq?yYGZvLxXJwi&huU|(JxRBG>$|tW~d7oqA3%>cD5vW zF+8M2q2OosMdzk|+Dr9~4`pK*rJG1$FjDh^?0-E4%i|QBe!YRfPfM-erzD zMtRlTpRG7Naw5yu3bk<0+UV@Cu@{zycsxkbfN)xo3&~?(c1 zU!@M4d_E#6R|VNMdk^w8eIq9_qfV=wx-p`IzKUjc_rDWvF4gmoPhHNtld9`Fon;6d zft8}P$9I?wmma7G>(`f@MkQ9)I)Xvkb{2|d4GPuK2r0p8S3!l`>P@u2hZbSx7D%~^ zH>Yufy$_l}N#zP(YEoTfDGsSnU;h%;=q%@0@|{c$GJxvg!NsdO2FbP(+{x=6^yIP* zQ%EKb@Z$n6Ipyk93MoW(g!eR7>#K;OqJ9UI7e#f8`Ib$75D@MoyGXn(uD#{9C!hu3 zgsCwLk^;g>3?mDB`vRcAMVZY=yxqW>rbE{hZvHB8eJm|vn17C1*GId~WmX4%)Ba1n z5+(1rygDu)l$Bg>x>B(&CL$<(L|b&0xo2dDK}ZqLCW@uMy{>~^B~B=C{;7GfoXlb_ zYY*X^9gvnTZt_|ybFl{={+X*Tk=hJ%3$o_h(G$#LVwhdQ+HvzW=frA@Mk^0S`{QEi`ixL@c z`;FxM%f&n;cFrz2u~%^U5kR0$TgflGGtUs3L4LEp*G@3kecM$mw)2_`i|*(9@QICb z>vZ7MWc+tUWkfT<2=bLn2L^6UuH(zRlKh@dcMnI~I`~yRpAwyyH2o~r{T2v+oJGdt z3qH}aUMJ}x6}BFlv9qtI>-P)ah~GYo{djEqJ0=(d^Y*Q3)SDWGXj5<6`}%E1|3d`h zCR5{oygf>aHJ@ru;Lz+jp2%$%@vg;iYK$4Z7M>4b0>vBd#;#^MyP^2QZ>4OU2Dd3+ zYl}8S$8_yRBM_KDVNRWng%LV6h!b5Vv^CFLZ_>n}SmdS!oO@zbKg+S&qdc)@`+?bT zU#<128+Y7b{K2K8P|{4z)Mad-tcS2U$P~{qu9UJ-3esY6$9Sh8q^RxAv_0ZcS&lXO zd@<(1rU?2Wtx!Spip)h@#T0Gv5%pHW%rF${5x3rT>4h(g^;(i*WM+TjxQ}0K(uPn` zjmbz=(GICoI%9y#WIb()*k3bc0OmHWLt3Q4i-)Aw->mHPx~<9*8@3+02y@5S`uV4o z<+HJ`@oIabAo>BK<5F8`V));2cSuQ*k=^~o^wi^UFY*iN{q;7{_4fyvGv#p#`h&DJ zDR0|$6`MAD_8Jf`F>d=tn37nXkTYHovTUviQK?sycjKYWWc_tOohc_dO4NsN$-HZC zXfN7|Wh8GGd~j&aP2j;@IvO{TGxlEH*x!qzR($$d|8?p(i2+;7wW0{pHmQA0o?Hkq zj#SP4N7Y=@5L{Bw&}_ZfT98U6yd*P}0Rv%fL0P_HBJa)7F#g1IVV44uT(}tff8Xqk4P9nC7IS2Qnx#!S8`(Y0 z-E-zS)vd8=b-0UETi;Q}BA{iz66nc26KZyDcC(wj)s11IOJF*VqC1~TO!v4)jb0}$ z#SLTCa`y{vI2V@$(X{iscujb?q5@RB!*!+tzGY)o>K2N#uzwd~e|wEVb_me&I~=zE-alP3 zbWh@HU4s_0w=;u`;ZIsBRbN@(nVQN+KNL}VvzoGXu~%h_&eL&tYo>FqrQ)+Xu5E6_ zx^l#-^N2{X=WVFn-dbxh7(5k(Y{iA!moBy0QgG@@8i9NIfw<$wrqV)U9xP%`Xqyjk z1%EIn{W|E9i;q049V0qdADZEUxAtX#_R!Ru`E7?RIN?Y3BL?!f z$1C`qrK~;TOKFa1SmjB(I9f(VRAfN*<}(B9KS`BUCq2Y}PE8zktNR?9amS2t__jGY zwe}F4ed!ktwR~PU&Y-k(%IgMQJXvsNy5JQit4Fe(ljY|Z!rTBlq3o0d-OEWVYG=XD zU$gKaVvFKjG89ECZU?Ja?(9nsq)4Cl#c4TyWS-TZrW6GT!m?@}_gnMT( z%5B(bO43A#2BeamFkBmPq0MLZVodFTx^7^#j(y$_KkyOJDkh#Kb3ZB{nrkVd*ElJE z73~sJ9Wn-WI)nQ#dt7st^<}HS1>!YalIMu&yZ)8(roAPN{?~%1fBbA02ol_s-+Vs6 zyR`^&Moi?xe>f>i zR*MvtxUsXexn5PS)QTVJk;FmZ9O{gqSGdlFcCD_*{E4I>`2mw?=zt)VP_CO6s5 z#wjL>d-w;bBcRZGB15phYejBOltIZ9!e`-68L6F&P{{4uP*P%p=+ zL(riC_-O8Xf$l>NNGLycP87<@#z`y}6s5j82RgAWE~rt>4m@_Q*%vtGxdUM&+X&&KRvutg9W zX$s$Ftm$>px`M>%1FI|-b#FI572EHP2_yz4wBG>n?hvTU7eS!lxtj9bOR5XQz9F|@ zx-PuW`~89}1yNoJQq%|&{orOW_|dp=wY+09zXXpf+q1vkE3kQ!)hGX&Z z4v)?U*Ej-+pHssMyf>l7R*L&8W$~#D>naln;#uJTz#5WXsR&&kGu*S$d2j~1Q#KDv4RROa;V)GHt(WTfc329B4cWTQ$eR+c@G5sCc-MAYrHNDqpe z=Qu7SX6O(V^2TQV8<-OfSz)KYDVP9^QM=sX7tP3y6SaIP zrYb2K^mj|c$@?B|+`4;9Z>%Ho)>qx55uRtTd?%%%V8L?ha3xzN+Qx%~NY=;1pj87U zXzs{rsPqG3fWS;FjAm^;d-8hlEx>`|)pu#Xe(pwR=*=3$)F)G)+Ok0P9Mul*j>^Ba zV%rK6t{zbTq*+k>)#zaGfEmy|u+z`rM+*KL-oq`;*R*=Z0^^>Be*=KIM7WSKqht9$ zUWMLyrPs6r9Z@y!iIQAjwEu-gk-b@!-vP&HJkyyw4GLM+EUQPg@D_*YE4aJurHM!G zwzM~-Atqwfdh|CSp|)0s<%sUv&rAr`j@Vy114i!!;nUw9a8dDgT|_*UmB|1vx0s&Zc?~&nCoKTrISWZ zt9I4eh+5ySEy+m|~*zy`<`CNY-mnc1Sw|P3d9up;gm;^X9ScPf zcbC4#KUId7aD@+R$T3Ym=blI{eh!5WAn#2rxOq0o=yJ7W&JK($MAe4&k+?X0$i)t} zD34F^@K3RbfXU6ZDS3fmfg#wJ!cJE7Va+WLqd;a;=e+cmSJ0-?lGPQ#K}Th%@x?O3 z$>yNMUS=RtJUYO4x<)SD1$^r-vbUv+qF?TBcTU@P4y>iJRBqwlg(Hbd1Po*dtHUCC zIPX#GnwTrB<5sde$JMsfz;k-5fwGwts-dxOVSj9I?en54yhVW)sRS7?Qeo|W zvmgT@16Re`KK2rCh)LtlPIx=6fWuz2#%{=ua3q@Lv*{r+hC6O!2-_*g6rZBxG&CC} z8POs+JuM&7YW0jU;@^QX;=}R&jv(|faiy^GLoiG7&w^l;^Pn^dh6`X?>DAd%oVs_H zYPd2fvJbeq&;0~M23FV(qpS0FiScqZCmVUB>XR8Y4_;&lzyyq%VTeE?C?jx%HDM*H zn^|h7e6)e9_|L!_Z;b76G}lw43M*HeToy~o1sjb#oy z+tZ!2Px2wF@Y4iRzTp?iTDWHB(_0yz@%B$1vEwxnflq*Hk7lZ>sO+D~?fk6vETf%7#13xPw;&xqHgLDl0y(%^6{K zXz;klVgDe?b-cVXoENK7dKLMUh>o7ow2DQ9IP{tJ)ZoIxWVtz4M3itT?Qd~k=Uc}= zDBs%;#IQ*r-(OW_zfKbfy}I8+obIR|m~QLj{Iun5QuKiMTMq~TStc-)0kp;&bR~yI4$o+6rbqv3kQg1f*`6+T35hFSg@i+Se47r zLSZW`&Az zUBYz(Ugm}>&_wS5pTn|x#JBJ{G_R=$_f+k$%VZ%Gx_$+p-wsR_wsgFP>p?41^X`?$ zafYG+>XphOjW-SMoQCEmufDXL4fnV(l$WUU$)8}eUOmIs zG+e%x`WDcFwtr!%w)~=t{CiJstW|66&TM-GGrbxUM`bkT7%P5rBFsE-d?4-i0z<>r!w)aJ(JRk2{aaw&l_O$+YT0lh zaRMHhJvAV?7=qVwailgCmMbjyeOFzXd{4AqUic%nhPT1)w>ZO-;UNQcG*k?~+}pZ* z52XD?wW-9Vp;^nyA6@>_gyO#3`Pq4)uIsW|FWn~p@IOO5ZQmO*q|A$7@DXG-DJ>>V zRJfDN!lxCnlE!4BE^Zf08buKnJmFqtw?K2dF;T&Z$|YedQ9%?}i6MSKno3czv1~w# z+vUEss^hSxe!f4j?X#-`iv}hIVBXAKj9V1gtm}RhaN}!bMv(^oP0-#K7Plb1sXBAX z10%o+k`y?@$~IAsuO-3n(mb@!x~j7hz24h}1`e2g<|xs7pUjc@28}32z=$-Kw+oIF)k&eKRif&i=Z1l}~$!OSB!8gjDN^IjUFPTsE&P z3V))YTR22-J@fTmrLM<;XsUAT@Z8pkx7VS8)8UYk2+Dkh`bhdTxnNYb2wdERIi5Cw z^92Zs2R|UoS^5asiPnmu-;GP(zI`ekpUSo;+e_@ak(XP3on`%p!>oqYcKBQ0vTWwc zRH_s;h6nX>ZMH!horJaM9iWA;UkoQ?D^qk3F|+sx(G ze;6H)`B4zIRS@F%N(t&Pj!tt*O_3y~2lt!R`LU|w-xudmFGO9HJD+EM;J1)}*AkEj)Zl#Z3ELO1Y_Y5gkjZ}q-qGYXAgC%S;zo>J6 z{klncCX=?qmw-kxOzz%eV~v|s4Q6<>Y8;f+98%#$ZBHmJ7>^q2DiTiU3W-f!X*|1}uWWzp6ua{lzPuw)KS(z0BRW-FYhtjahm^D@YNjG!}qpP!*P4m$X;)xTmBL=iWy7Ia(&eNeip z3Xx)Ny2CEJ@z|R?+8@*Rn*BaEwXUU(uaK>6$p;ZQ zMO|OJ5BsvHJSNtnzaj2SfF#(I=4>hl?+4PZe}H(oC-DfK;jrk8?Nd&OghcjV97~JA zb3gG+Xn|9O%sqBic28&sb6ZH(bPZB8*49mOZudv)NDEfh91TshGqEECUP&)GEiMbA zJYTOIwF2&q%H51;UOT1m=bHc*sxxpd6u@jW1LN%Zb$niFveM<9;f z{QarM1%MX|0H+B+Ds~cX)*!NY6dB0!3@n58$|DJFm>WT!c^qes-D#{ zCw%2luB3S!8*zf#`qSsak4h^G89DbsP%mUV8{X|aoTc6RFRA)zn!XKo^vx$`8izZg zEK5jlt1k+;lToT14gQRb*x)$rJE}^iy>y}KAw+ij^+QvwFZAs#GI;67BDbvmC1n3w zzAyHp`j?7Cc8=hsp!$u2fd?Tqq!Sg>aSpmTv+k%T3KnXA*MIR&yKn*ji5(JXWd*BJ zu#O*GtkmdEw{pIXUf%g{3jF_W9oU^k0R1-w{(ql1 zu=}lnve17N_!0jN)ctqA0*3$!{K+?f_w&uc``>+b{uvefKaHRF1F-#1xBUNaEeB_R YtlgmHTP>k3pI@?9iW<;TdCPbI3oeq14gdfE diff --git a/localization/autoware_ekf_localizer/media/ekf_diagnostics.png b/localization/autoware_ekf_localizer/media/ekf_diagnostics.png deleted file mode 100644 index a1561c3f5270709791a19557b874dfae1d6f56ba..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 145097 zcmdqIV|Qi2yD!?^LC3aj+qTuQosMnWwv&!Jwv&!+yW^}lE9N@sv+o}FzwbEb3*35B z6IC@ao>}$7Gb5E0B;jFjV7`3$0xvBkrt;;>*Rn5Pz8ynBejcGWh_L#sz@0^;)u29$ z50q)d=RUTJxTcG$y}66Kk(1dM3p;yTGkRweCo?lUXG?pRE3jUH&ql0PYML&hPG&|f zR`zy8YF4&pp9jBuVPRrnJ8W-aW;x1FCk*)Jjx7WV>^rpW9B$6OEPgcpZfBJ z=!>+Nu$o8C`Icvn{5|N;%}V?0`RmUxBe>xD+A)PRI#I16C9(U|h?JrtvUeFNX_*F! z21aTV1Kd}J*H!GWzN*LV+mCl<6GFHO3g5i=5nsO3Y5wC|?ql6!U%~vDS091(BJpT& zab+~|F;TfM@HlKwWoLy{QAJcMSRVkGe;eb~Y7Q!B;>tig^qkKsg-;TK^0PhpjB=m! zzi!TI4lk5?S`*jDI;FlstIfi-_<+? z1KXjSx(82A|Jz3iU_ zB;1$X^SfgzB&Ag1jgNEsA5sE!QJ%674u_?Ws+#kxIK3#onwcMz(H@!yEZ!P#;~fL( z?F*?+WRttq!^|NbnoONfs+U`??ue#dDA~tyly+A`yqC8|9rxb*d|X))eT8hVmr(vQ zoYKl4UhaqrR^d;snw(ib7~~4V(HobdeTFI*8je@0_#X*B?tLp$0DSvbihV5f&p%go zfE&++buZ#dY#mUA1nc>msuY!iKNTtwF_K*tw&p_IJ&=o{Lw3#HlEvTj?o47X)&u8` zPp@xc4y*K8aua7#N4Q)8irch;*xihGRP*Vc5& z$=>R$w`xd=y{{}kKxs4|xLl4rAlp9efy!wjzsg&UG@}xqtM)3uyGGhgg4tlBjV;BJ zBtn6S?~eb_)Hc$55Ti!ZQ(0vp72=O+dP?b|mDapt&>kbna(~lXFSiYsL)LBN$ZGeg zg+#1Zbg7>f$Yud?diR|pmHK2qXo)`q+O1_Xt(Z-yW!7sF8 z4L};!vye58yuDgQ5HiRoosa!}tgB_}bx?pnRIGrKqY*-*H%QH9E0|}R&#D> zJVO}??KW_PAyrS=akE8#e>ko{@n|OkP(rj}&<{bgpVsKiA;Q#}Z6tws->S>7eZug` zi8B~>zCmzgbyl|cX0wFtr}>?GAOn(vO}-OgMza{r?)IlA4e_TKa>`Z^0^?3pd|FO> z1unI-86pf;V@o6dGym~mUs!8#J-UB*tOjn1Q{KISYl$1Ozpm|NNSfVnw%`T%{W`Ri zsqjvi8eJA5At$VP<#%H8?Ca$!(X|~!N^glp($QWRLfh%~R2oc9mZMb2lBlt85Xw%ZfBPokMSU)T_czNf-=Yxs%Hm6qgJ%SNvBI&n} zd)h@>jEL+h^!)1vmn)YfARE%UWdWVUwWRC1-Q1JGJX|aITTds&+NsZ z&MxWN!aY_ufG(t+?4 z6!;;QYEXjpUw85fDHj;qHIq&S_@5uPraIbKK^eJ&SbHj4cMn?C~QR zw2^ibU}mrr&s^0=C)MKzS1l4-WF_Hx| zHa?F$dfzV*VB((^n=U4X=i~rT%WO1lt}?)-MD^A{HE{lQr=9FNJ#W#BifFC({1U=I zLW14vg5qz@j_o!|O@biJ(;(}1zDmsNcAoGQnM*dlM}huQn<`5}GL70`K1}y)yTqf_ zYLn$NOO>Ay#50;>ik#?@3F@lVr0JsXwVhe_TSOYZ3#*zcZ}L62Xuw0Wg-cbAjSNwf?D0{F61GNJ)q2%lpr z<=!_c0$P4@sAFQ!Ss`&zkEJTF6>E0ztYXYbp_hPYGF3295U(RAb6({QF2cN;aVKY9 zT#!{O?|~I6>jzG(Jer=}mc*c^UFIEwEjoPg6F;wN5@ESb;-s%=NryZtobdeN3LNrS zimPwYV1%$wwhtw=8*)8iV(n>rbg9;_m+OJOE{vQQm8aO|Bx(h2_MY}9ETpOCcDW9! zmEdG%6|d^{h3Af~YR=5b=I)X@ZneC8Z{@p6!VWx2P&AWlPdcV-R)lHI8L9G-lBdx& ze13a!%n(o|;>T|UejmeJI>jTaP!SL7KhzMV2|Hyib)KiA29%ThSQJjf#J*yRWhlyAL4Lf*+cJ67~ z+kxl9SLQvK=}H06cnTCX zSfcxyfcMgsrRmE%y1DqB&rkdr_F%KR%u37mV$C)O4?y|+{z%Hjq;dc_t~j*#l5Xtc zQ-fn3LW{dxf7_yu2@jI_L1p}HE?K&#s`&XwkxUA**m3_eEVnr>_S?_vQ`l6d;^Z#s zJV6%1Up7pVYK6w-U++w(bL7F^(Qx-r9g33KK;keN>}<~9TYEJ`dt|$YA_#hpkl$!D zh{vJ!qz)#Z!&3=MoV^w(;&5nHYD-t{>k%G*FM3ag4o+oDIh^Kfw*`Wmh@UQBclh#& zDVpA2V|o_J5sUbA-!R^NV@-0IUtn>{7pJhucwdK&QLvrj+;J~-cqsoxW^aCO9b18w ziYRDr0OTYbFtXsW0<;raJL9eXIWi^uy+j{>ahjb)*nFBgROe5sb2$qt_mo6N2S1+9 z>6GNin$E1&;m&N2?n~XOU$a@Y;n=M79VW~y<8nMbT|!H;=#r`2wXk}=Ak$~C>pauH z(y)tLs29wW$Mp5+vg5X6+?t*#QTs*QubPqOU}yWtMMh1iFl@nt&A z>NPWNS8xk;e5SvTnvxyM(A`Ez(*YW(Z`=suRv5HeKirDWzO64Y6*`ZIj>dW~5hCe* zZ#om#2f>z6x)!eKbe3~^aIv0>?_Wq*6D^YpW2oyH@XqRQICN%K ze)jSmm7;byF3h`qJca3f?5cwwwew5n_e^$gR5v!==v1VRagKvxxlF^D%J{^b za@B@?UOv>rC<#alM9MuBvmI%BG$=n*$qgujiLJsXt zA>3v4E=%Njw&$7mBPsWEdih}n-3@3=I7}%t;&sj#vg#BIH8-*D2H#&fY{|(R@a-Qg zB_L1@d*!}zUU)govk6IJ5|;%OL8*WN0eWodpX zqld8{s9kAsb#xU@VsvU9>5>bbP#wPgW}RkBTr7N8MM#}AI9`%HN7|{f{yK9sj19%` zBg)Vhhc^ylwza_kp?c!H1MTNj26gqdUlDn(b_i0J3)50JL6?vGL`U4W3}?q23Rx?e z4n4#BdHP=~wLYq6WA)ak8+c~Vb^aPS5?BFnD8S4)g>5G)_ZRYm&6$H<*`nu4>ug(oY9j78$7%4y1t)JH*!h;`}G3?QI{CJ zw(I3o8$M2I$77jRLYVJN`Xb`vh+sKe_g)fmx{8Z;CB%n6P~T(+D1aW^4+Tp-R@tj3 zCI?})Q%&8I^-P>+F_%Mx%1oNo`q%-NXe0+$pjkngGoXhLp;QYv(1iza?btyj2Nc!w@ zM8jdbHNJcSt=rQA%Q`fk+TUP}2iBW0(NJ=m$z_IaVb|^M#kLo#f5`nI?!E30WR+E? zGxph8?&4UGO73A)<g3rS(xbivxkN3&dfG|xQ^)c`sPDb zGaKHx!ivZvms^;OM!Ec6ePMN4?aX)9&PKe>9*@j!t7qpbtbD%PaKs`-+0Gt)$!2Idk~CV~uW zs0gndBe+ma#o(g@v}oYhXyb5On4iRC)WJ+Tzmn~``g)&@mH-j_4Wy^(V5^? z^9SL-tf3(^+!T}DwSOdveAF1TWDPAbij1>)X!yy_i`&UYAUP7?P%P0w9nk;*ALsK5 z9~59ZDTzvmjaXBcD7p>BaxxCv>^h2M;vDfdO8UUZ4pC5 zibX$N6P0@@w^H5;3|6Uj+$tH#gSLi@8zL10qvpNm$P*_ASUT-dsnPcs%!8Hb?0QhN z+qztG9LQ)B|MVD8xYbZScU6v#c;j(WikZIA=mo)PNMhIa+9;02Yl!8PrH@Kh(@Oa< zMq|aAJKiIt1(g_^4L+O?1~+X1MUO|wddtM+I0PeqgDPyAcCxA|Nv0bcey-lCR43G~ z(%GS?brs&_G^y6;^0(okkdQg&-bFUZM1Eus`qkQWpWm{U>VQQ;-y=nj(On9QmmKLt zlS$85fjV-YpS8v;5E3m)b1~inQNFoIYu^;I(dARuJd;U4X=@PwbewPzS036=eaABnMj^@x5&M>R&wAD_n_qN+jm=qkI|}qTSyoO3 z!tkuqQB($Ew7aC}g(o{4q%aq(K}AJT4Bp$cX)xLrV$D}etMCRP6<B{cMy~h7WWP~zDG7zY--S@Scve9X z>oa6bF+7E&7fRPspSRcF@A3`&PGnRTq(D=w#E#BpG@47bT=k_1Z>%IrZ(;tpA5MXD z9Qk=m;s0EA!g>1zuy)^hCgL{z?z7d5*}KYfy>QigW0rsH*`Y-@)5Vt{U73ChFe!U_ zDB;Y^cJcOb!pk0-P;4?$KN0fF+zJO?ws(nq#s)~7ThSnef_1|yB23svRCG{$VUX9Y z>yz2!d=Ha$#gvaBHbOBLW70@c{BVefU^w>o6fdI7DrlE7+_fCLGDCrv=d*@S??yo8 zcWmH0EQZdK_92;&J_OF8?CBUtnOvMScyOrzI!oMmdyC8s8JS-z?U9C<1AZ<>A4Rz(DJA+E4J?BBcYM_Z8uF_h zw(^K1oTV{voN+ERcu-uFO;y;_YEFFaikUsm_v}?=+%$FFfMCi|uka3?|5w47d{$hq zksgf>EOxJLlnd1!O`&33LbZm|s?w*p*)BcZCoM=`oL>i%QL@LIKXLmESEMyQ7S78s z@p}a}TG=@fM^qraB`?d6j;veVB8uxH0aR&>EbpB7ThvXaBjUuuKgl8pE~uidt8tDY z4xdm;%XzuW3#_%oJoT{7Vv0MxUANYk+tBTue`F z-t;U0Xe@#Hh>_fQq~9662&f)fQq$blbPtDsV3bcg;z&mGrPV*z_~ea3B0-aTDnSJY1+;DSrpCmLklVYb+n&;mS1w=Igtk%=L_yX&_4* z*lbY(GtvCcFyzG!IqtH%au3eehE(0-%B+`^`1rt}8L`Gpu4>3dg=%yu#Q)S=ljbE15gfMNgZ$)4zw4h7HYKZC<5U7$ zXZs!my3e0sX3q@x6tVda-;iqj5`UTEv$5(6_@!9g(KLs5PudImk2uPqc^31^zuDN_ zFAB}Kc`$>yP%3<7(~xQPjHO8AoLv5`MTKn(ZVj=m(~wneln*?7Y<%{;WYX8-%Kaf| zXKFk_l!sNHb!Zj_Tq}pBTV;yv!#`p&*%#q}gSVKJ-NM4Or!*LFKiTOaTYf_B0uFiQ zNU4A8Zx)Ag){bC|UdTlEjWN3Ss1P;tv3ts4{)O}PQL2hlQXF+mm%~;dSfBj7I6Ew&3RN~ahZx|Kqz;Z794KqXR#sFoJEMICJM)UY_ zQ;M;|kaKdv^W(!oz+x3>S}MUl+dLNJ!N;pJPcA>5$Cch4BOG;3pdw#|V@$WIs;;L+ z#~6wQJ|(+8J&F@7lfR_E$2O>IUSQ)M!4>aA%x~ZRYUjyUKbQK@Umk#Y6o3UXyu7Y;e9FLs2}@~V z_@}A~j7u6h`9^&{rn{B0`IUmq>t!w7zOoEjDUaO}Ewek-eB7(c(Vah6LZ>tn$+Ta(M^UOmjeEuur>`tSU6W6ty-cqI zkXlYPWAS>9w9+K##Wd>Y|~(V(cXW8H_LKUV9blau13=wEO5S8K#F`aO&$)waDm_@0|g z1{w7xfxZB6i5~@S)hKKCH)Uhx=yY#gyw#^Gza+Mf_%wQn#JS@!tKkrrr6o zRX8?L+g;*Jx1u8&m_x8?OZ^REt+*R8K!lB)bVtdQpK*4BGczb4KGI5AS1Uw0T%$F@ zSx@Yq={6uFwU8+HT0rLy=NZT8C#_N$PZL#i@E18NRkzLMjS27(3f1&=x^ePMI}>Av z($JPAE~FhFbk}h6&)3@7pUX_uWnd}Oq0R#>$tl$#meQ7SC#Hm94OlHSQ~S{{QAZWM zS@ZFre#)L{*W)R0%}HKITo&_N)SB(&_Mj(R1CIOd-aGqGtaC_sf6|l#hurk+1a12P z@cL(*`L7o*IQ?_Z2(UeAxujWMHKt5}oW+_Be+Ai=p5K$iFdm}G-LAFI5pDA=H1CYO zd3-;0G&7WFT5IeNA8W{3A4|yss&P^>dkD%`909wzoa2v20oET59jxt>+vvRwm)D29 zrA53bN7w56SR#CM8G3KjkCz>t-&y!0r<_YsTOap!lC~KtI<68V-?-MEJ$*^uwwQ3?u;9#f`M@Hmek7~&OI}X|_Bxsgzhjwnx*6WJ^Z4+Ya95_w zSsXZ%1Mj{RAK{3Z&K04-IQzRA-F;6xM$IPRrZyUeA>5T zHgQBG`|af|py$WY={-DMBh7E6*U5(baj7}Q(RG`8)C`d>#DFAtD*hAWVPI%a#vyb2 z&F%STS&~9OCVM?Lo1FNzX*d3CJnQc`_~2#?()iPW+@)H~{$JP*womkB7rfX@zxfh{ z^E9V0bl+iA+7G=a6-Vt}0g@TFcHXDy@noX|VQZ(-4mS^SJbBHvos20N-lZ(>TJ9W? zvefBZEtlRMpQc61md{QzZ?d9UbHimvIdMXV1&uvhr4X?or|vtfYUNq0O}k4tLhGcj z&k7w{Jd1rDn=}z?ESn?`tp4>tft6(z>=dOz&(*%rbmK>5%_75IeC1T`?EI9+ZCUr` zB4k%X@>qAa63-%7b~GmOQ1+KhUl$Gu94z3D+?Gj-|?qDC}? z2FUnMH^&V$QcE>1ctqTk6O&P!Lq^Z(Zz=g?gC)0)f58$rp|1sdhsoEI zCu_%%!O|G7%O7)VVYQ zH&xqNk*lo@6at}_Mv;T|T!E^rsy#;h-(p2xGJ|#5UQv;$a}=eB{Dz70xC#F}kZ(~R ztd0cPm(@MR7`ogHuPg`yJz0A`aHONXlqlWUUN1Plk;3jKdIX@Gc+Z{`DER0iMhQqc zkNlPCp!DFzD3PlReI(Z$kxLJEx=+g7UR}? z3Ap(@lIe5$XLxRz0NRT&b{Ggn@D1RTzE&+_Hv}QaZhZmE+qHYtdX{tZ!I2GqR8(yR zNtyq+`McV$2w3Sskj%l&SZ5%FH&|ITSX84jVKj! zVozy%oTe=4K>d8+LftoAefF4@*VY2rzi#GkP(umz>1~vlK>nIl}PMEMSo{q|4|Bt;U zLH#zYJ%)zNPbxpp+A``*F8_@p((4&h+9hiAFmrxd5*6-a9*_=){3_vD)+RmMb(o2r zPVQ^P3C&4jnDVxjE;~F_0c;AV$e5Ur>};gjci5 z8C}wD(%5ejk>}kKmvw4J9O36UYWh{r28nGc)|g@lzWVZ2J@}?}r%PuhsR0Vfrn|U@ zgRH;mW7b^@=!%NzNr3T9OtRQ zu_4Z~a-T@$T;9cWRkUf6E0OpgCJXZ1j1TQ6m7RY%zUy4p>a7#gr!`LwpzKY2cSD|2 z9Ob;<8f;xsdhe2paYap+FgdLH2>ATUWb&Ni(~`r?nGD+;XGL6G-op&uUaa;6 zd=l*jFdY9T-FoQ=$?gJEb95lHhQjWF3@sP#LBuIu)u(^$ztE{yablR$h%ZpW0>>^z z-+H`IH#RjKWV&wddj>1mE7$H{p_j{`N;4?f;#f#9S8j)7^`0%46{a`rsWv=9Cn~-% zw5|-9Huj}f!jhYt)2FOH4v&9UQqO`5ql;tuGB6hk(eir9({c2jV|+ci!#z7Yb+F$v zA!#WYpuoYP##r@Benj!wnltVm?zIRi_ik__*cduDATFJz9k1uH3;tZ9jW)WJXwh}q z>vaT!9**iV7&v=yq~}juGU%H6LzvcZYl-5ff!IWr`(}j=bzp}lH_i0gjER-Io>lSb zg498eZcZKHTj|Q33zf@`oDFfa6dpJ#oFQE!#Th84_%HKcwn4&lwdD8?{5FDYXt*C& z@|>-)&X>|!j7K13_#306l?ST&ejluO>)h)%$wkvHC*6{q=~m+n za-Q9k@Un3wKR&`UeiFO$n5_&%o$zooUQ*@cEry!gUleWs-JLAQjFdd3fowh>3)IyR zIzCXWowLn?)jN(acy8Xu5Q_S!gc@GKrPxdt8!3lyrT8Z@ur6#1u+R>9)JPq3m5QHpIb4l)SR_BW zmesem$fSMm89J{IS!eL~nmS?>WLPH6GTmsg_Sp4$dVKB_Kzu;0Z-e0wuO1A`Y!=nO zSB>{TB@%p%ry%1-JE>OAZc^IR{~DR*@)KF)dcIHX(d&AXPacflTinQb7npL>^(V_r zXVg*&n>K)~-U(oSH(HbOz=5Ls8?A3zi%u(3u5*|(E`)ov)ryun@xr4~l9eXo%c~ho zn^h|WrQQtpu9)CGD!)N~wBqBCkM7Lt3pXozu}w^*qt2tSDQ?jeqEFi=bTRU0(U}o4 zTyqM+?&~pQx}R7n`bcJEvGZpj2w=fD9`c((vO}4k^o>Lj?mJ+7!V{#}0(x($M5@!n z7|-H!jY<|%9A4L~8%sI++b;xuCq4{yo|8PW-- zyK5uc&2zK2@|uD9Lcu%?Y)!@Q)lMG0`3j_-uCfFG^=mZsz^LX<GvGaZv@z z+Vh9E8t-FLPVOM5Hq+-hTUhhu^#+0HvKgF?;QK3j9o6h6P(MeH8+!_-#|oRSn8R5S zU%;#TzWWQt4*n2i^*;8@A&B)T*6@t;pUZp5f16A~kH*?*Wv`uLoBwq+k-{EWvR-*t zlh+@DY2xX7N4KX=XEAq2sM$nFB8xHLb!`zAr~PMrN@uOZjFWPqMnmC0T?9vGy@PMP zcmB~@(=T0{{n@1dbpB%nw@U$uhO~H&Zr%j{Vi9K^$Q8e|OepETLLMDYnQg7y#g?Yb;VoLUFlzAH51)Z3>D1w?u{~I?IB4V*v(ep9Lg`l=akAMh z5{YE_t^paTi_3+>a#cHLZ;=pDH+Xxp&^NuIU&L8`WDI%2C|V!To)1%V4R0s0huo%* z*E}dE8h|+3OZ~O?;=4$C%H3@a=1jezUL|x-tJAqElkO~}o4ulQvkO=5+uO#Z89b61 zIbQk~Fmmvdq^3PlE44wzp!JzFHDu&tEiLwQ&kFTX4I2zjXqs&$FNJk#4ZF?Leu?K6 z9banXa|VoLc^??HlP6xs0yj2qe#SL4$n%FxJBz}iPBdXDl>%ELzkT;BBh zq&`tWFbW`Kx8?iDewT?DSPcUSkOJN0TiMxXE2rEnoh!jUIl#(s17Ix%Z()EvnJ`ps zIr~$Jj`-KDrf`S~|3z^{^GC`p?P#&d~fH37p3@CJN)CX-R*sXqW5X12SnC`Q@e01oenN z$LOMVr!Q;r5U9yTtWCi2spB|gteNkI${ZV6>$W01J{W#pCE0d)!54$>b&Idr&8cW;c5i%zK>jeByX9lz)x zEF6d;a_l>aa=mvh;VBy>B2 zsrnX#aDw+*kDE(zwBODBUSS8xM*A$24FYH%S+$=nH;%BDUKxfVUJhtjHx~IG^=aMN zs)sQ#;;L&9iWJezc><9yx3bgv*5glAdHM<6qp_pCiIkT%ZUMkXPMgZ)wg*}L8bZ;C zaP;VC!o(#nR>2#uf`o%ew#HAY_Vuxabxi1ZFee@$=t6ac@X1+pw#!nqL|N0#|8Phy zOHAYYC@lw>*8!hqgSk*jXAkR1LOj|HIXeHM>W5Kum)23xM~7c;?k7HV zXgVU&$XsAbHau*?TM)ToCVR0JcqHIrVERXOU!zij#>~q;*LhUf!V+txN_G05OTVQ{ zMDnm=0tXk%Q}6YsMj{$)jsL$)ZanlxzP_DrYSEgMO5x+_7fXu|$OO2m6ifzA;G5RO-DEduLvoWo9L0>yKoc=;(w7*!_XDg;G zOeAiz#$hNVuxw3J>7te|f^0OIA@I}j33-&k3=84%+qn3m3X#PT_vfHJZLmAivS(Ke zQg?54_ks@V;~VtloXvB=rrtP862^Uj!nx(chAp@RMnCDz7uw;6f;r*br#1pKb~2W; z!!SNU02hyX7Z`lbntuxIZ{kua7@=YPJ@cBrMS!<;87iLV>YoTCC z4(9G9B|i-PFYvcf*LE+2-nUlPM$r?}#ISe6k-vPyfuz_GM>11^y$uhKQ|G+CG0;<6 z&h_Qs9R=ch>6i#?3{q_D(bQ&_C%QjMxJ~f#P zx09i`RS`4T(aS;#gr&+o(CdsbzcZL|KeD?0)kIjeReSdUlYG3|9sL+!r*B-UaiYR4h;|`JJ+JZak|`ys%sn#;eK>x8gXNGj zaR}$0Ty0B$A2|E#m@co1abG+T4$HN#o^~vFCj9<);cc^)kTnkGTLJGJgwTNHsq?n_#nK1xMyicUEbCAs4Il%SF%PKB;7^ef(-JENlI?u; z%3}xV{{{XXk=89=U<63ISrJ#+GZprdIh>K<^GPKk zl$MvBY&DY3@GZnReQ>G`RHK;{%NOLE^kq=vNlkcdI8tY#eGN`W)Q3!H>bBX*|B*3p zIoi%;!ggU$6-iq`hyTVrG5@F1$YT9~Gk`VlJ)9MJD)&@x`>4ciX0}D0*zTOW%S6kr zgbLI4+t^>5pIFr|K7R^?gR$=X?0MV)3TJy1a?I#dwhIY&hdz(@<_v-)^0uEVpEg6F zum|^Jqc;fOuC&xRC6?LI=}aIZhJxqirP4BF=Ry<@q=JZ%!=gT4>jUN2mzYAOnp&Da zoJ@_g93jJujna_)SaV+bQ zz?j#k$nug9S0SeNGaRR{C-ZCStuhf`KmcShSC$FuxR7RcdgT3zgQ@9XrjWU#!y|CZ z0O~AY$=2)v$^vhC@z3rsHtf0-T-5tZ%{28OhN~u$&0o$x?cB#9Uy#tw!#lGHhYT{O zJim%s>TCmWVpC?x>kvP4a6dyI4 zwS2-6H}X9K?RcUO9<+%hbT=r?iaAanHY=1s;^Cz>R1K? z=+l(EH}rTR>_5J*boksYDCJe+#f9H~qfBNC+Jx8b5S*3WmfgP0ss#d;*fh?m?s`fP_cdlt~bm4Ep|+AfD38D85wU6wlpA(`XbA7JX2`a7clj~?5adz_O*LnwBFs8mig=doUtB1R3zyD!aZGxAo z1MK7Yx~q7>QAes7^`MD(h4k`ImxXeZz(Fim!dBeYTAt>MPa4@R)$4VB?wCYZ|Kqt0rW;`=buc~!&vOVjr;jTGOdwiqw z&pOg_0^>=cHwQm~+juQwx-T@LZ$MO4cce2G(7^|~xF;Lne;~Lt&#U*h@WbDPV@NmO z270B9fq_u#Zq!cs6D5K+3OUo?+itVR7jCn6N6&9lE;f0r<;%XWQY--eP;;k%h+Z|& z4(Cjv3Z9Rnsr`h%yTrY(#wwuR-fZW5sBwa2rTUaiJ+4pqYhQNUpWnm)cr$i`U$2+e zt1R<99WZ>eQ;8=h!j_i86Ut>=@_Y{RWXpn+RUHZEN}a%a7%+6Zf~Yi)sCzaYo6${= zpZ19P9zDo<7}Pg|qf}mp607*#C-QQ?KfgJ`W|bPzT;tGQuEnQ~CmGpakJTZbfCdoG zp`;xNuhn8%#6ltVE`IjyVMw`brDHczb6aOVY_zm1BvH;!mKIt;Zf;DIk%rHlLaUwt zHIYTSbeXdCuAv!4ll4_sle0`9zRt#f$jwNkQe#}kcP_;Y(Fc_Oyuf1e7PR6_^Y{Fo zyd6lNYVp&eTKAkzSVRWeYwuMwqWQoOb0;*S)+telQyJwW&rsM93Y}hvfJ5 zxkaUvPYA`bUmdc?J5n(({|KmBZU99oL}jjqjF4L*YYLP%r!f6KSXsSeb|g+J5Gtd* z&YM~suFCX^`<2*A8S!*5&b)U^!qAkM4+XK#*ai^?e=#!tOn9!6cb@Jk43q2+1l(t) zFSotbk? z5+<$(mIhCGeFLwr%>4o?jjr5-Qy)LvOM|-VSYtDF-H$+`(*g<%d+%D1s z6L1ORS710w{K59s4IOd#K}QLialND}6V{3&|nD#1nHGkbrf3?!n!I zVuksFLtf6z`TgSwqFemo*@gF7r#qrfm_Q(T+06e1eAauv_t*3FVS2|qpPmc*`Sl=4 zyu-l?;!S7CNj=|#u)5y9?P-TTuH^2$J*!p$G`?n&)w^6PrIkXDg(EsDd^a(b9Huvr ze2Xj2(b`DIA|1`Ng2U+vMKf{qqUWA02P12b@1$@~WHj{f$&ZI~2ekGhk1H zWUo~1bVQ|rJlsp8D|-Tfh8=6hj^*C#@SAA`6&klquvVFJcS;%d-bh)t-~Z2uH79yG zn)x^Kl(FvIIWCq`{g)CG@0+QP!K%wYO;c4n=8|Nw&AujeRybjQIOOLc8xIQqs@L3Go($Ti!%!yz%PdNCo|eKG=(|A=Kf!WTP0F;N+mLv#y+y)e%%{C9 zG30B$ZVwk{YZ)YeSEpuw=2>QiX>2ia{{?^VH$pJ*5bN2B0#Y?xncv2-F-)Hdl}E#8 zPlZj9rzqU2I_B_910;W0U-hlyW>G4}XifoHM4xRI!7*$yhW{csXVg0q>NZ}A?nS#pPlqPlZ30u zLkE+DAJ36cu?hjrpTQbTF>)=WMrC&b>e8LIlllN_x%lX{p zA^HExb$`)vyWk5(h#1JbZMgRTPl)VVhv1D+!i&1<&xJa-S+RX+tN-&6&ej@z@8}JW zl!8=7s`R?A9nH8nXF+4a{{Yu1=b#ii6TZHV#jmZ24%dhD$ zt|{FMBz}UBR4J1Ck>!V@SZb+BN&?*}x#(ttE7Sev2aZ7}0T{mr5V|Alu_7aDeJQR7 z*W0!dZ<9V=+`LSIzayqvMReyBjOu0Ktz=x%4fJaEVUmJz+=@=F6~g-Hv(5Aa1jZfo zWXdd-xRoQHXJadI6GHTZL0K|I6}NH}%gv=QUW8GkXKc6Q{WxR)H5O2^nNn^MMMAM2 zMS)#)@*~cChe8)o3ER5-T1)h7upQq@zd97PpQ4M0Dp=-?HKi`$-e(VXqx;>2C=|xacycAJwG(ZK22<-s-xc@_ zj&yz%S*eJ;9>e=IBQR1*1#(QInX*E039#>YG`-8=N~4c98LIhp_6R8|uzq(b^pPuS zx%L1?L8mz!Wd@tc^ApaIk}y$#pMZ%=8U{Qi=EMJCnztkBr}f`n*4DDe>=1BKXlQm} zp(qISuU{dQk#Qr6H0uhw9<`K&p?Z!*ePL)g=%|9AsGy?QguU!Zppl^2W07P;#;0=M z-yMU&;SMNBE~f0OtA=pQr`H-E+b!}Nj%|Wu9uiwTVP8uys_py}BljVZG{htAG?4DI zx#k+(ug{L)Wcrg%I8Ib4J`7mQ*^0b;#~E2wPMqcWc9)HTz&ImEjv`xr|0r-JqfKTn z5>amo)I%x?&ReEsOTjzQ<54OBe5~ht+|3Oh41aflS45f|KO9K~y|M-4Hqd}{myZtY z&kFu3ZKm|lji|^7`!UxQ4hqe$+O`B9k0u0H2|^k2$fq$}Mo6k$u4g<{qk>`VERj0; zIpcTfI>umiY{s*95I#>H7C52QFfeGyu{^g=;jkG3<;WNzCOysVe9M!4xjL&&?@%A` zyw}&fs@R_0_-aV_+i#iN_V5KJ$y9hXq6g?yBKtatNI%;sz=CgOgfR8`dTN3R0Mnfkfyg=gJ-uQxvPjD@wJrSrAM66fP- zN3G?z#XRHSDu|h>4U6ezD$9|lJNGbIV(VA0|9AfFb(Lp= zglbazDlAdXk+o{{0-LEymmYh*R~p+P=vqYro1$l&zZD-7@HEOqTxwEkg&y!M!chQ z?RP9bH){RkS7$;}PG8b&cf!h-?P!$3yK8+voz7UWVPZl^NDwR5G{9J5XP^^b)N$E< zC>ZroH>rX_29r-=Yj&LtkkAjDzom~26lPBZqx0P-s42$}7~l*F-dKUFGU|^&-Ouj?9(4B4J?W*{?D9 zbU7&aa^eYxs2w!5B?;-jwgGcLJCQaRrRvEqCnEZXZ1}Wm_Fk zTDj52b@TfsbORKIH&zT)VXU)3byM&!m(*~l^I2i_Mo(*Wn!W>(z5k23cMg&)TDN_x zy36dcyKLL+vTfV8ZFJdImu=g&ZDiTF)%)Ci&U>qIk4$NRZRYApdiCO(Gh4w$Qg@_7M#7{zd-B%RQ5_| zt~Z%odsyjCgHR_=c6LzkcAEMN#VUI+qN$<4IR~fBhe@iHYs3UA#uYFg-bjBjpj}^y ziATFbT;pxDcwpbyg>WdRGk$qgWfzCyKPs9y8yhD3ztwL6~ z=xPCa-LSb`ap*Yqocq=O{_Mc?`cC-qsAji1J$1{RFiOrZ8@pdK1QGA4Zq(bK$HDvK` zm0l9^V;@9^ZIB(s@_Ntr24L zBlb@Or<{yne?yq$EHe@Ns#baan%y8Epi#TmG=PMOh;@g>6t#3?S3kbEQHrM7-6Xcr zF+h>sg{UHggoKQnZZ2+bs*qgwAQ7!HjVCig>^cUU#aoq;gqq1{8VU5eEZwTJ4Dp<& z7O1!PcnM-B?jMrj@cK>Oiq=?Jnf2D2Ps~uQiJKIBa~_T;GndZDN5CwY`mI1Y07Ohw zG-2Q5P*iNe=Bvk$W^dSX{QM}=G`f$?(!t@ei?>MRN;ZxCBXWpo)ttfmoNiy*QjR7F zpk-W6&g`oKxD1tO8hWy4#5A_Xo{to?H)IK*^hO!5#5>@{Y}EZM@*A1xB=2*x`Gw)G z%)to_GCqO9WCcmNXldj#N%b>QetUDWS!J-M&!~8#OS#VDRhgktCZ|ck&Tu3oa%=lw z9E`3BeYBSQb!3$(yzCt6@gvod%OFAwwX{p-*JsiIC5&c z-1x5A+0gM+o55i=b+(FzggYHqxP4$&o{h-@Cc7X}fDe3gJw?iS5qJ^Sre_4Bc)VV6 zMbvxIS(!Ftj8=j-U#1+A+Xn%9u|>MI>SP;tB`!_;v}(?kN!w)MSWj||7R2S%m%43M zbnTuppYsWyee3pvwXMu^%HUSp;5ddov;k7)tvMo~MQtBv)KGj&^s0ApVPP(1zQfR% z=5VFRxW6G2U}DMRhI+CTP?Ih%Cbcp8!pfmvp$!WLc7*NXOtOL~nK0+Qn}^D;7)Zd& zxR&y+!VmkHan96igSXMgTwn=ZwurL5TA#5HXs0ge+pQMn4}qmLQ3H38YQl6rm$Ep(4NotxF~C&&jyz z?&>s!`uBIb6?P%n`lJIa2?Xj4ns;|Z17L}ZwUae+2q|&ZF3*jvIbAAxN1r!o#PRLT zreJ0diIo~V=%8;&sN5|bemK+BE7Tdt+?6KuHiGbo0&fseosk?-0OPlxtfKfL(390< zIVQF43pDG;*cs1w$!f@>h(q0OprOqxiJfKP+hGi|NmPU);1XrvuB`?MLuTr4S513~ z6&Ce|JED17wX{%~8RhGBoU(rhwLgEJU8K`c(v|#tD?M8CMtR2A&1lyaYvV&^ex>r|(3p3yhhr(rRXDrW_5&rE|JB4*viV+A$qxbg295~*e{LH|>u%=teHHxrRT;Z=3M{4nSQla|f zPK39C6HdG^7<8c|ySExV2s8eTXdgW=eU{xPCMJe&bgcWrdk5me!~wkp&8a?3GU7iA zf3;__Rl5XQxuNjnY0cAG8#m9 zj+*kCIu3HWyTOrm`BS;aFpamzj|AD;*=n;_ z57-fnrbNizo`@u{uZ2Sj;NgcrPF_&Z-XH%CekIz(k+HInUb5AW@d2f2(YgO#=$4h5 zgzWHS8|KnjnUp0RgNiPh116s^T6B?BIL@HLoD2&KGx=RzQe##7Q2(HP0Gqn&@WTrj z+L@zyw{%}2=?eBku;Cj4U&4S6fdS#b);S~*M6-3hCFPfk^taL1Dlz%JBrU%bzNHC1 zVAHm3WWinqD~ALQ5R2FCgV=E-?;)gL6grfj?xp6Mx@d{-f|5 z5gUgP!P{6a(dsV0{~U{kUXEX131XCHgtj6{A0c+viJ>;Cixh~@LDaMY=>Qu(luY}r zex4bhEJTpBAvrp8RqP!|N*1ogK)fcjnb_;D;lK}488W<*T8_WrV27PpzVU+l1Xwua0UqzM{-CtvEt7 zY}}hplPMwaF8yRiVMo)gzEO-X>=22j!JwDuxV6bB8I2z2tG|llwK-27iFUF1ji5qEmgs~kmV`lp|5W}WA6NP$Gav0(pim8 z>65YH;d_1YOTZ!TMa-0pF(JLaP4)_1=)Qo;^F|_de}MDe$lw=KMce@M8twm-7>pEF ztde;)5{B}s3?p4vm(<>*rz(=}%`8;Zh7`=Kb8Uu1i_=p_5w2gbq>v8kOc z@r1VNZhX>m!tEmj)bmPEB~3_!e0XyI2Y)|{`B>BvD+!<9#i*Vqn&vZR9f+rC4_ z6Y5&Q8(2mh>hz8e-v)U$6ARRNns08|j3e-QREzma8=V^N97#Mm=x)wfo12`dJ}x~U za246!nWE9{n!(VxNKUzLQ079K^p7;Wj@`$2Q!ln+uD3qZAH0t=8liESJsvDi)?04H z&^{BA3moCTo4f4fXYjpD4)5QlM=s1V$~8Jeh*@bLuqvqVZ1Bc=;}7Dyfq^A+2=f&G z)i+vP;9W_Rd$?BFy2g4&zl<5LW26t;iZPXHlI2mXXSccne%e^&&T7GGh-|9T2U|yX zDULjg+@!p1JGHmh-^jv9l;OYKx#8wT-TwM3W{}Wg9OClNw~~a_3-RZT$HBv=M$wjt z-7qXAB>I$AeEuq-I0y{Nz3EM>fLhDwi35mCz)@COfGGDbKk5?amg}I7ZF= zepx<;&U-~-iYe1yMf9OgeuzrAvWw~FEcn7HD-HIhIPQB(9r9O?n9-qH|5Z~kG;EV> z4(j!$Gc9p_fAvgU_c7}foQb0}G#U+;i2gss4kr5h;mS_r!o>)>* z3PUh71d*w8paGLvRX_I*wc+Vp&*g7AxG#IXBG>PtEH}N*Z4xiv@DqM+j@ei=+2yE< z_-0(PXTIz3_DppA+&*zZjdzijd1KRXIy3yF^B2kTPF*6k*}gIxC11Pw>E*FL;A=8e zSJPbNgn^!c3v=X1pAXpCh|Xm@YufDz^C%s*_OO$0-L^XoUMvy|K~Bo1q1;pRob28% zw?DVAb}`K=NFDmbZlW)_dV)1N&*V|RzWjR1LO(YW+&`C zBKB(qYnWdJGkbltKt&)DW2;#9>$8gF*0t}(priqBcN9K`X5-4ny5k)--1-v@Nq8WR zUJrtH-I?>jD8jYz@D(gB{M8NBV~Zf9x9!oMQ3ohlo7cUhF{O zxMI8>#^mX|f(1S=UqM>%y?W=TbWM%rOGA^|rT@wuzsG1F2R$}y_kv|9tZsaUUt7-s zWcB9IRG6V-1!qtAFR*4jm0cPyyR4Cy$|{~rp1`yar>cLjSn@la(6ihpd{>cBWvN9H zv(tN0qgH(<2<>Wx&qqDXh+|(GC_O@?rwppqmL9FjvQwFPFl%?!kT3^dt$7uhD;SIS zY`hMAoGdrRn$tcPI^)29QmuFrVa-3{Oy^=yHnOO?V@m8{ZOS*>P!9xMu33HyvtEtr ziI3_RB>=^})3b6gCA84U(30bS z4*AS>%2DC-C{r~8>C`TXEWU0)tk)Y$2foA_6Gi9~JAYQ0`9f=q4+zCx35L!IY%lu5SK5-gBaZg+HZQ&yI7R%|N*F^W@nk&g4SM&NewU&ky5 zF-qEYPnI}C4MRkk72DjZiU_6oTF#8(TABE3gr1j4SoJfOBZF*ypcbPpqsZP3lWZP6 zC(Mh&M?}5;wwd z{T#k3rP{^)Ngd0tEF-KoLC)$^tFTT$Ac8hB7nXIFRo>;NKbIhjk5m~dq0GIc`mImD zKsx{oQA0Z#)xFI#F+ZZ&Wn^th6*PgZ_e@kkz@Lcek{n<~iS(ESIZL@pB%az&+v>*@ z`hXNKz;tBApqGtiW;o_NEV4l$NZC}ZlcFHt`BpFoo|@;OcXoO@Ld&I2@O|uF&x~xU zlI)tPgZ(>^{I3LZK67T#-+_UGV&2Bl35xh1C)u3%;GS0Gyf!xL zXT)oH&e$0$WFk|L^Ae=|Gk11vuIow9Hx43xDPg>YO15zdGBJg@yH+Agq`qdCENn zjD+>I2g^{ z-=_3HEHN&Fcfg|<_BeHLt>u(=ElbocMO$x&56M;q+5J5IIg)dNdH*JN?A>>8w(582 z%g{x#4VGwxJw~>&*S*E)Na+m;V`&bBmxX}>liR+~CRKH)5aXzw_31!4xw?w4#hkq|8r0}!R;L$Ibw0x84v+ghJ--?U zrOH9xfJ?3i5^jP8bDz4FuzZZkldfCk(U5X|GzykhD00nt3(0b#K*aGxfhEp*+mn~d zeG>$=os}s{g`aoIc?JQQ`q)iWVJNC}vNv~Fjc?(@#oYyRAPI4~PUqy=LEb4O;;+Xc z08tOjrI&?jT~h)MR+B85uGvid8rCu}Z2Cs87($Ob>aFk{9)5q!^zqoAxhLyEfL#Ex zef?~^@=*4e;eDxA^9(!NEk8{iSpspi-!0S+yE;lQ6%?#WqXKF*;b^!dW%w({A+ngc z`llV6Axe!U)25+V!8Su3WDa(<7892oTQKSR`277t<<9DYa%W4|Tonfg>rQew=%8_o z6j9ByO_R;pE4O4($bdC^pDTmxXc0K`?>bRJ1Qd@@UhV2*B)fEzB%8_S3+bD}*g#3xE% zgnvQ_WUW+jnbr8lhW&$QiO^2~+2->;r}E?zZOq3NYy@fLPK31e`ZqG%ICtI=se1~T z=Y+(fFy>*qvhrn1s2_Ln-@qxLh!x977nqm|`NGL*u0QyV>I{^CI9h!X%TXhm$Ohp@h@#axaOq;307$rD`g&0G$Lt$^z!0jg{cf>!a-Z2F=g0qbSA{S?LWI~ zdx1DUJ?PkJ;S6TxS=nnFk>A?v$6)h=L z4Id@oCX&@FE_WMT=2DhUyCl^#C8yE}LhXBHQddw`|D

YbpvNBYf`F%rAI);i#Bl z;O*09jjl_wrtF!{PQy#ovD9D5iCz;7#>nKOXRbeIGZOZ}9&*%MB1BVgiYl8CxWIpg zA9NMp>`e6hsr4FvvIZ^eoM`5nfsq%OtU-5wcVHv`LJ=@HlAj@2+tI=%_|?-h{w!js z3EsZAyst?eG`1I6y+;nWGl_`>izAB9nR)DS#}KeY$qN#5r731DWYnN!hI{j=1xbFW z>!E`U<^4^fBz)hO(yrSdCA5ig{!I4VIl`UlMt3Fl1YGV-a<)0Rse;CveSmX~5r1XVIwAcMri|+N^y5E?8=P9ySJ>In%RhFW8o4>55Lf;El4eTGPnm$jH6;*7F z1p8{aHD$$;oPo*Ba2Zo{b}F`$9}N*UL`W6=LvJ1T80xWp=iq zso7G5OPkS^k9T<*wSylvJVp<45XZ|ASOF-PUYt+wDZYj5UfQl19)R|EEUZ@y1Me!b zrMMOZl}1PsK=N}r@5gs?wV^lS=fFm5k={>tDyRP!m02l({r{25h_i%gl^r|>8w01W z->vY^2qk}K#Eol3RrfE81r<@m& z99{E;fd5+i;N)mEeoNbm9Q8;2j}z|aoMQrlkj_L8LMDE*T^BXVmQDo` zGo>{esQ7-KkGcfq2M?+t$~K+Aw~{SKK+?%420p;&HlIqhna|k!x^#Vxif_E;aV)ak zp0mjx%WAHtxR<`E(~^bf z=RM!96i{b94t+@Wrl;@2{daOs`9NZh)Spw*yGOLIKg#^pPz2ver0>pg-dfoM;;M;S zVP6u$K9eIcqW*kEqsJnVUo??qnj2Eu+YMARqD(cWvh(T~mQ?<8jI>ZzXZW8|q=b;r zBm<~oYb|il=b>t061%Yoh13swiK+AP#f&2#)oySZ$3nIGME`S1I0Qk<{Kj=xFN1H$ z%az!JtOmG;Fa1E#Z;dH#w@bf`q6$Y6S!X$vzcZcka7AASaL&=KOX@kZ480N9Hbc$q z;u@{)inULd!8!>rLBY9NE|xDCEqBNj<)i#Eq18R#(-JE^2%zMRF=#~J4RC@gFxOC# zkTK~k{!ZBC9pIrcvBBQ z;1}(mS_K*0Cri{IQY)q#`IK^LVPM?uv*X{?_bcwsFwZd_!JUsL$Uk#s+BlZ&m+EXU zr!0Ap`7-y*PNvt*JU8I+MA)mHfB{?!=~y<$<2W)tlI{VdDNFz@YdG?zy#rc0s~ZK) zMssu*$CHVxhI@1_BZ?_vH=G-Xkv!w6Eb6Z%1bI$&vv1-OCiVC(Xgm{;M7J>H8EYa^(DnVmuv=yThHcA!KH=ZL4vYcfSHbVA zPR7L3e!c zyhmq!bocEsNR9(s*r8n->=)S>-d-B`lsO*3|GTANf#ci0tZ{48jU0&6{s6h}ezo1+@W)UE>eH_j%Y<_z`LrXqgN@Pih@9{QmOrE8WX{GGbUBp_$yloC@ z85A)%InqjQaSJpJ700`TvDyGK;$K+@H+;TRW6l%wFNF^r$|&Z;-QhCFaHE6(yZ@vd zU0Ezby zcFR`|B(@s?2CB~8>G$wE+wD8+?otfb^avo&sx>ddzn6Cqcr-nl1;DijJD>B9mpXy< zcvw7pF{eAX$PNLwH_KzaV(W*pWDZ_nv<|==7&bZqQsm`UAAKyW$8E)QeU8g6Nk2;4FdjCX!zqxJS{*okS&J1Vb-`-LYPm;BaUWbwASOkf3(9Mvdn-dLcR}n{ zUH1J6VlOtFbgDUR5gZrKEl-ZWDKlADs`tXA-CT@Y^>aS|m|;4(AGDrtopHWb5YbR^@yKM#ft@zqIBKTHP(9c6ydFMrCxW;^;B8e_A}K zIB-ylu-rV)ZJ1&ngiQPtyg+SYFkFS>GDe9m#~w4_t}3#Vq~lSB=D|;%v0i2nuRXfW z{$QOU!B4{rK`GN=yJn3tjz}+E3(xAgOMaOy5#rAHaQ*^n1X%YwV;yL(HQNaA2C-G^WDd8tReU?iIBV-@w!!O+-W_DzKMzv)RaC2S~;1$dk%T5PQqR z5)Clrr6(73*d#%EP)Zb5799QGV`^81->6gng-JunO+e;z9g4M;YUburm5WH z$epLwevD*uRwFXvPlC<|kmoLx%F_E&>Ex!WYlI*~4OjpA_PmyU5y4R{h3Kq;fVrg$ zDXa>jvGOd!xtIP>F?{hAqGb%44^$bC8xEw(Ggi0P7u^|IeYkS!u=~ti*-(b1*boz3 z#ExAXNwt1jDouYc>{;h|XY%L1q_pL4y+l;gG~TQ}G;XbERtGVXYvPj8x{&a#9r(~yw+-Zry zGU++lLTHBv!3j8=t?nz@Izok9s}(lkpoy*W5W)XGU#re|Bl*9=ce3l0HOg?H6e^2?7o@J~0*K7{IaykriEAn0Lw?Ryn2y4jk zuQRg8XRH%qZ`}XPJl`Di?#W}4#`=9SNx}%8A%}pHR4pke7);2XYItT1XK1WoY>$Xz zw+ly25C<_KiK>#RYZ={=dPBBe*Ip6|@;%=Diw2>e<##H~Y9k(*!t_~R*)D5a;v2G-&ssn%c* z6$+G!+TGscJ7I_^o_3ML;J7XDF{aP4X zZnS3xcd`XMXK3^?C)oeyvZSU7jEme_QAy=bfb}RO1VwUgD;%^Mux$F2@jTjHLFHZ$ zJsto2)Ia^X~r8CHt?w|=-pyN~S3 zxhjfpG)+!4Wm$dT9B4es^ucSRE1y|y;JL*=E0cc{4*2}I96*` zUt!a=S9Du1#~`^-VcqmqrD*XFG8wbPO^w0|ivrT11!E!n<5n!-1o^C1!K$pf(n$xD zwXjOU;)&w(AZ;ZeoGtC%-hEcr_m1mvb?#J^S80>eG+fp9#RlzpuMEsaIr74SS;Y9@Bd z7mWgtCt|b68~1D7&D2pCsnH4xfr2bEIO69Srv0&Inv)WrP)9&ax78W59=%H}-7Ek5 z79pjAI#z`)H^w)V=0(quSBYCLMr!iIs~tpur4}`J=1*$66h7DjvP7vh?hfnJvQwkJ zG#-~jfsPpq`WALnbsna0von|49UT?D{6HMWPLq6A>Ao=*a~2P(KPH!kD)cGo^+Y3; zzjuQ?xtwuC$~Kxiq0i3MM$jI`rK@MmHjG7MezhZsm0H=cw^To3{WV(w#cbSI>Jf=wX~lz z0T)8kf*b!b!l^5|*$#zG7)xw~7%l?Sek0gVq4KQFN(DKhWAnKi>Dy@z3PDt_U zBPO8`Er;S?A$~4gkf$P$Z(mZAUBi^j?uvn(0{Vusfq+ZkEJS(_penIMOQ znN<>C;xw7&`Dn=aoU_d&Eu{g+j0bj`)sbsoh`AB0WdfzMh9^=tvRMM}$<|pia4kK=@gUMu4Ih6Jkvkt8n zt?(!ok7nIi5b9om43$OAJ6#awOpqy&fvLE3j{PHrSTyqZggpYHU=GZG1} z79^e9TM>JEGs4wpwr%tOv(+D#)e)e>Y9fo6B-q5C&2ar0N1uLKkIJ9W>P!8&ZF9UorNRKe5b+)x z`p!8sZB|6b8PP|PvMRM|XAnXHqBQ@9JfqbK2YDa24>Pr&npWEAWsI7;j#0xQ>r)RH zmun``ct#njmXTfXM@`hK{oZ{Pq^xe6J^EIpSIQaEcea}~{lf{JUrEeKBr2PtXR5H% ze_pTH2H`Iy`)nD5R#vcYBf57e1S5PB%pypy1*%x)A!o?gwrkYtl#}%yg;S%IVKO^> zYhql8OOoI#-?*Yz^h4nn$$ytx{p|)Iv*9A&USKb+a3Z=mv){o{q-%8u~Nve@W#&F3v#&@$Mq1MRlEn*dh-Tzt_+`Wra)L9iTw-cSZ`+lw>k zr;~{fM^p4@jtntnztrhwW6g~V%u^2s$JlrK;J4=AG2k1Lx645L!@zK7e*Mfg0tqEW z;kQK^^2Q39RQCtTFOW=$cbA`TBxSe6?KcC}v z)4%ev9^8;!{lyvP59cehEe=QVG#})&Vkg*O^OwCM?0$Edu_H&U7$J_CVYLmvM9pt0 zx>8%eHe^V>gKp{9i2Z^!u~Q|%8PYarGJKLJTpu$JkjALWm}|e@^5dT`ON5oq3l)RX z?;Zg;LmC=?99?=BV_B6WbJO=|mFz!axkz|jacF5PxRCp1%^`TbHbah~ofJL(iKJrf zuGvW0M?b903Y0JftOh-Ep31TJ6ylP58ta)THrg6l508nj_4qMD9;^weD{kmO%NV=t zk34&9|JlO-0=52c1X(aghW|#&^uCA?VrIt{7vJ7*UBp+JUs;{@3;w0m39wWVKG$XP#H})i*9)IM5Uit01*_q*Q)1(st1#G_oTe)W z_2qG8!*iYW6HJp;hj^UevLiG8m(HUjTQx7%{IxaNQSq~-S=&9a_?hKA*#~P+=jt~I z^>?7LO$@$}eh5!Xp1?(mp^d6Zy{cqV%cLToF^7%#Fvxm?TSyX$52zQJVLlO)tvjFV zT`Zd``B7wsb)#}`9)t+_tolQgkMm4kB8`t$sxMr*AY}4c;B&RVG;sH%`%Q-V&4L~2 zW9iEJaDQ`b6xYXCD_R%Y7I8;K)cW)rkDD_+uT5rexZOsW?2syZITC9@dHxUR5ByGK zfcC^bLQ{?78i=ygvDAD|mD^i%a*Fe?pzVe+5h#wqwU9tj^C+bek`;F@Pm%bDPG zVSv{KJYtYrDA_Sn={AcX7i#U)qbtwmwNrBC2+RU+5<&+G{+!TB3AL66yhDY$N?T>? z73EQDEtx!Z8%rr>Y+2@1#^AWin|IMEzJ+r(T|TE~|1jEz z?WR1Ta&$Y;2S%uCP5`eh?dNkLgoW$(G~yRqHUoH}hiY*V|f+AlxjJWy0hi1F1c(AV_RFF7RB#*K!iwB-o-|4@=ccHzg?K-*EoD@_Ru@BS0B+nZH^8S3%jVF|=eTb^ z)Z`Gb|5(v=`wIWPqza|(c`xR<@Mav8)b?N5JtB07S<}s4#^Ei+q==oyEVWI|M9_i& z2cL$!SX$SgW&gMsFok*rm=zfReZxg@9j*FMcodCbxaxx@(z$r9(4Db-BiyCdTj!XU zaqQiDxq1sUtMTchcZP;OHM0jZcl<(`^N#S*_BeRUc%Ez$8`vZzU;jkqot7d#Bv7Rk zrK$p%>;smKCW^0ocsCrNx)0XU*t0GJE_2KVATwHiCci4vXUPLQdU`-Y z$8T-lKMpcl+#70NaAuZRcy z?Pj65++JUdaJ{|r7<)GP&u0Ct@{ixa{!f8}OH3~NU4@5}5x>$ICC_|@hy)~;dV<($ zk%{GlF$|UGE9OAi3WqdlN=gD+NiCrk`$^XHoUJZR9T!hXPrcH&qnTOs*wLMN%|j+W zypkG0NCOtnA?#T2eE?xLnbxGM4P&O5qVf8GsgC?GdEcHb2U>>Phj_=>7I#EfMvTg? zc=44qd}N|#`X*OS(&HGVv2!u?aEey%ON*_rovQ0gw`kmW?`OXcRX5DXP=0dz#V&!p z)2lw6{k@IRGYtM#x{7OUcLXq4ESJNeiFrqUNlX2Qh(MG@wB0aWQ6?df#~aI%K@1U) zMZJcHMGPqdVG28E*LH3b(zMY2{a?l$%F2NecVPY*bWr(>Px0AZt~DvFS-5Q{rW4mE z@Ej=rK_}7cP}WaOa2Z)MOW*AfvqCGNpBFIj1$aRvwg3@Af(4dq9<${2Z(hu8Anb%h z!+NOH1y$o@hzK(W-3e{|CHQ1gp1u12m}(>Y|62m#_?ZDPB3MJtb@LPy#yGE2o+ec3 zN-Z^7>Ylory`L)@@x*>6o?k#zf@b~|+sQr~9F}g!Q?#sLz3u&Gm6q2y~qfYK_J;e%i0@_&fihbsn16ja|0w3xlSo2>=$8cK|%1#@3M0!>;O@K1dhl9+%7myrcC4 z@n2pjtkXbKWbCVUo4=D_T0}ks_cKn<$HniO3cMh27o=^|0;-url`SRQ*Uq36p>Q@I z;~7n0(=}qqa7*|%P{_I06`~Lo?n~lO`0Zu{{KTJAn{FX0a-KGC8*4W107%H+0;Xbk zOeeYG0HJW?6FdS6DMdm4=h?&}e@8*S(gaz7s#$&k2{L@5uLt+zWoH+!wLh=`;t#W~ zcdn^}nTaIEx;h8v!;DN;u-GG-ZMY4DRc~zNk6HLlne_%q%`VLEgutR^p&giE!=iHl zdq)EMD}ZI}*WtDTvDRp1us0ZmyYduBBQ^Z8#4A~_hBRC(Mo z0`VyqV(Tsc=WU@TGIHFAx$!5DjVczC#dr=5K=tfbk29WmAnl#_I!qul>%3mt_N zgb<6^STed_+Ohs^pd5M_7#OLaxX4rNW|(?CS_se|1_n?G*_%gtzJhRpK;XPY7>U<&KBV0Gl1OV{m`lYWmi)j9Y}9XBhrHv^fori2kkF z>qE~#N(Cm#p2Y93w&%Ol%YpYIb+c2Q+QQQ3W`fvUL1Qa^u2mLF%c#Gk2yeyNl&#qP zDdm+spX3PH#-OmjKIb#8$#kD+=K;_mw>XIkyrHr!Y`1T|#R3CPUm|7Uh;;|LsO6Of zszto6P7guNaW^>R0H5cI8Hl+1@rL=G2Q%igf+s40wRAH|G@>Ii9?d|{b)o3%(sK1` z>}N!>b$Kz;5EJj+99ppvKC&G!A7Qua)4;4%wa3x&65|UmMc%Li)CBCienN<3zTR<*#)7_=kA~oH_ z$QB4jkb0R6o*vEC^^39f3Gy+=0ebS@eYty>d-4*; zWk*^A68tl@p`lHD=Fd2>LM~BEDn$jxgT>HUohW#+o55xXfHsF>S32a@mVk{haj0-Q zWGj1?*iw}CNANZ@19qg!@*<1BQ`MWBj^pfT)KPY7`hcdoabipvNQa1%9aw@^sDEel zz*V&3{h4mFuOz;6Fwyb=F5Cd)AJPD)&ZyD+qRgLtFf&XkMOmouPcMMgVWJcIQYAxs zxzn^-Yp&*;-qZbffDdZ35n}YjNd!mXMeb5c5Am_Vxu{p;CJU+g_rXRu|F%L@_4GJX z=10WHn2SDelj^5@V={m_aK$8;cH*l3d21P2Ic6aiYqSg$;uO!*iRICJa1R|NCpc$1cN3mf?ha?FC(0^*x-ObGgSuYUf_g_akIK9r zJ)!~ZNbCO|f_$>g; z8pR^tdZYD^MiX3VLcPDhNuYhhSz6;l37pP`PRhGBx8hZ8NUHF6#t;VdpILqd1JpTl zO?{I<4C6h|+_a_a0c8Fp{x5G#HOjE^y7V;@dvmLh-gP{cp)frY+paQZpjfxOu%1}9F zT7;8rgs}-J%}#h;%-`^jPZT+PwHGO%ewZq`fYG9mFTFH#P^ETu;BKJgCWVUqUX-ZUN4!sq-b_seG<-E9Lhfq)!O^cp)N-r2xao3 znM;@{(S=`O^`PW>wQYJ+GSMRcyNAsLP3!Lxk7qgG5>1i=JqvS`Z@{v*lZx6%Vwg1c z#$Fl}c(O(p1HQA9^UygtH+r8|BMDG{T;lfMi7kx`eyP~#yd>Kfr3&DIz>ax+puq+c zzV)k!L11<=USJBv4UTQqm0}_@F|*y5ss?`H*vhjWM2b0foHvR(aW@x*H3gNu1WFRZ z+Qx_6^ajQb@z=SfiP-|=^1EH%E2cQG59UfLB_I^kN~#NhjL+xIc>{%?e5_GYtXo_$ z`K3O`GuMX9IgfYoliB!|}Cxlizxx zR2*Ww3tVpYW)$oY&Cw+xc(a~3XVUy?-NG(9>iu22_1Bn@HN$=&mTJOa?=8VW$;Yo1 zhD3`_zM<8BnDi~T+8`d6hCZHPuL&+E8!C|Ex4|dFw5#>EfCaqy+_zK7;FERX05Otv z^btUr85xB8Vv1*$8d2fX*7AxP|DSK{hk?1F1U#E!;_Zx8zzsl3oxhqX)kZrs<&NmD zr`ZoiDv#E8S05$hA!Sc)@gEN!-i7l;zfwLfHp168i#t?h-$1=6X(Wul{{Layvb4nb zDRna$rtyw-hB-ZVB0oR+lf}tQm)=Y^>3%Z_-VTAGB7?wMOoZl{vJG4xD1j*6;Z!F= z5{%3{otsl4udx$Xn9EoIBbWEGy#plUz_e3TQ%^l7$*tyI9p!z+r?ND&@nXmKPiQIS zVEs_7l5RWikdFijqlClQORn2doT5UyD)}pb%*~~boaocRc_@U4K~8%QuNuj&C*OqU zA-^#zk)XX3=yOd~{hCM4F$~kjLZ^-0y+0{0ahqqCW11zyNb#l(o>`K)4l!<2dPDljNBg1@m!2zQp2hdE+pDAo#5k{q{)kS9oP zWGL=Dp^fzETRn=1HS-CD^X3N6FUvoB)cC{6EWR0 zgs~H>e|#aVX1nM1k|P)mIm8a9}A8|+( z{m2JjzvDP|wKK@Dw4KA-Wzb4gB9m#~sn&vD(00E0JaG!$SBgBAYG$hh{F9APE zXZz!#Ru0WX&Cy>?ZPoZ3KvG!|2@nDGz@Tu#{<@Wab|>QxxB;H}n24TrpnpO|n%34q9Sbvj627F@>Auob&o z)6kHcGhaW!_V>AT6m^E%^w?Ki)i-~WrKz{h<^#Vxy56;s7FtNLQC!KuT<-9z&^3MP zQgImjdc@PCFLiL$4;kxkmlOWr|KZyzui{9~ilURX62m;E((P`8nNt!CXC;AFVJt~d zH2^7dJrJoAw$ovvZu^vEtf?%SQ@pnvQg^(pf`JwB( zQ-U!BQW9tqL%jSZHXy=b$A1Ko%_;=f4v}?DAFn%1{|zthp-RZL9O6&ATxBHaJW6S9 zTq=<9#XuZ!?67}epjJc;y*h{@&mYYZ1pjNE%R`Wyvp^I!&v!)B`syIv$ezJ_k>3W| z!1%xvzAK?qS9~EdB)Yr(VJS}oL&vv0vW_sG&b*@uZLZrhi1|J%0hCLN|AV)846?21 z(zQ#wY}>YN+qTVJwr$(CZSSgGwr$(^>Uq0Q#~X3FBff}p;^eQzoNLXTGcw1O_dP~I zX)2jz{4Il>xKwJ!y72AFSg8T|-K~*P$f|@OV5KxUw$X+6^&P=;EjN5@7 zdT=tDhIp7-;T@P#-IX%3tXu^IO@o8;K4})hCIa#S5J^}P2*jahO#dXF4J>WyBE`#)@|h7&5< z)A)I?qR$LMGu4h}%oJAf*S{nIt+cGj0nlr628X2q;0@@>BUDU(q6x_EM5d}?sy4Sn ziY*Bh(EdZ^Hpe$cc}f64!0(Tb?#q1l_MTB^Pja!>IU zR?Ly5e}^j?FCr3o+Ncp8VPVN~fvA;~T<;w;<+&_WFh4mDhrO9;{Cysrkt}=}qia!U zB@7D?xWH)MbSzV(XwG*FV>1xBIW~rRBLUVjOi?#b5Nnj9QPIHP%;s#owla%d?F4@m zs)nTQ5Fn6@#mq_acxK(4LD8pn=bD+>k=1Zk4-^y^o;HR=Vv>=XOWE3uH$^Ru`T5Bd z&ioe!GSln>wnb_g2n0x;%T1mWV*|+ww>0?pSG3+5O9RO!_$1~=$CAS2ABQA`j~Dr< zQ^scCX*u&^a{Be?MxuKpRED~uAAfQ*U1cbXXRQ&t+^MO+oGI2S_A5Hf2!)^V8+B)3AWNXoS{W4*S+59WclBm>z1|vm-IP+wrX$$< zTKb|cW+?RStZj3EFq93ztSRow6PFc?Ne2_`^a_>fg$b!e z1ej3xJjYq#t!6t*Y6-a&AYHH(Fn?U7ywF&}$${i&UdeOfFcWuBbNJF`Zor`|SiKQZ zf3<*DmhWpGB)nK>N7%G_A5cgP9vXr!%LZ2HP9kBt z6!OJaHO%(tJj@q8hd?5A7N3#?7%e5zgxiXWHKG=RDw*_Yj)59$9L+U8+SHUK9Y zXlo*0-OojCqw40KeClWP3b0~4ihsB9Ya^daa6NW#T<@)43y|C!%y9Ed1${mr)9V6R zywj}W9x|UK?=LX`AgztB;Lsby$(yXjO4zdl884LPu_AcQI`krUgo9OcKlC=pEvra0BbDa9yIG9_t#YdI_;rGT|$ZWexqi2Q5EWLHo%pRfpnt2)TQDn10-GH z%=Shb`6~^|75J%5qpb8^VLe#Q12kK)33kdl@05e!o9E4f`#DQVYu)p7EZ_LE?jjQo zJnv{Xpm+sX5>T&TKmt_kOxGC-@GVf-fN_V32*%J1+2F>`c2bxEF6WtQsd#t-# zbIBThcqzUpW;AhQ?Qb6@Pf8G&z+TSDy+ehJIK)DC76v=y#KDu`>XSSGl$dKr#}Qxs zhA3$SZtnwPC3LyURyMQXu&iu!4R3PRQnUxtynySz#h+}n`m_B`0Q!Wg&()!~U{JEa z@}V)qDF)voE6aX{Ne=IOSN5L2`n_+juN4}PpoQ-N_YxcP$!F1!LRH<+S6Fghe(KKB z3P=k;WI%#By}6@#;GRbG$;tK44P&T^k7RR={Rsi}zkU|+{`^ZF{STe#&)m;Si{MHn zLP%Gwb5z{?>k&c>MwDQuCu(f$;_ti2PR3I&IgmMet|cmT;cZ+t=fEfNt951y{d*p| zE0c~S2E(BZ6(by|7gxS$$F?I38VXMtrY%~E&B%dE3z(~S&3wg(xd-DF)_9wk=>ABF z`?$y==$ESq^-F9t1+ooRm3VU9o=BFIy=d>H#);aHEgJN8S6F2?W`xFwnt#m~a#nce z-9m4r)wFPvgDHZUMu>N<(e6Kl1^f;T>mLfkSc?-Jll649`QC65_YbL}ihG|#6Uv{W zASB!)N&gq+alwDiqze(uo=4O3y8X|O75*g6rTc+92R`>0W0gNHM zGA{c+vCe4bPYwx3g1xQb?iF7`#AhC@0yUmzLpLLY)~DLOkk8b(i*2mJ^<>Je3Z#E^ zLKoHQb&wRnC&nVQo-;^qGMWuUOaMuU^j`WnI8(oEa2x+(h-*83r_FhQdWzZORVPE0o*|a)yGgt)R8X`+;lA2oMTT9r?p6RAujnbT1v+jI7?D6dkP~ zS+U=6%@cU*Ix_=twE14S6zJIckyVwM3?>uiP16+qe^hV`=m5kc`^r#x>W6CZdcLbM zs-~v;%?dRON*DE3R!TvTV=n2BW9zZy;u0!^2Z=N<`*G~(kJ%Orv5Zsek4`AhzkA*|C8MP$fINka%& zP$g$y4vhdbz9qrNIX2>mqC13)3aX$v3FK z6XU$R+4(O?R)HbHe5rbECw^ zqT^{}D0xM?zn!QdVl~YA_Xuv_lDrK4KJ_n1bPI`KW0|b^kfOJtABBCw zAqis;=@<9kxzFm4KCS7yLRhBH_+I0?iD%~%Rd;4r8|-n!j*P6Ivz*IvH}}Bl1o@ie zdCfOGo&}7pF!!TxCPUGPC~(U#9$`A;fLPG%oS7U;IMW{1%KZs^$>NPUW4&+%@4Y13 zID`4YB|BVohtcDc5K|hftNFnx*HR!279|0lnyrT1U5OJAky>GkYDMuuc(NtIX8vl5 z00LE?P3@5EBbo9FOr_gtEN&E8S2WlcMOMd10>-kF-7fuhu~$-rPinHiFU-ySl?+s7 zZ##O(KnUd`YrM3?>(uB{qGsXy)}f(D;wSIn!0(0`tyWT(ff+>UR~UmKE*Yh_5@iZh zcK1!)YJeh`2vC+%k7s_pOUcgx1LDpXKxk~TelObR7rldN zrH_kUN9Q${%K5=vHvd2`b%zZF)M_YdA|fT^*yqf>M~kX*2BSR!CFbS%X>KgSgJJ8lLP$K^d}#6^#Y4L^jr&>MgVIw4C=lc%d21 zIoBFmjgKFZUCC)`MKSZtpmp$7RENpZo0E_U(CQeKv=!c_Sl0SMq73A`FPt3V5tf++u z>eS~4(-V&gq_(K&(JR8fA%d7z8|SgomMVMyq6EL9HFnO^%Axfolvy+fcLgke+cNtH z;}cFAFu=USvn?cu85{fYdHZCRj{Y$FM!09w^IkXK&E|$x8M7g_=E`AatJG%XEwEa_ zLF@hO^z)bn`+hOc3YJx{-^eF}`>Tua$14#hgw<^ADSp+o%($T@>p~4H`m^># z?#c^@m~>;eg-ehEgm0d|2pN0f_^|>L7H9A4sFx%U1;4O`-o*q{6o$2Io3~Sm4*xhR z9^|eyI5&&4MH0whEQLr6Z&7ZMH;0GA87fGGZf~$psx8YER_&?CZz9oTtA_DyQ6#R0 zx+qwc=NEKv00!U$UWEz$6Qo{|5lR3-o5k)3a{}&*NLO3@5`fpoc>=D9@Jm7tE+giE zk{3O47SMUO62{()f67~2V#?GtN)GLB7SXn^8RWh!@6)Mz z?_`74<4FeU*vUG0@`>@?1N7VdD+oLoR5Ka?K8{%FSd~B9|Mi{6#w2Rn8K7srbSE_U z+`(zz3HsyS^+L}bND3<)9)h1o7Y zU5)C^q~V7o^feEX=lq3&;~(RPT7y8TpUoXbx4A(hDVLLwjD0wx=XB>6n^T&Lu+%)t zO;j98v_TdKcNQ`MkC+YTXjLQ1Y;#Wa8S^{@0P%#eTd9Jv(+aQI-)>?_(|l>l$%0|- z0@=V;9wQ2M2M4tep&Bb`ssujO0**B`1`v=ILiIELp?hyGHSd zFXY2XJ|>$&1P;)>c}5rZ4rAPNI;{h&S>___PEVh*kHGiInQE3j<($ zvV*6WGIh3>dM`Dq)o6EuUr|#M0R*Gq{DDQERtUIMK$Ln(R7QZ!YAni(?+{vyPljU& z;!PMAkqiHToV6yoL&+HUsAq&sB)=LY)tzn!wp+({{D*Di!07W>{8E`;K_F#yyH2co zOx!cOiT-8g)d0{EVG+N&x+CaSc0=Oy*~p*8_Rr2ZR+xB0V@YNk0@)*;N`&z-_ruGP$BUdaM7kl1u9Mf`_28zJQ$2< zRaW7ZXCPOSv;B~N;wSqDE_-Fby+HGg@u#5HL#XzD7OcF;xQhziL4Z^)S7Mf_rgb3r zy4%s43LeTBSjt_n+WCF}z|f!o@a79d_`eKkhTjPwj)p4O)x;!W(6MexW~(UM(PWf36|je z5d9eLxCuq5f|8sl-8!NHkbl9+=VY2mh5?Y5(VXs`3Q8qY-1b#$QR}iM7-Pak*NA)f z1c7%8;^*Z_Ws-DJWCXmMFne&ifz=7d@nt^(5tM28d{AJL-%Xv>JWTM^=G7M@HsVY! z0y$sP8Vk;r(=h91PnW>9yI9(sob3u)Mc;@E2HoCavo=g`isctZHzL_QP*Pra*c*{b zV7k3ULbgNTX?8qmj~*QGtxQS?fJ15~ft!4a!eE>g7Xpy*gkHF(F~=h?M3E$y9DoR@ zCC=BNGD(w@*qeBIQUX9yN_Duk&rkK>s1+fnz#II<&1?`iW%BZ)LV-75v;l4uH@!X) zL;I=a=6XCrouG*53JaB|3IOPD2?fTvuBBKg-#G3XPc2##{xe7j+!!ltcW1FM=7luF zPfA}qH8xNjRT(tRUxOI&l8RlECOACiNG}Mk#R(G}{lWX+qr+G(^oG~8wz_XLohglZ zYo&axB*!j(a4x^aEnqG!y@vE!FZVjG*BgqKVq}i=e2FOtoNdrFtt@YRhfe}?#KYqD z+Dj_2RGyk&SI>mFonKsiRR6|wH00jOhm>ohsY&k~1pC^*=YU^r+(7Z!sbqNA;PY|B z-2$CW4mA#Efv{*xxeLT+1z|J61-ZP!X8K@3>yZGY6}~NV)p={${e<{1`+?GBn*lRt zjVddRRb1RCe&%%or@yD-_GGmY;$PNuk2S zG32?x3Op#Jj8TcG3#b?2dare2rq@CWg4|gV4Ur7$>_dIcftg_$+`Wpg`K#7@A&oed z17ov+ES{xJ%HcJEI;4T*^9RC$(;j_flA09yH?|;5muMJlCZA7q2f@~Yl)}Kb10Bay zZy+jy>-3L9?GWEGgc!;yP=P>Jm~s4UNg_461AsZFG{foEK>Ag3gM(I(%{Qp=NqX}h zDL}A-WYz<5nBMXYIMhyH#>AzO^sliXecuTU-G8FZ>2Sni(5k)=i2SgOS)A*ZFOYTW z?a>68M1|3TCNPV)P=K^200y&VeZy^5bMz%-9Z}km%ZOY^$>&cBfVLj zUJN45-bma=+k!JTthxu_TrVO_1U5Py(UK{!;>}#5YJPj+b$2cL+Cao}(BOQ_Pk|NV zS3p(U48JoEfIt0#oyYa3onPkbWq@0kte};N75n!v>o=2JZ@wC4uM;aRHdt6}wjX~+ z$ebj8yX57nDSaT@MdM-_)wjLQn@WA>5=Ou$OYU58K2)qBNEvm}6Mt}_CD0U}=w?1?NQ?sjOS0obbVPFs6ziFFaxrA46%!qhpV{qb5ck%o{QEC`3c-J` zIZ0+k4ud2pd?GYmnEx927)knHT7Vkiot54=rYDoNe*_};rbPcQ1Ss#?VQsDsbWgcq zL*COVCo0q3=v(ST)t^*#2Hzya@6RJAF2%b26-ajQUVfEe&wDGuSanrw@H8K~hBn=K zR!pzltlvF2zB(*Ig}1;8gI#&uIi)l|hfhxHhtIg{Zv8%f2#NdR;^boQBP-+a z>AEo|%XBfM8YonFgU z4Pz?*)vb*1Oe9(u(F`ezXFbYiHrD_6SU6kIMMeFS7UHHd67C3Fs6Sxkl%1m)Fe}NU zNjK-s-fATIF>U4%C#iugaA^afc>6Sj!c*_!Z`VbZE|hSXVZYr4s}0%iaxL#b>AcU# zpNjAD9Zv%I0`l&HW+)TmEoEY1nv)Pzqu4&989MdvbvAIRw_lrDF~eUE0WQ7%!J8So ziGd{ahL3>Qua1xdh(`rR_x0>)Tm}TXpMcq#UcrtiyrUgLqxDukXynT<{P(dfd;LbG zQhW>$)m(IgI-iAzei-kgc^b#LadXzBF4(J)#ev!NW<#AP^(RM0QzT&VP@IK}4}awk zpOK}9S|D=uRYYl`vU)+!QDa0Wo1)P-eaL-$;~Tk#5wVzccc!mH8HSdlTTFjY1gaB- zQf_xI-0@_V7g)r9M@vk3xe=~|O->V4Zo+4UZr1v~oB0&TU5>qN7L%H+?p&S$tWpW@WLvGuB{$>^N`*sp=tr*iX`gJ2Yn`}k#N$Af? zMwXLn4l0^kxS+V73$dEt({9vyg-KVo`gVGBEjmtNe9Q~8_1CN!xZ%>aKHL5o5qftM zgP)0QC5=2R`H3&jLWc_BWAD5sbz0uCJS|z-G)~sd7Xm#ECQQD|x$V_-*($o&nDM^n zj!Rm!(bY^Xy ztS|IQ(;wdHXFH3WDU$vg@0eKr`b5ar*Y_>eW{@NGo`Vcr+1%#jqt50;!};zPW_m4j zK!7F{7^nKV`K%!WQgOkh%G%SrT3}!f%He}(=~6NMBE-Vo&5k; z9SxTi+AXx}-#&#OQ>TEbtxHNuuB>*vUdL$eCX&vU)SQkswr2R7I-^%xTNiJh(8E>E z7k6!r9w6Zky)Ajg8ah)Elvn(Fr;jP4OtR;zdGihCLqo&+A6+T-sL)}$tblx9 z({5{MkoRydHb2=;=AmhRYFwk&8mzZS!Nr#RL|9z_Z#(}H3D)BI$9+A+Q6d5^R#F% zl6E!-@$ks*?WpXb8WIaOQk}sPP*#^6NRjlAUW6cF*u{l4ykE^$s``Tkg!MIQlqC*W zq1`;aG^1Bg^1Rl7C;$M00w3JSaciehf9s@J?)|sj_IO6z3G1Q(=vc) zH2VueK$^mle0WAINy^zKO=RyraJ|o5i52NYCy>C5_63y=zv}J9%vf>h-y*& zuU(Ktp+DT=L}t+VOb+JC948=vkfpNfC}ewD9CYfSsws?u>LB6 z1{45upTfive!CY4S>j~+U18-c)%f5*Rf9f#DhP221@J2N#1F6VRq&eK)XD%wo(^ql zd97-KrAlanw0-41R0~ZCeQt+h%ulp|qQIp_%a^5HW!w%nM1*j7A_X92RIUQG@KWFb zD3s3^LHH>6B-n$qR=+lG_x_n%(4s|*q&2@#D0R@I<;8FoFrnO*-+?+4LD)Ok(>c$x zgoQ;$1obX?oNCX3it_}|(wo(>abbu6Mr!-ZYH14}lj`MOi3K6H1$uW%uPCd`&w-_y zF*!%|owS?~60)JP7WmI{AYQD^P^4cu#tb8#J0aD~B(0Lb_Cc*s3e=6+Z61D;#z{_?OIsU5o6Vyb7G#AOMU7X8L# zZELazAq^(u;chVwwJqcLqIb#F2;ENE8i;X&sF<^v&Hv4yofxO)h*)$i?mBDEQZg4_ z68I|`6cf;oI32r}I3ufO9E~Q_RrvJ-7(j(0C=G4#6cSD*DS}zvPqoq?z%L=F^uYZf zr^>uDi8iqQs}9UmEED> zHyjPW;v3Hefbq`Mkf1b7rEH%}CUiUAmcep~sg*pbCW$2yBYKur$5 zUU;q`zuNiTcTg1(iIc85K(oCk@$s>46(D9jJ^90-%anmY#Kof`Mu1gAo&Q~AG&vjw zEH-L%Cv*%#&drstcRyWk_9!8Zg%j?i5DlrbEmXV*ovFN3*DMbZe%ofx3#%vt2QCUM zycmh$SUw(-7ogf#a{*GM&N3WYxb0sE36Cedui8S^MH9*HKY-Y>Bnkd!B-#-zZh*0_ z5D>KDd$FvJ-G$+h7T2w5=tNI*e_rBzmaU1$ryIln5h46!yYLTHU#}+l1u|Nky&;JY z&nnbD6#^M*?T7_Yo_$T!jH2XD!}vpfvm4g39Xdd#;Xk)Bp}d>2*dron)k-^FxlTqu zqMw^Ln~T_~f{FFad@havlolMG`Zm<4m|l&L%Ou4KP8CpG^q=|T`2AU+9`{1Ren7i? z)jBlhGNw~<+8D%d_w>K3;qi-Ngy)r?Y0KTv%m8U!NJQ%~L&G6b2)B6bqyWPcOP=U% zpud_)bhvfQ%Nc(~R-aAonGi{o+|HatEF4RP%}{{=L3T803}hBi+-QpymIk^4P=UP8 zYtX?5WE_s>7WflhS6xX?Z`?y-QgL#u&uY`iKVJ!wa_6im0*qANuPzWQ%T~ka@MxP? zBj7?9V$n?-5WR1BBXh2?bIpp@77WyYv6&_m`Iq*V#bK#0&ov)&l9GM*+sZ-;%Fh%C zlb^F${*kA{`9*%pVLUxp6do03KwZvELI(b`mFd!))-OQePqn^&40`#4D-UJ4-d(ig z71afUXgsaQ3DYNU0Be-_^Hf@4CJ58J3-NT2^Yk~fu^PoCB{n#y{WJkVKq_dkPps`E zq6H@@w?!IGw2|VMO&2F+TxMrRCL?QDbuW5}IsrWYfc@1}0Fys`hk!#%a(JoR5LqQ* zwDh2{Y-)LUpqkEWxN4FI51LB^b~QykUz=#}vv97$BNbj*O+O|TR&ShYf|?+p*!+&h zv5~oywa|%9l*NizOffdTyEoR~{!_`vnit)Iye{_|*x5pJP-oe)@CIilOet~8n(F+J zC$l5Akt~^jh_}K0w-6z-{ovidN>5O((eL?HYhiFfWrWsB3alAy`_qF4E{9_jY5lm~ zE{>%6aP(GKApG~-J_G`B%W`*}^Kz ze$!{E+nMs#HS_fLPmvhZy~gFtaI;7b2+OvVy8uEC2o6(R@XI?K)=yUSlD0OE3g2$v z_0mVt?71a+-akQWG~m^|TERSjI|h{i!$7f;Xpf;Ot|+H+BSl+;M3}L9z^V9P0w5vV zT-1ZSvB(NMZS>eJ8{*Q^0Gl20D^eSTO&LrLlZxMVpS%CwYOKpA(NBvCS`$K}Ufsai z_>B;haA^JC;fPB9|Gzn++}i)h5%;_lEBVL1diBRfqZLLJf*;!0jn&x&?8Luaw|P-4 z(BciQg5l**uEccuR;l3hHAta9ebpoF&dwvac>wrv!gjG-jQZn7z@6aZQb_wK>KH<( zSE6ACf%8G}S6YUXND61Wx}Y8kaI!X%hApKS8G{Rj%K?ATlOTD4sncj@HD5pL-{*Sc zdEkh+sZ0e;#V1J@Ji1JQn<-s~zV?waWdaaoJm)

al zc{iPD7#_IEDsurMEI9#Ya_GJHLdgml#J*e(k(KF z3!>HcI=aE71^lE3h)wsl0;(2dP(a#p9`mQFmA|uEWMkgBufZUK*LDxf78X0M6)jq^ z?gw&IX}$i5zSq+v_eIBR!{2!SOQXzund$r&+x5$UVKR5T-Q1vou@S6EU-s_-)Q%5V z^mtTH3^KZr9@3{je?GXj2#<}2UN18pC@3&e+3W@}ULlfSYvF4Ro{#3m#oNPmd~t>D zsPs0+!kF|_1F}2$ETc9elGJQtp^MNbAm#<(g93ad;h?vOpfpfNw3w?)1y0)01$6za-eso zb{KtxIFuEG;+ya4D(FhL(?_uVMx@(I)rFBCo5pcD!Ype}v4?>c%BA3Pp!xOS5pQb9xYL2i4ox zSB)nNbaI3VVXKZ{%z>?&smNz=4YHf8dHMZ`VtjOI%pJ>tLz$n{h|**UGjZW9-~8!j z-4m}y5uD0)yoQIq$Ow+R#A!Zhy?dth%R5DkPq}`gs{wX@O(i6?8J1IuEy;=#x;Mu? zPR^DaV)W=iBzx{@#%f{*@qxjm2(>pf!M0{N?1)9aMpzdkTfSr#-iz&!s0sYZFIg4L zYFg5q%>eA`VA2jnc|e~^E^ojD)J;*a<$GH3$5(4o5j!I)$2u}Uv!>n z7R>aHmtp(f4rnF1eTfRN4^|6N&&$}Po$7we!CnDC!62J!}TxF{va!3RXN6bq_1D+1_TVmfT$gcl7BRRf<^B7h6XmCgY^G^i^0@mF>*xs{8ztHvuZ zStpXIaVvaprexB3-{0b)N4ya&k$|AcI>OE>NDAxN{utQmBa&jt+j1B?fC(l|n zG(Z+fK(2MLq_J9Sf1jD&&V1rb%&2hR)aX)Gb|1FN(pZlI0D$t3grd*^ zG;#V}+?_t)#LX{YBO>O>L84c(=qk@9fO#Y(l#h0*2qNH-Sb%I1 z5kMG02u`^}76EA}P={X@MlPx1aV_F;%@fTph=16<`TiLX04NA)xV_E60rqscmEP`Y zc6Bwe*`9D~We4#D9ygnqiAevOQ9rj~-U`z8X0cgau=VCcs5aN_EV*U)5DBO|nNZ zR&*rQymKCF92CZ1m%T8q^I8bm^N;<6Ibtc0`V@b`b1EeC+5xy`p6))8f%u_FVdLOmrAnUB!HnK`@cw41s zCRCO#TZ z^e)uP82?R z@6oebC#hDeGfb(GjyS)}eeT=vN-pCGYlVDsA4BsM1AdgZ{Ii|Ia8lHmXqK*S>~Nts};fVH4&|Iyq9=aZCMW zRfzW1&`=G^t?NB8J#*IFBx&6=U_r6NVTS%hZFh;}Pq~$l^h#=X(u_JVPKJ;5%_4F? z7yoK4+5Cd|t~@xB3CIYJD6^Def`Z>?D-;V4-WQw&0R(=boUB930P0ohFwZ>zhLpP5 zmcvo_r$r^k1SN*bm6!p5yKBRd+9;6L_t~xe*_JGS4S|}9+!C5R;{fx9>#d!v3c7S| zA!r5MR%@jB3IntcC384>pkH|81I3BLh~i%&F^lZX_G_qzcElQUY$!}Y9nHZy*lvgL z(=S$Du+rNf4H^wWq=z-<^JADI*xB2T^>HPLd_$`(j#umVxhX{@TTi8(Tf1Z%9QTgV zERc`(#rPUKVcyaK0IK*b1#*+Ki^U=R_U4Q8akD&D1lMa@ho+Bh&erAXW{yi)5tviDL z3hl^B&+eT3zqA0T`-2X6H>*`F)bCF8e|^;_Ml(_G7I?gXi_~q@kpW<2u&r^{6H`rb zM$|iajC3u<#wLopUN@AV1fCAmeJ(HI`S;MQmr>CEIvne#1G`_ElVV%1IMA-N zXk`^sY8>2^iEqMuAV2&K2ANJ+c5%lRb~G~<9MEsh-yic?BUKj=7QeSy+NductOe>Y zd?fawcjLZ~CxEb>#eAXhqjYU@VU?mQ(}yHt9YJw?#Z-1sjf+~8&h-g{W=2evGuo0s zk=|9V-V5CmC#9vzs3|n9yL}NTX?hTJ$THf>k}+;iD*fFAL7W(5HGINujBGR#WiVky zH`95|k4vNE#79ZtP=snVOr=+K@TY$D0i2~kM|(I+1uZg;Wm#4gwNJ%mQnyb4483by zo^_}{oTyZu0e-;=U&zBX-!W7Z`L7N7YjY|zBGQENC09)D&!)?Yf}l22Hz0b*URq~{xI+O^XG;ppI?{q|3ApGtwtRxUA18j>mORQRQchr2PR zyLm$xj7Dxoq`Xh=rCloyUrS2v)%FhX{6al~KEu4w?Q7qeyD2l}fpAS;`tH~z7$ZSb2Dg_(5huwU zR}Ap$4(W4h3fBw?=LR>6YZ8EyQjD@%cK<&$c*!2L&igsB*a99KIk z!_Jxj80+wzM+7)Cd8MLW9XVMk*CkJJla%?KImf2`f@1s0w8p?K8Q%+th+L~4m1fk2 zKnl6a00Egvv+Vss9`lu)Jw|rF-W;zB82IM53rX3Ty{ZY&2;&3BR{9<(fzMWA5)3#o z^M^x^)E7~y1*Gl0cf3IaG3#0cVR{v=cDibAc7Lm)Nd!iJ&%Q5nxneG9?1RBsJfZ9( zCei7qCEUOyrdiLqAO)YE7g6W^pnE^|R<^;W)X^C{CK<1VgqwpeP-V|R1#(^T>2%!` zfxA=2&s3?3i%p-lcBQ}lj1Y_L+D}r1qvYuAWlgD(9QX*an?LH&@iQf!H2=x;2)o@-XOuUC;iK^T4LtGT&LQ^x9}m_eRc;!@*F?yr_4b;VG5@GDnLs*@NZ%WK6q%84Ag zasDj$0g{iIN`)(Ux8BbEHa&EV(D@H(znaRL3k(9!QQ`eS#k?lU}e?Y+}W6DD9xzLU#QC$kBl&gb)0N?f=%EPe(0Eolne znzvuE*E7|s>`Oy9Rhk_MJgJ)ywd$#&$w2e~C6aVZMv{EE)Q2$TXyOxh1Djbf6>f7U zpUKqeGqEG}0_>}FjtnyWWDS@Kyd73=T68@g{t|(#4MR=o_~NxE==%x?f%#qhD`y1J`)ZsMXKc$1&zSIN5v=Rc;(Uj3PB+ z*?Q~mF$<0gAVx*dt7(s^sxqZF8$6nFWPDd8t-e#R2pWIg>W}zQwI|QV`h<? zAJ?Y%Nx26>eb2wpHQnOz6I`(V-IZ}l2A_+`I^56zlLf42w%rPiFU-xq;42M1JK0c! zG!##Z`8L;B|vsq=@PTbsRx`p6t0M#cWQvM z`fK#Jhsdtmejr%0uQ4p9HMU#XP*(0GUt&Jop1(Qpr&?~60^qm;kLb<2XL$0Vk6nu` zFtL1}n0z=Y0tp(NMVMbX22C&KbieE@X^o4sOunB6i9aKsnipng+qpU%=L90PrUzh- zC8F1d2Aa*jUzj1!7*wfOBn-zbQob9416UQOG#UI7c=Lx?F$YJwS|Jx^Up)yWs(h~* zDndK<5BB7w=h0qo&9}572+&p^P8*vl5JOTEQOvd#7fxAYR3KVQ`v0(h@C0TG?;r04 zd7c0}VfF4VB?&IW-hD<+QlK3~EFMXiH;Z9(ziec$C!1s&ZJN=|HygMMdUuz7J_#uE z*Iewbr*bJaCecl)l66Tc7k-AlW_8>mmpj*ety=k7|0t#isL{lUwBvefRwB$=9CxlHJN)Y&37;y z-*3Y933{vb?LS%hJAwC!xTz`7x8z#x`To#jIP9ZRsD16gjdUq8GW#nE>j@I4LDJs* zsPKiHe~mJv<)Yu|+NbN@+i}Cyci^v(*6g4+*S$w-Umr?J&rH-6)cD=o!67r9OY$Th zoT2=?n8Q|22wFjdXDe~FzVQ0!%iLC4k6cvI@rk`4k)-jncV%3PMu2Q#>3vDBy~|=K zG}d~suD_?on>0EoGBw7j`Z@Qgn2_XNLPu(PVJK5wVE7yuZ^1ZB3<&qx5EeTk4mk;(5 zmWyRJ?+~x9NmUaithW#pufrMcuBdQ|Js|!+-tICuj^;rVyd{glVzQW-nVFdxEoQKo znVHosW@ctt%*@QpvRGQZb2A$gF*|Yp-HY4&R@E8VU6GZY-M@G$6QNd1hqT6;+5KiH zKf%3ol)O8ckCljYdV`ECQI;oCHSTcAm-@BZ^wWpfIiy$B>wTl&(jnfDN!ED#o;N{F z1*>(=ZuxO|2$xD)(wDt9ZG3khmuz7zHtw0c-uC!yY*V(tLk1f9-UTgkgbHtw-50~xMsjFBhvm2GPYQS(#-=KO|hg&`s$ZWc3+Omlz2R-1ACPt4*<&=w#v)NHGpw7SBhs`oQD{*ejb0~Q5?5_yk=0tYp0#{AIR7j^+6TDwBClA*0A1JhO!1ao zN39NMch_E*u=frx3MNh|=u%d1KWg(HBijqdDUA5YMJw?9kirJqooNcB*V zTB!hHD(I=eJzKskBW8*KqolY=<^v#A9;pxYMF*-NW4OAAiF=Mz1DHE|y!@2a7cC9w zze*Q~BB7Gs(4*1j;*lvT^ml%Macblst8y~tR%r;JCe}ZJJ%^V|wlbz+>3R<=Es(&3 z?dphc@&kz(+}j%d-Y4bMNQ6f~A({meQJ{z8*6N-ojMY*^Xso}J_RM9_{!!7=)5un2 z!D`J+^pM#sKO@{E+)?79lJT;Z`kSNen}?%px6nGkOOQI5S-98^>E!r{T5*T%San7^ zP2TQ9vHN!$jB`JZ2biea1W!+G3a$tYByI9=ro_LbF3i#;1vkS`I_OU_-L(-=fZIJs zq2QZb@#t=M8tv{lo0Md1la@H42#<(Ji3m)UC<-%vTh$KW1tn=vNfLo*50?~V2pLtD zp1Z9HC%9?C5&>aEKcj_J77<}-?YIRGcOG2~?>!_1@wwbZ{Qy>symYda-s$iDbx`L0 z=$fzPkY2;0WS6hAi_e`gh4!#K(S`ItLYk=>X`N6mkPZSQ;kVHp334c-KiptArSH^j z_}tA)>o+5lOM5?GH&EqeCB^>aij6ulj;VMl;R=pMSy+lc0136V)8itp|sgqaG#!<7AovKoSaB~kSQL}Uw+wMH{>$} z4epo?{PIBR|6>od0PuR|IO8O^T55R zZ8-O*Nqod0Zx{(88pCC}a>CI+D;pjep(0c>yd89BemHQjjI<>Xn91QJM(10Fs|wOM z4~{uJs14nkB#=4U)ORTT!+XcM+KyRrF!aQ(yF#JDXspDdyK>oaf4YAp)RBpNarc(a zr0~%yspc}bN)$m#8_IqVRq*VyEGORVNhmc@p49AavD0LDO0M>~`{ve4rjAH20f?@t zWI#rxetRdPyy#zCCMI$Ic=>m#@Uk$SXUR5?gU7=pUw3w3qBwiHt7nz;e*<){xNL+8 z&QH9hR?1+)e)qaS$~?Tp8)ut51H{im{Lw7xjIa_%R#sV@?lm&!59xJ2TT>exqWD8Z zcMo?u_JXV=gj3D_#TRVJ&Pd?6zDH!YBocVw6PufMlitX)pma*Lmd3#B_AgFAIkoB6 zw;0GFrn`w%6K~Pgrx2GoSEP37;H}7Kj8ZSXQkxuq(jJ^D=bfT=Eth(VPvX(o>IJvS zS@mAwuOQWq47n5(_Wf0pxoOPWpQwTkiB!TVTZ~qDr1GhYRbq;$qA~+(qh^qov`7~l zz&TzBk^hfIX#VZLBSLvJ=XAZ^W)FBNfItJPQk6Lc-$E&p1=vi>?;GTw_BK~6FAFe( z6C2sPJ4o|5wf-_7lI?vL&pW8#_GJPS5p)#hB%~y0nuE^!w`624m0{fga{t_&BwIFr z?;nV?(bP+~EfP059+h=z-)ISAM52XG-ik=Rs{ybWw&!w)WdowNIYu_WTe#0pN=>j$ zK(oNyFmo$2<>B#e0sq9`2cU=g{Z~wU*7dADSmC_6i)4Yh>zSYrs!2%3thq-1DYTm0 zz=L5nVaQs7ZvBlm_$lajOH**;8WU0=JuT!t>7ptK97lVrLB|zaX}&VUp+~-EqdRT4 z*E`n(eN>*qT=R-MZ-|f|PuswRu+VDjA7BT%*d6&Q@)-=oWR2r$thF?fz+T@92TLLpJss}@5*gs)G z4d9ahl`l^_82y=Kms;^_wfroN*A=yVsZ+{C8srwFCNWucnIPnCEK)V;+$BQnvV~Og zDMql9&%ikY!5JdzU_>hm=gpD9jh}hE3Pp*Y9iYHe-MQ z+o{&s74m|Jo3m&T*+mAcPV)oSp2(r55*SfIA}P1B!4oTmd)tF1F7iz657L2wwGjg* zQK|(cCd)-Vym%-h_ys{ATH1mP%S0J|(DL#Fc8rzEfGehU2ov2Uqh+V8j9=e)2#?S4x>% ztDY_(Yzv8a4$5zc#?B;PNf+q;Utz^NNHFxWVh%?lSVf)EwMVq9^VM{^2Wh2({^j6! zLnagP-V!rTpV1%24!gsYDsW(|xWjRqy2tCe=mQZPi)d0ut~$xRGj?Q*{EEVi$+=pj zOFSg77B?eqY;G~JJ}Xlrs`Q9f$g?h!CO5U9Sy4c0rN$^|QE8*zf)kt(3K{8J`l;=m z;7|~fcY^j<z(uM~so7%JR zzSa=42A5Cz`hRt<6$5IyrQS8Z7%HCLG0b?Hb6qN|iG1 z+054q4xRW#buQ27^9hY5SjGap-2mS3$)pG>7vj@Jl?pP}Kf%gF@_RiZZmmo$#vg-& zTUFgL7X4TJJ)%ySg%L-rP?QuAAS&E04|E8?hyX#Pb4_sHMh%UK#deb5^vpmFtmD1~ z*c%-OiWYXa483Goia~KKzU%L5Q5yq!{s-5-6W~LIsI#o!{cS>Texsqp;9lJ*RNjz4 zq!KJEhw=Z$l4V3fR|L(krST4R-oLBbaxmQ#pn695Gd0$~urFN_-Mu{?Kz>a-TcVt{ zD6U)>06QA2;&ZHwApUVRxsh4HZ8l4~}er zFAd+5eaa;q<~W;Haw)PDp(!+u*!gW+#w#vKH7#U`>G;sN$)tYc3T`opUB1Dv1-r|O z-t@z`3JJeEv^fTRr^4*$qr_71GmSDiX6|6lc76$&yUQxD?tuc;t(TBV>CnG}QOqh8 zA^r&#ySII^<@WB6$oGh@L@Zuo2P9(x-=WzR@iC2bgaiv z#!l_7$99J4abW7ROLQXtIp!_@^a9L3KN?gGDhJ~2-}O$-P!Gy|I;N(*zG%3FJQz7( z>!V)aY`K*7`gP)_cRqXn)M{pS9;b>@9aZj|lUO~O78XbVK38<_Lqqzt0~}9_aX3^mya`6tU6=f0%xZdgqKzlR|pZVs5FqGu!mFqRxu- z68$9)E@AR8bX7an{?jCIW9L>;&G(s%S;@$))_dUf(OYQ-lxQ3oM^`Oiqr%9Uo^GM7 zgSZ^Uv2vVq*JR>J@7AE8nj^h(SFa+W!N)xXXBfJ4a``Eyp#q0&Q;v)gvvOCnBag-R z1A7JFl25>SGX|Kg)U&v8Z48?+Mwv1)DeUdR-~a7zb>m9sQ(nxU^pbM^EvoqkhseD0 ztsrltpJrL?M2uT~wjM=wV>K0NhqaLkoRQ;gQqHVu;YbetflO8}TzXweY&NDsfBO;W z2t^PaQadn%Uq&kl7Fm5sd_NLQmgGHW+$*;=3Bds)QV=O{MYAJvKqC5(*yMzicIx_a z-cBnLz8{lQgiQ|tKrL{zyG)(^U`~-N1s-0UC>dpnaYL=E-q!hC4(#ZX^Yqj_rA+@? ziW(VZpA0=vaGcIZsm+$%-E#n(QYXhe1V^7it8Fm`l^>%XQ&w&lNkfW?^_)=oYq^ma zzcA3TITH6hF!wiqg`1j;{{3@uMOywO-XE&SiyhP(mf~Tt^^$NAlGc|WN_9rwC(i>u z4*P~EMq5ZpmdZeg%Cib6zQTEkY1k(&J|N*|Xg z(mn6AagdNC`8kBMtWYU8*~(kc%c*oXb*aN!1JIaarjpgyRO5H?)ELus`{~QN?w{Qf z_ag=p?*G*94~UOS`9+FaZx$Bx&dnLiPjUcjZSsCsVH5k?9-iM2?Sfc5-Zs~fKX??} zU_Cz%h!;q;#B!v|7(GCxEQh`fds0u1bOu3f&=Lq~Hkilryj}lk=BVJlO)#d-)i-D6 zlfKS*?SPfBa%f&r!u?0Q$UOLpzw+rGuSYT&X0&?)8Q(SI%$@+@!yol&cRK0(KCXeE z95FVZdpme@oT*E*iM^?E+12~eTB2Hwb2DFj73dq|lt2yS_X-oXaOWmhRvPr)Sdt{S z+t=b5`hiO{MPVrn3FX@;{0!P z=(7KM*x>PS%3qH6Z)^zj?`){mXt|KB0{_o7_(Hz4xcd$-ah?#y|5GPe7=g5#z3S}3 z<(`%Ns{(FjH}03QeZBw8^I9(Vf1LURe(gq1Rh4Oab{c)oWtpRu9iw7T)dtntkqXXF zWBRISmJxL>Pn-IxKhchnH9GT9zEXFEY774|S9h;p6B<%rZ@lrd>6|~%ET7y$PikxE zI}6>V{=lkDs056KV71u5XFvJCt7_9|dLwgM`(J|8e2*Kc*RT#(^Hz_DiE{S3*OK&~ z@=e9SuGe%q!s#s_Opk*B6R);&(N$daa=edSJATPf*RSI_`rAQBSPtMb`Bjd=RzElH z>b1sa{F~cy{3GYT3XfNrfV?gLxMata_cesX``9(VKEc)CKW|N+eKr>zgS$Hu7Hhu< z?C811vH?xkKFOJrtBxK7;&~cn2fExg}*dCvNqd>|4KuCN>&(Jr8s9W?9X8W!XpZ9d{ zWc&dGHOy!MpmM-5w%t+a`^oPYsihvc5LklC}$LPsv@rC`eh>$ie#7CICHIyHb>h-#|1_+&ibL;}ar=LFNe z!2|lHE`8welHL%l>SzK9X(WMJdNX0jG8vT~Agc2wE&aZUV&ZLNh=J>PWDNJ5c#>3>Fxl=0AtSxwJ+}y(P@Y_op(knr zJN^`Sydp7u8ZW|U`mVHxtHe?g`fpYlF=`IvyP;X|JNg4@A|{=Vb|b=*5nTbxJVJ#Y zsm&&;9Ug0(>`vm6t9a>bIkid9_DJ;unjOM<1%J1}6OyRO$2aUm>#RRon&%_0(E%%x zphkJ5{drIj`X>)oMeARC?fKm@rQRnBd0Za}7hHRAh3u`8MLifVqrQ^k56&M^$){?r7O%1i z=6RBD>a_g}TEd&0zu)!rQ(8B^4m>ILQ)t+U%CMD$Ef6aNe35nq0fi~FuTfRM z)z=l8%!Q5aCOEB63@KYfh$=)O&$<@@l|>u+?Futfi73c!B1&iwRKimTuE=gr+-1LD z@X5+Iyn!NMm*k@`k97VI2~0%GQZ@l3uB*x&n=M(2vdrWz%077&*}F)A)j8#WJ|a>oA^{+LM2-fDOTSC4G~G}hg^|N!>Nk0-COBmacSCQn z8RLByxl=~>>Z(w;&>-oP5{8>v%9TLd_i#sVd`|q^1%Rm3uywrV;6H6zs zK;_F@MUxZBP00=&<-&}9BVP&VJ209q_0~UQtVmMXt#gY;$?5GLosqG9k{cU(^gfJs zSEJ>f_bsdGO-f3~Ww)WBrG9C45-;z1@c$=0PCu>{K4CX8{K z(4};N{DaWM>Iq%O&t<`?7188l!5w&DjbP8`hUAnpo+&tdu9{4C+~WUM${qD7OXN*YN`NYQ>H6>F4kMGK%{glqEKt%=(UD0x2n6*PCVVa;W!*EF*E?79dOKc z-Zob5I)anqv4thGw9{pFYcne}+Y+Mr`NcI8?QQNH+4Ndfk21S?2U=U^#!t{96su}& zE{P`1QKgR96?nduy?0BXBe8#3`bc7fR$ufTo!`2hEe}){m)}MF{!vL@W3*@Lf*X6( z~+yVgL86B{byutA5V%Y+S?hP-b&1W7krm|a_TvQ932^t$$K%)2>-Kg( zi@1>Lk)QA?q{X<7g$?f6|4wWDOR3Ra6|}TrQ!CmBB{F38<@23~15X zl^u))@r@!qckndgWAan&>5g1VZZN_y=mS8l*{d0!Q1+|sPlR~V9g|yHP?P)&Kpmq$ zCPDmLq71xNk7%@=9-XB>emcK6M0P#ooTZ#|6RmTUmbH zn7N&vaA7ryZ9~irx6A}F-qz2w@UNHA)}2%oO^_#>yfD}hZ$BS$oLi7^hL$@>k%Wzz zwFbEImz!@r8j)4ZdDBL)QR=BPKCl5UD@c-Nf2K98BffGRD9n4T3i1v-Q(!{Rx!c;E z5QVY?S}>IAEU4M1^ID9;f0h|)^q3hzu>>_ z7^vUA`z%-?T7Wr_B*Xz-A6Zwd(_j?ofBipm>O_<6E=Nt|yJmnURz-%MWA7ez@wp39*J;T5X_sZIVvSGlTB3^6gm{{+G#x?^1? zjLTZd@ncI!oIW`C-khNmcY|}EsrVYN8*E*+d3i879Ll+K^$lUe4<&^f6d2wJv3ls# zE7>aMC6-M%k)j}AvU38weFfy%hNtMo-$Ho^i8sgEoZvzv96&j$8>dZUDN5ExW{s1Y+em7@3e#jS6Exu}i-Efu!MSvcCSA z{gFhv`pToRHoM$7QT?_Z*v9}=s?T$VyF;;p_VbBN5vAbyOJ()F8t zlW{K3G>mxVfzo%4;^NALr4!Htf@T!H8{=p53B z8N{CtGwK5jyk{5oru8LXN=Sz&!WZ!a;@3ZextFMm(_*nVDBbS#^NM+mt&}d6EN&Z zDSu#&B0&bd6fxs4O!1Wi{gbw&m*cwS&!csS07auB@31d|p4Xz(d_~Q(^0jWvX)2A| zX;}%AOwl6>}Zi;+|!iuVl zRi^4VAzT-So*iWtc=U9f`VQ220Iek>v^mm2$EV)5>1`!a9ZOSaAVHVOn2Z~~tmEjfyDe9Q1_McxR3-@cj5w9r~?G)FN1Us`eZ5*fUko4dg` z9P!5*eq4b8Tl(<=u@7gu8olR-Mj=#1jx{C&CQ1r(9Ug}S6%b`>RjOrFl3!@q@-NZU zpDPlg;IU2FbylBxE?4U#lbPHrt-m;lEj6w!U!eg$UKz*OhrfD8*psdixg+&)$E23j zc;;9;paSbbjrn`9A{Givp}7I6l?N}UejZ-n)N&k(opPe%X{9>FT#NbC8V4cm(A{TEH7efD&pr*793i~V`KI0?7%+FfR(ia4-KZgR?!5_*=3g#SID zFNS)JBE?wwb!pLpV zyCN?X`5a*uh_J76J9XRAE%=or(8|kTv7Xf^3tkoJr5J#$NUGqm7CP5HNXAU`Q`PcH zrpYLAylj_4PC!94_CN!E}U)}7Ek+=(zrL?nfVKhaY zCcw+5cdCIn&T71lB)+Mb#Mz{$(0O}h6-?32&_wF8@~riY<5?%A5SzVUmqJ7hIS{5Q zs1UWgt1ctt1sr(7k6CQ@chMFI3M&~IG8q~~yS+QgFEES#R_mq`kAXh46-F|#&LKqQ z4mnDk7!xKe!qn_VN4yE3yGyA`P?a_vE5P_E8MdNo*;!9dE-^|d&hI0^Q;9TdxIR_q zHIsU44NqSy2A`m+?if@=mk3fwv#Wdd6%w6sd_Ku^QJOual_kf=U@gwta{Ynqbp7Xc zb-b|dz8&dSAxBdPFPj#c6K!nyBSgi)CHc0KFCKjCXl#i0*T6twThvOrdwwPO2!({5 zsHcNZ^6K1{kB+dmF5q0#k4hK|V{6mFzcoqm0ThgswtL@Z;klrIbuu*QN0c9-m8 zX{Or#I;{7Q!Unyy%uk8nEPz3xQ|IXPWrs|p5t%<3)aI8f$afW#QiQU8#410G%Covq zaw{7F$`AMaL=-H1nJ87HK}e)7;W-lPcz*Zf`4DhepO*&8t3lbb#+`0PJoCjKXE{@xSo94H;hPO)zFbuqe06{Y>RxDqqkjtv3ZLOY z=~@R~;eBPKEur@f;whW;RL{*=i`Jbg`lZ%TyX>1?)h7X`mB@LJOE%@k; zk+vw*%Qu+&@cgmZ%n}w)@hx$(|m+8NN9I6Logpc7$=H#yklaNKH^N;S29x20&6s(Ec@3HVQi-ybf=lak_J z<;X7d@;^?!eLc_qE}xsw;LB>&j7!w&MxAAjn8z>r)xujb#eG__35k>Am0V2mTbA7> z>*U9DWZkBoh%2DCRLJ;83;)5#TuUFlFkr4~s6I;Du}eXdSa4X1bL`_HRPv>{OsZ3C z_bUy?>3vaM75)|2#h2Lu&Mn{{pPxy)4gB!xsJ<>Oz3T7X9DwC;J7EgNpfOSx92vgU zZvFJBQ-jMXkf*4P9;~TlfcE^bFgJT@sYL)OESouMXYO`VxBCiSLrWUHd&VmA&f}6} z_!?z&4abTz!*v4bifAIRE^`o0`Ain^6RAYwOcJ`i_vpr2v~*be|oT zQwDC9xG?kln)BaBO|^%Co}a1_O-Z?Ud+)30sG_|pyP9hHnxlz?VyJHTkQewTS!z{!QA2lg-OGx&QJMKzyPic5PcCgj&JC?vBC?m6 z!+s4ewZKc38W50&X@7BxvNC1vGD(L!w%15}?NYb<6Hzpf55JDE^cqX^!YqZMX(&+S zx!s_)WgCAZY{sg7ZqO75FlLpBN3cEy{S^c@0q{%|$YMAZ5yO@io8+6TR};k#yxsh6 zGH|#dZ<|q;S;=w)2-nq{n6r?H3f8Kaj_bYSN*&oncvEM0b%SazAv{@{i{shOq#_i- z7rxz0Ve%j4edMTq`%*pgUT&6%k`f9jaj@-kmB6A0UPcLsHTFva*kodCwuBrD5}VB) zLo_B=Ya{U#gKOWgB2`+~u#TpCG%mP|(Y8I!r{qcr8G`;oDz~&d%H|$pRhO8`^r6wM z7<)Rj^>-e|BA~$^cKW%dsU_gjx2oFb2Qr@fagr1~iNS44;=Ow{(`ehNKzXlhr^zc( ziH+_AQS84CF9{Ll-Sl!xa`oPm?e|_aoL85VS-$mGKA~)tA&gFASXCLk_U$f7zrve; zv_ZHg_XmbkYz~A|>?xG;9P_SCG_rb;I-lQ)}k>O zFsQ@j4;|EeZ*V5Ke1>y{qArjhnZ3^%4VLd&aazG_Hzy0S<$8~Q3377>+CHo@dn~HS znXTG0lQ9Yqa>3#AHl|H(p)DYL`P_ar!C~VIg!#c55Kf^Zeu*HryNSRAw})r+bFHqoz#z~;JKq+&KDD_4!EDGDHDbVXmL-PQRy{- zt(RSF*o&TMN;g(uikzMe8(GcYFjovSsQ=~4pJ=mC4n|Tkb zv(FXoyOOd|TEEZ9R^~gNKq8{a1k)nUNFh0nwStu7B2%^wh_Ng+H8pwcd9M@`tqhBo zig_R!B=87Y6qOtT2^AIWlK05dHzzp69!a_OPCK$u<8jmJ@5kSjqqVJ?sTH6MkBH+g z&C83_zV%Z?x=GXA;AD7yTC%lh)eA>`jB!GGN^fwzm0M}bXcPUWpIDfLx>ZZK8ZHj^tdab?FjVufAgWhxIcW7vmbN!w; z`%0~Z!Hw{QEU7m8p{-_(A@bMlD`E#eR$QB-(%)2RximYQU9hw`B-Wv9$iCLN{>HYVpC3qR@i(^Ye#;8D%L&VMtb2CpE@N4=?jNO)3^@s%zo`=5Rt(n4-|ukvQR5 z0p*bX#C~d&LSmfVH7=e=IxOYP&)L~TNQaDO7woo;*3aV*l9#W3kxZcdq~M^XcqMivk>v&wv)4(67!=9L3F zaYTbeyR)v>S2R8#0J~s?GF%3WC+bAI5^S(zq{Qce!R8%EsBbMMsKXhm^80759>AlD ziUKqa$9(z`oGTO!U?CxPxl>xnbzj(P6vAxHOh* z5JIl`@kSaQKsbf0EjZ)6Z=BcthbB`Kfa__Z1+^mjt`MgJ3o3Z zXlqEex@Rw}&Z+&(vj8jl2J(T=tU&t z8r)n+0`WbA#I@D)pPGQ@r!nPlyN;lqD3Ozf^{YL#eDGGMf~fXv^kJLTU1Q6&zp%Jp z(6W47IJ_-W8TsPBhgolj{s<<%E2`TcPyVKrChH>j4S`1i92X`Wwu_ifId}|u9M}j# zjT{3HP!QLb<%aELHzJB5hLGWh|6vow`D_Sg$XFM( zkMU1vuAih{?xGq`+3@ppPWsWrK2*kzYv zyiR2M^=~#P=pbVY03E5Jj9^9GYD@?f7Bjv%joxD*^-WH%3ty#=vT%tIR}uO!sOf z)T^mn0)}_jQ~b;Z@lEr7Vtht4V-NI$(9CVb{#qtEw>yC}Sw_E0zy6{kaTE6gJi+V3 z_DIYnds;BmEsn4`W(E1#6Ubk(!)={%+(7b)qxYsmrUNxN@rlZaIQz7Rs!V*K&mWxn_)31!GEJF1kSpfZs zoh@E$B#KO--Pin(AfL5;f?$14my_RYu8<<23A$D-{6_`!;4ayv)1o_-vYgAG@KffbfVi) zaSf*?4pUvRo!;twexLuPlFrOFKD662Klokj-2NJ$LZ?fWm!Dt#tWYlPSgs)X(ZPyD zUnS1+9QKZ_pC6KAi-`EKf1RPYY564^Dkcr8~CQ+149 zwXZK5T3^zy!oj;Ed{}2MVngL!@m$=XEG(R_q(~WO- z(CT)#qG08)pp5_L_-}4u!WNGDg$wU$R^nGneEi}sL0{U z5cBXA1wva-E?xz*%n$4S9{*=1+QFLF9`uM!_}Gzqi`Kc^xZG@o&ljZpF{{7&vHiYU z|CUxatqstK?dnjF!xqcG7=(=qJw4rGRntDDd{-~A*$w!$g66L8H+tg!y>xF!Zo;RY z({Sij+b(*2bWk*zhPI&LUyC1?9DS{x3o250SdyO0u1wWH$kmo4 zkDyFQ8>owc1pL|hETc7mha+@VSVWXuh!Y8wy z1l2Mt!xL(>Gt(`Z%NRh%qnof)jNJInG_M>Y_S)$8G4y!*4^VM*S`&Hb!pIN2)ft8lxAL7uxk%5(ZX<6l#0Vs2n!)93o#cdDzV>f9*I86nNYZvt$F^X% zgxFhG%WcAwl1VQluuER|{T2aV$YbI~jSDKOXm`r%8d`7}jFUSPnf^S{MSa?+ptyqlj+r9)0w5jBsv%u_zz9F;ApwNtfjSZ`^*T zU1C$>WdxW37JIf90(uR4c{vg$>8B2-ovC$*UOn3~NJ%6IPiDYTzZo3dM>z1@C}85D zqsVn3HMpA+-5i})N1E_90v*06&oym7da@M%>kKk7y2x&smr6qNOL*|I**8k_ z`gP823^~EL=zYGy=xD-lN4b|HeY^!?L%f+C!}0v|Tv_%owfS`>R}r&o(iDyi{o7Je8 zWLZ;C>!2T_l3@(_HLAdEmRC)ku!HHZIqO_mVnr=mEu~A*Il0KY{V}Ii!oazmH!q+Q)W!_561KqDR zk%7z$ku@C1r7@Hj1|?k=SW00vrV{PgupJVFC{b=2%<8V~h-UK^Lo zy_wl5(i?BQGH$eWjQ}f)hgn;8fv!mfQC8f#E24zNgx^Pq(`u-yP>aq@Zp`Fo%+@EZ zxNs$pgbbpIw1XizhzW`u4y>L*4c^OS{_Aytj#n>HhkV#k4<)P zI^l*N^{)K!A0w}yasR0(KUJhZmes-TicJnX&M~Hmqs16(sL0sS{uR=4;i^d(ID3ps z%8J~afHh-HBrY#zYFMLw%Tj)8Mn=C<_}ULRtV9uQipgwi!1{P!{viyCh{zK0T+Mn$ zphTz5d|+f^_#kQHjp>pR@AckbW;WsiDzZCkA|i8WLHmf(!;*0owv%!(c#I!XZEFM zZyk(nG%qsWM~k8OG6hG?mAke2L&xJziR06gg@P{1rjIx2FtB<=MpK>?n36FUzB_kT zz5W{KPaO#N#@1|Q%2K^z84w{9U#!?uxzQVo z!zM?DN5tuX?(I$L$mTUL&a`In>!@FGT&jsk-5aPW&NL!3w%xbF+MyzCvW9V0!yqcE zf99T&Il8a&VoN5{N_cR&UGMNoTo3%C@0~x>pDjgbb4AX=E=@rhsnOETGuwNvsJ5y{Zi`Oz@5IY-@Bqs5 zUwguqhF^VIzh~zrYwtG1mfIx?%8_J$x8PNHhHYhu_x@e59!4UdtF_qpdhFAd*ryup z{=tod3k-|*F?Qq6bAw1zrEc$6Y?b# zC$>xCYB~=oWO4*6Qo?X7#n}3|Wads%%X8GAbij{17m%(4AAbt(U&U zgC#fTd@dQ|(ksAKmgLLDRyYqg3fStX)rh}B)!j^5S^UcYL_%HGln9Rvcg3`H3vP+!DsCLiLk~ zI=+~&ICQ2yWf!hd_Br5YhTnFn57gH7(lEzxNiN9i1*>>z+@S0PN~tr|{p{n){UOvu z=7TZux2k;fq;5%m=sKz0%xC970r%!m;wP3MWH*bC&l&AuHtGTX_WMEG7O`&QxrD)< z__O(~p&HvqQufl(TxUJPM^_CEYv(d=xjh^0_mLs|Y~QCp(SKR>|EC1eGZoZmM*ig@ z;pcj^_78@od9ek-IyC+5)xn-gWTJE^Yjz@PZ?OeP!{&J)|38Hw2j$~y_-j#e|BD_m zw$z8~u>Us(s^d-iuME^~nl9$zJfsTY!0F!^E_zg>X|t`79m4uR0K);m5V=y{GC5za zjlzA0k>}?I@->cOW)Fjiuw4s>_Qks^YdRiExvKx~F;ET#sZOI2t<#ju;KBwPRt@gP zQ193`7&WT_G42;G_)@zBfeC`O14FSWtbYW`{ixB*%~ZqpCwJ=3n#*v_l(_S;^EY=O zPgYDs*0orC%do))Un2dI$!hD;Z`wgJ-tfx2KTVIGrnc&(vt88R+eLRQHu|IRe;Ce* zPv@(Dzb`Q+C5bI@cQB$!!75KnvG2eqExzBKQ z62cN0k$abBRquZ9ygEZB0J)eMWq~Y_Y+%=s-@RX;5^DB8sC&z>xS}mvG=u;_g1fuB zyF+kycXxLJ!JWcAxI=J<;1ure?(X_3r{B3>_w7FYzJB-pdF$t{U90x4wPnsR#~fqh zRQ9(X+1cLJ-bqSiRgcUbpc?(GHFOGg9EleA^f@BpcS%t2__GT|TQt|8U* z)^>y_)2(z!kkDk7#7y1YL64qOk85ja*tk@urH1!wy11clSpD@h&SAtaDb#sVWsUI8sVdPzJ@vZ|kn zU-05Qcc|YOOk;|Xa^l%|k=0iU6SH-Wuh`Uv=zmXNrX0zQ~`@^WUAlT@^N9bpVPIDLsT z4@@>5+PLTS@9vl{feE`}IShU#E)No~bWbJ)X2x(1!W{~%4%RB>U4B*yxVQ6)roDD!Zh2}gu@ z@8)pd*Xoc0rl}gM^tzWxo*siXW?_IM?aaE?HgWJ%FZyF)2|?r+_Ht#5}teOolK=t(^GS$VZ{4dZ&!{8!5mE> zSRY(^*^q*T@X}M;1vOz01(}X`R+k#LoT)@Kl(IkKm~|q{(%JL193Aa)JsH&OCv(A0 zZ9H(-bzzH^ALGX*NQvk2(1(nmc~2@j<*x;?(SFzeb$wfmk)1QAxoQmBE3~V7Osda_(#XlcuM2vzd6c-tRy zBxzF}R+U}3M+n1bOkg4V=4;CEET`SeGe-UB;<_dEKIg(2DJ2s;gTik@5Bq(#XnHVx zczt}h>H}}Haa8~t8?8VIk|I7uZhEUXF%^Q&JVDLMuAxJi9^kag7%D9jJeMz!;xEtJ zt#`DdxpdbBzMA~FnLM2h3hM6q|J|W&YlIt85at zGugZ!FH*W5l34ETOz;G$nqk}MNb&WI|14eT zOj~J9i}iNhxgz@5KUmR4c~Jv4p6!=!^?JO$ebgTBM(dfDJ6YW;wBF(m(I~S!)u~Fe zvf5GHLlm!i@^0^mS(q@86O;_e+8BS-ijih^{fQToUQ(Xtd9_bl_0H*;n@}EO32HqX zs4cx#Z+fRWrXp{8=xg#a&VIU5;aaD(`%lmv8!GNcn)wMQ%KLHAiB!rWXNL>x+VRVd ziDOTf5W>1;WjO7_DSFG4H;f;NB*0x!)UuL zXBV$`3?8c*RlDJ)q+C*_Eg}*CX>RrPXGaWmMoxuLQl4p3aYfgO|1*%U&PwZl2=cuj zi;x)@AFQ}CNg(gXY@pK>qS2ej<-kkc8~n-pEEv~d#9D(eS6CJcYxWZfYC-|q-9PE# zVHfqp0&Q9?c4vxQ)qy3$0miEPMZ3zjz{`kzg1s`Js~qBIcc8ZeX_kKWSni2hv*`VU z3!AhAAZjKbmXcc2;{O!n)35wvRh*^PDIJ>}9|ZNZxo^;ScqlUFHgPo>tnQ?I{j)WKMJZ)*5SPPrti3w^W=y%3%MH zFOtvblQo7ZL;pB;K8R4PsxW~hV2OBU^}K1|^oOMaE7tdS=8QVU)BPg|ec3AVt-pL^ zXrH442%4jiH(B+`Nm80S_A~qJhqx&YEinh@u4yY!41tUX!JuNPS#eNelWKh+W^Yw} zUR})bqrUzbGwM6smGwAa;8dWp#waToeZpXPO_V>K)r=}}ed{!$r|C@XJO7pI!{^Fb zGqr|!HMalh#-mfd6V3JP+~{xp zq{{qkxxr{OmC4`F;pqERZ{M6zwZiHR4kb`F)pr z4&x6-(N2>4<)G%*mzkdL;zREf5rrvej<0p-Jzsk!cS#%<$wkj=g@_fzC2H%whT9Nh zFMLDKj^03du_*+;MGh}GDvlnTp%X$cosz$PZV$?r0~H}-t2V+}A`pdlBgX7GP-Bok z0|_(v)`B#XzX0UE@G~C_+e`IQyG50e+!D$l_>(ZJ5Q%m(UsY7o#;uBdY+MH;`Zuai z^L(B7RajP+5K@Kh>yZ=>uTMu%LSeke#}8S`VzY2P zFmBL}OWWkUS=F!OSAI-h*6U+Szz=zzqrhzR$hu&}VdyJQ>HJTU8to!tqM{%Y@QkjH zXF&zzE0w<6HO3qXv8bph-_>j;T&~_6xa1Hy$JWUXEga~7B2JIuA+*U$t&$Kncf?rN z8}B*2N!0LplK+U8$tJEhE4gHq{0yYUj#?(Bk7V{)!C$(6Jk+HEWawkjEJUgFj3 zpuRc^c0RsY+8b89G%lK=ZNDPa^mH!@`y{^}h$#ce!$PBC@(waHyV@k1f|1Y2gD63q z1o(X*!9#pp+@J0_`zehJ(eju|2Y|{rsAi;SjeRnY+XuObJdfhv7#H+NXHv?1Zp$-$ z$^an)Dp}ymt6030Bh? zN%UD~z^^e<2lz8J{Dsq-J|Q6zN?D}XVgJDW$?2hTZD*PTTlN)*$}CsCy$4Ay>c&gp z+n$OGqrqXyyyDb7dq~G#RFIIKHkx?9Q0dt!F!1WEnYq{$pG32xc_*hVgX&~5#w~|N zAjs9vY-;}*8ai~5t&>ljEZ%^ST`f8uQk|-4#$$V$$r+&u zRNF0!WjT=`PqW0*;cN>@u`0EB*~UXJDmk>~o2XSz%aq<23!>yGSjF>UKlk6$^P2p7 ztfi>a_kP08bwPmIu;7eHd9vGC?>%>TQqs8J{$L_KXA@2=^_U|?BG9Cyr+X`%dj4wW z$*UgQ2dvZ6a#tfWM2CH*Zf}iI3H@i(Emx1LD&uCm4p)6C^%I@j0YGi&xUQ#8e01B4$Hz)p-7Fl z&c`1Ow}LFPlW9-2E`?ycy(=_hxDP(Rj{3NzE1%SN*1g^rgBp+<&JAZ%j zZKoxbSwCrHf4cVWA3H>2{zsDi9X=Ro(ndGue6-E)wo(^9OEl!C=cw5r< zMQ%0QrtRJHkWL4vlkM0VM-k$PUE!6gN=N!FkDSIDR`-M&GCA^AD>`ntr$p6ad)Moq zQSJ#)&-P2;jljn>-2ZCgGAS0movNEk_W*6cpj-`Grd{Qo01)BW{W zRzbT2J*%A-6yL9G=>zfdY_B@38h4fzXNX03=FS#a0O=MM*nH z9|{U{#C%e%1OF|GCzPHA7)tE!P3@eMG8oN>I#x%RnV-PA?l(j2OLCSFD@HnQ$fx@M z3dN($m->G~@u(f^dia&O3!jDsV6y%bO_nuVN3BBD`Y~H)X;K2|^TvB| zbU<)sow1JQPJuNGYKPS~kua=7xBV^U=W@RE85Tq1cI`9s=-A<-hdsC0aKUKC_;lpv zbSDQBhsUwJNpU>NY*PG21rd`aKe(_LHE~%&=E{i!nIYCmC zD$66ACYUef1IIPJ@sGS-jz1V#UmC%2mUQNON#=zsK2yqU`@^~$i1p}{;~R#2!d}Pt z0gvxKjZi>A$ho_F!xA*0q96hVotRcYI z7khs8C*`J%9%6^SZ%U2vAhX*o4e#5j!}Bb?u@5m6;?f@kJecqMvZlZ^nl)WR_9X}~ z-b+C=7fMq4$CzdrGKW;7rPz>Od8kJ}`XNM=O1)Y+g*?!ujgkmw7(HalN>}4%vZ>1T&S)S^I*sl=v z@)OMEE`aSiUVCs;d-dRmZ4>`=eUa(ZaYvCBK)Xu=#GPFwUFS3^q` z`WbgS-orqu;NfwPT31)?ll2^Zc&JjJYagCYEJwrcc=_`s80<@J=pheBxrMTVP7dN< z?pGtCctYFPDn)tGd1zF*TGB~~NFo}B6sm^-9oewSw;Hfg+!qyA4q`@LN`A?DXd?RX z$M|nSg^Ol&V)Rn!mnZznnY7L`8ehpgBP=eQ*y6jte}QP$U;6!iA}#=+rNs{*p6sP1 zg(f;G4<{O7_^SHVkcV59_mm7)Py!Tb5bRRuL{H~HBMnnssYcbs#RaX?>9E>j(B)x2 zLTBBYZ-)=*5`_dEMzAm9wTnr_r8rpMv~cE95}TeI6Km)fm`_2rggUTF^sHX34Ai&W=_pNW}QF^a&W=<6Azo2rd z1Hhwt=m zWx$95p`k!zx@-&@{Sqn}c|bx!6Hs)-oyvv%?lreFNdZ*t&Doz`CJ7)D%i#6j4#z<# zM&a0=!V*czg@NMP3y<%tP7cU-P<~YCmCv#=ezjE&EOozt9XLP%scw8v|q!7WwS(6q-* z;lSeiI{8D{1a3(d;YWs4v-jGbjE`0dV8*4;OR*p{UVAKO8(GGLt8|~^)`X#*M<`AJ zLF%GV;yztL&}X{wpL7=q_xs1T@9?8bw>1RCt;p4i1&Oi0BdtwBX~J)pR_|Y4WJiBZ zl&f*QgPF$%4pO}OE!S5m-%?|Ty0w4Icw}23N7XrHC(=UeQ>5V%?QD2+pZMWPcO`Fm z;M@R5M|(H5Gl~qybsCMoR#!76LO5>RXvGewI4S~x?O~_dDE7MWN)rBl8a$y3#w5^; zyN-&EASpOOa$4lV$ZH`b& z_2EaR3Ny@_Ba;sO;Lmn4!j>t!9_(a)_ON@`w;BzGI8VtQmUbqjY#7t$M%~4&e5bGA z6!JSyZb%+!q`bbqak39gPC%<7_zQ`*Pb4YR$}K-|x*IZ(XBy$@P0uw|R?Ve&%kes| z<$Gr@Wzk3Rgpw+a4{sdw*Vm8+Xapt>q9F(J2qZdhvs=T$5%i4)HpgB3&Y`Z`WXz^g z)~-4SAF}_)P@3L<1*N5KDK`WB+3?2mkd?P?gAme2dXO4QZ)=Kbo9b#${GpoZ9%4hp zAxaawC3g!GTpk(8%<6}i3X;;bZL8xV3vjtcx1`D3y`G(){H4pDY>WTX*MO7P&H&q- zj}Bp(wKQKvQ@3C_Vr5X77DjxPIO`qWPLk(>FiH1==Z|fRKZr3m)R9SE{TEA9l%#Uq zN5#N!Z@ZlYjb@6;=P_-O(r!yog4!hc4K$*?!7De~*%Glc>k}pZZg`ng0@}xvyS3rl zPDqM?#!i(8tlVFQ9JV{2mc#Tv<~f-R{3l0lty^+zg4pxJF2+=S_sB76<_1z}us19H z&CIzc=AmgFyXAqAI1;UzePFPXI*a10I4BV3?_^2vFM-PEy!cnw#H_U#2?#0$>45)0 zGt=ZdqD$~b$S1AwnzCcAm9Mn|s?l38>3|L>fAevIS9>t+Qk}yRT!N?O=1vSos?=2I ztY4x{kp=Uh5vJiz!AQpR?OhGn5jw@O-CvqRgl^`vG2?swv~Xx`p+XKqmeA#&eoW+WOUOPP!IRe(`_-Z#1qu2cu~XDh1%lw zjnAf_BJB^0qU)tQyCEa@Ccef`aYcEivmf7P6MUwIgGjL~ucr)A|1|E<9b=M`I#YCx zv?8OfLuzLa#d> zRhhSua3h)^c0cLk(jp+wEJs_`G5j{3p@)I0-?I1zjmakbAPiaTv1;s;8g-~sv2WEr z2yY>q*}h-GtAjHOH50muAiSC`*cilPf_%)!UcGY~$;A6wo7^dwvH0OsfCx9f{^*77 zKz~QcGc#UylsL@NaBAs*uRS0-V|Xfe9hI$8x&M9qYV4JhI{9bH&f@Dj_`R6>3K6-R zeXn#m17RDaGGFr#l(zT5P+#|i77GmJJY8uzXom5(z8l|lvu+5y^SR@hKXkDPgU(DI zNxP?zyuwz9j#ZSj=w?}jTqFcUJSeEUAu2+;AQI@Q82RCnJ{P-$cuqW@^F*o)BMb#_CLWy!}k6j=V z2FF9aVt zRy(-OVs7ut6PkY~;&d<2PNYdxxR?F!lc&NwN=o5R;-f`4{rXs0@PZ0)`U*}$+^SSs znzNxZcm4dcG}(W05%P2Mzi{g+CaGHULvTzgDn@ipLWnUn`=hKzek*i&AG@Nr4l`)Y z@vmMMd@RmkJX#61dAd^$p-mfnCTP0xWf(+;A2NR!eDm-Gf|TRmWir?Tz4o;WBL8xf zZU1y`7P$AXNrsGqGMSv1W!|qqGqEY0N$GziGb7h~e~ASVE#PgHt2MU7tL zyIKY%uT3y&S^w?`{+CD1xFI6T8FHn>=Px=Nr~jzRYpBKvHIDQ~VLlwD69@6T=U30wh|9mH6#D_DNI&1pS)XYbcHtFjl@yWSZrp};w(C~M%U9Wvd!T>hd4-7|8bxWD&F;?ea;#QOX1CDc*bw#n`$Ze1gsUrkHD zCC~eAqg%{^-YKXliXO;jMw>SJ^lDA1II(Ha_J=shv^`EMId=+zI+D`#4{L| zY!gIv=@Xdg*TI?Rnoh(#4h2e&ger|Nq?S$PI5uk>S#ez|iu2}OVv>FZZ2KjMZf-ao%uX^O7Wzy<@I81ofXEZ&x;6$tC<^YU|UPV z<36>oX99A%wiQZ8f{1V7hq?v0mYbbeGpGwK+6`s?_iLR{ef3FfzgNJhG;;P|!XcaE`{ODcPq z>(^Jm?@Tgs&G*vPpS{gL-AIuMPzUD*y;lhIBVSM8l(>YpuY|u4(wjTHUK+ydKS^_Y zV=4aQNzQ5qH9cJ@E#~5K%SN!C;3^4|!pQgwc4oqx(cucKGn{GNGWsv;pXeOucf;;L z(w20=RowRFpMjqgwEnQ(ZB}E5dped~n;u7~@U;I6;>!}4)TknBgZb-zxJxTAO5|^B zH7rpGCr8YXRnQyCrD)_ZOitJ2L?@4CLhihKxdqs0F|FzqqwCNHJ)Q`}L3@TI=Ooy? zwEI9|@m!yA1>1k%CsF^1S++m>by>+%8T$8rU;BBl^7qCEbtil;WhriMZeA(;#|L}? z^Y-i5Qs3mP7pgjBt^RR8;D9Q?mASK<1%;x2H!OxGOZhqLG_2fNc>n8w?t7unxMVN9 zll*ToI~4C&Y!3&A3F{Hx#o(TnpN-JOtq2o-+Oe>r=~Hc-s@=?~rzf0?G7R8Jk-3 zRFO5fN=E5vLV9Mn0c_`~3=au`yodY`l~0KzEu5DWI^wNYh!|R};q2PHfw5s#fJTP} z2i6jWW`jw&nwL(#%YSHDkn*BQ4iRrrn7B0MK>?5^y%xh7EvEPIRPO0UXN`ElL^#oS zd61lmj~QgHP|wbbgi|?}9+B@I<6LdeP9Vavv|JqVdssu z1uyAVFcKy6MdAM_>NKsI+57h)p4f<2%S#$pJGkp>CSyA86X32yj|o}#F7SoOf0t}dzaio71xM#op={NavcqpVW1{H?IAG$+ruriU-frGSv5(qTt>t;zL?|2`}Ls@8=`1dUc z>UOnb*x2HqvFi(5Pv-0G)*_(FS_n^kN>*xJr_3wUk?q#I`vzAO1o}{*@{ypbwc4AB zV{cem4H|DvLMffG=`o~shxX@N%n}LR1CUU9<34%IK>eg zeG^}FJfpf%iz--%oRREK+kB3HTvp;tCfTz3Auz9Am7;x~78i|2z~94?fM8JfMS+6( zE7uO@5j%y>FmFmy!Cj-!$#e3iV}(m<@m7VQ>c)`3L?+QA<^*#K>>9US^YBKLS#Nfw zRUUO90ua4Ie}INd9K2Fe9^o(I2x9a<>cJ)LYJxQ##DRpL1A~b%|4e#c1fg4D6A=;F zx*z!XlUn>pgfQ;5_nWBWMaW3=9`Eoz$kZNR6>;m4RFZucRY9d6?62{4M15m``t3hv zL5(^&M@AUvpwEIya#_czY|gi-dH@gP8a^h=V1$1IT)ZUrX2yqja&GdTBrYHkoiMeJWzE>wA8Nofk`7kX061AgjBO)LpDSg?vl39OKlJ*HDRBu0|fNHt%?dI{Q`p} zn<66KM$8y4BYr7}2fa6rUasmb#>IjYVG|H7KD`Ks7pY?TOgTyihTa1j|;bh08{vXtxx}9;H z8DWd#Ls5cS&F%OIaHQvBWkx zKho;mRlm&1w~j@jWQ6Htt>{(|h79kRNc(}gwTa*^St9%2*W-S8M$NJkM@YM;Wl$5x zaHh@o&>8^5m182_nx?Z#>tf{an-<45eveF1MfaWZ3nrUjJaXSzADJ~sJ+!F9`jkoz ztLyd|osr$J*tKsUUk6nHk&w;;edgC?eO`QMQW{R0bd#&w+QLV`S;!O<+9L9n&k(pZ zAadMvEzipg1Zu;_is$RhiodxN*hjUrX>>iIX0Q)zEAU#bRg&QcuM#Y_@{F~sp4PA& zA}VIxgLnq%H~yrDd5pBIM^kAAKjSWK{i#)Kx=HL`1#RZDY{aQNX8i&2mAVR~k-97Q z#)AV#7dgeUK^XX8rr{+DvBk;yLLx&F6M_**`ocISXJ#k-IK-MZex>MYVnW|e2b-X= zIk!1M&jmjdf>39O{^h83z8=QU;^h$eb#pWHj++L^*pOvzN3y;M5U8-|kxspAJdJ}} zf+VI(#)&Lclto{~E5`- zNGpbJ1VhAkFWo`S8Z}y#8oI)mt+XgFg*Sa4(#iLk+Vjd)I8@)xiXv#h@Q&6;gVDNd zjQiWNZ94ZQL#d1l@iNO?jS_?Kj#&(3GdiDs)Y0>OAF(EUcI zVS{+GiL)86-C85dS-gXL4G;cmlGQVyKP4fEzj5S(LCI)NG;^lYOrfQ}e0mWTNCEb-N+#LpKRdrsW!@KDsI z+%aaWzrk)V))FTJ5q=*B#HN5jKsiFe$CLjs>m?tb)%;%U;s_1bGlDd-wMg8aP{Vy^ zh1Jshz^PIp-eA?`Unc(OxMFL{uvrxq4*7nznrx^EV*_$KE)tdiz-X-ZLTx4w z4R?*kkw82zr!NH{C)P@TgBBXa|<7G(VvV7g6UeM|_Wx0|bA!(&M9BS0ZQC zXdjgd;G;l#xr#09(0^wuQ*HnGxqqdfvh2d(iAq|ukK9|ol7t*Ws74}#N!zs=&$QTG;C z8X(IkkhV+}S)Ee4$>@J?_$L=&pjb*l9{=bxvP`47$(v%h1hUNKLJ|+9q`SkTAOS&a zG-JpGw%9KC@hj zEsm|O!(oA`GDL%}*C&#_DH4v{@~Jfm1XCuI5P@$3{mWzedaa?t%OBIW4C+^b zE-`;^n7$}py1Sha8AS{|vkGo^p6iWAjk?Hi%U+zz5i|Qkt%~hpGW;F5BACb?g+}d` z_P~RsjHiB5)Gp0#Ylu>@AyGihF`xn z-~Q~tRc!7Crftio#4glqzfIj*`U}u4-x?UaP-BAi+jLi8mOP#6m125L=iuZT1W8Ks-XJ78g#u-7qSEFwfAF>qioNUg|{<26& z7TkqD*XZ4lYV@^efA)L}%x&jwxL>wK{Uy2Fk^pe zPM+;&DXO%sB|&v9yLU>45;-?3EV{)X%XcyO?cEiPclhc$X-bzqht|JA#kHj$WJH-Q zHS~z9ic<^J#1UkdUU8h}e1)!SRovNIqfC=5Fo6l+(>v&Y(Y^UN-`p+sJ>tJp*m{Xd z26bkeB2(obUk*{D2zB#gvTV1+0fI4m4mt8@{GN{pxw+lR+zXunqhI9kdBk;c;mM*O zg`+RCQd}2!C?pTIuZ(eNZYy<226j)oj_SdoFaRvS_jQP%{jDDSvgP>+BrF2ZIxmD=AyfwdineFDhMhUGc?-%PLt{+9{%&Od#z1!CH+`HFdjr^D8ov(G{& zw${u@vuL;+@dJ~G#`~o;+CFHzeaV@c$3JrR|2pA3@i=Uh7Us%T( zu%%@63Cg}bhj3Di+tcB-{IEr_zdP;zL!oa9gr=A=S$w#DI#g_b94M~fdQmS-LUEcI zclKCt1i-3kDuv-M#0g$}ZS`^aeTjnd5A{JZ&V$S#I@s&b;(t-K9~+u*cRX3tmEd{hQ^voL z+MzbRg!T%`amu6-nMPo|=;voG-Hk2phsbgI=6RV^*oS6RjR$N?eOS(SX)pd9z(42d zr+oA+BTJ{)Y11JwgpGB^Y}=;Dqgu%Ni4;#-W=}!O>4F&74OdAbEBb+Pzpiu$A*Ga~ zf&uI~*Ae7fXl+SgQ$Ak zNNJMoeiUR}MM2P~arBi%t8F(Wp?69%cJeKFO~uQCGk={xI%)E2S^Bj}qDqJn60_6r zl>IgC`d8HPL7$;VDsW6}pSVLsq$d_^BHux%+mknadRDI>!-)w4;X=k?b%y>*gkmK# zlhG8t`3&Ti;MnBU@~)vUL{$Zy!Vz^~Ubw_~Iz?ecnN(W*6o8Ic>-D4Hrz#TMp6O^v zMF!woM3|dqql~{wy81N=MuOPtTW^6`hGZ>MIcCfFZsnws$x4*rbY5PyhAcg@N=JGk z8%^LbgNXk)u!~ZC{OvlKceOt7QDbZyT|-O@K7&33aE;=&R{_`(D*N>~v{|@N2Wo*S zDsfXP&dg~}i!yS8jguOK9A4=n4-=7&f9mKE6+)`+ge7C3$Rh_jw}xi~VhZQP&5@Co zj69hJeJO`HsR+~l=m+RZ9K(NKb-%VbAXj2pm0ukdXKI0zXmHCn8D23ikT%i0V$|+q zsqeh?@=enD{XtK1^JtVdd4dmpQy%l5FI&qQB-7~t}{`y4@97>W#%epN{Uykkx(s$Z7b`bEYkEs zwUINrAiDOv4Ux3U>xz3}_#Ci^-9xESN-v8h)C1M4wK2IqL$$oo;c!(|<>C`>%V^CZ zR{L#_N-}}e;ISd$PLEx3`+83CJ_X?qw|AV7`qPn&jf=eqZ?0j_B4-znqxuPB;uD5F zOL%@vj9k3M0Y}|aRQSM|)@IsAR<4q@R?39Y$pBx|DGrZohf$A;fm0sYV8Wq8zEL5w zCkwWu>C#J%Lto-B0(kk(#o2d{j`Q~V-7j5q@X0FTV5A&r;E@75FD$vYhwDFh>na@m z-rGhyO!imJv#2f(L>+zwN|7L2-KBQid+b{mPxndf{1%ZOe;q z_obn*xvKcMV|4rD=K`LA;>^|Ri9?khA%7yr+R@JlYgsHGUlEYIjcC?yWB3wKM{462 zt`)MqoBXTTSD=nRid>9E$#d6f8<`Npf2C#BR`-)J&6`1N;3~bEAVP z28pfXfr+%brV=&wX+kRk^=;!NB$TmdS$!tT(I0N6c-HPKSN0oOW>qj+N~|MId&1{( zc?*TVO8s08r*IdDr8*!U&V6b>D8I+z8%}tiHP2OI{8^1T`c9AN??6qbi>A-4H>x1R}0hJ2;@m>kYI|2n3#dyU@> z6}xRzf3C-LtF|;ROpCy8SNC+!@;g&n2`e&n@6}#W^KbKOs7g za|u?(XA@C&uVGCNfcHBFpb4B2-u$7?o8VD+V-5_L}F&p-%sB`{ufvS=X+VIC`gu==lit#l~8p|dp2_rL}YgU{N0rGJsEugrD#2l z@CJKy3C>a!n7!|xuxs;2w{>!-EGqC%B(6Dc@s$~VhTS|J@gJ`FbFe4P)IXB@`lVYi ztzC>Ys$VP>n)oXTG6uBYco!eWi0@MX?oM_OQZ06~Z1ou-^HPG}TREH!`x#a=uBs?9 zsy(L-hc%EXItN<&FPvS~={;QXzH2j3k``v=UQ_xlA`gdN$n5yTF4R5G9B9;8ps_U4 zA6&)d?Qw@judWh*re=kL2SZgqzV}Y2M}w7_LuF|wM|;PgZAe1FQcAyM>7EiP^>X3svnYJb?siVvhdZE)(J`W~vfxfDrNb(_V$-%UYOHN#NqO zG<{=~PenjdI9!E{$&T9W47{@Sv`eyldkz@B*{Ip%bX8nYKpTt!IV&%w8mUuDVzPc_ zotQX-&#LMqGM5V@*f+#BI{W9MFEe}H`^|B~wbjXSCbm+=p)ZqMN_*RRniVoo6K=kT zhsuxQ@&6iiKo7Mh{bq%!SZ|W-%N)9RDqQ7QF7jq29*2v}B67rHhpY$!06Msn4ST=O zG=(5B8nAvcak_W;jEzl2ArHt4sBvN#h`|#6cwZ~I(Ep8v=F=MW%Rd!tFs<6-srPLW zZtE6*HbOhl8Aj;tx?36o$UXeN*sf~XR+$(={NEuB{vu^=pjeE;$^s=lv98AU4s!aY z%Q;hPWO;_3)e1fQNUmyu9;B3J|DN&wH8KTlTZMM6R2M?dZbfeT&e3yR5kBk3Z>hZ- z9X(0Y)xf~KlFi?S&R;9MEh$Isd{Oa!h|;BUt!WK^1JQ5^r0Izgye`S`bSNSWCG0nj>`4fB69wd zI-}?W(B(?n#Ma4Z?x4`d@Vf7~0(lQTnmh#^0pMVqEk`~<2n~CMRIbFRH9>@d!B1-V zv_Sd4;{YIVb!z!9Y<)W5$-T9)MiM>9j)uLZ4W$34Ml&u05ntB zkXGkQ_5pT6{(N+Xm`t$=AY9 z#7NywI7^M-69V+@68OCDU+XLeUxsh9uMC^Xwt?X=b}Jz)Oi)tyTGC%!Y5}+T_tP2M@+*>sSZgdhJASoFViU8 z3w7K^M0&~P*u_W53*jXf_&}fXsB^9z$( zCM%DSkBB^|CV%2cz>K2bM$?fzZontbA!x?`o<>rv-cIyWOC?^=y$&-|#IzcxlHgSILXWv>ugb`z8n?G0STt#tv)0sO$LBBuQ zT05$cWBfirW^*)wOhO`^vgu~W*0w2A#1xxgncJHJ{G#+AS9q8St{&yi3u`jWdzBGu zYTq1#FfmU%aaX}%_bw=XmC6;LkEc9&U(r9OI-y4|&rz{_sG#M{76^0AOsReeig3SU zs^tbPQa_P-@dksLolgfOqVZjd>7Z-fz69Xg1pw^wzw9-NW5Bkeso841O4Nlj3} z#^rEwD`Y7#J7ss=krNjaj=J<@V7g*WCFb#VXGLUVa!}vjTJ8J61}OKuhyp?XRlLC2 z&Kp^7xU}Bj9^nxc|7YJTnre;?PqBw;!i2(DH6xAstkqo;W?Xz$|0{vp_Vd(TW>^C2 zet-5obg!n;tuJb0_@ZI>Nxwkp@JD9bG?%2=XNp+7{7DOYwrG&M-c0;=EndkZ^!izo zQ$1DB%`1dQBbmF;(KZx!uZ}TzG_N*v&XY+>-roiP%GulPSGmX)q0ev{=iIxOJJMJ| zg!ucXZ;8F>LL2p!*@(X;aUX%Q>eb*wSc$)uu-qS<5m{W7+D+%x(;|N-&=0WVkPbD< zQkIb!)h`H%0V&mYfv?#m!}oJj@R2Hkb{XWlRk-Ha@oHO(>O3g;w=`Y^RykR%^A+;^xq!4ojwD>w%|~&|dC=;kZ=cPo ztc@Gnv%qQ)G6K&#)bMyj^#018cKF=+UYhv|ii!r8`*aE@eYS%wHkZ?KgE5Cc-&0v8 z;PMsPdCkk6y}ip_{$(HLOnmYEXb8e4!=v0B0h0fTT3U`XO=+StW#W76c0UKd>DW>i z^|ze347cpwwwMGT5w$1Oyg@e7NuEG@0=#yz{u}-8NT8h6vD>2c9&5Ocz?QNhlYU%L ztCkH}O=kbf{G+!G_5q-#^1qJeAakZc?DpZI*vG`)4ELD?>U5E-*$V4>b%B%5lGJ^Y ziJ`RY`I^Z2a&gHfhFm4Pq79YDmz*6^>y$Gxsxw+^HPA}hbLW;yy!|~nF~HL8dM_)? zLtj5#+%aCxK^saifj%UmdgIkp{)1xoAVj%2<(-$@Zt)BR0c&*M-38NbC(L8Bh68Mc z_==)_Ekg(6Pr`z}b{P@|l7L=yw4uO^kx~M^BI`5eW^LW8>S@3hf&GD0F8dyK+lICD zukK*{8xYNfo#h^ioX>>-?M_6HRDf+b+9h}U@>yg8FPSanr8~9oR4T% zRkic4aT?mC_MdDy-~RmGb!_E*VNtiIK3^VhI-K&SzoO^BjvW2AbF}*5U*MWOz@WWw zbyq^@=UavH(>$vK*s|+%dh_n`vB^0Qm@Q0S=QPdPIc76{ljA!GV9+np9FT8c^=6F( zNKdhICQVQociz^nr@r(e@@pAYy%UoNs|YzJ(d&~%k`r@TXD8N{QJad3OE-pDTzw?K ztBEltrZC~u+6^C&5-*!BF~2EV>H+0-WY8TS5E9aD$$J#oyDti7Dbz@7Wy?^fNz|(DpL=A+*=q4RG_EZ{}Zg0`2h6<9sm(_mDh7eV8eC$rzF{(~` zS=w04_W8uREDWZ0S1H@VAZEvNGdoT)O~?%3K((7rNJ9w&f--M;P)@=ST2Gog@R9oC zVDawQ#&GoFbAZvF+ODiqq94Z`O`mx3D1RnaBu)}ue3OyxIdZ)p;w6@r(pd=hr|I@G z;b)XMPJK0;jK(I;ljwct3IW~rvARs(b{F0~?a=nlwn33A7jM~BMo-Pe%X$gF@lp2KI*9;qt@J?MfFs{8+qW{Q7Qc8eusfykq z4IHAgo6oV^4-a0np!&VcF3vDxJ8XS{Jxa>r2~Iu_TyO z^3V*HL@ke(vAQU*OzhxNMZCR6S1@$Tr}B1D*;0qNu|&nOl1h~B>S4Za0)i|ublAJVYFou{bhsMk?9Gxs zkz%@9^(E_Z1Dm?B$mx-`$$Hgcq^s7MEs<60;@08yj9V!2Y1T>ZVDgQH^Vdbiuh^d} z&PlJHurR)72%0Whz0LBd)Vk3lb{X5@xzY7!e(Ih~EuV^TBZ4CvW-T^%f+uW{q9~le zrJuy^>^OC)Bp&>x0x%W4mKP#QckIhwnNr~kQZcIrC}Pa2e(u>9V&Xae|0$%TEh3MM zE|}Q&8W$dEa&zK({9&oRKEy1rb=o-?UDBK-NREY;e{Mk`9EnOXows=k6VQWhpgB=% zUy1U0K4*1Mo{Y;=@1n!BcR}f-{~~jnFBHAsf+2rQ*Wz*z|0)J>zxnF1ZZTMC-T7hP zSsDU}eh5%BJ1XY9WPA9vx?2CbX$>!$e=vjKoCAU%vJ|6b(S43XZKc*j8aptwX9m^k&Tt5m-9Jc^ zPXH8M*D{Z!xVQp0#ao2^AAXUS_--jeQK6RD?kRlY0P|p%v*w%qMB$fx&sd{!o~#q+ zaZelh3IG7U{?!jpJ9Cz;%MWXmwb6H(ht0idBVaV=7+|a#2ww~e%QtI7r@le@bZ)1Xd-N!^Y zIk8Jq;iJyX8yG2t3$um9{VKRSlJrGSb6yMQW!wA9ft2>}+jO~FGXq*gVEp`=# zt6ydN%%~=ifI9#YdCu&;AEpBE4iiB5|JHH*bg3;kH1C(bgY>VZ8f&QG%zyKD$xQx5 z9xN4%7x}2cQ%>PhTvpBP{bP?(_xi_vhJ&vb39ryE|8|y~NSLslPc+`k0{ec-!r3l4 zPcB7rH21wDv}6%_k)~MYA3)pY8ua=Ig?a&XC0|pM863v!Lh)C2Y;$7kPML;N(a;n> z=c||yZ4;dv;uT_h7>Aik_kBliaEyzqgX6XVBa6 zT7bRIMWYyu& z2nSk?DRnK>^p@J9n)35!n0@S%)sYN7XV~NcB$g5*Mrfe;Qx|YFiZ1{^rXTEjbh~ro zYVt{D4GvX5=PI7%af66t9&H#p)0E|D*rkP5JG15(diBr18#4S%LB`LCKYq3L7XGnp>1xU$L(ZmrP(s?C zcV+zY{ybRE>P)LjuSF_zJ76@TI7?6yOnwiYpJ%rnkId8FNCuDCDMlf;8ES&{((Bbg zz?LP8-<^9KR{coDhbY$kvul_^x&A=En5L_pqRwo^r^KSPw=dhO_}wEkLvFZdjw5hl zg>}1IPbQRguf}_vBSUihx7r{0zAMSUSr)-!0hHZNfI&XXK&~XuD_-9y7l|{ z=LvLs3$GdJ0PM~SJ5>Rx-N~NMtUphiIw~q98MO&4qu@(vpUq(<=8GKNTaYqIl=yXmH zvWS%N5`{y^82v6zGuLdj@n_HvCYA)g9dcxJbdlL|18jCrRxb;zk5HmeKgmtxC~|UR z?XO6waIk3Z^-oiN+<-SCpWeQt%l8zIe0>VWw#|49OXgpV9{Vl}7O13jByvD4OGeV6 z7N3{D8{DT0T(T-e6Rl1nV`j#J64ZzjJ^Qhfiia+uG)u$7Yxz0agZ%Fk?@c?i8uMAsx$^bm(jsdmY8S9{axHEY zHeF4BGK}Sz8?umV>@2|o_Cniyu;SB4W+1MF`129wgh;{Z>o`~fyF zg`|3x8BVQW2QxG;RK{7Rf=cxJKhvTFYAxZr+VXShr;t1iAUEZ&4(*7%C&Z*|$q-Un zoo+$mHB0W@y<@j0$46?B20>!PYQ;RArE){p8i~~aYVpW6r^38!bu=_PtJ~ZRXUQgV z&`6Nf7YH~tOs(UkeTyO1%d#u-qfLc?rhA`r26B9d3+JjI3B|So zt|-X6cVBl_s6Q6+tSySsDi4ZFw}o(ykF0j(ZfozTtH;w5=Yi(xpN%v}nNzRtAZ3vm z;Vmj2!WbD{1S-X#!q(3I4K(UZa)u3B)Tv6|a6b=ndsRYf4-p}_>giQR> z+quuwTW8{1`ugliIbpLFOQ{37)Hw=86SVX1XuuqdL|8@>hevzzq8uF7(nEoy59XXg zCZ0WtR%P2Z@)z)M{d-*tYBwNp4b|)2=&Vu>RU%m<#+fze%3?%;FQ%<%`cnx z-ih3@uSK>%=RW{Nez{Z4a+u(=9$UCq?)fUJi}S}V@8L;tU{hLmdWs4G3Z3vhh>(J9 z_hweW@t7$pkszAU+lH+w7X?UqbGOz24d<+~2-)Y%Cai3F zTSBrqr;yy>zHAsO+UGB(K^dm0A$KXHh8kkmF|kMus7k;)y)3?xTabgOckl2JD-d&I z$^iCrL$_w6raTQJq;w2{;TSCWokYcmWxIOz$oZl8r1+oM2<_!33eoe#4hY3+S&AWP ziC1O!|5$El{@ZdB78?2(K0Eo(72}e#GB%y7cJSXsP0nBfNpBM^o96VX`~Svg+Wk+W zCgJ}@)U;cLu}+bo|8iQ-cxS z#ACSJTaDG;**dT5L+Ja(+9mP$z|iuzX65jL1&>h=U#+=(Zgpk*Tu2}$meH1rh- zNCf=oMZ)wlU9IbpSaqkl&a>}PVT{z%1TND+l$+n5nr*lC@!-wd>#aLadvk{!g50Ef zG5BgUTOF9KR~jE2KjMyv7d2gTVZ1DzF@^?aGo{NeFbI{BaiLuJk02NJVw>vT_k@x| z__gYqB3G1Wcy>Y|#f8}aV_$hfO2y@bm@Oyk0qV=~3!voVjVpf|jweFho?AueOwQ)XzKSP20%dWhiqxd_mbH`WTc~E?&*q zLctgcm3UapZpl^tn{Vs58_6Cd9km)fl#1o3I~dud3rk$@MQ`o{%J;qIb`&kfFj;R; zL<^XI8(M6z)(hZ_ILPK-#%0t|D3aVHnllH9nxTT{~LGWYNebcOK*+tpKxG*X;rj5>Y zsg8_Jb6qYUE~_Nyr+K4k>iycQOo`th@j00^^$-SgBpALtG5gRzZqn$C0fyK##_weGf~aMBm~eFzL(CG#LiNI84|Oi zV&hO}br__O=Z;B?1Ydw-G1<4xckp$5`~btdi9XVP8u4Bl<;3A11o}$f5w@;e9fQPS zufnaMrgpC;NmEo_JJj?T~MjEJeF=E4NF%c%YJlQgPNQPR=k&Qyi_?G)B6&dIurMx+wU zkhe|7o_SX_WRv3&kwO0i=ULBI0Th(O9}r8nU1AZK0KGjVr;3_bO$b2$@ z8SI~L`05x|SQ1f1>xS5B{A zdl&bJ&9QC+>n1qA8xmp~*Y-qJx{X47Mm`$fsL3%L4d$Ulr}dupy8F_);thg~{O&U1 zbMttbOLG7V|IZMYQ`g73rbIc0{h=&X^H5~v7lJpPs`a=c?fCHQCUp3a+AGC6a<++w zMXM&1-K74paVjZ{dk54n%Kp%_3BtjUX|pA}iT6PI$n@@U6-QxUF)^j}^w#yu_-0MG zc0H(Z7v6q}@M(m*U!~#&W%;kS^t!brhKOBkks_ibWIPcHU*Ho%jb$

??p*h8I}VrmECFrBqvrs$pT4H_@s{?J%QscWNa=Kk%7}XeC-9HNsMv?H;P|? z#7Lvk!%{#k%S;_#8fli9i$5#i z@`55_lvBTqT*i5aPmA>b0F`GYP>X&xU~@BTKT}a}Wn$)9C4wx;+YXCc0O1%py9bDO z%- znidBR5fLU;ZHg$Tg;u&ey9(@I67F{vHEwXi6k(FOE-eOg<=@HejAtnJ+#C=SYkS!`O0?iPlI2>a@jCV0BDP~liR?24-|w-<>2VyxT#4xM z&$xg7*gPxd>cbPb?ZD{QpBu7B_T<0CM_8Wu6RV#tHxY8P%lf?YSP^$ze5I5U4s_>f ze1XFe6m^GI__rO1{&&hBC(IqmGiL@3<-GCDIWoi_qd|uScCD7_>6SMr!xCtK)L62i zb&IlAS$>#mv44cq2zBZz75-vdDitrzfyNq#8b9Sb8c>ft#rhd(;%D!$Y5|BQ9fTYc z;TR@4LRPAo`u2;|k6`_CaB}f5lp??oW(vZ$rQIb5hKtHr=znhLca3A^9&EDQse>+p zhH`D_f(hG}2>9_D!s?&YkZDB$Uj^|yRFFe-DP_XtWG3HN1ej>URq7G7=qhbuM!QH| zQDu_tb#LjE=4@69Z}{ij%+oOpGz<8rdsqffA+>Om+ud`eTc<&W0=zv7zWxjc#2AYL z6SR8HVr~7wJ5D^)0$Ps=4cnZtP+hxmCJF#QNu-7^NFX~IdkAK zO7Emm>LNoX#hY$j!-3Y%KlZPn=}GId7L>`@^D!;8%Mo^!juX(nMV4a!}LSe(ReJ{0E?dqk?6eo@|n@Om+mcB3ASWZUIP|+sJ z`w`DZMAuH%+s^9y;ol#=+mdVEax;bcesnJXltO6E@@&YY{N1j%AL(5Fh7?Hxb`kzBZ4!~HW~*X*j#JBrnR=6N}sU>+7>iewUBmpxW)`bnLz zD73*(ajEGNUPGSv{JfAb_rT)d$jwVgLh@s55Z4EKKLJ;OJ^)WsIG9PLSci@T^PV6$ z?0s`>B4NZAiUMc?pFdOi zfB(vMvmXE591a%N@3X==@AWJ46AoUx#^CV`-gXv`yU}x{0)5~H-w%Ov zo*S)ajMu6Y2hQp^?OrL%Bx1JVtMS6ljs8Aax9DL z(eKG?nJ!Yrg}alXJ~+4~UhE6_8)H6eeMc;mu}PO6&MM z)7FDK%=g(lMS@;1A8QbCbt`A0Qh|z-2U_bm(!^YWKsb8?VRPtFrp$8<P%#6^t8LDk}_3;;*wqxilR&j z7{)mI>EtJOwLBw$wMWg5gw!`TA6S;(bh%=Ug|EYAt{{oj3PUkfrlP3Ph(FYE_`6P3&^u#+q{wW{5Na?K{E>Nq$yh^xvC<7pB7gZX)DS#D>d zPpO*atkWRndfL{wdUa@j40p+%XM#zfl4z=IDc zjR5E*8wSH`LaT3?%;;%VFD@%SxO?F1PFMW{4NQMya}XrUq}Z&e>FMN7?RYH6Msn!c zHr-u$0%bhgEA#x*92!eJl6yS%@Pt#vd^|=j`4TdECf>uqz2y>p*GOpW?g>N{<4n}g zv&`r7tZ{_qT@B-2P_2Qd3{NJDbes!hj{dfN-Kaagq6#yPpW1dK^u+pgAj30e=vz9# zeJpgdW`MPNE3)d>BicIj;l&wKbS1w`!GyuyC99F$?XgV6dSa>We5~dtN?F!dQ`D1U zKCx@bEXpHTQe!Mzq%zSR=V~VAXLC_nBwZ^&%>^;iup6PJs{QDq6!FMHBtX zmZ>Y);7@H)hW;jVVJ(Kb`!`cN{o(vhZQWye3^1rlO8Jxo4cU!>jf%Q?V&&vK^BpV` z4Q0L`e@Pol!=>OxK}PPulNFG*4>?N%gMK~~nU6|li$QH4xqgbJ{?M)4oSRp=VvR{n z=$C@)D%zn}|4{ z3rezTV=*qLyG@(>D~6P_xoixL>*E=ZliY1=7(L%$`ix-XjVu63&-MH1i=4a`w{mF6 z3GGY>CfM*_#WRu3rhg#PPyc1D zHpBE~wyne+J~enfcf=9g>cGw6*DME|o&X zpVJv#w%T#2H(uA=Uy7#`-A29b2hikCXTG|>l0BK4@+_Nb;zHV%SXl`Ga9;Mybw(q) z|J7*J{b|fP2_cZHcxY&-`#;r`kv=eKYqZ#KPO^}u;n(v2R9ZfW)fdCB@<0z!jBSG|1?E5dHP+up#-wLUcN zP~i)w#2S?&G$b16u6!%m17q-~Ybd}iEPN;EyPP(wDSj$5dlW?E)*T{~I-2VnMJGaA zq8dmKlTW5TKcG~-G=tkYr2fcfm-b_#6h8vd>{w!$SJ#dw6C?_V-Ad*s`Et)Nl{@%B z)Uz$Jy!+%rH?g1*6^m9!-wBi8C3^pb#Ig@3FW0fs=t`C|Y`#|-!u3B`fFG8jl z%M&kW*XZ9O^J37PJzrS2{A3rGJ>*NrENCOCNckn0hD|abvtlc$x6N$A6@P0#dDg|3 zE7Um+MGC#xTo@!c)%T58;>iSg17q7!_%&M^tZ6gLA&A=(Uz^*ihc)h=tGBSLAQXpHDTg4yKX9R@UBsMYIPf4_^!JmhP$(@))6_kQ+^DW+R4r4V@fS>7Rf*ksK@5}QGc z2|Ggn1cP*IZ9P`mg?`jttINGA@sBDs9iKI#K645Xkdx%-;c{EOkmUkj4eEI$DG*Yl zvV#QdPw|KvpL|G6Dv9-FlJHqzB0hP^?&ywtIkT7~cgXip zc1={p-K^-U%gQF%*2gDaY+MW5PJ_K3+s!##q$VRflF7?fp+LKy(Uq zWRh1anPM=Rd)O=ox5Tp>Z1-~G1H*DyzKp@+ZiTWiv*B(1x;}!Nc3z#es+~n}hei*j zcfh>FKA~0f3XfJpmVPfCmY0z zL&8;H51zomoIiUbSdPfkp-g;Sj$1s&4XMf@%hapji4OV9=<;EWb z7v=z=B_6XdJ-YhhI+J_4spm%8W4)MA^Tn7@EDbG8e2>D zbM>PH7YKw^T!LYM5Od`KyAJPIO?Cp8N`VtRPby3lL2>afpR^Ei>Pcv*k}O1#{D+?m zT&{UMl4J^8-j_0zKc0}~sn{4!l)@KioL<_p*j-P1C&?Uw6j@|9bfSi~C*K?MLG{@+ z#}`I*maDcZ3Y^&%(Z%QF?SqX)b0hBt*8ucvWmD>nBEdk+&g<`d&xZ%fq?!^{6 z3gn#=1M*;&^k#deZZeKW!~IezQc}yEu`*~$E_7eAjmbh+ ze7~-G-_MP_zSFA8RFG=1!{1VXA`(SxLQ1dSy}A6MQ1>k{(?K0FFp7LRR5+6dSgI)YP?ii6R)tV)DN6>p`>x4hNq#)2`jzb~hl|*ECz5vt?ZeIs zo@7*p8vUO{?yaD%#FLg1{{q^bP7rr%6v?;2b0R*r(1HfmZR6%XJ~LRc zOP$Yn7&l6X^Vvn`Ts4)#-6lAC!b6L=z}oh-**}r$AMr}2I(gB*+feG_E*aGWR{ zr#!^l0tvkO>(4~w_MPk$K{4)Z{wBU3qQ5hOQ1ll|?pG6#2`8bK@jx!R z#EfbF=|G6oNRl7Ib+vv({pG#3hM6qGuEKR(qLoBRq;rs(D$D9{b_k=+rT#7--Ezb+ z@Ago&)TU!R$w*PXnI8s^u-F0q;8Xd0GT}g2iIFtUp>H(oRz{^zYTR z(UoNfh?v_Sh{-l&bY%_!s;3IuP^mnU8B1-TaH3ZGzx`}gEG^rQx6uRdzID{@Vqy2J zr91##Jnxt4|E#<9(*KhGQor=)Q;0c`+Sh!{0rI@^+PNb=cEW)*JagH|6oDNNW;v!Z zU$($)Vm%iHpM@vKi3%!ok-@U1_S5*6M|0c{1fZ+y)DEr;!b*g7pB(L~D4-mLVRo&z zp_KH66jx)q|GT8TX<|71Shml0qGZ8=)f`$9;=>#gjrL?r*uW9YY80;JT-Q0Q3_GVu zKli|$!7DTrDeHCS#BHHx>&V(Yobm$(ilw5DR@vtQ?Tq-B{G$eI-)zm70@#rjt*DMd zwHW4No4Zz}9Z#8`z8uR}i`EfeQ7fdZqKJ^Ou_q~^BkZ+b9bb6goUg^E5g;uL&yO%= zbW;7U5XhclxRM61H^4fzSn%mF?pCUn!P;d^e5yDIjT#X^gTX;^5C0)|yALWdg42C! z!^|Yy+A5qfAaj58Y|>KRny12`U6rMWyJI_fGcLI{2sIh200XQ(cIwiZKVsT;CMlsf zP+!e@Y#=+`p*e83s1xtfFSyI0qUFaL z%tgY{BTrAsRkbv6!p<;L67#Y)xfQHL+rKA63f>#23{*CfB#_ix+ zE?cR&N=$`#SB6K(Nt~+Bek1O8jd*k8FSCZznOU2OcBrYGcEmdySVMpHyhwE`% z@U%;xW*IU^&LdY^>gz0d+e2mSn*MOWwcA8sYOjlriEgDBu-8(Z%TC@oHHn<|XcT?C z^>QLp2sUsfDYFZSj0H6xIQ1qDeT|~jV?}6&5i-J=ci20g|BAS-o<7R=v;U5D^@N?M zpdiYbQl%j)jW)ckJseS(i8D+tr@N)qB_3=Y98dzQE2#-1@)LOlBYT9bTtrs7j862s zqxG}}DATmbBY&;}O-v(eTrtQXcvC^=n8SvSuIxEPM<7CPXD_5MC#1!ab1B-x)aL41PR0evvr6=&$oEjHeP zi9qe(-`4cmx+)@d3nN4}nK>Icx5*8?iyXoZt5a!`9LmzdBgupLHedjwA z8yAmSST`Z(g96Y%G7W@D*X|+;gLLWaf)+ncx%KX%K^xfoXTZnzIe(lMvpfp$;HGZ=eEbV_?|HpT|HgvO0MjPsTljh`2A}Aqk8!G2E53e8qff_dokNT{ zlriWyMEOenom$_9kRBDuDEVjmp8Tj0FOvJXTK^)w-ovtSY(`8JXyW6o#yVu+buRes zY<-Bv;>6tuR4pzRET>@gFayd0lDa`^~1%Vn!%F_5rHYZV-Utg+C}chJAI!yl!Kx zSg;z`ziNxe@5%Sa7(KJaTOSvf@T*81a8R;BwU z#3WRH7A@a@wene|1#T<-ZImE)RjCY-x-*g`%?gyvAyvgQgPpKt8}Rb zx0rdEt~@%;1MWi&Zg}Y|Mz@|%i&e&k2TeDbc7AQ(>fLmKp628p z$s9yrI)Q@<%XKJ17r}JaolrMfd7nu|*4&qg6@ziB3~4#6Ydox?|AhV>QQB-Lbk z1Et$%k~$xTVMuS+zm8=WuhKm-2u@yBo7{%)^Xn z30lTCjeNse+p}qGh*s$u5Dnr!ll!U#`LKuTi)csLfx#k&apqUB%1(FW_SojFI>KA~ zE##X#sOHiA2OI#=3elc+8;nMhx+RhR^|t$b`EQ*uHa6BL_8+YV=N*x?U7Z>2IHMuv zpB5Rpof{bU&UfCh(rF6L_;3A^^`PJ%bmwv?7eE1d&9_LgD4$)v;_mQ_{yt%A{-2I2 zBJTX!g!db^wYNJCZ0-ocVt56?A;cr_${mVq}O(Q{lb#f@w&jxeq zMnJj?M6D%qP~Kmq91od%k+ZFLj=@|WDr9D7pM#=YlcSUHh&y*Ds_D@FSFN(re`Utr z95HjGWmDaOlfO8@F}+;t<@^iR4c6cCY%r0GcQg+?HmnJ!E%8q0cod^+hM!Tw=j zx{FVCdpJ_N%l^^9hLM@XUJE@v8R-g6dx$(k$H2o;IUxQu=h-!&F@JfgabraKk*q6) zN{RKY9Bl$%^!C#R3CX{&?Rx2wpV^fbPqRBs(QJXU-W@+UypEoXTs6PN@bo$L+rhL1 zpe`)Z$1m5D(+vYLx;!x5=j%6}=hSYmt}Dh8%*TpC?)AN6M%yWo28Ypii?5}zHpu6e ze=R1Tp6zqh74Pb8SL+)}m7y6HBs-e&zwS_)oxXLexUMuBcpvjZ2`DUHUe5f1;nK4J zixjd~*Rt-P8w}Kqdrl0gpkFpL1F350z4(?ub1$KiHh9}U0fhM#>G;mpd#21cG*O1T z)jhq1P6kI>W0)|SFrMWuMlTGPF1IInCzKib^e5`I8dAL|DW-3C3)0S^KdqiVS)I## zc`OFaQPR_E^Z)kN!oCBz{B~XAf4^7_PJ}3>RHFVHV&8krmBU8~DlWmK4jV9z=dX03 zP4`s>@Ej0qY4!R0;NHa>&;7DV1Qq5_+d`PseLNIr?~%bB3Pz6^GV5c_wQHBemez?$ zJ!w{%K`+oB>IF5nt#40`pTV7kQ;P&cA%;r9-n6#3qrn@^eMdvI>v(gq-m=e+N3GL` zyKp1HO$Lia!yQZx*x!t36m@VV+i6`8$4>sVe*y%P&on*{t{%UAgfISVYrTaf>T(h_ zHcr=}KKB(^k}n>XXn7&4&*%Mo2&Ef0bkaTan?EyWQR4ZLDlbgjxgUPJdL|Sc^DT~y z*nIoFpfQs8Fu>@cN%NlKRIyreHo~OP4&YMDmImx0`6-y*O|fEwPRvnUa-*zXXJL-y z)?w^+>C}Xt-$Og@w>5o|8ExdbF`zI$CMxYrpzwB?do{Neq3cs`pf6RbvaEd?3C*{gqgsxA_^4`wD>*_PFX6v zyiy(SrA+F8seD&!oY%-(#?tivQ&2@qHUA|nTsKh_GnH8uo((b1ju(yt{=n~*46R=x zGCufFI`@tXus}z)s5?yoh^Ga*hE;-8R)=SkDK>N&FvDli=C7GwnP#-TunoSY+Rnx? zAm{01@bCcF4KXO*8INw}qftD#UDDa?@?SQ5ofVq>t2tM&fTrLdd&@G(21)vd%8OVu zL6*qKw@=8A`*Tq!`(R4r`uK-nrv%k*0P(^c%q=c5ayY55CsAh~6mZEB#p9h?0TNgK z9TOw(5hknhh_oXhaXs6g$eiPuK`4~cTn{R7aym0%lDV}%+@Azv9Htkza?NLc``F^4?D(%cqA|uQ7bvk z^HWIawCPeZjeckr@$H!Gw6{)gwKLsYc+ya+}q%u1j zl>tBR8lUvUdd((-WdRAp2S4u+kBqURYPJ-G=-i2XNM1_MKD;f!g?WoQuig$FQu)wv zTC{7#+30kQW}>LWt}L|IY-ke&DIqw;MyDPpC@ioHghScXNBJUru&&+Jo+s%&=&%3X z1BuYCer_-E@{EG!x+B`~^(Es0;34(9^*f{~juQHd03oFihv85_MtlK%j4VCrLLj2mZZg>6W`j zqth%N%sUHS%DiSfbQ`%~o>#PbCER+kx?OLQd~$|_s;aOYto}wznNrR2yoa{NxTVW7 zG*BcRbKbUd4hXA$K3`efJE#jwGdk-Z?p;VKvNuugwUV;9&eEZTEpkzbYtPb=+v zD)LsB z+MKn*s&tFXHN%CnYtNhcj|~`q2CsMa_pK#g#=jvS3AS zm-w<{TdVmbX!d&*%7Vd6GLbJ{OWvd55&9ET@T6yWBIsU_yXDZ5yj>ud;31wr$(CjjnIseNNxTz7e-0dj8ILMrKAvzB8XO<`@FeX-z@W;8!}| ztij#Weghy#@UpqFk^X57N!iYaiHyx@{Xq><85@m%Vb`0PDl4hEEO|89GCl2}Apa9y z{?;^9lrqU`6A|iT+p4e-aL8AGoR_CLsB;-|RT(J9pz0iX3s;qp;2Ky!qoYWDPi1=@ zZeNOLWIvv-rzFvlAUMn9T8Wvgr9Z0SJojE)7*N||0)b)0=*#ctM*`Z$^bw72wqC^z$z!Gfw-?v*-A=tjjO+=B+k#8wekak_Q61lis~w50vJ3{l&VO`^2=^7w!Gk= ze>_j;vWhOaD=K;0%#jR4Mi-HLE85Z)eM1!ha0@3}Sz%yu^D=fHcc0o~x?hl7Dz(C+ zo8v89g{52OB#wD;;j^tY12}v#MZUEv=xwSsfKDma5h!O%Fsvstd=SK`A50ZQKdG3E zCcB7p;Wt4J*67SxQ2pbxpxHfoR6LB4`)CNP0od%&W+H>BH({)iUt)qMT3aRD*m?dC_kb?ccrEz z5+x{G6CO6UA>+f|?$C-?9c@O`+N3gSL}T{BYFZRU7;@wLBhdta#T}mWFdD*EE}7kf z8WWYf(3(qeQ9e)@X8mh-y^BBZ%35qjho$(alMpo_b(M!~V?@G4SR)22gU47akhKGq|SF8P!h zuT!V)nVt0y1^)wx&pDYvWl?5aKH3buO!zi}%Jy#b-{kk|ySMbwThH_IoZoDp`FgT! z9v$tX=Q{1>cgQ<@xD*NYnh>u?t1-DoB74*xt@E;6<-TN0;7%-i4S=S($lS3NSCJYEm5feDp}$wEF$-wit6`JVEqR6 z&81Mqq$GM%bUm&|1p9GsE5Rvf{ArqO8P>z;jm^aGdtZeMZv)(wnl zdcyXWT;zt zCm}HgELs z@^ueVw>r&{&+L)`*)i^x6cz$Grc42s?nQWK7_fxpO@-$MdmaOYB)@5!K7V#lH7^?0Dv z$I*Dx&;hEBqn`nchrvJJASW2q8bE}PXFEkdvP5`_&kh*T^6K*=5}dlgu}(Ud@uMC? z4tR~u-o>ld%&UBTFups@08Q#(+4y&hwz&@i=rLVAr{^AqI2`WYOs+5v7e+7l=9W@RfkZ-@s?@XLc~QBCK$=j7+c2-w0JAVs;{s`T8xq z7*z8$S=6e{Vs z7A7mrc*v8jKo-iilKzFO#$u%`4A}^XH&ZUBtXzXL(s}4t|H+0*3v4|lAoo{2Uo3Px zcaG4?N|~lOzp40X9>%LcKbmPBvJ@#pEmhvc6Ro=McVso6$%DNdw%#)#bhsM+^&(|E zKdVXjd{Eo~b<@+|&PB{#MBKE9@nnL|bJy%MB^De4ws)-_Os6|&u;?~tGC|G4vZ-5t zcr)Ap;WSL$g0y(vw09Y~EQbm#Xe_0;uwrlV%vBxCE%c;c#0K9}u4IlCv99@Yw0cn) zQF<8OE~_rok2Rw|hUXyCi=&jJ;EwAjosMXrR5LVHAT0pk$A`Dzc8!u~q1s!Z#>wB# z&5G5$_g5#o=9=&_cdDD+7LFoXVlLD*AMIy5*o!O2zPv3_NJsWTr66I-A(rNrbwqbL zIUkt6ng{DKEV0haKCDmwnc9B)-+)HcnexbC_MXAuSZi0?z#Lp)}jqN8_ zJ{EWW#>U{wTbHZr%dFiTUmc1mRyU*nQBw{)OkrF;P*VPH_YTN-_;a(DJI#i>8GT;v zY#Zaw8|adO@$>Lchb#Q(tyUCNDwTr0>TCzsb?Osspb~@&KTKp;a5yrWd+;p`uJA~3 zI0VLX(5PC_N~IAcKS<`VH8{2j9NJ15cb`pK2?mHStz#3?BNmbcuo`+ zU&KsaIk}rNHvccc_t%{7bI(q1WPTa9Bvmxyd8+{e3oHTME_&kjwR#&T{vn_4*vRnV zInxJvjwg&!=3cIztR#Ba{I#IzpG27Biq(cRbz$)P*Fr29k5WwMpY>%Pr4Hp_Ko&C^ zW0Mp{SCcvkd4b`bqd;epsWa;T(!34kXE)CmlLiQ;upi|}^2QaFn8tiCZ``pxQS|HQ zd2QY0@P6@xn55#e{~Tar6T2XuMG;60wl2Yzn;@q+j{2?rM(BkFVkpD+>mYa%r}Id} zPR%fF`9=&pB|Yje{nb%7F`eM`n(L6>05m;I+mAJy_~%8UOpHLIW}R;wK)-J;U|3SmwD|{ozp0-$}3JmTY?x_jkO5jUBJw z0gh@$#A;x~OH#FXQ+}B#8zVP+o>AKsC~%21`MP_U#(NU}Dld+x>mQv6;#!^n9g~ zLOm|U<*`83nb3V{`m6Dpo`%ZpAloyRDl^K)_%h)@Cx?mf|Ep8`du5BfkfJjT!*H-y zEp?Zgo$+~aN$E*$WJK|Z`s7Df;f&x` zUssH6WCz7V0`40w^>(@NMgw2NRWd1Z# zzE#mTc98rdJ-~;Uu>0V{TQvI|^j0T%#hY!~0wzPJ)tvF1JPw)+vA^8QvcJd@tEw~I z*l%sh-_#}4PGKzhY=U=xk36WI$75lUj`PoPj!u#o$YvjT`UMkY4gl>}vr3{tFVki2 zKAie*6Q*>`e+Bj=ilbM`T9_r!eE&K&^0eYQrkVe?Vf|XC*n-i?9^C2Hj1~v^_W`k@ z=>L*9e2{|pIIUOf4u6ti|LNJ*^)q3Y3Kq&#G%`B)NrwHWskR&Ve;B#RX-O1*4#{^l z%RT6h=Du{MU*rC_P69Xi|1fRufNSki(4m5}xof z$FS|LPGAG{N zj1^51*B2F?O~x|=sp&ya)#w&k$S7J2I~t`qmLn%V){XbLgTl-?J8`aqmEX!ZzXz4} z3i&^Y5cky*Snc1{s9VmLDcSDNfpn((_b;cYD2L6_t)nn>8;FL|1O^K97T_HEhUb!Y zoyDmgl)0|vykVpHtxJ#OyK|4gN5hHw*^c1B%ZqTkANP#2AD7js7f60<51?x);a`K- zqW_#F9+kagc5Z))Sz6S49HeqptwkU9!zsj;2Y;SDpw!FRqhiIYCz4??&Cv-fVaa7c zS=U6JptYN2bJ!%Xf}GLSyYEzIH|gxt77!=N#Ya-~u&mxwk<`XQbK7-uoPFl+<*JFd zSKPC0JQ=PKg_kn`8l23z#HsjtHDnfY)W?H2{Vu%OsIo4&6l*Prip506al;Y!(D25Lk0kqRuf7ml z&w)25z`9l5MsDf8vAunRkWsU6DFF=Y5HA^}J6q=1j1_#$MaBq)DYleLty^0BDM#q( z&oq%6l?R8dE0uHsQ*0}o&yu@=@dXvSFe0B8q2hF zUIA@=J{YfmYmISI6O>-0arzFAdFYwe_0BTKP|=drWO}!(p;Vw{oV!13 z8u*f3b341M8ZNF|fUG9jG7;^exjZfo(@1bwQhRNwt#5e+mkNp@ux}py>0JF6^(Jba zWhzfhKbeu*si!8Tb0|<^qs+TMrP|i2*(yBFe2;7Ou6a2}5Iv^w)BjT_lL%m6%`6zD z5oSfX%1)*f0hPD%Dv@|&SBiE)c&HPVkO8#DXnKxOs!A#H5B@Ij@8;O-svd%}{iPH| zrRw9YGnS4bSc_WifJ!>EN&pqc!J0`{9QIRfzwdq3nEqc>+B5k}Gk1fRsVq<4GsGt5 z!kL$b1LOOiffZD99{Kyu^IR{^F#$^+>wrGyy zoN;mm`mO2jpVD}P?hbJY#vSZ# zl&Y;YCJ?9(Ds=Q-(dr=;EsbYFir}D+XJAVr#)3~aOIE+c7F%b_#`if;2>Bg1LptzN zgOO&E3mK0&FukHmY8x5UrfTh`u&O?HpSQWjI$DD7ldEHDj=k_4{WXXA_CE)2OP0b1 zGRDPFxYHtZr>8c-IpSSoK{IiEwVoz0hVNW^8#i&HviT=Z?}t-nHvn7f!dCgUc6N_< zTQ4#hvruoTf+gwezV?(A;@}t?gPuOkup@^f3*ND9T|< z<9)9wj%p$ys>SA3VQZ7S^%5B$EsUVFdzjd=BxeJZKLWzU93kpVc#fmxSOMvNNpbkm z_^mEdyrpme{F4LW8_97V`rNqY?%Pu<4M#y|{oKpGT0GJ(BvsGOdt;m>x83u?n4}mH zKie#nP2jrV?V};IEiZ3GW3owoyH|hruEZAl;M=J}zKP6*3%}F`RBe5Qz~75_-R1YE z3bXL&#|jJQ?3pFp!NY2qLys36on}~4GTOsbXiRkCj)dAV7c>r%6nLd-Ql_^A&6GXlgIE;$gBb-RcsV!&v?P zlt0DQnu1!=Y0kPi@02FVi2iD}GkMlgP_EJWNSn&yLK#e|v40;G9pQ6H8YgW+%HL7D z2MuPa7md}t*!BVm&jrI>1J@^s*9}%CDY2m+qTvy011f>M*mT6BrYbE5S6C~_!3e-; zVgyE{J~o`@|9}=^&Dw0A))$lwviUSWs{&q^eDEkj6bp>#l*gg&amETblOL7^x8Rac zweiE6?hUwAn^nwpwC%&i?_xdppRLQ^(?8p{#g#p6KRR7B**dR^kbm}XBWX~8i69jG zq9>A!1@I4L0R;sN%JDAz3qi#n8x{IMgewHAOe8Al8<>PAB=l>&^ZE0$77&QWNFHV2 z-7V`y&*6DuqLtb4YJ-!T-e1!*NYTXC0nX+~!##(p1idSB11sydxI-DtH@m5UyZCho z3OacLxj^IK{CIam~(ek|CP*AezLOAJ6 zIN>nFjIACyi=*kK>9m}iw0Uc%_z)J?0abnNPax&SO(A< zCr)VB3Q2&yn9{}9qE0I)zq1+vu;J+YO?j8}24i*YT`kOiApwNmlq@5EV!flCGZ1N= zXSBOrA_} z(*u4>_E@-+@RePD4ZSUimYDDA-=pLj2J9d}Fa{a0sQLRQZBYE(IDClEd`YLtsQiNs8~gbSK3LJ6am3 zNt&P7nT5pg8B7`;P0XwhQpOe0@DXK#k`{`XxM6Q6Ph@gLGq83b6|;uHP<>)p*NR}$ z5d3b7Z@ArC3*i;v3EDg5Yhlel1izdoZ?fWGC37C&Ee1&Sz4YQ>O6{5EjXK)gV0Vn= zRLXI0@#ZudGG+mFmbi}afiyYljUqX^e96f zeVNK_AOxhT>St)Bs$*=r`ynHWIy54_3nY@r3k!ZAJdv*WvdrVIk8D6_!(%_f>!f+g zXL`P4AT?B!tY~$tX3T4hK}uqT)i>LV*_6zHwwhm-AJquvtQxMhb->G3or6ME|6^hA z%h57_3<58X@`8xW1(sEpo^c_uZf_powcf39-~FPw+Kb@IX4jD%EGtzRAQ}PdGJYmM zM)Xgmv`8d&)JRvr4Cw)X;y~FAJK@{1aHj$p&PEeBd$>2b_J$wst$Uz&pt=|C=P#Dr z7rlFl46a*l14BbZZ0vAi$F^Q^P26i+4&Tx0lij&5?vJlw2^{)2kBiz%3`JGw<{vAW z-Ya*>3wb-+HP6Y`ywC|Ru>9I|;3U3}UuKjwLyhJs`ST}9Iug;r`34h1iUwdHfx@vt z&TPM*Gpg844rRzYKU86tnoyt)3Pk9GO}B6I^~HRutAP+~I4neiEyreEsSUK7IA?AY zF{m$sQiBWo+_<`UVi`@yb@Rp2;WfqxfO72RU4JX{HIgaYk|q-50-hBsw;w3HbSMC* zpt!28kNc`7610dRIh{np$j9Wxd1Y>XEsU^`u=Y_H=|?_(Sn`M>E=4 z-=hAHlDM}lqmaJ%_|+bD0-Ey-1O6rwkrcPPdW{9hoSa94Um}WKa}|h|O#%jj=Twy@DP&>ZX zq@2|8;p?0V=NID+%6)2$3E`x-1D(vtCL_gAH!*UWUbJVp=JlM41H^K)$MI92Qn1^gpneQzUd+?eo~c!Bbr&q=sLi%-vDb@# z@~ip~#I{K&wGZ>?zMNn&$1a~ugLqj8_jD@AL{P+=vJmXCEg=ydj^Mm`oxyz8YBFcJ z*>8`{ZR@Lw!|*DPw^FAI&(YmzOu$t?8L~RhuuA`wj_#%_O3KvL_3286`tAf5>0S;D zNyM6IjRIJ2{n4Vg6QR@K!brGqHb0p+8T`nAl86%vHpo}=Q+ z4B{gDVg@wpaRl$$ECK3z2I7hV8y$KAbOAipr#B^%bP>h``@XlXdz@1q4Y38(QKk}T z*~^;2YY+AJLHJSzf4`XX6M+P%><+lbVOk;LObfkmQ}m#~G;d}Lf6*e@Ut4Fi9HqAs zn2h!XqFUuKSjQoxR~3}81{_V4esH8o|7P)EujnA`j{a$AVN#PJH|vrwBtfC_ijcsg}(x|%pG;-y@qVfF=!gg{vk1Zx)g?%_4K`3vY`I*kZ&EepF1Eey zv#6v?z8OoMfc^0lGWix)i^JM%{=Y+#6iCe`cx*kxjT*#LQh4`~o(M@r1#dg^Q| zdAE@;xSw3&F*xJ2wk0Y`7S(sA+x_SrLpSed^7%wh9Ur~^MHe{SG5~;?MfA|o>*nse zEsxnLW%DEsH!AI!Y_BpqJ_gRjNJ~Bx1^`i*y|pqlL;+24_O zz)AX#J27$3Hz+75S`Rarl`W@$Qo4vYEr`g3V?-a38sA}Wk^oQV92s!E$x z*tWvIsPawkBG9j-LT0$jbo9F8?|`GJJ=?ImokH<3zhX7t&vaipKhq&aoHTRde`ZPU zMx8WK!Eb)i-ODyw`*v+XRPZtE5&C$w{qX?M_MmB{G#s6;3i0>vWA5#~HBR;a8GVjZ z#Hupw&X;e+XSq2!IX7B46X~+S;$X!;X|_HkSWrJ>8hotd)yUPz4vXDpgI^gQ6cjYb zhxO+-LQYN%OtySv&7aQvV_EV4nvXdIDdXqFey)@=VW;3{#+;jp+lTJshrp5W^{_&0 zI0BiffL`JB-Vr4n^`DfEDBWO}<6E_bQZ0;R;vl@yI>XFWf z{&s_#cQ?ewcPBBk(cwFOM`M15r3#B9BSM>N8=SX&D6RC4NR{XWVR<>%m}8?u65_*U z$P<1i8Z!ED(Il82obc5EFoT1E>zdCxQH5U5Baa5^eW+?I;Tp!zRSsK$wi{$V&tor7 zE-&6GR37Xux+ZvN6d=r4d+qkS(|6OOg5_iuIL=v;ggM;)Uy>kTbR@6S}F!Q(te-9TRY z$~Kemb=^G^zsQ1;FT-UUZWRkN8l1tqc25~fc~SDPX|TMy@^xYG;bhZ)fK1|RzTIz! zfk?P-sq{kmfN{RVEPYmkpDkVmyP4kOd)Z$B{>FZzrBl6(K9y3{za3zkxqO4s-hRV_ zY*sDdoPDYJBRkQ)3X}cafyMvuJhTPBo^u?X90sCnJTUEzTq%z4`_1iG^F}AFK=EH* zfaAYrah%|r>k&g)nrv%&R4PxlL4M~>u3ke>6)$bfO6BkQi|v+IAT@m}^fS5hC|V_q zP~ocdeIdD~x5mRVDV}?fe12;*sf61*wQj=nPfwJ@F(sc9BpB`7_t6WQ7J2b9($n)6h#(LO*io2AI0+{0diQ=o+ z@I*KsGFc_*c+|_JImpzVtkv$rJg^Y242UI^2DelB?Jl3n#N6aP_5>@WJ~bUq=MKyI zq*F2TV(sm7FvNSf#q|j-?o!o1ca`+SiS4h(ng{&dybM;HE@Nj>j74K;m#0#hyTu#2 zi#u$mEkrmfl=XE++7_Bal|!ytJW5iJ$=g80>i=sxsot&E>ac4BGvf7)mW|?Au=6Jp zdm2E+hAGQKY6go17uWhWzKD)|FjXQAgS!fA(Vv+6!{}7GS*25u9S~)6d#5b@bpw4d zVNud;Mlio(v| zQVO0NcTq$9P04&zpZ}-881^}VlfO1#vlA$~tVb|{j>frLRNNgaqhy|I24gNF04+mL zX0~&Ziy<6%O_X6^I?+8c&AnM*3A;Huh{hZzW`eW#^_tB%bk+~6l6Uiy>Ly74Je6); zp(#lGnV0%Gf#mRTX!W&28aS{Ywt~yBy~J8b_<1YuKwL(iyr6|popKNvld$v zLa803&VZBn5s0Eh>i$xiz2XPl4(&K;PD|vN9gE@X%5s&^oRz$l5w~!s7dZLNW3MUt z3S_E+Er<9TP;z>JHL0o27tLKl3p-_(<9K1Aiz4w>Qfs6Ddg}|V%AGf*y zGQ5|Xp9O@IMRO=--QN(tir?t6K1r}}CcfoMd3G1Gf298Ii;%?eYV`9uaWg<@H-TxPIudol_6QYg-)SKhxUkKf7Ew!C!5v?^ zK0K}~b8_>G(Kjz1E7&Qc6#nk_3=rp2D-!$qchZ*!hSY1A%O-iyrv)_>UJRdmxCF!x zysXlm&}k&pUGjFE>Q^^WsD2j*AWNv%MKEJ0T3?fN8xyx%B!$hOjTSEItKqjA3Gkk@Ajszp?U^K)3 zT~>^VOa1$Dt6eku3bQn^x z3LOQ9f-~q}Vj0QfPHXgmj3Q0&v7Ap%!N`Op%mGizmhCxh0U3xWhiv2o4Da6d#rAoH z4GU$uw&^LfEd9mBf(V=G*AdUmXm3trbP6>^j^gXjtMlQ+{Dl7jdmLA-C&(=hK!)@7 zhFtNRWJAL%S}}QQ@1ijNrR^_qN*mnvrvqkmHn3jbZZ-elnF!{Y~+wo>i+Y!e_cU#?XqF@L$P*%Bxu^*th}0h<_$U?vjhhMz zIghZB6r1drsL%{8(f|7z_HW>0$f|8*;;)XSJ@V9F}L0U{)0-(C2paPZN17#Imm4EL#^lxdQF=R>4 zI!cbzs7t{KX`vd+h%e!@UTqKnTpZj+2Hfc0UCltfXCn895&-Vd8;dz)YpHU8dr%yn z1Tfdmu;uhtfta`&^G*E&9F0iWWs*>x%Gt_NN65l-`>P#&tz^K{G0%p3Bti)HKraUr zG6YaaboyNB>8g;Np0wLpkLp9G2=qs~VF>2Q;jfnB{B!eHpRVzv9=KKZ>E4jf6h(IEVu>8&k z)AqR}U=QAiDjUM}uRxYGY%M6QlPEKaF(yLBtkav0NQiXrfjV@}?hTXYk|C@L&MRt2 zaZ)e|pf5zUJMV0Dt!=FteP5x?j_w!-<&|(<;9+h~kPJBhfsq85;D{(b;+Ik}c?X{Qf`YT`KCKEh0fS*z? zbP>Y+Y-VRo08%nGgA>_Rgv$3oe6J&@y523o-7>cWu{Z+nLYfT^$o7`=W)CSffRu2H zvp4jGz1jM?@4P`2Z>pf&PuDiJeH-W_rel z0TL7Z3zRS^j9Ud{q{Y%I{ASmI^Tq)1iEB713s?FR0v8TgAi(f3vgFb-rA-$8H!*Wk z$@N?Zd>dF9!QganF+Z7rf~rXLNHE2#hp$CKwLGj05P_+Y0QM}tVO|~rDl1_A)?bnD z5itfRUk&Tjm4gCTtub%_RGRLw!NZpXq-^KOAhHpFf`UJ4we0XH3ngleL<=M08f9RO zZ!&#jhPR=gJV0D1J0EL*UbOFo)l%4%2Um`*ec-5ZOloH-ZP}Cu^mAAJ^sxu}$6>MBSXQ^*)YHQFfxex1~Rs zme5T23NZC?v6tIm_>-%DTcD|DnB_n@iLuJ_nI*FxGShPm9bF(mJs525aRO(KP997w zMNaB(&o^{qL}<^PEW#D?BF@q2cG_S{#$9@D2zh54EwLAFK0@LY7wPOAQ2;qni)A$4 z@Ft78OK7adISBp}y6(r?8tQuPQLBd+u0&u3;lw@f*7j{dikm~hli7-;a0=T9i}^8M zA>&JE(OAXbaJ zieRv?t=K_D3$P9tXgX=krjRJ)H}AI~1f%!i0{nr{DLD_0*j%^2a1M6wwO#3AN5=be zmfsi8b=^}G2=U6*3|&M{Nf2Z6_OX!k9iyMQhgIui~A7`t_eesh<} z%Ze=fyF|Yh(C-PhSd(qhn(&%}e8IlKss@T`tsVRHup(blIjR3yvkCp)1;)s?Y{dC> zcO%v1FEjReIGZQ$iiI-}G+r74Ae4VpRoB-;T{8(<=#Y$797XJF`s%W#u(%;+aA0s< zMMx45$XYi`z%7zFAA9&Dk4QM|Y*dvPu=b-x*cER}Qy>gWxTTK?I=fV!-&i3Xe>AIn z8%y?OWReJ&{I#=-q6Yq0^waUoSy96&1AkdT7x`-L&4Ce{9op3>R{h6H9D@GQ=(L4A zxv&3HI3c3+t7JZcdnkdE^vfk{s>7Q`7itNS65vHES7gw!>76mUpMM$4yLE>Rsl2Gc zM+4Zx*#-uJR-%65=LrQ=AeAq0)9MaQ+^VI=41vFI@ZxZGj=Idjcc+2wPg{0|`oiwr zGmJ4NDukfy_6+)JgSuCeBO0XOG~M`p_@>7qaQXr~St*L0B0hZ>!pW8;?|r56MOJ#+ zP&SvF90)~8<_YeJxJz`DR-AG8Wr$IKEL%jtZ#tXfUzPRrA36c z_xqb+>tVAYkMqUT^mW8EO&U#o^X;aCM%yy}m|J?2<6$zcn%MEw(Y7wlSP{$p$3*gJ z8TGhKyo&vM5&o-=Hv1VBjQ+#rM17pq$mmCFIXr7uwcW;C<;L4QM%P7U?shtLiUy1M z0sdzK>m{ywv&-XI!Lk$7zAG;=Y+tQ1XzY zEuVxVl#A^7B>K3ALiOzIYB$$HiDwpOCKV%cNnv<`nCr?5u7 zdk*%a1!`jySW@L;Qan5wr?8Ci1G=^vbx#o7AHHKu=2RDVMsU_r0eW!RC$;$Z5i8!1 z9t1FKoRUUI)74#e{H{v>;)<2IUo zbJ<2oVUK8n;7+Ds&8qc;-&0cOVz-NBd`?bQqnx5H-%F>)IIB%upP7Fa);t(r2DdVr zxPy{f$C`FT#ySw&Lk-=Vj-+6*Y6mTG)rJ*GK)9Q96%3+CQeA?jLYfU&`AscE{qlyg zuD%l0nith6R+R4or%&*@z*_RaK zvJioyqQ&Kvs+AP+kl|Dt>1O4KO+aeCnSauM_%kP0XkXy6n5E?;@n+fkmox(S6e$_j zGd9sPqXbpd0;dCGBZvFDnfULVVZ-^XSG3A7R_b*4IeE=G^x^4YPOfBSakvYoitR>x zy)2K(+fsJ|KXL||^HZ^9A>oE|yiu=8*CnxrTS|lBy6CFQ@54;>zFz6E`Ar#d@ox=J zuRFXVRD6B~Dwoe{YRflH1=Hi+og(4a`&JJRYYDc4iu@0{J5aFJlM+YD$mQz+6!Lm`njJg_LvwzQG;~GX@MbD~IlIEs&F%ReX{ye1*pzBm zoG1E8*>ZLS91wtsxf~a34TN+4EIOUGs)qIo^V(^Ly;aQ)ab9`#w^ZJ{hp7S&N8t`{ zYdb0sdi#&ydbN!Dw(uP5U;;4n%vm_Fx45w0V;**2Sa0?T+(He+gc4d?PiRDltEVSTf*?RY_Cx4@xV+yFS;xe~%*e~n|IW3b_!&I-6!%B*yRp6I8!h(VO1%G2_OHc@wMOWl zmbo89pR)0^{z>5>^FQXpk+f5g`x&lBa{m8D^TYGsS@Xz5^fuHj*M$E+pq&f-do>g~S-cLlTJ z6XPQibjfqRXKGVAXwcM|032yd;ITquk-Ph!#*^}QCr!J=+nK6v${0bg=d&a4!3v=H zcl%wohKuKy_qBTK<%`KfBFeiT#Ef0ol`gtKlD{0u$q|CoRd0u99b1~)4-M{5RLr&= z5x$yF&-S4ezDTo_R^3*Z8}Y#+zwnRne|eRVM7}Q2Jea+6y+vyIZlhAd1`Y3ULdrD7 zIvNo-kr@$wzHnJ_KVS2roNfnTlCxJ2r%qsVGhQ+k8{eL%xCNBC$_6XM zdC_yH#3fMH4BWGg^!6{G8E^V^+ZUM@w`Y{wt+CxeA#3o$EYIcH2l!0h=T*L)rTdiH*~J65sdeLlGGX&Hg0Qh>jA@mp#%GO2k%U z*9U2928;+H&-V*}WlIT5{M6Lni9(1-sRg39V<+p}#;?5NMc{6xL7B-| z4_0Fy8Vkq8-3As^KfbcalP#_=buc$og+ee>ct71CZ$x*VT;+r+FuRhDeKqe@7o34Q z?k22J7uF2i$b}BJU^XpJy=N9%QlICiSd;1%NkrIEJIocHG#cQ}_R7OhNQ@nvlshXb z8@U!m_myjPJ4JIP+gTo{X6H>R-UL^eT_2^ZVXmTxj+uS2sPWju${Xc6JA^SOKYiN? z>%xjhtt`(XbAreD13k`WE1Xoj=Gw6pgu!Ac+{d;Kc7_dCZ)&DRO+@csjmBX2 zXM$iCoc=$MK_t*_Z{^7+ME+&ISz4K7@e?KwGhqu5M7)|)N1*kI??k2yN9WBeIT_%O zSh%>nz-q0du2+rHmNg){=ywNwy%!rLSW<2ra^*|2gUwjrmEFA+!1WwC+91LoTBXY+ zr7qA$o%Zi)zZ9nUrh@v{878Lxa%D1q_O02y^zC=h>JpRM?ti;C8)WL?x2>3$*xwkn zs?599f!wC~(|(@NqAedHp3M9Ky$?SPJ=N+wsal?!q7B{E=HG8BSQo=zN}`Di>Zm(( z?2_+>*}Q0QVgRX^KUm&Kc5W9>OKo8d)9#a+os<#gHU$n4T6Y|>M>bbnB{APywAQUN z?Z11Nu`GS2m=5OcK4>a$ZcN1^Vs|_zLGN0QNQ8M>SaGY-`bEhFMR2iZw+qX+%)?UGZ4W@iOA)7?MfAjvBQK83o&uO{7ykEd!DOtg!c+@E=uC49uCVp}bw)}8Y)HFwd z#~4e)(}Va!*E<@c)SIodzWjH&Oq+BQWLCkjk6I)uiXD&29pkS~`bfWK;$)m*IWF@= znEo5iZzTO4`~L;bCsBBqz6H!zAcq)IzZpbZAPojTCS9Z{p6}ev{EWuTa z z1t%9g{N23+RUwy4)E{iEFL>)-_Tco~wSKLoIk}7aH`+{!keLlm&#h7b!X0Z&*(fJG z4G4sb{VmLNq9CIw1$P5PNN&E;3U;YfJ(llk@uegHR?}ptD36Ii?)*aVc>TMI zq2`y!yrf;6V(b6G+&c!@8nkJ;W!vU1+ctOEwr%aQ?b>DAwr$(CZB2b&cSp~e?&&i# zXMUWYD`Q1Q=2|P>m2uryK2KdcpR&J*`r71)2$^&o(!CGk&zX>9oV}iu)hwuwM@UWM zo2Z*TzGorh9b5#E?U6wanK4Z);*`yV)=H?e3DHz5iCjBl45E@}oo=+v!|xPppCUWu_{-wm>Vk9Fe#rASQ;{jNgAQAi>@D>rN*X~}<$L>8Bx?m2|D zB~~NZUAwzYL8a>LRQF(ZKp`--8VpYH%-JDewUQ2?Zp&AHPu@`zd~Ig+3JaS}MF4Ww zdwm7Th?eA^Xi1YxN3MB!hi$n{{waJyet!j~)s_@qAcQ)4Vj@FEWa-8r*<$d z0~=t;c<%Od!pvMmOC15yW7|ZJ`6#@$>BImw;8Gh}9I6lEDPs=hI+Jc zp2v;og94O{>~%C7qPRv!n!Nf5pO>zth0x&)+2fs#QMgAwzQ}R=;y8q6jA~3!qwCBl z&{~s`QFMfCA%1OKA(g8^KjPxJlr}&w&%pN!-U2HMI7i-B#A9d?5T|!Y^tt&syk-P# zPZ5-?^Z-a`q>3lY*RkoBw`9v$5L+h=jF5!`r2-od_?Y>_EG`hlCKqG?y)FpT>-(2F z0d)-R4Y{L2SNi7{=?E^E2o7Hes8hZ7XhMrn@XJcW6@w#0#ju|RGEddg$?{A~@YE!O%MD}Mn7@q?|FT0E z!XHmR8z%@-SfEct%fmoj4=BT;BcK`koRA(~3?45;T^qMj7uFxFxyD#e1Z43KY(6@^ zSP}rgOy90hGJ(L*VGQ#NrOIq>q2XAom4zJ2!L}{VwxJl5eb1YH|h*)vSbiIOqDF&vjmm` za$F+7>C~7ggZ{MHdC<`Y06^5)b(YrwoyiDZIA7vw$Y~6y+F`?a*#u#Pf9I|IgQUSu63ub$`fCobkPsL?Re&9m~B3#F8ww&jK z#h0`O*`3)jXaoo+;uUsDsb`|tXBa;yP!HWt<`O6eET?H+;FG=n-UsJ$ToJ+JmXgt- z&W_|q@L{77>PEZPd%Pr509pcDHf(JH!A`PP=zYV-cb?o|%oDbf42>m`97Yo^v2vQ= zdGGP((&(Cn$|^_OziTT@k#9jvCPDq+?C={Rp-Bf2k2h8;{m>m+=Q-=CRP*~6+`lEn z`~G50>Jg}cgp|1El%9@!1nr9WqalJ@|%PKLL{qLYY$3e<}3#_yebi2zKdFb2%r}) zx4JV#bsX(JHAiGIoRVJ^+OYXr-4y~}6) z3=J)Bhc7AhbpR1}NA=zL!}dtss+sOgs*-I}a{9Io_YT7XUvW zB5@TQj1c)Z#cR(cOIt?pfl^;(JR)cAFKjHgSB#u^h1kE8z=hQ4Bc-F_2|r?{2fq^L zjv)vuSs}{#GSW{nM1bL`=O)Op!mlK$Wpx13zQ!D6@^F}`^z*1{PVBvs5H@zXuTiJb4f`#^-qZ~rEhP<2DxXc(DnjgHEuY!%(E#0 z^UsKmx>wmPgQVBiiGI~&B81imT!IXMBU-Qk1Tr!jAR|ckZIhr0TvI;^!|(cpWlIzu zBpbK{Cx^8V4is|r26q|Q)|oXmoPH9D9a|9N!AH#V;aQ+E?(4Pou&Y0TI^Bc22wf)T zCW67jwqg$w%fT|JrQxhJlR_$;UANbQ=!f2g^W_AgTW}T{y1Ha{@qpC6!EU;q3>3?J zE4e9f=&_avjjeVZ@6ode%9GYd2advnYbdAp2bbp9_?9Ps97G~|$m8cPaD4~u@HCa3 z96(04P_yFC@#;TKl6KY{;TnT<#-RZCF>gBC<8-Dt%an{cJiCoO7<`8L!AiodlJTc9 z|0J{5*KWm&=RE0^uR>D0nF$6O11~QwXX`vA4FJuqgh?WiF#0gPyIY=^QTNBr$R$0_ z{77l<$tLtVM3cuRwW%RywS;T4i)K0HI?}V9;LB^Vex$nJsoERV>64VnZ6DlA!l!ed zO>7!Sn8Kawn}HBsZizB1g$F)(Z(ijI1-W8%ie+_^+7)qrR2eq3LJ!z z`c-}>I`AjY>D!!>PCQ;kv6DR(aRULfGY7@g$4JvJ+VdfR#=>a`4O6VhE2kNV2Fq9C zc_T?LD)Yw&n6eQIeN?jr=)fHP#oA%BI)mrlI^&}1>v2Y`TynrO8^ORLDP0@!L&O%W!RAXD!z^p0nHeTcW>NwHdZ%ZpuEv_D%PdC9MuLTgyF??U-1jufzjvcOepG_3a8nLs`-mKn9jrU zU*mDv! z`=T#ysRVBaRzDv{(oRs~j`~tUU8}uphJz+^;jaNWg|NZ1n-3{`oyxbfNs78tioB!G z%x#cL-ou+i4Ra)AG+ISIUqjdR=?vHQ7P>>zQ*I&Bf~M8Kid-Bk&bM&&z~G%W4=+HJ zL&*m~^-MijGUY74rY$VvP6~DTDPQSAv2vLBaYEkW+*1IGzq?qrH6wXN|58Q(_SBPi zQi!q23e%OQweeR={%de6rR@(i=|cUdC$aRQzFM;f;n0IsR5BK`V8k+KPINH@1Q4@^ zG$h@-QVF*c;t{-M(2w8G-tB|kbR`MkMU{IsPM4G6Mf)TSJKRUbsFfZy7`T)*^Y=1f zw7*P2+`LPHI z-XyyuU8L*nO)K7*WCF1NP8IK-_UlA9{1jjo!X2n(NVjcQbcHOiYZ9We9PW z=q!i_IC>E7pd1;iIJJKe27=-ioVOU;`eH7e5_NqG>ei4JmT5VZZ<$H3f^L*QLkQul ziyyB?-(eFL5+({%iqznrV4}1Y?%AD2#oL(%N_nU+cLjAY+lzcyN2^Lm^ zMX1Af<8|vQfca|-$?h)coa}WETY#?6eX_1VaxUMF;0*!wCM$BKt?4#9OK-vB{fu@u zUjJI7a7;B_{?q`A+Dfz2>_?H{>X&4ViKq2|&mu0(x|grCOlOVWCc4}06Pmhx$eK?w_mXpBs_c|JxygK9%h279~0NH8~ybKSF>X z*B-CcVXe_}`Csk)V<6)#PeyJ=c9EahM`-b%F#xaJ(Ii+E5sR^yHc|Yu|7+>H4pVG;J%4otu*CL#_Rlvv{L70hxjhQ$Ad&kvLk1N@ zFZSkDBA@)v!dfOB>m1_a?#@9T@Hx>Ek_U+-!StdBF9d)Y9QIsSyjLBVJ6R<$! zJuhc#;O9R#eng}O2gwSgzO1^=-_q?aZ#a$ylY0@9moOBLAxEwFP=ATf-7{!@COiwr z|2ijXK1;*6`&8XIgHejPa1cY=DZQg!`n}5#hsgIX-GGN1BAPwX8%W7kW77xWWDAS| zFDn`VuCtr$)QQEyrxp{y1AU#vWX>7!eZC1!6`+wbg{yoEl##j)Z7uc@?6CP}u(PlW z@dPgj8dVrM&KJ|SQdxDvVM9BFZM(a&ahq}@BUUn=IW#eZ_Nsbhw4bC2KC#9Q_81;q zcya=dj|ec9d%cIzFwx1Ca!}r_Cl_N&*kq>UG>P0}G79qw7Bh)Gwxs{%G+X*(+UZT| zK>v{^q9|lCSpr~%WtbB%6`&0s4aDR<+ND|giAk9xvsB#K507P_{sU38LXHCK=DH2dds zEg1RMM{|ndtJv^{IvUnXAl&Z@oe9r5`7?1X>R|>TH(J0xUJ1Zlvj?9eg&Wa2cpHGX zdw_x{`vqWVi~r|*Tt!KfBCDLwJ3-p=Z*H%=SmRRIkc6$nE-F*?_Zu&^%3X1~j?mBG zR$^Msc5_H71>e9htDK!Zi&!IUVRe3zMzTVM)>0G^|0T4dn?T*tmtd9_`%g;^WkU*h zaEnFGwilKCoJVz%pP~@Ld@Q#o!-=I`vQD>$*YV_h!ki@69~RMq<${G%8vSpZ-Nv~7>Q=E?<>ljCCHwLXi)fb1g z6v`>WB#A`~<--O)ksbujPNXK3-Mqw5exiCbuS>6WJnycGwe{Iszhs)Te|XXN^7Lq8N5iAK^?ywm&#fUdKn;g<2%|G=J9iY z)As<*#Fjexu6Nzql~>lp_IXat%KFWiAP5AgKu$>LB+QQ>Tt+~Uhhn}5iYhPPD}z$4 zg?Jc#h>Q~Za|M43a!xQoJPu79NKl+O5JbUb>Q6TxsUJYXgm3NEE6?=H&cOt&Wp(E= zheu`oGM#H&SaIE7Oc|_VBD@R-_)d^9M#D6-JBFF>+Cu6bWztSG*=ML!yT^Efz;Hrf zwA+pfdebeT2b3HmcmMLL_yd+ITs(0|q)%`f(_U+u7SM6JkCFg75{R zR;hoe*kn-akjppCVCd(x@dqJ)7e>FU6lQJF%fyQzoQsMuP*MiVQjaxRW*j))ud=EA zbT%5@aU{mB^-%1peO{Y1Bx8PnfH28%Ro7*Cd{KzskIa#H@_f2Q4V0U2mf_Z94l{|Z zW#Vg>lZQJTI;HM*Zy?Oiv)aeS%V{9cN`kAovyho{W`(iG}~7D?Eis{ zuKsj)Xa*Y~YI{(Lx-Q(%h7kvDm=RH8iP?}f%%Y3{Y+s&A8;rS>}BE^Qv_6^AWrdJ_&D;Aq@$wlpW|@ZoZ7Gir0lhDk>9 zj{Wq67I<^OV|!&#B^5tNO-`Qca7*R#j1p*Ml>CinifC+7i90FI0^#f>!>N}W&k@4I z4Vqh~FFCB;k!aYj6nHT0CwXsM{;dL~3Rn0WNI6%igCFJKR_k$(ExHfmz65I$tJ@f4;3UPMq#~|06Zo zo6jT-D1E*2=jfW0g7`-o@Dvh3?QG;{&5QBEl98f~xN9z)irR4->|6ci$Ch{X5;W&2%g1l5K76ss8_KznFqydvXuEODx_*LvM zDqs<8nbu5ZDDQ8e<8X4+6mH=4PhP(SZG4g(SEQ7XU6M01pX> z8zIzA*v^28poKn*OJNu75jv<}8=W{vSVy zhiExkz3D7wwOql2excbdSs<84`h#268DH{^W^A#GK^qK%S0ld#Brmsmb?Jd8te9z6u9wV5=B}Tsf)ku1{m)&`H3!{1h~!@*9D93o0`f$>*%JsSnt-cT< zP0|>I0>;IFPisyI`|238kF_>8x~%x7sg@EA-_`~!_t75Ae;~MS@Q1Yp|x66Dt z))*jmXW0Tm)ES}*;fuVt-FQViP)MWpx-&PW=H-`C96YhUApQdFYN%`0CzKdqda=M? zXnsEhd36*_MnDL*0p2^9w&l`THWf2OWbHqA>LxS;E&BNSnz{IEkzVk!O;5eItNRSb zhFiGLJMM{xlhibRpPsd@zD!WRC%mw9*hMiB+_8up> z5N>ysK3tz1F4S)cvo!8;o9H%T{&-z>-l#+#JcH|hq~VC~2HYNgm?Gvke-5Vpd{HqX z#&G_>4+x3tG5A-TQ{Osi`yBj2?DxGdXle{Fe{ZAm$ z)dcH!oW+05fJnZ=4Nf&@#EqE7yzY^_=GH&Uqp9XJjP)k;^pe|15M9HP7q z&9W2}3V_3qBAf8iT%oP6)|A(M zgpTd4%Q5{A1&{{E1pQhFGaFc>zy7lwf22#irFu&X zbq&`Y?N3fzfE^tepq#-v9DGsVs4a`dr5cFd~0K@z`kMAy=iz9+U$cER)d~-C{W2~mUOvyQWMrpXM z;Pi6y(q|_C=x~+GI6b|St=YQV#xa7+#>S%EvNR*+UVnoJObS#!88*|+sVOAhYoDAT zYXt!Qbb90;-AIO}9WlCfkA_*8>DNksG&EEnmX!n)Xnr@LS0=3_Gp(!7Hlh-mn;*8y zixH3>Wly2XfJjiF^&0=`YVrk7bd{9(O?wpQnyx^`p9`z^$(s4X|Ni!nz<N}06}0dLp6R!r}PrBXLD&+1uP&89du-9c-eIH z^;Pj;*w6Fl`OsxMERiC6Ll$2f_bIb2GJSdSh>6ClGy-dQ04V;h`lHAP_HDr@IvqNr z<;%TRjJ>rs2~f782|0}7e!?{Kv>Z;qnS!eIdBjMA$^M+v`+YaT>a;pfH>R4h;<&(Jm&s+Wy>>Wb zV;jZpKHXCWq3eX%i)u**HyZ9yY6eZauMi1-0p`h9#6_%p6uZWIjlQA$9QHhs$jpC# z=Dbj3$RneKm8lAIC8Llwr5x^ZvIX+@(ojZ*@^+O9dspd0t@_W_)i^Q z+%VbYi9TNf$POrw0pb4Q18x}{-f(Cbf%>j$gWU@G5)#0&(Bc}WcOt2aWu#qE$RG~V zzfUdy<^ud7cP{r6owN|tJ#f1he|hR%XsyoikRpJoLoCvx!Qy^~J&L>zPVq%5xL6B} z;+pT-aX0((%~Ns?#{ZK4Jq&#-dd&`k86KAz2X9>i{&$>TuDkkXKO6+c0^1M3n!&-b zTEMU>M#Y(1-q^9j!(i?C+EDJ??xYT$$bMf1r|Tl` z<*2ip#oaqD5$Bhe9fee0N6?|u? zbCwW;>!F94>d_Q|^>=Q15#6`zT|A0`z%>AO(}sT=oz*a% zqUI{56*{d}i`~TcRGWII5@|EvcOb-(!ENaK&6~{o6oPd9Z#6zs1pn`7IBnJKuPm=} zG^32K3O;vfKB)E(##7GSfC9{uqm|RMzQONbK3(?ysL4J&VaQ|`*=&U@$E(>JKG0fT z@47|5*kH+IGirRy%DVuew01XXwUoxPZ8HKf^Ow*K7qS&v!NF*$`g*p@U-%kryP3WZ zx|E?Q7qXoI3KPCATw3gIpAURo<_CkIf0p~vKg-PuyfS8) zu&^*6Ii`P(W&hh)Rjl|ww+N?7{<c!^bP95CEGjf_WjK1!=W`a`Y&@I zzT9s+mXU_bSP$ea{$?+1=&7G}4o+2H={BNh!r_eQ@wPRz%kMT({qqW;;?;}?uCOul z`dB>E<{oYRuH7O%i8vo{IwKG|YtM!2^ANwvz)O5|~ml1n~vBdBI z-?3j=)P{Pz1eJXC)ytk-^jRI9kZKp>HKen<^U%3W9y+r z)K1Cx^!25rxS5!_;Dg+JepUJLxir}g)_tjT=K~S+zHDHq!Rr85IZ%|~v)}Jrwk?QS z=P1uI(K`i?Cv;Cwhp{1DvU~{YnQibrLYISb%YO3-F-APsc%rCZ)we)t58 z%}~1mn+H1tiYiHOu=;$fM<~jFNB@Rj&I-Syako#~_^T?i`$%W`I#4#7;)S!3^~vM8 zrv=UD_Cf>gSJZv}nx|0Iov)@rnxgrO}_K9=3+R^YkzG%U?^@nz& z4CN$&0P=Pu0GXdVBdq7~0%^W0dqGlA^DI88puf`yxqNLih~Mpz~)dSKvo=AN{idBoelTvb*qeO0H2Rva!M& zUK8kVce`e;*MgG`%FOY&IxCB{j(V%J4P#oc9+pZ=@8OISa_`+lNhyx)o+pY|O1o08 zIC;D*SWLf{lbH%b3*v`GK0V0^PByPKb!e$*zuN&H5Oa+1h89(E`Q9jAM?c)PR9Ru1 zidBv$XI{24S`L)d>uAWDA8pnJsZ8d;;p?rftkXJS7fK!uk82lMAR1 zC3y@m_X_iucKUnTCfP62m6CMrFAtDp&gKJibvVzs{a13v=RYVpwo5^@T$&%LLtcMx zyDhQ)Q7B)U(W@9dg6|$mG&jaZ4}xA5vz5G5{E`pinH*4vr#@_jReVu9Uwc@zJhcfo zdf&x&G<8w8JXE6fd9-&4ua-^-`9Y#&laF}E9gZqG8uvi!OXUK(0l`0mz~{~fC9=;9 zvZca9GI9L0AiKAeWe~h;3FP6IyE#F!de{5~87Q}3w#OoGY zBUE>bT|ZT9xu|f5`P;8)#uBAE9;Lr^8P(6WQyRSP7Mqh5+ou#$8<~z?8;1|q99R%wU!g;buR?bB9C_l>0fIj}G&H4=2_6s-`|@ zaBor>^({*JBTxpzs14lL^=15lpH=jYKZUGnlZan#ad9Ic5r4pM$N+6_+(D!6zR8E{ z`b$vq1ZU`^%>)aCa%RWddc~O7&ML$9S99*2k$fflic+&kNoWG(%PpwDGY!AdIo~&j zmLOa@oy{bWA~wd`*0RylhW8z`oIEfbuQx6d<|#+QH~v+BitpNOZ=FTv&fMFsnk|ZO zH!`wJgs-zw`s$LeNjltN|5pQZ@G4{8QahcW2Mv_tGVdTnB|)HHQQIucy^13LO!=o1 zUNt#7L>WvM%*}Jb)&qztdfcF82-C{?L`|D~B*as}Pr=$C`-dUHtwejum7(Lj#-@u( z4Z5_6t%cwIc9h7p;U>K)WF?)dp3jaI+*;3d1msA(I>VHCY^O<|0=sagr!2rv! z*CORln@rUdL7}w8raqL5;<=J}HbHZ%hQr=z4hmZ@4)^3^ zD0=)l>-admt}GUd;h0dSJZpsqu0C%SHk__LRg=z)!zEV&!veOQAk4O@cay1-IL0|I zkLStu@&qMZc&J34Mw8CNG`g6WrrpS+N?g3O^UCwuKM1_q8ml}n@-)F(H``qC5crCU zp!RrmXb2X_XIo>VWwQ?|&w|Kn+O=#-M~zpid+~wCP;-1S$l~@%C23Y;A9hZ%+k`-7 zc_h2_JscwWbMHQvV?B*&YJB81A7QiR!NGGWN_IFu?-sL^2~XE1sPS~0Xa+l(&#H7H z#IOtppYt;_w_2{2>5DWk*%5W``t@ZWs@q-`o6BBbp_I|lA>m`ajoq|XWZ)^dy)wqE z@sPgJ;lbX;85v?}y#3dEGXs-)aIK?l!!v@M1DnC)l|haXyo&8aFcIc#>$BI5o!s}L z^Ywn_0C(t2?+Y&p?66Fs{xi08PE(Qo*Kv7yuNXn@)5@YaUv^Mr=XFjcx}4Jia!36M z5Xvi#!kh&EZm^4OuHk<+7dTy@?cu-$o=7%{bZVi8L5oE zie?kS!91~Zig&xG1%`smv>34oAXOJnzt&OIr>Y=$Jk1QhiVG@o@$9fEcmCy9$BfB$ z)ZzFhz5Qr>hR$-jU#~z-)*LRXr*yQ{S$?Zz5`fjwDNl~1jC4mk#m(vLsWb9HocpZ1 z1}d~rcL}#Ho@M=A%7w+K&QgxHKrZ-P(fh;j`cK4PE_H4iHP`#iH6Q*!&YiVtKD6i@ zsiP?_-S7j8z$sr_b?HyXxtD>M!#*OSLoOXC`Cv4~H4cON;Ec%h+usCf79aRr806;IuS?uz&CkRGpX?2);r%yn2Tl{4Ki z(V7?$9#ieyp+bDsR3*5T7^L0KbHo~cE7RhRS`Y*}8^UOI0*`;f?+>b2#6VQCU!bf` zhg&9l&wp5VS`N-g^^c|MtgaB%NM7bUm3_v|&th#im-VbU^3Rtgg_eFSv!{DhxjYI-C z+1bqvI-Ie&XqSNS;)21$0p#4C_*yq}lHJfTo;p)#?YA~6ATBfW_tp*ZGg z@%;6ez{vRT7dJf|sVrUy7-+GBfO+fFghW9Ut@1u3^v}S8Y#M@yn)Acp8EC-K2M9D{ zO5coVrqd_Q{H62UV9?TW9sXgBts58!fy%Wg1{Y^M6oeqqpccn>TamG8G5bW{qTjX; zQ47GaIrElR?1lCJ%UrzDJXozE+A+k}zanB4&Q_|Rrs`x%4OYXuFS-E5YTX?sJO+_B z51_s2axnL@J+`m};X@Cec^+svdZM>vsrTlAk&w9qPNTC4ngm2m&9~eITpYA>Ys-O> zFh@jExCB6>J}y;L8d>~r;^v3ws(SK8a^=sCTm*HM5#jSph1ej*c{^4sNDVxqhL77X zN1Ec>GS#zf(6t{=uQv4utN9{Div7wFd8|oHoZwsJtIOcBG+cmA(eLF`ykMwwqlNFd zI%nU##Mp#T3G}Lo4|P{PBl^DZ%iD_53iq}61BurE3W&=o&z6R79B`wGI(b!Ke#&=R46%jZp?Z{DHy6;b8^*q3D!l78@~S;M*VGev~D!K)-TEN~75WeoA{!nkdQx z>;}o;U-BDlfWJ&nw5oO5GHl^~04H7O26)Z)5sm{8^j0q-M4lmN^{z?Y*kHP#Uu&!V z&nUVd;~*uvFHqqgwX)F&2*C!z`v}vCj+pbltzbmT3Dma_^n^yJeLrtslOSIM<~v@N z)n&kb{jlNKPzTpl?<3`Sy1E9?`>Vq>fa#mdlwVd7o49-iYZK~Y3LG&INCPJg2!u!+ z?s9Hf03Hwa?jq0VN|zIs1KbG2A1frV3r|RVn=dfkmn>iE)LXr3m6_4vo8AP&n?)UH z!8WOZ@&JRJ^>@UqH+D!yw_!GT!SVnVfE*YR`;T+3xXq}##IkW06Deou+qWa!&=)(( zFD?&`r-~N@*~(YAb@Z#@j;`iz6tilZkn@C2UZsGmvIznDFm59wG+^>}0fjnyhKQR= z)8MJA>I!jPZlFxjkI)y)bb3>9Ba&r6EJGAdo@XC7Q&$Wy8g0J>xye)h^z=B1(0TpJcI2{93b}gem~~;v>ffZZ5uT7oNWVN z%vgH<6~=c(1qOor>bT_&j`76$JXiImBg&TTO|=AJj$$y|Q{(2<188HuX)!n0rroFH z3JxW;zljGJ{|AXTyxO$3PudsWE}K)N`t{S$R|rT?nj=y-+{&k3?V>>fO7#ASCD%Vv zQL=leNeh&mGrINOwFe0B`322Pj>f)`XJOLPdXZES_+ARI_sug&36LRXL{1J&ZNz`y>9lGXy z!rpVXAHB~Vk1C0b!twFvsy|KXAs2;ejn}=-NTX)HaxBR7k@XD3=*nNU zFQwl`BsN2Yh#?+n?Z9VmEyaa&4n7-^0f!z5Bz*e!(cCYMW>F<);ef7`1cI#tu!cmX zsK!$&w#bv-R|{g&J9v_WuANAdLZBh}0(Bgkz#h|wtLMBd(D1U+&51u?y$OHSnR2c0 z1c0phCI;31*m>m0&}x_ovwgbhyf!gxOe)VKf@E|}K8W+dzScXkhD zjpe1eF4b6;fqjT^7pY2)*g@=6WR5H0wXpaIl~lov(Q%?$Vs3eJWWM zJ-kroLv(Hq`%sNKDQYjzj15A_9Qo%n$I*E{?D2P(S7mJG%%*1RX05I97}@i@m}-bu zG41}5bN#E7r0!YX5JRnR!3S0Mscr!8WA^?LP`m_K_t}+5^HQ~AzbyEl8@<R@=2Xe;>;5%P z;&xB(A+)eEt%GJ@{}M=VUt8+6ktk^0{ZBuvVD7F!bz=)<&m9_8`+L27eWq56dkJsG z2ExtFbSA=8`;-vF)>XTo!o4qf^ADA3T+ZyA3rqr&5plkw|^n0r3aaO>k1F57tKuqDIv=0o4bsl zuho?d#3n&GI>=q91jAw}hxCd=UMK1DqIbTcI>AGR2(SvIP>TSY_6p$GZzm+p0ikGT z)!(0DrfQInP(dl~r2Bxz0*?`h3S&;KXUW2oT?BK@FkvAmqN%ak8=sHj*8R#)Ec_x*bcS zdHFc4GDE2l(Ki93?FY|&)XbF(0lR6-r?D8d-!5BFM(Hac23XXUgtiSdKo3c@cHJzd$vNKEg+(!V?!TBHvF3Z2( z0q-7M3gG+;4|@*G9U#_XCyWkl_c0`$Kscj+iv~N+tq!9ow5X-pD`5MRJd-Of^PU|~ zadj`C4R%tFQPJ+e4ol+0aMpT5RgIl+>UVY^@_B-hX=Mr8rgHAo3Fyo2rHObZFN8L} zJK{Nah{4s^^Gwx5roh^l5I_x%z?`3;*7_qW=P;Y-{?K7I8b|Q25y{%D;brg!p z!@DP{3Ab7(hpda(^Xzs`%P^T5Oa1esD}eJYa;?*CeM#%H^n=e0Vux1_T-LWYq)v3F z(6YktkGP}H)E_;Pzl6BvzM82Mj+$9U-N z)DgkHbOygmz1}ll$(}1UQWfMA>|xp7qb;usU^;z6=;^%&iqM zrZ~JFmqpc;!@R>YS-|vnKhE|{7;sE^!dcmRYpa?s3!SS_HsQ41Suk`r4QyltHyZZ*U7VvC32WvDHhz`kBi9db6LZtj^>lc!-GKjyGc*{Swq^BW_ytv|s}_-N z)#iz%sX{``^-axMy&5s@6ZM|djW@>OIX4P_)HX?Pu-m%rM)dj(@gGwVh2Q=zM?|Of zrZe@wX9y09=7P`ZV-rLfT_Bqk8**YQ<6Ug-BWP3WU`C6Wrtc7v|4$J&gb`=>&*U$$k%ITf=s7^FB zkjc;I->E zC)E5sUWkjj=&?4#KVv_X>0Tgnm|uAwPTv8;-(-3}N^`~2`5=+;ub@AxtlcPz(vE5s zN5Ot8v`z%*@(ttJvz$~aDjwsGkqRB(MoKA6?OvtI)+%~2Z92QZEm%x_RnwVDApRza ziFkXJRgK`L1@vyq%QW_S++r z4-0+3)vP&KsE0-SpV`K8rN4Uh<;NVlwz@eiUr$Oujsyb%08r(A3kxVYv((gcHoF=p;J~5q{+d=Pb652X0 z(jAAYR2WijWXZ&DT-+*fonbyY=wHI#C;v0EeegSTDf8$p^Yvk)zoF1XDJ7dZL6&DB z_)*ByY^KEg2G+2g&86;d^by-=Uw;Nu6Y_cbX6bC(EC$k`$56FFv>@3Ttzr~a2>bPG zRwVRofz0t>Y)h7>_ZFcJMYfAe0*gj!?H?#`X88PO8Oi6^;7I0Dh!V`lI~@(mzdrwc zOmZ0Ci02VA>8x|{DIJY`E(FQOhbn0OFuq|~JNn;6B0K*ciR?*bMvvEIrH!d@(z$$7 z=2t}hK=;+etT&I>-T&6xSp~(xZCMz1CrIPaSaA2o-2w>&Y23Zhpur(n(4dVIG!PO9 z-jD=ug8sM%NN8L;SR=z%8pRPp8he*4lu42UZi1Z58L9+L6En zquH0N2@N+|IbX&i({V_7lS9mZ%HHu^G$5~Tcj&y!nCHJnhJQG&t#j`D~^%CoY%|0PRx+xS5@s40e^TY^Z-hyf+LEmT9 z98Q-uh%O{V>%E=;qd~RQEJn5r-JjC~9SaFsPdi+|IVRwo7mz)6C8=zDnkR0ObeJjr z^BO+N&uh1OjBBeUQ?h=M_jei^rX(e8P$oAW(sBJQ+9!T#sAwQ^wK5#LzxEDt(EaLs z0iPIz5e?X}oHNk_^}PF~t3FBZr?GQO%fzU!P{a~j{JHVSc1kZmb0+wDdL8^Mjma+$ zY_TZCGiqtV$%W_EeY<0Pe_SKH;$6!F0M~gP1#Gdq;Ndwxs{AYHklUkKk6JvknUH*! zi>YkKoVUNuWs@O)F|&#xPe@A}p-~N0#pMUy;o$a&=a_C-+$+(GpMw1)2rivhohi&h zvQl_HK;Qp1HDfF_=$f9Nf6IfeEOK`LP+VG>*2VaaPMs5SL8`y3WgQVOUO&fXZrFmW3m$WeHgQ-;_NwaLX~`LsZNh>< zu9K~Zl;$SN02u+`G1SU`dhN%qtK^*EHBxM?A^_2s{4qV}br^@a%6Sbj)s4YuOCM&9 z=M^2Pj6ntXS})%_zZnbiwT;l^XJY8uLLyg4c3I<>0gTOty8)n0*{*FsV9I`HC% zq3XG(T-P6pre|DRLvO*KLl>J}N;y9sE~czvQ#BF}Ovb(OxxMnaZE~b2NPLm^XO8c^ zDbfYx$o#k%Gycnq^V0;gpChS)LXsWP&or)nejWe}kMu-GBlCCaas7)Fh8AJgK76i( z5=U3$(_J^pnSwUUIrf3s_nT*XfV|h`Pfqp{Tos(z&h1FTL%I^P@EMJ3M7<~loPL+H zC;%Ws)iMWQ;}CPhA+bwNo6FBzQsK8`P70f8%YmnS3zw&0({QDz&Nb6|h1}%AQ3u_w zb==K8blnKZ;#lbIl761gt%-w!$B>S&+oUf6uL;8|Zqb|xM&s8h>xD_8L*qY33xsQU zskTmXtv82~yf8dz!g31Y4t~T9TitS}{C?XLz#v{Nv_H0}`81nM#+y|i@rwm9BZnl- zF$nRc=A6*`P@2^?+@9aub?eqI_mx^Bjd|!4sB>zh8mIeg3HNj{Ke;_WAJAd&OV_~xeY-Si zallvz8z<5XFkD~7OztI;8qGlD69gjTz}^1E4a?09E4GSy(1Qo-De%t!#!?zDSQ?+1G$jT;jT>dV zkr3uBlWLC66UW{DGLA#w24717tVnG;|AV-U1|xHqoNvSkO`6g9ufsO=hItiY!sof& zk*O`P4FFlRc?-S$!JZs93jra)aqoo9e?=+>v@vz$<{*ELM^{pI@f!IE_Q7Hn4zE!{ zSP=ITN-MIADPC?3hmI@`^=c~t^us-WieC3!0v(HPO)lW+I1FJBq6- zx%?67e5g9%W<`56GSul(OPfhwII{Xrx)@Jyp@kCbbRs^xFQ7Q+O?WSvxRpY!n=w9$!8ecIG@xIcOcv3?)+by^W!e;TG z+zq#`eqVLyz<#utDt^AEib`pls{Qdb!$RH#>p-tm)-5AO#3S6y_94yK(r-w#%dN1> z__+hr7ayO83)}C%@hW&D7qAp_JnI_jd=!cq!p^&d>q;f?($TskJ<$>q`}(Iu&nhcfo(N(P z>z1*YZ`~1noE0Rw?-X|0oS7**Z<8&J$C>daWz-JMQBqS|Lcoc<=g(-(!L?31ZkbgW z+1|i<3`xMpQroWGE94O3B$z8O53~E*d%|I($n>UxN^Vig>)u$FW~}U4rJ`O#038-q zercv?Mn)x?xF-#_8BIomiwy}f=Di5(Fj4))aJ~05D{$XVBK9d>m0Ks=r;autCa8Z0 z%d{}T%$j|R!1HZKNC#T^-%bWfn^TF=qEL(hgY@oTl9%t{kunT=P%K5XlOquf%wD7P z7tR|Ei>~RjQ?zn0eul4t)#|EYz#sxe_*h))m6`_@ErOa`FPTPqsi3Nrv3UenWI*3bIebbK@!rJ7@ig z!olb*CxNKocSMi#>ALt=7XH&$mkQBg~w9r*=o@BD7A-{cxfPM=@mwU`5_Sh>kQPE69ZpFIqx+-H1OB=Mm2X;V-uqG7wF_89A31PS`FNO zqaje23%_c4H;hYDf{y)cQ#u|jRa$l>MLV104!O|PYNw42_-U&M%g)>d5bC!MNFwp} zB_t(?B;)A>j1isuWms9)hX`D>`;gR@Vp~&Je~^IaXyGm@@fUh0t$w#~m@JlK^gE13 z<_2rtCK9TOZXj~`JDO0$3|0)p6h{ipJKZgq&Yey_SDZZT0qACH?ZfjA4!9Oa(ve7E z=#IU?3lWm-r1H8hN6N#tgJXBU_Bt5YSKC)O4YvGF2A#kYZNF`|A9rcKx&%vkKBJ`A zM3Vzbh`Py^4g>*csg*0%`z+E0&wDqch>Vvr702< z{xcNF(o6Qke;M~ONegL!sc_&}rAlmc;;XG2V$vCsC3m8!gmt{#P_=$TpSpIgU{X~3? zxyE*QODE5GE@cxF@;MQTOHT}i8$(UbvdV~ekJbwD;p12stD_Ktgvb-M>Rs^XS9{+6 zHO|qkI}`%hL8VTgaQT{K&GptI|4hf1Sz1C&8=ojqGQ6=8;IJY?h~30!rAaJb zvnz^}P58x-A02F!$TMZlac=(b0ZmHH5W+HJ!UpJD=pARBH{LID_VaOzVqf1gwR73${(N0SJ#U; zHF@K7%~I*K8Z7&!H)Xe#0U`x4E{FplyA7PyaAr{R2G1PqNTM~F5gRf46gspDC-gst~*;L=U+!2UzIs53{tX0 zXj$>&8Kyl|qlgP2(Vqi9?c~KAi^Xj-QPNJ$`2AE;=25c$d?}&Nst@R%``N`K{j}Y& ze)(n0>eORE=GY34kuT!orRyTZNo@%u9)$uVKGP5t4)Y5nj(PpHk)+%_MDnJcRiF^m z2Z^YiT6fi0Hbo&JzJA8oK;!%T7B59Fb%b(_HuPfG+;oHu;nn8s*jcfg4-Gv+Hcc@Lw zur(!tqR&1q&eCde10J%IqXV-Ow)=HMuppU53% zXSaL%7VE@{k8$`LqR_Ef?gPl5LuwJFgHmJal7;HN?Qm#JiGhQ60ttX1l?ij7<0Bi zvKsHOxTl8;j5>0UbjIJP-$)<(ZUhcRory${=xni(%V!Ac6Y$TC8`hIc2g@xheC@pe z2V5m=ze*nay`s#9qw>df@B@%>XtY*>p(^mq`+Xl7MxL`JJdR9xlmy*b9|QtzB&p!B zZesx?Re&}=zA{C&1b^2!k98l!MX*jC53J$c^u!~B?;|8v$^2UWG|;JQkC z@2UuSSur?hENB1#04E_XtOx)A$^TqOL4yAr*-ZNbeomlHf)dJ*KbtqCarnuvzvjV3Bb(O&c=ks$;i>f#Ma5&&iNXom-i3{_e*Z4upV(Mm zADEto2Lb}(*zR*aVP)H-C_Ulo3G-;)MZdpaSH?Nc>;|h|m(C z@;^@(L6bDN-ts(Es&U^J6wTaIlufwL5q4Ezj++B0+H+v_9a`l}=ik;FtvuTF z*E-rB-FobIH|oKMXGs$s=1)3ejkWdxR!v2;kckAkRwdDel5Cba*{Z&1UQL9w+SRDws zGKNnkXPc87QBdL#FRG8W(j~sF=VXZ{R-8lukKjT?7)Em)f#ouDGMt9^w@n(U2M z9KKIxWEz|Ww(7-7s~d}VN^;BEu;p>M5-i{FJOsXR$PVF)mYKNg?zuC8|X9-;4WZ@CkR- zUhf#@I*ru8UE2C)1py=TU;>Z4eO3EVGs#Jg9wZ|@N=UpdoF`R0h?~X)U+$V}Sh3Q! zaUE#DyZe?1QZZPbVt!p)uU;2EU$YzDXnbAO0mKsWXqe$VqJ8%6IOAL$MQf8(^ceaj zH)EKS_?xKxwyCok9r?mRzUiOZUbn=^FkviW;bAP!o?2~b))AOyQ-J+?1A7uwmxf@` z>L8)H*15+~`=Mi`4Y(|?0Sz?}rJ4yq5kqAHd?GQ=z2Ym}Fc1-7U%*>|2~dM6M!1c( zZa5HoVg`>1=LJy^&iLun@uzqHw+#E61EMpD*uMHvEC>GXO*C(r(k2u-CzX3}@Lmxg z9l`4!EzLGIp|Zxr8s9WKPZPgJR)t|#_{!@&nlDtt2mANX zC_H*<4f&co`Bzu^Cy1GBhvp3P* zDH(tsUCj3?>WxHOzr4}E+l}Kv-5G_^cvE{8?e{i(oxGL)E>5`T=h3dUBc2NhHGev9 zV~%NdmON1A@p4gdd2|HEd~4sqy%arn6X6FAjlr%mZ1ej^WKtXxYvQ6&`gS?|_zU}h zU{OGb5)|zA6Y&niw_IdY)c(;_)+_hxu6L-01gJ7Bo=(cNdm>lF8eTp$;|y|5;Jt>x*rfjLKVyNca+$oXAp!+)#1EHh`Y&(qSt&+ zBE<@$MuK2Wx#s$aUuHP2{n7dDcxF4iC_*$e4!XEyXq4NMc#Jvs>&RyPiFP4oVFmZ!F0K>D3yqhhRP5gFV%1%amyK!WEA7e?RAI?=r?xXu zQPs;U?2?6s+um+;J^MtNyA$4y|0L&(gCH19_xp8W0N4c?9QXa@M$;Uc$$h<3o9(-+ zt@<7IN{$rW@7D{{uXY0r1ibB;nBE6d4JlkIKcCn?n=M)Y$@KJB%Rh%V&)D{XztNBG zo;z{YhXsW~pA^y3BvWqR#t?EmpIUxXXkG|TGxHAC|7!lY&A>(bX{Kf#@@CIWbv`>D zzq!En+PUARe~TSr^2dnr8akjsmSDVJG9KJIfFQ(?%c2oiNWuPV2{UDUr6yZxEdoZi z(V{yL;-CsIuk;>_BF&hKTAx(_l3Wk{ILwvi@cg~wpp2N9D&refFnP=;l!&;peO&r6`$p-{UU&6e$?GgV^IqriAvQ*oT&m-JRHx0c*Lm5&iEn0LWI?)uLo@{k0?!RlRI$n zJ*X_)2iZvfwqR!t1hPbM)l0L<=qk3^f4|aH&2kPgJ;LB`Y^Jh>fJmL4Yd@vy${u|l zb~mIBY7W5h82UR2sHo;hQJ6t})CS0CPt;6Xg2%A`O)gCtwwKT%s|e!Tg(Av>v(Jd) ze#x1lZmMD;VtVPypYVd1Q_~8~6E$Ypbbl~Poi(k>n!NL({x`CFXtBQ?&6guHM)|K@ zUzuPAVm9#MevH%ANuhBlTu6GX@t<^Dds{P!3(XNj>?_1<>7-kGRS_GD$o76@=P6&J z*{E9naw%Oa8IMl*if@^0wGc*)46X6^chMbha9Z($6CdV#WP9TE-rodldVz?&YiA)F zF|d5PfSPNSFsz}ZqAVA3 z6jTMeG8@^)#|OVI^5$XS#^3t4`r&1Lx9SO1MJ**Y`^~~IW0pWVjZ7W6KJL8iP$$@x zrh`#lZ1kCwp>KkVazMN_rw3e|C>0f9e6LoV56NYTSBpHmp=V9L6dZ*w-wyNJykW`i z*;feGzzF)#+<$%2=V_Q?&LJVSS+PgeR;UYraN=51kI&x|Xi33Y{h>#`pH zti7~-5F{>i)Q=`;#d&`wcG>al;#$vB#HQC{+S)C+IhSBVYomBBv;!He)v(f21Dk*m zTA@~a&qEN@)(rc)@aM*LfC$jcWOIXdpRAdkW=*2wz$Bx&L51dVH<8w8^dxhW#3l0# z$tzOr84h`$E+c~rWI4=r1^JL_h?_9JRG!pw+5Lc=X1v z8TvPhE>c+L&6qA3CWuE5to%TutsRAOI&s!yp=fp0XG!M~h7v_0o=H>jCcuiOBQ;&`uW*#Jk=As(4uLy!28xyX*1A{mT z$uy;dKdra;+n)TNY7ckUq*T4rj*+vaY0{VJyuk%`Ht^`%p}cUpf1xyHTZWp!=r*Xc zbt;cwy8Wp;XyOOgUXegSSsAdtv@nts1(m-fG60h?Vlyz+`&tebuL1oDq-FQ~%~eAx z-EMDa?AIzAZs6Rdr2t4@6^wt5;l#qs8O?*fAh)hFW>tkcSaNg3V1N!;!g8798v=z< zz1uO=-!C6T!{-X8ZRoZX3J^9Ais?yqq7<%8SKkn< zmXKP##Q7B>pfZ?QxfD{+5}N%wzhjAF)~dTn-LlgQhit}_!8D`y{Q6p8eyl?7rT8n} zm6R^u>Z!C_ryU1&O-E{YZ*8ErQo9o*ZC1op^nml_;kmzB+R$H=cX&J@WF6A4cr@I~ z{NrHMc=MnpUAP8j$FSFmEORZ#^phM!1$X}SkS;0u+}}i4o?QK7ETBTIWd3iACu|L9 z*}Avy`rNM+ljb}yd`<%XnHW&bN?+k2^ah3riOf7JS9 zsPM%?_nyVuN4Fi^zVtKn9?gAWd7_E_r47Le$UOUGs1ij!dW0T~�{PnX$FjeS%=s z1OJdp^M5*Xlzy`SfzJ)+9~yIN%SuF>Lxq>MPo6RS9PkO3^rW3(m;beoC5-U|scL{gCI-duo@(TB zK$H$MFPCNdYo70yf)Z!`)GCL1s}q8&t#+VDr=1XzI+nn^#AFsbgjQU(u<#I+wrBj( z%5iI!*;renK0EJ@RoJr6xll)PJ>HD&&=xV6Zcp|j`Knb|{{*e7BPpv{bUvu+9G+*|&J^D$zKZXqI2fyN zx~-cQ)!7@}tMRhC*f@In^zzsej>u)J%YWya9!6l8k3V6Cbn^v$ z;*_tPoZ>9T2Vv;B9|gZpEX(XG_-YG^@J}514e{m#dpO!sh_zNr@{z$*BwK2-zcpAF z$+fYlk~&EfCLCEMY3Tgqp0cAeU3Ph;>bqS*%~Q3cTv2_Z+ChaOoT0}KBS(5W^w2_m zX*l|)v4|om8AbN4)%OwepsG~#`mg_b_v=E!su^kYL7UM>vz}0@V`HIcNs&*2Bu>jK zgGJl)Qc-4ObSK&pGzm*8`~$gafX?xjc%CUJz^e*`n{?DRujQqGU63Y93zz;Lml)1Zu$mokxBDNf(U<=V}SiVCGnCji0q?lbJ) zH{K9WA+*^!vZ+2h<;xmLtR%*8xC;>H8N1S^Nf2YfI|%!ymW<$)GW2S^MBipC)glG) zRFx}~TO4Bj)g)qLQk|~$&X}9vnp3)*hL^flqFp48oLuG6Ymjgd>u}YbItYA7BA$9~ zKMuR9!u%%;)0~Me`&GrWOAjY)c+llrg>fJalM?u2)toL64U-$sk+F7bwwWf5gec8Z z#~QH^?00LK>)Rx!C=S9Z?(R!x<#L*n1GSWEy7r8on1l82kI|3blT#v|FCENNlg)HZ z?0}%>0F@qrgMc{s51IBT5yaqcSO;L?{|BQ91{T-aL4${;7}e2CBoF^?TKhyF)|ppNfnvzXCZ*RLih7(4E9^?<>-$l_^=XZ<%NX5eJ#!U{W0;u z5_U5~=H>JC9qOe1^a}am{ZcD|Xu-*YqLcYBT*yVpR7e2nm(xq^&zpC_A~ydo8AYA` zR?NEnZN+#Y^%`&Zk4}QS{)<#32B-jlfHVR02RM@XZ{Wz&0Wd|ib}mJFIh6yI(Ay*i zW`}*^>`Jcqs^i_gZ@XL_3sy#Sxvm*)r3J<7`hx}NAj%(0;Y>Q5lOT0kv5#wd5m-Nw z9C#_`IRa1yw*{f-Ak@tlXV*LntfLCj-QL!YkBfD5V(P0W1}8)zU`7qg<}M*Fd^~pu z6YQPAJGw6+AacMxx#&Q9@0q5}T&Hnjc#=8_T_q4!Pi+2a)S&Thxu0Kq{K_DJtet`} z-Hi$V;6;TS-4dDF-PxO2-8K8RvJ@S5o%4CihtpU-?Z{Wm1;e;E0>YHJ3QzLTU z1ES@z4=n`-%-eelIx*+{5skAuHZ+97MCy(0yLq}Ecv{7Sg+p!Ch8n;on(^AzBV9Xp zlJLrtd(zB5sFmpCn3a=h-Oh5Vz0Tm2?s~CNv9!s$f9~W^f-c?J`DE?gW>2E&w*JLv z4ugM?<&o~uA``1KVVi6D_OLUooat_0n1bU{D&jqk*i5rQ9b1y!k(zV42#e{HEHRVz z?M}kQd8T3JsjO=F??C3_@Xyp=5CX`7EW#O~7YtG_AKaf8F;jqIp|nKwI)b&$y00Wc zBa6!hms%0BS>aZs&5+&Ca(g$jN^p3&e-E|y4XKh(^wD9i{?q@tKkA?*D>5|4#BsKq zTot8>N5Ss#z%9Mral%)@dF7{u-T&yhUr92GnB&kNa5^rLEh|2}T`+8rkZ_@9h9Am@ zmu`Rk#B(dIDc~M--~-P*V_cgd;q~0tbB|iJ>H_FYjSTX^*;>pubkU(*Qxg4-tszH&u-R(2p1=YTe(# zEEXiFKvRq=sYV?|nA%Q!>_fX|wY_!(G;%%gM+m$vl@5VU#Mk9Sp+lR%-jwW#`>#=+ zTEnOo(Te_gGG*I~1(kD-S2w@h(4@*Z!v$Y1c$i|zZpmzcbciCy8EfuNh>x2KWI1B8 zgP{h{M&HN@n+FJ?YpigB65rnOC51d1j6mHIN;WSBL|#4tD31@=z>Z3u8Vsnw3&yw? zG6m6^RgN83evBo~cI`RD#G+T5odO(-WSYP0(NEvu)CRWf3JPYSQNoKUsT)t51%G#` zv#{aP>AUp@g1^Gq3bxU;l^^=?`QjM{zIOCKuvJhr#ScS$9?J#7V|e(#FOF${%@-o< z@mdBoOhXTCiHG{V(}VKZMBw%NU>J@)YMOJ_G4)V&;uZ-)-(6r6#eTd&{h`FlPyRH* z$#{e^-KGkf^RW_wAPMyJj(*~E>$_nUGQe6u_AMv7*&y556&wplpPL6teC1Z1W(SsO z*LT-Ddi=cx(|ew$@M}Dl+e0Sa-&38kH}vfD`T0irK(J&dQRR^`T}p7o}y( z!!(fWbx+ZEu@H8vnt5^kwZXD9V$*@m2a3a%imyf^I@S{nO%fOPV|&kQ=h{Tt^jP}2 z-AvJK8QQs^L{y}@nk)$0XG+L|Lz4({pf~;R$U|2!7^KrVoW&DJ)s^w5T&pNzupfg1 zSt0?X;P1~?;Idcbp6ZG*9*P=b0ent`+iz!VFadX?kJh^YN}oBOF9l}rFN=`LitEoQI26!bnTH+d{MkMZ0?_GiXQm%N>Al(E4E|{-+++TmXeh=2pFKds)vt~x zC>Q++m|yMMrJDCZetwapMwa3~1}Y&pAE6ZA03Uc1RB8;i=q-yJF!;7lvSgCmrRLFJ8I+F3LxjkIfat>xoN84sZi>J z_6v^vALF`d;7$s&S_VamOqYcEbp4+fo|N}%C*F@m-8=*UGP~n$)f55(5D0E(BoVF#P9AckQ);A*p}K|h zTTxe%h-c#;M}-l^lVVwKjQm7MiMh1HfhR_lg`g3v&80Vi5y?jA4b9!c;*{&}X=W+V z0?uyce>2=n=DkyttTg2Vg{z$is8nf30T^sOo!mt0L(@j-Ik;OsAiqwoC1FB@#j(Ks z9J56elTq5d%qh-@y0{zM%ASuBY%I@AU!W7tzlRj|-F9?fDtc2ASuVhR^gNwsER3%y$atVcS@(HN%f zp+A^&rXb1bZoK{YH-54kAm!S@6odwdg(~JNV2c|qnfdVbFhlqXTQOQvVkQ&C?_Vb? za>2v?>?ioVbHa}5l6>Mr6)QtxIq@NcUqeu3pnS@~iIHgLw0FOwCE}Un$A|I=UiDbI zZ(h3r8^jAa)L0^%UxxsQ#JDI{-gdBU;TZ8k{EL5Ujox7aU8Mq5K;~JJ$CPxY-S#X1}d0nH8OOzySFl2^S7Ajn+3WJ#?w|978a%o;b zIkFoD+fH}m{#)xz85Rdq*2ol~!nv@eBI7eWcV!?^3XoSS+C`_+;x* zVM!x!VzJoTOza>e;pGSm>V?9c;t28R}jfbV}4%PG7n4p2hG&jbH!nhwR^z%TwDV1AWH z!G?S^^Il$hW-r5@G&VrQ30Gpd^Pga)FdaGL<~Cv|H`1@G%bN zR;365X}uEeY%?!r%4u7uK9HAJ@~1*C>(}H zW=Z-3ldY~H!#}vbU^j2gIW;p;0Y!d__eMmt$25(MW#~ae$;zXWbBlDnDJT2writoj zlidlA23#Gib$x z@ALxcytfgS)#*IKZkBX}zP2RyjC7TNOpDOVi^-)0T|i*>?2*uNENZw9B?@SR>}AN-P|w^|xEH8hZO}t85CBpKR1tW2R715?u+> z(48wwSb}q$rcy-?6kJ>!5=50_)1*xK$#Ib%@H#z^B+bJWB(t@&h+#7%kc44BHS(y< z`wrt;eIT8}8{e(AGnKCI$?N~;`|@gi8+Kl!ex3~Cm3;;4r)@BrZ<8j(@|G%0!z(i;Ot_k{9~9)*hgEd=!3;#B8$>F!*E2{4nP#N&|+U2i7d zzH1eQ25Ovx9}d*{Ev6@Mkby1k1TE0m?^O3v)F4j^G+h#;pXLgIF_S&4<5{SfRj>Y` zh5u5~HS4pC9PL#K%w3`dxzi5UNmnvJl23THNSiW;N5=eZfx!Aj53s>r7M${=xz!!q zlLv}t)-)#ublm-Fv|uwuunlnBX8pGxCLV9It3~_kYJ9SijcMQZs)>Ye=&WetMn(zk zNd`9@-k^H!ao?j&xfsHi%O0{fxV`ruuol>+mh|X6-T3a_&@;WalJzeB5Ejg@r7NT!$Zq(uZy zjm@hpcXKpn6;=K;=E+C1PXSa;08zK-yVjUc+JB@ITGGor0mlb>u3VK|vjmP;w+oH0 z#ooPLD(+_he0TfZ3{i0-@{aG8|H-!nFM#-k^40tFA5q1Z=ywlb98`O|6&}X#6$-oN zBTSLIn|eflKb=0<#|3d@Mb(s<)o%@x$5i;AUAxBFn1J-@GQ8fUj|~rEaPLwtoj(@B zzjIZZ+wHJC!xG4R4)hRDRS(%&ST6oJ5r*TYtq|=G_%cv z!1)Od^(0nP;3cg4pYDs*OF;*EVzJ=d@ApQZTWR)N3HrrEP?>f*`y)P_ec1nS@PUY`D0G=3akd%_Mt)lKj8zc0D0YtGh|+95DFII z&C3KT#YQGcTQEl%DMhAW?%p|9!Rv%i(I#SWjfIV z7ED_TZfJEx21Gn#;h&{I+1~;xA4E8;!0~qbr5&8)P0b9Se_;E6H)8TKd7#- ziEfoPpl{ro15~R6LW~rYEtufXix{5@4zbnmCCr$s{voJY;Vx=ox20S}gS9S9badMg zZhLLu!+X+HX@e+~t~mc_PVOL*D;kU(P6Vj&$aqGog?fwRG^_|taeS|t05I1j*VVcI zzfiyoCuxSR|7JGw#;GYdM2TVX>YhrLcY6Qdx;<2*5Rbl&E4%9mGJP?@aB?Kv7H&a2 zv3MdL4F+kCGhd$=J9iPn8LC@g$TT$G?}C?;85nm{y*CMBba<;+Lu5I>JCOYq-RyX1u|?0u%FPI)UyvZ?(R~3o#IQG!0xxr1 z^ir0}=GyqQl7uX8lzU6EH;-g^A|k)Nhuxjs526>i!24#Lp|E{*f^Fu4740A(uu+il z%6I<}|8~76ScJ=pm=ML){`l0#bprG9#SSJ_GYPiC5AGYdV5Ow~r_s#itBDg69zO>e zw-E?-epTdzkI{9Ks_?q4_+UK?B32na_*{A3clsq7jlYOs&_FglX$!q!hB49sWbn)T z53BDM50VQmF#!;usf^13;SXygXuf|;>!B3uwm;KONWom`vx41)b5(_9j23q9VEVL+ z!=N{+6sM=)Z!rVeQBU`8bBTvCx?8^}tNx4ev)tSQF@cnNud z$WU^~*!k?0%$loN1d}D9&gd6bvrYt|Q14(~QWSy1jxj9e26VTMtdR)@0{J|x{`)wH z{NoF5sNjVnjYi4oeXiemg@hJy(6{ED(t2A1m*u~gNB`G$QES-*@(GujeyFG&PYSZk@$dLm}-6?_ZZP2ok3^Y({?kECS@Egf^PSEpU!{vu?y` z4FZumIoW)`&}B_bzP?EdO?5W!431-@O2K#VO(%Jj@!bb$kN?C7PE+>hk%vkY1QK~l zGEe?JvG$aG@V@$GLido>g{g*@)%a9iOiau>=7S(Lf08f59i@~uh?_QnCOf$CxC5J)a~HH@?04U_4uPL&=t}?WYpn^M1guL)2#*0 zO{L~2bp3Rcui^xtso87XAe&{T};6H2ZsAWr?G+w(|^9zK@U7zPv{%$Hy>Cy zBs3~!8+ID0S{N4p8@0EFGN#|tDY8V?X#PYRHlmFN{8kTsaH#Ebz4zp=sEHMRyW2n_#B!T}h#?u!Fxm z_DXM>@L^(Fr5nKru!5ob|VSzyEn!k$xz!ZVZIJ@JyyWpZLIL z0VdFc2=zq1cRaKe;rtE38jOwDgGhKaF#X8x8&BU#slCu}lNfvNxtsU=H$*lI5cKo% z3EElq%yt@HzX?cy4N{w}4o*y$6J~OBw?>K{*QDkmx+~mzz8IBT+vNu|i!}`2F|CAu zcEXyTP8IO@`p|A)O_I2kGMFYnpZe*F8)&T;LGU8ko=OSa_DE&5o(%{$%Y=`~YM^8v zN&N0QJPtghun^jx0ZD|q1P4et)hVwy>H0IGUub#2w~y6ZXNT5mQkg`aRy~9RDGl)b z1gVJ8(HVFnsXIvB1x$N5J}3qCOU^eW6wR{8U_m$CsU3h3PAOHmk`8~PiZo}nBSxXd z_JZnz5M`9NaXqIjx}hpk5HCaDk0O(q7N%33YJNa4XiTVFvR-I|i3XqvqyiTr%0Oai zgd1Nn4=24O+gBI(8Q-T0UeDR=Rwp{xT>_Gw>cc9th^nY@6&kKBxjo0ICS=I?gut|5 z%xSU}D#parJy_rpbxdIMoTJK1CwU&& zM|BGZni+i6S>Rl*Wd)A~tPpipEB~QA**hj9HrjEhitz@nbwGt8RQqo%a2DOOP1GCB zm`>s@!Gow#&Ur6Fke328FTES7#}H4RqlNxvQZsnZ-CFIsK(OwCeMzGQx?DO;e^>y= z;YJDwPdc_|BdK&qOhL(h5XI5^frp>xb8TSu>ntwBs~FjaAgV9yi5QU+5)#6>-C&>+ z$<`6hf%E=GnBQMvq_-MiJYB4ZlkiOqJaz6Nd+*vMe-kGr_5?lu4C(3bURD)PQAp&N z`pIrys-87kgQ=<)p(Q2Zs{Gx>U|5L7{Nk88v%$~ ziGaKzwy#gREALgV^JJZ_h;W#0#9Q{mNr__J zEGE1FLMBfSGS7;wHG@;1@sLd61kBE3DOQRr@s;Vy4C%xph)uS3?8M~XG@_Ofdv3lqW&TG+; zH_5$-QyY!-;aC|nF}{tX$;XF}gTsZ3FN?08T_@MFGcmF5Ov)S{pYi7X$wo{jH$!BJ z7wnHb5@qxsi17X6{VL=?ps!Fk;4RN!r~nB_p2y8h?nvr%5d<6VKUnha6ya6K_l!J| z@n21x>*Un)5{bldBws^TEkxZ&$o%i$=y)WEd$)3}f{0&!;X>~JEldADDAxb4j7nL- z_IkQ_<=XiDqsZ4>tWY_(tE8F%Km$76uD`M}{}bx@VFgSM@P0cj^%LU?W*f@o@v8HB zwyoEJ{N~KqINFiO2KiqJ`2Xv7=u-NRm)Ex;VFp-1d4JLvP`AXCfnsp!F@G~4kEqch zh6Zo2yL}+znc7`h)gIU0ro}e@Fry;SM|16GNi22d7&~gGhgti{v z(+`XeKP-P9wBzt5@dVywJ_*C93wS|YCc1dxIFH$Br>@> zV_{-DlJV2)Qrtr_lLzMtjzp;^k(-0<5S+VIo@Nr!JNfl<%E7-2dTJ#pE*!q}W^8ge zJN$SOr*`PY(L*{o%Gy%z6(BF? z9aA4pg5*9dvDU2b;8S3@bmQJQyb&_q+UkF%#IifgiJn9AJUDenlu%w$?O2{N+0(38 ztBx+>uxFJ@3^L^8=F@Lqy?z9{B5K*!vKx~{rLm6t#ct}#`+c)~SH-PDu}62Yc*>ni z$LV0$?G9h$%ML0FmFJec$uNvZV87@xJ#0*g)~!BQ&(2FWyKK?lRa%N_hUl++62Dts z)x2H-kyUB)W&k&A@%g_S8@(ngnLy5qR%LFm`cpMKj_;R~0+NTj64!O6;rKc>kII$K zO^?t9NeF&>{Sb1kShUvVMETxNFzMb2R3l9WCVF0HOO~4LX{HmWrRgjm?Gv#18kZ^N zYX)FSPUWLG&Dlbk-NTB!u}zC*Wi9rm@r2ydyKA)uR)=U`ahx^q}sNz3rsZhE{aKGpRo#q^eHH8GP)cUY%yGYzm@ zohk4|x8`M|T`8c?d5=VE#=GeJJZ;S@$L?H^(27Z_$<&j>92vwx$}gA+<4R9#=O4F) zzge2K`|Er3k->O3fWTt0k37=e+E7^Zdn(@M6U*aapP+)8%iiQDuIUvXqv=VXKW?eZ z%CJUPJ9P4dFLOasD`iJ_lA0jbs-sOo$&fh?6NXjSag+4v_SvvTwFS5jZUq2aQ zKtKTb)ipFsMEDjXqDyA%&}O$iy2w%&eb_2#;qz(LNC#izYphYc^K-mueG8c#oixS`g;QHAEWwz$OA&l}!O=w+~O? z?&?D0CYT&Ype@!M!HunWLI%gM*xUodHca$qMHH*{tVo&ftTM3Aw5>@N{(gElWL>_5(8oe^aEl-7ENvW6Q^_S$Xtzo4}+*e&t)&jN;D zK60?k`HsPLH?hIGJZp!WQKW7y)B)6vTEf2JCt{Xmir2fY)|Rn%s5M_Vjo#rr=kNrv zfcU__LP+j=I$$Y0sI{fA96+~mK-gkoRh?qaCi1`42Xg*4&fwsI0E*HKE>=bnnT>%t zJxzRM7O`AfY{B72u>d>KaP!`-tUY>pup$R(Wv7P#uU7uWGX}V@29=vV#%T6- zJ{*g$NBJ2#C#qJFDe#nnE>Fa;tFfQrj@gRg7YFvt-1g(vs4h)mje06wTn5-z+&oJ8 z!J;{r=XRd{?+8FNxR ziF5c+H7;jG(cZxCgGtcLN3Sty-tPqP+ww)0L78=9)*kg8Wm?Q&Vb6IV$H(-#uZY|K z#RDn^CT`=V-J}LE3)ARxA&~q&RW}-E$#lAS9P{@6pjvK9fE-JVG2I$7!DO^>vhyV8 zm%yF`%DVpZZHS5d${zAM{*K6N#xr76q@f5VxRLCHH^!`+HNuIG{Cn+oDDEd=-R*WTwiaJxxO}J?<6|ExWxOjJ$Qv zXD8pWdG+H<_`IsU;_JzbkE-#ll&lnTeS9@WeMX7gofnK-9#`gjZs}%lj*c}#aVGdO zt;)-pf?6AC@>-e^be2e7ZWWAxM$Q@1n(7NF>p)7YR;P-PM%(vSbg7Lj`Xx~uIXsj0 z+x?_X*4tVS@YxzDQ&0vt$|EqE;rp%Uj(u3^t|l8km+x94h-JDybW|)KY}%OL4J7vn zTjnj)eePT`?{V)xMknmeK|vOCKkUU?VrIRAl&mbvV6^&1*D8FOp7`_99C5;AG5JH7 zGM%l!=veZfEP`m^F7x%VWbrryvP->4)YHBZuUD3Y454H3IbyO)cV*hzz6tRD`gbTI zz*_u+X91K|>sNans`kc@cQR6XPyqe;=MV^_>`|a7B1g_o%;yik>}4$bY`hMopdl0|4)$(cIgt8UMDv|w1;H2?%MdGE$2H}!SO)*q5KHQ z3LC>6<8f3g4@Vdah*v^bkru`9^@*fag1H$(@ZF6+ADVuLBh;w%ey7OSzz%oAVEPsN z2SEvMtK_RWmKJzeq6&AZh_by_4ecftc)fu{r`?P*e`QJe-CnpK zcTc}+1>u>}5GGp`q$7_a&1)GrG7Ja5)(b_^c{_1^tkC7f$6Pm6Ek?SjyMPbJY0E#0 za8BRd?lgjz9_`h7E!0xu@7BR0_IUTZY}Fmn7jFeIGzX^sDZ^p161F(6Y3xv*;{4P5 zjdJwg6%U9qiO^i53ym@?MO;VspS|;^W%g!sOj)y?$rr@V5mtc{YM5wE9t@pGW4PdK zdlU>?q>>G1ArwBieCECR5e{`PT9VHq?>{OtEDZ!kUyS>Y*UC2lN|V@VSdJCn+cm#q zuFmQJ)ht~eCptvOqaBjr3B5W>iPQ5$N8Ygf_Bp{yiSM*EYj6UAqNU%JoaPOy&d5`S&|I;h)MS_8v{%)SApQRR zlb(zld^$$d=xAU#ovDn{`4o4`=|xJQhU}T_* zjwoPcA7##F6Su3=9<%4g9xyVq6_+HXN#MB-kzV)wnzu8MR`6gMVCN>XtMK5W-QkEG zH|-rF3C%LDTKO_r9(JG;RY%#u%;`*?Bh>(jQkeQAxHX-n;CSXreX0b!<~PHF#d1T8 z2PGGj3~FU(x4Mgj$DMpnC)5yJnFaUD=lL`a0#Gb0MkL@E&{sXPB|;O0K!GPuR1k<9tWMWN7>L zuXA$>VI6&Y^+MyOEw?tXD*+t**Q5tbfQ)GR1DZUGFr0*MxQt)bfDMs;S38bV>##s7 zGi15qQ-*9Ntmt3Bd`gClJ%6MEQU7Zih9n{s1EZuHZVcUM+~~_~p1%GJ?@PYMocGKe z<1R0rSIFM}j_dB-657dGQSgU3o9eYM=n>2E5xI7cEr5h-@#K?X`+61Vdig1cGp_@B z8Zrn7kZ5l??5Rx;1pS^!e)yVs-AVuuIhuw}_~ikurhzH|l%W*~T3TU8B<_H}VoQAZ zH7I|=h&s#lnqO9mq%|TtL|ZBUaIVh0fzj_jc-~4_UU$j+C0X0D6VT?#Y2#`v9VP9)md~$m68C}%;|xX~TCY(rRl2o~VyrcHh_;w} zFnX(he1mi8P7aPvBr1@H_-L63J!+n^Q$jH>NnSpwW2*A)@=N|KMX>pwbpf(5hP&|# zY*+Y$IyD&QLPS8P&IqQmWD~7`qrRaVN)0J9Izr8{Oar5ILqo$ub2(DRc?4pYalvGm z9G<2LNTvfx1BZDMhPgn3xkLEc5;9(I%?ZQ*?29`jUC>KpG(`J#Ouqc`Q*)?f14n|B z(uUrSHqI{6&F4Vu0bf_0Xe2abyn56DwJ5pj$EhMr$LQ|AB6z_*b}X2fZy}9>E9F8n zt3s2Sck#w)5yjSj&%S4v6n=Yg9Gj3BwVjJk=iSuwIeDqyZVh_f$1yK7a4}V4_oOxg zFGVVX^4un}z7=apC0Yp&W#J8hjYAPa5pGOSdlD&C&+~>`oM{=3yBo?ntWs~zJd4}T zzi6N~oD$f4*3i10++hzxa>edRe(&5h;s2Uh=NP0+sie!x82pvDF78EK(L=1<)ZR)}Ur&Ag zS8U(cUOQ}A#huwY_PkqIux1k*D;{Tjx`Fq`3ibxOImZ5KZqG7EDw@H9Jihv# z-TwmYXZbWQdh+?)yJ!vd4Vzf?_B|B4bo$=1k`{pAZ@gFHLGL}5neSFnwWN$OX*%iG ze88^upoWckxOm~`hgZhnGzT#8>2hk8zsa2iiI@YYv-+4W#Gc*81O#@jPT7|@!moBQsXgfNembqOsSG4z;ok)z?PD^SmUOR;+O;47}te8vM~o zpa2K9E#>~J3dl^3!y2O#=jun^*fLh`4L3PITjx)vAS;D<-Gaq%;K>=o&982x~B zy7i|@W=_bbZ=#JD&4M-7iN}}Eh11_>M~FkDlS-g5srYieIBf=Y&tNVut86l58gSjC>|Nv-Zfo>&{xCl^vfx%!DEBt!v%_ zu77d;k^R-Wsf@F%$Id|zqqwaF381Bcccx!NuE&94HE?)x8F$y)N7n)b|Ego&jl=1e zU}7fpr+Dgo>h~Yr|J{lC3F8G2*u|PBOBkAN$F#ZdT`+_98oPdl>hTFQa>wcMRCKLGwdHK_elI9OK%z_4}E?(ukV>G6q9_si59z>%07*qoM6N<$f;*c~+W-In diff --git a/localization/autoware_ekf_localizer/media/ekf_diagnostics_callback_twist.png b/localization/autoware_ekf_localizer/media/ekf_diagnostics_callback_twist.png deleted file mode 100644 index 4608a90e5522005fc9eb6ff7b3629b64fe2024d9..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 17945 zcmdSBbCBoIyYBmK_q1(K+qP}nn6_=(#HL@6o4EZy8LH-H* zDPuZ`s5>dynmD-{I2Z#=ZEUTLX&j9ljE!v^&1{{nL3((9PGT}wR(BF|Fg9>9x3wWq zHn%qZ*$DtJ(lat2wl&go9A$>lvmB)s5iqbG{S9EEKMV_@XE`oOaLOOe1^@^E62bz? zZkZRG&Q2(5*x)y&OKewokiQ7U30hHIW$egNQd9O+OBKxg74zKkP$cc4KwI```+z|u zZ+8e02nSVGkGBD8Y81E>MHxyLJH6cnbWd z68DdnTi*_x00Kx`T$N!yEH;}D+Y})L(A}znmlkLO$bg$>Bp_u3P{JHx04k`!KQcsq zFad-+2~hc;t9u~4_Shmk>h!bpi!j zI*aOms%g((zOYM!qMXe97#N9;V?pGHj>|*}%s||2#mjl#87z!k>2_e65*_z78qH?X z+YUst<3Tq{8kv`Q+ps$1qQt@Stjk!i%{gb>5~4E1E7lhTfsm6at| zY{oUwdl7ph024ev3G~|=+A*N{97=*=XRbqC^KC0f)VHhX`CDE(?dzqK|9S^a4K%oVS#Vguqj`^<7TQ!p45#lgFEJyPgZ z9H@N`17b0a5qcJdvlZc2Y;75?{H*%EH2gUJvkhX*?SsDwvK=zyzm{+Idzu(v83mIpFoFnCqv++Wt}NwskNgHkgO6j7+oc! z%OpBXf3BvREmqZd@oejz5(J4Zf{s}J2HeXI^~A~EB{#iPT8p66FAA7m`u7$G-kvvf zD%yKlh%Hng_z6}&)h?9gxjqbV>GX{Fr^kQB;-vZoS6K|DuR||#_@ZlOGcObU27!_4eG8gRMHacIjWlG-3LPtrxl_q zh)5=7w!q1b;tsKC8cax=v0}5bg+0}tp5`J1juGr0?HosZ8k{=j$_|GOgb}+luK8sr z!-srZJ%fkrD%NE;X2wnr8k}sNGtcr47HifY9vdm7c88ofaguh=5Hood+CG%2pVtr| zCQr}%c8Qdb&BD*z9AzFL36x#ivcO-}6ykY`hS7E9@pfx4j6aXvyI4j^nmyItGToY( zw%o%I0JYlJKZi<^0W)IjYr+(w-x~GWhgVC>h2&`niIEU*CE1sf9V0J}L@W`jI*xQ# zd#p<S5E`y3+C)6K1VA@|qfG&o^64|s5*sI~ zeJBQ>`IrjaYkr1yVcfG?9J{578mFCZzM))-+#Q`!)VP#eql+eeq2E2#1+2M!iQGx#{`PG zJ6%)ytS%%{F57G%$R$v0Yz+9PN8me-v^7rawPH#kN5fzv^IM0$!xQBrxmkC%HB@ma(OryIkyERgH7xsUTWVm*2ljktUGp zW~#>0#w2s>CfzOu&N=;Uz-FImmxiC(a7r6-q1&6Wcv?uo88D)lo_D=!$SOPX+*qk$ zr}5r8yvsN>AEGg+l^yp;j4f&z0uvqn+wcnh=fFK4nab>x$Bqtm!idLw=hb#QFS;61 z%d0sq!{u@>B^kQ))KC*j0=@aZg~rqUV1>};vy5(B^GyBqJd)Yid1LTDm5#&}$;~}E zKB$NmUXM6JnASCgM!>-qGY|zcZ@))paX&s--m?h7;Sy!vTlvXYotCqV}Qsa-bEcl zjKi?#ua1|z*z|1ti$9DK1G5SbYM!;n#nS74$ehWxU6N^EnLi*uAqO(G!rlYnt_%yf@l?cqGy3)Bo};uTvW=0Y^<3mx#S3nP#_dL~C7cw%t z&lnzbmtuGQK~M{5XVW_2)2w@s_!jc#GttyR$&Cp{ObtxYj&9vQ=4LAi%hVNGpjGY;Q3-*?O%OHbx90{ z!U?~d!_QtF7ro>b(vB$Wsp+1Xwga*VJu!6)f&zKPdf~ZZOALDWt zE#`njsCy7#bg675K&n`I=o(=9GgZOKchsx6-WKowG1FK2SuYA|z@bQC(ac3yg-|2M zF$(^TvZ{zfZ%f7p7-RZ9aE~8f@AS=eL*jV@!IH`dnSt=Bli>~qxd_>_OoPSQU$^vO z)Jn$sWRw&nTZ)qYTHz(a_-p~&ODr2lRGdRB4*Pqu^!fboe9ykvf8i7B_}&R+fl4sm z7E6=}y1+v3^R3<3Jee5`%$mJs`l_L77Kk=mQR}rL&rHz;xP(UCF$Q)oE0O-kkM@p8 zub1sVbxFE^+OchP<+`|A6ghIFFv)Pm5~1JD4dKnl3CNj!zgcX+*Ah$tQaR0AsqI9E zGUaV0k!o#|bUWo_CWKf8mmh7TSX-(azFyDX`FPHn9WbEewNb+it~4gz_yie|EzUJe zQxl+A)Z4%p1&IRHZw+xim+OQ4g+?Md zAa@DWMsTOeU!Ex5+0!<_j$@J~V(mJM-=)@HZ8!)XKoN2!O{o7#v3a zkEN5~ZxnsSf_wW1$z`YzP|MxnuCZ<~4@6F`lw(FC8*;3{blo3zR`Sq(NiY=SvEIo} zxDNQi0>}Fa#Qvc1lK%LUWlVh7U!o$Y03%>1EyE}MaK2UAI^y&Ft4u;_!OZ;A6g30Emke zmSD|wrIsgb)-=6B9X;SjB9rh9?8Z{@e_z1z0FQ$MxCZP8+A**^Bc=MjBQCV$cEfGv zyTzp7QRBRRQH8LGVA_hUta1!=DAP1v^8iCnOOqwYgDd%L1pF=;K=e5xx+39=HG_g6V;@7Wbzc<_ChbN!#fY@di5}*3 z{OvWf2FLcB2muk%KP<8ZvF1j!ETK7Ul@)oriYH8IcNdZmJv_)%qEsQ@3)762dhi7k zyUummgj&M~L4nS)tK0hivb3W;Xe%g@2ReTDH@!%Zd{ z2t)TbY6V1N|Bgo9N}VsCOZ7V#--pXna^x;*wam>xJ7%e?EmS+)s$c0xb|2-%?g2UB z+YVM`tQ(BuPb8ej82|?-a?m7ee77QGyH zrsea}T~3Y7Kp$=Ga3UVYuNBJpf+f(A-Ht{78tf7VlYGPq*RSBgK%T?iuGxt3es?vR zPdHU~dXRt{;BM1zL83$d|N~LGOXGnsdZi){({Dllw42 z6$?!&NR3Xxf;L5~*o;(y7cQD+H)SAnvLrn><1eMUJ?E1y0tJaK9r-XY>{| zxE|rx6FXz^;6%3_%%h_1qTl&ycb|6)z)zJ&oT(qGVVEX0$kx>!l3Pkz}F4 z@m6oXJ>Ee4omeAH6n}KCq#*<%sFS>{BQbrs1s7whlY+NoLAj{vM75bE^?QY^@Dtj`0#~En?4sPlIy%|mTRs@R`1J=`zZL=Z;mHoU%Z*HqK(Q@g;O)V zRwOYiUqLJzyU#Q<>U|rLCP9hlA`qSkRsH87ws}&$D7Dr?R}zmkmBVGR_)s)X1Ojb66yGNI}3P~yXX8_!wJC*PssA)M1SXP(46 zMY#lKzMU_8kNT7zWSRvFP4?HisX-%V`gp`hh*}?eQ_WHoW%H`j1KeIpAvPw}sl8VB zyoq1hTbj>jKFY0i+cAw;d|j;p1%hMq>#}0WYXP#|Dz9H-TIM6-DUZ`#li!iqJahY# zn(?~Blc&xI^bZ8;huFe6UywsvDIMyd0x#1DAOt@W&MPr+DZzoj+0m7qym-w<5s3s6 zu`@t4G~B-LJD=?VMHgX<+RFhN-Da>iX^}dzFtEbczE$gEe+cQz*!B*XDd1)}&I*c< zzI3KX2WA)c{yDS1r*q|e{F_aC@a(pL{&;1(fxqx{L)*!64S)PPA{h}(;N|^;2I%2% zNLNpTnf;YHMK(KlyXKRp!hHN$R)2j9lAHNpe<0)?a=Q+5Yb<`EHQ@w@*A81{H?_e8XXZ0bhqhn17y;sZh2X|kRpojPf6g^8rYX}Pk+3cO&77@Q;e{N zC4A6CPZW37;y65gO+4!*5~_+q6uTSLegLzbn=KC#lcIMkK!)bx#>Q;e`)=^F4K}aE zJn*n?I28?%bWd(VG}hH?H+P=j_Bgn=+3_ZnBjY0`3?lef|2jb^UMV8tHblYfif1Xy zoz{oy2zG>6eB5}e5Fv#;(I4Vs2+uy1oB*o4efmFcrtHZ*VHAswnhg|8L<+mH{@Y$* zicj|JjIPwf5D)`yH}u0P%fJcFG4Avpzu%T^V;^NVZ-+j@AsZzIH%F#!lzP&{=2p#5 zR_uYOMQsM=wuT(E70xh&k=Lfz{p%JN{0f5;Yv8LF9tW4T;Px}?P|M5w3yt3Gi5@8~ zVnupankg5=hr@rH`bF$3jH~v4PMrSjr>`5gyMV%o74gI#K!&$}&12$5T|F$B%9jry z=rpf~&kgS}8hbXl!Epjq^pwAic?5SmbM>=*ZmUotgr>Cg))}=Bsy&bI_nTNKpK<{S zacO}7u$G=grB6fBm|XFB)0Z(g$sPXhIj!SsJHW;wVEKK${gQJc7W6s+^By%dH-hr9#YApwqO2q~PQ1785t>O+R zw@;ykwC%bW;cw8nU@@BA`mDX?gw6AWH@ZHPQ<%Q3kv(CurZJERAU;fim`7)rGQiX| zCS*QS#%?yy+yA`ok6RWCkoZR`bM66IT`_b^!*zS}CVSDU0z28!BAQ4HPy#z-`|c`%zhhiRS68p9?ec zsd+?9C_sUy6h%^vI+H&ah^+h83RPhOQZxrMJn;-HpOwTqt(#5ZLeDv-aD7 z)mwKIZ&B2?H^yA$<`}(d)_XRZn+Flu1NtOBto0?eJuCq?-N_1cvQH(g!H$Pk<(H_? z@|@YyAXup2@y@a{;*Iq>Z|Ea6YAvi;0FY7(f!DMd3NIJ5qYH^?&QEW*?fhw~d34XJ zcWbgnrRbseM=yiF4*2lYL)X24im266Mk6ftCW$6xIeiR`>Gxe`;b87)!82nl3_DV%PF2 z8-VNB5_gsvK!|<9z>*uZE?8PbJoPk)Uy8oTaQBvJDr#FpaUUs3SeCM> z=e@{%VPk!}&Fre({(BjeH&@5-D~w<%a^$P)F{aT&7KZ zM2`kG_gC`^nI0)ws(8j5d`~_f97r6m3GmCUwCp9EJS3ubakMmLye~03Z!hfQ>1c_l zN3M28nj+>DYVrlk3Ic6ex}QIRib>*?egbpn=%9u4f4xm?4pDw2|B`Q20E^ymiwcVd zT?CcH3|a0cLFLc$Z}3IP z{1KjiFoN%Hk24eE=VFM$cnHK^pzOoO8NzTql%i|%)dl&t9SMm)c$jCo6e3fsu!@M%8F?gqFnkOw<)UawR(Chf@cPG4fuFy4@uey_5B)_@7V5zA7K z@~n&AFzUW2D1C2m(W>5H?}wd*cd71Y3f{OdYB?y^MN}qS*$nj)t5*&_Nt#381mfHh z3J5y8>U)q!dqIS}N=moZ*fk8Q4B(sjz;=X6W* zili8pPI&@D3z%%?8E&_xeqG47(O)`SoLOm~ATOjdO=C(Vl&LK{IE@o{teKU~uFqDP zkvwU71ezoqWsI+sl=E#`IVqPpHQqxR-W!a&F)%3A$-ukmi}JBjAIe%rM_536dVnh% z?)y`v*&8L`;7{p=vKr-Pkg#ZKd8FD-$_ducb98y3mn@b<8llRv8+$crNT+f%6_YIb zbhX|3zYaYo{AO?J=25}hZ2hW}o}0j)w@@sw96*(m*sp53Q0h;phV3~X4O;Fw|6xCD zQgA@be=WD0ib26}xi`vEiPwUu_q_iy>t&6ldxT56(zR0wlv3Si@W~Jx^KLEWd|`#h zJvdQlW(HfSBoWLOPciE<#ydPPHrJ&>N{D#&+*K;(v2WsH*k|iS{EBpX2mK zB#+N-4@F;BOT@A=L}D76in-$Zg1@xQ2@)bEg!t#=%+#IEh7wm^MKiq3uU?SKEu`#!ZW&Q14*zM2f=Hu7YLHTf59kyH za}C!enshz)ROwZ|AQ9yht2XlVy9U5odgK(XX^SD+gBfeqt{k-0_pg8(x-nkAv1g8! zycECmWZqYQ9&Xem=EK*;S5Q10)g(!YY0X66oeox{yobXZA@I2evYx8)JmOOgZwF8% z@iBN`BQiCxJjziySuAtTZ<6t{pO&)!Sbe~&8Wl&Dze3d{UH2E2`ds`)g5m6X% z_;8~`U;yO~W~==W7Q}`letS1%bBH;#T%j)yDi;YvXnA_h@apTWy&Ylr<=#G^WuPz2 zK;fX$=(0rI!EsJaGiBa+)U*yPyLY$9Vevrsmm+3|m43vh3N9NI7y^Y`oiUv}lDZyU zEZnGDrL%=FPPiS|S4ms21`(9A849P^N_+kSP{T0wH;j_K zR9c#w4HOrAM;XxvnkTZ>XY#uLHm*Z(!fN245v1(G+WE9m(a$mGD)NM7KXx!kUF%{0 zs6{N16%(jFdmN+IK3hd*H=WD>6HYX(R;>1xJ6UO*w(ueZ`fMKB4u53y-v2DG%-tu1 zux0b}9aLgtWJ?B?XZL5Cri^&Mt*rzC6+q%mBims@DwE3IR-f({;%u^&zv>jTKVJTe z{1lHna@YQ}ASeVwH#SN_D}VAO%@v=x=#z^jfv-gxJGSwvKAS@NXrLoDO)^3HU}%)3 zG@0KxK9Bpw=|_B4Lr9?6hLyoameE-LyM$Cq%awgBUHEzgv$Rx{)z6lNHnnoVo}Hte zm@Zv%V_(5FrwdHt%>lRRkzro3J}TYmnf07-KV!=FIZAP@F0a#w-@@&6>cw|RWXkN6 zJJtm)gx|#(E}Z^qcMO@*GFL0UtkP*cM&$jUSJEoPOreUE?N5)8d)m%In~OR=uGN|+ zg?Y8|TvN~ENMN$C{K=BPDj?I%j=EH`POB0i#gmv>o$Q@+i!}4ASLvcsB=$$;)CCJl z66NeuD6sj}x`f3oQt&)OhLg5emt|zA)bvtdpz?DHLXe0x7qUjNhu1Tg2h)*=%P&4O zs(g%CAsq@Bl>kLJlQLbA@-!-?MMwYR1t`+PjXQm`LZWy@=_xl9`9(lXLW84yYE@9A zcshb81~cJ|mi=cec-88ty0}~12<~rt5_YrAQTnT1y(fuj`2)~J$CvIK==_haerfy6 z`ebaMg-Ye^6C?-a777(`Gd=nglpOxc&4QG`Ja4%u>$n`4uQ$JHz4ohO*u11W0gUEQbPH@L6i}wVHQpVM2ApJM`Z9dL);lk z@IDW^Zm*zTo)mbhC~|=Ik@kz*7wGvUT=J54AOh@jr{GR-+MSA_*&57EvIVi(l~`PB>eB#WjjcRd^HFQJOLQm~n83VoMjYUDczfFHoyONlGUmSS zCx=I<+Z-&{#@|ZCRJ}D3)}b+<@_}$JcQME|sm#vqP0tzJDDWJMzVEQBt8Vu~?gM2% zy$h@bwxKmOSWY*-J3V@BaL}Cg!51cn5ahe~y&5n!n8?Kzw|4-IjtjUKvN}@(tMUyG zY9104wz+^Ky9H$vK!E!9y=);JH4p-1JhSi0qP=;M=kW$`HA)aDV&iPV8=1=K0W4~nM^wBa- z2-)x3|E&i9W1rZ?e>eh@AKoA9lTm+~k6m$ilMvIVu4OK${j8`y zVd290{x_*87pt!s3zz1U+iUTY50|ph`C-BDpD$J2Y=!FSS3%~k8UfQ@e&dSS694hU zOrmfA5oLo9>SzMD=t3Uz^wgIW z)BoNJ6}_>q57Nx@6U+aY&W`?&GMe;v32SMqVU$(()ukR0NLk48Ay2c?R}!lFWdS-yz4 ze&UhlLuK0QpUXRuXM^OGRh=n!uDyrp-=UEM3=>_9@RsTb${T+Sd3hmU{c^ zAj=!EBPZiez0F=pS-rMUqbXnd7BwN7mcVUDIt)*<8XK=JGNYciZUX~#p{bSu3ztmD zVt8F&zlzE)OxfS)!R3&0cAjSSW@;)~;@l8>9cG<6&BI!T0H|L zI_JB^ub`?fPeFn)gZ)#Fw_o8280?XUL(^Kc~Xl?iOCvsT(K6B=ZFj)UX-0qKe4Sk8pSYK5PLj9v0C&Z`v-akY?YvY z@9rqWyjQZkwPy~j+2F|+>h@PRh31_-LN7U!!%WV*sVC2NoBZ5M^i^6?!|q{S%S!E^`?NXWP;p3c>?cgSS<XI2sKb94=QEL}AzEy1?wa$ci+(;HAXA6qrTW= z((h(Kk_jkKo2SQ5bHA+ZEr)Lt&#+!_#5VPyp+OOfebq!)0#A( zU9T;m3!m!myr96l!~)2gR^-pd{RXV7PO{Qls5S9|Jsd9Y@F zM_&>QR~V+P>(KCXqMMa83fn^^Vq(OZ9!<1lSqSb)b(podW{iiliC`Hm7%bE;$xt29 zH^suZdacTbzbKh}j));#$1@wdsnQZ@`toM>Y$<-&0EF8-kXhbYDBR`iVF(gu-#o7x zMjami`P-*bg&yGSBI^If+g9A+O!g-1S=|2O#w1<}<4=qBsvKCMCSFmuJy!yQRTvmF zm4rk8$dfXmfZefEjZv21ufp3TaBJ^=XnHxYerwqLaUvr6CM@3D)pP?Brr(_F4L^7$ zbnaI`Tn4u=C>Rv{R_M5rB|j{IHCi`yxpeD|Rpj7hPX4-@7J{(`98WiXfT#_8?a{m( zqDQ2AC(bZrAYlj1B02sBPH?g8Kvq}eP2v+{;oQKj`49<4(}U}T?k$EwJ=Bn9qcBDC zFEY~SUa<;VA&p8JQm+N@?lLY0`+tJk00&Kd3foA5Z!n5ot-AAO%s6WK%0fL_Sh;_U zxs*I8*eTC~yA!_`6G%3+nFM1&$Dyoeh&)hJ;ISh}i_mku^MEt64P9iOxE~Z!;va#R z1_O({5xL)hv82;OX25-FWjVusU54ygWJ43|Z`lSi=qKZSvdW27m_Cw+u`)Ej8no~B9jO%A&_}oCEP66Z?^qr`@^ODkOhlof`(w9l*%XAQw>i0%d z{kSQBYDfd=%Ux+o@ktG5Zyo^Y$m5LUdfLITyJc=^2fSk0$~{0@AK{`k^9OF zEsVSvUDLgI?ZCI{1EXA7&ycNfq;93+`5S}yW$m^a=)gpGHJBwmY*mi6fE>}-!gqvR z&QvsUZ9GW}%B+7(w@D!pl+;|*(Eguz7?=h?4-WB^8FH}9QO4g6He5*+ ztB^8WvO}Yt8z=eH!QDBHp)HcbpV5KxQ$u*wHZisJPQs&K=eI8`HPmcbn4wV3XfvAZ z1xB4Q_dPrK#-RJGqZpj3Qr1CUm*t=I4&D3e|fKTzo}XE0KX*D0$nz-q}}bK;c(!_ z+%Tcr)4jUy5>t_}pGLDc+5GCiD(O~78#Y`wEvTE?fW&WX9+(V+6c!dH*xR!nl*&F~ z&&P%mkrwT6?HSyo@vQT`R;~Q7$8*_4PThh2&fOr3PkO-gpr0=cjW6M)N@i8Kvm$wM z%T9mhJx{hPO4byRD9cM$G5}vPo1_?lov=VUZ9~!B{y^pG*_ShwVo9dtvEGcR*Y3K? zbp3iAj6S_!2QT98k*( zV8tKLs&hz56rV1-8(s>((5%4Fsbp3z|55EIhuQ;G?^V&J>3y7$MhBti)902)11Ntb zp-`S#YoDs+5q5Ynr@q@5PthHZkR=|>M^dp<7IJr8{)m1wCkI-|*EQ0Rabmmj5xB<_XqGS>oGyl_kB)#sZ2Aj9ck z^-ai`q!`KF9Ro$Hk4;8kCC5AkQ`rwbkrnQOFUOkqFIqz&hpE9``B1ybJ zeB{uSQvWEv)9&|I!RS8-LMjaKmSZqDtMDb?JNpuzbJuUy+ zY(+HlEFt}{NFrejvD=VU3qdy$GWVMh4UYuj;MO)(5aG)=Ov&xPJ?H-yJNo}G4<&D6 zzdv7pll>%&0rCVE%hjK;hso9eFhB42r%$0F1W*BT3|r}+GF|t}UJiNaP0C7-FW=MU zI#~?#Zgir()mP#mMkxWLAa6K;5;7o8j>r!xfZ!kzGWS0!{(~lvvTS(YWSE_HtZ83r z5W@;bIg<8;*NmYmXp}FH0LI?+&R*HLTT)vqSoZYxzOA+8Pf{$r1!A^m;pE^T7+-%$ z{~l1bBW2hf!jmz8i0cd8(Go&{JkZA2T0uO1d3Qx#} zvom{z&Sz>Kt?OcB+V7j1Ej7FjyUI{%pe}lyrJ%-MMwX#`=^yF_6~*)M2`be7f*rs{ z4Q(jGV+}6PJzx0kmO1pyxW0d`mvn9{J^j~!^*ef2R0T-LHyym%H_D-lt5@SK^7O9^ zJyYZzniH>YWKUZablS%OQuD;$Ai8d?@O%3pxrS6$ec-(x<0GF1w9nN={8I%@+3rD! ztmn2Jk{(#g08U3=T9Yvlup3aM82q3oAyQ{QSwVR*!5sbWhpY9Bg#+bQM%^#IREGV9 zOalz8IkX5Ph#Lh8RLZEesQpb?x23ybzFWr{UiI^N6qQN-o&kA$3-iJlF);`8&XY)I_E7ddqb$r9Exq>YUMZ9io$vb_qu`9L9NvN%_C0vFhpW#EA zzEcZFaP*Iy7@xX-zKw#7J$|{~a&P?pbh+PZzn}fRdkWP&>)(5yT0cW@#S~W<@9N?` ze%17GTDmNMeKM`N*>hOUHT(cya(y6IIW*+uajQk%1}HW3qt$!4n*Nfa6fMlsq0 z29p(a%7kK?7Rt(6>vYvhs`8q z4CF$0>$muvUD$v(&5EIdRf>#3J9{{46W&D+)#K{6V)IjBVl!unHWRuu*02%IVU0l^ zyekujQQ(0$&Ot%mb*&IxN-DAWK@q;i>@Z1Cq)kT7=VF}2zee9^?pu5Na%wJnYe`YZ zjl(%syoc+i>}Tl-#cK1;K`&3Va|*-5omZx)&?4{Kvh=)Z2}7S`=a-(l}Y_3VcCbGi=HLLF$v;YS6nZug)| zb88Lj#pqOoBQ{2Se00rUhm=aMjDHn+nsbwzDSJMd3hMS+^D?kmNO*T8e*Z1mr`oI- zIoiH{B#S48#eo7NARqt?eP|mHA~N*Ai*A|})SdLI5SLcv$+kv-M2Z$@eCDlSN&!T* zxmv*>rndN<%Hd>bRp~eRLaq7W_&?w9_w@x?-T&4Y_`Ii^@tMQ+6Xgh+p95q*V2RDO z=X@sb6}5|Cxg(2`m$wJ7G@RKFPv&1fp9@;;-hZLEOx5-oeY82U4tp`fYS9w&n^q0Z zca+q*c#*+qBZ2|PT~muabK=sQ>#!SEK^4@>0MmZ*B6ndw_eXd-R3A#Ny)vx9>Vyd` z!`jiRppk6&LC6uWlsj5j@*5b5J`|aW!)@JASwRnUIj%5Pk#S1%!YcWkBYA^!xd!jf zZIa2awD&69gD%6>^u9E+%-ZkD9B5;Mb-vjQKF(L%h=lP`*RKit1eK0hlqz2B%Sw+? zol?=mO7Agq8V)4O7CGn~tQ85AIz$$=80-1Am?ouS~awP2x+ zIc6zl_s|{1jjQ)vynN+P`N{raSNvl8mbk6Ds2Gs2m8Evq?9VJrYYYKTLU^j~xaOR$ zcltQ$_P73^PG<}%rCEm32oyCev1IiLOnN`y5N?HBdp+c%h{rnnz<<+@siAbOdjpc;%syz#m@o`U)2gxr@hFIOn? zHHtZbdF$W;Ts4Up)>5`Zz;S6vlI(tK1AGBk`4#@)s`UrHkD5)iRn0f&j}p(v-Nd!n zYVXh1lq*sBr(-F(Z)WDScfMg_*)TPR(j^0uMM7@)i>rlVdhUjqKDZvH#i~v-eb%7l)qmNHW<@ zmkU*ixIev{Bg1Dy9fw;ht!~Lly_53Y4pTvhsG9$|IHJl_6p{-Dm23w*X*!<2YNX-} z&CqT=TsDQzGL9xSc|8Z?kyDI>+Dj_YS>OV%)^ERCDNOt|hOj!wdWgwp@S>Ko#L=)E ztl4lmU>=CA-cOC*EPHZ`wJbPXwxXN!`Y~yC&VhLMCtp^ULY)kn=e@fTeW190Z-g3C z)2N&8XYiC}VegVAjP|P0`o+66(~GgAX5NcmBZ9#SLNGofZfh|{n4h1H2C;t(6!;Grr= z#4Ye)Rvu9bG2@qs8ZgYJr30k85Eg2cdYz0}vEGyT3%-=<-es?lMI{g;XKLCZDy_A5 zbOzxUdHDjAfxXiG1}j6n94n+$g{my*K;bWf0I2%io=9ZZ2U`VGb_tk zE0!I%lU%M0C610>Ui1{!Af&&~)>H=B7lmS7sRncta=n~z##3+wleGEG#j8)aEg3>Q zE=6+`pJvRRYN@tRl;qNK?d=1Fj%)?*ct0M-@yVAQ0a$A$D!-AhtT4htvRZOq;4|nO zf*n2J<%d7H;0d(U_}B4hn!e=`u_s7F0catVDx^aA=Q*Dro)*tzm^k8$D_wJU0SKJt^DJ8po z(VtHv(z7~pC7K){%h#ZCrtthDVwa3gr^srSbywpH?613l$`krdHj7y)!IQ#j$h8^5JX`7KG96@c4_OC`aQOK6r13e2+OH^8HmaQg|9<5gdlMNruk# zYAGemx%?eyOL8@41uG=pQ&+9P2?Poj3ya9c<9-H+!T_MyRnNm?`94u{cs;!X{G*`` zHFb-=0hN4M5fWV%1M5y;9Y=6t^AT0_&*dEN&8&KTna>dV2I|b2*uDX6G*Jh zenrCVPK>35rQZUP;<>#ZvwfSBcWLgecg4HmID@3tZ1wHmC(29YiLRcZ>anv(uXW&@ z=SvnSmCR{O)Tbk~mBXJoZ^k6dyBZkxApQIBte!3PFR>5vebOTDTU*C=af=F#J>V{i z7ljQaGL~)ktS{WAOQ@qUswf12BH8Kx3mwz4sgDgu5P z>F#*6h`?2V8%3PyV#FW> zq2JyPnh_e!Efl<+8){&eS0UG|hN&d!b#tIN!t=>osxX4u+i&Pr-V2UcT^mpZqJKr2 z(vj#m>H9;SD;0o}O|G>BD~WJB%P8sk4XP)T=JyMkcVuVl^G4vFs4Zre@e3&14QziO z%+vl*le`^WQP8Io{`{E-yus4ak+^z;-Y)^w;^`CP+Vv{P_54LJOG?+>G^h^%2xrG` z$4r&>>+e4JUh8--EuP|n+u7dOz(&#y=p+$ElnBz7z*IhonvGk>GLIc)zX%UT2NJhG54Vn=_qA6-JUHTh@t?7e6IA1I1x%X{|2v5hS0G%-j*6di zS637#xHS&^)c}6`EQibl@md;*7u!OyUs-4(CJyO?o}SIc#2lU zs!z6)XMByM83^;JRsCg?J<2j*8M=B3yWZz6rvpwIHAn_{6UF7p&qPeD2(W-BQE>F$hl6BKtDbKL-0&v2MRW zh;mz98jgyXymA%z$h{-sGXMZg`9J>!7@9HX@zAQl69-?h5^WuO-rbJA#4Ao^u`JWOQ)M83c5YWU z3O34)$?-QnZf4<<1_b|;1C7*Xgbp6JKOF^mDHMF**n>w|sbzPfIGhJO+e%94EH2f4 z@4=uFg9jzJPgv-|0cZ6yab1hBh1tz+*HN4*J65M8g5K!B(~VLZo>^NokQUmPM=eN# z$A+m@zT=f)klPhz_-B-d0`2~S26`@Qui=uAb43&HBNo#BXYQLV$W{&y6pO9qj_WOC z`c9EAMMoVrhk|J30+-#c*Z&GM1k3w9TA)Qj_B^EiUt1=vs4QNM53a}IK64P%4WHxV zP5IdTWi;kbOM(Iw0+YvMwDJq&=d6WcaTa{szj`1LDzA(IxUPJGqg6Gi zIsQ-lt#CcwtqjM)EpOm4W2Xzo*8kvN`@cfq{dU~*&7*_o@!m_nLB+QgVRd2?D$2^* zpO7#p@?Jy^lAuqYhneOH`2B)Kh+mtH*sCR2k^cz{nSa6eLscG(0o3g%z*}dABPqrR zU&mLdD0vfkJ7tV{WfCGK71X9^#F#pNZk5nWD##`)qKv)(Y#9IWV66SaQY=fz!;JU< z)PMFTEPv-LOw%60y$T==nTntOFb|op&c*XlYmhnY9R9p?9Zp8i!G<&);OTnxNQ2}j zvyreV4@>8bf&UUaRQp~=?gui`H%`Y0wF=Ud#du;>2J)YH24OFJ7y6^?v84D09)5ie zM%_k}Wxw&bh(xlrZWmvgoWLOg3e}1~2gl9gA8T7lwy^fYmCUr88KhOH4KmX{eI-Av z?bzz=DBP&%7ZFRV!H*hkFh`7=!;PPIwEehmV{%=7#|);tt`_wbOgu#Y&$RZ z+AHMZ<$bU5$D<<{=p$414P(rtbu4%GUPNl!td+++qfs$ zSh0o6rrBu;^`)#<=o=ErgzqfpE_ZDqT{wCCcQa^@3ZtJQQPKp^WE;=9zdgu~m)>fv z9jABj#VJV~9;BsOB~jK5qRE=X35&M!jGH2oCx6S$*QgD&#zkt=n!#Eh`iCcR`YU^H9%EgH8hAyd+e)B)cZ(iRVL<4X zbbHVrK`IEI=#SXE8%~nD<0Wi)G8Hd;(&F}M<^JbUQuH{6^w$>3K%bu=2wrh_CQvw0 zfA%D*s@xZoG{!4#+M@2Hfj&P$5WL|IB~X84ZEHrBw}w+0kzH~f+1?t@+XnjlzCli0 zh2xG@{XGpqxa)|ENI?*UKI-)hRNUTJa7V<2Ab5~K#jTA6cSKwWLJtWvB_-vK-d|Y| z1mSKY_CN(e5c)_YP(cucJ`xF35Cox*L;@8ALFglqKm|b%`sjZM)<)5;rm?920000< KMNUMnLSTZNm!rV| diff --git a/localization/autoware_ekf_localizer/media/ekf_dynamics.png b/localization/autoware_ekf_localizer/media/ekf_dynamics.png deleted file mode 100644 index 63c81261a718e8c4dcc4e9ed6283aa6e9a2bf56d..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 5346 zcma)AcT^MWw?*k79g$u`2)$l98E+h!jy9E$IdM5-$dK08X ziGXwv5CJLiMepyub?^Jj(vXml&_N7!%}GcubCHl- zav>uno_Y9Wg_5|FF*CN*`}OM=@$mouk^WTtkjQ2THiue}=(c|waTToklyhH>(K69# zn)M11qV_km4k96;@B96|^hBJV7?@Q9qN{Bgn!i&J<;~q6(!ch;UFe(A6zEknf#0HC z)C?ftGw_0jL!+&dhdfoML@|kAf#XozWEBnb!~uLWj@IQ83yNi|u~g>&%9U^#_+omgC_Xfp2< zM-5*oV(R4oy7685BDEP56}-?}ebKqtWTy_di4Y8a7q7G25vp;_HnbgS!P3y>2tO8B0F3D`R$B~@UDbjo*zD@ zg8l~jen*m_k`F`r4}TD3=7!GJgnd}Ny~G{s*OIAlvd@&x6jQ>4eP(RHP~R%Mc`a$r z+U*yf`%-_O+xu^Q?^a`^6VuvL2_NSp%WmaxCTzqFzAItsb z;;Rve(s<+l_~W_QNe=e7_T1Uv6!>7x)-^4vkdHP3YunmEpTebuh}dkCZGoOwTqNR@$bS@ zB>luo2U;aQy;bdq^Ezs@q+T7Tu@Ao80PObOdzi`A5EI~U;Kqw>kTEx!p7Ys#;c*@r zIii_A>Ns^u<(Ds%+|neU&C~oS@!sxES4F41*6|RVrf)}H4$`irZ&NMFJy5Eir8)w` z{!Su)VH5n;w2rMw&MNYLv0ySj?W^^bsqv~_3$QmcPSNvQ=9I;`S&b?5VSLt!ORf#{&0(1^AouR)KaqaHSR)l**a z^GIio%9jexnb8knXA*9^D8Y6`_+iiMWt*lRA47H8q2o8~sMP4z%Y5wUn?I2@XYqrp z)&p|Vq9;u9y9i~ir-dBpL*01cd(p%5lOKw|W)V8_uBpUiry7|=Qd~Gg8y5BaIjZcN z^g^J9mS-U87FPEDQu+ptI=oCaPsOb*7t7j)A2*#*AW4S%{nmtLSH%ICQU6f*mG)cr z4y81v@BADlsR+LgweV{_n*tSCjCm~l`uH|kFT?1I+)kTh`zZC30K;l+rr+2DR7N(t)DCB&xAxaIIn`-c3o7ESYPI@| z{Z3~7IovzCq`rE&p(%R$jjN9<+V#1gjcR8v&!p~|R~CcZDwV>j%)-&98`n!JjRJF3 z%IZ@%ocrmH_#8Nqrm~q!lW~pG^YvT#WueNZvTNSy$B=*O}OHK7@SN-Lo-~ zALgRCi6Fap?dbz15Q9(9p`3U(L8aOD037{e;+D!t$1^u^5jKPjv}aGSFsku+-^0As zL-&!IULLcltKQ8sJwCpXq-VMj@fz=i_GipxmWH*TcQe#aNqoA~`DK${SUJ@#;B6?P zKxGkqEngA7Qd>b7FI+8kZ}7{~lOOPZtxh2#ydK$Uea?uxiTIk!J*`s0dDz5M4f4W! zd^VqvlHCVwJjVgM3HMI$Zx>l(S)_tPpGOs|arE$fHBfr%oG|4-{d6D#RMy&7mY{=^ zeVEHN+a!N&R<7$3L)g4YZB$}TK~(NXe_E}qQdN;ma(MO5EGhPdZ7jShyaaCCaO*tK z*LvA+WOG`z$wvKc*VboiZqdE@ZS9-IsdYz_LDlEl#Abx8y(+8qFb%p=@bsSJ@+|7( z(V-LyW1g5(h4BjXMbDL~idZ5>-za-ATzTnMVu_yD^(Z`kMlG9$DL!Ltxj_5NhMDkj z{YsxYrPeyHQ-be>fC47|H^D6G7;tu5s^YbP@hzCvO{32n2)PK>U<@DjN&+X`G{KXh)u0qg7cLtt( z3Y`c&Z{$g^IJF;rxA+|!g<0T@pS+V68I#xM3^M*ca4W;+D>j4 zZS@HDlp{PFc6OV05E*NpTeGrLrPlwVGOjwhzcb>cxfTQVIB!X?R!!fpN5*a^Y_KB# znc7s-bD^}Gx2Ua2xfbnP(QC0rZcWuly6v=?klQ#{=>b2@O;HoL;tHfsrBYBpw3cu& zP2v#ekuT<(RMoTVK3tEZKZ`$Kr7fHccC(GFT;aZzk<6N=a{WaxER^_$5xA~-qu>*i9uF9Tc7c}b!rP%jIKPD9UhS5qq zS9xU99$j{q^zmp|vQXWkHM5S<{--3l zTD#m>XHF(+VB)BGS%@#8M<0Ch4$mLEr}&bEOq=mvTZXUUU>^-6#}LheUcAgMH@_$vgbR37 zZd~f$e+ea**uz5!83bI0a|1+KzU?v&3jaEI=cAtY(~n@9-MKdnjAVSANgcSpPE#IS zx+OU@+QL=Wt`le1w08TB)CRt$wCUMjW8o*(xJp)ZCbj;l_a(wdHCr@?L*Hr|u9LB? zbPlL&(YhjpPrDX2Z@{;P)sz}_&XCjoJSXW}*99!=vmSMM#FVE7bzVoga-EobWfq_@ z8~5Gd^eVS1H%@PVuY3$1(AwRjIO|k<(HcT=|x#wyb(Uv8$Rph(I@h$uv9Sd%<<^2 zZ<4DtytH*{AHa_<*_#aOmEy-W&tr3#2#G0xOK>uPFbxngh zKma6%eL~l^iat?Gg$2R%_PzM!B`Gf>cZ=3Of68!$BvL(FbKuhxh`U^#A`f#^Adp5# z^(cfg-gTL!X*@m<(yg|Hl5;$*HGlM@vRr4$&#SmMA?*`SsXnjM(Rf>6Vys$ieaD44 z&=}63$PGdE73C-Xhw!-;K`iU^6H|63HH#`$=@&y)0AaEo(zeqI{8u zn4!$YOOnxW6n$d%XsJx8Gu(hwtVIq+>m!zZ*e*ouNCCZsdG;6njr5ZsWH0fJlAW`{ zx4OjSD=HG+Cjcvze?YEI&XE;tc;2exsQV=i;?6Ux^bb5Jjp3EFBT^y6@O&^wnX}FT zPKh&Q6(}<&CZMZanzR+q+4d*Q@XY2hffJ<|Vi-P@qs&p~1UG=FS%Wn=L>o$M5AYZB zZjqPL-~@@Yx3HaMmVLttE6(iOKN5(SoRH$+5s4?Yb4q(j^ zJVMDtw$e`mk%I}27)L!xxi!}L#MyG=XRmwb>Eey8k$u@}mioar)_9yn!M~lTae#d6 zzTS+$zOY-VoE+6yi8ETRbq64xeCGC>ou4@Pp1%W`W;D2R`12sUfPledM>7Qh*vp>tEPFGMtf6QfKrv}0<158Ha%8gx!Gs;gD^RJD$H;RwYKCTFc zhyaql;Xqn*bRJk_aEv%M+XVFS&Ya8a>$nI*kruh|xwz~a*{0o&i2?bpau!<-ly|RY zQ2lC@FU7lTB3}n(A~S#~M0H69Ywimd;C(%m-%tZ3PwwcSNnI;CK|}pvhHt3PHgxnp za5qSW<4sjDPXq>l>h1V8XeuERi8i~Cj0*Ve-;>qVx+<%gg>(~0&hnAtCi!5i63xfMg^R=Bm zZ=xb4mISN@lP(#lYI6us$K7(j9u5%!2?3&s8bG4R2PV{YDg*_K{Ur4!6@)(y9GggN z$#o_tq5nCIkCTSP#4@z%2zt=a=>Um8|9Wcu{SeC#JTNU%Mv-w*mmIp~X7i0dSnvVF zL&?raOKUS2=LH(oO5bEK#!>a``2b=&JcELV6`8?M;X&s5)HoUDXctpfqHQRQe(w#4 zYot1S_1jBTDT%iGGj|t}aXe%338}N`qUR_i;BHg3XM}X6OxLyMP0R=qbM^I1) zBFU(48>Tyu|F8Fkf0!Ff;}cgSZRwjG)tQAL{BS?V$8|KmrF=CRy8dl8xR?SP-f3X| zRnBluhzz`5cJ}&W>$+r1Jvi1>Xh2vVtM7<)JGw!-iunZP|FS915)JUnbi&_#X$zi&^PjYkvgAlMGh5wjrwk zwo&5nD04tWg?C&w(EiNe5)8)B^TC6CDk%UKq;SXu(YOgx;O0+^2eER}r|asl($G;F zmI}}y;zO2N`*~4{N6C@C0nF{a%i0gL*!hjtYsCJYFF*k3s&{kw{Z7in@oq*NMoz28^3Bp! zkK-qxlLPj$ru7yAtem**@`NQ;ZY?@wh6%BCm=S2w``+rOn8`F~Epfbk@0;ts8e+JW z570K@C$2_$1*`#_^g^Ju!@t;wwG!DUOx*9*zJ#jLmW<~L?0(L9n)e(VNhF*Gx2Zmg$A$A+IU7n_6^KE%(pjE^{ltaG+GY4%;)Ga9)gL?j- ryU|P00BXQ{9_I3K{($eI3g=p#){#rCKmoDee^WyApt?0+hnW8YJM!+Q diff --git a/localization/autoware_ekf_localizer/media/ekf_flowchart.png b/localization/autoware_ekf_localizer/media/ekf_flowchart.png deleted file mode 100644 index 0a80cb06b85f00cce2b295834a9c2fe94c727f2b..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 146302 zcmeFZcT|&0*e@ElTSbwwML?yAQj{vvK|n!7ML?H9@IT zLk$pmmrz1)A<3D*{=Re1z5m>G&$;WYv(`6@CGpL??>qC%(|*5shTxaV3KW-aT!KI# z6wjVMeg%PC{2Kx}e}U{TaHTrlK@9vl>n!{1H5nP%*o?|F`0sTWc}*8Jdovd|Lnl*+ zxt+bODX+7!lc}klvxU72_H2VR1acGd?D3=5?un}tzTPM({D3$tCRZ%btE4~~(P5@( zV|D-A^=l4^ZQ&1HojTPhr83oUSF+eGIN4X!EUGTAGDfc^L{810{ocCz_+g9VRl24w zijHp_o{ob?=R3|_t{!Yb`05&`+uWmeFW+C^Pw=fTV!`ew(~H(jv@&}&OlsNM+MWR; z1#LD*W$^6j$De7p0#C0}>lj@-y;jQpUzh$%5+n)ymrnejZwd|;6(|)cUT)Cxu^VH_ z>+6rY_mzIPcaU0ckrK;Sf#f)GF6Y)q8oYK=cg%sOgLqyMxO`#(ej`_!AP_Rc<;o97 zW~QJ~+2=Gr*@j&?hHh16;-I&$GCgBx3W;D%5LmO zVP@t+nCRq3PdebUmRSfhEKbg(w!OWbk$i4em`w1c8lO}fCEj%qkhG2#fLrXn>o zGE!~U9WOfNEr@Z1K>o-pi!XdFD=V963ZlAxpAE+ zr0%hDp2&3v)!Ic9wryW$b-bZ=VPR>fyQ7`uwS-fn`qa1KZ|J$-sH5C$lK4z_nP6iB zaprUe!uPZg=~2cg#k_ zi^RQ$K6y}kPD_1p?2nba9)4>U4)ceET=VdFhlL6)#YnGQpJgbt+#a5nmySo?)f)!|L(M0=)rbD{hszwRb@mh=joWU+><8MxFV9ML=D2@@waTjus_u zdSp_S#a?91kbIES*Tt5BJZn3hy}gZrNGtuZk@_E{c7(3$OB46qCU-&_?UH!1@x}p4 zxk}5>%3*yW$Gri2pMsrMlevEI<59k(QtWdO^Tor9ajIWz#hE6%+Y$}`nW^)tJ$ofe zWtboKc5#P1s|)6Ebl^rAWp~`uoR?rdh3e2A$Xzrsb}n<&T3fZB5+Ur>I5$+c(c38T zArAB6v4g@`=A~EN?dsqMTDjl-&9SAR#!Wqz?XQU{%YiIOZ2k7(QVQ0cd{3J(Vcd^Lv-(ALFf$p)2HL*+Sip~RNHO{d@nc8wk zaUN0jIXO9nqdFlS%)$$OZFz2NOL}fYtLC!5`3mZd*XIpc{i)AWPARlm+Sael=8e6{ zk|Rs=b!=gerZr^`@DNWk^(iYY+WXR?l-pas`XkSmrNU@)KGM!RD&hC~NAF$1;zR-5 z@=Hy9En&OY?d=|{(Kfmg_Urv768?*s16;*Cx~e*A^|)WlS#i;{YOz_eWUQ)UTam%) z8A0^)Y_gq4Sw}6-OFVW~&qVp*g;u(reP!2a>!5{$8N%wKLmWDCzk9gFi}SYLm(4aF zC!&;A43tH9@(cB1USvmw+UFJAwa|4qT=)IlT{)a6v-u9Z_OqU*>t=IaAA1YuLeOic z?zzyV?qbC(wXl7qf{|+DmL}mA#4l{}QnHubVpp8b51aM}UF&1}jgBly4t))KQkWcz z3uhsz`@fMgd@{spwe$28{KU5hE}BCdgAt3}qt!F^to}@ru3g^*GV=2B%F6Cz1XwAL zb*@AFe4hG$rev)&LC?pEs(UY#)>OT@>gr8@*m5_jLC|oJ0-8(xN^y}_Q$w)Eg5SJ@ z`_MuDnMEEpMclL})sU8U32GfUm?3C(EX^cK=0Q6U%Uf$Yvc6{1QL$q7CP@^!+4@;q z#Ah)w9>3;GukBe05m>yOby1v)_phI13c#%zHYr?Y zkT&|&v>nT%eNEQF+8VbR;d|W5VDF7lO9}B5`m=fJLDA7B{VS0(vs%s#2%U@Mtp1PN zzu#5oG@a}#Nq4lbs`nI)>^5}w(0Zn7xXG@Tb=k{&<$0ojX~#kf@S5m)i}nz_B$O-q znyAlu>{O|sq5fzrHbq+EA6c@(_8MophTUJ;t}4S+c3^B5Y<%+m)Oo8 z6f%FZ)~d(SU;Xv2$Z>bE;fF7YReu{yVgK|^EK=*R>)EtPDomUpV_JFvx?o1N#J8zeK+ z-wr!RAPe;vWXTMlb`N$+PWj)*M#k?k*SKz`t0y4>s>VH*l5$_;h_{7@U*y%#NBJBb znEwMD{^$MydAI27Ti~;U678Vv(m&|jQDV~hgKc=NhPp}+jOy7pk8?b-FrXxqjYHuR1rQwxm9+7t~iJr9V zN1O?D(8)PhMg z|63~F3t*mJ-r%T^(7J;~fxa*u7beEstQO}*6koo*g?5yUa;A3wj2`yVw>w-D&Yg{} zoU~LOlwpOe6-5R_C$a!me-|g)``bpFpJ(0dv<_nGXVYh?<7LU(p(_KdY_eo&-xsqw zMu&jGvDP?Xa%Qz?={3R|-g>v3%jmdN7k_hNM;8~XXk(Ko$r(LxIOfWxgXZs1l&<0s zyyJzgab8N7552!ab(tIIzQEqs1JIk7W5;xQeo@>GT+1zhny^>ZfIk{;kjB=pPdHs4 z`2a%6!~J=-+B*V43bo7ctT`uz>Po%nU#|td3pmt+56XOrC1YiheVYBlEctn%JWe84~$>8oSWl({pJm< z`e03q2X1MMgW7eIXX{luOr@ClI9q9W%_Swf&jzoJRRvLpOJH*HiwQ7a|Xn> zuf7{{rn}rX7+@^2IfaExQl2iZKUkKV-jyibfn`9jc_r)mydovR>n05xvkdzZQG_ZoW8dEzPd`^hCjnsD(YM58A!rfADqU^|o z%b)sH{-P3t!PEx6jZRl}9JW!!ud%lq7+Cxjx-D3m&6(o8#qWElXojB=AYNVOfk1lo zdiZxsQC4QKBX$3*VRbhl|_|@kfE^ z>q843q|CGczKkASiw#k$EmAE>aP2PoIYS|G@jk@pn@s{jp6G{W( z3pMB1wsL!r@LQP)*c^Pc;5-BI!*9JSM;nh=7sG#eY%f{_y<>h(0tioIm9c1-5?|Po zp{4QKc)*4D5RsxBui9;mS1KYxrbe2oTFXV9b^32w_V+m`>s5$a@{bJt)PG)to!=dtO~~$Eu`rbE*R%5) z$wjq#$mFaPun8l5OdJ;v8@IVSTqkTq1!~Lk?)XzTwxUO!Ba@QLJP4~TaURNfdD6u` zIxV$2NPecTQO;XAmJQ2gI+-GsOO?ljwXyqwRO;%K?e%X&S9)4|B3_6p%h$`z5a? zOO=T^LkF=-J=%wR%wLsJllNe=XC=904Ade$ke%)GFg>;*nNkA6y4YtvDTnj=)dkJp(Ofdv}S8$bC(RIbwx}qM#UxNE*>vy}C zd(lGH{gvA&*ZW4ELtV?;03dz7lPgwSf*)P|qGq4h)k(?vouNUn)U1b@r6|*KPngD> zAf2SIVNfMAH(w?9WNK#NMM)4#=x;vV8Xv%>)sdQ z=dq?_)$_&q=k3x2QH_^c;!}g&l=)UL2?Ja4@qL2Xe2PIXb6ufauS9iqwDiAOD6wk{ z4M~f6Z3-^WDlYZZ3crB8byZU&<3}dBs*P5JhSGcp)VSQeGW*H?neIIgCnr=FW`<(h zIoeYBXl(SrPKMe=RA&ZBu2 z4Ia<$KL`shWUNI|a!jSMM;w~9fjox0@fid%4LO!`#mU6z1FUDk`L9tqd`V77{$Zi6{JYQmskgYWc}b3kzh~b+emYN^tg5OilB3g9kwqhCy(m3e@+Z7K zdMWxU07t3)N5xQPe>UkXW{1W*UR!RTI`ZJ%)LKL&R+^bnf#oU|@lY>Yc4r_j4 zAur}SSaraw+%xQr4h6{zUveGdhv(GT-To-s$$F3e@6Y0Pc@6MSHgmCIuFL@A^H+IW zc5rvE$dSeBxsD!e&SfxP@MPBb|H>jqGwp(*P`|6^rdzANg<%E%@smT6LL8|z#{l<4 zY7cElUX|4TXD|IstFS})8<#mnbaY5@Wgn%v3=Tjb@Nm+L82^FcR}As&2FH>$P<-=G)Ae3dRITyePK+Fwe5arV>x#@q;tn1s>Nz38kz6T`yyUhD=YoRlCX>l?9x}e$4pFVkcc~zCaf7YpKLcMI;v#4ds z4$avn4>7IsZa$`He(ftuCK@4zke_KcNupIqw;lVzt5s&w9?5?80wtrU-T23UZl9-Q zytexi!ua{|j22OMWGHlbYPi^mMF2AWl0@bC-9`seFfe;>{JOy6T~blu0^siLC!c-#yh-tv#zRDgAXL848>*lufT+HL|sQhPX8mK zyY8EH0db+a zJ>|NfLfNTs7UFr~M7N|O6GF}~as)T`t>q7{@UnhSfQjW|0&A4&CYHF9JZqMNV-u1O zMpv=jNz%TPyi4=)_wPU+E|G+vYVNEi;3voZCCY+$raycqd|pmNupEbck3ikvihf!XL}!w zA9uxi6MN-$Eg^pTPeJMdF=|w5flwBrcFJX{_tH|>RK(mmM2XI5PNXNddnU|lEIL*h zC+|$gTA*`pJ58t6_lE@wr(&YI4_=G40wpczJc*%}eVXWC*R5p0C2lfs76Ok2I!P@@ zVkSRONnhK&TH-5WGvZL9T={?3rNhI+3oBg^xT>qsFxPHA3%_!rq|aufP7j9oqiR0M zs}nw@DR7Kw$)%R<3^5>z?2g{jVgC!Fa0xKKHv<8E`=v(uyk~iMLI{)Z@un*BFKYTx z_Tg@K^NXEghO!Id!7U9>gQ)wF(ovVwRvnP%A-w_8s#HKH9LRQ8hOrd`%AuZ@{JuR+ zRNG$uN3T9cL-+LvV!Xl;KNC*|c{`hbCGP0# zYzt?q18H0|w+3^w;MpDRfQ5{ZT5kd3$oSsSN@0-c4T#_RKR`o`a#B+tUe4f@xFcY* zG5rf5a9~R>?CjPNQxrd8PZM8OS4qBGI1s0SI6U4`0$Y027tWnKx3I7<*BZtk=J0l~ z9MY`edJA(A^x_EF|ggoYTF{bmmy*nq*p^Ax1z2&Dy}tpNqZTNUi1k5%yh*gKn{7G zSZu6#MV0D2r1{Ak9UYxPLC}>^HbK-rS;+F0nNO!igQ_>iDJSqYSVJ;BqTloFqD$M3qBeTj;qS!3&!BZZoW zUAxNz=F>ml#qGxMCS))HW!Y2I(HUEO%~dYFH)0H~c-|qc{l^9xWii(BkuohH`&3TL z(b`H7R?B-jJ40Qs{YfK<`zGNMIk_NdcLDl^5-1dI$##n%9x;@E<9=v;ef?axBp=!^HRwbg4?u?2+0k){wZdlN=or0}&J5O|Hh(6UQ!tbY zw(+4)`7bGwzkoDPr9S!~0dw6L={I;R2?pq*)`az~5|8dEAR$Nqm68=t)Hwib33bi3 zb7J%u0R;F`Tv@rRuuZTx^Vw?WjQ#rcu_Vhy{fu;w3f}m8241&l8oE>_;phM-e}qeEyQYR zW*pSga#_nfiFWNlZ^ntJ?FE1f0y{S5C~LybPQ5tM;QJhS&Qd)1AJsZe-)y46mxzSz zl>@vkm2_gaw}$oHChle@MrslB)_vCxi{nUnY{hNBIjqB~oLYQ)j^CI~fUyz}B8b<3 z=~vu-q!K%XLecF4kwAh}xT25H!w3?Q!n?fzms74g78K@8@_t^S1|G3zI|kbuNIBkG z3YADcY@|nQ{Gx*0Yy5JP`6QkUkCvHscEt&%08S~~JTO8Gcbh((Wec&dAVv#P2~>Wu z-SLpI;tI2lFr$SESpSn+fFn?q~BzITACrq-h4qelfeuSsw~;epNt5?9|alDK6!d3=%6Za@|&!r z%mO}P93cfJOK@olq&V3Q!$NoZ6e4a2Vv!dJ1tEvXmM#tL5dRcbByF;A&`1*w+X0*nE({?8Vo?Je}n_jk)WOKRFXb@ zbpYsp z&$CQP*$`+7wE$t5n3}F_+w#MAUMVXpYZNCtb=<9~sks2<1KV#TBm!V&&^dBCAz@+A zjY?{#S6?5FMc^nWA44D$rU~F*5RDB1n!#>e27tyv>l%dm;_1Tr+~MbsI0io9!jluV zc}prInCfl;MCUF8s8o2Acma}%J57T2)+Th(3uX5pH)TnF7zE}w`udZ_1`TH=_a>&C zE<>jMPEn^z=R4uT_wV2L_xFF0z6^ON`k$9u?s>8O1?eM&XrQ1m>FMd98(zw4yxK7c zJk!ta-*1ZWygDB)P%(=+OtaoN4@s3g9YL+N@BV`aB}uerAe6UGC$N44M5|}dp6yTZ z1NZ#pUvW@PV0BKRo78vkuGJ_~6a-Y>AA)i)t}gr5f8az&32DA{&W@T5Fnnt`lh?Jy zGmsI<(?{b6k`xiTbmt+Atp5r?#lyn`blf8(uTN=%`F=hf?ufmYy&j18nVFeEwqO=; z60-&t#ojBzaGi9&_`mn-026)m=#fS-`u0B{3qG|;#*dD3t0ciJQg#0Z$c8^5 zr{jGGRtLLtNX}osaZlwhND2L^+%Fh`M2nrB-Aj5(o$V~-qyK5|GwAKfxBmiG6EF;XWQcgIZ-gf!1QISr%6}F$vS0^IER;8dEJjKUK|JTa zd$+x3Z@~TIrv?}pISw^AC}clbzm(z&?{&BZlK^0O- zA52HGD@tz$t9)XXl4xX2b30iUi7GIQAQqT=O9(9}X=GAKc91n}UpD`m>}Y1Wd_6cZ zk*p2S{vRV#e05<2$ChkLapG~d{mL-@Q)--+fW7-1i6KUh57l`wzg~TTk~q?RqBrg@UG-0KySQ8E^hup>;+i;Wnh)%vbo8O;VRaGv*-=92M#Co_0 zkE%jc0{$l4JX~`9AVLE__S;z|F*=%d<}J{s$8C&WtL9ckhp~<{1T2;B#;TxF948U1 z?v&?BVah=>Cl@z&1{0O%S&|h`^ETinuHRUPEJmIi4J`V1XJ&+jPMXwpj@66 zk2nc)VFrYb0bgDG?}$bG!b0qQ6~aNA458D2aNn~3`>KshevsU61ClDb${e<8jlg6va12O>_QA18Z~B(d=QNw8Mc8U9IvTjM$i5j|jd)6*CryX-uE;_8yL?_d%9LbA`^XtDPK zH-o6%C)ax)1xT~H>Aj*e<$1i>CdvH9fUulTOlb#35az%J!ujf|^OH&MmEj0U#LaC7 z;Ko6**EXovy0-TE6kYe`S5{VbCyH-_vIFDAnbNk!iLIexjpOZx$C4l)FLmp0&-Pwp zn0kQkqB3FrQBmQI8=IOeGgYimd&EOB^M}PEz$mhlJ-N#HxL{a~Y~S*OK~}I+3`)cL z_(k_a)riK8ZPLje2blcgopgGhfU1Eegn~maC`{(MNqy+LMgw&gJXGhVzg53SN}<*3JW21 zcMnQTgt6dgSmg(sR-XaJ`DLeBA{|E(QWHaCu3V?XcIik2ViaxnA|5-j+@~VS1 zd*1}*Y&p^z9L{IP$^*axaam6MvP8+p)l=XLrl}x#dB=t18GCgAETf5&2QI6A$-mJ8 zghD@f{=rg&2^~^uf1H%L0v*I$f!fxt#a)R7f2QCCsAWuMlWu>r?&|@je zowp~CFthFZo=}X-x;Q=8rr7m2~wo+)1PVQOzGlLzOMT1_UpQgMjS|qOs`;KC3m3h6at=`dlzsIOC&Gsci=S> zK>sTDwV4m9WTuZ2#J~xmKg~4c=MkLcKh$n9-Xo3wV*>~YtmR@N{Pqs2juqg(hx-&P zj;>~NNNPY@KqLH7!TfnTgO*vYER9VCt_5L%Vh&G%+&?09F4&x*fbU<)_4HnHy;x{_ zVS2Sz^=igTN{RUo%=}X_Jt8pM-_&AbGl$1bZ8&cjLfSm4%~jvaSK8;*hpZIKcc@n+ zt%@sN{_ufD`A^~`u-INMC7EAftiteTsrdi=`m8Bf#$g^(55^g-zW3 zhcf&=kk)VSWI&2Ol#EVFnqZ|<3`>9&oYR&Emmnt9AW{HN>Xo~>E*b~)#Wii2zxJ!4 zgTq&ns|p;$3(RS0X<5DiMAC(s5#tCYib~SNtEl_3p88+dYutUOFg9oGTBp*ZI+wht|rF$bJK5G+@rW%K}7WXOb;Ry7vNm zybR%coR=3{nuaIOuIKHU=@ttbI`@8ge z(*75K82X=)X4$*m@+2Cum13NL4Tua@;+LuW!&%Op3@@pb21Q&_;%glYM>5-3<2ePP zxip$i?s_q-1Eag`LV56agRf^GHwUUoWhxJ!bcXNqFp6(ZawZ?{-oAaqTyiKzsjlIE zVJPg zIcCpBKaCY%6Ryv(pNf)jT^TGLdj<~)(sfy&*#D}5g8LR;9pXub4n*I+Kq;1MT&1iv zK`0vbW2M*g7%OO5nY16y%4u_BG?<)i4aNkNH@FUss8H}o!-w0G%4?HGtbdBrhc(P3 zZ_$E1sha7KaPc7j^zhdJ(CGw4r`xu(!ei9VWYF;xR%C1 zP_|H5td(*Z9}m0xsYOEQQ~Kkp>9qTw;4a#xa%bs=Y|&-L5ohHqx3iRLJW!DoUaqPM zD|w>B>cu&CQiS1C-z){05p#`n$!oOg-L+ffqP#hiw)>Cu)1kFS;Y(D^(yOcQ-Fco54i&(%((^Sw4Xt{Gsu1K)$U7Q$l--=2@dm(^tvyq1%0|Ea!-ai^a{f;;$>-lp4qSN+r^)h z?9&vyWcu>rjDw~KCdNnO?;9WCx93=o##)Ee^F@Y&sILr}4u=;gbrBbsJ~)FyU5A|= zNt}GzUT|Dy=M`4})r0A0qI!`bNqP>hcH1CKL(t?T)BV|Jtf;5fG6c7doftL|#lNqX z+UzRGj8^6Gou8M?`ou8U&{^7t+IO{0)O1-pXyxFMcJKHw<@I*lZ=`6BjV3x%t*FM< z4(jtUPqFyWNp*%lYaY9qZ?1Q^HgF@MtsMxOi#ST{f6A`=LL5gtoy^tW7#8FH@hmV5hC+(L4j?uzgYx#W2hS= z!<-j+6xrm+^pLnVNjq`k%^naWE96N|58^PGW1znKs>!=#Bo~hp#Vvhle{4Ehk3N1D z@#ev1ckpfU3s>j&R}92%7N=pK^CfubSlZtAr#1>u>x3QtW>(T9W0jP4cN(n^YTfGs z8*2%GA)cS?j7&tMQh;Bzus_wDP;{AAsAzUzX=CVTBs zSG8=~Av>}REG#u{j3JPkmn*4Uq|)bCvsbpkNTYGp7Uv6M_AD45+X~&+?y-uoJj^+j z*YaTs-z3t^o$K0qQe0R5eDFxuFtxNa#Y}q`+b2n|p}IIc<_I3InxgtKDfku|=mke` z1R~W(mE=SjX|Ev11s94!0!QCWC@3et?48Z>U^ieKvZ1Ht)!TU7l+mcnB)Q(W*pc;h zm5{=$_EnonO0TpYrV-N7p-$mEu=NC%SDksgS>e<5QH%&rja6TiFa^%w<^A+bJbAH? z3qeig*mWU<-oV3U_L1~A5SlC$9)J@MkegBR3Dzh?g-v^XKNgvrWBVj(p|E|+)!_!; zPFw8)hw1C3H53E&lrJaBk#O|ARl(E+WAi0i{q(cIF=l)u1;*5g&<@4gXqJ(z(am3K zpg5#v!P1a*KIK*KaY5dED`q!rF7|nG&1^6}$zm)%P|Kn{ewQKro)~nvISd*m%JC^l zw|7|8J#Q-e}hK8>p2j$zmeWEZSfCQbgOg9eI6xnju-j+ z5^Hm9vrcu>+X{g`F?Db#;!d%2@3tK}k&Kn!pBhue78z#fw4ZQGk{L;n2J=l=wN*44 z{^h*qfCH#>O3gH;+wuddkt^5h9jzdj~~LwKUMa!u_qWD6Vlhh zK3KFBMO9E&KeP5VRI;-#z!;URVhxHU367Y6@jdj zGOQ^lm(^PTY9;0!sQTAz(1nqpEVJ0hhU{?y^m+(=;>9X#&-pvtgX_=|}2(SSv5O~ zzQ@*ZxQ3xadYc?BQp^5v-}BdbepIyuocKdYV>43Xa^a5aWR5DuuDVZ4;ugLe5t1C| zIA<%^k)j(lk}=RBSzMiJsHw4;-x0I^RdYMa1Nq}f@Rcbu$WvA&V_7rL2W>lZ>`B< zWG!6e+3V;@_vPO>jmO|z2lvs|VCm+B237J_3;7MJ?B+SqFk;6z=4b-NL8G3j;j@UT zNvNf#U96JUpZO}uDe{7HY-gmBU85^+TuRTV`~BDxJ#lNLyycFRd$vXm6DZdev^%o3 zx!;3)fBym4-%Zuq>;lRI(Po9U-*(0p9d-?KiLlF6*b&xJw8hFD{seqDT3QIaQ|h>e zF^|<467I_H=wWcQA1!Ptm7;oi?@(ue&f7`b^cF~2;-%8uCwG1=?IN*PLiLNaaE*DG zZq?sC4Et-#c;>sgdA4hp3lBbeb*_6`&g&uBWIyJ07BeBGgR=*f3A3l;c7cZ}|6{s4jxrvHSWScX55T;j7U_;pm9s z-0{lVw>$7{gdnT5xpLF{JLt&}ml`>{LsNMq1IL8^53VnlS)aewc(ZzVP@>s@R3`Q` zsa9~baCfT}6POqJZ*{aoH$YpRF}pf;lC&~bJJQe8W7-@V$UusLRTqrtE2+lvGv z#}+_L6cj76rQe|obz9c!ZE*NgqR8=r=X$^M6mx+pGBjJJw9Mp@rR8CINM5CIW$+!k z&Q8gNu3z-wjG~quA7Q1`S2kPAxc;ehf@#|IHTxQfAE6JO3D%SS*}&&knpyi?ZJ9mv zIilCUXSK5s)k3pF}41G)ZD%etvO&etu74c|L-U&gc8aswPj& z`pbtLFG)cf(#t2c+1ZwSG?Y#{h&b`cPi}6lstS(Z`_T~4fI`*(SdE(sr0!wX)ZMB< z?n^9xcTqTt7Ci-IYh58rDLAde@orz7b?pa8&@d*NTVEG$HNwfqEVx%LUQ@Fiezrp6 zR9@&P7Q(a_@_0|Qj(>T)W;^bzbU#jxMLNxSiEs13akMRyo57)%V87IJR0T-0LeVO~ z)x~S*7ZrLG8XkfQgyNK=p$_`wx|zk|Jwk8L0K*lF>{E5UU_c{ zU)bMEl{$s3y{NVE8fR1!)lmJO6~;8>_AOZFAUsn!EElePmr_^utV_(gkVLAN6Tjh%fyW~&p*`_}p&VN)aCUnST zw}Rt*JypcDccN8xO7?93rdyESEchO#mgq4Xo9l?B@^SBgin{*kWrct7yKVD!Q#^{p zAnJy_#~e6e)R(c`eYS%C-({&F9!K;KrYgoBP>A~M9?V6k*fZbc4ZIAWR*U`gJWKO0@2JFq&-ol(aW;zy(dpE523;bW;jIv*<2eW;*{SvYKj{!4-TybN$^V{iKULYeSf&I{ zs2a)eq^OZfv6|IA!E&c?fXjt82(eU4hY=&e;mYkH3^=nBI>F;l7e>zccZ&fg{wVOe zbopX0<3H2C|2sicHUL5ZXy~vO4L2s8cne3U>&KQ^Jx}@_enyGa$cwSjm)j$lemSt{ zy7JJGv*I>_q>VWLf(V{?^6Agd0&}EGb3KP5x3t{!1S$@?LhVvCXfh=S-*qr=b<_BFZRrJU94+5Je)uC@WpL66fCphA0 z=_&9Q#ZfA&-v$6B6y-_lYcm*K)vdYVv|Zj!=bLNYq;q5fikgpv$<1^n2{h(=__}cM zBnelX!&KUB&T(P$(JYg4uc|u&=C7;fNV>*_uvRBy9USICVDn1B?7fXnMwKk?vZ`Um zQ#7IO@?>Zm+u%9aE9eDXNgP^h);}Bgsn)Tz5skl^R@l&gepfiue7*K(6fRlZdsTfO zsRMoMyqS*XRKyaWx92z??MdY>j~NdNyG6gT6T>{$nZ7e~T9@IVd6kZ8H4bj2cHbX> z`u3M22dcU}bW~}4Y#BMy=+`2K^RbJfUxk7n8}0w#&?-N$*3gqGH;TB#sj88XlV6yp z`SR#zS8zGAkA-)GPf7=EVLZMia*QQ^bjZf0D0fm<4c~PvP83*{l<}H=%a`R!SkrhB zci6QK*Qm(#9G%6OhITT46SqW-+lL`#t|Bjl<}FRaTE32Q@8v+#yP-n~^lvoycv8fD zHs<>kuuOHsH4@E6fY1AMWmh$auWqZ%x-;KxB?n`b2Y!+hCCz``CSOvvTx7C-#Dgla ze9aQjO>R#Nx+v&&E>xsY=ZE`5SqnKA^Kl9%2NhYRDa~`l{VGq532;QpXl9j`ypvw0 zWP@Ifd|!O|m!2gkA5HM;UgGHX@EAVFAySY#UXr!7Stf4G{0)c4OQ+g7x8ODOp;PJc zQrg9V_7MTjW(ueLjD!ld{rPS#Z3YQP8mK5RXe77q%(Pg?Y}XbaGo|JXT-!|59vU z{7v$%Zv@rhl~DUTHJhdJ;O|L<(}%|i*){(><}0-ri0{bm=wRW8FOqMz!?itFq1(lW zJO1KBK%HYWgp786m#eIyS>Qi+~#b0;7DnYdkN5=1Srn6d@q%uDiG$mZn9p#TTm;1)ank%s2`$j*y>S;FcnpnmZn z@9}+A@qCllM*0}tI-&Xj)g8~4HG}FO^%5xT?8Ox3H(#fu9w%6Hv2ZIYeIMI7P#W&K zp)UY!fcC8`*dD*KE%r6-fex6x31}2hYfYSLFz3nhVck_HOS791wc}=TRp^d3h|^(O zkujR}H^grl?ULTh>s!WgiM7-OO;O(VM%Tc>qDV;Fb$E#(p=6wJn?w1Uk3P{o=*}jl zBa^82hA>h&SNDQxynmOC%dWv?u#0p)tahJ8^}g%KsQIE>C_AA(Yb&^ai_<#&NO(b% zYU-+bSAw?7op>d`AE!|r5+py1WLSB{q-j^2Tn8m*Drb-=D^%&y*4DT;yUyahe>5Yt z&%+`TtyGg%07mA*0_z<2aMQ0I(@hFivxmF39w5gn+~r2V{6%}NOZ)cQ$#;faSdWjg zYTSDA;I)986EW*-M1pr4bU`E9+Y+@Js{<9SuRSNK@=VxpGc+4X>|^>+Ct4T}TZt0& zSuDG*zMJ;rIIFHT?6`-$R1=#{?iKX;j_t^I>t7!9RM^qgcl+Xfi457_kJ2a(TuYj&UK&hzVj$&UW2r=@I^>HiM!>8ZgPC>;g;jwx7(2Mm8pk{&v+1Pd9P{cxD)U1FGYO%1Gk=NzN=Quo$z`qv!=4W zInpcZfp>d()n&2XDzenI?Gp?R5o5d(nv(N0TDkO*yt(KA;;|x~`n=NJ1h17zCC#UR z3Y|JuYNsxn%fRxEWn5HbDsjMM?1y9Hm}Kvlx-S-V%-gjc7uTq_Q_FtT6I=T=5nuB4 z*fFB(+aR}&_RGX_MYRD20IC{qff zd2X)6M+#Y{Q@E;tWajfGS5EUeM$gIxHN>XoEikg}Cn|R=39K(hn~D?ee~-iUN$LG~ zs|W5<~%Z~ZkqA?xEX}G$yNJDK}Yl2W|$*7VMJ)vPU zSD9NI;b5ufoUp@JV`ub8u=B!Yo-W{sJ{ROleeB>9nGcQHJA7_RPn$ec!t+LKCX{}C zJNiL}Z^PiTjN00X8`U2g`YFg`iYT*?1GKT$LdK}j7l=TL2~DR0vllF?St+3 z__15feD!&0@UaSa!YkWrpC6rOM-IOq2iIcQoz3;7Tn=cRt-;|+>IMfiZ$<*P(I}uP zNLYXz9!i!C(U4GFwaypbMbpRXzAt;yxRW3zxU zL$x7U#CfV}n998tgu5(5T?a+0ei3$=J@p9)MdM9A3WHI;4}n5z_e|U7C|0WMCx&>L zj-#LO7wRTSC{O-$RrlznkaDGI4C;57~MJiqvD^3 zxVe)pL`bids@5~*QJg&;%Y({Q1+}Bf4OZRNLBe4-lh<19Ypp91^@zNBo<3P+cy?kO3%R-%Ee!D3VVo1HQpNQJ#)6W8)R7D;Mqy*a zkJCz8P?!G$p8iau@8rHAWqLGR%n~={l=gWTZtWbJ(Y!*TG?dkrt+#!EOUW1dE%8ZKie@qz-E`M~l+u`Xn{RbWm$Nj8En(x9c@I-(E~Y z`eT=A-dC<_7w7_-w8KqA^;{~98@iR$#NDbn-Z9y+%s($raGgM8WKKk?R$%4&;t}Da z9#Qmm-W!dmzt39`|7F!7Z{0TQ?I@DkP~AG(RVx?6s(=jREg#>o8QrNmD`PZVzn**6 zuD}cL(9_%zE}CqiI1z(Sv@lNJLdgZz5UVE$2vGI_v$zecpMiD`xWF;y&XNE8gBPbv_Go%?1B!?jnakxF; z@0{;j=bv-ex@+BU|KW0mz4vriS65e8)$_Ffch{$GO;ou;JKV!7HhS^dt`)tjgN_+_ zZuXrlp*ABq&6aK3M^(Knc)@kApm;)X1{xCsMHM>8B9yz9+i7d5Sw{V#qaWRc@dxKt zvx@VCi!y1sDuaTYYkYFXLf!Wj<^?;%#Pr9duY#S%PX!RjL9+PnQfqDWSj&mVQL&+3 zzYl-SHy58NBVXysLd=p5r|LlY58fmcBWG`m<^Q!@wsY4Tg(Rl1$JftBe} zfe}m>Kef$3yw*z6ROxbi=)70O{&bUEz9CYouB;{Y!>zS#$;+QE{N3EO-r%D0wE^~8 zwq^B8VG@KTLksI$fo#turaO(-jaMPlbnBnq*06tBRn<@g{eoKVKp2nAWM$0XiDYGc zCg`lJgwPp#mN0(VnF5kGp{Y}|JCxBp>8s5`yrXLtl+MW-4j}3~pmK+-+sNfr6LCku znT4!yKL`$pM`Q~-I&}nVrkcmhyE%!!O)a*@YWH|~s1v#_*6T9m zy03ZnRbcZ#EmZZ|qe@gzx9N6o`S?#?im{-Moc zUE#aXh|kYsruqz35Kb6IPIb?z_Y(|JGsOkb*TEXa3^GqKh4i>wTZ*EI*-syt26HAg zz}&{KY)PM{su*j`5;enJ3rFauUCJ-SmN4L1QThvlPnU99T)m4U3l^T$!yCB3dL?Jv z=w}C8YnJ*RZ$V5YT=KA5Ww?mdU9!?LR|{dWmspxwd5?UmCg#Syon)7l_wVoyL06;0 zz-j>;k()7oAnb?BVftvLq1Cc{SRyI?efL6@;Mm_t?`rYFPu(d`ui2a`(+ z{;miM-Ew~N>PJ$C+%|bpUKmm1?1*2sd-oXZt+g(?79i*SOl3UnLyWlS{2f|?GTUy7 z7wQCC&4S_pLh@oIkZrz)c-;zTg6(SLlJEB31ltw6hj1^u&mQWJ+YULu?dRyXt}Z+_ z_MB}Lv|S3l<~$;&K3r73ASLe5{N6P1`c@>7tG|)%!Ouy&D}77G?YLQ72|`C}+dVNh zLVFxfuKGo)+-@jk{MPNxb%e{b^K7fX&GW|+55P99&Z_CSW4sTtwPUI_C2%wcOjLQB z;_UtPlcrtn@FZQbAiNM)yNttWPV)(Sx_XJ!UzzQ01xcsssOvKTmu4oPScOwe26O2< z$$5w`K3IV^fck z;|zIb(7D>G1}~*@?KTGswGn!itRz9J9=+(xCt<<FCZ+4T$W$$!$cQWv}j83WTZ~ZAhdGo||*7tS|l3{wgL1uMmlNjf=|8r|VlrZgO zy_br;A>;M(H26`vq{pAd!je=ETqBtdx)#F~Ua#iu@mS8@@D51r_EL&~lnGW^12+o6 zdF@j$u%Gld1SxAbRQNqHWTXmn#kk5NGPb$csDw>dr_pPT|Jpj1=}?1I)@j{uP`(l` zZB*{H)~cc&;?6B%*4L-ps&cSZo8ghC?B);m6qIw^#bo5dqfu|9e)rlMGi{+C&UjjzP0B|FDPaEACt=Y zzeqC$Ko@IgBWi9XyBiUCmOFVAwWz)qiB==-~YuvcH`F-&TOG}Z~?|32Sc{Bg(x z>;I5I?{BQ0vjf!4cXTL4OidQtxac-E{_=zC68IZB{cmKPjUJOkeY_O4au)IisSw;A z5|PttII{`D^y8P$S6q8dkk%NQ2G#s$@pF%*77BcXpL&5JCFZ|G#v|A`s6SITK-Y;O zkO_RqoMv+XQ}7}%R&^Z(SBUzrFB}@Xcr}}z2I{=f!-Vi-LpcTP08&j{&_Y6Pt0ggq zDhT?+|7NS?QyrVHwJfA0Q=j(E5<-WOxx&Ps+z|T*4d*0IqVt~#gN;+xMIIgfjpMJe z9ZX8oJ9qKkdk=0&^gD%toK)5z23eBtv89v0S*B*-GV>8NkbKpO`)@YMP!d}5>P@)Mu}_7nK$(!dJ)mF&*40s*tSvb^so-y9>!~HH^$TaCH3F z{H&DnyD3Ff8@|B*R`W=42T#D>a_oIB)K)7ELT^WQdG0v<O7@!^1aI&QQ~ElZfv z@$-=VaVIy$al@N2eih|dc;;TEz@?R-!T|MsC% zPs>duw*iLb+f@K0@woA44^V~T>gIZdrR0j-F~oBMXgUfjg%}LHX0zAd?`X}wy9Dm> zGy7BoN2nn3f~MaE5?EAJ1T^Ho^kj|ghuaZMk6=7sLrwey4Uya_lp{<(oRXUW5MSH1 z4@CY-%52j-qR!uSGu!;u<22Ni-9J@XA6|ok%5G3CyF_$xEe=0FfBC@TO+k6;>vyW6 zqGn1`*nDMqshZ<4ibCyD&$(>(DPLjKw}2;0SpXf#!Nx`J;^6mq%EeN#vKTzKr1H;N z;`v)t7-)xv?I+946oPNk0ksc!lA)p615{|MIZTR5=A}M-9^_sDtt~!{tk^1rVI#$6x6*&We%&p91xIVeB(zW3Tdp{S@ax z{Oi}l{Z0nyE=>0+pX?`5Q;?JAfN?f%%fgrCem6yCDn#W-XBon6 zQN_a^S27t+tmHe zSZ#v|HIei*tCgPe3d32pP(<$rwZKC`50K+@Ukw4T2jD#n0GdE-fEi)|kgF`vmGhTb zZ31i#n_ymP=_$x>f>8sQCH0z3?p~>rf3F6+L;pZ?{z&Vy#L<({CVHb>Siblg|Or&U{A&)J*7_+Z5#o{CxSs*3T}G$B7X4;$n1Q7 zjTCQKZprX{@v+184$$F=5jKLSN)3Vh^EW}E1k7zM2`zEHr}^HW?T$gGA9Pv1m<1S< zESueqoq15<%?yF>YA>x~vRXxfQnrRGLg;_pI2SIz*Ulp7Xz(pip&{x$@&i99T|o9N zU}GJI=}B>#n(y{kh66en1H2y6T;mJG>!-*vfE1M@4V=4q+h|E;JQh;j=?_N`ULIgn zt+9ca?t)@ZPC?u+1t~s&(%zYW8-8YgBjo{H?Y=_fvj~tAm)QA^0QCUkOA(hq?dd9o zbb8H9(87z^ST(7G4>S%>Pd3RnnhyK{m4=8CAObSSYmZICZ#Dm8bkUbH%>p&`k*e%z z{_7M`-O3TpZ{9Q>4wtsRD&LWR_v~yjjeIdSHU=stoO{zGHMorp;03D+($66H=VVG7 zj$s(7Er<#?0JhD8vixjb0Ny!M%bkwyZustqK6v8`?nF%q(e0+A%!f)4Ht-xhnHtV! zKKv-zNc9Wf+|Hnyni>7Cr{}UvNKAC^l2UPd&3o`t*1w=Uw<&(RQR8=p>#spgQNkltvggM`MhzM=|)NqcuSZ zU77vFvgM?EFF(R?yy_30z`8YxA-(nKr>3(N@i%D9>AWz)6HJ%vA5Xa7{-+keXatG$ zUqQpt(QB1>X=)1L=D6McPa>;_ZC`L#R#uk6*6Vu#tmMp&UHNiW`FMVe6g3~AU|5xL5Kkd1OSe55{^r3c9prciQv;_>8w-~m~lb)CYV}?nD#%QdSr^l zZ*%+b@GvKc;jk|lKcsHE&djtHco_#60?LBVo!kfsX=(qx)v>uBrbCK5t)E zL&#M-9jBoRfNFkQ$J@QR2@L=R6-JJ$m}xim{gWAVu~)QaWA$zMOAh!wV1PRDIGW%o zol>9Q2l3nzr>!)ln8pHtv`jymT$rRLiKN79(IbAZ-DTGwM8XYw`%lkFkbl32#-BRX*B-U$Zf#HjEJJW!XbFeF7wW1S{6@5x#hXSOaOYlDg zcTZGBe!riYnZdv8KEuJU@;2c5i99+3*nEGyi~@2%!vPZzjf@At*|@KcZuW>{vOu*a z41))BqApyB{Dl92a-Sl)7Z(?|gPD>>IT1vDT3uZQy>EOHd{gCgSAxeX`K%MckHA`n zUvSs&5G+N<$H!CqEIwfn+wS5AH6{cm+~-RtzVd;V3*U15_5XJ*+W*A{=6`xQ-T#;_ z{0&b%(#J}lZc9TDCvM8NQ{EW(kO?4S^FJI+*Bf7*WjOVSqL;ksD*`~-=V6BpsgY9S z)8wh+d0$~b$>OP82z1B=I1{u3&p{RPPkZ3w0N^1*;1#07X@y_y?V=BWXLJtTBKUqp zDPZ*+yN;5cCb_8v5bN4!RiFeLIH{+}!*FkRV0k|M)i(4L-Xa8|bx5xeWJTj=EkOV_ zF+F`MS1mno0vmY8nt*`e)A{!o-#Dgfr%U;6ZEq91l7qV8b16>;&`zRmst{fz7&ymt zeZR2OpQ+&FPcQ^a*q(5mk%m?YIUM?Wa8 z0Qc^EOE2;qxFJ{35ZC1)JcueQ^}G?Mp=<26_SrGE}cD)gEO2n7BL`7!=G&@-%FObIX?-RE*}+;D>+>fJGTwvut`zpcRF zHEi%D7~-nO=l!~AO4XJ{c6ne_rsl~*!1-Dbq+vEaOUF@Y`o1{ zkF?UGB{w9iM^%>#plF*iTk` z;3SOH?P3)!AD3BqXqOtdJo?IeE5whpJZkO_(!eVJVzF&x-TZqNvp-qkRddr8maU}T zl!UVt54mi|rTn`#k{{o(yF`zjz-?NT7?-Xjt=PiSLok2hi1TH{Wmr+-zJ6JV8Kd+IiibqXGbKN3190SBhaBx`1Q=JP0Cjbd- z+JAP1X53(q^7->CI#WNKT99pE_`)Jt^O-?jWJt=vBOw9x2eA8%N1JU73iZGrCrHr; z$9tp;SPzit7?=tr?|S)WbzZndZhAKKJBk__v7K{()?dtL-!aP;%-8Sk3ji>l2fivO zxE&4tyAO`7Xjm>NoSB`yZ%7f)^Dj_buxxUGlHCb_fG*6>U-GQ}{P{D(DS7$W*p^}Wx4^x=JLcN}`!5~OCCRN zTy7#4Zw8xzZm_7Ot?nE!B{CcEj!BG3Fg1xtF$Mu~Ov893m@Pb>h2O&|kdmqhTXvo7 z{QUT2Jy0;XVCu9Jwx%;t4QLAtVI1VZU!LRxB$rRM2p^pb>1!ey(8N!j;;?|TT5*L% zEY%@{mDTf&Qb)YTt`}~e0yO*~wWLM(90gL>&k2>UF%AaM`-$=JEr|xyO$Fesj_83UmrBUK`M4Ip(Mi-m&0gcdTFq4GFF*^_ z0KCL>z{LPIDxn#&_3|cGXZjEL2(6Q#fScmt)tgm*e83a$@~lxyP9r~iAiCSq`4${Mls@kaXTK{|KcpO{|>S8uSs2j&=TMk9bHSFBr^ zrR9Kc?|AUb2!WWm%VHlO6VVTrre)XN}u|yuzzIt7qb5i7ZsyJhymUE zS_(LF=FL$grb~Q;7^;t&#cCI z40eAJM#WGy;aQ$|_K(xQB-An-f3-p-0UPu2DPWeodkfEO>S72U<~ieVy34qQJHkK! zPs`}Yk_)28GvEPUJ_|Af=84??$2FO4KQH@Bcx+4qznoG3Hc#!jx&-X|01iH#t5*xD z00j&BM`!8r*v?Z5038c>yrMu6;qB7W5yo97us_@AdjxerQIEw0JPtn-{rBg{K9JVd zP`ezQ57hT?H{&YHvCFHhFudsR3cvapa@CoEn)lV~jW+yd3~W83Ij>O`oh$zhYhysH z(h<+DmL@@Uyg46U*B+|@+69{Y;a|Aa-rHU=tI6`6UgGcU98$byT3C}ERz`bQ~gv~^Qr*j#dxYtf#9Wk*j z)mOYt+vh^1@VZxcDwX*HJC3K^3$c^@e)q}wFNKVknLfeKQ3J=O%gX-SzX0hcqamKj z?E^U1CeM2vbek#hivJ|kKDl=x%u4S2SDEuC9~R{0S<&5fQf-~wXE3}ob~f}s4Z&-$ z^Afkn$e0-MlM1j2-C7C_XbLn{7;)4#VC{d2}yFEKTr%-3s=4C@$w{Dp1A!u27Qa%aosR~nt(T8pB4 zQln^~u^=2vGv*cWHuA5=lKguKm`5_ZQ!t|#A_Zm7#PwBw3eed&z$JGQ^%(#s>=6dR z@LwNt0`#kZPLg93dOTDAiyXKF1Uq-ZBCxvH-{c0u<*&moToF58jh?gsV!wApzILlo zT+|fj{Z3O6QoAMuR^xx(KEmHB@b}hcV2!j44e9KXHFD&kcv~}F#ib^6l?G510SCb0 zzuo)x;#H~B<870p(DvB-`uLgcsF#z~33v=IPdLTW5VBJyVJaq)5KM{7k-vi{&74E5s*N#o4_8Mt%Gn9p&XCZ=4X0V6Y0%+a}YD|G5kB=`^)IJQMAWhnYLy{F|Vv z?+B-#{Z-=Qajy>%5AZjCe>8B&Jz9#u9sc}C8qIly^6Ou_;s^X1-Lj@Lb4vMg{8Tit zpn#<45@qdw{+^U`ndZL2(*6ImV`&0+dE&5FkHGT%xq98j0xFji;PG6CF5$yD0dKQ? zd&_{ymMi<;P5o7UdZasl){^gh;6NT=6-<)TOuvtvFSb0ts@(`lqt(yWmhS<#$;br3 zP5=E4U%*0Hymq#Hm@pAs$)2ULjHtV7vwvCrheA$bL3GI#0v<|m?iOG@lJoV?5XJ;i|7iQuOpR`53KH=l~KLH+m)>*!Vg_DEV?8Dd|z;BPfS zzPRglVPRmC6YKdQl@^c;6QIr|9R^^>NByn7f&+hi4WMd|CB!D z5SO_%F;(TeXU@K*Q}pn7yZmV)SWkF({?h^5qNcly8Dhp<+k0ZEHMI(4!$D(xADyW>!2)NCKxfQXQWE=9jIx*TVG5QQ;cmm2@i|u| zN;0?Qf_;*K7AAeH%WYBc6c-5ZZU*zFkMpmC8KqLuMbE;RF?+F11u)V%Omf|S;a-z)2P{^`k{ z&HP||OYrzz9&1!>GiDr&I-P<2vk&km_byi%Q7!cS(P;CLQ&MoLLitsjkF-tK;%H}=HI@5Z@lmGu>Mgemy#@K4SJ|$s{>eE& zKh#Tz7c%!*{T!`sCf{b9AZFWi-COHPu-SnTw_bvvZHHRm%1*qrE z!{p_O7^r;v)nYknxD2#b#n4CnguTa#V{SS-8-y7jqIx)p(DWBD^|mrdxBXu`oG28r zuWt$%{41<~_k0BJGp&>O%v29YIrnBSY}!|14vWoIiAmpD_YCkwg@p9D40c=S`q%Rm zHB~z(?iKKkXv=yRa+)wYz(FM{*2Y5~9(qlaf zj4Dg@zj$HBXIK`fU=xAb`YAQj!g7MYh5X^KXO(8Vt|Ac|wXSxjxUB+>3^F-c(&+gd z3-#2_5*1@4Uq|{pL}DzzkNRjp&QrfY?87yc0*r4W#ur&K)2!958&%9*@2;1Kkw335xWGT4MKuiw;T1mqx@+;)%)nq=1GzT3OQ?0ZfhF} zCOs8X3+=@1g8YpU%{T~0g%q@Uzo~>mLG~YTUFY_8+9!vVztVx;a%z!uQygly-TMXdFKl^bPkQ8I$S-qf za%>CIIX%99>j+Y1Z><<`C(!dSJnoN^SHI@eQM@%Kbv)Dmq7U~!q8vj5aFm12htCMs89EVO-`nZAG8Q>g{T-{{zz> zTq4cQRteV;81{aRn4nmV{ljkTW&FDe1-*~Wo-$sJPjHpp9ieqRdZ&ODPv3WKdZzRE zO``GKQTea&3^}SOvEhJ+*XEaE!_9)j^cF;2`kW0&N&0=}I&rN26}G!o)0c;+O1;Y- zm4?>4pVSKa%ey)S z>^XKq^1PKheYTx%*Bfi0_TFp+!T8poMXyu$fpS`+-mUf(I=6@{Y^vBYR8?Vov*}zV zT>bY7t|KlDg_1$dHQ10YO3#;9JL&B`5$T`GEehcpiJ7yIB7?HKh-U8F8wpY`92Zu1 z`6m!CWQtnxzf7iw)^#*O6kT8XHcuL+syBtlI+Y}otg30YM^M@)`*HL=3*oHa_7zkG zaXtZbY z4qOWB;qg~lz#cL3?NM|Z?;FZLblo6B?8~>6eQhmAQcO;|^ezvl#`2KxW}#tqtL0xp zLqg{L4u~bYh}_6C^iKtb5Sg!aVh@_OI%4K@`Ex(tX8s(L`=#{*xeZKv9s7J|H9T|U-=c#EYeOH=4(zeFDAZ>z>Rjj*J56A#~A z#tE}|3o;n~tVRz@xvK;^p|>N6wkMcO88d`?{oNF7bwqa~GB^d-YLL+48ssH4ElaPB zgPEI(FFWUL9Y&6POc$J2R$>PTef`fCDapSc3dS%&5L57+L-X)x-Rz!mzAq#;Bm_q> zw%xkhAl{pBy7I3oN0vc6f?5388}iu0zOC?Seb?ev+$*i%p#DMUks`yB{jEvw%I*2y z)yBm3(VZ?T&P~Pcrbv<=mR(#Q!N=D348g1#mi5>rx;g(636EOb+EmV-4*;g@dhTxP zNROJ}W!!@r3Arz(l}zuA z)lUg0cAc6|yxG|%*C--VV|b-mu;1ErNYVxgHu`K50XUEbbHGy*D&4)EaxS$TphKEY04o z)?7zdU!&muRrU#oHY~e-j;TgYFZBI{0kg%VkM8J2?5?6{G0x+^DhMS(YfpO`olmr( z&fd(5;Xr0!OLo(5(l&Fn=ZSR%PjSxSQ>#D1W?NbGI+2QsX?HqIB8NPhEwoML*f}LF zR2ADUK`PAk7U2zu9jVTDjJe!)#@WssT=rg{AI$c>O=u$6Wo;*|H)i=$QT04G|Ix`e zYDi7tLsE?xSg*_--<1VvRmD|5IyhfL_Dd(ig#Xk6P<@(re))R5s@5SfB!rJGXU^e3 zo`&+r1L%t`em{Dgb`&p*+6~k~64JYfX+gtQlJkUOmc@wNZ&5v!*Yl0LZ%@yoeU>?w z#vf(xi*2nth=w0^h*sw=9Sr2TmP#yohibr5Vs9cm z^r$21s;s8_QjBhP6m{-NvzVFucz7YlU@Xx>3Cl~Cj_jO|D28W}ZbeMoeQfEC6ML`J zVCwogNdu8b4UDMEEaithia`U1g>_pO;rF^qmqJyepFbOr;#k5k&JsyxixpGY1h^8C zs)t{bjG&`Vzcn==v5pOU5Ec@GD3Nk0cKx92J#J7ZaL*`fA^Lvro}y@~-?_iaiTjO@ zOAuUq$9I%&_fh}4?Zu2n^(_VCJ@_?FWzDv*i3UbSvF(NlRq2|M_A7!rdlJ*7hh~Zp z7Gg2oDeHZqwUZe0us6buz6q5IOkLb=zcMaIjoMPn%4W6e@3v(WNRt=eR-bt`XsKHY z6WxaH43#g4krO7X3lySjfd zNXk!B4I_QW+(UUJPp}~AX?Vyl#p-ITX4P$n_dllh4qwVOyDcrx#tu~Cyv}r2_}sWr z-pv`CH`K1pkk870qny8h4pwQ38m4Q30S~4_V4}DkKB_id^r3b|geOf~E>vAnlgrP| zsM`4Gl)p{S<+Ftz8Vo-krBJHfR}gn~qjOjFO}zi_%@D@kKB~0nk>p*nCDA!p*;nwi}iX*J0P+tQI?JuNK>Nw^WHC6Iv4BN2}sOmP|fK1cHqMO3&-*nO%7Iz~}g~ z*P}aQG;4#*Dz;0>u3i_kY*X!3KN3w~*InL@<&QW%MegNfJ^492OP^FdzfQ3;8+%*+ z+;Bemj%75&D;2@ln%jJpmY1Hq%bd$5OA7hbKQrK)6cU2=vb0d!maL{G%O!?O5euYA zcxt<@vX8&vxkLW|t#1HrfPsaZu^YZzeIJaL$oA^$oSFkl<3Kv%bZxwxS@=FLSFP-J z{QRF$xTTS~^VIz7P{HG`*`6;XjoadAZprO^;InzAj72mR>xW z^x)==5JqpNd%UbJ_pQ?k0wv{j)@c1FbV(0m;y=c|XfDYeIr6R-*=;;bn15+zn`OsS ziZSSBhBqiBga~iTrGc2tWB}dQ|Lj8+taEaTqm%9b zN#jgT`Q{v{m@Ik!nDka&iP#<7j8)ow1-PvxX4neWyfokU}QV6_P~Kft!8 znqmjeeZz-$&jNJ;Z)FeUM(nRKGR`2dxnzm zAgqJ8OMgMcoK|Bb=FpY1?fUz4<^1;Q^;736*9~ig-go0|ulCm5tpqf@BBPD#QRYlN z-99gxhiypg;2V;{Vq$z|=ES%2!%k(IPJ$=fBr zD(RE>M7_~f37QML@lnT{RZo~~s^tJ*+6@^IAxTRk8DgyiV{YdUFuJOfNccC~j0bAU z_THbEvsEBV#Zdp=NJpf$H*hd({mguQUU+3ky2R?u zgHcSgOwL*HtlSH);j~+lpJz9MHdArYZjvoxmmpQeO;D#68e# zbo=U)SPJ8`4SR#EJ3QzmFqHFSWmnqRn_Reh?fTlf5OPwjm}4(Uu?%=)mxydthNy>I zOT?E}&gSKvzw?qHR-%`DRYt=b9FPVEHx88ADBe<{iLQ*6^w|CSr-L8`-9MMT`UEXWqy<)eR!a9{?Qz6 zM2bCh7kyv>Jkvrw>u#T_hV6bi*=?Po$~n6mt@o6+8oK^KtJJ=TvU65VF)wIfON*AD z2h4kOO0VR|kzMFaS%Iy+9P#d0oxALO;~PIGe4@f6Q+e%<_r4(wMya#HTUJ(9db?>7 zjqO`uS&)k^cPjs;{q@ZRbmN|ORNR-#H1w)Ob7BRysA5(PzAd2yQQH;0bz&7squELA zxWssyDv6nY<(`YpHdH6CtE@U9ub92-*&SMgMrhGNsssFy_o+IKh9D18Nc0rqSz6U|3dQN5FDWeAgN`8+ROX%?~OVkscBQa)jz z%)n{v6*0T?y0eO1O6C~wIl+XlTyan_yb$JN5yTxwPdYY?cEG;3(cv!|(cpV-nvLP|yWv)NqV$hd5? z?0yL9iSZ_4^!3C0OCJdS`b&;Cw&!)zJ>UjpB>lb6v7Y(iz1nahSSo4a>r%GeJjM*K zLfm5Ua#bV{{1=3&{d!fcD&bBgl3W^B6HW%%2eSiKWA6g7)h~E}Gi&-lRM*bSxLsj+ zr`}C4B*d+uxv@YdE;)j@N0^;AKMLZ$NKr#;s9{@}Qk_c7oiWJL%l;B3WU2QocUC`r zvf=R8WW#fXRAxvw4I27(>dtJ+R08~yy;wzttB>f~&==!xecvof+}4FSPh8OnfdwH} zQb?}!!fhqq*0H*kbl*`iAsNJLg~nf<6%1Wf+z)p{LoNwSJA$q-v7Fi0!j3%rUMcyZNT;-hmkjgPo_%B7N#Fkd{)O8CTRq%*MDf%v|rHy453MYu|(Qob3 z2&m*TB%7p2bc?kmNJ1<+H5F$oj6JmUp&5(2C+OJ==Bq#BzEnQ@CU=;Sc^YhnXLfe5+mQXP7+8Oaix+nH*$0!#-K zBL`!mm84`Obv*K=mx7CJN0MMDWz56&F&cv}#0^FU_1y=?S0~fVcH5E#`j^_MXGm{% z4_cb{Bqv5swvkXBaSX^&&r2c{zI;NI4C&5p+lt9ScvKn(#C*HPR&7_iCW#<(5`KM~ zZAkXQo7y8oUNkgAu}KfT;C|swGg)zemaO?LEW1)1&u!7<*$0U1$Y2$vVj;hnFrihe#Y|fY*8582{CtDKndE%*vP^Qf#IX{xD*k`fUyZWS7zEZ47;gt>@@lz|g-*HJJX*&Nl>dT@%&(?otAAMSy(%_;u^v-ifXCEl5&b8|71CP~t3heBIN#A)Y?d-$%ui0TP_)IUjP9XE+ zhukCb^&k&LkaBhLj1BJWF9DCk&a#we9|!{f7Lc8N`v0H>a_5OQ{OkVDAG&+nk*i*W z4S$IhmkAA=<(kiK#hsT;oVDWreD3UP{6GIM8n~Mtz}|aS5iZDBnWZTE6ET&RD9FAv zGr9;ahH$mIo&>~jF|-)tE}3pw`JkmuUV$hq5-wt`t=)JMK<#$QXj7bNHP+l!7~9&` zCQlp|8X3U=NsIS9?TEREOHcj6=9#MZmzU3St0^P+OE<`Bs23}6xP~lKaF&$1dXA3{G8?$U2lh&u z_-klCyJs&waf*r#R1^tv`1L0B{ss<(NMqkE*DkhILE%8R>1uLZi;)oZTs| zo*PQ?ZPc+A=5u85B~1QIz_MR852i<#HD`ZXyI(p)O-ZFjQu8IwNKNYqn^@#?*Lh?p zYo9?@0f>X1ga-0V5oT?QtCaLZ`PMcaGHMok`uNzn43*_AlALwc_>*zf;KW+XrgSrH$B4^EluEj9AhQQsWYWzJSszW_P7_+_luy{qJ(B)tWvVNU~b<yT8v3AH^hoD>Cob>eSW523e%BW;lV38&C+di?}K|Um1RA#a#Un^F#Z`T;hZjUC;TN=RHsR#X#xGissF(GgKhPA6^l&@5X zs;wn-S@Jj`^AA(5js~iCf`h0#p4*Z}+$TF}`dwJ+tEu+~~F8Bnc*EPQUKDS>gGca@Hlsb)1SX!`rL!PFH&PF~98@t1BKWRz>4(n<}6<^Ur@_(rus_3BLAD5F$a@L*C=mrvb z6`r8a$DyIpTDv%(Bac8D9@u=z)FwkXn*z{FS<7D@B^9e&W=BMFu5(i+x^>2+B!dt(;!>N=z^YWj z2;s4l3(<WZmJ9TO>QQ4lW?m65(E$oc96V+E)J8fXU z{Ek#|f+n;`)JwWJCmQQDkPlDU2|3-zC6hvWKJ8ZI?k6N1ef#!cn+5tt>jAUtfrDk! zP9&@OcVk=t)8}yNb@XrFp7HwqRY;lC#xWPC`4?r+o0g{Q458w=#loMp@Q{KK6{n7I_U~1wu zt4E39ZDz($(S@|<$6p&4`b!Mq`S@=-vQ|@Qc0pB4_2H))6xyILodbJS*5xo7(%R47yCT8FEhb1p($Y|6<(V7u^u~zR-f??I(3d}}tJSaH z78GQ2RhF&`@O^vLfqwppqyb74IioY7(oya2`@6@)KY!?WK^!#W)n}NWFAws@erGzT z15C%J5T(+zW)~)wo&yH6+{U*@Fh7B&a)4;SVZFW*(bQuUo9P&+4D$8*>7zre*GNg2 zcwvj}9D%B`KPz2bJ)azrM)x^aO{hzXB39*M&XTNPaz0Y~_eamQ9}%L^9_xt3?wr0` z&SLOg2YsYnhl{6`QVswvLZhbGxTM(_8A&U)*B5cc2tNlmiw#EwI`Ny;z9k0LK5hEL z!P0qv%4;2(p76#~Y4MX3#P{g(g=-%a^)km@*-4_=6ETi!W1Cw!!!=l}oxYgz`bAWD z!=h)l2xS^2Ks~rjIV+b>#@d6bjD7b6as9zEvEWLf+Q}4AtVuTu|RNt}G8Oq?({J-L}Pf@1Sp8K5P7 za{sKN8%W4YmeP&uA*+r%MaiPs>=V{9Z2e90k8Gy|J3d=o-=&;Lsazz3)I9zvn(++!vi?s9qu+vl z+Vs|Xsr~a;olv6T`08)HRR~R;t7_jr#fW`7S_{|7O@lp?Q>@mj-zy;{QGb!c93&>{ zJH7d#1W|MNsH`;cRpZEQXy@STuxus;=Q@3<*uais8?_f&^k#+E{!HiORmO z)LHXQ(e^mYQ|e!$z+8dau$qE?6hp<>#GT2y`IG6gr)@Wwrri;G1`R0P1B$4c5+kkZ z!JF6eCO;>-$KUr)XDfg$j$~D|Cv=71=oBRHbjifgPVsf9Jwv(Nx$Xh~_EfcB!kkI} zhrx$OzVHEullIV%JSl&xPA7S@+8LGyRAkp8c}Fobq_NHBdLJ%jGG=^ynp$J@^8w?9 z(%iXcvCKb%QTaVq&z@(g#sCS3?g|KEFqkmnekiMA`txaL*ZR;O)mnRDVRBb<`%b}FN#1gR~dyysT+H{gV(;n>?jeDAy87nXetc-5*xW zEx+T8SOH4S--FS=gQYygFujkOJuoq!QGWIFlU~*ED83<)8?_V?qeNH0{eEe@Z**P5 zzx=u8A;~5n@?9kTe!^<4rG$NF(sQ}YyAZWq8vR2W{dC5#Rkwm(%Ldbt(R$fE6bl(7;2n_iRSm!M@nrvjsG*@~`y#o&^2WxyC%C`PxPLD@9^`npEM9NM%1Z6}hBaDX zXJt$X=uKr!DqmIUD7wfz==SBtd&qWl=bUnc`9uffd!zPh;XD>;DhhtZojF{z(RY{k zh_inxhdVl9!U($#oV1Q{E5s5O16#gl*D{+_%JmGh8(YXXT*+39sl2YH*LV7H{iy8m zMK(|S5zS}i1b6NeYgXk|hq8`cQ?H5nO4GrLx?a82I-RoDq}=_s#1dtmcWc*}lH(HA zqOr|#BNNf6E|vtX;gsBedH}>0{;t{Jn@h@1$u6$+nf9VsdN>~bdn^I=jEvgM!wTKq zjneQ_<}V7eoI8~eX4m!|S4eYr^U}WCl&1SYRj6eA-2KQewq&#ZlbNJbgGGu=^cGd; zpbWveD#(s(BmQg}0()?zJ+#(k^Cwb8v3i2ZJU^$X4kzhdH@b+Vc*Pb|uZKa+;p|~8 zhBQ~mRP)lh+tj|3yNVpy5BJ8Z5vOLg)74mBO$2M78-Njk=bUT%%`2>PL{9z{?zv>H zka@@VH#bF^zdcB8rdl7YDZUia0DcRmg6%EoWU^vu(>6TIP6gN_oF==K)T^77wpS+$ zSGZ-0XlN7fF&R82oj>CTdcfyed>MC%EF9$|m z`*z~k!0e{uZDr2Fktx8It@ER%qb8WOLS5S?nCXp7Scp-E&8Ux)cj~2`@$)*q{BAyM zmEm_*U;9|f`Y(hw)pb~SFA8F8uax}P3@W&ym+eyH-PHebPE-QJ`TMau3}q(H;;QSr zadVmMeq34ftCCr!@5H62DxPCb95rucZc6bJ$G^TU0$*4$IyUu6(n}x&ES2n3lnK^t z!tBcyX1{f<^ssC<#R#lZ3>vW_%ufk68J9_R%+@mAv&+*Lj zrGg$@UO0sw(LpC4r`~RIOp315h!5E_-JXlOH<^?mphs`gkq7=&Qi;Wo&?49~5q zm6y3mbI^m$CEDpun?L8$%^YC;QEat7xSOBXP*$^_uN0A^-$ZPTI;A9m6)pBuj&FTv zw~5x!I6`XbpJD={j%2&*pTz@tySFGM!Y3nZ&UdZ?Ur(&c_$G`H-lLT?hs!LlSQYSu zHM-oo`3W@>>8e$Hw@G{o*PnU|IFdp zVXY>h6XN3YvKR4L;msEN5LoS9R~XY~UB8=!8=Co)3K#|_6>QcPy|;FK2T$Pjvg}he z=YIc9x%tm!mjs-6JX@yQf?2M3&?c6_)(hIL5zTX3HEYJSd_OD%k}r#~jkE;h*^1uw zkAofNIX!u7^4vKXWqp6}Jwz=>{NYKvt*-iNC=#c5S(;YddT9-DbjB!u`xMoWm@r(RhtOx?qMJ4YUijQu(>5L#pyMZtgDVy zsv%D~PZvqml#hKb%0_ZSW39cYqFj|r!2=pIma~y+04BcLQ#Qq|93PSTL=YEc0Y9Mir+LXH;(GbT_!B2Zmn7l|72z# zM5UFxUWKTfxD_m`7KMiNXkN^1VQX_L({a0|g!}H!ia7#~Tn|)?kFa&ZMfcHaJo?ns zK2x;u4ldNkgV-+Rk!z%# z>Sp&|J9V4uM$WSUHrcerIBXtn?_|1^SrQnmlNR#&K|9Sgn4WYLv&g)3?%C9R;Y)N< zit>|C`|-;~9gdy6t!@MLZRXW4(X_iEtOAO}wXCo0JcHPzXTQ270Iyruw z#pf7SF>d>Ea9FClBopTPSLv}&AH8r{)YK;y=B#Ph_eI-1(@kG9;U;OtA&>poAy1eP zAK$#P>QV)wsrO=PCo0-kyL@v#skv$ZG-5`T_qJJFENyb8^V1VnuiI_m4DZxOn_HRh ztgnlhyT_WJ)Qfr!#g*HG*XZgX8y8>_k|10lgZT*dKaqjJ%JHj{z~&&rX31Jo{@BFi zSusWUo3Hhl)^&-uA}2dRwR$0owdC0>%ssXJj~}~jlRmW1F01>P*j>m)Ab zF*#bdsgkfe*Q)wsy%L?))yG}D?#OhPw&M8{MhEtghpg_GtUR#X&|C1!&c^b43Ct<) zn;BcJkJh*0A+JJG>)+yB4$Ufjot^vO!ZFe0^6%+(_9nH}PM6U<$A9@B1GLA(S>zL&-ksnbC_t}TxwxtMhsq~s{yeGmp?I#!64J_mTT#Cf&M- zIieonIH#_cuG}$mGOw$7eD3jFx|lB&vC1@-;^dyT9TZW%MBi8WeU7>?!@+fEXXa4f zzGa!9s+5`;*4QYFoRoLB16esjvOO0Nq;oCIW?+U5G+&CkHElmG>C?Ej@Db>@ms&_i z5DO3wW>^l642}I9`h6VYF_hTMyPOnf79RGxRbE*EsC%MW(+Ud<*0SOqTQwPdoq^wk-dAs{n|LdMlSwO^$t!Ax$!;-!| z*BbXx#bp_kcxX6h>WIah>Eg+NB>voJC{27__{zR}6(-iHlUfV^YKupM)RYro(P8`h zSpL$<0E??wZxqUyXsH=Q;$6me-vdHPAu$HBg#i72mj6sVOYH`U?%$ZK zf36iEeyqjZVM`xOYs=Fb`QgxU72g#lkxjOl1$>_v%kb~X&hHHSKZ#-fdF%T}{%$`8 zquL>X@qO24W@iBwp>x*C*c^=gaU^Wt!h@`9|S`t)A*@ z&XpU^r{YT=Mmg8STB!a+hbYQPKsQ{%%q=TPpyHf2w&{V?VqAabozv9;RYRC0-up zAP>(k7?gl@&wc{{aj>?riE>ixR5*V=_4Snvzq`BZ>FEIiizQm9GH88#pY<)@KNs{p z&yhBK6C#@2HrT@{nA7*^-J*@7q?BtBQB06bcGSDuNwmf-pg=n@M?v*=+vf#C_ zJ@^-BfK>Or-wSj73j~Pi;w)R(fd`i##`Hcvncy>%f~;<557n3zFrt#XK#ITp(yKr4k{&!3E_%aBT6g( z2@=yZM2(%kAa#!+*EAp&S5q<|h9R`*#kE?OvHk;#qmj`0eL3_a$9nQR5|&;V3{>;I zu>8uE%xdkXZkvX@w;tc}yk1k-BpAQJ9Ms!%sc3LV^x4d>T9Pe2i?>D0b z?(gze+X-dU*}fv*KeZEu+T*ET4EFaD62R*S!dtvQwV1Ry|`3d_Vu zVvE)B1c%S@PNRqd0E7yU!~)%^wf@5LWt($A#{-9h1ET*DuCPSzi;4}H1yJ$9~27+)M-09cAG!Kaf} zTi3QniSa=}MveNb6B%09R#in;`a?@XxNs@sV{5D1pm zhg|sj3~76u$a1}$_C+2BzyB$~d%s&Ste-6XwWa~}dsjVf*JwJYvGtpOs3qkjc@< z=Vy%m%jxoK)vKR`5m=tr?wH=e*Nx}`V}>(s6a7|E+!jLI8gWKB@QYNgRa=MDb zpp`~W$VC;Tw(_Y`r@7X>d&&1zTl_Bm=T9!Vhpmb6Sl4Vazb-L{XP$?np6qaxlh+qd z4uEQ(9~e0pA?fvJwvdWdbIsc-Ak5zPB3wTNaPf6Fy{aN~17S(GrJpBet(-1D%6%1s zz0hly4NoGYhVAdkni~o4sHlYXTYElnWo$bWk+te{!UvE$Z}y9_p*sPzf+RXkbg*L! z+$|99{pwn7-D$uC(9~4s9q<4E0HLL$gZE<6Ng8d+zyUeS{Y>F`r$_a{ugeJwKy&slUyr1+;`Og6Q)7U^U=%`u5yoiZY~M31NJs_0wg2W%K`qXg zd#>JBT2y#o$St($x8{ro;Oy@aWs`ICUtf&-Ba;Q5&NyG6;IfSmfH^GUqlDwT*jsr< z=kHdj7}mb7vZcBA6>s+_XlHZpu&|FKX_i32!;5YnMnep|_!b>I4nZZvdX1L(1}xY& zor$!985bF{O2{8&$Z9yMG2nmuj_cQ@sS|;IxSqlRD{=I(-QxGA{2xLASALd-ZsUR7 zztwRjCaPCHfk4aAf>}2n4>yT7hk}2`mM#bTgTYn0Z~Op+wtfQ7qcL2+eWeTl4-&`} z3i@58FPJF(;qOp#CGx?(=~PU8^A>;rAX3uC*?susJFUGd z(lo^-`*x%?r;K58vuyR4nu_Y~sBZk%>w($J$!OE;d#|Gt-&5T0`yG7OPD2Omw(?mI zzQ3~Zxad+mSze{R4#eWMe zd{B*6Hn#0IT7Am4_lcfd!32&Ne2$R`vJx_RrGDmb2T$->oxsyC#EQ< zZ)F1W@p|d=>O%@wCcO-eoV5ihRFAA z_YEJs&UygAsd@|1uBMsS&<4fK2QT@@K(IEV`a9k`&L3zo1c^52=vhl<`;3 z?ID!(+1<6D_N0w!4biv&$JKgu;i9m*S$2mokF=Z$97(hnePUL+_N`mnf=I3bC?|(I zuO$z2oK051__Vygqlf~2IMeXif$g%PfxY)K|J@wX99^gok)-!9A?`5KJG61?_s%n( zS{dwx>3^|?maI5@H0SgBjV>=F2;?G4#DSfdpRYu6?5SJnn^5O#tNZ27(9jStWT8Xq z+b<|br{}{62q^SAapdUNVZa2+rn_xO^*+Ib-?ff5fYmuG$0hbo29uso2rGP_X%b9c zQzym?E9FMmIq0zH>y7Zu{%R;arui&MSvL1;+O-C!}iZpe}4~*!w0Wv2}*B z=8FP?{zi0(qUl{Qsm%e*F~#2(pCF$vhWn!k?oV26bcCoPz~hfkA|k&;Q+=5>M=Y>q zmGv~M?Esd4G5o0O$sHA5!Cw))`SVR>`;)^fRJ6&{Dke~aF6zZS!n%Plut~G3zJ~qN z+{8b&R@lfpCvP*)6IS^(HJDPcyX`ZEw>Of%)&_T5$OG%9$#ga&;%>G5{%g_H!m$$e zO0Nz8BV7H63VAwY-intBn_mQGDrW7|?(M+`IM83@H7NBal=qKM2}QLR*-sZ45%*la z)UX(dS^S=+Bb?`kB?-0q;gDe?oV7_e zRcmqNp8U0hST2$8j5xG7ScnK6c(IHd?o6XrklQm=auF-!4Fq zytsL=ktg8a`W-YzwF#J)5fx?&TI}V|)s@I%DWidyFPW4ix*d%*0h!ry`x3-YYtmOS zbef5#8aDR2=7W|y38c2MHp?L<3!)^7DBp^k#3Xd- zcE^<(J4T9Kz`WSygX2&VD_EyghXnYaBvdwMmcIHYtxbGN-@~nD?bW7IHV##M$X$2A z=%{0cW4sIsSLFOv@!e+^4eX2VzbxUljnWG46jcZy(Z{=kLyzZyi!t)^O z4hy^0@_tcHAuQ-W=C|6g*PH0El4R~(zp$*0SLKkL6IVYR57oYi&So@QSiaO=p~Bxe zPMc|_r59~~Z1_6~V)=`iO4M649Ur|3f5TX8sZZQU

igjpiJwv z!h(Q(5JKVYP(Ipaz=J4^x~ZQr!039*xd-6gn$2b3oDIJr#J$QV;cmP!VA4(Xd44Q< zkFp(qclPJyaIUrMv2?B~PxMjL7V14A^ToQ)Gf;NnFbO6iJ7Zu+{=M`#>>i~5AMSw@ zP{Z-Z#-GRy!V_$Xc5ymeK<_YRIL@2vEn%^yn0y#9RVPJi+U~Ap{Y9#MDWT#@`E*zD zQAZE1!P_#PjtcKsFV=8bh&i^>D=BB3^~!zd+D5nwugp7MPneB4EKfJwsm~SHQXS8T z_IXtra$DWqq8Iih%*xKZHLm&wXJd@@JA&r##Hlv|hS(&Pu!96x-oD z8dsB1Hci~HyyCQT_15R2<*0YfrRvr$wClup=ZxnHvHdxwopAqbq zC|#bKQ?^!|$r<^8YakcnTqQeYeSLZP?ir5wL`@#IFEfvGCy`Ah?$_>JM}dJ=<4UXy z2hRuKn1a+mx1nL#Fjn1YD5!VV!r-RMn|>@&NH)&JIkzHoYqVE~?49Ib)wp+g+^C)y z>A4vtm&EXy%QsE-<}4((bRGu~#Cc+O`=TBPy!SklVEkCk#`w;AFlrj%-*DQl^65E5 z==|IVI7aFuTBQ1sc_o>|{wu8YI@FRYo@drnAs`c3-ZBAvV` zvk|v8JOQQ;sRDTta#f3c9onSla>OfKJSA=iCE8!iubW2#I^_; z9%fl{DuSg-nee_AX?Hl?v^qlsBqXVt_Q@h&gdsF|@qlLW)c(}@zVsVEm|Ye_nbJWu zbN%vN^90n4igI(AE;1Y{VsX#H%bp^P$#FC<1a- zJmoUb?@;bqXM=Zm)m9X#0EgNjlH5EM4I6P#Hqbu0sTm+Yqu-J1N{i5YlwY5&noQ=*cOg~b^Od5`>#Rba&hhyZaEY=jg9jGa>IJT^+9Z{`t}WdULH0_2(DX zS6zMN#|_4>PrrWjXLlMJrX&FZ`hl6R_g(jQ(3woQ{ri7?0mK*XHPQj5VKb_`Rd$GY zmK@(|u6t5~ul;AiSZ&t*o16@?yYUQn5vrZfQZAb(H_4pB*qo|!hi1IHjb$25I3lzP zk1ly&+LZ@;@PakVaUmLrEM~zoquH1guf=hMJDjfNiq4gsDY%x!HLmxPSvCY-J zs8QuHs-L?^I407)nc0ja)fG{=fYvo$JzKvDE+=pHR~$aH2RUfzjTzr{D&2EO0q5IiaZ{^s**5gg$eg?=AH-mz_Vq`{7Sn~t zYVXm0pQeu}OFd4voGTpH1|=}5-YC+zs)!~!I9GzvEand+W>ii*n$Gd%+?*fbG+G&C z58RZVD!;?bI_6@UvR$33D5=2sDO6@sxE|-n%pD4UmivBbz(?r?4+?N_u&O)vn#5E> z1OFU%~#cTWMn8^{wAfZ6>>kdp8l!!7GasUSYo;pXT?-5hiFL#SMxG{4MK9Ldhv)K)Pie;(hga+I+wzi@R-NxQ z2Ce#UGD_t9mvg&LXsQ0#av8BS<#X|p*T!<2#fo!s4C}tLlB(RUw)gC5uX#aG+aJ&p z?(Tse_cZ-#A~-gr7(IST?B_S-@>7VFG?(zZ${4gB0;!5jMx|FITU*mi^J)XnsC3vi z_U#bel8V_K^ysGPoK z4uMyB!}HdM?fk?&&45Y%o!okFb!n-u_w7m(y8+jsDccsq#I$<(&G+!DvuxznqW&WfQ zHbF(@d^b7ay_N=WCUe-@(Jv0_u%67lx^CuFV_%$&LMD3P%K6M(VA1-*EY_{<=PSC^ySkJ16Lsn4wD6s>78MBbwP-a!>-XD{qxQPjk;| zek@U&N5uI`L5A5!->mhrsMdP?NK)IKNmGw!3I&2!9czV=Q>KzG`tb1r9j5;uj%GIPw2yZ|!QR58^K)w{adhfD!8zH93>&6%p_HIkh2C0*Fx34!zIxGNQYi5I{ z%mJ)VoLYas6)g4Ky18mOmo1eR9wXVd8h{{{Sf^4B1V@#3W`LZh|e(?r{uahx&mzN@F zx^*#eekQ89Op@R!p;`jP=bmxbyN12c`)OAYupn&@KV3|T@@~T+z&hTtvXST0%;>fD zl^N+KLA;;m?CdzQHdAKL=7019dfM}0tb<>O%-FKYFyV$xFcvL?zsZuc%2fhtO%Zz2 z+=B{jOna4yZw z;#uhO^LkaZm{p^OP8*CYeY9s(eE_Z1b5{ks|)LUjeFP?jvZAAJ4q7n`c0V&-|6 zIu}C|02wlGd9x%+2d(9O4{C!$fEF?AAM+s@PIJ%I?qt3ADDs(1j5+BTq>%~B=+MNW zmV1qb>d(5K=ckSr&F_2n`wDO2Kq3X4xJCPsm$HRuaSF&^*thwHph584LF)Ar-BYli zA~xOeGhGM~!Qu|bDn2TtmiqPy7GAUaJCFQ|MTFXdPfNa2AtoUceC#bXii!;NgqKNr z`DHIJQ4|NVvK6hIwNNdo+UPkR1*txGXeSaBxrCo~S7SbZ8Dpo(%>ev8I`cDgI6Ev! z3aF;f#^jS2x&dW!KjXl5bnh%WGOQ!-PXMv@m!{vZOMDDko7J}aXc;J<`+dx(FFZSy zxj`9@8DOs0d7mCU|u0k zP4-Eg(x4c_%kDGlToPqTrL}WO5#QCPhur!EK`4t-ONA?!i-}V6)w8j03Kj!;PS5+3b!|^mB64(om~rJ(6K(72G=%DBv0QsrHapT`7P=}!$M^;lCBt?h zd{1l*h{T_n zGm%Sfx;A=_s z+AyC1EuMi>ya|2%x8{3G+t_OYt+z-ChKamoOd%!zFlkTe{m^{ z;i*W%lZngQ+F0T<3F-f!sI!PC7fi+teV-Y%GO7bxSsE5HFAxX$iOZ|BF%iUe$sF8a^J`n_dnv+ z?rQSmK7|;UH1!R-mafxx^&HJ0~Ugrha97y>C;>aL~!7b?(x z8thsKLdB|xTt}jML*K8Q*F}(3e_@F$gVRik!IUD+ZO#5a*AbSe2T!;bU!9B1wnHo0 z{bU2P}=c;lf%qCSVnJLRX zsyXJ2gohWem+}H@Ks=jPR5$3a_47X^z02j$x&QbO8!{XHt;L-pVHiW(Jz`!qi9sX) zdsa#r1rV;8f1QGjndx@KS`;@nJo|s6Bk#DNVi7)kz2IM>=MOTh+uTfl4h2jFY3Nyx zbW6<*96YHZ+);#GDYNKnqlDJjBm6KQyKUe|ab*u-2Ls9<{PJUhms5yb+J>bPpnf7%F)QzedE+`d+~N+gL#y|P3J z%BH!Hsw!2Ff5Gb551V$}9<{nQ+?JpUgiJ46d)6^9NQACgSNR*N;B?#R&n69$w@Gi{ zXKV5NQ2mU-cSHm^VssXU*it>th5_s|?9T69nN#(xc9Huk^pf7F>^obZwQy{Kh?7t# z*>NIW(xULD2U4QmSG%x?h*D@+BdfUc`zV|%ipdrmq@<~!fquBD(SLYIv5ek@HoyB( zY(SM33=h}m4BM1ak@;C}PbOA@#O6BrAnl-K;xXo@y9JvOQ4M>}x3?go8M!GFe21D& zrN`wXS#R&PY=;)WHAgIL>^Ip5GhSPqYt*=a#sl&J2^ge>>H_;nymOb*Dpd+4;`vGn~UFO zN6nX#foyHINdo(|l>^vCG34??_NroGc=)&m#}oqjZaGLQx(n40{)U!%drGA<=ODae ze#PYbQ{?S;&>*V5xZ^OsFlrqxDZ+_|WYhy*_4)ERBoGl94hoQ454Gs<4l~m#bP7L* zRgnQ}6bh6xeTciudNd$MY9)(X@YS^Gn-_V0KxjN$A^TG1i7|oxv#`vZL>2k0kL6)s zO?B^*$QvUz%@$ZZES`G+7+$b32{;}ti2<3E?qHm-R$5!A1)oqI@~!}5-rr;T^7~&e z+ov7Yw_t@DGComz6Kufdx3RH#7kEZ?kQUI;Qr!iZDiH+HP)pl=o<05%xaq%>b^}mQ z(qRtH7W=r?r8%SXYFkP(AW#o#{H0w^p#@Hjv}QPii%6^ugDfW&NuRosEPlZF!QS{k;IFXY5&C*{r))q^obQo;<_o1QeeRA-sH+FPAfLG2IRK+e1x(a@THR9z5a+t&ryV$vvW*nfG;c? zrH=7P6(HSi7GqBWl@WYV3nIeBN5p(n6Q+V*iN1C2u|V#?>{rzz>If3yz8B%7qaY;c z_WRM;5DAZlCY>LuWi^!%L^F#`5vJR!X+XVes5WjUEtYVI`VNFz#UX2*Pvi1bIN_q< zI);d)zwt%D_^}4RuMmMa7E*W0659k*nJE8DL+;~W*Oq1NfHgr>Kcc_$(DZ!(3+w}= zw6sxo34g3Pkw^oLD*%+f?CZNHp^lY|c#!?e-^RuDS5M3%34t}I&9d8{Z*WHDKsgql zyc|zALcSspztTQtbC^~bhUt>i0aA#~vI=T%$vcp6qpFR&NNI*STU8U`rRvP@{zk^B zvsFu{*|_GurNY}_ZPa`%F_O)^z@HDYUn|7$^pma6q%SFP$5LnSiBzV%Kr0^_g9Ixz z&}sT8FoO>U?b%h?=`$=;xyD^sL&>24_0c5u8kLh07Pyq*qb*Cx9auwdo38#rbjiuU z&l!2&TuB&Y7qJ^a2>K)P(;%hA2BX;{0S^>2ryK_IJI}ay186n2&Uh^>%!o@47fMUj zq79`)bRBwd3QO-t735Zgq+{614=874r=$Wwol3#WPeNjP$v_HKp@^A7blj6-3|pKE z*vx8PS}2fEDdRk*I3TbzPF>ni4&*-tZlsjXp75H+!~Aul`j1c1e}0@$0aKatRy3{K zD_FHT+d_HRFMCJ##3->awaxS>RmoSoER;O1@5yMKS8Fx#NO0?FW?0f$Vm)n%I+s@4 zZl5z+A;&Fajr)+X$hO8_)Z|%ora*yQj z*=3B_eReB$VZCllDF4%dELX({AAei|V#>oxxkF&sAa}(&Gs( z4wIEH7cmEY6ZNkjmx4kUO#YwY0-Unmgd6JO_nJEo;QI9GE_-P?W18UdhIfnGZ;+2B zoaG$1u8hKp6D3*H4l_+!z{cGos;j96e$97N+!LBXBjlJb3g(&UfJdp(D%e8Vd!1kL zkMm2Lm!*mmeQ#Abt&Y~7cxqg#nOWZbgOx!33Mo{&o%o&TQ$j9-Zl(%l=uE8Jp!hl?gtV=1~=@Mq^8UY|d`QX3yj*PSgdHg}6lVgC;EQLE+;|B`UP{ z(^GWY0u$xM(usF>&KK(keGh7UCGyFao>UCNetbE2p$Isl9`Q&EUFn}&g{U@uC^i+l zETA|y-e6X#1@A!1CEn%YHZmIjkfi{M)x!0?OZm^T|DQxS#axX&yZxzP>OHV=Ce>En zvgeiFIrI;aIW*XOo58L0CXWr&S(#B)yhigdQ?rqJemS7kR-H#Cg_R~l4_sX>hvU&m zR#(7_O_HN|7sv_YU4WHKFkytk*3_^4Bc*h6hRJEjl6yIVv*TA9Me;y`#V1>dkatpK zgJzzh08 z4p9(PO`WZb+|$J?eMOHo2^gFy*HG-%TgU3zu(RoPL8*=sDejLm0>M8>kGt_jA_kq4 z6%P`>1<_n9bto68dhN~6tBC>m2!y;X$_QHnIC7>B650}!jA;2j^pbgGck2!^A$JQ@ zB3l?3MH=Q}0*QJvPg`=w`;j_C3oFy(ve5ItGIBgZgwv zD3Jc~mHQtoVILK+qg=qNY7RFT5rc@l4 zL~865gk4uC?e0l`S-TtwgSxe5G2)R81tLl)ELc>K$q^y0Fw*domYAhg)5m1w%XQre znr;wdPgS|KZ-vtcCjK0M;0CH3s$2TP{JYu!J6fb74hnQg-{=ll3xZ-MkTk_t1kunn z_mB!Qbsb7|^QW)rcI!rlomAO=PFhKQ>9a(H@>3|yG%F6r!~`dsU2IU*jaw}*l8G9! zC$d-hVd>`YbEi&}mZ0UmYYXU3_-PHd!Uji_aA+E%_^W!+duk6fiAKX+g_hNzjcXAQ z;zB=z?J{eLh4bNwBayx!+zR7@+mzH7f;i8jUvrNu`)O;*is=%kF@;W@C#t!h{sh%!MR$hf9( z|M^Kc&6MUCu#TWM_~YG<(`||ssDz{-qBP7IGUgbDlyI$WA!+C$LywthXT`S#BuH-^ zD3+G9f1VrW5Hu?OVA(91mtL$Uz>tWVtEJNIb$p5E(!v<9+`~;w%v8cY`KyZ^s7VoW?X!xy6ch#zf!ngHaHf@{F-;Y)~@hB~4F5(Md zwKFPX@K}jz$HWKD;6dpX!?->DR9M?Mu0;#bpmI)IuTs|_JysD0*rfZGdbjLhTu^UW z^HwO`Aq>cGEQ*+9`ck%fDvp_ChJEUXBDIN;P@>O}qPgJU*-)^lb7SGRDV&Y0Xh@`r9(=m#KF&0ksu)|3iU;Y&w(G_iPZhd<+rj^g>L6m_Wt#` z5IikESYQ+zQdUuVm7MfbhuldLtZ5jfBC^Qc$rF`8rVM{8wY9V>A_s5>Dv7clTyu^; zwd$lGg$VKw6&)6X*-9Z@Pkl5B2ziIvRrn!t70`yj0 ze*Dp-?6DnnSIuAZf7YmO)E4W}Y@)%U#U&gR%`x|IBDeB(09~T&fkwxOo7~Aq4EDhT z38B+bNq*z0!uY{AWD26m!1gZi`tr=-*sd?XqI*r~?mzO)Y_7M)a&D z{%@LX;hyiBqK~m$ztGGg2MxSUVx@wQIZ|#2?b?rDC zLb3A)7c4kAxk#w=8a^b%qy}Sy490lq%<$2c4v}s@m_x?MK&V32yp~R(gZ|yUaq27% zC=>7#(_?&=X2yA2``k;eCS^DM_w;xsHM(x!}%$H+gcQVdJMVrOq!XXj18o+Ccvv^wY1 zeuIuJZXzsY9~*Jf5ehkPUb`0GZ*&V3ShE3p_1wIxjv}S(r}>kQ0)xgzjol|&JfQMR zm^i>6BvRtxHO1yPO7eyC6Kr$&2N2%jlJz;jjcjH=?(v?!U6l20Kc?nvW6sOX6Z9&MhFBm2iyD|ii8G`fLrTfz=coFMI`$wqtXKB{PF71(l zFcPZ5gWTRg;b0pa>z{~`G3ia19u%f6(D0@0jUQG+x+JJftz1uj%OK3gFgUl5gZe!< z&GM~bw{Z&!%9fb0b4dvFC7XMKn%yzqQ2lYXy5Z2kXPm3FU;Ide!x1)P(zT5AUE~%SC7?gd{@>9Ja-bZ{A0*X&1}A z1;vclEv@~gc??G&CjO!lm-pdGZ)*yXUtizJh6Q&@bx2sro(~Fy%9un!J!nz5jNi}T zqnPn*6+eJ1V(4(scbam&nRxLQIzT9-AWRWQxub5{jFSQlRUXx=rS2vXH!f}gj!`ea z(QJIGIB1~vJV$guS@O87`3B>v_xpm0NP*a%(k?*>I+@Uw(a zMSNIF*;q#d;TRuEpnZ5ahf%*X6xe7MPamj`+AMra|NJP$!ZWV0l)OJkti;?EtwGM+ zt#fzYs|4pO+_NZG>7PpD4h^Rzdk!MIjpyh^SdbXh6+5qP}kT3XM!(prvj>7cT6@G(7VCQVC&F-uv8x2WJv2%wzsl9OpQ4^xn4pd-U-tp8@( zpj-!p(PJ(K!YqDVSTSo>cZ6nt?e8$y2?+5n-GLalC+c3KF306z8n-J<-USZ>ZnI7Qei+)K=n0FgU`v05 z0HKG=|Jb*0jTN#R4eR13;nwBF!3i_$Ps^d+W*4t_nmWZAeV^4^rL!XO5!s9+xbJn*DLfvK;X;5LLE$*Z4teWawSui+ZOX= zK}jr}5W~T=+{A7YNCnN0U5Zd!##`!X!WLi%Ii!`YodOHFw;g| zNKotCKD^5fdw=Ip%bCpo!^7>ITX@FrQT&*jzn({!e+P@?#;Mc)fqbCfjL-E##E!@n z*XAD>L?D9gkPQ5vgFG$s%7V!n*m1{k9@9ao=HaJ}niaS^Py0(Usoq9)C|-6br^T395aXc*91~U|_D;!|5SQhe3Ayw9x9>v3ge@2XQ7tL?iB7fuSVDrFb74?UZekZws z^H)Z2Y08DQ`@NO>WdBOcr5*pA^#^=U-zDED0^hC32n}woEBGq;05eFl83>)O{>3>$ z{41G-A&~zM61owj{FOeI6XZ2*$GszTKSEi7_y$_fM zlzKr7rkiz9!@hR_?$FA)@g5BXMP!)qs08z*<7MG1f=kYPbxnnd zL}>o%v-Z$D*E)Oow};;KafgRvi!Sm9WBMBdBvv3Gqbqm(+e`da6P@25|sD z2t(jIcBUN)^@YE|f896MnWW};_Yj^KlZ3X-K_4pZy*9zPx-A9nWW?-Rk1JpL@({={ zel-!CW$^tKP#%L6-yUa^E-|@`1A-1DyrbK6m}=98BUw^hD!DiCt+|3Lj1!>sjpp(Zl8Nm;R4Yckullhr-;p9px+ z6g@r;xp`L^V~R&4>Dg=`y+!D%n!tOhRL&#=*}tvvoZ!&teJh{+2@@V@xbV4z8U0}o zlX{f->)rg6@2!Z2DPo&4ntk7p=!Em({MPIZOLUOq-*n(Le4`p_)b)HwT@?P$zH<}vK5sX^A7)%Hs?N{43eX)X0sPHLsf6&H!^<2*} zH2`R^&R>Oo789`-=Ey=H#muvNP)6WbI~~!dPjvXL+QxattQM#3!hbnB7nm-@7956~ zFE4Xz`=A`EI*g*?5M^6z(U#(Eh`{TfMy#fC$klA&FpEm^$tzeM@^#m-wU9FQJ>@`z zRS!%tKfu?yj_8w7 z&q*?bguScT#n}hcqezrYy?oi4Ok^{bD@S*6HfmPudOwi^(j-az=?+n$XXImC9f?+x zilcnW2uZ>t+RfoExcDxV|G^8@!8q3fp8ImxI>&3S0VyjrDlJQTEy%vK~87~+7 zrlcURMl1x*X5EE0KW;`&*yyWCG{({&q($-SXh=|3d;d-S|7->sKy$AUi)spo^pbm( zQFTtJ51D$K`P@aU+&y)l9gVJmy^ci@1h6rb(1K561OlWKxVCfmPC!8RZS?DA1&Z-= zX&nOyEk>|C`I*KIGUd2jEOpq|g-S z3GoZ;GD$AY{C>9raWw$0iF#o!rEZUhgLjOrzXw_2)~eyU>6hH2(%m=t=FQ%V&}6pG zt%)FPG7?&^RjaRSz;{+lacL`V{&@!;2LY;DrXH@|3=SlnZKyX@GG}I~2KD%?i~;Uc zhBewP6HXLlu|x?i7X}I{)WZ(~G<%nFi-u}T%Hb^q(vPwZlg;vNRIUpmGFfmij%W#J z(cE_G$NE1<<~idn8z(2-HIKE=fib@KQ1D`*;#))ENcYezg@j^4q-`pQAh%v6}I3Q}(T!n^(W9vbyt%^&M>oD|LUX42#x~T!e-x)+=MXGEos9XMS{QZ#~5Z7s3b}D)X3C4S6?A-EK8XcRgxcxcHPJeiQ`}AJZPRajO%OO7W ztJN3f1U|om>W#Azx~Urr<06|I$tn-I@CEyj_ za6ZW;hdKGSlM~rzqiWBNm&l99XN?y2E8=%olUYMACMX6;&h+8`ua=+4TuO>Oi(tw zF~xJRHm0ef(TEqubK`CVw+pu?J3xNWa~B*2Bv4}B&9X4_M6@`a*yQXKrONTeBX4lh zrjD1(GEISyfr4ajnXB>NiV-+c_rK{a#l;@OqK{X-V?vfHOImFS9we%_V5yiS;i2@0 zuzCjV)#-1G_7)AL`$+9iMsq6?bDIe<)PW1Kspa{@LXNhz81e=->&B`a?AHjujZ3Dz zr2baI4qL8TKx!$yVmzbk0hHfky-w$+;Qjo+j{qfq|(N&*b%z5^&ED@+wD*+=x| z&+4N|!tVw~{SKR5mlF8x6zGX-2b__dFY#n;;MLf-XXWpC4+1#3*Oe^St!*#}_W$k`N`fkMBt<64twu6@@pQ>(FV( zOVeDlgk+-jQOqC$4yIHLx}fzH@$#i9NKm0&nC4q$o5<6Syo=gz(egM<&~qzga5LqP zj8Orde<)vmQa}R_PrO3L-*EV%Y#UNlN84F_GqXvKA7WY%Eh9KHXkMD?R~(5s2Xriw4GKC#}DC1y2W=zBz)>U;+N;& zmbi`!Wn-PGiFm#GaRXI^i*beBmP&P^)BMus#hrfFr+er_H+lfqUw_~_AKpTa_zv=c zVZJpS7WipBXUj&_aKo@jF6Sb5I}HG0=M%L3`yZ4)_={!_zf2DtNf0k#jbMx?an3i? zhNC&PKUp>VynGMwxW~!3X~K{&sD=+z`+7MeTGW#MeR$v!$=Ph+eQK;2ziR7~&ULdh z2BgaYlvEQffAdG>e|%q}D#c4OgmBl_n<+y+C{Dy|JTqZ=h99+WJJ9Ai+!o~R5kLm? z4lV5ly_ok^y<1)>(UK|!vGtF$TSHdlaiFWO#Hn(VQoAQkJX~$IjPw8<=EWX{0WOOw zV#XQ9RmE^Po5GHd?-ek_f4&^3XiQ4^fsBb0&E|N5O}3lkm2X^4bas_%AW=_D45QRL zY(d47eMfs(L})78msMhon}|unL&&N56CCQBNwRscD>u)9BxxZ$GO=gp1D(Vp!|vN` zZWmUbrbhG^6fc%`$0CC+)ZO7o}egOJe z0ugyiG?R0DOOOfBGsSXZtX;)c0P^PSMgJ`pg+gB z%^r&uX`C@^+D!^YT6^sy5J1dbgxf{<0X5uEudc#h0X0+ic-AlX?BRashj$*{(-CNI z2jLK^zhDNQleTfq;*QoA-&4E}j z=F?HiKaf9=dd>Px>18huT9xeYM1dSq07ka&Zb*A6yqTQ$Umb&(47>hDRquVe4pXx%{r+|wU)7l)iPtcC7Z+0P>x<+-*Kyp3L+#XB zs*cps`bnVpNU`FgZ^uiKVRyZLtdHI(v^Ha=1(~D#zS4|POZouxNu*A-Exfn;LV`(% zF3tZvZCWk2e@x2IDl3fB(JytbCtWXOu;GP7m8I@5OUr;S-`4G-(--?7OKqD?aCu11 zTR1+huNt3|X0du>cBT6{LqFoDpi)&#(y!jFG^y|;?vNt(H`6hCoKG3~=zK+i7`L$% zLpzOUmB$FvH2}tCOy7m+an$l_`8Hg-na_x0s*%%X;}h#D#Cr(T4UQh@lCqGm;BM;C z;3QwStF;Js!v;;FD*u8kBjQZ?bJEd9UpgMo+Kq_O@~5ze;|*C0sa+;{XAYZ<{p8ce z9_F7hZ4FjVas&RGmozlyLWVKVzEb?gkx{2kzl}Q*L*4X+5;(h$Ev1dYf9-adKs2xC zYTjYdBu$Ta$XMInjhSTHEdlDw3(CuUtrLZoe|4E2ed2{IP7KHL&Pr+Y&*tmeQQlg8 zYF8}cjbw5M(-S-mf^E0n$ri4M36jnC8vm|D(ctuKHB&2=Zzv(RmJ=L898 z^TV2c6z4pPF-W~I6YeeJAR(F^Achnp>@ZA?yTVg|V#`$6?5gy9L- zwf@bH)r-HaQ<+}bu@aW`ef3nDRl{5GGVFlr${PC!fRO)6M#TkpkU1rzx*Aj8_6;e-wDmnDGCih}zryPJW#X(27;Hz_UCDSE$ zYZl__WOLBhd-AY9+q<{>_b1xs{)d%ggGOJZyXu!8fldJAeC=p-n=IbF1qM6;OmT-sT zr`q2A?^tX|_~xR?XtNBOlY{Pdt_;_`i(@PHBRIouEuonPYSu)H1a zrj&?Ght-B(5(LJm{YO(9#Xslo>Nz< z1wn&;lvio;UQE&VU1A|TsjZYW?N)b`*~V8aXDn1#n@VRiuEu+U*eFhEL642|u;7z2 zXrAd!WNp%smxToW*wJ6K!UJ@_c3kzLf#++R`NK4Y_9cw5*Zp&)xw+j!sq%b@i2Dp7 zFRxj3Eb=YI{O;$^i{+!Z)-~8!G=jJDrOaue|DS*2gfh-b*A)X)n<4JWjS7$+Cp{N(}B9JxqWzEwTxQRE&07Nl3b%3 z>Y{w4J3@2_x8ZUNXHFM1`cdxtJ}qXqey`GZzJUQWVU@di{`tHeYoV>7&B;^yu1FQv74Wv}iX<%v$d`UgXG@q&qxDK0KnIh&y$g70Ix207xQ~& z*3W$FN6`8l#wY`|nvH3C?UZM1H+Ei1MT^c+Iw|7;tsUvS!$;Y|C?PeGmEExc>x-Y& z-&J{ghi+eU>ldvB)GN~aL(xXDx163UzD-h7K;Oe?_4qqNeOkuF0s^Rg9GxSqG=~n7 zxF-O>s3XsF>pVP%c$Rws^|sPXG^X#q%zXM$3h_q^rVTeYSX)80-=!yQ&a>J_62p?j8}BsTc<)T)?@ z#@L6uh`I$G$efgL-up^?(`o%Tf!oAum27QUIn#~M)v)i=AET7rU$>f}1B%R_@R}gcjJanjqRg z!@p5$)&w$@u0KUuYtw#O{4|~*ts-Hg-nZaX;DbCLTY^mv9bn1Yy)4;>97z^DG&*@I zT;OL!3Fer?sx|Qm>7BkPdY{0 z=_}p8Ep_R3DD_Fkv7DK*@8yF3Aoqt%jyz>gb5?lK&*PQN4L3>cCiP2ExBu*lIq7ex zm+~__3(~^>SpA;fgHD`z^E+C`QQ2_YZe1t1T!#x4 z@4Oxu{TEv+Sd&ZQtl;!3p_sEq8a~Cvz-3d#3O+|GNZ1eUZN}~Kr)`}j zvPu|!m8&ysYE$<*MQp5z31p#kLI#l!J=;^$h$H07epS`deAnqk*#Gbi?r<450Ag3? zRkQLgAt^(fSc{8|Pkewm6t>6G4^jl4L|_o<(*^G1Vh$^ZpO{aCYvBd1 z)ytISV$C7cG=73OSbi{6=0hzhL}zzSsL_*I`t>Uo^5`kW*?g#+%vtN~#Ej3sz?PQA zETcuM2)_ZdBi>SH0ljU6CKNyZIAa_DwYUsrSFv_!UCrO68;;rP{sQOlEND26b`O94 zH@{ZI&uhL2$>pX7x%LYEU^DTpxwv3(<(--moY%#$9J1&H-lxWBkr>^UP;mnyy5>1_ zI}3u%{vrAvte1u@aaCg|j4xux#o6;BE)OsnhX54elP){4VM$)r z^aBvIR8`_kBlK_U%8729jL_VOmrBXtQjM!sDoUY=YOTty?w zq@hfKB!)2b6%y`bK-Qfi`+iew+{R*|7a9&TW#oA0Qc~-lgu8eBA^E2mSVSpM<2mLu zz)OBG8n#EBL9viT1dz^NMj7wB11S=O_hFuOBy%FOmeswIteNm|BRfQ{5PpO zQoZSsYBITC98~1sTP)4mt>dfEYq8K^Rk_CgCH$HSy_iEw&F($c0()U$K%q2C-QSvm zeKr7Kq+g&3spo9Yg1?q@M#Y>Qwa!2rbN=6(3tec2L5Y z)skAZD&iua2?cpraE@7`r{bQwU&s_L1CXJrzRmZD_Y4iC_WPSOwkw+-lA@aXGI|+= zzn}v3^05h&8e65@=5pu*FSAkcFV`tIZPv|ZWkdCTR7i1DUJ~#*R-Mxb|7ml(7FLcQ zq)bAR|L8kX$}$JaCzMNq_*Nx>=J5rn0y5EvYj`=DC@B_%;h)Jp>?H@g8c9uKsPOD< zBep_LGE5EnBrqQkVIh9XVK&b%56^hF@ba;R8k(s&QP5DGxi<^g$ z&}J6q4xx2+&|Db*~~#vjT`sf~QBK%=5(^YUo2+$Oy5z_1e|yu@Cikls*6M$0KyI zDy_5n(rtREk=Gc-zKZWg;_FUt7Rx|}l8<8{5!;{(7}?v|%-zaUug#{V>3~v>LznNh zwxm?e$f5b|cK;o<*~ACAnLI`sC!_jN+`GwE z%;Norm+sKzNQtHQFD7jcd%yZJnU<|aSWAjhs2uNhl2<|mZ~9X@9OYTN=ah%8qK175 zy!-GcrISTmYwiUj4ZFeI(o`v1qVzNOkj}m&@=L;1USV>5*LMeCULz7f=A)>pKtNSX z$q*t?#b8j-i9mMQf7Vfd+k=wsJ++Mi+{rf}LIcW|v%2Gj5u#%nC)3^t0H{--+*DWx z%wkeRUGD9PUF5ITr^ln5wtk(Y`CZQqod^4Me|JDD#(PJ^uz?qp#&EkY-Nr#AUwvNp z+wk^0a8(5Ic+A=2D9U-v8M~DM7Zj2lyVvow@ID-rGocPnms>O)T|9t)dd%9o->ecj)>1OHj;mBX&Pwi{0Hb^LWH~J?8 z!rlyOwNi}G0Q@7qnsjR`lQr!Y#qsttfe9H0(oOGBCCl^z3ty@$-i67!3s?TX_~w3sNMx`gj)a zp>Q#gd1^A-Gnta0C_bd?uf>P;2n=%QoNh(s zJ=Npl@&thF9;Z@#K;);+&+iruo)Gdl{u`d?iwGxiCry!}3#vi!Xap|0bWLs2Pw^YWyRb_OJil z@e_8KdPU|zE1MbZf1YM;u6Su5)-Fqs^!xsvXZ>N|K}Wt`0wwk?D2FZU+Xw|a>(F1N z)%Bp9=8g|a2xKX;jjwGxbL+@2C*1w3uOztu5Hg-!&O>-i+Ed^^M8eOr33rMrW?A^f z{LS`vS$_mGa$qy-3(S`%yW>3Sz`SU3dw(`S#hg>8LkDO)W3-Kh_NYX39R{5rWcAgh z(LE_V3a-=pOx^B{3g(m{cT7ajso+Hclg zJ#&GUtuCUP&uO?8{aduWMSNK66mOG>K{XX#e1=>&e#mQ4-}DqiUE_SaCn?Cq1Qy5W z>H~h>eB*_Q@KWnWPLxq@%fnQ>wji&U%!3ghog3ju(=OK}-(ZGtn)N>UmbY^$e}#K? zq1>13sM&sy@!(8oEsjE(`Ow;7r&cnnRrdXf8E~$zZCf-I`d~%JNI!cT^S;rwKMM^V z@i5x=XwCHO!v<$ZO}B}va8_K*pXeV-{-;Idj950_#1Me=&r?4s`s9sWNtA%E<3e&C zE*m0L&B#Xne`WIt3}fZ7@=Oi0ueW zX!32Wp)x*1ciq6hm$forr@-}>2h1N!+Yu}tm*s`AF6%-(IE78Z~aK= zguh25*>N`M_kq-0?sWZtpOb1L5co7A&P0ufDxgxoFRw-+2oEE&YpFIg7fckua>zR8 z0s7SpYntU@_RQ5`0m_@T!WX0vDr<3<&gChjI9%h#99+vVXm z-S$?az#@nrO5Wo{V@Bcn$M`CebE$g51Bdmq35!4g)6aHL2> zKsLcXzpGI;G5HsSM(nr7+7ja@q2rzj(QjAbm`2TYZMSK3yzpbd;sF=pu4!OA6`jkW z#2L1y*In|IKaaSPu&w6rXxu}t4hnfLob=&9htOp>mW zpX8cQ^dyhbrz4u2hQ@|jZ+JjaRa1vH9Eygoc{#CRTq2N>vgOLDEZ8|D1yNXG1Wp4W zIcob7^F4t8nT(i!xv78Gq78=>_r(}%z`0V`5RBaArYo0fx9u3F(L)QRRr`)-FYdqq zbb95oSz?GMilUEgE!B$X4dx;BaR9V)CtbBq|(#}36Vv4tNAYait zyft;trB1)avl+B{OgISyd8kDU!1SM3e+uhcGxNXmb$E`^mhtl1S#qT%YdvqWD`V?( zyoSIEaOD%C3PVnxC)inO8sxA?&9{g`FswzAJ2%l?u#{-m&Ax^076}AXugh%or6@O3 zu>hz}e7Y33O*ly(yU~e8)$%`pE;C}G%tufNcfNsHzMtkhUR=%0%p4u7`;708*rOOe z?Tv-SVPrXR&s#gshoM`&^S~Iz4y)yCS+_ZU8lBXI00KlzY#ByBFz3+{Ngz^a*+@+C z@i<;Q7csPO%R=|y+be}hty^Afx0LGf6@3WKuX2NC1LcNof_jUizKfUr;U ziG!-m&%*m)+|UF~>YD8;`*Au;Ncc6)pyPU{-G2%*%en^X@6Zj`xh0?1$pOmKSMn_h zrum~XcNAulO%*ycjqip3*dTzfg%6{HNJ^Q-cNuI}1R}|QaBmO6TU!wr%0y=j(vrEgDsX@fO}U#WJF3b z%r~m9`Nmx6=6YZohH__^{Xq$y6axx&5yXUYJhyAdg=#e!u)@vmFSf^p9&Nq6_{^2k zv9#@)3N!cn1={7kRSPq0VI-O)K95xg$&S&#vP9bq4bnlT6zUeH*vIwKWoQlQB|t0z>ZZ|c#v)^?@Y8;Ol5+7S%+7-dPDq)PhF+nS zJS};{bGFyImDqIW=d$pm&%cJ*ZL4dH-t0;RJE20Nv}uMdPFoG)eG=%UF}=^H9csqK zy|cKGnbX*?Q$_-l6|2mI_3RssZ8>Y!zhlZ~UAXsr!5!`y0#ettZ*L{(@ZeN1H$q`#V~q{!TD3#@8 zyx~L2Y^U`nrQqU2O)4gBy(7I;z9j|aJa4|_E|2p^po-=F&$CU<^78gx_r28vG~2wc zn_UmpD>K(kMBqs|xQVJDZndO#?f+n>&%t%0+AdLzU!Eupt0XFOS9&qm;UFhAkR*J5 ziIbIxtIg>{6w$q268AY?X9~r(`$;eBvy;)%?x1`ZFE&8QP= zx6A0T;_Q(#8p%ns!_eY}UDN*4ccX^+%{tuc_rz$$5%mRC)7iJ*frki({$2GZlOeW~#$OpUFCxIx+TwA+gKwmdo6h%MJ2qhRk)|PgdXgk{sBs?x7%n%rAM` zynTzKkO`8XH|tmd!3PCJl=cRNjB9A$xa-HUNR#S~JELDsNj|U~# z%6oTePUrD~cJ7DSjT&vPI~!XLMALeMW#>WCoyGdzL&|rA1$Uto2bB!d(+78*d%s5@ zfnJ%gXjOWi9*6jRrKA~`D*2Qh)soA6MXK`-k>ry(6l5J`~YCZ2D%;77JhTm3ERb2TG^oG>Z(7<%XES@=4`T(U6t7YdLbsTBArY!s35$K#T) zTwH4tv9_Yr&J}+QOR)qxyXq{6_3Zdbd{+xVx11!l#;qTo2{buPLco)cd2Qnr8eclX zBFDfY=3RPu;?fD|6iNFR+3>lKtVDHIX44xc6r=3VzvU66pv9YqQO|1V{vNkVYyk&qnQSU%0oe@PW=Y1RwF_UGaPib zFzf3_waa@4Oi~VN7Mx%Z_7FrRlj!q%J~R-1*vor!BO2{j^Db?X-uw%QOaD&ao5>oe zu}ho7XbwC=?6wi$D^EKKrNTpcv$P6o1`OF;${O*Cnw5b2_pdxTnp6f}6~BIWAp)J_ z^unEj7J;z|vzEVjk^Kxa9PG+spKDYF5|-DYJ@1*@7K8JUvAiEC9Res-2@I;(*bjNH zZ6rKP9RKF!kuPzJeR$_85r&4fGzy!yX>waY|3V@cAVtmeA#7@U+*TEPM|Q7dJ+R1H zzMLM3Q%cy@QNOvnN@UV!lCI?GUd--a@SrXhU*lYJRuTWdFK}Y28y~FL9MK2txpudT$Yy z>O##)qJ8J_AVQjm>udkQpd~%hn0>I)@W-it2jz|TT3o8y{G9Le*5;0EUuW!yS;;gVju-y z?aKw`#w>1_ZX{ir^95x>snBBS#8QN0TF>H3Nfxdl!bh)2(@3%B8ts&aPN9~ssLgR$ zPp7Xhr@D<0Z_$>s663L}%Ihye#|NSZji1yK^gEmW3e% z%|5^0n6b~#OTP=bf$`BoVh9mqV`DqJV_ojusNY~=otxuj^2%3(ZIndc<3sj^p^|8Z zqEv?IRcmdilMdcndhtzfpvn|M&v|PB2`_Yl=WFow{&EI1jiaZ9&3^op#2RnbOUrJS z&3j4xERWX#6v3;Bqm$PRCWe8sjmH-N@Lc!%e7|zZ?m+4F^XWu({H1X% zqP0SB>8y|0?|h8VCfa_W{woA#5L{yMzuIJljx@Xn7m z3I82od5cj&e3$40|1fpt8e1~OG<-PaLjZb*!r$%kpu3HC6BNOZdTXk_g|q$-+y3vv z2_(T6DR;v2nSDGakgqd@b68RCHy`EeuS;F$;f|k#X zP9W6Do;|5hp1Fz|K12ZYwtdEhK0Wpg@oM`IB5jtI#|R3yc7@B|#W-TlC*%Gvm;Nq_ z{7L(k{&zhLD|d#US%Xl$Sd3U~@r3TT;)tL3q?}jZy^VY90j$0Pn%{lKp%|Dw7rF3) zJTHeGFE+3+@TdH*rNXT93P2}>yUUNeBjnwOuPmz;k-=EZ5CD3*hJ8lieEz`sH#=)^gE^WG5^9wLE6UMr7b<+D1)=D2IxiG$n+bS{C*Ulew(-FeY- z1S`VxqoVMm?Gn)fWHLH!|59w9LpMS31K|!)5XCGq1m9<-@6Dn`makid&R1|)k@K^& zoZ%^>ZyMg~`e3$<6&nuxxlv00wc`&l!{gGtMOB;%vDPO} zE%P#&6vgtmHxp%Z2y2w;peZit^>9nK(OC9ndo}KV%jYty4CTfDbyASN1rNJe5`OfZ z-;~CB@$d5G#Mix>*;#_r@|$0>at4p8So+~;pjdzHdJ}ID-wgSfD~)5zid8NOpTkc@ zsfK~@&FDMJRe;X#pQ+b|3%`y~p=RM%c@eP~G=KkW&JYxM@+WG4HupI`9Of2?i<~zG z1!&@b!ta$$NkJj-cvM@aQTbM)ZMT^bG<_W+$LhG|?L^@nJ4HCfF4v}lg6b8`%!KOS zSN6e^UK#$6_Hjjm$AmzI3J*^6+cQRmoIxj!IK`5dYxqnE!T*<=q1u2osIavFbp2cI3)g{DLNL;MGzIN~|04y$O) z)f+_D{}81f!jimAH>ry-qBpay>25O`*uA$ef>6W23IE@RRoKGoIC|$**#F&XV6*tN z(1VC2+-i8PG1G7s-|)pY)ZpnXun&dV!#4c+J@2I!~T(ouKfp1CjqzS$LvQjpe=uvEpk>dO7C9P5TfRl%a3YA-(=+j2w6aeK?kI zjp2FHCb2WYd;j+ zjc_kf9R*o&s~v@4@u zyz;pU*XDb==JIUfzMLH-&$>-{0OOa?lU$}4fXpU!iZmwFobVz4_@A`V#p(Gg%#lrN?o|W@L`Vap#-8ytgN!J&* zI0p)k9%#NJWJ0&vyd^(b>P$@(>rPM0>78$kFRcG!AUYg6Px&3VXJ(7nxQOOt_d-XF zk1&~S-Z%C4SBTkG4GOrqEKH1l#9kyY7d2QFuft9f2 z^9irf3M2k4rxGIeTbK`3%%}h9DdVQ|Oq2cGd+bio;#U!q_ShVqRm1TFq9 zA)7{%?c5D9U$kBN87IU!Zlj%--YG85G#T5|b;T^9e}^_H&Z{T3g#L=5OtP!mwgcZD zQWTPZZP&0}!>}FKx9Wwhm8{Y8$}rSa|Ap}KRcI3Xie=CS)6-o20IC=_<)Dexfd8r7 zQJtCYz2})or6eOMtqizc{Ca#4qNPRuZTUKJgoFz8zs%|Ts+agryTwJL)4rS4D)FJ) zx=rUy8NWjS4(XN`f9^71MJ;k3uH4#w%J=~Q6d@S*o?2z<@QKPtY7XADYd-yoV)~bd z7bK3_F0riKu12>x4!gwG)BxZprsbzUNB5bm4PNZ|tK66hR!j8v>@wLl+WjM1yMsLg zYl!EQlg@Hdq8dJ?(V@m3Pc02YC}Fa37gfpIBMY zf0Ql-feLhImaSYhXJ}C|tJ3xj(-=PQ`js|%Y62TJG`#Wj=vjkhU#bJ^VVcIxn4-TO z3YIIF$NhjH(eF8_SwW`8G#M!Ieel_K^JYN;;tlQe?cK~}ozMx1kaV3=BdJiJx-L0k z#%l`=(p4j(@;-xaeYb7WZsJH_uQiioXmmWO@WRRvD(Q$gHRCI)$e>rl?+&erV zpt7_vA7xFzKuzf%1)$noac;MbP6RNZ3phT$!oue?NigZ{rTfG(i|xGx%nG744;WEP zz^`KdFD^9UgN4wfE3Bi&ifUkq#~D*Befx}j5TPO8#Zpy4=b9~CC2zv#%BI0mS5QIW zE~lNjh9V*$T>lW}T0-t^M(E8gMP?MQY4fmGY`i#FBUWzz<8z#emm2_|{A z`Nw~6>Ghxh5ri2jMiZ(6OpN_M1pEmw$oA+?#7oMF&ocEcR~C_V!Yi)E4u{BE_0#zu zQ2Oe^!e)PDj{UNvM!msv+hI7Os%gyV7sM4Gm^-=C*M8xa(ANL z1*foclm7hzez?@=h>BI1YibxMvV7y{S$@O%X1kA`)zQ9qve5mKKXYL^I4C z-+xMZTBJjPfY(Hdvi=?h3s|RoY(NT_m6{L3u2>{dOdp$%Ky7ya{+y+op6rK3>O$Oo zkO{xK`Jcjj_kRlS-iD@I6!PVc?D=0c?KS#kV;c?v9$H7Gl%~tpo-_p#5TNd3K)wS3 z{5%;unXIq$dH5zN42YyZjS@$Og2Znip>%E@8vz0kvpapM^}Xs1)Q43skW+^75pB00 z2wDlBkzIXXj|z~C)bVIbF&Z&>g2faCa>Uq~-V&%69KKK5k(sA+zMS4WtYwWexQ@l#W#2*mCrGF-M7=VE{0A9Nk zSx}eQr;}KEf-CB6FiJLZVR?&aTH}46Dj3nk-0{vi)sFuR%liumDd(}iZC-T}Y^e{W zQ)HCr+njzC3eQa9i*wk)viL$ZhWi?^>Mx@YfycTq*voQL#9CE%F_@DZ{-i2hw@oc}=XU8dIgoyL#SuUPRMzsW$d4D5F9e_Q8ZnD4Rf@=bjTiaotj zVSzAF2Zy#Wr*`!$XU@c7U8#4CkarJ$8sdw6-=E3>WZ6}h43ZU_aMfaF&O^ijoj+Tk+g*$F37AbkwFBv7OdyrP@IORkNsb)1d{BRs&Y zx|gTJ;zacSFncV*w+iM-ZOiCir%kdNV|hpJSu01D(BNy%%%cecQClvsQ<;AAN!z?% z8RDH-BkkZ$O10AO?0ENpq;9$XXy;p7nszVk}1 zO-{xI?y^z4j?)N+O@i1D>X={!FU%Y=5XL{EgM5ElIBr;`K!JX*JEBcbi2;yLq&QZ= zT^o|4!1(iPws7i6PSipMGv)*ueA(RZv%8?BtOn5ycH;$0_Ex3sU0fEBxCVI#GgRbc zUU}K%u57K_H}e&Ou>v7tpo(A3WmD3{>(bL~=&l2wuol_zjq=)_ zd`N*Fk?tBM=nbxJW$lc8i2~~%OUKz`SHttTrtvKyD6w=hgadp_M3a148X*^`TFN94 zuSi)?OQ0-QvzVTsCi!n0l$wQ+yOzgi6WSyV{KVqux@)%ud3Hau*Ioa((BJqtGxwtYQv4^%l+HMX@g;I-Lc?! zI%s*&=Zte94$2;7Ybs2RcR}#c$t1St0G4?*jOZ_z`K0zv=#+K}HW{5zz>*Krhg4gq z2b9^3A+@CQSw9Qz$={@knH2Wbv1)xs|0DeQ5AFt!4*D1XOP$Cm=8Eg1=n?<4h!l>u z)V66Ai4=&)4C#@1Cs`V0tYpFiHQ_ZbE67PKLOr<5$RzX{)Ir2e`2!!&C%Z=m?-$Np z*hEc?6$|I^ROL*hURCgwvS%;b4)x9@3_MX^@Ld?4ZA5KkJ+ zr}_XLw$t*cT&>GA*@JrL09^!YiEy36>gs_NxR(Mtuo3*8lz+k5lu(o|yNayRL>sk3gJ+=(8c(|ouKahJ(R-mgHsZLZnw z8(QOMed}vYE7x{8J+ueo#jy|@PT8bA@e#BnL_JU_9Dui&J1$aapWcM~7)Z?_o-&-@ zEpz>A8->>T<15n7OP3Suo#pb>=wjB=^VESn<|z`21*5toS=i`TQag?5cq6h42yweP zOmDxx&_rZ63(SkFvn@c)WNu*b5u}0h{wC*U=qD#uH<-E!^K1LtR_v>5v2zav4lk@~ zyN7rFnbUW;7G_=oU+v^|sy+pcoAE%L2O!f!6;{E536>Pu{WZA=Lnd(0J*M+X`T|wN z&u#(CmaU$$`~H1-rr7ccKZl+C`O6vbg21h&vL>SiW68oEAo0l(QOUezs=uFvPKQos#6f{cMT9T@#m7E#BvIx`KO{x;z8N%1isWy`jF>G$h z=#=jA?*8~_IXA9Uu3UJ8%WC0*_Xq<*-)xqRI~&gr5&CPKtWeusd^~X+p!ZuWTJtt| zo#`?B+o@{IwczX4bGM}Q#%|1ZZu2zRAhrcBu`i*QXsencJ?RIl(nhJWh8@%K%<~1M6KW?l$h&IchrzDHgVjnHnn>;Bd&1u@odCA?Y>yx3l z=-1$}3hT*bJM-GS51NxVwudw7gI0VnT_xqB$Cl$nuQK8!tEx6bbuN3YB-h`=e8rldf}M+Vz9m z=9xF4cLngwZ9eQgP46N?gA}T&x=Eq{8!kg6pf7wW-DF00d$CSH!e5CA6X|VeeXQ)T zFSSBECSk3bBkE`E_dAmMPw(!ZW2oPG|EwFq{FVV!;Y?B|aA=|yLit&-@UT(WpTk&L z=S_-^RY`k%5;;WgRb7%=O^tS7x&x8;}bjY}#uw2D}qoY|hg)2mbG z1m%leHooso(q+ggy%F1ivzFqIrk${uu#Gk8#3GaD;%{CSftrM` zf8BTnJ8$qr}N#ZCTvPN5oQ z4%7#w%r8YAVrJfmoMS+hGmuo4k~F89M&Uv<5lOk(H~aS1+UdvUmB%M5CevRt{+Q#H zmlf^xE`zdnvt|bXipEH`GU@)eW1ESg(HP$q)>zDS*zZMi== zF2Z*_Pb&Dk5lIAnF(Yltga_{dgdPy#-Q;>KMEBihhH@y!4I0hg029d z$niOvh9nf|w&q+ZC;DviiM+x%VX&t8tc~BLPzO{1un?T!w?8v32h@=dQ_{XSNb{itx0O42I%y_&+3kj8 zS0UL#n2QNlkyIx`}rsIH?5U8ffdZ-Lw-sVbGI$t2Wr73v}qc337h zSd&X5&Qq88yiI(Kh3nav9G$5FxwzW6JR~wyhT#7V=Y5b?Y-MP^OAmo5Md!Jiu=05T z;?dEvcc8JYZ4$>GVG?@NNz#Iqk>Nv8^Z30Rs|DfiUK54)#RpbVUd2I-N-Uu0kJv|F z(2oz3C?EXCQ!gqLQs1R%5NC8?oI|}k%z2aPf&CW!Z^TX(PCn+R%-2Xz1%En`AnT=U zqK(hRm3=Mm_i9w^7qDf%Tek$66yl)lAe%JHIbI8@iB;W9_n4>y-COKMaOLY*AXg`m z7Xn`)LmKSo{0jBT<^Cu{TaH_^XJ-yt-X*}# zg9AwOe=|}J$;47q5dz-uxxSw3G!xI+i0{#&A`T&f>zLEW-N}To6Iq>(eX@<R=*zBoOO)K5D7VQkh!Xn2XC>1f_-U{50h z=6^CVS{dEZKl~9;uwm=tKeg`!=451eRXPh`%PcOb&vEda+`T=aF3@JWnA)X>UisBoKMG8mZbN^+w0oowKZ&EpS7v100M0! z+kwk}Ray|#-xzHk1sjK+&h(6&Zw-V9@aadl-IuHK`30(bnsw41v&wWRBB#nj<$=WH z;cxr`&>wKxkq=z6t&Aj`Rp`Cy%(a*Kv-5+3SB@Ny*3!O<&3Aub4Crw@~|fh8i3D}DpsX2t%d3qz5>XKbuo&9N81i1 zF6un?{^HY%4Y=;Rq(Ym>>Dl*XY%&!I@CnTVU4?Z|%A+q#kB~;&UN1%Uf8hByzoM(W zoN-N_-F3{I^n{%L*orP(Q42n^*$)oU4W#eONW4~vG#9~ZCf?`%$$v4Srdm{wmf$G4 zo1s5Exsn|bqbrsKjfYBTclr9a4hQIk%67e@i{`SifUJZ^WFA)JwA1T^7n4#cNd=a{nHj;VgmbVA{?y%Z>2X#(!gq%UDbXW z`Hb_0u%xmI1e!{sy**j_GDt1C$sS`}ScdN+GP6`+Ui}pfAx{96;E}WFCqzvN1PXJ4 z45|Ks-cWy&Mzv5g`Hr+?Y}%QRUJapIQv`qhF4D%1-#5JCb0&e1wZ0SBAwfN%Tb zhIc|K)M10DH2B$w@8~FD3j77>95hUV(f+UPX?NYy_2AO0Ne_s6Rx7 z--ba>FkB5kzeK{|{(IDO$0!slHG32@0Z8lnasRuThF=krw^~X98voGTx^i{_SL#%* z^+s|S{R!yh_o`vclJ3HRx@E8neOI=nD=CwMCV=qN-$qU)&x^A)H=`saW_j3si- zrv#;k&tY2wV1)TMpvgbTLSY!NLN0w6G)j~w0ifXKM_$AMrte;&uqiv>vCY$6)pZP6y*l3aMPf*OCFh#3Ski+DEWHF#a}i&9&ZFHe*?711V6l!??&Hk(`}cF^^|igKIn3ZtzjO z1~}J*j~Lin$}P7?W>_CrO3kgL960&N>atN<{8mOVHy+PN?08(3ww(|a-{($(OS>Jc$GaS2P(x%sRH*HJHw_^0lpJq~!ldtxO~ zsgghqvA%9%K=w`8;Fcu7^6)iG@gl`1c)vjr&}WvysQx^ols>q5J`dy}VE>_mp6|jz z8T^5YXvZXl0cO=UYh0%qoDl*AZy2@8>kh`Adf?biPd9^o&f&Ql<$v9rBi#!$t_C@l zt+WDL;}UJ~QZYaAmQtj2qlCT&ff!TM2!G_-TkUXd^t@P9^7=_4FZN|7?%I%xb~CrP zoqfF+l`d7z2IVT0=sB!`n~kFJM)|}08Kt?N=315T!f7`d^$*$u`BVT-8x|b^W6v%- zJ&7l&Ab@rkwGOb| z>;QW@)OZ6$!j#CVPHT`&%6z|oq{ykyd(WwjF5m5R3Y&yxd6jnDPTH}l?zG-}=RQ{S z`2#k^ITeDhxFUSlRPA8bMD$4N({_FAVx;#9l}gc_(LuXQ((-sAy9A79(mDVJcTapl znd>Ypj!(O5kR?rP8@KH@JSM0mHic!m3XVUh6!Kb*=!ds1FyH z9;G)f!zHz|Hoczgixp*>x|;d)coMukl7IpOoO1OpUuEm$#Wncd*GhaapL{zDA&SS2 zNnq%kXAwe4h)tZ30MTyN%smj$-0VjtG%oLqJ6>?8`mCZ5w5#`TC3#&Qt-&%;G|QJ9 zQ2_~suR)-hIfb3=Cn}LexO6%9L;OV8g@XkqBIYK)o1)TvGr7yF{ZduyN>h4_^pDxr zCqUsjvS|xUrX9*?L;-fU26z84=66Z%Li89&t;yhc(IfKU1uJIuL7tz^~7YKQY8~pVLD6;UEZaugn0{o zwIiI*DLWXUrEbzUGa~^FV=^HAjOv@)z!If!LMz{4F32&wD)}8NK}Yr{QzAeJK4aSAN3U$F3rOwXtBa74+v%yn3XX2y{1!C{NInn$VO zdtBT!mUM#)9OxZv+8~{+(JV^8_;G-%h2wY!IvIeC zM9kA~TDw{&XGUgiyy2nW_J0X;33U8ZK;wnoJ+M=?)o5$gQYZvl0Dbr>tf6@M;ZVEdw(jmHwbuJ36uZeKD=y16>{@)Zr3FAi z0yo*{ws8Ni)`g4e@~uCF`pSQP#{f|Rjtq#$8YD#@uN}87{9Oh{SnAHP}aS_`Pr>v(OH?UBHj0g_@mnm z#q@Cf5P=s=Z@gF@41RGq+-80n9rOoO@)L-nNB4_%+tDBSi(-1Q>aW>9c2=%9CcQPo z1X6$qFzH}!P@1~)n?~F9en>&#;zefn@}DF&oNmtP;SM2g89>RN`i5r1(meZI9r0%j z*gq59m~x*HqBK!$Q%Z|zg?WCaq>`57R(8lCBcPibkN9{g-QNa3C&{Ju+BxEDoRqv& zTJ%@4AWhtAR`Eb<>OtC(OvUb;gb-%qD*V)w`whZ3KwD;9DR+2kxO!M#4QyG_fnZ)q z=vd4=WzYLFGNHK@t643d^uRRECiiROaq=6eENy>(vg4YcX2N)t8}_4L`_RXBcIqCV ze#CLZg%aiqoFAdo^q-a5{oDS^vPb1#ey_Uo_@k4Id6O{nKL;0hvt)_|Rl9cK-yPQ$ zj`5b9#Lw7H6nd{;$_THOsT0PaqlHWL&nGZmexm9|-Jrq0|1r37i3FKnQl?D4>n-c* zT2zG}SMD2xyJaRNHR$mRq$cN$t1xg_lZQx z^@E}N4Q{XcKG0JY*+m*l2c$lq={CDk^043(+7Qe!AANQ!Dev{QijL03a-qU!jY}5W zO;6i?Pb)JP6az5|vuk{QPcoBzv%~|JG8O)-wFGr`+_n{T>|MIOoq79)0fP`u38;+b z?qR^Id1<>>EnAVKB_5=ia|>4NkSq(Njp+-W1Xq=d^~>?nL*@RkP&ZTYVV;piFd=?D zaeeK3q=j~2Vh}3RQ<3Si3R|@?6&lw8ifM?(;wF3V^P0aZ3dgf@hf`32inWRbOMQ*L zi@aUNT_VTSNdBva)1EVUdD_(9%dOwam1IRo2`^_STnH`ipV~y)Li^%u%+}E8thi+S z{oa9^xQ3Ac)d)1-v@kyRl3+40`rs?$o9-{ZX@?rbF09ci>^bJRfHeU6ZAaPt_exO4 zy}@-ZLlO}t6O)mnV{hU1(dT>W4HgJmZ| zyYqjr0N0gQa1>}!t|ins-*JKPrQpuTzYi$Y$AP5Js;jG?C&Pf6`hPWLH$S<;?W!es z*9mjY+qQFHdc|E>H6>bm(rCw2nn})3QJ^tpvoc|PxgyBGkN$Cc{=9efp4BHAtNqMF zJ6c=bE3RSHiv=x8;c6DcLgro#|#4@E?VTkUAl)K5|| zL0T-km76=yhOU1+@M913lF6U<(ME(fHidh7;2rBT+8fof8q z43^Bl{h7J=vk;H3k|r=_iw@ca?~FDU9eF?AohHL%z^=pFZhG%d(YmgfIaHCYn6y4x zt4(@@$-0^<@55X)f|dxfHCnj(PIFAQIMfVE@A+jHuFa!8g2nlw?$+k}KeqI|tn76F zGvLaBw3L19A0A#-`-}Vz6AMz4K;~i8bRgVQ+~rE7gYzL%qI^thRpllfA*%*CQEt*% z!FC8GY?~L9`|HAe%+%XT1{VIoaW9XP-4LbX5xFo8>i6iZ7AgBt?Z0^0)dpQefM(;S?B=0ib@B0*99xcOpGdy4gUKN*?mJ+#~AAbRL5Cf%BK@bH2 zE-RPiGHGmvGyK;e?s3>=uk=$7n=o_zrLU2ZC>#YPC04FBupN9VYH2&K`T4zWWha=B zBNe=(K^L^KJGy;sE-N-(hZ{ISZ#jLIYipg4ms|N-TW*k{L8Zcf831y!>W5wplG*U0D&K%#*KhgsVJn6;|3F8$McFm%cY$@A&gVw1%_gdIH|jjxsAv zvzPh&P#JW11osBs(KTgH^(VIuoV}T)`|a9ySHpVNAP&qJePAqKke`5KLVCm2dK(w` zi;IfZIZ!~3q1C2io72+^7!+~@jGsa6ZoYWwVx4o&Uj%l><{Ccg+12wCFQcbW!tEwF z04@;+LzkkfFdXa6)lpRYJjjOn?;@$xSd*#cbob^Mm*y(0u8=Q{PQ`eo0Ap zrzO@d)Bdwx>5~f#$Wi+rl9EkxT@SgN+)6jG2GEqI-sd2}phwsK8a@|%j;r(YWHw8z zcDIbosO)czonOCsJ&;4~>QG40nvSKd^^$zUdlPRrq%@2l6{1u-~(Qq#4<_n7lHbPAutwn#_-ek8#(iBB!mqKZP` zi=a#fq{a0wY`x81Ha50B+kE|*SAz0J{CAW0$7Nf+;3zX7=?ba)1Rov`Pfz>mL`s9wmp7D0`!}{+1dM1 zZNI%pGcFjwiPxHqXMOa0efk~&ukoIc>)Lcrq{h&LzFi;0E$zhC%wvnqK{(BlA7Hot zeA3=?R=fo<@a_gV`sB+$yKVLnHJtXReK~{>ZHT{p{&F{_{1EunrYtXSTlrW*zXbE@lMYEa(Ra8{;5&5Lx>oqyYg5X@3uD_3c(!KjRUXlNV!~=4qiKo}SbB2t@>v^s<+g>iR zfunY};`P!P^sy$5yO*j{%cQWzB_A@BQ%u$>}X!GE3x> zW5S9RsG|``?TZYONhEqSJw+VzdKmA$%k_SZjCXN&P#%fH^lioUHv$n+x@2^|yNhNxZXI?SPW4R3);N$rHBmo~0TKZHCV_>4DbZ=P z2NKa1>TP$*3OPNT`_vnG+6Mnj=10=5(lgi+F#yfh79|s|T@lKLaC-VM01>;Wh#n9N zkwi32cWWdm& z{GO|&eBS9@%dH;rKCILmk1oNxz|6MY(3l&27)=FzM4!NxND`Sf4tPGoXxub$EXnZvejA?Y=~peD(-3l;Ueh;q%xo zt?|)oag7RYX=!=B>WTKGc;#Ey)t(0|%W9KE?gX};r`>dsDxg>hnPGe|;C_d{f%%px z9Av?o#AZ3u)7O^`f1ueLxFq1V&ua6qK|GnSnGDe9?@zHiW94#>@!e}5z$hq@&(f{~ zLkr2r3aP>$P=C@_b4#xI3C2;AP(R7c=hL}M>r%L#?KwT z3%2cEhqIOF@K0XLek1NW4p}{2sYWZc=Ldi`uN>>SY)}sU;&9h`vAJMQGnU5Jt?PMK z_`G9MED<7-cKRHj@Svr{HiSN26iZ`}uF1IFX6L!{YISZr{cV1^<_M5P>2dANuWz^F z{dn_s8qMqeQoCXI7v@mBZkuOglJSa!_hlk1qId+tHV^j6-k9=C{lwGb4i!YK#ewzw z2tMZgMJU2PM*u-O-%-{ts~y3?Z`zbWpa#EBt?s|*bS~zr$V|s#Fvh<=-Ve&hGw8(3 z*4sw%R=(kgB=X_BSZ=Ck_*Ak@&(FD)`MXm8L2MtvyMF0vxO%MAi>9`&Zf4K1Ext|6 zYrO|xZLBvip5oA}edW!HRbC-3X2B?38)+PQ!qjzB)c`i3YI1C@3gLSw}-- z>a==+TT`p#z;VG|=i!j&YjdpYgF^N4Pd<@eVq8xQo;yvSHoA#!JPuia2`A42(wyj$ z1>_!GLTe9E+8jEORaI3lPkjVr9@Xu=Fr0mEpex5{S2-|2j)KSPdS0=|FP1jYbo#=W%~r=*p}Vi@_u6$128YO-@%UH|vg9TI$IO}XO-(}}d zlZLJrdMxtv~uxa~DqRakEn zuFKL5=yxdruj@%q2!@E`{h#`vfX20V4`sf8T?`OtQ74kVJ6MA9T?AtD^Urgo(^JDm zwz|;JS8wIXCm!LLyppd4l`(oYe*F z1ms^DLsY&g1C(=#Z(4p{U9aL6_tjXsz_sNP!EbjY5+!*bqqCTxMSHo;j<5Cf9(2Y# z5#^2x{HB_4Xmixm&fcwFJCKDC%GI(=ulp;Ezx`XsInLCGyMNuT;I#H_3!+z4T%5e9 z|82iBh$t~c@)pF0_t(aHi45q^E?v`lZC!Rj-`76hPid*C`FOeA?wy@Y^1g=t0RAe7 z%FRxDRvvl#mZ0AS%e#Ou#U0=cy)Ey?jpD^X3MFaU_LBsJjAD2`Uh*PB&zq>kPoIu> zW#=~Hw5L$UTt8>+4~^At@3j}EzmXPESNB_$dq-@TMVL$iSggSDzh&6}?Fp&Tuvh4K zrT`HGcZHAMTIVZmQP`D`)jS{x&j`vT{Ox;uZfBk6C+M4q?rMIo1aa^)x9a0bW*0OZ z!qubWO`kOKXaaOYG{9hRua|hp9j*Ek6t2rU@y^c9ylLH!x+8~ac@@57eAXKuPp8*w z8+M`GMHhZB&KB-l=3qa}dqhM5UHkn@?HNI6Z(v+jNZRiS-7Xf}i3HRfhdrlk%8fMP zuG@#?C|004QnJ)WE3 zZJe=Yke~7U%Vrv=3(8kwJ&a)zr07gxW#*cHqx3Oth0K=OG!^BNgvb;yMhv}^R&rvb#1dqwjx ze9L{BAfN&SS?(_MyN*zHcwj+}m}Qt7z<*E;yt5Frm+52(R0=AxcK<`jQ;(XhQH zn$_B>|A$CHjtu`{k$*nyu!g^V3xs}vVu47)B1nGFc>i;81``lV+ZCF*L<8g>D_N^_ zJcEjl2Ed2}5uuCuIjJX(a)wzlA5Pu`j~)0^{1apS`|DLen)#M>W8opwt`N_c_I&P` zG5nv~uF?apz9Vk_oWkb~9+Bob1f;w)$m&0e=kHalD8@K~@s)UCzdTLN+J#7({tYp| zeEEe4&{L|4NlK)sZ(zWxO##9ECi5vdiRkEz3Z&>Eq%JU2rWAR{<`u7W8>uW4O@4v} z*GbTWNxkijr?MQq%q`15(@f+tgoGoYAe=-8^TL2b^n4AJroP3LKtnWUN1Y{->m)GH zu--8$fX`6hH1Jx;u4|>vEuVF#uq!)jt+%|%<$bxM>l+bt$&NS1JuN*oR?#DK7e{d% zjVOX2+_WHFELxNKUtG}4>)1Vs4c8f8*5pRSToarxdfg<(B?AV!sXQ?(o9mM z{r=QFE;x7z_m~2hhF4$3B_^Jggc?vji~QUxLirJFmCS|?N%cd&X1_ixp^x+6mQ;xg z50>B=yNr@^uTQjvK3Fb^2~dm{@_Tq4Dnj@wDzZl&D=P&p`NC#{p;Z~1N8tnN8}iax zR5UKSJ!<+OK~|n(i~}ZhLQ&sz5z-UXU{6vgk{C33@?6_`)_dy3Hp^FEKWsW-pv}EC z>M8bnAO%Os3qCkc0Ri#C^#8CAq5bVX6P=sAP_OvFey`nr z8%w|1K$WPu;v{-wy}XLrxKt!?mhyj^pa{S;noH&$aZU*{y}j1V-}^)@O(=~Gsx*-r zldHniz%xHlRfnfU0)~wJ$c(B9Mj*!4Guj%-=B;9?M~qe>QEYcbRd>J8@X9pML$@Ybqt@&b zRlxRYF^^Ug)}vGL6;>hic4}eiOcd^4{Q9_Lsj6AcJv6}vIr{rtXw;1|>#`AN%-`oS zhGvom2b@3XvPhSV$-ixG`f3RzXs{3ADMzy>X@Yyz$ir}}+eY^`a%LHN{n^lUp~tx4 zlG0Pfb^i)ER}6Y@hY5#1l?o4~thhZ*u!)S&HbSk2ga}wOqYIs0mZl0_yMSYU{Q)1M zDOb(EA|(>W(LJvjt!SH_Kpqg!HKwpl3KnD1oVNJ>Yd>D(mo00x$R?fgNSI2%pm7^G zsI|+23Ab*0H`K~#I$y-{;mqY1EINEFyta!d53MGmAxmhm|3rUmqFtwm2rFX_Mq5`2 z7oAdU!=#uLIVU^QRP*0POuxd$R z!gK5H$4YX+Ght-M$Xk}mRs9(rri+X?Z9VImk+ri+rlm!@EsC=lkW8D+ph-yoQNu`Q z;ht3%Q?h`*!BJ$NZowE|z)E7w2l1CA5n$XLwq+fm)VGtFU{xLb6em?XU>P<}Q-1OB zaP-0nP6M2^X2<1rFx3`L7~i6k&dNt^TprH%BQ5EDI?HuaJ{CN#0S-8>KT|K=_)Lv% zWc~-M@=SwY~kHVuDpa`ifUT9WN$Z}dDiZUHFcZXmgLQ% z-#z*R3zyP;)4-9O!{0-aME477_vR10P}CXyFpD~Y#8ilJh|F9@!%rEt5Qynqzezts z4p)&_B<=LU_YnW8eof{-VtkgYc(XW8+47wh{T!7dq(J@hI_~6Bo#Z2nuCBPFDT+wT z2Tfq+=~c{^*{ZkhHdUJvP^OSVwl-Alnekg28T|VhG;)(%-=_;1Zcj5w>R@aaOD!i= zJ9_#ZuQl4iBeJkg8q|{Y5K4X5BUEkJm+Bmxdaq_BDJRBHlU_}4sH!s?o;3WjMfq>z zdw+#=fVUM_wI+!>gwJ5W!Afq!?ShcbMnt7dJ0N4-!kcPkqcimx@+Yqw+2#wLvbtHR z95|EH-q<7?*a8ktSoI%{9akcbn#|LVwXv!o0BaitmCLF`Di@lH4)|k2?l|ZD*!G>3hT*sdWRn@Q zvcfiHvA|$k)w69eSsXMprn5#|{Ipm!w7KvDwY{>Epj}o|ubw~4zbLVC8LX8Mqf}a% zNvINLx1CS+5!S!NP9z8S1MxHb_5!+<&juklqCJa@jXw$&KXXpqbUORB`I3S0O4MNM z@0djc$a&DvF!Dld@8TLm^bXd^0}J!S#U%%cMQ}`fH>1xA5`U^hHE^V0v@P zgX0iFf`^lpYPXQH(c_ovl+|%kV$RW${uiT|!Nut7`YZC`lGt(|M?}$l)5-O(r#5*~ zopksAh+s3sV5*r|+Zm^En>cR(2IJvH&vp^eo|fRKN2!$zSu3P7Zp3eIV-r3$mJG+> z%`EZ?nur8jCRd_MYj)$OY|d8|X9Z*#4NvH7lmYb+ly)4iY_z)#(M{N^vE#USqKlPt zs?pb9C3}%(yK{>XlY*;kAo~XbT}r8K!Ogm8Y|`Vy8~&lYZiAy52bI=2)T)faA}U6V ztX5vZY@4_mV3P(Vw4#{rAt_j`;}g4;K}cfwXi<(?Qge4bqtZ^t?LV#C$}ZG$_mP|1 z`WGv7mZtxpCzp@ZqN7ErymxS-8d_pj#^~IlgzRirjx33me0t|Htq=H1|7pMRfXVSw zr0h;Aba?1-Qh%!&sKd7u+Vit%LGwxq_w%x01!qWbk3O}iw5+c}Ap$lAU_$i1vh>Je z2HUI};md{pgdNmn>1FTzWvZQ2O5PM~Rn^q!K2kKsfdQ-}`m((pW`UAj?q|2m%zmf$ z9t{;gJfJ6jRAkb%n7Pg(TWRjAaT+1J8~R1gn6I-Vog*p_whF6cBB5ChafJz6Du6@1L+q8`hYXvJF_w8%2d7-Vhqrv1W8(;>;xM+U3Q6*j z4Ei<7$7OkYOR2aK@1iBE&B9W@hy1$AJMcePfS{4M3FhSR*6p9Z!xue0r%gG0>{W>q zrf^#@#aUnyRSeZ4J7znGH-ypN&4DE-1?zk9PeTm{xtTmH{@13OxRa|-ok(bNQaa~{ z37yQE(rZDl2XNMBFk7JBVZ>H($YAA(2c=w8u8D{|L+eGoR53ryZG8u!7+?RysKj7eGGkiB$vWGL!$1nS|4x!GA&RjEwtm9Q*gQ)XJHud~T1;~&(?MO% ztTn`2FmZaOLZaf2?Dxd<96F1gO?t6PR-Qg4`RKaIL3B&L9BF|ZX$o*9Ev-&&5@BIt zVH^ibT!Jq!IQa0jFqE{2Oof!wpIGEyMX`;E zao!19};PziIQb$(VFL1&zQ9* z#o}@F1gN|X{>M8JGoq zHfazK|KGI){eBgrzeJ?Gf=U^OJyZ8p7+?4Ljb-moBQGvAG!|ZZh)O~=HL*z^wN;o9 zzs}L!Gh@3N;%hN}KK&)^0OR~21SfnYy(wd;6@m$@>Zucw7jtSSG97 zN?xQs1kouVO56)&)2#B=t||h*Rt$`W7NWYCr)QN}>8p)1nZYq1+|RJcrWgi@4p`wH zys$FsZW*`N-=ifcm1PxcHe$bJ$9q>Cm}&kh?_ES5+5l4w{wj+l)jY3@DX0jp5!PJ_ z3Ms46v9c_8+7f%+iv2&sb9@U7FMW0lGEF)wr(ScMIiq8p1~@~M-!-F)2p1Q<4(m+v zR&~OosPlf2mJBW$Qx{hp&Yxsy^`fFx!cDBJ<19?(a?bOOkBF}Kjl|o3(&VTL?^#BN zP-x7ZCD*FXa^sZv<*ZS232)ZmosEcyi0^YCDbFm4<`GbkfM?7ojY9e@W-ZA9ty$RX zxC)Cq$LTaI0NL7&REv2(qKkpu>y@^3m$Nf50(o@S`bFm>AyRVbXt`8a+Ev?(U)z=f z{-3c3CTAiYKpAy!>O?E38P(MtM3I>wLg<3Kr|4({&1fiD>s>gQd{l=Ab-LlA7GKM4 zTXW^z;T3uZbjOi{xJr#Fcvw*+DdSN#mcNbY7&Z2$;-BLm&U=Q^)oN&2w1kdq<7)>h zW&o~>h|!#71*+y*xXDf|ayRGMms}MIqv?Z4)VYhhS8>5T7}J9XI^&A8>H_tnKjMqf zF@UMEcNB$O`$IbVH_J5Ljem)2+jLvStuxz@5>YoteOCiEX8vuy_`7f;v=C)~jR*|Z2(K8(&xraXT#8Vk zRg$-ko3LzSv(GcW7(l-(Py_qTnea+W20m9|pk=3&Se=(p&6rp>dLT@R1Tu?=$Q9?7 zblYajZf?ZrI1S=m(s_5!T{bR~3TLwB*cAS6jd9@5Ttb0^jmZ@g9Bg%Wp_;dSKs6J? zJ1!4a7Ne8km^t<$J9Vff-!dL?2FHbm47jPM9S>TSts}{r`HFy}#7*lsu}41Dmt|;x z%Pi-6lmsC5u0gT^BQUiV>Lv-?^IQX_Vs_Rz%^ZBz9*E&mcJBT%>-oXKUdldXZW&U) z=+Fj|n5$(*cn9;OSEd#(Q-4X0(2ey|QWW)w7;#`?;ULMfBW>JJt9Ijp>wXt-{Gp@W z$cvDTVLvyL)fa<@D)!?pe{a-9lKl`8T%eO&S$Io5 z*~BH>=QZ+LTvWcN=YQEty9AWo?yvMU*4HH}e*|kxTF4HQOHU>Z*o?YrMLYW%ONZSV z{B(!t5*55zbH`|=H#Cg4&eS;Xoed7q8ejC6IN~qaGLu{ifBMKgV_-N?$0B(iSeeND z%Y2$nda_zXWc`b(gf4C`edUbsU6<5A?4SfrUSjs@k%1O|d`Rn|En3t_Lb5(y=G@kvXEaBR%8&JPn6qnX%%rd} z^w&sYaPiSfP!oG3ZdDL-Xj{@6hXi}7N*1phU7{GO*g0S(+9qfiTuQ4%%aQlWC`$yC z)Xrv%jSdc1|2}D0jJ3=A=~x;|mQQ79r}P_9$Tqrpccd+SVfMj|RpPZDJVo@$S)oa^@=N zls)>%lcN)9<$kwVl7a23ME+3o_3X#uqa%PP-d3t)g`*%&jE1NM!40$kpzQZ-`&Ct! zSb){eLQd>enYBiOi5P9jE@~8mIu}M2Ega^MHJ!=KG*=>ky=^m%CoS=0RYfhp^!Nr% zG3biba+Fc@$Bz=ZtckD$+;=RRd>uCxTHnSLa5!6BecX?N$KpH#k8g34qc6bqp+H^xP-_tzl+F;YZf*#$`_ARR{*Y^ z7`>#K0{_6~SA)T7^vYgLG)3d2A73LvnFU6QIAPTfW3l$H69D@Hjop;T+rK|;{zsE8 zZu5u~Aj1cU@3_XJ)`-1hsq^WH-OAZ<&|LpPpm4V#IgB58)c(y99R#?v@0%1b4SUa6Pya+=9EiyPj#jd+&elyv)6bohaZdN9y7sQ>UB9ZTP`!_}O=RO$bRe%jk()S@Goq@fISP$aSpD&co~Ql8o`HH1 zUB3@~c{(LI=O8~S1wP6^nV^+U@b-(G2CJ+>nx~D|ywpKQ!PHzht;Y>=2ZJK+SU&u5?t(@76mf= zykVh~)QeU_ZyqFjhvjA*>M?$DGLuurgeF&Fv&#PRn@pACR95ho`<+ox%7x?{gs2+C zqV1Jvb}T0P%c(kdUr@*AdT-b+IvISf4St$83zM+y?t1i zvZm}dn$%WdQbc8X*t0vh_JK+`HR6hh9ARm4_2%tvqE*IzUOTCK^>x1gu`$7w3{i;Ws|YKo5yQ|VO$tO z8!Xeif`tCFL5rYRX(U|s<;(0uH(0hmBCRdg-^D!e!(|rh0V~@t?oXn@>jvj}qL;Yv z2oA=0v!Ar;KdDycmlPNh36`u@UeUVFeMy;1`|yF)_!ol~_Pwo>dE53LuB>|7h(I)c z+z%TzQ>JzdIfjG~`55U@HZ1GSEx;GK2wgly4l24n*VT3`w{c z`HalW*T*E;v(!0!`&b9~?3}JVfMJCi^?brE*_WB0R%D_mY%RkkkGZcLw;h)AV^YB$ z_QehbFURS-}UuW4iC_lwJ}y{qg$r&>oUJBUm=)( zAIqdbpwBYK$?gD->O$SdT;~3jA^Feo#SYlE2DvD5T^iJk%y+^?gai*P*U}lw&Se+H zsfI{OJYEq0*XwaMG7#I~=r5N|{XMb3fAd-5Igs*}_SUvLnRP<8|BU#*uADtmDfeHl z9YCru0^t_RXm=L{Gmg~{{}}*qUi13zP~%=GqMNsP?|gW8O?@~*T3K#=VdAOSxIMs; zVMzN+Ltc!-#26CKh~Yp@F#i?845%+DH;*CVz1T!8Bo}^BQg%!PFw7J&GUf4BatRoE ziD;yg#R}3@M^N@u_P>Go*D*BKPsX+TCdT>xartrjeq5ahrN8sdBPz+9q8I>A777ZG zo4U}f=76#>|MRQ8&XUr3!-$Ai92Lj1gvYzSDRrA4tC2NO(U3GOzg=q*z>QuSP-0Qe zlg^2M>GG@kJv3laA0#UAdykqo``ohums^k@FV$@KGX}m7ct}^L{)@-o3j7+*i4PAE&;-K9;vh12G?gRsn#178Hbq?u;6HI~!&;Us8goj$6W{SIOP7a&gEE5N^lJ z%>cS5NJ7(|RN(;{r~L;u1^&A$0e~DM^=Bb|IUheKtC`y0;zwC(c?jzzmv|dPgiXZZ zL($CwC>IV8Dc5_tJnt4JdN_xh0;1U$#BkZNNCXtbtaKhdG`)g>PC4VxiYzA!_pUe8 zDaiio0C5_Lhfl=kw)AK1hmh~XSu!%8GC;wco9sM$M+Lzl9wj6!B~T_Bsz4GhlHf~t z{k^-oyT7e|2aOw@K$>5HY!Ij;xFo>4P@<8ynQ2~Zr{i9&IO za=uc}l}Sn5t2rL3s;Za1FDJ}GL%(<;1iyETWbl~@)@_zLxcO{vPH`LeYa*6bQN&J^We-SqGe>(4-fnXo4E^c{+D49gM<24=llG}>-d<|@_kp?X@O*>a+Ss$nqiJpK8i1H z8+G|fCRy5OL~N-5YBX;DFEIKtL(u!?UqBqM_s#F_bpTE880ngtauy-3(i(Or+A|Fn zyoU^Uv=y@349OdGIs4q{w>d!`0xql6n#mb?*?N3h zj=*Ub_#D8z3grOQ31Mzad$|EvQ{)Pw4Q9kvhb3R5K>)cs!$!)ENEh}m|Gc{L{21Ae z1JTpfl@-Ib7z3VM+xg=YEFvx-j0@sQ=O>jX=Y@7ny%wzzeI%r&+xfd)hn;~6?hgR7 z!p6s8>av$OLV9{9BPqsksCDb6bG1aRhN`g5PYkL>{bzmHg8{I0CMG7Xv=Q@~`@8ea z>FH?zb8MUkZm{A!Cg=nfprQG*x=N}VB=mlA66v zP6l~MZf6MSR|DynIIQ}`0oV|S=K(Oi{0c{2a~$*yO@&e~7KE4c5QTxKvCyD$m{ti_ zB*5W4x_U;c#$7h={6dA;NN@7&Jt~_NYI)gDy38lV=hH(2&~_sHYt%d-badY9bNAOM zsYt#Y{RY1rztwJ7<6hiK-9^T>#NMAr#<9>fk}b>vvt~9Tj?en14}Zlc?*1<8$;-=#_lvk+zwp}}rm;9U zoVEi+{7-8+*HPufFyAhRXffO`Vk(wvf$5H3zMK$vn{9`0525JQl@z7XK5oWrX(r8Z z8v$#nfzHEVF0P>j=3DNtMSIegH85@>qaiw;3$yzOt&R2ty)>{`+#|bX0KG>V&8O3D z24zk*0PYZ=3rSKd)AaV{D*YLJgMgiGHC^4ulZA%Cm%EHpCD1s^-3K7V4dr$Qh{ z>x5_{>uz#VI!?c|PhBI^5NzxT;Brre2bBPIcsseuBzRBg?)X6d6OhyvH--!5OLf2< zM7L);7tlb53a`s9SpHYbQU(}Gk(mB>_`x5@g2B8fduhkdH+qpj^bF~I3YIj@&CTuY z?c?Y}P@28BXnMz+Pj4SWz#aRlj%YS)X zhih2zI#g;X4Fy)Q_KcfTz}PJH{sPcv!SZ!(3{d;d(=og>1d3OeYj$P^=n})~J96OP zmN@AzGPcNm`Y5v(;O!c0c4t?2 zPj~vdPug}#r7LpbzhxTt{8{TsN(2la+Qjxy((G>qMq%GnfN5rUK33n}F6X|Uop&Dp z4uv-H=^!M_=K$ikIXHM}qfur$Pf~B)Hnsnxmo^dwx9Vtd1c}(>Ms@jA0#`Jnh{JJo zKdN&B2c*ViN4=sW#P#Erdq$86NioW|pHP>*hOOAJ=I&6SzNi)#7i-nq&Ub!;14oFW z#?YdQKY33t#uX`CUR>;O6M{I_ry3l3A|)XiH#de<#RuF?cPGuK2HwY<&BPH+E;jw) z!&#<&JyE{CaD5O%Q9vL%{_jK@*j(n8#~8F|fTW+|l7p_)X~ENU5BeEkm3m6HY2JVA zCiS3!X19mZ11K|p(?T0Mb*udW_t{o;UELvve7AcIh5um90KK+vLLfGD1l?g2^EzqoWiyNRI!#o1ZF_ z2;nlP%Uo#%gdVUHOT9pX)^Gjh#8s*B*bM$QKK~OUbaF2%G@x^nW9Zj!Pi1RV@R)An1Xq zCY;QPRH2~e2&tO7bwqs35O~0-bx_L;Vem3G&2kPJVf>V$NQrfueyjA`%tB)DYq4}V zs6CMEXNVLB%X=CDGB@qus@iF`9{Y*1=okdli?~o260!l}kAwJCwDW}uklExz=SFga zF%0x7{>|rCiwVG8(hr6*?{1+YrPw%cv%c1k5QH6$ehl+Y^LEp~9TLo-pc|49%g@+- zkfLr~9Bv47bDwfXq==VmP3^nkNd9HyAIod%K&!CBIP_m>D^<(FWD8%0oxFDdF)G*A&nwoGGt;@ZS|%=E(-ts? zr*eFKq@|1f^OZ`Rx^P!p_fd3#v8gVMppMNlIjcwV{lz)ryNrD8*c@i7q(x?MTz~R+xvW0+P>pv+`8V#6=W9pS-S~>@*WWvHX_;S&3mWd%Dl1J>0OQOGk z{JZ%wNbsqcozoqVP}VtayLcR@;1aDdEqe2h?bNWVxYByfYl&D7xC$s^!iN4B;O?*Pj1_SrbvJ%hpR;Q+ zLsvd+65_kz7~&)JDNQ_7-RY%raL|K`*B$m|*b!`soVJ>vXPe4W)w?zi4X-h_=rbh( zU+~OQS2D7jm|KsAa35fO`+rAWIcdJ+IIbc4wA-1nx1nQ$f3N45IurY*v0>KlsTR48 z4mHMGV(#`8aN2f;0WxzHmsl?R`?qM)Swnm%m870)laOEpA)~JXDlo%llGk;_-@xRpKJ_dhT{gBBwCZEojR;}v&VGOa9Y{e zH?_s5Bwg<;D){Lb7@lqx9l+=MpF&2`NQZ2QKzofvnNf;yu?&!DsZgO^_aQuo0Co$FcJyb{R++*6YnxTAL|!i)J15HCM`*Fc*DKaMFNl&X zM~zh#6PqasIq}Dc6Nh0^owkFKUEwu>I=H)%QetMWbnpOI(y}q`uV|G|Dixa^Q=E+0 zXn1v&eA7tE14bg_1m$S>Is1+n_fs5h5v^Gwl^wIJSR{v>AhjrEl61>}vVl1(q079E zD(^f>zKwa<_5Hv|x|99?0jV`_Oo{x51$YJ4>eqMPartg+0YOU!^q&=ag7hi{?_%%S zunWvL>m!FVaAxdBb@HpLAC_!Qqz>YRESb%GpU`P>4#LY z+*}j=g3*8uUYhdjmU;PbBq9}AZr}%E2m&JZ0h53GM(8%U+2H+Db83$*J^H||gBG`@ zgxJK-1Kv_k>4fQ#k3FRa2&*Lhmgtj(SGP{ zVJZsrzBmW|@y~1`TH)y04f3*!07jwDh`1CU%3l>jr27vjRBC^Q+b$qd9D|VY1LI8u z;n}bEPuQy|nP;89R86f)`zu>U96oQv{AisuusJ@dtG>CdX`Rmy&QS5^Ou>b26~!FA)y?xarVNdKRpp30s*R zMih;F)SpKL74qV4PO52aRrOwKQb7^`o0{Iw%zZfDbf7>a`M~$ zq-DZh+27}3pnV`s8T3R(>*)f-gK?MQzMS^(pZp+Ai}1fvW{niZ-&{HLe*u&kp=IDW*Sw*${%bE#Jz%T$yuF!W^mtg7(wtH+YTw0X6Q z_c1og?hXkG8pu(vb1^#iep&8XaSOYgdBh<7)H?Xg;AMduTteNf?UZKM>+lE1qTt-M zVKa=xp4&5xAqdr}*A-@DG`E#xYLrPZl&Il^UlR0LqkMBq=u?dQSxc^+&-%vE2H(&0 zn#7ixne#c}E!XP0D!=y~gbS@9Hpy*K4b|N5L`Bf5IJBW8}t0 zvs;Jsms~G@PoEPfdXxaaoA51xig6N@;kxv}%vK^yD$Q`X=-G6{jL7NNM_Vdtfe8>D z89ALzD;u#wrZ;N(y6K~=s18~TPe0_nwDFtl!##G=HsEIY%z5ifa3{!mL27L5!`462 z9^H%4SXege;gia-{zm-9X zi3%m4;^E#Il)-B*{-bV?eMlfF9@Kw{+^6F3E^u`lSIC;@?sMbfmP^hywu8s;$@a0L z`z=rPmi-_jms3!`cxYy>YeAnXECDRYGBKrYv4sTMX;Pa~i>$;bvmwI|9u$vi?*7ZS zJA>>kw|O4Rk<0|^h)h!1;WDGDJltxXHU|IUFyq{o4kz=_%sVN+M~5YGD?LqbQJ-}J zZFm!xF`jgOb&)?wn7{{)CYF%`Gg@`TJe$*TqpG zGkB}e#8(ZYQYmr?zl=eKns7x_Rpa_MC-x=2*r1u+!Mr?ADabDQkF7ljr-5sI8;e?F-eG`z#na7hLJ+>ma73OoTcFaBp zLiWh<3AQuO*3K9PDA{`LVYT4z+bEG-4Bg6B4G=@UrLRphU6H7 zC`3@)WnwHjs_UH^9X!;>IQPb8;I^UcSOVBM9X&OfA`RqSr!sa?ppJa(g(i9~^~O{m6b@a+sxx5L#OTSg(pSFx)#Z;=Ech>dLczNofYeckh}q5b)I74mXB zVTUTdV=P%8n|$h9afvFHvjqJ_#w-4E2JxMFB88ma?{S&W={=d;MN#sa-R#wW2UL#2 zs@nttG;v!6UZ?lC3jN#eHW2UMT%YD3W&RQd>%N@z;&T6OlE_h#0MP|6zsIvL5T9B+ zjh?Wy_>SDbn!X(-lt~|suQPweSXcXQS!E%;nm-K$f=_&+5z;zxlGT#3aZ-1U!%Tie zEK%Upd&w{8)y<9Ag8TC%Kxu1_`c|ij^aq*(WQxR$E=yHun^*bzrZZMjl5cT_L3XA3 zogeRu`wy61JUd{KfDn0Lsljr%+jV{wqW}8 zW$Ne!RD1TNKlw)7rS0E>)@QcF2L=1AySq^tM+Dg?k#Ql-D7-Ttn&*t8f4C)0q+Boz z$tO}fJD*0hQu)vJ@kd91vX#=Z*d*K(Wm$A_szC2y^-h7p3hIPO17j@ft7YLVmSenn z7aX~RTqCDmb0NawF4Tj`QGKCmgF?w!!qi>G>Z?Ujnjnysz16--5llb7k+{I*7Ltga zUYw23UsF%MB-PlnH(!W>WkwPxw*a&j1^MjquX^60Us`g9h~`A%#k}xIzKpM|_}v`M zPuL-e@5B(p&&AdK{i^^jNM?0T6h$`(d7fBgX^O%pG4^gA$1up6M6<>ke19*lqJ`9a zGp$)2F_*lJ$oj-ajCl#P(t%$0X`%#PRf0j#xP}vDi$4wJY|P`(s$;*wHf>t{ALhKUo>83cb{y& z-vNyn9TJ*$>(X2otErHUT`^^2tkU?17vQ1j*#t>^P&{YE0BN*azP~;(h&n3zG>Tp3 z`x94U%3{0l%KZlmfxX`r@l2It)w<%=f|S77*Tt#xo`YNtzr^je#hY&xr}Unkc=mC# z$BBp0n~l5^<--R%AvKM49<3Q0IbJEWN33p>+m?s=eVZ-=C>E(^=JrwzY=c-688jw0 ze0Ys2RA$N)@|YrewsVIOweHWvVT+8-cyt^Ok7PqS2a>Wx+c)1HWy47jEr?pGoKHRS zaz5BrrCwj=lgfjup!tGC!6_6=k2MObd6&CmG4>`jpjSUf*uBT{LEI@{Uk_`rQ9MU! z`01W`Ys{Y@t14f}?m_J3%c5NawY7OP@csDnE`8Oa>ZYBZKs=%L=X=z+Tnn2}SF1(x7ZehagW3%Y2(^(j_tZ`uDGs$n z`GwAV3d3|5Au!U_Zv%{$(}m;H^OKn8z#SarNbA2R)`J^QPmlURMdG0bhu!Q%1A6rn ze@1p2IXJydvIr#d!t&Ln0!6f9O+r_d{dflLe(2~V+wW4dgL*#CjYX%FXh_=lbRluR z;Voa27vVRo@S7+6AvQ+Koanl>Yq_yJ0@7L*VC>j)CGc6JBw3M{BUV0!dC5 zSyjfZIs&Vxv)ueFhH;;SQ@r{YKhXjo2fxu%=UQIz%9;IvUkc0G6^5GeUMWO^gRCnD z>&zd+@8oYuCmozqTDHiH<^>UNP@`nuX99m!~qN zN&1_eBE`xkuxLq#$BRPk#qew1IQb?>w3ddK6V6fw!#=Oyf6CD)eXHFoHQd^O0BoyH zC(vtdjV;V8yXpYTv%!F8_B9; zkQ)KSKEAcodp+9PfPsvR47uwU2FWF}d@#H5&08h{o?4fs>Iwgb2V4iRPriNoXfc}K zhLSgcyNvZ!+C`UdJJCcXr1z|1)A_MwZe^d-X^I<9g=RBFL9&!JQ%yRyi=Ts9F58;h ztkP$S@P(_Hfxn0=^aEsjd|B^6jhrS7cpu%Tt?rqQKd$C?~U?NU@3Hq z@zq#dSA1NNBXpC~f+EAckLJ+Php)Y=KFgavGy&1B@lK<|pE8`nLj{-%anmRg1uZnr z67$$Fd&N%C@Ha{JbXXO+UY5Y7-r=KS^QGC#ycn6Uz7}msmat^}4tl_>Ac!rgcF1QkX zy=iAfH$vpS0Nv^H{FU_It4}#gPD`Aw)_O~*+hZA<8EiT(O+$e2*Q5DQ@Rs|47eWP1 zhF?|3#28TuW0lFL%4Mmd_|S1wLBwT!`*TG~G+2XWP}fL=k1QGH4#)Mu!MMTkydsr$ zOdE@!fRu#8yU$rU4grljcYaYPk>-voZM~k4p=*NLy`;PP)SkDnfuMJ=cbb~}f-fbT zl*%f%ku>2b;vaK{pDWE)pK{`#9WuH;Ug;@efZb}0DWE}G_CGT{lc@7MofEZ4Oy7e& zW8S^@GnjKk_#HjPHX7G+d>%Shtli-~N&Ev8l=`@hM)HPhUhS;u7l=Zs|FU1dJWk;B zJObuND5Q16Hl}FHL*3vaN(0)#z`q|MLy_TKIdVN3dlk6~-F`#l-(O8vSh-r??my0W zYJLC1FN7xVlrPrBzlsPFiCk&A)LfVc`WjyVY0kEmL#C-9?3eg0Ro&<0|QLq7n`FSA~$0n;Qt;aw1YpyIZ8v z0lq{IQkcSrry*ttUlU`_t9Tpm5AeBej5asBaJ0{vKXE9&Qy+~3{H4E%t(52tqae|Z zY^3W*mB(yKhotB44F!TpjL87CoQa8Ysj zz_mxN%#YGob0cmGD0G8j*Mzp=0wOX1H6<=8zP7Rk^=#U|2f?^!kb*XN?0IOt@my0o zFS>-_{K2i;PSY!T89u^`cU`U;5Lb5#5qmFx$&5J<-ss}LlWcp`TwLYkJjQ@8^UN{H zR6i7Bqh~ut*l(!{=O{GX*NT-oS+VcLgk}QmtBh`DGDfFc;2lgy1i(r&n zJoQbWWw>VCs=sqD3x!iU0tnjm1cb)3eJ%^kb5oAXD;e1LXHViHTlY0EApX_tb_HQ3 z4HK<~F<-W$Ny$-Oy{K9D&Q6x_XJTxugJ^1;m%>h=szDgn7HE)^>U%Wb>{<@}L{zq0 zYx64?C*vK$nt0HA68A=qf*G;epaK)C`r8bmJ001u3KFnYi%IP z=sO=J&cH(0#>r!kgTwBAm4WE19w7ud$%^(?ItG|$3fYnhAC_20coD#dwU+f~SUDLR z=TTh4&!INwE(nCuT!Brg2e-`?>M^++YF++FVVW3si!Uya8{QaWlSaA?yck{cmFeX` zK4}UsK<`hPOR$sMPT~->$p4h}6yC}^Fy($1G{a&DAK>8`L*u2uc_oz%v{g8nDqsn~ zI`e?paP|HK!h0rr&hA#hP!6@9l;I#e1>PPppr1WHL}76Q9fT0f28nn<6z5r6$0eW&$_ zp{Y`9BTu<;`m=`@JJ!`Hr)fBZgr%(Wc@Lky^KBqh>jy4qnYH}p`x(=Uj7~tu|b z1=;Kpr2o;JWd!!a&0@0aCf1-I&@-Gkhe0b1fiM|1NxPS1 z=uBtGhJ9|*Gzb~@%G&JjS2Udw6>pD}{y6A^XJ&>g$w{8+&2t$rV-;Ioq%@q&Ns3~i z@^NmB_?fdUpc(O_3~*6JuGHoQ44^;b;PUpXFk=x!Rg0qq?p!<-{a$%j7uS&{UhfP8 zQuAV}DpmeXL@kX$$b`g5v>mY2@iI7T(G{byX55_|dLC~(U`R!;yD~{V%a`UQP_;48 zrM~C^Et10_WTg?(ZXT63GniX(W}mrTC)5eOc=tptYdRqgZv0}GZ)-g)P{XkPj#|Gy zuRH*T=I?xr6Z+eg%A(LiBQ-kMzlvMhre^e(x{vW?yFVyaG)Fv7!$BQRi3!9Qo0Yo; z|Fe$#dpTiC3?<47XPZ$HGOEkCNL@uj+hF$h3BIkIZ`9)cgdd?KyJq4(&99)y4i&&t z{zbFAsRplmTd1(E{fP4Ylev9o)+HmVbpiqz2l(E7@R<5da)NFh`z&ECA1w5M&7vC5 zCcXlG=}gi7MT2fS>f)2w8u#J!cJLA0^@4Xo)o_nZzW!a$;Y-JQ6CM{4u0592mF^fi{-!FCK5n0trO1>4vd)Mc`nvi9#yxm zHBRoC^rz`&1x2*fqKHP-`(a96g2 zvR}Z#L546rw-@04=lRq*8-J^;bG0y9$F*wiw*^+3R@2(fo@iUSjJiY4Ly=2koA{F( z!bAK*XM=4C2ipY&L(RN)l)Li=TVPyIWehzV74sI0Dux-GcqA$BH3kQWJ{Z^#q3SeU zwh2GtC>l>mvXU{p$r~_m(E{2sPw+5LY7xF*<&gN1G${YV5{b;Q^k;(nm{vsduuvb= zPIF}C-lVRwMCBlIZybe(3HZusyO>mZK*uo*PWrcIy`JJ7-Xw)zH;Ix$se#p#Zq1Zr z*#Up5dz{v~C7YwouM53lusRKwVnf)TUdaB?^)3I9+EpQ=yT7h#=HKe1x`S!&C?+7~b!W@={Ui*IE%s!K2-}cYqwniR;8@fW<18KZ zD}#U^Ac#3D#Qap^7cMS|fLiw9b}qWb+^vH2P_?Kg`^VF-kzU$iCe*unYVXjbOnbWC zlvFbgh2O2hgTBYrZ^VJ{mfd8b_$ZM$xedQf8DNm@#fi`_@en6<#b18^ftIawfP0M` zfm`Ml_uOie*gunKNFjFCv~nhKhuLQ-$A4T;?KO7>PQW=%>otH5_1irWr3TI9uO{&C zg+H!K+~9u3-A%@LXbq8V1z{Zsn1oru=m_Z*rrP$SKU$Vwr-v#92=HBe8GBCbqyFrGo9ROR-CACfo@F7ZW*m9KUgSGh>{~EL5C0VeN;RAR z`PB7AU$qDAq)V$93p6MG=s|5`pgoNE{-ff3X(maC$=|+Xltn)IG12ZcZ`%LumHhL} z2l2iJOA`sx{0+{aej?R8_MS17nxfgnqX7l0Q(1x~FJ)Hj-+3H^ogeU8Olm!uPQzNk zeUF?niGg2@60DEEC4T*6-)@nm3=2A-KEAP1_gO0;F|FulMXo{H*zWyHwJP>DWhM z`GfSWLN+DlEMxG8A^e9%mFqWgwpHG5khdv4WAK3+$|M?Lfx0W{qE0@lt|)kSQzsoO z+ISl}D*PPMHf=H-=>s8k1ET7E`03;c&UqF`(!2=F`<$Y&d|%AWmakXj=d{cMU+7EX z-|Z0Yl(f%5muLhER;IEqlGf|dEHG7( z)Ix1XT1CfcT6W3K%>QlOxr0Cd^1HCZq(a_Z6^ru~W0&xidS1m6PcANtm{F>A)I%t(P-~<7^OLQQKqMx< z?FWMD(cmg@IiI}V6ig%X5he7Y>J!gNagh11=cxvH@-Mxt!@V)SkQ&pFr~7Me|Hq8e z$eLqtvzvXp&puf|PztJ$v6pRannV|i?0;AQ_O~9ZK1o%2Fv&rWOwCS3OYwXTKR=Lr zazRAfi{Oldoc1&+x;HC^ZPMw^Y}q$R>0kc@^ws2<2&d6I#jS#26- z0we4g5G$|%^=-%C`CX4&au*4IEqIt8^A4`-PuIRMmj!zcqY$gyi?s|eQQ3iym_jSR zc_Ce#W^viA-sC=c-nPA2eO$S<*V7-{E`zj`A$JHvE`=c%N$o9;*vfsda41B@Wo58m zR()>;FNfLlmebFnkmIEO_1f@Xi}L2Tu-h-PFOohmta4YgGk4{DU#1 zV|T@pVr(Z%KG~(eHj48T(}ML-s?Xy0fwwk?f4EB{hPfAnA%}HikcE@l$exH7*QKsKc#YzNSs!DjkG#Rf%VOd zW!#PeOGZr0Kf^FSSUXvM+^TQ+B+U=)&5A@I(y2WSo@=!RFN)?~{`?^_iaUHCO`Y@K z&B`g@mq;vy(BEK|UAxX?Vi8^Kp(ATjzT7<*yiSSjLUP!Zk~PC&7Nk2HS?j?V7zfdB zz$U>Qb^1?w>m8PXX7!}%DLBw@1&ZH6?bQh5OiDS!IXL)|*~;;kRt5bPx=4bqtEZua zqAWZ71-9Atv;~1r6jY8p1wydd=BdJ8sxeN1bd%9NgiV@6{LR^xRkQEsb{VWz^q|ky z_S5axZ4AIvMndIFQlk0!4vc`Cl998HZH`m{SCZKh^tZC6_w6@%yiB}4%ZO1ftYLz6 zoMo7&$B~DmkY-=D4`av76BG9dzy-clVd04hoZkF2D#M}lUk0<1?<1$K-~L=N?Y3Hzvl`29suoTx69Qo5bJrY*c4V1=-FeQ>lk8WK%izcse1D;WXFDQA>_xc=RVun%9g9T*>}z5O4nwWO9@8$^VdJ)*9` z`$N?^tu$8$COdU#*%vbv2*~wu+43dzfkX~@Uu3f6$BYI213|1vZ?Z@94-Zv^w#v)M zL1_JEh1Z%tJ$j72R`4kTzRK%a&R<=$Jp*l2TdN!%6I-zHt>1#+)r1}NOp>TsZvq+B z)k!nwUWB{&hcKN{G<-dB54thcL!9IG%{hVHQBfs;rw9{^95~(*=|25E z1HzeH-hMNwW%Um`FMrc#9xgJ*OfB}!%$OGi;(uqS`y|~pBz`hEi*2x>~-8W7bfUEX;}u!0NcdNzK1Mw5UQd8TO=g$Wp>rg|N8{vwq*ap-4+7ItNmbvQz(2UQ&gJ(h0;OWY)G~&? z(Hoqo1;bBPyF_WNjxqE+JV^vq6RvAP>V^00<}Vy>7sQxU5E{Q7UqrdXaQabHW{lFg zyEfOuIPG*dK%VmHF8$x7g+nvA$SDu2o&-@G9H^Hbp5_55x-0^J_(ONtP`{Q5dtvB& z!Ccm9#2LX>f;P;VUjyn{K#;6lRn;ZFu|`)aX2-Q2_pe38D5j;?yF7z_j=XF3V{ufu zEo$)lp;)n3x<|zS&o~O1Y~&rm6{POx=*6`T{hC`UeyRPxa;lF=$Dww)@d)Y_4{q0E7rq%8c^Hq@U zzW!bLr~L|#K`XW8wbiVm8BXRi(hc&-Psuf>>z(EPG^;v=PWw|(AWZ>ZvhQ&Z1P$+4 ztad2j1F(uq4=)e*HxI=@pHFvH9uX%AXckYAWCFg9`1Jbrxqgu~u#cXvC8Ku#^l=~u zl{w3^J6{D9s|3!=H-HYHmDZDZo8&Sp27WrG^94Ts>@*vmR+?o6CW?xZH{-t?kwGbP zSh}nM1Cz@eDPf>^#Ju6^QH8LE-{+Y1-tHUZU!VMIY&PA?_3AdYvO|vZ7{}*uECn{{ z7FC-zC?Cu9>`o6c{O6mFM$BGF`ig%@iLT6KH@x^RjvCufeRxa^;&x&W2_I7GoPFnW z@XJObw!|HiIen*lBo5lO=#7;6ZQIwF3cEKTbCjeBNCqJypsMz~cvQAmWFNkA&F=K> z2tZZ9KMh@Q0^c6e%vyM`TF8mKs2;#<{f5053@ za{R@Z^mST1p3BPHr^B_FYol+Nu|$?Jc6IdAP9(RmuCNK`)V&<~3hH2Dn6GOZi^o9T z5Ipm^*&$ypod3d}ZU(6^gYZ*6CnP{mGynGTLS0?(y}%91rh)PGDJU~ljJ_VXSKU~{ zq(dk#i_vwPxvJF&?wO%-u!(CZ%ym(e=*(HgGILQd|CNX>JyW&|FZ#3?EuvswYXCsuKHgFz} zlabYEv0ZhT5W{~!dOw3}A*{3Hdw`}(D3}nHDbsA%Yu}$kG?LwJ`v1_29=BD~>k0EAYsbXogRR-f{dOuUs?~k4-hc4#t`_%3 z6hK;d<FSDQc$V&^{{mks8}22qvx6(WzSpIBju5Lh4fPM2g>jK#L! z)Pe%SjHE*E4m{CYFI~B38n@j~^I@0bUrr$-2h2eiWnaO90`JR%n3Bqvmo`65PA(NV zbE@KD2<&<_e?`R*`C{k2l4yXY1uk#-Ibph!JcXGcN3+JSY;dj|05XI^soCP7 zdx_V~C#0jDbFmLgKLic994WPbTU^R_PMVF+#k0?Aef-6;Mr`k%2n_A<;~fnzPV_Qc zYYe!kO4zHT_6JgFkHo&~e8s)XL($9&ok=ym9K6GnbjIw){VVWf^BjFC0QJkew1u_d zeYM!+)^7o3NIae~VcTfI4Xm)Du9M{}mH1)7q(S;oOi&4BpG%N%3EqsU zE|{TRXT>phl2JQ0A+^{P{|8s6d!O=on`XS&DpU<^^lpRLkFTHr^q8`t6%UGzQI6kt z*h%@u=m>hhTs4R;BQT^)?)#$jf~VNbOzDrEHG|s#6G8KDg7q+*RNw0QV}>=C(2w7l z7~f{7ZdpTWgrwewarP$KArjW#x`d#w8k(`po1!vtO;j2Oec)uxyk|lewksAit|-QR z??pf3NVcRPOW~^%SP`>b&ak74@7jl9(xhjV_b4R}Rs@N@gu9xXef54^f;#O)1E!$^ zt2AOGt%hzX#Y~nPdD>fVVi^Jrz*9`-26BW_p)K zy}p|7DwJCE4)NVT(n>F3fz+4Ze7jnJWzZ0Ae+57DmoD6I&D?4>x3+f58g#3(7*J)5 z`TD(p6olF+Z^;9=?IWdAENAngh*E# zS?00>|#{q#~m99%i=38^0c?Va1A{#8rW z7Ns7hNM|sHL@)P%CMBtTYac6*5rnpSnh`~K(Zo;{+in}8s?nv!i}Dghk~(v+dr>;; zSop?|40h0MF4HSp_hTi#?oC>1#@((iE6>zE9hud4W_8s>M%ZATg=uQlN+yFYr04P4|{qK+<#-NqtI=snI^X{OOA!;i+op%lB9%Xu}S1n zIV?y2bx^&4ZNUz8v|A_&JoIF*oM!Ah z=DAh`ow~-Z*r$N3Iy;1-_Z!-lFoQ_nEF?nEgLSH;}YBizVu(^^vV% za3$>OT<))B9FoOk2uXibr*tWE`R=*BbqtsEHuP4g z=7d(mZX;I!|KcI!;v`6Vd)nA00UXGyNYOk=s(y}qMghuG%<7{Y%>Rg!X_(e_ipj?3 zFC%ig3`7_Toe4@`puZ>;%pEexc9vTTKb>E%kr}oEuXTAy7EZHFGeN1aGR@7f2aR zF92kU1t>en*ZSaWMEH5oOx^@qRqCQ(koQ@tBMb%GVVqpZ4{;A0OVGF=|@v6$|?iW0`pH>!5&yA6GbH zUS76XIwMgzy>8q50-sFz27cm!tBu|W6u{j_E$dP3<2Z?R>_%z9T=MfZ zD_N&?Wp?N=Zo*@v(T@`jWLpUbS(i!(H$U4TNK`@Qe_R0*`C;hHrpoG$uU z6~3SCI}4^IUW>ha;5&nIU4H;bY}KL|AF!7HabLDr7U%crG(?jIcK5e+R3$O%m?>Jc zGZ3PIx$ZwIeO$c9PUYpaOP)&KR#*tidK>rVt;}ur)Aly_KKn{9QzS-gHu@h_IxXMY zvtAMT{cTlpI;=Hwmg2CMYm(4$w0+ydpOQfw%hOBT!)@`|2a)9uFVvmy-Ap=u$o=CN6Xvz2e%NP4lOjvJa-YWfExCYEW5C_D zC;I=qh-vTp0>6{X1R~F~%M}YyNOBp+o-Ign=qv2AnaW!0h^{3>Gh=$bw|D8~tCa;6v@yKRU+=V^LII8NK zT6)%m>}|f7>$^{^_eM>&r*?CDp%Xt9Cep|r4UcjGOf1h>U8!gc+T#1!cI%UEWzK^Ey_cN82lGOU0k5uMPmNC(RC*MJ7qvC4}Rlka+ATa;-$LgP35wW1K z!=LDs7p}KwXIz2|lA}1pICC9Tv4a%R4&7^#<8UX?qDW7(G>vgHQ0QFa==xN=rk>Iq z9Sp0k!cDgk&*T10ay64UxJ?3i;(QGPL9|N|KqcGIKGEuJUrLFrOwQyEY&qk}o=bn1 zGylo>m_?pyDJWH^vEs|<{mg00RQqKf#vMmK;EnAO#rv=C3`ltbN&i(_reEKOGCh3H zYVaXP)xQn*Xy~5Hej*(8Svx4MR*ZDgj_7ttCnfv2R$Z8y)u0KzxeKG5$7W7eDjXZ1 z9Mv_H>M|$`Zw|Vbh>fq*IQfgPi+5H)a>$!{*J=i`Inrh9&M&lb7++yGX!@c$XtC=b&0+B@V_Z;oi) z!@s&M&(8KidXdHy?QYkCeQqa)GY~_E39RQiH*ZMAzR31&*|(3uZxNn2lq{V6DpsJE z=+fnt4)ta_t?fdTXTK@*L7~6*%MZ9-!4RKpAdUPv+AA~kzosgeppqpgL)Pq@vzaC#aKVRc}KTg4+3RulTYV)3nWPFwc;9%uenPSB!^cTts$hL{i>ax_ROktIRXP43lKD{ow7X@4{kNqtrF9=> zw+6|+xt@}_&}CnL@)w6qX3DXCSdFJevbQ#0W??;+7|bVl2TP9Te@&@!um{HHjt{ zm?Xp|n{6S&xFNAbp+SD%t! z>z={N^{|Mt#Xc7RhY4BAYqQ#jv8LE+gQ<~xJGQZFj(3XVdNLTWmjcjs_u4NI&eq{cca(hl~HV8|XMFzz$@o33_-nP&azf4y7N~V8) z2THS?ER_CkhY`O-UmFklk6AHk4`;9T_f7Zg@enD#!vs0t3TSZp!63t0iab`RaWaXv zc3PKVQf>75OC%aKnCQ!4lxD!S;(mS(pb{M?b5)9K{{|2)!}Pr0^FoghTVHaJVWu zu`ZM+>+$Nmq0n$;G|<_{dq);CcpD+_nt4L1YAZ#kMXwa7Zp!eBUD88@@MtO~9T8vZ zbon9kY`vUGAf=?7-1Yhch86DLxzUlMfq3iC2?JCQbm%0=MzgAd|Q2bRvR#54u_D z!F6+E=b!kxmtu9|a<9JJBX+%*LBDkVMLFlj(q6)Nsb?L9jo@#T@MNAph|l4Gg}_Of z72ZkAxwJp=e`I`VSt5qZu4%8021$)`nj;^4^(eHcn@|LOj89>18|AWiOhgaPVcIyB zu^)#m_s2ev65$N^GMAI27-<>^Wxlc0=&YY?Mfe8npzne5T=}e(gy7kX^Ek~;b)lv} zBetXZPaKnX1H8BJy?Q0LZ~@`6Sv-q$p=2T>5`N3ZF7$o{OP=fRh0wJh2GM{ZT|5zx z4-Eub{soH&cmhjD2{C|li}W=r3}jXyS-0EU+Z(GaKB`q&gQaq_w^$j42mWzXu>EN% zi;2&DKlr(3`Ofy$%C@~z7A=_e)_I0N2=izcdo_s{E7-NuyKF{z4kVTF2n$0tJ94(} zsQYkiq{=<|FFN?VCFs>J3kr~4HjKy)gaKi^*1bmjeArs;_zcSuW+p2^3}}l}`-vQA zHH;f3Cc9{{QX;<`M5sIU9m;lH)AhdYZ>W&F@r?a-4pWfF z`T$pb(y^ouDBv>&>yeh{B})*g#d8cgV0^#7lJ|E8b(z#0U~W%3#~6>uzyJ$ zM@87;lCe@!`H>-6d=RgaS1@X$3x7)UTa zh!?#~4zBam5B|PJgOL3vM(}6Uv+1m!W|7?}S#DZapbYfpmUOZW%8U+DnQqDdNA8_z3DIf4O4CNpWC@KW5!(#->^t@p zmoCB4ScV9@fN*E(;vzo&pPimQD>mobbJE1&8*`_1C10#^ikTK<9MBu+nlPEivU9;y z+wE1$11*x!A8Te9uz`0p$Z!T_foRP_6|gD3JP0Gb5oE2h(E7hz04h*+=+y8pvClLI zl~9d&usKrJ(l!+cs3mYU_kA8V8lH^1sj>+^WHy=hTxO}8ra||aK^yWiScYNtw+-vl z#S^9Oc@t{M^vAavy#%w#Ji1<{ulP=zx}yGq)JP}ck}k-g5&x@DJfUa6i-Vc{3ve4o zdj+j3e{}g#^$WI^OpMHPXE9l>^nUXz33vaXq7LXP2~q08pqZssc-&5?fXf1AUeMhd zbGJ0VJ3;Z$Qs+jfWPstcf`GGf@NSI8V7r?1Rq zCm8_yO39OjfJO`+b&?d{bek~{k2Al`Q>ytUM0Sr>uBU@R%T05ha9aF!c)!rxWp4S< z%J*6s4kZ&vFOVSqpE5waz{~k}uz&r7=YnZ=?2He~c0RMpxsu;T9S`M!D z7D|c5zUjGM$cW$%`8ng`n@YM`**nLz$loa#>H7u8En5ww(+wg(<8S ztK(rr01?ukT$6X^PNM~+*y^(qGwX~dQ~$P^Gz0-ofL-c+k~w)$@|8iF8XVq9cpq0y znzO_Yb}Jiu1A>yo^=cXWS=e#|XT6#IvBJ|`T>&&wE0Q>Jp zZ&gg~X?(d)1P-d9tNxFv0r}3tHp|-D6e$$nAoqM$tu{FwPE%J{_>_*)jp-X-XLW8r zL>M1h)SA6AxGno?S7|+KB;GbceuupxB>D&A9T)KrxCCyU~Q zxJ$Kl>F9)C$O}zTxo*zs4<<}@ZG8Jj8cAgf&UWQwLO8%V^WGZm6G|uR@@&fmzo-@c zanD=xw>VWR-!Y0pXKi>CNW@;cKiHcNM0mI}gm*#By=Hi=eP>xBjf}T>KUMDuQI<7m zK8qNM?|-$Xbo$#=vNuF(2$MacR#WsO#SWrA!BDZ+q1nY1g7|rmzt6soEIan?RD#_? zrcXqsw*63+&frfb;w&4uO+MAQZ=3Psd4b{*%M*^SqZ5A7L5WE(Hz}mFs#l%FaTDX> zX^-&-F*2uZm=ew*_Bn-)I7{#CKZgAB8L+t4&!V$2G+)1TMzL7xY9oV0L=NIuE|G+P~bQPel9ott#HoLm(%4=)d>)p$n#kRUzS1J-n+|D8g*Nr&b#h2fr>X@s-??L z)Y?$iNbNZ3-GiRI>B2sHAI{?;xoc;1PE}Q90kUfv=6_+S=)+~xr7LWw=fd%gOMFWP zorGrq$(x7SCKLR1uuNd`fSE-qcbBJ*5R~8j^*RyGmzYZGSIhbDC&HNehr9PViw?iY zgQy*4WXs-uO0w5CxfW;XiZ#?yN@+jSEJ$KU9JXz_^ag>X+y4+58xAIiIU%7;?{r{} z{23eHRW<>Y6inLvh%YA!pk`$J5TI$GrhY~RGINT#^uIC&IPU$t!=CDiBb_s;Cv;9#cs5g<+9dR zUbo|UuasuJ;$^*UIB_di$fHB0Xuu&(+G_bnBLT-zj0|y`Q^Uc2(r{b)siT7pFRcKGo0w_ zHnP2>f*r8KykcaZ07~@c))5d|+fKe-mgM}*FOTC=TM5T9&io&%)(p9Bso{PmN-AF ztm`l&1&*3CA_5i&<~Vc$Lz1))-ESpzYn`xV*q!d%vB=o;i-vHY!E2=8iwnoy?~tM8 z7ff=03dnG^u7>9C&+qz7r%xALUryx}_fHH9AqnLDb(`9O$ZRautX|n za4-CfYpQy(>3%LPaaSJ4w|i6?DlE{(858OODzi+Bh$`<`l>T$^nIb57{WqNq5_y@_ z^|X65SLVDoPH+;un)|lWwy->np4KxA39s%tb3NeY;4?}l*f3ucyNkGr;~L))w>u-{VJFI@(OL0f2Rj_Or8uuze=@cO0|rR6*S*lymso%ndp)?|a=;25xtpfE zaR$!NDTNxG%ba#g*J0HY!fR7yFWuB*@VuYJ5r+UF-_AxJtUH*t~3P%#$RxU-HkBPsz&=ko14`Cq2PkgRPcT zH!E9jf~TtgpfyJD44qiL8W~^6x`#$DjS*+6OEm4ei>FB5!3{luN^15_Rrg+IGHOzT zmTAFVp1zh8FxW>p%t@v<)sO7bQ(78bQzz#b=Xt&S^coFDEEt2`4C5wp+;m(i zlq#yvn7Y{^jf3dFY&LG%Z=h61D+#m&VFLZUW;wetZ&oq~9W;44XV^ZP=Qxff430_u zxI1e$iFLa<-ihZ~j<^3k9Xj!eSt&7z1M!=%P>#M8Co3Y-i=`;l=S`66-`ehr)hs?=AYG>*1F6b>h3HlqbHh29F z%%@Xj?1>K|loni59e;-J8^{kcJ@&f9az^x?6FVMa--1||QM_f@C}a*JIcb<*hNDG9 zk-BJX7a>rs*z}MP*D6A1OKl3@oL=1|3XKZY=@&uP+2Xsg-(7O2x5O}{1&%MNywUMA> zu*Qkb`(oEt(g5HQE?9P_0Af2r$9p^`o0Z0i(NU|t@f1b=^FTRjEZ*Flf|^o8gE?FM zzTsz10&P3%>5Y#ly53@vUV6eurQc?Cs$xAP&K?Ylx=2Pue4DU~HFH}j!ruR&WUF&m z-xFsK?j_@~z(NRsNwQ(>i&G$`&UKZEw}x+KV$LL%pCMNBw@)kXJZfg4V)b3Ai%FBHh=(X(3teDtM&bu@bzAIMt z&-OM^lW214(4}wv1+;ZP2AdoG!)Q@4>}ebP->x}DQf<|T%rp_(HOLnI)jR7Sn`XNg zOj}vdibFX2oNC!*;TT@3Fjev+zwAeT(@I-E$5WKRq0(9erP zUSSzgm_S?|#BmaLTP0Go8)0|-qj@2#&sPS4is0fJIumh=U@5|e*QdrMcXZp0u0xV% zP#YHJYrdkOF)p+8d)-U*2dh^%L<1GsHI4T}p;u^P$IfA;kz#6( z25y+Q#T}z|8J%8_kLG{3ss{Sl?@>UYj_+(?04lO*|6G{{8VPT`+sSfraxwt&Y#?-w zo)fxea+5^5`hkRhZE0O|!^Cdqs3~H!bCrOB0vsz&cRLu=9F@cZmH<27rk&c@E#9~V z3FlwT@gx*vooJB|9Go1HVXyk25ld@$^IV! z4Lcot(lm8(F-jDzrje`kcY}hTd8WUHhN?Z=S{jRUMNln|EcogdER*1IuIQPWa}V*# zqlGQU`<6=)aHiDQmBcO1E*j-9#fWwn=0PBcO#{J*9(*e+tdwA5%A2^g=RRXDzb|fk zM38v%rYSRpm=y6+y_(IJO67NbS^cX(bJMQc2XE%-FmkZ;-<$L(B+?WT(a8RFwbL`s z$$mTBKti+TQEZIwUZ16=<`xXNWBm`9%Z%r{UX~q-9gm(R;a@kF85ySAXehEy@Q!&N zf}HdMSLLaV#QH<2*fg^K9ORF0C-BsK#sp)Iarsr#^loT@sWD|U%-*!P7P+14`OWa% z!?=ZHLEJ=m$Tj0G1?x>{IhdEY3r|Z+af{hQlCmW73)Lk-I82?HUxUc@+nz}7l zA6}!D#SadRS!{cFGjz=F(QdKwbgHm_ynB`<9NmRmRA{qZH6S=^6%-8=qCjA(1Avv0 zNd6VjUX2+Y9SsZ&jQ-Kq+&m6oQv%xZ-@@C^G9dio&r^c& z3HKi`mR45mH#+qW93BP+BJh$Jbq1SWQ~%zcqbVE=DBSp`cK92(;W2wS^!6Vr-rXzs z=PppCbuv7GP0m)tOl=vZ*K5k$`Cu&M(>TYRQ^F|*ZS}O2bel%SZ?a~J=+@{fj|#f{*+ydzvsisb zvstXaR&Z0(Q){_Cqqg&jyt6*XcAwIhd#8ujv{&RTh^aJ8nu(JBs(O|exViIK$3gUZ zgRlY6zU|e)@8?^6YvUw?@+ukt6CDUkr}I4DO0ay)FDSsl#l`$RTcV;-u1W5~{T*%; zIQ0)g)&h{_ffoSFo(X_l>+5T(B7?FGp6^6$p+R!h#rSW3(ECBN=%PdWFN)uOWjBI@ zu}X(U_B^Q^_;)2J^5?&r7x-J1`W+8v{;!Y!aG3xk<&O4t;J+Xtf6)*=WMo}&8JlGS zFgOLwdmIg2Mj_~PQDO}+LWl^50SWO*1q0F#84r(1m)qswSB_{1wL<#A{{H^qArG#e zAPDq~KypgVf z7QtqbfEU9C^GcNZue@ItWLp1dyZsdo*O7|2~@gznSs?@HgJQdnY3KoB8Fo>y=>T zHR&a>#nYZ{5ZHkSWgfpaQJ)7!CFrPaDOlZ5qi0|#5{D%3WrLze>bc^$(qgnWPA^w~ z2wsi&ec8s&&U$h>-@2*r?}`)9?O0ya=rL4c1qEy(j8uQPoAQ6TJZaiM`d42?$QzI8 zO8%7r7Y7c1&+qwqVRTd`C-1;rd*W6k#PC;5pWZ>J;V+ZDGoH(_4?siW=uA-{>gLVz zoLZaTbL%e*7-YMNiPe-DxH6N9>xSg*<`sKjF23W&8VP&>u-!5;7+tV|AD%0(bB(<^ z^bZ_Bpy1|nENcF{KX2p&VDOU}7#K;@S$@yY+wBa;hz!Ako*_?x?;5nDeklRN6BPNk zOd#HZIV=0sW^$k}hosPft$+X!Fc`drNoxbmYnxuwMdhs8J-LCHpif5`a8 zBG)z4Ip6+G6)^u$_^rp`X587InAKPeSjr)7+bkE;rc>gs%MO@;-^r}=Q^A7%G~UIP zrN?om`2LJHz~l9bEoGbmA{PN37*hAjzn9LzM_|5|%gW2;q@)hw^nh9uUY?%!_xIN$ z>prkRdGZ5KJ)K=ea0rR!}!fpea7^*I)f%SU|-f9_Kwd`uHPQ z(1G;{T?I^cz&A0DZihbyJL5$?4uG=_zwy5tyYu+?xV^o7Zz7EgS1kYpdLRU@Ms|== zg+umibaSiQAMa}bx_vtWVA=&36<^01{##>~+3ab;Zcqr&=TCDZOCH}rIo*iIApM4m zO)bm)Q2eZ@p$Oyjz-UBJ_R4?nBT-EWunR%q0*(L})G(`nO_1z2fH|1|xAoyat*`%D zzasx@HT=l%&duXDoMHh05C3lJNsC}LifQF(fRp?QHwMvvnPhPT1{Q?u_TLSt^%QH! zZax`5V*39dTnJT9aAfNhS<-;#CvS6zetpNU9#Hp}pnp@<{iToj-5?e(E+`-eAz>bb zz)e{S6U@)>j&sL>ri*DS6hCJhXhQkVqvw1#z#JbNd%ueg1A0i$i*vrZNGPsHU@^R( zOeVm6;s3W1EIMs9&A4d752aO#)gp*6AkmGtIsc?r03XEC^8V>^swh9de{k^O{+=8Q z!69j`0C6drtqw)50*e>(KqGpR>A;srf0FVcnzgP~Bc==w_%#y{O~A#}n=%5Xi%}#I z*5~N?^t^uR2SAn){(pJkuecG@%e@Jr2yG!yFUzbeOaOVXfRbvI36bH)?gYZ%lxYv( z%u<<>S!0*{JOE*iqZKBbdGR;h(8Su(%zFcXivE^pGpXdxidUu-msR`esfj7>w640g z-or39g5UIa;_-#u#5%7=dV{B>M|Q|QCD972nR+5_qGeE8^m1Br3JV6 zl)3x@cw!6;chkdsB{TKB@p1-%d5!uF*0M=iZ(pT5dp+GKQq!aIzmPDkg4R<%b`VQ@ z&VS22b(09`;RWP`@!h);cum0s!|Ik8H5)OEhlPe(?=W$wLl}^?TNIt4;e$u@RG!PR z?d4ZLqe$uVR(Tm_)#6%q&|(P8wQU_MOLuhDMqnU=-}1+s()s*N6f!=PcyOq!E$#_d z>gQE16#v+T2^97BqR`8?e}1L!%BxhTRgFb=~~r|`-(o@}#%O+Op;2;0RK zV0KhK^!K3EML@Z?>Urq1bm$&$GeK?YD^3H@EbEcLunagbcF#;Y)gG~TWBFe!$b4tP z=6ub1M!W4==kPB`inahoOo#dKx0cT6T1QMPV^=jQ#P}8}-pU#}Ysa7coi;1F@4CW1 zF>tKZ<=kr;-+AFk_InJTuAy5ng2C^XLP!8(o|Do*j!xUg!aEsV*sQY%)m)8{BIpUvQPc9WTH}^CL%<9s0AFV zg68nkq?tO&$6_yaaG-x?d310Q?^`45NKDMU&$unE||qeNdCGkQ*LDv>{Z__8f1QVe(mG2 z3Kv{TvCZ#m7E~oQPItIyIc659sTsvqM+m{FJT|R*NDsPA)%y1xEB?0^;*r<}K#zlS z94@8tN#>pk)zu^>+mBw3AsGiU@nQ5?S-ViS)34r)<%631EF_C7)pB556k;N7qvAcCPv<`lp8_=UXZdg;VOD*g9eAm3SLIxsUh=t zH=h2sPJS-PTyGJwL43tIbWH=|#qL_0{@U)W+yK;>acA&-maX$4Z3Ox;bFG@7bl>=k zGjh*i`%-sPT=^cf%Bs-8><9_10yfi&50t1_GfQb44O4^0>u(XCXYJr@Vd}TYJF2Pr z^g`_g^&^i92CZF7OEbu!G51d*_CCgmy9~qvw?$9IDNc}(SURM ze`^>}(UjWP*UA&h*kF0iN5>5YhfTGLLU>lT!M!5i@B$_KsZSW0rotQ-XjPo$KVUtS zMo#efP|M-Q=;@|+*y`D+ig{>?na-x>cNip^OYpFZa;SQ^pTSHpo&S42l6>!4%eVzix}V%0rI5V#w9Zn^UmeYMaOD`d2i`5EwjrnzEwSn)Z}sL| z3quriQj^qElM=Gxn*Q3SQtLyGqPX#AUChxa!-ebL=Z19WRK5{+s%4k(hNK362uTg2?tF<5f zj^EWruPbVDE|`V7tUT)fMPXramb!F$Hi5ZfRJrM%5V=4V)%;WnRrfN{slmUk>MQHM zY|{Zx^!DuNuU|Nx+9nfN3M!6bDvp%quVKe|D{xdc=ZWSb^Gy$}i_U8BT4C@lJXB|; zZj1+iIWUUUne^_gyu^LeLb`>temC!DRb8?piVjR@&uJ^>E;eBPrJ3Jdj^`V|V*QpRk(NcS55R zDl6ZCS7v0px~A*e8i88XAH3M)uT6-K2QAW#-;mO^)Zc8;EIMC%eEYB!Kf&Yb1&*Qg zh;!0=TtPBkHNLf@yY!%~Q<&N-%1;!d^vr7_0`Y#G`6qCZwIW+KUn)v!*i1ZqWZ+vE zL-kqKmNGZ%Y3^bP#ai3DIucLuinN*;R3^9)#Xdfz=gZ|4ZdsVkW1vX(^fmG@76v$cKO>7x z=c*E?0vO=%tw+<}A5pOv9MiR1KC1GcE(*dvl4($|QHF3==I{#mNzzL8OAY>rW3%-W zbSel7r`f(QP9C|a{w2gkgGk$VXcdkmsJfSF#ACbufbKcd6+SO-zI?3PkM1Z&tdm^* zcaDF}!&6K%d&MJIQ+|`?umy(!qewxgfogH-q~hl_e7TL6$6ud~FymHLm3n6SIuXf! zHAs0hT4o20&?>cqtCz)}+IC(64A$C1@*Zbj5}F@z2SoKWYFeY?NF;M4vZ(&y6HhjZ zLQsCfK74icKdGhcU=15}y;^59RFrGCSeekd%<;#MvIVx3Rt$<-oug-WnV@${?$B1C zo}bBOQc&gU5ZbL-`kq8E{5|h7hK`C>_hkD2w3JC3 z++CIWynLd%e20p90o(z9>&O*nsJ0F@zRs%=ERSJVq+D^yYI8`~LC;)$XuQ6h6id$y zmgqdqYaRj&*0hoBNWRnEB?QA{YX*Jm^6o+IJNn+N)IBgHwVvjpHl7EEHfKuOO~HC6 zG*k>ZrD+NKAG!C?GVpfKc6?0}*-X^c@5QiG8!8*wNC*v`+{IDH!ob+>B%599Hv`|A zzZ|r+s6ukz2J8J9Z11iVsd08BRJ^wWcN8`z7N?C=SH-t*h>3mTVUsX=_(u0GO82jq zS!!Z2^_hcsY?Jxz4Kke#3pvN&hS_> zf4ALG2DUVI#O;N1z0&4nXNKaZ7@NDLNn36z)tukc!}iULwhUe{Mr`kYP_$yNpJlnL zzo=LUPkoA0O<^q14$U>j*74hK>kOpuRT~T^yR@40|1Q%qShU-bm(+ED@z7uTO(NHM zsRf=7PTN;DUm@C;qe?;XpT$4ALNsG#rmtx#XS4Gl7-+{c=yY^7Pz9gZf#n3%+P=M4 z*;`)V_{1gMz%_p|KT~7FuP$R`t6o>wDwiB<4>#@EQ#lQ0mlX)Ugl8wQ zH+WToImqdc4Bz;Nq4Rk>^8HkxpeiK;eB_Ret6ggq&Q*Xg?@QxlS7(1zdE|HRrUT7q?vvo4ErLQhow_`t}w3;Y=f?WKqr&FjJSxkQcYTHjWp6ZsY zs2Yxq|7!=kP5gIZvbO1~N1VYc(b2H@f5cE>oaJ}xL#6gUi_1`HgF7TD_J$M4!KW@u z(l1VQ*Bq>?eEBK8kUOstrFN^AWbuFs=7vqRx`a0Xk9?$B}~ogFBbUTh%* z1?uZ%jE)3K4(8|s$kgz_s>NWdo-nQW%GOr)XeorrH?eDI`_mC&NHGbYJ)}1@loG~2 zeCMpW`Kb129^P~IFzwz>tL7={cG(nY40Tk_FOuLv$Kb$yy_{&DC#i4XP2D;?rHmUD zF-dYS?ig+!WYXY9$2fEixs1>j$m7%Maeu@2Myzox5CelXvu0&Wq`e3cA;e3H$+bgQ z>lS|_S0dpx&Sx8uZ^gVf^r#kdoz3)($*mj1)JK3m6b(*C&@oD8RBGia7_%2FiFToG zYoq_VI;~;A?oalc9?1S-P;${aok-}=*vhQ^CUnb zKRfxM&&HzgjR&(jDJ<)EKW)#3yyGe-cfNTCBiW$dD0>#+EcT1_YZyZPq}EEhaqXDF zTlCe})G#12;+Q%U^Iaq{R4mdzRmHj)r~I#r1=@Xc@t)l|GoC-uT83Nc2u9~f##S#% z!8`Bp7T$3-n%s$Vd3TgDY3P~UHQ4*r@XMwwjl3qzX`p0@>!>Wv+yag%IQIXnKE9!k ze(05@{{pp>yLTWtN7kfL`=5=?%E{kL(sKW#&CDED1EtOEl1%4#j<1DHyvk$L-R-3T z_F*EfK~7QYQ@RKfOEzS~?)T{T-+JP_yBOxdpNM}KXrsuQ9>;DXXE4j#P`F#mAFG=x zEtM8m-mJ=cDU^ny#JT#2G%?E#U}CWP$tE=#d z{%u5Jl`mDuJtmevj}=A<^B#v}U3cp)ls!&u9OKYsKP(*utUcq zyb}}K;O79QMyB@{EUXzvAFgc@f|Z(~bg8Yq!|`MKy-*jyL%CNjP{2zzGc*67`3yl< zbu`TzaE;=4796|&B>SBIDSG3hg{FqLyPJ1lj&gM9%$$W?hGOeHmpM_ureql%zbtS+ z@8sTD8=QqjjvPKwHaV1RVR+5}eROHcj7j;%n8-aMUD2`DG!&cfMux){(vLXYQTSo` zb*H8oR%7%e^QxT`#NNNF>ssN?Wl>lC;4-2I&|E+Y%L+j)`w%MR`q zC%Y!#GFRwnP05@Mz20UGo!=!byANN-Z>RXj%MO-nh=Il}nX<&HQ(x(Rs=WY%s|&Ft zpvmu6MvWJ<@R+vxhvxg$$@z{C=Eh<@E!w$v9cCngYqH4QO+!PQvBYWQkqb|E`05*D zE^ZgWX!gulQ!9&0f1~yW)o+(+)To~DC@wSREpw#IQUzb5b+5ymu(*!E`z>|yw_36~ z>+#Knoo#)H0V_uIbJ}3A@oJH0+Uay1n(|$k{AXwHJ>x!2r)cO+%o@$V$qP|QQoBU_ zen@I2)_)g-;F=DzA@Hp8H7XPtkkbg!D++3+49SydAGg726J92HyIupD$!Uwd%>^Zh zL=g*uB=wn7fvn2*;;W7Bs2`qk%ZuAev($IB`5|n;e{f3LIb2Ij3cj-6 z1f7GI2K4L=8BdeDR@{D6Je7qqva>IVx;rfAUll$_)bxR7_-&p?kPDy_#H!pubA1I6^ zXB?R|{-3Z54Kxb|i z&Y*Xv4OmD`8$Y>toX&=hW0SU=t+}V`j`|LPw@zsC`Kh1ZMS$VJx0chJ=U7}Kb2buj zJR+uZ5;a}VWj68UlUwJ`Q{$miiij1T^Q}sWy2hC=8-^Ao>@I`p!=T@U*p)fl9d)eI>LlX3N*P5eDDSPR%fGQPcef z+~%mv8Z!b1SmlNmbur86a~Lr%?We>_MeIMKKFw)&_GrrTwICg7Ro19&UUL#I(g#mO ziQ|LmA}Q0vjhJVPc<5RE0*Sz$~vNANs)L4pn&z> zGefFY<%838jO6Tn)`=Mf(4DO$r5ayj6Y=z*PUB;+gXk5zOTu8N> zu#br#u_`SR-FWxI=IxZFQgg$O7;_*F43 zmY;1N{N*E(Lj}2qWg_qYs$`p!qlq(JdcqNYKT~>l%9GNymGb5OlO$qER6gVzt;WS| zHMuC&AMj$%V9R-Q#+Q#5eXpy=gNW-=cGh$y&Ol07qsQq zC)Xcf5qM5~sSi$$rc!HC{Rv6LCYBc`ezVqUK{&)1F;Z*;6>$l)*M!$v;JEi|ha3%p z1bbErKHY!yr_Y09tXCBYD>CJ#{_yLlt(|xOwyrn7Hypfwbgu;!H6B2nGklX3k|A*{A0_4WXg4trz#qF0XPu{hRX-zM#qJaCOasSUsOfBk~ zKzi%gqyAuzAl--{U07Mw!-K`TxuhyQP&;m)8@%N*KtR7kRg~b_Ci-y0^xMUMPJj_D zqL1BQ9RV$Xb$SoE4~-aNc2+(fF<8OYjc(L#ep32=+2sePJA;ue;NAnW3c3s1$MJ8Y z_vtc5Mym9Bmk_d(B5@Wg-L+aKX5)&x5k#}ZKCpZr5g5mCy!Td~3vXsB!ghwIErEaP zF~-B@&x_mG@|rlW;@GjIQ!8W?96^ION+-$Cwi@DV;bv3q!8jbHvl`w|4cZ8&psNTo zU95DU$~hmWCWymWdTUgLa&7O{4B)02Bf)cLC1@^Cwe zi~%siP<{Vw9dC=Uk|r$N$g%1}*VfE-qt}>5Y>!RCMFa*YJd0^$BL0sP*^Cd%`>y-) z{Mt3lk`**y(W00J!!dVRc@)ZT) zjpZUHydXgYy|i|$=IXtojY0+nK?V@X7mIXvaS3Ri(eQirGYcw_P2g>#;<)~~YA}CM zoVS`~kQqlmHA=@-Ly(qK`02V?3e1{cGHLDq$GKpp52|WW++;j;+INkKDCyv={JY(Xo?z#oxkMuPH@A^?_lBX*?CA? zT|Jlp6_Lwjydjo@JQCBax6~JZGr@og4MjauYvfB^oSqF*9P$@n<+WlG70Wlbo@(sK zjbJRlXE2oabZxUq9Hyb>6a$07m0+ zlWf)WQCJzD|Hzk>pR7!IJx7yix_ml1*+&pXrtQuB0aKDasVdrWW@`T|1^uC#s6xBs z$M0!XO_W+XinGO|%zwV^yDNVTGU15{?5Q#g=rL};6nhsF9ZFBnGa{ansyg;TbuUfI zaxL}2ioB7v#lDj4IqxVlBoN?wRV;BC5U?^d%xX+=J}#|(TekV>m|xZKyOA8>(~o1@ zBv_3Pzc3t+e9t!@x2V|MC5r&5(O0wYdgRn8#H+YP(004c-Nf`_DT6citf~`h?&*W` zatzzDBDzhvFjdwy>CHtUIRR+IcE8hdmnoCia#-sU(^XGo)-1~en zQ_`4LXxT*&0bz96sMkn=NQnpC@Q}2XXw<&7A|A=)B<*Gw7T^6*#qZkB56u5xdv6^T z_47RrFQOQf0umyipaLQ#NT-yFfQXcoNQrbei=uQ$cPb#=os!bsv2-lWQcLVUv&;Ma z`Tf3sJbymte4leZb2zdt^P1P4JGbwh8IV0A!J1u={QxCPCTMSa#IG&BsrK-%u|s{{ zW{>0u--qTrB?>GlG->~mFc|&HsSugpW<-_rX+A*e`4|A3ji>C0|J$#3cI3C)c)$%7 zA!CgbJCqDGy}_(YSu7oLmnVKtgrvhabMV%t`o!u)U**2;fIs-I8g+Zksy@&t`Qv$A zVt48~q16YqAK^YP@;fI&vUr3S<5?ZMkG@e;u0&|t$?q)x|j3kp1@;^v8& z@v2rGap|;-zC$BBH>UZOl*y?5(TDG=3MXqT2aStp;O#fufj#g`)2$YHS?%Xz-q9gq zTswHs6Q$svm#7KoJ|6uJ?jSb5=J2`wv}j^4w8^P5X>pN`xh~>5so>>iL%MSz<_5{P zmA8c#%9&jjG>x@h8g`iYlZ%j&fsGv3{ zHjAWWBXi#;g{r4M9RK=YDP1fxI%&40|3G7s($CNUC@;%u%(r|b@dJFf`(ryV;Wq}#YiR4;ZQygC^>*JH z?`-{yDYSOE1<03SO+)3$`(w@3#;B+~h4w`*U6RoqGqeEZ!bFn=HN=bR0mgHLIR9m~ z4s84a(EL(^HfBWk?$eBJb>vjmrO52;HwmUCoFmIcM|+%4aNlIPX8+n$iGOr7-0+=B z?oWTn+52&z*3CL)9|ZIL2wL)Cc^RbXGWKpJQ@fO(-@86LVVRMah}bTE-hB1BNPPIf z7R~rx$#?&!wnRnpc;c`~x3Mf$O%M#!>gk{$k%dpzCvUwtYrGv}cQ>1jsqO*oXlMBv z&ZB$wx1plFx0~5rS@ZMUbSO1KbJU_$T82$t)d?u1`==jhQrKxhl8IkjYP|H2o<6l| z zqW$U)PYcForc1S2G#i_g(#;(9Z)36*Jm{ULMT`9FPDPBAdmwpoAbXD4{Lqz2lL7eGFhE^_~703P=yAYg2qQj3~k^z$N4PjC1X&0$B z5kGs9Nwwf*oxg=gOk&&ibjj)%xDiFwP&U9pB_AFat@n*r=C-w0^W`%P&Gd+j)1in6$zUTT5 z=z_68y6^;~G}V&tcpSu%nrR$EB7I7s9&#=pK2I&}$j#xu}mM2f2qLpEJ zIxrk4xe^X_>8|A;`=be;+a{}Jeos|V8L#KBlxY3;fcW|$BAU-VUQ$wX!D(|X^=zu< z291nlfW`*3p9ZevLvgV{sCzYASEg`zM*HGRiU-jB#=C1N$&BRA6=oiX-SK~giL z>9=6han3j?^sN2(tMfnGlM{8mvAQh=E&re4=!3GAn`BA zcs(e1w?`csz>xQNfy%*7O@GXkIP-R)k#Z$fhwHNyvNYGF)Q@RpZj5D5o;AHzhjM3ePJW7k^_L2d` z3lfsIB~P+SqP|ve=w$vDZ@XM~izVuZ7;wqOgLi{{@&AI;h7`aeJso5aeST|p>0S!n zrf*G7K>Q7rJ2isxu@y|Y=lTjj+0Dt!Z_wRZp|i@UHhx4OTJgPQ^M?QWA4B^sT`L!X z@#l9UM#(^KRhmcCe)4Rr=cx1V^Dyh@VXuW4?1RVLIX=3miocA%^pod`{oV)!Qtpkd zff4I{xk!z+dsC#}zl?h)Xpl_*0l9vO%N2$=x}*~o&B;avB2Gd3NTE`0)lNk>tJd|F zT%M2djfYGyqH?3Lf_uj1kwN>WFX5>_-dX#zu)JT{s=d!1M&=);Z09Vm@gwH#k8w^W z7xdV)3+Y77Pd>|qpw+Os%-ew=TmE&w`O<>Gn0Tl3-jM@xL)He1o zes*#0oL_VkCqH>^`CL3Q=(vjQie$5+g^#8jsD9bM6@q{}43sL!7{<@N$Y)V}6v-6W z%PH??yEM`OkCHQEB81gRDA#gmO}_x6vijSUO-=ON|KMqD5zaM8Stk~ms3I|>7Ewsg zE%6|50_r|#N+06V?7vs8@>`8Q?-4sIXRuFnWsgOP?e29;ptUaPhg2V_2p>JSzApPt zCoxVl(Ztoy>e@_ft!jS(Pk*z0*VM0}=vPwKoSmv41b?`$^JlsqXfJ(Mxb914&b)j3 zuFe-$@8rBsJ z_}LvZ;ZCdO7rzF4+03;?aQ=ko+RzBp{nX!*R}OKNd37=eI!#16#Ir#S`?Gx3-qO?P z{k9nxa#xJs3IVnH=a0A_vk0#z!`H(ihF5Ik6LlXf=m+)8pzilFk)gu2ty@T1UlwLC z-4jsF?CMsHh#y&ns|Qi~4*l7^b!3d=M?v;Q-Yq^h%xkk}VPoE5F{?x%sQGQoPnozX zHi+el{#IX(IpBGPH$A4(Ih8L$um7ly!sQEh8T3%yhYfqGWqA~F& z-^BJVLx`NMeca3mx62X8Oh|k=pZZm^@P#TfQ(eX{3t%>MtTR62_`CEOv%pxy{aX0Q zYCMm3F{X-oY=4NxB?8HqWqaU-pLgUc^-jNnS`{z#H3MG-yB2?b}EE^qq6KGsc!*pk#mV!GRDjGr(kE(C=0MaKbzZLpo_m} zDwKdM+VKylwIB^CEq&nB#+K4VB?(F;h**LxB|{5>d$zSalqK+f|Ihkfyz$4&|Ffpo z2|Slt0m@Lk4WE&4eyOe#rTp^vr^Itq3N9Tq`laN;7W6|?dhT=Y!Av_VaNO<@!>#XU zbK?z2h3hmuG;bI?>2#DEZ@px&sRO5{zcYuPpiH}4>udj%mv6tO7IwBp*N(=HErG*k zd{&WixYY_MD>0F+q1T<* z)x*rEk~c$9&sUl?ec}}_;I=f;g-H~f`@MkfC*l%(;CUBu`cnI)v9kEy0BhTreecMo zM(KlGKc5$iH_31L_+koh`@AiGf?t@18?CfYt=Q2Q4su(aI&*U|)FgLj*O^LFKti3= ziOwLqBoMglCi|_F4k>z9Jo3i8A2y%q^q=TG8O|Q*wGp|S6D`>7l=`j0Sx!nk zih|?=eA)M0)DIPKoI9CS?D$ny?}5V0yZ=GTy|7~ofeO`pwNRBVIKP>=;VW^&Q&q>d zEob(2I?|V*I{%wt*RiD8K{fANdr7qu_S?P_pMW1h6xlRn=_F}`1m&{^l zX!zV40&!^fxy6)9gd6eqzN1SBjE;+IrWdu5y_YqCuzMo&(f8c(su3?T{)(T^8;1vt z5WK6Iu3Fm4V_)_iiV-(nv6%F(jY$ImwkAnYZoD@uD(&SY`<>{P7xMyf3Mh@gMtz-t zp4VcAyG&-joV%gH3#P%b>^uVWP(acib!}UA**-xhQaLmA~^M0 zcLF=3*sfDwhwO*RMyb`^5BcyJRIow_l=NEF5QJ05Vnxx+hzT?C}@YOdL0 zO6w&!4SkkNdj@r!&iji?)ubO$MtcF@0pUuX5J7;q)>qM#S>!o-Bg@vNt7_1-?St|yL%h|y~= zenCM5jo7{9kt_CnlSC4|2IL@L=f$v))5nSHVmKyzG_|mCat$V8RUcm(H!EBKHaP3PD!)3U5H?zU?0J!CTRHZ=h?I2wH}1of;jgFD#oLD z5oN2ndb>tET->QZYTg?`?mguh6)w>+G1sYyAyc3j9jvt_wRNRyv(GKbp`oGu{HePs zO<-;aE0yJg^-r=-7M(`Dw=k?ggeB=&o{i1TC2M{dYJPR)fP(EBfOFrM?sI7?iI{>2@|W5Zavs`Q z;lpU%r(49O?_UdlNokITl~TJTy%Ufh`{2CE`70a8`S<>}xer!ui;C_Z(_)6k2Ddrb zeJqmrwD%T>OB-8paaC-%9Fh&p;(ySA8I}L7LUhc1JyAb*$w6xVX6A1Fr_SFRbco)@&9_T>Vanmz;mLJ*rdx z`0T4iHDQmju8`i-*V#yIgj*m6Bd%aB@mYNB<#f~!+E6+CHZ4FbY$}MHhyl82I1xhk zErFX{4!4t>z$_riaoEaOkIAqX4{TO?mL^NzcW)(F%v4xOjQxNlkM294AO5PRR&8`V zS<9gEy2bN=;|}M?=GV|B{i#OwAe8lPYQZkRTQAWHl_25yQave8wBX#ys@~DW#O`LW zXcrj|rNsn>v%J5C_Eg8H{eMKG;HG zcgNMTQA~$`7~+Vn4F~7YeESA&<@{oil*O0ndPJkUfa9SpD?6QnL_LAIFNVkfvx3o7 zs84=23|~6%4#-&5y6g0`0ZOvW$m8Lm?K!1@xlc_RO`RX%Q}-s^^p#Y=6YVaq&sIr7 zl|3JGgy0n=^_(Be`Rdx$R(?TrcVF%P8>e26AHDx01wLKv0u!-02`|`f@Yn-{2zxz~ zgNC7f{&u`NYxDX3T;?)l8e5AFvGuR4MCzdSD10Rw(dx%7{RzzN-QC@d(pMnD)(4*# z!2Y6+PWc_^tF!@8G_tqR>oQFst+4aRU4Y7YJ)J}}(g@6~LgFeqVsZ%Vjsyxw0c>JT zX{uDJ<1(Bvvgj=@7Dc@Qi-uPeEb?ZLuux5?dZ~(s3CN!`&ccxq68b8uh1M--jnh^e z-8Z5ec;8G^^Uc8)xmFg{W6`K5I`>1yu2GXfZ0Rnfr51_rB0Cg`FRJs!M?Nyb{A`li zRKl}B5l4*oyj;F~F0kUW-EDM6M8vR3eyt%!`MmouP}9KJP37fdK2sA@W^z^K^S3|Q z@3rg}izQqq9a>5Cwu>ov5(Rm!7yo9Ef7{!ngZ`dI8dn;82)uI9BWolhZAoY(BdT|WjGa$_A0I%y|BsBv zC4KbT@nBe$^~sZCQK-Pt!n%o$@NvFdG(8^253OqFgN2+fV6nm1*>{2isJNC(N42R1 z?Q;sgh#Ni0&Czz`47Er)-Svj1r%%;5DFGsPPLa=;L>iLRfBaD@xz|+;B@;-ko7?0% z=j3&$!)!2H<81>x_#v6!=41#^!}26i7;R{8B7><=Etlf*&Y7(Lu{~GYx!&mr;DYPa zB-ehw*DBT3nu4wqm~6=(9L7BRy)1YMa-lP1@4--q z`cA-J26CoP3F!NYIy+LGd%KA)TS%LYJ1m82tH~!`F)`yT{!tT?vPe;fZC6C~=hA}v zI0Sb^6Hcv0Ma!s*W=BE|pxO^fe7_N8MHvds9nGgQxx0^n%_O2Hv**9MeX9^mIzly? z)%Kg`0ktoo3bXm2B)QM8*GnnNeha(-an@bbL7%9m=mCl5Auj!dTy(dY^iJS%J^Gv- z{ldluk?9xaO^nLU+S^Z)-S`{AAVuGw%;J5CgS&u`Q1mSM91i=Qr0@140;#>Urqs$! zdCSSgCI5ZtE1`E)zp67cGuQg=OQi5XksF*NBaN+tay@y$@3L9gwR0F#fucVGHuiQ(_E?Uq-du~TS4++OWUu7)@gKu zW6Hv%n`%ojN|R;gpO^XQ@9L`y%}bHhbYQ%>119eY*I)4QzQrIdgvg=ak6F2l6t)M>GJOE|;UVy#8_D6ht{Nkb_wa8~8sHE*IG(zhcjP_Z_ zl=kBmKS_u~cLYn+I=kkosaxjhRyDhj(AjPqU45sbczz%yCzxu-fkn>w(nsN22|({d zQ{0gq%6hE?LHe`=8Zedkvz4B39q6<0H;KYVTkp2-kIC4;+zu7}qs|w)e}Q?x4^E)z zTi0@O-A;~rF&dlZjt9pcG0pLVbzD6yn9p~1g=i*H?$kO?BrkDWzQR$3B5gtQL3cWqYOxkdhRkjqA*$6F2*ad2@x z1ixU7-2KF)q@>{BUa*_+a2sZkb4Pc7J--_WIF=V5Abk_joO+4wCu`%yMhH9i4>t=* z{Lv)k=BFcaE4}E~lJC36c}Mby&YOz43{QSG(cmQmyVvzBrRaDps&!^(90!r;q;lW% z-T6u(^OkI6zN5*g=rJ>c(^c#2#|kn}T%CX&@r{UZHZN;%ZN_b76C>zWd~Pu`CPDih zT3_q_giGkP%^bC!G&3a8^#~RuCB-)JaJwc#R}p6tlKXuYv~}AeE`rsCWuTkOb}fU< z?8?YJn=o_jD%-XB@AwA?6hHvQpZ7Y@L^UUJ4noCO=^l_!i_>5B5YhFriv}e3d{m*^N^>HQCgZXE9XhM% z{XRMda`|xnYm~ReOnA+w-q0YQ91SWQn}5U-v#ft=I`=E@Sh62>stRDlu9|42bLpYMXu7#JA1fsgO|2|kp`qLOn{ApVc88jJ)N zY$Vj-DE747Z&E9zg)cuoXg}sQK8f5xKkOrntWir zp#Qe-4TLSFN$MN%j<`?p$;z_Gg2s~VB6)P}4l{w391tX0)g!l*m1x? zTuRd9aNhqU-bmU^X|jG?Z~lg+9ahhtvD*x1Sqt_qfDVkac5r)2bPoTaA~o@iaxrjB!Y$is6uV5J@GGC47EorVmu z&xxHk5N~+iFrf{~a&w7s-v$08{k0xg?Dr;itNR~5KqU1I4S5cBjqgJp?Z=2xqk4&= zQQu&5o>xT#T?-DJxy}MOJyKrT_6no+#(}+NX7G?)AhJ5J*Y7%J*R1V71s!0ctFQOy z!d9XZ8j*0)yc=3HV8L;X=9__`;WEeC{rt8JC*du(?b@>E-V7WzHjnrgk8r*q6e1J& zcIDb*lwc@geEdH*pII-yV5CsZ&zzyvR`S-p12(+k{U_LhN5#ce>`jwEXKzacMYU{a z4G$|v1O}?|<@usvc27pGog0T&R$kHjqo&3Y@I5y-cjcXhZ(v}bIN=k5rq_rB&Ta>3 z8!lD*`M4yg!06CWv(?>E@Q)nuBgq8BJhVCVo=|!f78DeGpu~5{9J0wO2g;&P5r_y| z3ap_9@aQ?#6eLe9D1e!J^at~vL}fjZV`{?Gp#eq30m|M}wo zy#s+2gY;C@Zl%?Nmq!S;|9)dPH7^p_5HY|#CwTkM$PG6gdWDZDCsp$_Z*h=dI(leV z*!nI}FE1}QN?+o5abf9z11Rn`akL%+cjIyZ#^He^X8>Zh2QsE^`Xq|=Upo}UhnsyR zQ$rYJ_BK2J*{J97=huNHTNeTD>c7kIVU_yXXEInr7pC?CLaE7CKJ?-Nro%;m0#mn4 z&1FdNe>%KJe=RL5Bj+IT_=Arv*Z@zRvOlx-cg$w+_1x0Z1y$g@JGbt}G4<6<+Q9yP_r#i5mQ$^Yp%iE$n>Em)4rii?Xej^yWm zF;Xx)H>YcE-cw%RQlyI+lw;OSRqFs~YgdaPP0BD`QS|;Gd%Y%b5<$;n^x@XCs*b&e(;d=lx+`MWC}Y)D zZ{EB-L~=j*E9)Cm{I5i;V<~<#G*%_b;C>|&qh{Tl31=~y_nGMyg+FO>CZ2ENWT_Za z-fo_|$AtHd*;wkDDQcORLCPL=%m0ua4{}RQUP( zgSbbHUh+%QCV;W!`JCdOj;^lP2~q4CceVj!d>&b>8ay>fL-=o1&?`{wd#3T5)zSJc0 zY&&%bIc3wk2~KUOak&S9p5v@LT|xEhcbr$h>Se^&hC1D zhVv#K7J7TO+WmncUhhqysz(-rTZO^?J$UW@{MY)kN_sny?HUA7_<9MrUv6TsXPBXs zAy24NyEFfF1+7`gHX{r!j+at2GuvDU?s=VHV{Hw1kb0Z;nim#snV&Mj=Ep{5qIKxH z1VM-9YB0F_p$=D8nd!>}cJN}revU_C9L<33llfmMDAX^;(@mi{{KBvdjPItd6H=h;(9(P7hc889O?Q+vDILs+| z{5=xRQtyby^YxXSuUgOZcObqjjYU4t`gIju5>xdiW|H?_Y}X-r%+Q?3 zh$D2F`kOZ#1|8v3Q&Wzr;tiOU^Ke$xvQw5I&VKm_>bR|?aE@}oKE`1(T7#N~qDKR% z*S94s_u3g1VxB%^XJ?;LzR80jzGQ8Ga@M+&;ryUG&mJFG_9hC~JMM=h331exmGR5~ zVf1aT_7h8%%Gt-5A=<404!Q=5YDrsGIm-H8#g@G;=>x5R@318fzu zUkmlxPO2ZqQ(`!;K_uR3Ii?)ueyZg#eb7p6A*onmrg6~a4HeiXR?ymClJ)D|pgs}+ z62J?1;KGN0dn4I3CU#z{sEpW+YB?;&7`0a1h^5A$<^yaGfv~7O81bfaKOQ$qk`pcl zikogmuvFtnsoolS9F!n(Yg-5cxl_D3S$^((n1g0^u|L|HCR8B5eOoS?<32E9TXp*g zu$i0FVIZ`27ut^2N4Ng~6}FyR{#GGR3vmK{jp}JoaC7d8V(T%R?<4}MKcJ{TZUH*H%yj%|t685AcGRninwml&)y0_TIA30WZU!2e6yP7H zxk|KpiKTe2c1F~`=z3S(IS6i$9=(P@=HF>(RPROHmW`^}-y2BVt}S=lj(YX#6|0s^qXD3C>JWjM^n0773EKpA36 zMNWui^j156Fg4)_u`fH(4Ds@F4 zfz1v*^)jEX!te`_Mk2eD*EEcc*UpfLpGmXOwv&sI3Q**U>^U(*P> z(K9kKZt+9f1^^UU+2!VwDq6L6CUyrSX2Y2h2Qud0D$3{Q=X>3@Y=Gzy4iPjKX)a)x z<-r^gCX-rFu+zbkUvswC2@V}9{P5@NL)l0Wp5Hk4ij9pe=do}%K`d90UxHXRg7b+E zR{Qm48@{Z>+XO+$A%TGy$!EDZFgSP$^i{b93|M!{@80DAjCIF8%dbbB0HrsdhzDud zjR3a+bueexZqERGYylxT*pS>$0u%-$=!;73`!sjrQ0EG}^$|j9o*bQe_a-kw5Woks z*LWH;RSCpff}p514ye5i)HF9Yrw{qt)z#J0vjvn|8_I&e1c&s&^$h1DGYqN zEQ?to(C(>WM#Z#0SfIg&Ymu1QgCdGGGbH!&7jxWDxWU-sq*3dw~nNupq&E z7yq*DzyWzHD)tx702cfG&&%48D@oAH&<+D#h*-@(-@Wt()~3UjYX!7}0%+si3o_(; z=j{@s`tl{_uR((VFp2vZRSkwB;`OS0LICkez*1>LN=Hu*8#6P1Gp~_>0U&R&jeo{% zn*HNRyqj=-a?sh+Ba){Ffe^jI68$X4{`x383(NXVm{Uy~z+m{rNOSz*9T7=M?BG3t zU;g=uO2qY89QG5OyC3-NpRbr7Kkn%572R>cBfMk#u@yWYeeoAvY9YrR9PQ1EdHYU) zdEdK0o%dz~g*yi5PeT6yr*SdqntD|?aFs`&<3DTZ3s!C$feZ}|1vrVH<%B>^87`*% z;LrgX)!7K~ke0fb#0z~Rqp0w3*Twdn91MSddUr8&P#>7L=-%sk_w%CSVm+|b1qv5X z$o#%oY8O#1u#y!3@{OP8kXI?*jm$P!|%QA%t4Q)v;;3{5zQbkAJ$d zV5hH;&$3xF?30SDz~ohnpB3UE_qn*vx?5#K1|zEqv@I zDgKUBfm;X&^t&Q^jS7b%h;0Fi7Qnh5%fG9f*ZrcRx?PsnFuuk?*Pw!EEl{f<8v;TN ztpbFXu+-k&1FWf1)A1rNZ%bZBG` zjbJL%d!V5l>JSOk7B#>=3$h~q_9$O!3M1>~e*^2MAmv->=VAEzsKQCd(n16f?;m-O zxmKoKCu!)m$CwWava;ZZn3D zC(1?FVCGfGlEK~=!mcX`4qJ7nTN4u#z&uuB#1L+G3#j%m>WU5#Fw)n5T{YL5%BF>V zln!XRv(|4G4(slp;d7wVN>>c&_JdDw3>7C=R-jR*>u`7~(<@oo>XQiz+mmKkOD#Bf z@$kN|@HqhgGYs`>s0o-~sZ~`1GcWsoVKkdqaRDGNU|(kRB+;HxIe-*qGAH1ED(Jzp zOdC15Zp`s?!08HmgoUj!-~Awa=zhrGv-xPKj|0$=ci#mk*7j^@gbIirO<~Lv;5%_^ zVaV)e9dI?mBO=mzDBN{zf&HSk0#xk%O2;WtjA7^pz^DQN?Ka`7v5zsr@fxfXxc?d& z)KZGT(Dxz`W(S50#PWrF$F`;P_WTesElS(Zf#Bc4!8wj;L>acCrFQGUUk9;;z6AGH zMkVhE7S*k>LWUX6K1u8ZkMDdOGtNl5wGEm`u-Y0#61koqw4Gp86Ci0P=5I+A#VN3}!lqeG(Aa z|6dG?(?a)?zf&a}0pO=g)=-6JGU^^TOgS>>Z&%NY&Yl;7 zYjm{ysVxw(PyZ@s&yImxT91Ungm&Uc_?^rU3T*I^l`b1^A`q=p>#ZT>B7!6{TN_}k zD>2frDecnCRM&p4;P4sOrPVsES9R7J>IPGBKvJ-%Vnsant2N)6#+ni6sjFF0dRA7} z+4{;#=%5)z(8s83r2PJ zupe&dy+`V$_Ty(6hA790fFeJAGAYHDjq4N&TW3>4_xTxZ7ZjN{xFm6LAwi<$FEJ6! zPu3(((|7?@hjsky-KU3@2Rf9In*8V0X-m63mmr_MVRehgBNmH>aJ0kvsjBBg3Sj{k zC$kz)@Ln3MHIU4_&a*`)dWus0o||~IH|bJa;=0$6bAe;~QK3q7(i_23zr)OO1EN}& zX>pOfGV6YcaxE_B4=+dU8JE%x$}L7qj~e>XLdX<~$HWefdxe~g2EPo9ei^JJs)Fk} z9o|KVDhnWEWqYW{s!iGsW5(6NT5VP(I#2Y~)A7y)$-uXXoy0QHZ0*W68Cs%-`sg9z zcA>Qet*h?tUEhptRLw-E+96_Li-K5$#g^10w$!FFMoNJQg?Wx6mtPQ!!b-U-(Q@~A z;GwdMuyUy}I7Ul_)%El8{=hC5ZKZ>4e<9LL$$Gf!rK+pR$zHkWnXTDyx?h&u?Ir(2 z*I)Z(Y!Y=&Fi$0EvW;!hK~lwVO%b!HhrHc0g7FVw+T}H-(|bkZ#1TPtD->Mpg2IJK zqQsEP&#@Z))5OH`0}{pX03h^6?w(m^GDK+ZSm@kQtrDV=^8Gsh#mK(BQ&vGGoL#G~ z=qVM5JPq#+Sm_O{2)S(c)%-;LmJ1G~L-Yo}`(=)dPE>t2P+p-CRTIyYHSxBx&b2>u zFH4{7;b_D(r=g^EPqD-1DJkiAKYUG3`fPnFYl2B}XeFMjicDWddA(Cd`)wWb0iDU_ z#`P%qtx8MyxHTo@vfMvlmepw;xL@k*6g(j*rOT#^-XGf2|Ffg9U2imBU`~i+Qr}(7 z9o4o2(PP?1;lBYlKndxMyTV7#7wA_ zmIkU1*CzY$oRnyMuM)wM3Rr4iTU9RMq@RRbN^#C38!E64^L_xn5ACFd+RlkUyV8p) z{jH^^5OMrUhitlvWOjE1mSn zM=7e(^q!vEQ41d`omQiD=L&S)X7Y7A$#aFOh&zmBy0cg5RII zhM1dzw>qncn6@`kT29f2$W+>lVW|CPm0zih!_Q_e@5F?p6UB&NH?!5-gDcA5xC}#I zT3mm`(doxYFE5oa+c-(cwMi8E1};WS20Ts=?uvEy*=D5_IS4tGp}5=j%(rK{>Mm1h z0=O^U`JFOQr|;A&ANmE&la$uWGhrh!7oe%k4{`x5X^dhHOAy8qrYG5fM@g+{D^)$&P z5oSMa{~9uiI!U1-78Wo;?R9wVMYvYiY!vPlwQZryGjQ}QDo$NgiTQ$b!tfxMv5^(X zr*MHl=uYXW7k8r0%w0aKhhc&+(J~R0IK*i{tRw8V@6p3i_Biy=6w(0EvCRHy^<(=1 zKHbSlAF{VM8ZjvAcc&K$?yuUl0_X=O@iJ?S&??Ql`Wm2K~dAk!lj+Ummzs`a4FHXO(ojA;#lG)4(E*lAf< zOgZmRQ$J!EQKely2wX>w9Ty6HU!b-}AVKOQ-p442I z{tZA}ikR7Xrro|cl6792{keT0ig<3IprZx<@gW+X6_G!T4%pWguBO?UYzgvBm90Z} zryS5Bpt4bP9cg9|F`J7>#pNtB?dlWu!B;9d)3DmhEYS15sdKNQ+6PfxCkJ3)HGcHC z!GU;|<*d3ek;St2kO~`gFJwUQk=*ghWCsynwwe2!qALNUFW|y6`|@~W_$R8mG<8X# zN2@O1<+^z+|L(F8QQCJYMeDheNkfZ?6&3>}sHO_6(N8)^WaSeZLAKU==kAK@ywh4I zeYvoNI#aZ&>q8w^cir>s1m^=GR8%SsL@o;JR^9x)|Hbp_%5YND>snNLW!zzqY-xnS zU~9nf1cQbGop8>|AE=t5Vw7BQtIk>O_-#72cgnKqI#$Ee2e63|a}*^t(QQ+~k8QVHWI~^2af|QS#m@ zGbdofW=S~&3z-=v*__xhe~NoiS8RSTZ;(ABFYSbzF2uoq5>=@n)efZO1aVXzG25d~ z!PC~vrY%}k0khZbUD_)IRAWE&wCP`|y2q+0KFJ4W}qxschlclxGIBq&?tX`uFs{K`d-|GLzVuY3|Efn1Bdz)g;1`{LDY zRyrHE^Civp4g-UFjl(~k-zDnLcXBMEOqsi13(G$ez0(vbsN}sbsomBOb8(g4o8KkQ zeZqcf;505H!dz?lmynCDrm&Z@LRYuPgSkE-?&x6GK}1FSwv=Mg=iyYRZ1VH&$pM64 z+l=#e?Py|x%|6|A$hX&6VR20@b>&!{J)Y~djkwEo4{4B%t||QN@-#$MZAfo+7Qa=? z{$O>!1|X*SR5;V{)LTzY?x{M|O0BwVGgY!z*1g2CK~#u)VU8aWS^r*JQ9a^yFAEdg zu4gvnXI_oHsg<^E&LZLQa<6u^>A*&tJHG=eG%b77Jjb=V=(7viLlUR&S^^I1c0J<^ zUV$`RIV**yl8}3v|B2={Se1YPW4_y_NhTst$$V|#Al&f?cqh7*yI#I=k9nmPZP(JG zf(Vunj|>tmg;2$Pf0>V^a!%9xQ7v=>31AAul%j9=KYTGsQ*< z0kXjRxVAB_6eX~6&Z{xohjor-t*xz}a&alGm`!Fa&;X6%ZK7d!uJdscgy6SH{`HQ) zE)@_w9?89MeTqQP7NqCWdz_q{{*Qm8`sU3KftpHGpkovUkC|#m8D7Pdcrw^DTI1-= zCT$Jms~QXt1>yCFpW%H~cI#f$v=DD>aHer|N5hlQqE20FQy#>kxvBDN-=ljgK{i&S zWQWC#j|7zjfcuuOkR-CUww8%FbLwps1R+-<#idq46K$OY0SXEVOp=ui>q+XEn`7d^ zN-K;jD0>hU#w7VXBzCiPMCy!s6Pf&qii+?EC~qF!{gj1up4BOzeSY`;{d+R0XV0G1 zCn4gnIa%=>=mNVed40Hmj^&>#zLNAa!hN#HHG*uf}p?0Q$tnR(CuPuHKMRECJX9i5a^EFG3LLfq1z6&doiat5xDP z&q1HUzf)+hg0%7-Y?wx~#B9LuQEQS#Tu?e6Yl8l@jwc{suua%A@t$s;Z-YR`35gwB2h(^mM#e z+p6U@Cy^&MdMjo#1ab=?ueStZE>KXgq10Pbwl_SgQWq;wZUPhGEzh-Jz6t@SE&-1l zoAwwc9R0GnnS@$P5;>~uO*mG*iH$aVN*Az$W42z2p3M=1E4VWA@@7ucShwq{m(E`R z%3_oTK?ppeyL=!$3X0Gw%EjJbNd@`p0SSe+Bd`#gv|V>w0GjLeI#^E6qAGzX(6j@w zIY6VhSBcKX+C<2Y$gg38fZPrsBaDf{aesP4CbhJ*M9pJ527+(ta&aIpL4L#y>;RBu z+${`t%Sld726>nvC57(xc3+oU7XtNIEML3U`2c?V=mrouK{4c3nEgqhc`RH6H!*1m z^Dq$Yfix7pQ&n{U(ks1(cgj-2%E}5P^gRrFB0yXM)Bc;sz+mCOi5d(R{!0v4Ec~w^ zhF8I$Y6vuOb`&u{2HDBK*mFXwxaRKPI#sHOYdcZ!di zmmoNkK*LXw#u8kFre@VX_oqt5@tDnP13v@ACABbryNH=t27oPD=5vkTq37#53$&LY zx*gr!!k}nM diff --git a/localization/autoware_ekf_localizer/media/ekf_smooth_update.png b/localization/autoware_ekf_localizer/media/ekf_smooth_update.png deleted file mode 100644 index 7ac26fc604c6f38b2a4fb4a99af3541237666aae..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 146470 zcmeFZg;!MF+dj_o=z{?WNJt3CAR#Rs0*W9A(%ni9F$_I4Dj^*zAT13;$Izt+f^;`S z*U&I@d^ewuKJV{8_^o%X_bivr;LJH^-}}0*`?~MF4?)U`G6c7&ZsXwK5WJL?QpLf! z$%un<-S_6-;3pmYZ+E~y*Bm8Zs^7eMb7EF$2E3(olGb)ogPS`c-Z+@ySlGg0W*m+t z4rXSyj!?MM*0n})9GnL@FQuNTyC$wr*}Hzi)?Z#C_=`pJSCUi;8C5?Q*F@3UW!(6z zE<8f7Up4SRl;M0%m@jq{YKN8|cgxzSDr6Xv(6%4R5_w(XUZnBh4UVG9`AaKxP0xI6g1FQxnsrnNUAk-L_cM zj0{EO{^5qFhQ9P3_1)StGDJ7uSg^d7)=2#z>6w~dId8HoR997M;I6^W%7q=&(RXVn zxZj_bqat%C0W$77;^}roIduKswRryn2q0djs4B^89A5e1%jY$ zHTe+of?ZgMRXd(X^Shao+K^x^!4|Ik^Pz|1!{pRkRCcN5Q?r^4&A;!fby_1zP|9e# zijLrgS{d1AO2sV`Y*Y~K+5=@KQF``+L?bkb895Bi}JJnP-0%Z#pr!T zv*?J*V{dg`R4!L??{}rx(_gx*76vCZTw1V#hulUqJHujqJB7dXrAcG*OxOC0)6M_hOB190;xfTT zt)AMoLZoBn&nL$7-ne?lB1JN1hwUSq)>p;G~oT()r)7P>`*ryJe z@-0y?Czy9X;`GWXTy2W%Gvw%B&tuioH${C36&8N+sYSDH|6(n`UCVG?uA zbIU4TO4X7ua>9D``nA&*{{e*;CW_&G&{A^pTCD;f;d~2J%8FV`>&5NRIiP~pYBc@L`LB2JEqo^o(=B%v=pW!hb+_D~rW&;QNo#6#=t=H*{| zc^b((W?Eeh-I*f87*((IP@@MHJe)LElcfDMLo7=lTS$i6m$n3SksPGTkdlHc@9 zS4>YIs>GhCq4V3+T5@ZnO`MKDOs(mKRPu|d8Q34rLG;$tlu)GIM*1~1B>r_=oOwW7D>ApMCD)LCHnLIA;FHfap|q7}#-M=rSep%zl^{^# zsAj-1G3s?-v(*r0R#w)am!vgKA-1(aF&)KBlj|K_nnj#Ii==_NE6qpxmMj~{t-WwH zk^q=y2$OIzt(OZP;-BkU3%g#oH<+J-C=?`G74u-_wu_b%xHF-*mD-A8T#gH4Fqd&_ z78X1&8;-ALsJHyWdq8V>Mi|SF$Ux*ecC0lsc)k1$RsF8QvvcY}eT|2lkdL9#5v|gk z&;Z{+tE437HrJUFufFo+oJ*NPWYxcBGb<16jLQt4%K7nKWwY}W@Dso`Z$Agq&QpsRViAlCId2hNiMCS@sjE8 zwR^I6Jv@`iVq%i4HNhejw9+Kwh_Wv$himPJq!T3HRT}6E?cU3;pfs1hyOZ7rjg1+_9Da7{i0O}#@8>Dfqw_WHuB0I7pCF?? z3TSC=@JQ;Df?|9tLSv9avkp2^nDFxTwUnYXQlVhD0QTOK5uO#(AUo6q%3G%OdVqcz zs>xVD7D5~5bkLYQI-y*WQLxccK&_?y&u@SQP;51sbha2eW!~_Q9$TD{xbH8ncgetC zkymAv?36%|*3Fq`X{FHhVMXjNvd1&c$bfS6M6DK*Mp`u@P~Lh%C$kmie{B&Dw{6&|J^KI2i+I+ z*Ft?gVI^YXJ(@*qQKrPv*fdmrMj~~lS zKG{$tYT&?rpMr1VX^F<>69i9tR2U%-uv(FougKB(UZOzj9A?8G*QU zkxrz2*(M8`g376^<`7oU$Yqi&S6Ft?YnS3~VRizU@E+$mi#}d&Yc*TyjJGy~g_(Ij zz5_!anS5}Y(GQQGT8@+c?b>Eooq!x#)KYisn!Ofsw$(ZB=He|+%EdnRsF7gQ`s@}x z(L>`FF(@*SH?V+2LVm697Az+VliOwA@F24|FLCTf+0In^V8i2M)S6>SJy15UkHpav zu8LymgFP*a1agIGfyN$R9}9H;Qm>C=#1_;!mAv49L+uFTbH9$(72Sy)^K>zt-+hqW+eTf%>JmwRU9$NKex)t&=KMIE-u`~Asmykd8xQg5;Kr|ks8I4C zsr~5?6_fg+2JcZuUwqB2fHkMCAR2ftqm72D$$1AYsBm_Fovpo*tOkm4&J_6a zKU<1-{>y@yH9N8e0?1PIML~}T?3!jcf1^Lu!u4`Rks_^}d6P_eC zyn3>|fGM{oeLhi>PWQq}&%WX=(uDfr%cnfVA;yI>BVfTp_qizV zrdBCq6@xSCvvJSuiQYqVCsjip)tQ-5yNpA1#JaKvrn>;kRtArWG}2E@u5~OI6OoJ< zTgT_4S-I?UQ9@a?-c-;yw2CO$(qu~i*2Q5oXY-r#g|D@wryrz^ZcdDjSD=Jevy|F5`$qk;Q3xLL2i9=n-MjgoKL`& ztHU`G=oV^{%Aw%|DdjSWyoBmmizLP^vUJC;t1o|?i>myo>7e2GuFLzwKum0X)HD7? z0{x~RE$G||n$(LRQd~#-_G6dzJf@aMK1exORuJ($#iR=e#Wv)}jaMZ9Gj)``jg>2RZhxp+De`^Z`P@twhs z>s>;3;Sxlc%f8pBuJ#z~jD_*rc>QcbC>h+C6H0*CcvWR+N2#3}dM8w=aMf_a$|=V& zxQy|+7dtPmOISE<*OzGGuq^UtcUyF!G$kZM=5*EH{8dN|k{;?FX6@ef9WobFntULa z%0Y&L(riR^n2KMO&)|65(aeJH=8a-GzH`_N{-DxY7-nN)3^-<|U>vhCvYx#wxh{MQ zMkKeNY!$k-8@c_wskD;7UcF46Nk&YpL6iE4y@=VQ&mhSo_njoj8Z3mCrUkuNhVKUN{~sGf*g~FJnOEV ze?Lrl$99_PcBS+k>GY%$ZAfa^5{nNzt-NzKYKSv#RTO$MlB3wv%W1sQbwX14ZhRW2WySs~Jv-_WkfglV;x= z2Yss{S-nM$JH*#7^-lcP(*#pQn#bU2H5ChT^~uY33-P#{i;oIKqXnU2*F1#3kj@{A zsC4i7%a$M0aTIw!x=&YYdA(ig@M*j5*-DEIPSjux$uj(Rf}2^hCtD`)&Hd+&*1KkB zBQuy1-~RU#B=Z@}i<+JJyECCC*OUR~=&sv4TVGmpiOYIbQeQ~_A#H)+{Md2d+OpN_ zCvf%GL@f{c5jr2QX}R?Jix|Z}Furg3D5LOo%STo8bm&A@PQ{q?@Txig2=ud{?;~}wk6hau9GwtM>cEPV(jI|&=1Y9c@_Uh zCIcUS{KIaP?o61UV5-U-;Vz-&znQ#8fIf60EdP?9WfBm&@hwwN)Ck%a?UjTS!}2Gn zIg;<{V?`@Q#JO!oza~86C$LHIrZ>X>J;Ju&I(oKKPY-u?0rH5j=l|g5IlCkMO!>y$ z8V=f_p0ACdn5Kr_^r0RzPGMukUjE{^y}S`+^|-y-E?z4f=dUL{oPTUEA*x+4FkoQNbnj0OrL?wmFTizz$!98FBNIX1 zRW~-^R1yKVz`wy}WL{};KKOlXSp9KHh1arPb|Z8Dc+`n-k2!VQEuc{yO0Dj%8Mc@s z1EosCwg_Qv4|sMP+Dp>=2IELEU6dq*S$YGF(7t?o$&|L~VVh%_ePyJNZ?$WxSBBvo zKgk-&zgui8v9XDvsP%>~=V`xl=<8xOQTWOoaUB)x=SE9Cz4G+-!+vRkY%31Y=G8Z5 z6J5i^)DdK-knFKYWVRco?b*8u6Ki>-v2$t}iwV0o$P$wjjtZ+OCP@sP^0L<}%k^iZ za9{{-zW#sY{F{~? zXDBRn;NyvLIX{2WRwEHdgM`DI0jb|}rSDw0UiVGY1#W*5wAV|Lw|1bvvXWmhQhBjB zxRUp6P2ZTh#9MhmQ{Wx2LbH`>;n*Op zKoBeAQfZd(Eo~#W0M;{cE#|N~^J%FCae?w|t>}t@I+DhNpXJ z6i;n{>+ZywSMw5!Oakj>o;8Vdb#D-r?ooSiO?~s7>7NO-26V3sMD`qtJbD*Z4A}Hn z-5$;okX^hfQhK6|{mS+6TwWW>C1)@%1y!>frH&re(5i9pN|>|bl-=qi4oMMBmsG($ zcpywglf~v+KS!+PWBw`hM9bs+Mrj7QK`PP%`CJSV1a*~{x7ocZO#0ucdz;rsmMkb+ zn7*_~l`V|5)*40lL@h2E_b_126W-5?MYZ+0*74GA1WFzF`6iq>M-=Lc{8U{rlqgQ? z4&_0Y8SZV@8{HnhVU@SFLN}qXuDhi>munqv{(>neJo1u0doOA*!%yGin0M&Fv2|D` zm##&mx&P9HXU->$b22w5FedOtc=*q2TgRM--vm@QnL~A9hV<=jGPEm<92+qoNuEXM}1O?Ta5h$iq zG`I^z=nhBN<+eKehL14Yz4;H&Rti(kV0tiYmMrAa$H6(8KBtr=k2UMq3_0QPa;sFw zA>MDYOI@#|B)QZ%k{ioywJ!69Ppy!xZ0~+6irtuq2iXd2LR;Xp!{#WTlLh`{(8Kma zK}4p@4nL@v&Bfq{A*(yk%=||lUeDlGt~&M?yKUSA;r#9&28(oIjx^zJ0(uvbZuk|Y zMua2HE7$?*{rC?FEU&%oJdo1qqJl$RA5XLodO*RAcnU# z$Gi-Ar_PEq7cMcRsuL+P^sAL#5LNjtsjwMqZ2j8IiU|ER-ePP6@BV?#(z5{ueDjgL zjpmWE+SbPleLlWv@m))Gp{#hnsM04oEHV^zO6|8b)?i+p;w!w1IvWU~B>Af^Iwe)y zpfY(5|6rVqapH9NESM>Qjv5yYI9+1vK7lTIjW!&Ff0L#r1!hcO!aOPUPTW0X&Rm!n z)@<_+64@rA#T%bVNqw%KZrVI3P;#d^z85c&Q>Gu?Qz7LtT#MK6O8N1x-6?8B#UR>3 zYk;9K2xR9!O2|ki(42mf#6givZFtb@o(mqR?*Q-BHuU4dm3R zXU@*M*~)$8r2+!mTxTO|6*bIrUL$!sI$!yE1BGwfs zfr~*)h00e}JK?gXJ`dgbqISN)Hl6kK4D+7&eE2Q1h2r;WGS0PR9lMs5BU_NRMdxzA14$D-Wy-Pv-~l$+ij`ifkoTb@eU&!Z2m0)+uOK^ z3Moh*R7+BxHQ1_zTzg|Lse92ZS$cSHB)^f)cj(kAWHr|cotHWs?kY*j-(!UuOA0An zzHcI5GF?{U{6=TyI3SCLqkyK*Rg%QlD)|kYgV5BWmh0w9ZFKNstyQBcS&TxUX~(Pb zj6h>HkBT8|I@4tlwXbON22F`;MAkxlL0NEcY*oF)uE?$ot89I`14bON!syc+qukLT z%a`1Xj}%7hLb+Tx4_&o{I&q0r6s(ZR(?5D~e!O;;m{6^QC|^3LaZgf-Q7P?DrR%t4 z=M6e4jXnJfcVb*YFIr~gG(j)j;Fd~(z=sZgiy2&Gh}H9n{2`?y-&t9{)JN6k^4_Ua zv#eA#k3S5ZFSr~sz!ZwEzZccjW$1%GiR$H(RvGfNPAzCF`LUrhTWZi7um0cgQ}DLi zMHf_Y8V--r*ctKr)*d0-ggp+{T}N<2c{id})pR~FLDGa$!fbuEdE%S?o4)PFj`vN7 zqlyd=L5hdj$heTTw3j8~ll=|f9#4KM)!p{S^vBMn30WNy|Jm%1){qoGnZO`JIm$vmItk7V?W?zu7?6F0fFwraRjj};U z!oR9M|GU~0x`OhF7Q0lETBw1`%_hxN$=pAbolW9dWFn68;`(LH_Os@C%dFE zV*qWCV8dOx1q=a(>d#jlrs?*jmP==uWIg`#?avg-&k2SOIXM$;c@*0o zD<AOQJhA|vUcc; zbW8WX{tstS$ssj1O^hw<48NH)c8-;H+u|UOf?xW2p3>nOrZ{}+tkVcT(-}94CD{Pc zdBwy zJIgm!j#Ez3K;8PL(BGzOGDDD(@k7<$G0CaWor)PIAMD}t4FZmLWL^q$1c&4v0*v_x zzynS`${Lf?=kJzTB_|+y&Dd_dMCDWpGGAGQUYGB?ZPVCg@lRgJz`%oStL0Mco33^3 z*@B9=8bbeg0gYIJ4_5J&g-Iio(9gpMj6F+|3_iJV&^XS@smT}Lx2i6H?_cyeq|{c;E$*%@c87JS6LVCh3Vc>h?6E~( zd_`>;46(5W>o;T(T(kwF1c-&lSI~F0$cNyB(RylPu@d!FD}66~9K#$J{r|axD=k%i z{w^l^-LQqh`BvZeA;LmJ>xy3^x>m9K^%WKFX3`}cT6@Jk^=17`5Ca8%>hD2MMp|j~ z>UpK47D|u-Jhc`HvYRbNPhYQ>B;WnbANHE@#m=7)h-0i7Y;VJdXdVlJY@LmK8BU9F zmES|f1Uzk>lkUsX(kmaM?Wv=$m6f^1g-e24d$^+xNE6(3TKtoBr&S@fK{_Ou_O=bo zD&HV3{H~P2g2Pgf%U7}fku>JMB+_<`SCj@5wA0fQ)Oh-@M(o`s zXZT2ejncnVh$`u!mb!l!GnUEG+dF({J&_j%3;0iu$t7shkEwsrNQB;k=u>vC%tP9( zP3tUaUx`EZ3Y}0AhftC+jHoLJsY7j0hk3@f_fzGt8BHc>|y)*gi zgvfZ|mk@G!Xqx{B>77EZ?3HC=;+H>6yyzsQUinTl8y9Q0QQK7;ZxTHC^{aI{dfwpr zf2P05Y$f2I-D$mRJ*O6q=VLFG|Lg@2p@;D7)I2V-D9m;;G{9y(bxoS0pKZz#aPDjE zr(EX4P-8nCUFn?SdxTk9AtBFHJ)Zp>ax;sjPLw_-XVg;p2y39z;Ag}gXD$1+*1WkU zmRivDZ3gpAxvbGWr14-371qUnug1s;nf;8BLQ2Y}gLTTWr^_L9_&Cea@D*lg|5X`I z>)rq1=~#nJg5AI3UTOK1rjSdgDzwG@@r6i!u}T9W(RS=>S-U9 zRz)=>@Sg%d&0NgvWC|GS&mC0b11ynWmaFUb^rwGHVen6BchzBqdG4(PC!@l9tS6!` zoeuHa?*;Jabq46!*hT2ZcUEQ}m z$~b4ksFttN-)DbBUK0!2*T0+Bg_K>BS|uzNB^5{8ki4#o{Ie&b4N|1MG|3Ec*d_>S zqmK>#%DkD*B+^uhI3mvxZyZ59b zH>RaWN=iyaf!z0D_=_96{)Nie_<%30A3>W30*Okwr?=iReJ?G}fElv!m{`6+nmFo7 z9=}os1F78B$yaGl%vs+aCtDd<0b&eVieH0K20hoxu}W<*&AWLJ7?^`+(5?T{X6JYy ziJ9Rd`|mzSk87NS{}a~Q3A$L2iGu>y#~uz({5XTfIeZFiliBJx-P-T*_#&i3K4ge| zuYUNe|ChqW*HPAv#4$|{9<-X?#AJn)n)J@uR|}nzmQm`dsln0vedf_xh2=qkLQghz zE^26o3QNEIeA6F}vh`won0JleEi+HR-_v^7nr(8CP~F4FV9h5d$4)-ix^T=iQd>r- zijlO(aj3{8Fpwg6ip{1WyLpH)L@!n}KfqPb(Ztj{8lj1TFLad=gs&MD5>$_zHW&@o ze6JrgUpp@rE3bYunJbdQj==h}94G&}u_mc>gN>ZLGM}Y_>Ml%_N{@qf%O<7q`NQ@Z zPEJuz#^1e+(3ObBDkrt*9t3_**MjfZ%(u{mQ^j3$n2e~QSwAh_m zHy_X1li*vch2&0#F(-?|d3os?agkV2(LI^2rMLOHxA;ahV4C@5Ayb(5Lx*G01{w-5 zRB9Kt;mHR?oX33k#sRbEJDA?N=-e%pK~KG%U-2jW(S`3XbQ6{Ma5IoDYVrfT9C8g) zZV^7G=?7Vi{2$k8+@=`7Vn#=IS`D+;JDQ7lh4=+sn>{g9Pay}_%dM5KLMiyLBwd|z zjPd~98x>eL8S0yJcP~$4U~6Gt75-wPn1@T9^>2@1H+G5v#`&JZ(qI!C33CU>VMkp` zsF4B=C&Rxxc{oS2={ka3fJba+``ms!Z$R+2jeok24Y zCue7xC$4sNc@&I#PqGpd<0AZ8Yr{i`>d>Eg-@AnwD$?VogOVH<= zh#Q2oPrOc?&};+QN-3gkYJj=$CmeDEj<^ls0+B5iO1pQ z`7EK2kk`q6NkP+Vm(Qen0d(Evql0+sjKuDR$gJ#PkBF(s!|xx*ho7U;)n?lcaIJ=q zllDN`Vf=U77WYT=*^*$YvaHlArh&tT!+L7ls#$9EQR~k9&%-TrqvLY7${zn~Aocsy@~#U9WHCWhu(6lBuFEcO~ry;zN47y%3k(qY|Ir?Sr@Z({9U24aIM! z>)fKFqxY73QUqY}eNc85mZNWk-rH>q5no{)e7>#Y#4q%>Gw@xsEwD6+Xd^;FPrgmmfE7ac4!M@@CjpzUL- zu+~-S%n01{mr;eqTQVVd*;HYl6nO6y?ru=kHK}QhUdmdQz-H>mdi>_R{(8=%{-&$s z32FaFdvubpuyAXCtlHLw)n3sfjtZSut@qO{&7-U}rYcq<2}#iv(`CiIJY!J4E_Mek zLFdroVp8tzFX-Qs{~)j7!E6Avt#-A;Vzo@RLc&4O2y7BLF$@{TG*+p zkVb847bEu<$uSN}$KSP~YR?CHFz^WZeu$;v|? zGo3wJH0K@}z0q`^o8|Zm{XA9K$r^*3ZOpQtpBEd8^b-AXY!`NF-XdZ|MjUj5Ee5oh zLY#xL>pHF0ZP7K4lo!XT+y%<9?=BuujEA!>A7UW537F(xbE~bJUSW%jQJI29-{o)X zqcArv2cp5!y8eWds^I2TWzW8hsnb9<)Faebb+PQ&RUJrMNo!T>(}WPcUnaI`%el~8{;?E&F2`}O%TJLAaIsE3Po ziIK?ZL?_b5D#vL_I>EcaYUh4PyK4FVh1F$vl}l8%s>9H;MrtVsGDdk5V&XnXk-7(Y zHy@>A=qH7&T=I~XIXAP6uq2cedkiV8gH^5jHK)&$M?tQjqa}qvsD9RWw&M?ev;~nM zw9Dmg{GHyLws-gTPQ8V^&yLD12TJ)xz0X|D=j}}mHEZiLL`u_3a)n8)?gSX>(s||< zZhm{ZqJtPFpmqv*QeW<>Aj>N%7NI4AmyblUr1__?7EDKBIf9>&636LjR(HB@s?2u@ z5cf&(5id>>PcE!P-w9>?ALev)bR>Y`2azyeoHky1VAqD4D^^!lM$0TB0zH>S(beTc zW^a^X@^#j+t|PXQKWKf9y~qf-)Q9rzhPbHggTKdS`L7B1-Nltr*gHU#-7r+B>*%@Rs4Y|l1d9;aNo zZT8LojJRA9Y$T34J3DI$xo5OC7qAi}b3mvo_7e0d^$hYKnnYb=D6q|thfrbeKC-JZ zH`Ba(J3vOi)l#!WOsl-YPQGVm1SJI#^ZI7R#urF#8D^>oU9q&ZtR4L)?XA4uzXhWv z`nVgBsF)qNK3(t896)e-xFzAXn-S>bT}|isNUJa ziBH1!i%>Gg@y{M7XhdBM8I}{0l&I)`WElY<-GTBY-G4Z*U~MHC4|!Qo%bfltV>n6n z99aW)MD$bUxbZN=%C;tG-qXn<*VwvC97UbcB zw1+MjT`U?gDa7yBg5-X*GtX7e=alsIky_T-_6Lde2_1KQOAZtw7Pl1Nf)y|C8sS9! zrOM`|w*fZod#^*RNr3dnsU5LztuSKeX9^lY5XeW1vc;EBAFt!{662vY_q2XtPoH}X zBda>LFxTAFx*wzNl~aQxmX=mFafT$?1I7DM%688+3}PqF-ws%@sXrXtceRurMRs!) z=~z07&F%$=U8D%(A>1bM3bJ~P3%bG-Jm!YU{@QxqPzYO$a6dzwQg3pF!|g?P85@{K zDNr6-QeFxBBLt!1|6*{t#Ad9t+HtwzWGxT4msgEKfR0yAqa%hRfzPu4i&kXlhe|#( z(Hx{9acyaiKzXxfSt@-MgYrEkXs{Iri-VY^!MSW)0elO$MW;Ho4omEFMCRiZGa@Wf zc3*vji&}6=a|m`j--txnVl;`(Gxg_G1+BH4S}i=HQIoy%deBe#sNy^Ai|BQFK=L(}HFU zwgr;nWW7!m)}horR%Y?D_RltRBg&uQG@`&G?XM1SNq6GRRMI!tU>fBFOG-tY)W7SHLDxpMQ{A7`HCsU}34+ ztig1{Tn^U9F3-`INrG@g9i6e+<_}zMaX2Se<^Fc`?BVHF4W_Wc$I55%zJzxj+@Tp( zIc3gA)dP!s#RTpcdu2LS*Vg8^uCDjmNkdC3_VZ_OK_gWenGb;!_yIO-kFFeIu-|zR2Y>*64HTsum(jhCm5bS~K|raY8)J``0i#bb&Z zlN*V^*>N&p6BQiH%rYvU_2Bi+qqrs7?017G@Nvt=o;a@!%Inj<<-5wg+)Lew!UMy@ z2YoVhQ=WTWptc5O=yJvJ(R>8jZJ8#$?+YyW3Nvr>l;Q9#y33=V)dU#Dn@TAJbUy$l0p~ zu~(kAN`GUz{&X-`jfCk{6{fH@0Ji<@2Hn{P+=nEJ8eX?EfxbA%EV$G3;Hu&Cx)X&$ zB?;L}O4&A^AAnD9PU5zkI!si+AjW)D@Y;}tu8|~0=bS%4?Hb(gv{E3opp+m08+_d1zEpf@%*yW892M4Z>c1gC}GeD|Y=-JyL#5%Kftqr2U=Q@jpz07pO2 zc^|birv$cP0gdLv1ecbUHm7PUYim9FGhTusRuN8q4)Aoizn@|4y4NKr{V?v;3$RI@ zj}>BcIzD1sy%_WI6I0lU44BobGe8*t_A>xDBhQ_dk%j|QrvxRRf~e<_osv?|a*B_* zWq$^6*L8JuJB5c<_JBc~o0|x<*C7~6J2=ih&4zF_0IL7+*s4c>QYkSp5$-up4QjaN zV$7xfOYxJHbin&Waj)^$+zZRg*_Xv~n2ilFr+>TJ+q$KA>yzYHHNa#yo=$BYpg_NB-{|sW1WZo()=0g_A+3_M_wk8| zQ$uwPX8_a@{pRN3CdR8r^Gq`H@-PLJ)9&D}E3yD>@IG11zB)tWVf|M0=g(mF>`xCi z-~cV)>Z1b#BoRO1fK5J^hdz~KHfJU)cdvL$2dH@^Nk9idsHByYz~0*G%ZpRcDMAko zVXrXQ^zK@=ViFi{1b~3^Pa4D|h{^Ir`f)G_PmtiWE5rReS7_R5IJGr2oL(EsyT`5_ zS)I8DK6cpqoX}q~wH64KR^!PKn2-+}Ygd>=S&t;Z8z@6sq)fp{s;jF3FYJWwN69V# zLR^gt&>!n`de6``wZ8rw%mq;tAiax|6F~OleboJ$KsyUF>bR0I8Z5 zmsk4Iea`0TfW{uqf{|YwFN=wZUG>+%-Aw<3N4~$m&nF;oaDKX$9w9FG@NVUlOTq}| z3azeMUK&ss%nQH|K-6_@FqaD`cV`^$RZmeXUt2|4*>0sb6@7Ve2*$eklg`HzFa?y2 z)6OFXz^JQfIM?OTvi*#p^VvX+9BiR4fvnJodme$b;RYnrqANby)(+snpw>l0Qa$eRWj)8Arp^@#Ti;Ig23JT911lNv2XZ<=JOx1fJwx;WO;?@NlkGo7F z#LR7NlcS<`K1iIUmY47MralKnE;#2{jdNaOX;QMi3#Fc#4sV3VoDpz=G{7CSD<- zqi4Q+;L9mK7uDI>%WOq;JeK_rbJb4(@vc%gxKGSTQBPaj*MU`_?#4WEz`%@^n8+9y zBvn=-Y;4veJKgeE*VoSu8!xA(r!QKm;YUYDHsj@%%iT#NN92^{8zkXeGnxl@~-QB$+&aY^;l9Cd5!|~FOAd;@m&O7&owt>WVCW*$@*noy~ zK&7jzt0zz`_4Z+Kc%2?xb^C!DBnZOq+`2{Yr>(6mBrHrnio?B21Rg=AaKG&j0l_}O zVyuVrQyYXC{rvp>yS_Z0A4gdOCxcSVo~U!%`|gj&!NGx8AGP0IcDO$rz zXDgX%cX@HnteDsf680o50&#A1#teh7j(z)%4;H0W?=C#u~Ph@PRLVRBfQf|=RkilWDLbxlq0gE0$fX=(NM z`Hv{@Tm5d42*9V$p6&$1#KeFUC@3y|0W2IZzcC!%2)J3)aKg&K@ciN3YM?tn=0VWF z*)P}fima@x_^863KH#>mFc}6*6?sS`n07p5Vl2>e-GZz;tdzyt`MtfpZ{NO+kEe>3 zla4mnc$qh3ZeekWF}kb)!>@712*AcobE^0E2b5xCV|}ngT7wZ{34&kZ;@sTbRjF@; zy?CBvnE+hMTuTTI4b6uQl50)p^dJRt@3XS9UM0Psv>u&AHeUf+xG6&AV>!hx&-T=^ z6;b8o5B;1Fh=jN}a624&75Q3yo&}nEAk%4RWUA)Y)YeW-P8yq-balR%m6&p1m!iD@nFgdf$B-8alpedNwwT{x1`M_5#SWMi&}2PH*!I`Xg!f zueb%~axmt3(FpjOwKWDLhVD4t>=7@Z5TM1Vr>mPIrvn5BA0Pid0#z&`B2rpf`rg+! zJuMA5Q+mH&zMH4dJUu;uSo%CU-yg6-)xa%hfD!uq`SZ0Kcfi8)6EL#+3sv);WEdQd zo|@WNU%yXEDs^7Ag#n%>YhX1%>}uhssc0Cq4Uau9@VM%FF?n`uY;06vE+BJpHJ*Kx zlODogr>3TWP&|0>b!6C=2=b{NM3Rb{I+qaxgppY(`3bAMW{^~xIxC2k!n)QyBBJe1 z-ku+=t?}N9A>;4;KYWnrt##R)w1mUqHwBbeoNE02rNM}&Y7u}7O8gGJKqQj7zkQ?U z;VFe*@&bL*)MSd11tHg99ok*&_&Kk&0N4nm+~@KXJ!T`oFNrn5VBwwp{XDF!YY5

DVKZ*K5)vBvIJ~Tu|LNZYK z{5en)C#U_zj#w`*FOP79vvblDHwO?zfLeh2jkx(&so!nftAt5oAVI6NE^74;ZoORZ1$VwZ%mJ}v_{H@A?G>&%B=rlmS%=9Cplz}{He*bG{s&S{E+Lqoxe$J*GsV$q0}mX^=u z`5~Yc@GE_NeO`!Ea4zGLFYX>br#T?OkVtlRcAjK?yn@0R^5*sTGcz-wYy}dXJP(PI zeRy}(sb+iIZtc1l{g2L0_QzL8-%0_{zF2mhv_2>ji7eMG2np$U&ZXloIlDTLZDL}= z{OSw$5#r^;k3h@t?s3|n8^qYz*Q2!zA3vVvu35uiv3e%6ll^( zcze#&j*X8iCJOB|L}!7z=&E#l-tZk5EVA4GgtX|EnJb_}z!fB)Ki6T`?C}}ZEfC=4 z-2-6ai39C*vx|!huRVC7VZ9tIikwq_6wN0mCwG&cmX;Qj7PPM2INX2#$7dM3xVYT9 zbqlbnz7?>mV|niuJ*adM_V$#W1yH_tUtizGMjtJ$dkJ01;$Ah6NG3oUi{a42rG!@j z7Xxfwi?O|hg~gjUZ$O$YQrno1s;oTR^11YAKIohQ3Nm=NqLG2u>oEmBXDnuBrgv%z z+_jDStp};ft}{*V_V=Aox?)XcU{W|^eL%9lCX@W-)e>+ySN)fFbX3H|&(iyHi~@BF zK<8m;?--KsYCPVen5Yq44>!Z_CY6aOw`}r4+j=c1yp!O6qArmt* zGb6sjLRwlHZZa=GLsNQK$D%k$IbLOwMFzE5>Z~s>(KQDxuem3urjnA9qUFr&?1~>@ zj)6n)ImZ}*`1pnjCW;~ob8>R>^5h{=`ZZ3u@b-%x7JyYy3Dx78@#v_i5Yzu?Z@1h& z<;TMdX=-{}pqV#h1u&z)t}A~tHzx;l#kg!Is~+2B<}NLnqjc-t_LkmlEp2R^_serl z2~J0T`LZ%MC#jJIdI;jK+YjjdIu@xEevM$T2L}iBa`HnXBPkL-4He**MofBwga9Ve z3+;NcZ)p`WXv9>m&E8-?k4yiftE&L6NrV&ng85L$Ycf}DwLFzenhOa!-6sCnt5!jtUruP5)u-!vn_nyd^|hz zM4A~DKEDIMTHBX)HT1OtE(Hst}_P$*<03+!OCSi zY>SNo#Zb(4bZ`g`3?vF^advhlJYOkE*P?$Q2cY`w*{C3pWpTL%eT4LlR$bp zywA?c3OGSd|B##84%EnAgd5HXgi*b_M&8iL@iFC;8Hr?us-?6vpzZF#fxrnAhvH2j zXjq0ug5n`7i;0>#0c6C6mYq|E*bew~-J{qJfJ2$m=TCvn)7GZIX6^yMB~eI{vV}Q2 z-czSuxFOdFv$4s~&Fx!t^7i)j(qoZe5lBc%Ote{{?W02~VOztf74XHe&KGBHv=K5l zL3_sAWPcu%U2AJ=M@O#BfrdqJ7_8p=T!j7yuxn5&NdQ$7lXSVv;Najju9#kcg#P|3 zPhx%gpCxNt0E659@4L*=hoXzgx_WxRXYo^orKF_v6?J@Q2NF&~LXum0s#Ro26U{Wl zke;5-AR&PU-HWNI^LG#t5VnGXff$k)gYWF5nL_vjX5kdd)sn~yzTt-t7{i+kk) zTIXP>-%`S;-bP1jfc)w+#f7^H5;-UsfwF+KLRj8g1n#+@0LjI}R@S+_ zV^CxO5zTT)^AL7i>I7{Icg=9sydm&W;355p?tC!e(*-t%hP8nC$`c-3TLd=HkBFDI ztbt?rDx7bLR6zzaGAinWW+|myJWY5HngW2M;D?;C)^coBH_V`#g5|)%0bLn#=-jUr z77^)==f}JgQQZgG2^1p$_MlA%95vmF+C4HduvY{Z7q@iGhLxMQQ008|$|myBGLeVm z<>loPT2rjAuan-q4y>?WWMm{!`YIkEQWj4i;H>$6wQBC?Uy*iT1KKWw4$ijSfAYdD zP*@Gl?i3dnH{1yMVQddN<*~6^Xn!VW!+O(^0Jw4Ba zbhUPl&%k6R2|Jq46t?-AT3gq;W35Q$2>^i9#d;gMs6k#;W_fs?p*S))sIH|YBPB(_ zI*U|CzJLE7jHtU?(Z}azidhagY?KZ^3N?E49YOx(!@#1E>PUWOACN{D|b` zyhV0SArn1 zAD94~ww|8YjzzynQ0f~p8#sw1DYF30c+pt6xZ?^&{)tIp4P{#IdFhltlk3&;^01MNDFW=M4(ce zUtP5Vh8EEB*p&{^Qr>qS7x^cm>H6J>EC9Q<4V zA%dia2HDWxZ?4oRK@jx%1yfT~LB^<8{ITLB^8eU-^KdNRwrluml8OvPB1AHlBtsb@ z^E@Y0rX)j|B2$J^NFgLsQpud55HgmK6iJ38b4Vc~W&GB8xu5rb-|zeT`|rKBXM48o z*Xp-MbwC z@JvkcDJj*Cor34ijUqxu4j+3KQa?1!MZbl^20sZI)$b7Rfdd9v2B;{cH-C4Rh^2dl zH4C<}5jMVXAy0p#PE(3CB&+Z>2 zPkO^*81OttMxE;xR!RE^LdN?0$27ko>QCQkAL@*aj-E4mrYA`WgiEe4cY@A&{aT@I zar3QPh#}xzub7l3M$}n@-$-!Vd|l4Uu2*)V(}(}SfeLUS2yTn@EPxr24fZOgq zFG}0C!!Q&Uwl&v~g^^K-^)$i;k|1DUFhR}u>gq;SR{DWkYB@g#luQT{_oa4EQv^nZ zkP&@3jut$A#U>NDJ6T(!K@R?z_yXDxAfc+Ns&c!Nh^Qzl&|_otem`|4zSy@c;!e2b z+e3CRG4aw;ViPhmGcz7Ec|G6~!6xkkz6fi9@?)Cb*~P`hsKD}Nrj$vVUK(=nxpSL0 zZOSz+3|{az5`Gb6W2814d$!T?OPZ)s~7s^K*}my&k&ThYZ`dF%F76O% z>FDU_P7@s)yFW^0)~E7e$UU{RZYV_{N^Sl|H4JUJ{_4Sl2j+FB51CgWanGOtqp2I+ z5V$#r*fu&J?Lb&GB|F#HIswQaYR9n7#kTO+A*=RY974M za$g!8bav;DV|%pn-??WQBmzs{xnomQrQ_$f4B`YO{qoY%+omS4;$>z|C}MBkM46n? z_8rik$ef4#o`WbUZZybg_ls%M*V8jIGg}b52-XL`27wGA(fP^~9A;RBzm{DLp&c9= zl26kt!V6XK=FKerM^H_FV)tS5bU@Yp?%nL%9BZ}#6Onseue6L3@fNiSA`y^k+8{M} z=f_no9&T>q9(RG57onvX71~mV)PDCZ!MD79t0ox7vU8^a*u{i|#&2#zLqpP1QXAK= zOV*0Kb&DttS|!9jG_5Qz%7C^C4h}|;*PW(F(720=`15D18R$IUWVUkuWgmV0wjJ71 zRAM)bX!yc`lu5nnJg^k3vo(Q4xU@CFKLlro&-Nv_dAg|oqbx3c^b0qk* znFrLDCb}Ww{2?fEJ35x@a#1NMz>gPfZJ#3`LAHSe5Yg??)!lu3?vp-<3pY>CsWN#G z9#eCa8!FBFa9fcx=l4?tSvfjNnn#FAW6dTF3=Cj<-?VX~&Z5Xeol<-kh%n*(`>&6; zS?-NeL6N3U5j6ctUwd~YOJqY%Ru-YG0vdo_0=@*ZqnbPom&{>0~JWk_grKTSaLNsHum%^;Rw??b*jX3 z$~?L^V-9&LI~ah*k47zYKhf!+=|Zs(g3l7ifqGhhYo?xRc+& z0@}V$1gD{I@%ds|&+5{s4D!d&{_DxK^eikW()Y$RHmAt2@7QsMDNcopP;^i?K#Gx0 z^=lp)9E3a@la%zOt1GkBj%s!1&9JblrI{v#3NV-IX?nH!oT8#AJ^lsLMj$X279N?~ zTw6bYBoIQwZd>>nH-%|e*$63;ja;PCCu`Ac-Rb}>at6tq>LJ!SyO$U%5X z_dP?5KmY?zoq92*(FV59YOiVQzBoG(6It0B;J42L+vao!M@JiM3o9!sR{oS!>+)0( zHWs)Fo|u*CanU0k5`6ceieFa^b1E-Qn5e034OdzOukTRgdtZaw(ZL~FEe$FZxR-%f z*UbbwZ?nF$6aol8`i#AqD4Y*f&VEEG4B{wVEBOVYfTX148Ubr)XjlaedO4X2suDPw z7q~-6TakN?J+pn!Tx^nz8Y>||m0?|1iL-^Hqd;T>SX@vMM+tAop~_E%pXFs`WzU~K z4^@)D#gDHG;YCM6vm?@7SoMNGbg5_K>0B;n@yTXUzoRG*D@{_8Vbg3n&g# z^|A>5RZq{{=lgyT7(g`$(*m(?p^?PBx1Fzy1=MqJc(k6$q1dPOk)m|m6L*Qqsc4V) ziJ~Z&q~)0@gcEMHjG}P%!~gkNq_ur-LWxo0l$?=~(O4aHm|s{J&@Tq4;2*^GOnF-i zzqxiC(%M?W%#T!{oh(rdyp3c5H3V?#*RNkV>MYCAP!KDhKGn@KxG&-Hwxz`x*|)d1 zH+cC$Lc(Y0O3Hs~6W&6%1Mf%(B)D?yltSF$?4uJ;&oqcIzfadpT4;KMJ+=V533jd5 z-(Oa!G2q(tba#iTVF9EWc$}LN5qViz#~?p~o@IopkE0nA^BZy{Q?HY~J&0389|N#f za2lY9!g@idK%M-=yt3Qwz69wODY12R-#SuYh@qL;5+sscyLN$)h9ClU?2t*(o4!5^ z?ii5s(~t;1arV~LorQ)49uXReh|f>CTtlMFz_~?QAY2NFav%fXR$2ge$i096?t?Dg z%g_Tm^P9f8rS4b+gMBwX-flKD9E5XZWD8(wxL{~C_7eDOq+`&Nez;XMe;1hqfU9k7 zN3a~g7RCpVPDTN!Mp{x@Yzy%d{gT zdVx@%ZQZ&xb1)ks8SDc3z8=3=Odwxssj4s|32%!-Hw;-li@VQ;tLjxn~dScO*v znsgh=7ua4R;UIyO>?2*0nQ7OVcbb8L0k{Yp$Bi2|up5V5j{5yz*iiFE7B*(fPK!k0y(VGy-jDx0#-JJD_mhoo$@3bl;tW{_fZ@n9oIF2lk(8Dmc6M8oUg1KS`YsnYz2x za!b)`h8#&!?|}6RzX%cp;hCInV26%KID%kZ+{eiYkE5-7W3~bRVn<&_4`{>$u#OPW z2w%tiNe7Rw7Sd_T`+8-4&hG|^4M+zrBrEbs+jj**#Q?5HTMnWjnCCzxCnBWc1EHKD zAFGQc9i+cu4oeuaGKlU!Ir&x09sgMX!<;mK8vfX@mzMa|u1EKzDjNIh=0HFxO-&8* z!C_1-EG&E|e8JH%hZun(f>ymRU&^Osjue}`AN?&UAu;PCUEK7;qhbq5iD{f~9f|5N z!EVJy@M>_!j8_REO-P7~cQ!W*a&y5 z<_pKq8vu&~x+2@Xs;$MY#S7BLUHDD_@kGVM^wc|QLuiy0761MHtE2qj2{cz*UHwRu zAsXDjJ1dgLoSS4b+K%msXubPY>1(O0`~gNVV@+VT0eIWn33?ea^b8a+l{yv(!qwoe zAYS`l_H%Bw6k>Basr^lG_DNZ{egOL2oRv8Y0}pSC#bm;IPGIH_ANKCt3Xo0Ba2q9` zd49>WXOHfd@yCuM2jGm3T@{Va9HGXM00SJHM`7^nL1m@1M}(?ioIb;~V5zPe>!(;P z9Xs+cX$o0UXVhoEW@dzE?H}BI0!Ar#{|}U*chvTG+})?jyYqQb5$r4oRPwW-3ps~( z>eJs)Ae20p;j2;~`0jG60!OSpBLK#ykf0?PpPs7Z8jcPRqx8m}mcOw3$dM!5G4_s* z>dCwL1Oxz62q#x&^X#b%VAp5QKBCe^!RONd2GTNiGvtgT`SK;Wvh`PF zAL@Xs5SNx-Ms8aDL`6yI;_12Th64EX zh9Tt2e50qkM< z$|dY0f4a^9fFkOm#g{18aJ-1vd*Om+YAehXmNYOclxqt=C5j#}fCH&%7>Ir_kKg!CN!!XpzqyED_U%Td!3r|`(gz5=US z6d}L^qJXbf4q|`ai}&e#uEA=;ZKa>nJ~1%?_yayxDRu5%dp>ncw`b?!Z;(vgd z0Kf>p4Dm$CmlJR8c!<#{HTl8bVeJV*}ozMA&xz`%0IS-v8hK zA_+095tsk@Crf_fJO9_K#(^>Qrmt0gi%=zC*91EhUs#}FV=~6Q%JG(JE z?cKyhSQgm%RQltmEEA4uh|<%jorDuKD1zWq1vFtToQU{}?xS@Jq{U@K1pf+p~QX zDV1=VDRSx}Ai>9=?At+J(xB@;YG+RQ`>$ZZ01VGEJ#4kxzI{7DEF>e&C_7Xj0HfD# zBV37!h=9!Y^qg-^Iz)c&><=IVn07!NiQYmU5=(k-Td1$EkI1kbSG@$E>UG-a`}YMI zZ^DxZI5zg4plwL~S2%iwl#mbzvo1jd<+~?BuC2Ja9SRlmnBI#>gvh&z}WuS9WTiy>s=I4wGt+NL6 z9vDbsyr~!tEC-69IQ6h5@smg~AC!I9Ti!zfh_*vOC*SQbj>Gs!FNd4%;_{1ElPr;t z*fhX)pq%e?)H%SY|1Ea?`t_(7l+KuwKSh4aKk74|V2@nb9#&_a%~}M;@joGIND)2g zeJ4Pco0zCkZlR?71upgbF>=hL5*-%5#lsmjhDsiC6hQjs2jtJI7d@U5@T21(L;@KZ z8RCxJC+Bq{mNAJVP=WzQ0S0j$L@yU0sGooN3NJ^6I(I)>! zucF-!X$ybcXMcKEs&Gm8%x0FA{c|~I)nxPR(Id{Q(Q4$c2}(E2p+P?l ziX~XA!U&ZW>j3>6c^XTB1(D8oc63}s4d+9>ee)Grke4BA?-epo%245@dIH4-tOca2 zyTHWYnom$hHGSJ9Xodt|QdkIE#5lt#w4RsZVvLNsTpC!g7*qi&Dk@AJ=g3PY#Vlx1 zMMz)Rr>KJQANOcEW7SX-?5Dp$R0pa1f?ke!FJn9HVr7+vb${T#k)a{uT*#|eudr@JE#;4fg4QiD z3LoS?IE#1h--mb@8ayu^P?rBmUKJ8W|HOo5MjOO}ii@LK$y#wxIT2~lHc|qZ{|qL4 z)OBQ=6*V+|j_haxN-U;0)1pU;x&#)(axT~(w+Tn6bksxFZnv2Y|=i+%EL_zn=S*+GPxi)de&BQSEjOH~GaxQf zX!jts5Uig^OPyOzDrlV3BkxL5{jLNJTahAg z>ud3Zqz~Xce@^5};#F#L1g`ljEc=z~z!Y&QH9JGaYnG`Ce(>`1(^GETcZ{4uNkVm` zX$k`k@}Vccz18A*@w#SN^3~tkwf@Qjr# zT!U&-BClEck595_!C!{ zw!xWbDadlAk@$z2)Xl`7_!Z{zZ4mb&{sje^IZvLP7y8_>^FM&J{@JTnatRt@Z*E2nlHWtKZkl4ObHl`8 z#0-jRUvE2mr>Ej=pTWDR@yS_l(>}Ic8-Yzz(@DHaMqy0U($?m=2EVM!(R=2d@SRizk(X)% z7_)`g+qXY>!qcmtYlw!!-%lIZSpI=8!K()1;$4^?^{0aoGT~2cjo(T9yOf^J|BTBZ z{`3C=`u{&m7-5!)HPA(@bWQ4$($e^bq4rOo&|T5rZ;6e7|Ic_+wEOq^K#pMIwAOU( zk846chnj}uj+#N)SAuvii9{3JFa#%fd0t+#ke;ET66Ju)Q4AFU$Gy8UYhBF;d7@0S zJOEQkPjx`G?B20sOgnZII(?Pcvz{EO0$n-8#XZq5^C@M+h7IuKa6Cp!(Tf)*dudU& zZbtcvSE__EiAjxI9^N_#+<`wwLi4kLfCB%d4?0R*Dc5S=`lI}XS7={-b3?hVyorT3 zJUkrIm-G4a;Ek!bZ?C7=+#hv?JdNT^Q{L(FOiOu7%YL*^J%jEE0c2%}eN{zG4gFH^ zn4mMff7&ZmdJS;~UeS3;fwqyi0{OF4Vzj`SlfbW;FHuqf%CshMlBh(<;iLXGI8#6y zITby+;tMHO z6<~8D)!OxMb%=UzBMf4ZqV$$eaaEQ7wRCdEAPu2GbrG^oX8y_+j`L!WJYPJ08bzxI z8<)9xl~rvpe2r1}=r!B3N(w}mGIe;BX1LGID!lK5@&L^DNb+l&1Psrf?dR;+(LSIdU6Pe`gH|q1)b#7WyRGK-+*w@L z?2OqY?kaosn}~WIXILWkZ1)yYjok_Io}ERd1f2?!eFUxE>C@7`>OO742ktve_^FYK zQqU=Qh?WwzZQ>@IXCy+kO-K93nTG98jVdrU4khV1mHU|n`~m1tg*Z@~uEa&}Vb(j) ze(7G`q=;GlZP6n(??*0N*Slo!Tbh-F3dS*x1UO_R$m^(NeB#7QG<&fhPjP0-%Fbqf zkj4C;;zUS@EfU5=WlB{I4Ut5-3AlGqLxM1>09jj5@Zoi~8g>H;N#LlH{IQ=xi;G2r zUj7YlI+&84g0?$*?TU0-9(Fm(sF@p?5x)c`>Q0qtmMoq6xbAoRccY`}`Fnr;Fb2+clawrPU8@FaysYiELj~;Y z6NN)A_|kitlIq)PX+*;uTFr)vGEgX-3 z-qUYWbvqQLVKghd0{~)5gMt0XuT8p*rO>nrF%{T~JWiIOl+>1F|#3Y6Lgj zDKoP@?W`tT^!RIhH?15BTJ*#m4P&<|#kGM(hLxr^6yz}FM*KIVGep>$?>xjd47{Q{ zk(i({QWN)e{%TdpdpL!fns(f*`xJWpdL2wQ@Kk~g(MWAw@ysf?{T4?L!|NOa~)StUrl=ha84q2V((>ed$B$YHH7(KiAUKjBWY` zhG)_v2Dv+&Mf~_Hi_)ntB~x&dU!xUEVr5`Zylx6_Cpc87o@k4N&JAYZ59R6_bE47k z%?*+umF_w@%GAnej;u#biK2p05_iiZzMY^%+Y8q<0E)$4Ar#QqQ%|0}6B?YFVrOBI z#3*%h`_I+1v2=2w2@Fp!F^yF@?NHsk8h3M@<r==wglAaE)V{yPQUo%C|3u<7aP z4WAgb_E|l;cI_I%3w$mps=%nw%Grr@!^8|rCzeRreS9A<;H|AuM76tpjS!I%icHBJ!6m7rl3A zv(eX;yLppK-@+uzw{S3r+!*{-EhZ{TCr8-b%1uE9q^ZZjVNd<90ZR>9EJ574*Dp-e zLyTT7wDN~vx}&WkCC96o6MkYOrr&Ep&>Z=qFJM*rWf{TMfB+2=kRTIPs=e3O#6wK5-uj}ggc7}oc1A&fU9(?WEt-l+|XMjx! zm2B+Go{K`Dyg_iw$Cot?O~Z=l2TNS`B>|3WXVcHx{IDa9AJFW>n9+cV`?4TSDG=T|T=yY?2L4}H9Xr=IJ!MWwXcQ?C)Ho z9o!>T8c9hy!%E(JwbQi>TH9nu2@woFx)7!UjrvN5^oX9$X zu@XS6kSNfXBvVs#Po9!PfrG1mb?!-|+)E22Zd*#X%U=*BcoV9(TqU0kTQslRI$>E_SWa84& zquCVDJo)+f8sEJ`_(Mn3XPhUBwi6Ez#j3@E@qyQ_dqJHdC@t+Q*n7ANb8-auG&!UW zb6nFf)~ZNfO7VQ5$)$Dt@h>L2cFj08?yrYbcfNq=*VAKmJVpETD;r@@8(7h-`wlek z_^ugs(VyhWdb=-X@%yHO+548>S_mRSkPUNi%%$mJj)H`=H2T|z|pE;uIU1pXV z>2e@|{lfYyfwaOd1pr~TgqLM?2Gi+md%)zcekaGjeab8+ zOYf>3WG8uCf!kK)9T`IRTVeOX(l7T0O)9<=EL6aS5VWf>$^_^PNDzDGWzX}fsuj3) zzzG*Br9M=;?B|D1$EvStn_h2LdNj^;?e>Fs|EaSRvK6lyD;+zw-q#ZU49K`9AJfF0 zw^I1aPC2#5UU2XJ49e=TjrB_(kDCZ`Eb;5bDt}V5wo)Hib+lvKOgckayPAGL%FWyN zz^MMfpD-O-Cd$#&=krvbNYkT}LwNq?_HVV>W=brZ6At2zV*%l7}KVOMK z0C)K6Kkn5i`fKX;XVXVBSrY+O$FozXE=V^n1uTF3zK+DUg$(24A7^FRqg5ZL{!=7$ zu$JSCKWW9TuYg(o^y$;jujQQubx=z+w6w&0&cfFJpQA3Q^EIi=Y?2gWPstHrLo$U`}s;NqO4L+yb(bRKF7_7$Y*tUFO?B>=@iiCz`lLm&b)sKN0E?( z0e2f5!k}F7s_Y&6`Ln`xsGj481)25`I*$%n8=idgtew?C2%jM!Ehwk?6eicOeWbBD_5mq!Le9-Ur%vbcCY>3OyGx5=q_$K2z6 z%XX$I@2fr^3S;015AyCWFwwB`-YRMoL^`!s`MRb1QJT>ycKJ}s_{~h)BNw4Om*xHN zIQ{$M7wUVC_d6Gt8R>XvTxV$MvJULFGyzo;@UH*iX)y>eq3(o_F0stmJ>7%Cg zFl&H$kTAqa{i?xJ-E3c&9p@`ketki2UVe|@z369`>7rD>YMSg~k7cVAE;zM=2;O&bd$RB)=ZFeP4n2xI4Ta0wHEr{BbNN&hmt# zlM}iNenGp0W6mOA44-bR8-6E&?sUj5BZ0HsTmMO%csnC6?auILWvb%07NGq12SGu# z=(mJN!0U%1v(LHwDCHHd?p=?w4YXc|*=A=dhXv(~sdumLh@$&LUpkT3yNM*h0U^Af z0%wdd3ZPriN3&{<>; zv}xkzFMs^he+j7r2rVu)_C}~)))L0T?cTZ5y~Qa7zb0_qUO;^qrrd)p6TLmYip1V~ zM=x-8F_HS~GsCc?k})@_pAPI^{a0}5uwR;Y{fh`s;AqnSQl)P9?^L4V#MztO0)xZ* znyUuOZrk4>^;{%|shOR7A)qSqMgv1S$w|(51mcc z;^FL^+W#vR;TGbu$l=3J)6)sEpp1PX9)pr-@5fWa1* zmOuO$7T}z46rO+dOhe&y!r1{56&>+aDp2*%%h(vx*{O}eB=9j$Jul76)5>WN3k^|j zIr4P7I{pIsBR~-&9Y%pb5q3kv6}q@aCJ8S{sW^;@#U>Z@^rBx{($e8Tp}v91^v&Dx zbmuM!&THE;Y?f-jTI4nFJ*BSTPsKyB{6);ir*edmAMsbxZCHgEYK-LQNx^|t5+8)`_{n=kKSrQ0fDBXW05l!9lTDRe#MnaQoB^9>Gf`z3 zqB%xm5UvN<6P`a8g9wbdIlewVy=EB6CakPJO*O^BBMEcRvuwp&_rpLV>%#Zwt6t-2e@Sq_r zM-V@~0;BaBUcUw!$^SBfN}r7l4zu1ec;B$wjJg)$N%=j<_Na(T?dgOf9V?xN0fSX&zMx5 zlusztxO@1>>&A>PH*URnR{?;?#K?GQbc45M>K=Z#B(*}*fTQPH&CX1SoxJC_yMtt@ z!bu!1KO|pRn$d2F{LMKCU;~G_GMl%;L!DXwN3g78m>!1KU=k2UKvau3!q={v9>oqn z_#>s%@0Z_THX*h>;ihqyApCg>7`8ynDZMY{{mk2k;C1~U1@pI7?X3%GXZ2M(&Oo<& zVDFXHgXY^LFO?J*!zOczu$m|;UJpejB!&Ht;(NZ|yykOBol}MG4jWYS7n}o1PHhOh zLOkY5=nfpH>FMcgQeFjBRptr?{Ot(NgfYnaHRZ(;v3>%ej6`nTzI~EjEFKCR8gMY$ z3pC*Iy?gsHRwx;DaCHe$oApG5nf+^^$m+NeYQ%T;aZaX^+Q|fiSk*JJOJ{;KOa$>O zIT6x8j|fW#oUyW+hDkmbu0+@=M=r3FD0UII{R6%aO_8m{d>7m>;%I^8St=+H@@3;5 zKhcoLn4F z$6unTlTl}*c#m))SZC z-5?hBF(!D}<1n*Ea-+Qq_(n5c=w-!eYEJ&x?D_Rj2KXlV`a}(9g_`!jaI#B|g zkC^#7-uAxTW2UI^a5c}u2ijG{A!`z8!&gLb%=t)8{@UXI=LqsrbIAXZsnpe*Fz8Y0 zzyaKpW{vmT4dK;Lj$}K@yAwf?Fh{hkE@>B=_+2zcCN|IC6&1qfliBA>WShyF++fM1 zkD>M1{&t&4!BWJIA)$a|VPW}l_VggQRLrj{D=iIugS-rf#i7$LY$OPa8%zh!cxNYs z&x#SJ19eL%nh7e+iDm&s1qF9=Nz4io6cxoVjW89IYiK7bV|Ut(g~HnU#_!)uN?!Kn2dL=u7h;Wxnox4ogDp^3y!zbH<~RXt&Ck@|t=NB0l; z8oheh$h+&J!sAA(M;-xln@I9Z#O|&6TT{9;fL!-~(2ieeJ~c4lia|^=vmfL&Qn3#LUvjyaE-$X*Km4|J{_ME5 zYm)o2PK@p|8a4Z>P_EcpUrx;=pOQ6{l@0uCLd>Zm|G)~kAvw{pClNx;`pLmVLE$yN z1&Gk$g7g6;Da1~XrPawpa~S?G`MGcuO;ViJ=gyTN2P3bU8X37~A?H(X-AW$?UpY=6 z<_TH94lTz{KxWpiJC(;h8X3^BXyI^J&G72c(i=fJnaV``yPKdSCQ>HlKJ&_p?zEGW zAZ}dGe)7JB&|``rlboPqq}y=|$@6?bFP>e{+9Oj3Dgvb*sC$LiXthR12T|%_{E{bO z5tX$7(rnCTT3!{EypY^ydD`D3TP-cSXvi+9`1JBHHFfWR{H!EcAT^#qZ;&_ag612%|a z%lJ$tLBIk9h5XJ=v>>@HTE3_jV%R{Mq_BXRP7#KF&8g3Y4YO#TE05!gEoC1|*2-A? zRZF88qzF4cjIW(fjL)F!V6qCI73h!V#luTN@k^~>X zB(#6tg9jPtFbsgGbEXID_9@*GTHEWZ_9zk5)fdrGF#h9*qRqSb!;s{#pm}KFfn^x} zXG}7}>+81zsJbw~w*w6zRID3nZWCK(%o&6~Og8W(h<~MsuVSa!vPG9aHvK9hEgE0% z+`)L5I54o^-0^0jZ^o#HM#R9_zueQuc(5o$-Rur^G%Y7l?tT!DaRo>CN%yklV9H0#r-n6+y~=~1D-e+<2Hh>5T~YvCK?(RmMCO( z)i{YrZwp^gq=Og#4Y2dyFjMzl{UyHa{k>!QI5{01nBMrlw)TvXRP9F6GC^B?&;~jJ zODhQc-A&j=&>e%__eCEAdYT}*fbfP-1OOHtaWV(2DPoosfLJ-L(*Q&izVYrmt!VLa z#lqj(V>)Y<$I<$Gu>{?23_Z_2nKROyoTJ10u7|*MA0ojMfu@9#je+upbO}=4Gbr*W zMn*cC_;5vNV>~mii?Rsibl`DMlndZIJm390f?V?EjS6fvDPAv3a?y0oreq~wtW~v8 z7#bRsv+)US@tH+`9vZr+Z5faEwp9%*rp@n8&Edf%!yx_S3_m}<-0~>qR!gHqM*XI# z86JuhX^UuulHozw;`+b=qL%s)f&qTV(Y*vGK+kLqETF&9c7j==?_>T}qOhswC$m%5 ze)_kCR;=ivdTKA84v2qY6O-EacEy>PsxOoZ&JYud%`m1)f#`=(7X^o!NDvALCl8!K z*|LG`#uR3yR9yw|XK1J;=Bm8;W@?ui-Nd7)Flo`H*<~rbV#U|A%kM_&z@4?n6$amg z8iE14P)eR1H%_g`Gcc z17cYv!aOvsaVm=DGVTQWia!kz73|x`wl?Tsio}#19K0cTx9V{T62s~r3AkxXx) z?}Bqe5lhfTV(>j65+7&>C}qTY_B+AUegT0LXcJ9`JLurZLq8be$JZV|YAvlQPEJjw ztRtb_PaB^31cincI?H$v71!*cN^?xH4p{o@N{0z6@iGA`xX(t}>qrzw@grp;Azb4_ z{ICNtbO#tN1;Y+tT>)Xjx(RhZC?OSfb;tAPchVu#V0tf3c+cCg0E@{xh55G%;_4mv zj`Gt8PFAHi?|rd{F6!`+g+fA^?4RUw5WK0!A+}wb0i#FvpmP~JA-$aHt^+CX#I>m) z66q@@k)cdH2itbTeMDG9d2}6Ooa#Z7qD(}aef#$D@xjcZrT~uvsyavzdf<$z@N#+KX&m3!zl9Hk6|`fYgFX0kpcj89vA+N$ib9_qIh-)aBZ zh1Y6n|7Iql{xsfMUotnNLr@_?IwA%){%qnqe!kWF+?iOj;~bl{-fYlTubFyXk2}5% z%nruw@1nz{nq*&zY9k4i{xW4DeQ1a248Rx^G-J!S}4a13l)+iM` zBOo!OmE-4)`C<0zyEtWW2Vb0jY8dubH(TvXWJE!n^2%!)!bi`vXZsUIzx$z~F(G#8 zp+QL^ENRVq6*C@ZYpnb`(KfG~Dj=`9?G?J@;Re81_K%>}di*w!oQTKo^-};JfUo78 z>ABc~8uS04$FoD9m=rr;y41*bw>O2ZxA*&UjRrk`BF+%r{?X=6I(u#K;kNxQNnMUU z(ga3hVnSI;!*Y4o+rJ_CQ=T)oUG>xU>Tea!71(xRwYVhr{W8cBi)#O67}(#nA0YJ$ z67`?c?K^k42=saSRq%GO1kh*DF)s3Px1ZhHw(yu&EQbQl*z@X?jGcW)^|bRg!H`&f z$m~$ABH`5%B@r~{cGuTDaiM8fx)gm+3-x-^WULxzjFEUyfAYuH-tvBJ*V(YxQjuf;Tt4e+?$QElU z*gXDmkX)P!ri`IzBl!`;ol7zh*Z1pM89&nC+tMNM)Iur|j4;WUax-0&#D5CCdzTk0 z*h#YN1Ya5&3V=X>D&i3Y8c94_vwzO(0`(E$4(KAeFh5kKou-60=RmnR6^ZE`Vyk5- zAyv5a*I+{FBJt=1a6w4*oR8Wa&<^$@S6fx}aJauwk)3X}7-77&beT5e<FtfL1eL{6sx)gXg{%I=nPD>>>uHNyqhJ>9Zh=wb#b(3gl2!O3tA z;URg8WF!U77F?!QywJncn*W`N1Pkv|Sv7RqBzHT!Oyyo5nHk+{>wi5p2h0)PiXx1cZY=i;&}?k11~2mpkx zIXDEI^H9~D#>s#W3z!D*9drK&z#M=SMPKgV;K!+OVplO;Mi~QCsdzr}#mcB3o5a}@ z_a0@X582)9uC)5tZJVJe`kBB==@}VE!k9@Ek~jiPjKD!?vO)glNNwdM5FtAKKx~!9 zo^)QN^+K5O@iD|uprRsVYB1j`;{+bBdC+;-&rwAsRQL5!@1RFdyFcDO#Cb3xrdz4& zW@yYCoF%RMQpRRx=j#noc5K9^r*g%$!h{JYDJCoIAjAT~!*TkBL9Ss^IoabPZ;YW* z1WynlePQ3vq^Tb-^n#R9iScHj&inG;uOlrGh=b}Zh#&Y9U~1Y)cU|raa77U$7M_ps6Wy{)%gbx!NZ^3tL!EeYSPh6-E&m_#$&Yx> zUGR1=SHJpSqL3n(D_3`SD(ns_sv>NBPe*(;DVV6zBk@QX(5>n3vAm#WE|mwH{cntt zh3Q7p>^kB;p<`+03@ZLOfD^1zkify^UgWV7Rrp0MN%ls$%T1<~%nxoVN7b zosbaaQD)f1h|w2#)Cn}atLTP1e;z#|e`aUz9XS^P`67XNGpWayhz0#SckN1g6%4N& z9suBeARFV6@sb9PCAwfU+E9;b5tN2up4l6-6MpFbQsKh{4yypxV@dL+rYqq7rDQq@pQh~ic` ziM*Hc0nrf#%ZrK(6i{*B#aJAAdWh~92%tWqfDEufi#WRnEUK193SPo8iuzX`_z9j$ zqDlh!1Z0nSHHX7X;0b}r7o%wBGIdkmp}MbGB7TV_tngx$ctl6#9nE`3(GW)%Zk4r( zH}3_N5fdN(_dlik8}w#EXaUeBa~>NAlAP*5dV;nh#!hF&2}85+(KR=3UQa$`3kHZZ zcvc(6z@So7umQ{?3VUha=O~fzK4P&8+}}Nfwa@p)9@OrdhbU2a08nTBZ)K0tEhaj8 zdf0=ZIkH@w-$Y_^A^+&_@k)5m*IcwXc9V>V$v8GUd<#do*9AZ z<)5N8p8x<<1c^-4qUE0X_DA^m>;W3S3hvHr`wne76pd)JjyH*)5FCPGxR{xP$>42z z)R5rNRgKnvf^rC4N8Yp7Fj6Hxo~do21w#}uwu(%__@Y2L&AA!%07_g=P^GBxN9@Tb zgti^i2-_WY(9(fCj2^dIdU_A1yzW*E*{B<$oqV;dg<@B9Cd#=B{0X(1Wnkt%sW`$2SA@_0DG z�-r#bfj|_Aw}7_6nZzvL;+cB%;F@W2aGfLA!)BmT(DV+v384l7fQJGvZrov}1o? zv8mi2ezLQg;^S!8@l!K9zFo-(r>P{kVFY-Lt|lZ$;+!L?|LfjFqB6u)e#l=_OR?M- zKhMvJasm(*T(V8czB`z+2^0g%u$i9Tqs||&4CA>T3zcVy8y}Q#sc@L*Mrfwe+tRGT ze*O+MRJit42C*{74e)2f0&ryubEofi*_j)R$S(63hor*BMOBuR4s(! z3Bm%G>)o^i=1RPn$b%gE|LkOSqG1uyA6~g`y*zYLON$Mn)K=lNy%+CgJ6!KfOSF*M z!N>@Y>-(+)Xp;xV3|w&m*2gX&RDcn9z|c)2e(9&t?@Qzz&+C{;Ke3IIQ;Th;KiX+) z#i&Y*ZkX0VmifvhVIAT`d4?d!E}--Ce^-Zgi#wUw*l=BZNC;PB7Z=RzpU~4KyeMs8 zo;s$NcxWy*I)!&#%bckrDse)vS_o^kBW7daD9g(Sh2l9uxn^Z<2yEE?J-NiaVxkaC zp#|t>C_WP@+M(v^60@L|)iGy^BlD2Z5-0K43`0PU_;}3w;p0Tt9Q+EPNXb;*T3QYd zGozzB*8db?2L@I|HHkKsE#yO>0MSx z3@_nzd~p&#Mur-j3?a?lI`%ItRAe_wsESc{3;o1CHkEj2YNgw- z?_5qHjuEy3_`Qg&Sw_e!=$<`8p-n-2tC0A)zLxxmfb+AP_}=U!Tw`M*i)B%mgEd#Ak!21n?E4-vYo8i_QQ1SJegIQXFFw=)I_LMDbGuL0`0fQ#p|?vO7F? zU+?>r{v*Q901+cjyHNm7r!kRc`G06O`lz=*HNK>#U~^5r(XXlZZ6>!*XEdJ#Fy4vHv*g(mGH_pmZkVJolzE!5vO+!Kn{jO=-18b ztaaEo)F_c;X^N5*Qv^5%=L)=9=p4^3u5hPbzNqtd#*bB?B){Y6#tRi+#Irk8;Xyfm zAm(o0L>h5H{mKa3oR2Wxia^+|GZamZ|Lz7~R@C>nIrMmBalOV_Olbb^cX)bvFjB#}yG__Z zFSRq8V(M2!!3hNoWli!A#}*vZ>PX_`%!{$<`82t$Vzj6w*CxAyd*Fi*IL4ki}ay*>h z?Mt7!KNTDKVg=EGN=*6-SZGVZ$2oWFll`bZ7t`=`uS(w%A}Qi|40DcgIL4uKETn#J zR(-BxrGE@Z`nfqj8treFc-q-B;Oo)MG!w(sUnW^WsFQ(KEp{T47(*&5TAY=os!$)n z%EHFBf{a4=)%WjDgXe;a%LeHO4*|+(V?e+oYX>*q1XHs(d0ar_)sqTmf^_oc1&#finKa_vS-s15?)01Z>4ox2A;FUPg z9_Q5cyM>0!|U;}D2&+mEd|HQx|`r}gXOz=%S!1hdf-#-=)wjN78cZKy+OFsA> zQgAFVcxh=V+1P@Se$O%K^Hir3cQ8^h@f14ZnO}>OlBhdixWwPhIv3)`L}IaC9I-D$ zs#MG%?4(ih_EmSjm7MBL2lQC9!IaxgJo^PsRE&mp){5^r_~y=44LZ7( zO`i9~ce3BD&vyDV$`ifDd8k6dCvYDM3E(~g>a=H{geM10)nusC1E?cQv%W-Cu0X`F zsU+l^bp#wqK94`0ge7B~nv?U-nJI_d>yMJS^@aJ4b5ftQ9&#ByMJ{m^Fw>tK010X_ zr!WLo)Ls~nDr5wSSr%(7OY>8dekILL949ghMv9Lt5yyYs*(l{Xng!A)%sEjbOMZGl zl3k35#g@Duzq^Bmwj%H|@6IqnuE7{h$TfsB(1o1T-_@UBtmKK)zH^TKz_A!7$M&U* z?A3H<*mkyDAN=Wi>eQsYOOR@F2qHgT8c@mrIEqXz5dJGXrw32ta)Wn{;Hv}kfLi+v z>)-K;AFZG><>CzRwOy?A4&;@2T9Qf}>Km0KY!!6)l)w`hGK}$B7vRUoJ?BK(g(0ko z5E$Z#D*J^pZpd;T=c!rmlFUZ!JO2+=e;pOo`u>l@qbME&6-7F9Kw3arKrlu?QV=QW zln{_c(f|fQ5NQyR7D15il5Xkl?(X_sdw74I?|SwhXPqUmXV1OwxZ)LV(|hr_s2Q&n zsw5)d8VW^bLQpCN#2xgbfhC6P32z{6_&xRI4-|bSU*S=Z0(;$@Cu{n_6L!3CcD1~# z*RNXvH4dp@+b^WoK*d!bGy?tZpGH|Q!0-PUzOh|k|KVx247263Z4i#_i6_<-p-6IB zP-Bt1%c1eo`JG6gd|{EV8fn9jW&l!EN|FbZ;}N}3a)Rf-PXky0+1fOpc*gIw$^JT+ zK6fqew;vRkpqI1FZ24sW{fyO}f`wA2N0+~Sahs+au@jA51r8GQvY|zX9s}tz2rZ$I z>}w0B?PDa$D|M+K!4HU`z19;F3AaJboa+?0_eYdG8H3?|t~a0nAm##zBtAIv0BF<| zabq{kb+5itivx=V*$F^ofaVaWsv1o-!wsd88~Ty|ikqpGya^(N3 z$%=?imq-cZeC^KfkhM$+fcw-j-lt%_^d#|Ha*NcTaO3bgwyJdshO zxj|#*nlj5!FG~l(40M=_-?#!Qq~bys*aFKIHq(2rr?{VbcVt>P0A@lu5EKUCR$ zB&|Dq)n*x%RW#qsB{)*i3nS#x5OkN(;|a6Ldt9{IF(HF z$t%K-&(1DucW27$g1hn2Wp&r>+h|K+oBjDZhe2Ls`CZc96Y_sKNr2{Tdx44TW2NbW zaWh0_6Lb_uy6&V^A%$b8$i7)4By0^Ch)F>}ts3n}X!S1y_j^tD2ln4v2XLE^!N>xO zWpYt;^G&E|5;6=Qy*dw_I;1IEA#XL5+)i|1e`O-PtwY4KWsN*OLoum(*HeflQpxJE z_N>2Bl!Hzmdv(4a_4qtZ!R_6m(J61TmMU`H;QY?37HDN(!ED@?4l@ZeN=h8ga~YO!QA-Za+(x5C z7pEK~bEZ|KRr8F;8>4zVo$R!9pJ~)qQm}6}ZG9V2OEjKd8DbGwFQm%V52U zY8vmCqx9h;caERa9QGwA-Efghd$QY`-(q>4@UBa~{?M3`AH|?SDzL)bele zpDdr>MojGI821m;kas*o5fDs~X~&XgAi4E0UC}o4OGU1ybS%x+4KBsdXb~vMA;1#S z?}0kEbsDiUL*iw+PKt|ewi&_tFV)^;t5#SCfuAY$rUou+bV(qM`8Tey^yi|8I7 z4gV~4Z``}`LHYCEsz7xIUyeR$;QG++LZ&O9J5h#ymHFWZJGxTB$lNh~8nM!Unss4z z8qz%WXOH)*pFI!M5-OP-*1T`F(Q7@@lXEs<+r^iK#=KEwgllDP?xpG=5;;*?{W%IGf znEcm(oZqW+J>#ULLM=x94@A_h@Zs><10LC9JEj=QPiSAQU&? z)hR^=GFJ0N6($*_u|aA~Y@AqeZ4J3hMw*rFB_U#&+2!pA)4RTbW~bKQhn(HN_X$f% zfRFgU(xGt-RXt0!Bl>?DT^lhFT>C%HZ z2!`(%Z#RoYs8RpA?36ZS4)iucfAGT|5>khK+>ZkpC|yM`2KSo`nIK*X zQ)DI#4}iKP0B|0(&Zp}>0eqwk0Ekbf$>>X2d?_kD$H;X9f~JThSnNwkyOxw$sMfBeN5v}soaj~OmP?|}Jl4dY(^KA89(E4+Q-fUo{J^ zZxU2o{Z!Jx#qHgFh9(|szq_OAb$40n;q)m2o*LiC;*yg0t2%OWnR!j$_%hcQo(}6# zvMm07o`!O@W6>R29ar~!&_SwPfE=TbMQv<0K|D%24fu?X%HlL zAUWl&iaT@ejO;9r=OjlXwr{8(kCpUVY#m>@;y9TnH=Dbb64DyoyX7j-aHp5gl`({-@RA%+e{%Z}wP5s7*W2{UKT!L6fDvErGl zeSSgAEdEn6c(l|6R}S4t+j7kAwau#DAd8@}p_yFo?;uB>7C-xhGGPr8%m8*uxDWN- zK~X493-j_SV!lO2PB(_Nry&zJ4Y$In>d*FnJ(4Fnke}OnHav6QPxAWdY z*he2KSNqO9wDq_SdzzQ;T2uPsd=yi7%7)6ZtwLGjo#S;&(V1ky;GHNHLh>=LUnN3( zx|(ZmBFBqLO)o7uL>nO!Wke7F%iwYhh{a)Vkb>9*&2)&9!89QS`hOQMLb+BLiaQ`j z4Oq>K7ePxNfi+D4=L$fGJa)^lt=vEslSH6PscfAiw@Z!S8>Sl2^|2gyH8~@!-POkv zJzDB@;k(89SYzx|F)_(eYw%*>kS_}xkHG%fW0&=u?k-!_Un6-7i!Eb=-}jgE*yV?W z^(Uv+U)fvtDW+XHu&d>XHTrscvhnx+*u<5W<83+SLx~&VLM$6W9d~4RnPg36gbVNJ z4)+UwGZekEb^fqDC)@qyS3l8Z#*O|gc}(S9i~01}qyFOzS{aIBo^nRpCE@nJxy9>i z)i)KbVGzo+pa^*bFcVM{M!Gx>Gtr)1X`0JpV}N=z(bk48Q7SYPz%+`@FsXCy|6#UJ z7P1gxe0Vw69{Wf~>@{eYFFqiwbF@h~4mO`E)(pHhY1{DpuHHTT6zAO!+3d%a#_>uk z-fzm;x18*&x(2y%&_YF)}dU6 zG9W5J3qjFiJO?}rc5VjG!jDyUDtn4a*4FE*uH5`{BD`q?77HQ5fxb%`8u((JvPX4n z_cLeK)0W&V>MK=W(v}2Ss9O8l71So8< zEBmd;1x*N!O4#hSeS^9i^|^}sTz~mglUD>4agn8`8PHWG7OkrcJU`@+^y#ji82Fqk zXI{HA9Ff~)>iua&mmdj!Py=iq%Kv~=3JAxC@dClE1cZTrnm5z}mVvg`3sIhJ5M?M$ z5R?_iZuA$iux)twpRO*t68p%7issm}>6Ujumq0{vCN+1|y{&9Hr^Z1fXhdD&h5j}i zXOLJSFeNbK1C{w%SOLRGo~0#2JY|L=?F$r^eeLS-PM(=l-k1CdhR%FnDo97c-neRY zF}fsHf%#Y@@^#v8eu_iSKPtjYu?iPDf36;tx0s5^cT8I9_btxTM2wlG$$utaMxsHd z5T2TrbsMWYyf3WA0?MEB#`46fW1tik9CiolZ`fUjFB`T5CRd znxXm{0QXv@kwxP2*o#v$kpMSo!8UK@N zT5pP_hV!VW#CpAk(w71KfAp8{}LshHcW| zr;~Rc3Q}<82$znhbQZl9d(JDZ2$fRv0Yahq-18ARn2#kiL`AKsjJw%8F>f+sj+|-d zaTS9H>;MA=zZGlnVnsT(NYgjXWs?Q!yGX~U4E5JZ;z1NA@om#ymrBO)KOI`?uTVc85OrEUu9aR=~ky07j3r7x9 zrk@#UHrGqFe;ch{T(Qd(aGWwt#YPZK1#x?~+0C&F9Ct7u9#TJ(NU~0ziBNl-*#_v^ z^%p^zd}a~OHLj14w@9i192CH;HGjX)f(F7b)RmxN0}j_X^y?)IvKZUd0tx$#+znac zW2;RRF$x{)5#7S}1v|0;MMXZG|64A|eA zWSpk%zZ)1r{zUZN7DxXzGchA0$6r=ZM+5%z^=UQtNu#fLH_4jm%BRSZwwRqO6p)%&-_&EFE3%V4w2E-^!#11oZYSc z%0&=g?*mvGQ2LClpk0fracEcI!zX6uAbZA-G$$x^0hbRn=5aWCFlz-(bta+Az$>R<+enFpPYjg;!*)<7VZ$BnBm)t8o*c{D8vMj^y|b127x7EPVas*(jZ+1AHf=KN}tw-0A%{ z{vycF!$bD!xc_2*mIyHqNmcQxZ3eGhV4|P6}?I%+E5icM=BUkl*s3psjt9vCwM{S2pqp0=*58J z2`?X?AV0rp&!16n!b3LIksOYaQ>6a|mZvRZ1*oYHryWWd{ywJJB=5AIlv0(qR7~pr zl=qV?fjr9ayC&hj!h%?7`14?Lf#}lspKvFIUfQ20#|+AX&;Z~wBU~< zw?EZ;ixOsgJ$fk~@rdyzVeLh_vRz&6PuN$lrR{fJj>4)km$LJ8#pvcErX8>c?vGrV z3%9hV(!$4gqT6yaz7{RNNv>mn<_#8JI)pbMbcHzbq zHS#dai2udD(1yNSqp4oVsoz72cpb)RTwef`>{9H$nK*Sk|}WZU9fwifp#k8b;ND}@y@ zRfg2+6xWw~n>$x7=hDUd927M*l}rwDRCUmt zC-hf%+d}FF{sIXJ*IK~|AhMennGPr+?oCH))=l3(@2~|M&nb>p$2xS;E{68@J2Xct zp2wS|Mvc>Se(4Tr)?1I3}i51 z45Y^iG1k3kB!L4HAMv?u@k3!kLOb&NVUN^=r6Zm$3K(~{@=fFMcP(JqjSl-K*ez^g z;aA5=r{LhaWXKy4_Mvqhzor*58L=S{q<~8(i?>Ou=O*^YN6qIWPT{-(*jo0`ztwkX)reNE}?}ph@jla2t0Yd;4Eh7>qEN(P-vG zIhjjvO=7K~7mSznrg`%c)SI`1+hz95@t*pwAUR1k>$nN

3>RLdLTE|`d3y~27El=5pk0fZ~@gB;2me*69!uV z{3tm!l^zUUCOX)VO%XN1U_^7U`Tg{?pJFv@Qb&UG1XT4b zoeY$-Gyp;b@M-Xu0SV$=5S)(QgzXmw8$(1%$r@0n_U~lOg?_Ld;svelU@*nV^PomX zktFr$Z}{b(KWCuTP3-NCg@_U4nVE^bp|t~6T9DxO_xFSDma{?dV-PEZ{=K?7Rc7-w zzncCM=fY%7+~cBrjOP}2>v`w@i{RrA{fxmpPY{TOk##$N0qUeu@{k!PDQFbgztPfi z!$RvGP%41sM?f8?!B_|YXdosJ#Jj#eRfAmobKndJ$SpTF6iF8H@<3?QOtEp~VWC;p z?I3}dSnNT%8Z)Fd6-e=NyQ8P4)@e>Nu^l8TKo1YlVBfz}8-N-XKnzX6b*S_85w~q& zaYhDU#sHYWNefMIopk^bkfE zoYs3xdC}qE%mqLc@K%3tGjBN?xhsleY1f-^FE`F5Y9qTNHFo6;tdAn2j^0O$0>4;j zSS1JM+mM-8eIL1X2SDn4!mA3BZi zgSi@D?j$8ILTh|T$O{Af5(Mk{e>bfI4is zdwO5tYp@3FgK22;@+>UxZb-{jnX;FUuY!I7 zkol@~RTa!RFy5&Kx8#M781AG`Af-$%ysw0f1i~&VLqZWT005A%kEHCO1h6!nH)6 zuuC9f8|Uxb1HdUjTBabamb-aXDoXeeEMlNB9xp#@T>xmk``~~jBvb@c70}X-j(*2< z8GwbrO@rniIPgUFa^Rl9=OJ{58XxNEO)%<1`vpv^9P;ig!H?X4)u^?W(Z2|25yN!l z?cd;Q4bmRVi;Fgolr9-Kzd(bQHYg;4jN9WD2)ZUFCkFxa4=YYTvln7QooW(R<(tIb zpuG{SdI& zU|g`iivY`E9?cCP>l2O(CyNOJu-pjrW1QW5i@tWjUB>t#{4@H|5Q;+uy6Ds*E(ZX4 z=8gD_1<^Dh*MkW-i1P!659{zD`7eGzU1dr*IWaM>gbD`pQ6ip`{PTaX^}{uy0X`0S zYN=H^(BTDrLF)8sQ(myTd^=KyV=pymg%m=MJZQTs9d z_uqe4F96olcIHLu1&UX-d%wWTA~x`zaCltnEAalJHHRmKtC|9^Z!iw+?T;~VLO=}( zm>hN?fE@$d5^6t&fVyu(w6OLokvESn1Zf3miGuf)BfHZ{dNb{p+qd$+1Q zTl>SHnW0NJLk!T*_EXd9$5&T^ai5GLg<=U{Wuf{4J|c~^@J0f@eg#cT=Ek zTp;jz_Vh#078(axbb5brwGPzOvK=`n(aK*QhOm%gIqU$w^6pK6D2HdKk#E zG87l%H7}Tj#IPSMEy-Zu>m|r13E3`$!bDMK_5E{;pWpsu>qs@GhMDyj_z4^jL4*wv zLC(wD0U8hn4glEc0Kc|9QpydUQ-47+8u+Y)whmWd;YUA1(=fN#9>+$7#1;O$81!E*dvevg!`ucCJV-$^y@qchg@(=yH?dyag4btM`SG}tM%1b%P49??#cS5W=OI@Hd zA`D*g+}s_I!>gzxWeSkILL^RLoB-!%TNp_OdU&wMfJ{=O#y|Km2QeJ^q;(Dgj6@*A#lmZM{d%=nx13Il5GSD+WotP*$#$A~Q%=h9>|JJH>wTc~G;6 z1hE!Cyo1XjnFGk+&|Ry8768c1sP&)hr+K2X4EvtsTUU(NHsX5ICm85j2)ClZ%8rqZ z4MHkF?lfW_+!O~!;xg`AjXXl85chAzLf2y#gJe835DsC|55gg%-rwmA+dWvRZ!M@q zG>KwNc?Id|MVW(q4}EYYUleuFcbQ*1_xG#sn%C4;Z3E*@o^h2*Y;FaV4gd(QR%Gw5 zg6$j}ybs~T?b~M^AHq2MI3pjJg@~`3^0I{#LUjg|QH7)6XmvhraFL@Am<78~2xSfd zFa->CLNYSM(w5Nf87WQ&2?F0D+eLCNFig*czXfLB!VoUH;Yi9h`e}dBX7*g^1|&-m z3t~EyAML&|iH0JcKSnTzN>U`G`fL8up|%xZfHLH&bHCBz{hRY?Zhyst7VH3@|ZZU&XbcD6r_ z5)mtotekpgf4b@A-guIE^Kj??8isiuu5Pt{c(VIR<`pVw%!zP zA0Ilj0dqQ6m{bC2zA44Fa%h5hJX?rKx-z&Y*6Hm5M;%zYAaJjftqM7pOr$`S-ZfTY z6F`n!^U?!7Ng14!6P$F6oxbINZrRdGM>y0ZIY=^be5)53^WWtA>mhM`jM&2C<{D`t z#2#g}5Ex(Q1-63eK%Rfi_}y`X%zNzY%Md1!f1Uzwy90O&p{yS(M!}LDTQvsQYo#qn zAmP%Li0~kn^uiLSQc?4A*gL7_1$T%=h4!shlHWoqGAPnqp#-W*z5Z*_s25{vivfU>nH1Bh+w|7F%EtRc z%)%fu?B0lFK13tU0&}=UkMc-=+eC{t?)LAsZ$U={ou`}Y8;tBEfe$`dLxzhAB#9ya z4bv^w5Rr%#I-MooB$di}yFOU$R zK0sA6NMaHcJ|L$L^#{5D#Eg!eN-tgz${`vtdnY^Ho1gI&F+Uwm3uo}N=f#}^(cNFq zP1m&ZvUEm92UB3I|16~|CL6+YfX+z+;Nl^iJOwA89vFrwsjGw6Ef|5C7*v8DC18L- z^9^=Ppl88lr}+Yme?f{C0|juI*U0yR2^j<#=;PPz4KEGo8V}xG;`^yC_Ff#RXuu-% zpwPQ}&3}kRbg&v6v;ISNv1)cCYg4kb+lJ!+He1|@AOvLiYhDwGNu`z5K5!<}I*mbF zz-*`}EHspV<8MX=r~9Lam`Bmi(EfQpY;Ye;$^h9Bc4p*rO~QR*idL(y`tu1MbJ1t< zsE2~jzC04^l(s&*o(Q8`&4YZR91vC>MT1zYsku2jVSZsDX#8-46Fih~eZxVy^9Zbf zxgwf?0s=rvXs?3RjX`F9Ny+!#{C73upg7X0pLX(=tBZVnFN3)a$e(q0Z@>FB-xPAp z*=`?v_#ymt(L;>wk<-4<%+SAV9?fixe9KS{S8~{jz9D;mKJfMPA$EWT*cdW2Gz4r5 zo%9~?98%VY+#VWVu0T!$p1|DZp0=YHsFc~m*#P!(GIJ;UfAx)G4PcY60+7$Zm7myK zKVA9g+x9Nlo1MLwbLls*J(?OCXwfI-fbJ|LHZDDbeECOEuZL|Aa?Iz?uXAylbg`x@ zfBW)iKC z8q09lBq8|(b8;{T1kX570RdbAEy&&@!6y`5)SaF0Yaby&)kolLYP~msF$c6B3k&Rk zjpC3cV9;c5NM_&=MvQ{}#oszQf>av^^0wew>H;%z&=mw69u!P`5X}pihR|#SPgX1- z9&K=`DNK8w1=YqVSRbLJu)2J%&<7-eiv=(bU}&${KZPfO^BQ9Au-yibxm3w94O3u_ z1ZjcT1>k1DMNg94sR|5u1qBcftMYQG229;&gpb$|x4zZ^x}9bp-{4V|SMp5WBK6G8);& zogWNu;653(tz~XSB*s{f_*QjphH#yOQz082;8}#ZUh#GVL0>@q}tvf zE-B!0umeZ)f~_DSsH3JTr=ww5Z{95HL|7Vb4aj$jg;NO1XkOTcNqYEm0A6@{0@WQN z1)#HWhJhvdbrA7w6f`q7mS+xvV%XyB>@74OUoL=c#p%96phoh)PYhLtiX4*Hy?iOi z!SMhC5Ml_pphZ<~Z46%sIhl#!I0TmnLjMOhd%$KQDvE{+fSkw$kkg%&QP|~+}TdS8j5V5)oy=%mVXQpw|i%Lo)}i&_6)5 z1;IVAd|zPR2Guzv9tCT-H{cui8bNJxBp_qv4HZ&Cunu>Weh&AALP85H!Whtwg(DUC zwD+=~oZM{&3T&`_Ln9|teNvgV3-a_Rhbgk?XESqM@EcmJNWwh@r4Il;pvj%L-GL1` zHKKVmsR^ruOWFDt<{??tlWQ@U&2!U#Ij?G18( zgkGnlY^3by?EK7G^$@99pE`A_`PKgt^fX=q=OfBZ+iQey=9leaFuW|;^FK4)$t7n( zMJaNgYsfdTE=gcusf38rfpYPf1%K*1?!35;%zU7dkwmrdk$-+$d{p9q=U0Q&Q;};s zy6+(pk^TFd{XzRf1>ba1>bHUoJpD9dZZtX^as$NTj)Y_ysw3fMFwM1`kWu#7*xZD0 z9;Ox9XHm2~BN3c#v}Rc+2+X;i2NrZ$=s!>*0p1|s^x=ds0HLZTopef&9?k_G#h>5gjRxzZ z6`ps9FZ$Iuj=GbmwX);Bf)9<-ktl}fJIAA*vj4uxa!o&P_&o9F)FXIDP)@$+fam57 z>lBy}-vQW|n;U`!Ljhi{P^FTj($;kE%f2 zr)Y6Q$-n;zW`aaWwfEb9#`zDWJDZIlo0W`UDJnzV6l(K;3IDRr-Dck z;VskQl0zsh;$lbho=G8US!C0`mdJZDNaHg5BS$UUbreo!vd*vCzmx)U2ZjW7oe024 zhMB6rp<)4wCcLDV8f#%I2WhNK%Sj1Hc(XVm!3V4pEEn)rhH#2(V%7dp^ol!)Mp@%Y zytZ@RRB>%&U_E8BYouJ^omC&QQF)z%Az6o}E6I%;;Ib%YfAg9b7+yiDq{7;T4Y7A{ zfYUk%3-kpL9Egh2gqC>3=hA%KD6D81R9&LB&hg=`DmSHz`F;uxMw-Md2!c@8uYOlO z&0hiCC|IOWz1-i2ZLrAz2#m0{VcQfQp@M3b(Ea-~`hK{3aonAi(kR!U|HYEn^Ld-q zm|qq%ye$yz|beCnRIeD}PQ- zy^+yZ+~oN(4=_;jHgEP*+t5F6lXJCIljog`DFMobtndCCHK^_p2Cjy^nYiFMdHI$% z)K@_56rY-gdRV7B$^)w zEu5^Z4XE^pj*p0J!Q;XEggm>#_@u}+A~lyYJGV94>caQ*`6E6XqWrCz&y=Q$@-*=f z2G`kGSr2MJX*IUA_mo?D{f`|5ZMBf*()o{@K1CxeB;4HPDlC?oE%_TJMh57ws%|u+ z`3z;wwUd_lYQokNpzvjxFC-v<6q6yeshHb*>kO$G2#+=y(4vXGvq4GO3zMN$etMec zWP$;m32K4Z%Y*g@bqXxG;}^)xzKr7Up84v@5N7VLzk( zv5g@VZF~f-d#``-p(Cs0(fs4j=lSM{LZg z!EYo;0uV?>?;bqB7-#Q6o@-`ms`u#}K0fIF$;dRDq!oigwoydW)a-27*RL7o!zIv( zxq;I=gxumx08Qw^Qle8%cx(o~P>~l_fS@B)_pisPE6Yne&bx~&Sm?kNWGJC_$cS$z zc&Ik`Qobg2i78yDH6%EwjLR!zOV?oOIsD7qN~y^fGEYILy7_nM{d@)WkCzm_%Pvg% ztwkudh7a?CVp+`h_iM8SO*VkIcAtlh72BZyCULL%<=4G7!A~Cjx4UHZ)rciGR41uI z)S5LW%EuC@$Sw)_8SZ4{y>ZMU5X-G{-?Mbq&y`iC2;A5B$`(#i25;x#U;bVbF=G!l zvUn%2{D1a$>|TCie8n6xFUZd3Y^OruKlm(%ftIZU>RkBem0s^FI~ulc=UYvhpo43Q z0FZ>=SrYOUQ}R52An9RD;Ol(jgj&@v&H7IkQ`4U}Et5bgaJcD{|>3fgdift5~QPg1|K+fa~! zIRgx1IKcrG*|Y32ecYJ2R86r!!Cot-sU*s$^o^ilT8l5KJC z1Yc`({2vw|KVR%Z*0Dbi_dV|5sfPZYHk+s4>hT^o{5H%C=vqq6!ml>#3B0qh_>-N5 zKm5+~;7P`d!&quH%ip8pK6y=N@sE2prZd`h^@>uz&ELJ9XO)Q4Kl3wg9!Fk!G8_M>bBNBMm66x8B8R-Rp+(Iu?iTNzalS5(wuASwnOux3 z4{F~vw!D|;)2q&YK}>l^@Q+IM`NAwavh{)`SHsJmk2_jZ>iu0TDwWVpKBJ@^pAOpa z*wq(Tio>I(TD;z_Ruq53>!s;l=`QiVbAC)HeP;By;*=CC@0H-Sflv;3ffzJ6{v<_E&|krAW^N6kO;aE#0g4HB*47-fuy3u5 zR^VDHF^gO=R6+1opc_RW1IE-)bkm_~NN;NNkfOKcwRZq@t;6JlzA)BXguN_Rie6}GiA^%H zm<@9{wm0YH4YO<==5t!PvJ#R7<>z<*mNRE&Tl`euJijoI_475zLsf4yemS@B{V|3> z?BYk74h7R9DtR@LFZr2`SHH3;O(velU;dWP#WcIUpHqChy@+Z)FYnf}c*ig^Gw+#e zgxOX4|8e)*&lkM~#VGki7cy|j;|Q;Mnh$HwoFqZhZAWo7tyBc7dud@^`zv zN_hnZcWV~ock6n?yeN|eN=L}KZVp)IJ#(S6YxkQy%P^;6#268tW`f^+gOl8g|69_x zTicfhHv9}EO-AuN336Yq$@Z@f_;I0)h3kGVOwk=0HZO|1VfoYhbK`ddwtf~h3Qzp4 zX}3!$bdGkFS0nOVAj)+RTUZRCED&M}ly2H9fAXFBpxLR;cY(AfN>)pL4SiXKf_zyu z{Q}CP>;T`*|1Jv?2;uq2UneAtmQTXYTyfp0fcj=+$B7kgnK+2)h=BPpkn*>Yvaxp+ z6rjYVrS-Q0podxqX4&9x7;1O-F|-0;L%$FC&{>dHWM>qhrG2Zp)q0Q-nf{a#jjmXI zpJAqL@b;Q#y$3O`T8UnkRZK8ubvaL%gH0e%B0D5i)##LGkCS$cwS^IVVJDJJD`s5t zl-A4TY+1s)9xpefA5^H9;hWO9(UEud9p&5Fn$O=7iO;(h{j-?0#7lo18~kxduF_9^ ze?sQjv$yd+ar(M;n;TIG(?9#qctiak&G(54qHI0GkD=CggO`zcmzvf;H6Yg2TfF zpd26;2FYutp)4fKplDNyw6j!)%-%ZJ>QQ*VxbTz<^ruU^O=oV~mxZ)=tLZe|OQ!k6zj zb-8MFlUjJ=s@;_1aRK4T1zhzKJD0Y?z%fVv}y z(G00CgI!EO9pu!yx&5F~J7zx)QJLtB$3|SYCi8)Uc3|9UDRXUFT#veuoGE&rN?(na z(BI;_lnR0H|Usjv`k56wYi1ote^!h!@JTwx8vwu zCVwSiY^V?Xl;LN`B0QA4%(tuWD&zR?Fow)dIBw#PSI@hrr9(vXu1fKq<^!^Y*#S$J zP#>W*f`J$a02QXZAXrsH=TQj7w!7y*TdmpnB=~Uy5p788B_t)G=N;w`;w6&tZP392 zY4AK~omj*_Q1Q_7d=!?(k?@47DNVa(aquQ(G&AFu$4v*5VfWHJhMa?2S7u8F=DYrp ztg{>iZ;dy8Xb9@H3(461J0WdOXZ}`Kgsd|^jNMFdt()o|MH~(Nkgm&v+)n$b5W>nU zH_^jCNh~czU(W2^5-JeHLlJIy6nzFI7X7!q4py_a5;&$dj5@g|U7zc!(q^WgH zS{zOrtz!K-ub~+#)$>QI{C&5E<6@-U5O`r?dQcp*tL?n?r$6hv*Vn&4edl&U!y{3~ z3!gQJDszlkSUg3xmw5$KlG4&G^v*gABi ztQkrvHlst2Szv$0_H%ATaI5`%Rbo|AHJGN;dhJ#(1v9g!d9x|cQRCuu>cPlUZoq{s zdj@^MHvJ_#dbMVHt*c=_=TN%B@VX7DAQpS+T-&23=|=k_u8TVLIuyZ^9?x)PMzZ4K{R?atyl81-`W}fTrS$6^*FZ| zU|(rxaGj7WOyoQ&k6@nZ)Kx+dD?`vy5ORZOF9Q9`v0v4JVhyOUxIbD&L{?#AeB8}@ zhm}=D)(C) z_Z=7SyGZ=e%@nbZWqrN<&X7dC?@KWAMs}8Qy)etqj`e_{=D@et3D0-yV~Srq-?bGr z7W1&a%%gcn(6WejF#s<*LjPRqq`~rpVchG!jl#wO!)<+rPxW0-bsxX49nyZrG7+!p zBGr8PyeIb6J67G%64T9+tV)C4wP!N9ISZMeejGRY^k=8(Y$&Z_rrxPvm^BgO41P69 z5$F9rk7`r@tXKm%fUpntWe3Q{S_i_eGhfmV;5GO3`TG9!*Novno%wSps0RdmYcfDI zwB+RcHAF~_t?~z;bpVCJGiT0(N+sY}6es<43UCjZp6(tRO6{J9Jf09aGoUgYpN1PX zRCPpxaZ5r2>q`=oUm|B&f2ha~C;v%I6pNQ<3aST<69YO94ya(KfO!GnsG5yQP}NaA zB%CorO}wf7m2~H5#~7v*zNus_FXHX~8u%8gxOVv(TV2ooG#}^fTsv!fbn*yISBiT6 zr&7I;biBv9`YKWShHMu*mZaDniyy3p;FZYg$Gz@(nQ(1tK_uqcD z14DCJ5>7|HKe0pn%(+Fu&X^Y#Bb*E?UU@#b4VGP9dJE_b)umoapxe#`{r$vndEw}} zOK;*n(O~6yBDTISnRbqfeeWGjFRuP@i53(y@836`%qb1LaghBmPlo?*4lyd=n)fa@ zUl|^_bOluDfD59JpP${49n@?P0L|ulHysc8XK26z7zSVh21ubUA4+Zj9kS%NJD3M& z3&=rwO{s0qL76U~&c%S@N@{6oluATre}6=i?L+xjyb&OS1$APz43#H<2v<@fA(W03 zfEMK7E&-qk`WLrAo9j~K)EI#1B6mgRplPkl8oW+10}fX6^XnTM(3NUFUIO{CM$HEx z+m@D@nF*gzF?wl#bc7OcI)Evx(gD5YrrqI4EF7IY92{j(EL(e40b&%t6`}P6a<0>^ zc2Mtu9UBqk!fb#(*9CXl1^T@isUb}>3JLK|=1tq7yZlw2F`5Zj5>H>KFvZKOC@LCo zhJ_MBNj*pc^i((2U2j#g=k81fH%vm2QQ)|+@F3*nRMLAB*L*O>1GV*E>!pGyH!Cd{ zJShQ4wl$qrpFq&8sY%0y{=agE*nz$h+8=|6Iu)dq?16zj=yV`{HsDAPVN5X_4UkIO-p zG)#+L3%e&|Y7v?nsA~4C(CqQ6=T6nG_YXJj+kHW5QKStkwKwP!0QCtKGUy2yh*_W1 zDv}hC=50X%0Bzt3)eHZH#Xbu0RlNTFL6C!0p1KvWfX%WQ{K!r7>KZ<&?0}$IURbz_ z@F{LSm&*6hsQ~#%$a6sx$eiZ2K;@o;7GuxU%!>gUMoQ)@T{ z*isLJDxtMhjaF$Gr`DE9mK$YcjJw&A2zYXCx0_ z72`2?_V6KzXaca?bSDrlY3o@$n01sz(TP4IHwvU`p|se>W*Ssr^~J z+O%ga+v1r`dp2_5NSr;7tzBx?6;`zHq?AaXC=s6OL@)aCa_u zm1WOY|FIIc1R6Jrj$>N6%Sp3)qjRcP)LduC4}|d=fq+Y+QK;1(xbR3C3u2=}4E>kN9nIIW=6{E;BXt!ne)aJ!8op+CfNl7h&~wYP`$ zm@+p@DMb3_c6_1DERFg}$r>dRRHXy$y#4**<7TH_^@cm`8HaS{)1TL5Ge0mOEwm3%iPa0jkeZR9H2C-dEts!;zZej>)LF9S^aoZ^KUByG#zK(#$&LWRFU@ zlozryF%#VQ#TUa*6vXE3%uu){?$VTePww$|_AaN?e|`7b2r|mVcE6s|YJ`wPH?$NR z{wqmc%nH4%(w<5o6nbO)TLSJKqD1vLNC6>Y13Nu*u>|lDYZ?)eQaI%R)(xnD&``pm zd{94x(kl9EonEsE35p);fmbT>Bil29CaG4lX2Es0Izc49`Y_SIrzF?J=TkQyRh}qB zclAR)I$i$uy8HeK`n8L8^i2OT%$E4=L|eLO}&)ud$xr1l^%8LLYH`mmKTK zK6}iVDUe#g%AO~4pcmG09OC#6#gPiv09geE z1etXdM=PnIz(VEf)bK7gYFtpy<6URZfGNZLYKW5x`=B$PZ@Jd(u>l@4h3Tmxn;#G2 zUvsD~mwdw3YKGq$C7}$O4p|CH9Sk&y z0skS`%*jRZ=($=4CGLr(&;SMn>?AaQLF6@C_aC5IKot*w7Z4}pEmP@ns({5KYzV+J zh4n+ss(h84oE-e$u3lYXq&Nq$gM=PD*5SvNqw!mw(v)b`(C^v28%u%~6{0=teX2o` zfklNLkK);t;D0F1?e_kGZ3+{OsA| z=&+XCgZE#YM$un^7()hADup>-r8yoQTwlyMHn9Rh` zW&GE6{f*qveil#Ajlqbx#|$*epGA42ME8D2CH#Narw5>GQE@UuZZ*$7QXX3m%_8W zbcf?|(x@a?*IDXaev#=#>8FJ{=kQJyMvn}Sa|(|eGOGvC zZ{^L@ki=y|vd>hHC3T_B>e~0)-h`sm|6^Lc&T0ywmSsf?Zk9sac!vBWbAV{(Y(R_D z+Q`4(#BOM$cG_-1M1HHc+WlW?gy9GU%sSzHDq(Tk*ZYY0_E)YckENlJ|(@Lllg`9wVI?M-~3&72$ISk zurqUt{H{IZ60u%fEPD5G_Lw{(HZ{&Y!^geZp$f%e`~RL-CR>-oRNUUn-fk&)t~{FI zITlOa-0;41zra=Fm9;VK3(&4sZ({`D-|+Yw#GB4fJ+Di5xL4fb|u_GkI59uhP6ncV-n`X zhOPh^Kzd4H?{yIpvqsJaZO6w3)_} zu6=e7dMN|H-DYo+u9(0_-9!Ut6nD9uZ`Q-N~X|yjUTj*0U3VSo`=BkJRk$yAsyu0!x57stMcVJWG7X#C1kI za8eX~;qql$qf+GijNkZwF9He)|AvN|4Ki&8H4+Vr3o06`qEJ+AC z`6?3npA=C|9B~Gg3wggr-$gfKOWOb5Q)?7SIojYgO&W3G8$uBa)K* zM23ZR-_W?0)GehxTcDFd5>Dtd11t`Al~uO(^}Pj<2p|W+7LRmeYb!_f_eoa{LdYri zW}3HNy`}(F`E$}9$~Cij+kpJ(^)rCtz+I%inNG<{)1IXRY z4Gqa@X~O`N07k*t(*Q+*sw$v$paa!NoB%+FDjf;rK35O{UfkuQq?o)3ASgiL0JIR; z%)0o!rnY)|dLU&V^TazrD(vqi3A$_OuMLy`!=5;Yh7kZ@zS)!-Xnc(ZTz)lHHY6yH z^8Z`YC_}5|yiv0htIX`ytbFbl4>G?WJq>}nP(uj2l7a#lYbF7HhDZ($yzdXfD0H(qKA``wadlnb1yO8O9;6o4-9qkKZknbjB0OOuFw1N^=z3+*JxJLee z)5U9VLJ%07k*dUUSJNARC*edSJ7n;w=g&(TpQp&{J9*=QcT-=Q#36XlNqhw0IAG>M z(el0D-`gmNw+9?-O>cS^&EX)AL;wG8I=n>!2r}CLcFr`O;S&2}2cvrn*Wd*IUIwJO zJ21=-AKtkG;{Fj80B%mv`E1DJy1h|73q-z}Dk?-u3q*}x78T=>;B(Yrd2`QADeZk@q-abAX0DZ8z*8HD#T{}R7S!>e*zEpeSYyJ@^Ap`YsnnYMsdVF|d z;w>;+U%!5Q^UcH2|Jq=ZLGORGVi5HWd~@1DHadLON5QQFI5lQkBz0}=?P;iGpukp+ zDhz;VMB3}uDvD5m14<1vn^Eu@hw#?O}l!vu#z2?(dMu|c%wAz;t?q;{$|RYW2&JQD(8V1h?RK4<-RSF`UY zm*e%jM>ke|1J6puPTxw!%OcTkBh3?7i|mNW)LjZ#_p7e&oZ45KG*wm}GF2X$4;VIk z)w<7*_&AbOPH|<;I$xix3%Y(aq@2166PJY>kA)?E;oUo{AMYF&54&i~NfLwpyo+ym zA9$o{E$zDK|I6j(al_JXz*ey~X3%Qlh!Q@XV7kh&2ZFVvRrduPLNcg5vdkPK2>2&L z3-O7G=vq0%x~1k#!6&>z`h9mGc(P9CJZnZW69xlY?+_ZaLmTmJxy{}+41EF zAd=%Oswj~TzzBkBqCtd)qT94Dc(V?p4+9eRlVR~{CluYGwSOa5xpBu!e z&~;AwGG#eifIGt~j!4$Uq715klQYJUQ*_f@wxB}{SP?KtpTS`UnItN8 zoJs*|*M2lqBy2js2^cP8U9t}i4Jd1O5Xy1{OOARlTx0>iX8vFATOxgVrON8+sDnBz zV5}pTR{c8Mrz9zJ)sN?J|{5u&(>M9oMVr%S6#uq z#~UoK0bB|-5VSE+(gklp!xO>JtWm#U%!y=+B>`Cvmp~53HxSt!77T5lw;6w*n0V8D z73>glfj|Qy1MZzKKvR$EHT}%k7_cXm5p=5o#3Tf?Kmm|W2Mf=SAHKQu{Tv;A{pwX^ zQYsM4FTi7Stm6p&QgE4QKA5lvD9I#LYMT6gt*xyA0B`8{E6UQ^8hj%F-CFJT9GQg{ z4KI8R5^0ol69BovT@KDvLSMjs?shZBxv7eQK_LoUy0rU%J6U}c8=PZdp1XCIKfHIZ z3d#$=ep%!Vjh927;}7j5$ZqMxp0XfHM}5IM5OkpS51JIdW!BaCpvGvrN@7@Sx(jp)!V>`sAO9l*&;b$cGc|e1_tZX~k z$jSUyuuTihDjz$Tc;K1!f#o*B1PFs*x+Hq*mMdUO@1Juil6ABLXi3_y2EdbGjOge& z?ob6EIu?9qn3;bAY?WAP2S9`G1s*AbXVcTC<$X(_xIYV8>3vHWWzc#pIbvplE9&Nh z1yv^)ELgN~Sqj3~Z+QwnbhZ5)`rV8IP@-*fW5{(WJWN+Hyc4!nAD z|MwC0@A0(Kz6l~k#09}jEu}H0FS}K&IBrBcP;_Cf0Fl_~!CP+JHn1xNU2|dB1bOMP zVYfLs47~KL^iWX`$y5UVF09S5l$c2DSoo*Qv%bqaT*wbOIp5z)o!%(N8vQ1sK?ENp zxlY55R4MJI#g#WU8L-sqbWKe!;d_3(dIA{F_i$(?C1GY{Wm%w@HKm@g+JJ8ZScdgq zO7N|-7b!u8Xz}pWsOoA6KTH?Yp9;e(A~I^m|Io()b{lQ6YGPm3lJhh9kv%uCc1`i({4l-c80)C?p_!UOq{BcA0 z!O#}&q?s-)1@eLH?Dy?G8!j(S;iJGv^Hd)KUJF1=OB+)Et;C*z-_(sd#MxJmj(&W>Cq0WI%BQTg0aGt$;2Snq=BBSb(oE%G7 zGPSj}bT_xP@+xw26pK@atD?AqfW7zRcV~e*6@*|uq{JVq@z2tQ+DNhw$1oa!VyBf8H?Bma7}~d zfvQx)BKD|1zma87<1!DS7-5Tb#fsZmMN%X-ZRuzs8x1#k4}cUNRpw@j7!=>z|1(B0f>4!5zoz?B4Lujg=H^sH z18KWvRYn?G`i+QaMay6=W8e_x^GqSY1_2Koeo}=UVR1F^urr;ofq=sR-%A1>pou}+ zg7TT&n5@pr%_YBny+a(Brbsb!4 ztV-_{HqM9B3_ra+K0eOFLxp<1NREj!UWaoqtf7x7ICP&X6fs}*AFCvcxqG3_U{n|Q zv7M&&6C}cbuY3n~HE`N#vgvnWJda$y;s{5IV|Rn)*TjG~4mwiM_sZgM0{A{`iaZ<~ zW*w4QXd$pQN1dGVfum@&08atf`d-qecUdFF>(Hv} z&um0w zmp<~RS&cG$1^yBRYv%AI#Af|g6Rf;j;{YXBR2-&AnPIBc0!z5 zPnAnp=2`LO4TK(To7445x|ljTI>c)RS&yOci2y8fL6axb>THU0MoIoFOyFNnD1Dm; z^bL;LCj$ssvni7jY&RtG# z1yrMA1c*g2HeR!$UUR_Rx*H$=4Iv^zI%Ij>GHCfrW*h=(Prpk5uRMi{JNU58q*fuj zMF4B%6Jc1SPa5wCnvN-S6|13+4M?KstQr7UsN;N3mub$==Qs)e_va71Iv$}eYNkRH zY4XDm!=e-@b{{Qh%pZ%*zzn5xHF;qisi=590vj?K1XV;WKEtag;n4Jia3Hmpd=2nl z6aurd(>;BCsQd!hVvP`@R84{^2&!xj^r6C*e{*d43gvH?zRQk?S(TO;=JfgQ$C2t7 zyax^lGlnSV;$Q*ZZ~;=1eP=jwKM^uw8!pBIe)MN0q2jP9++GUk*{E(CLgs9q=se&O zj5B?g(mVs(Hap4|UgagRP;t#TRLo zzd>~#0n^P2{t2$-I?EUBXF}WcId9L?8!iNc&V1>6-#zTsz<}9Iszf3SuGK{t&sp~) zWEIaTQC}K$VZ;e&X{AVPxOLeYUdhgpd59OTa?nuSq z`V?p6zsZ4`AI6|zP{DE=EJ{X#zjR6+PF=&rbQ9N7BHed=Yk-4VBf|`mAQJ*-NJ&xA z3;2E1wWkRbl1FfC{@#!pcx9oNfO>IiVx=e0$AWkeG%sL_feWy;G44A5e#K1)VnEoU z0Em+dwvDg^wcp%)R(+@_)#`^zZ3Zgun3^_2yM_bkx;1>6=vo0|B=m=7L}qzkh(n%#mQ3t@9|`J|Mw5W&Sk9_x<(;c9G_x?Eee2&2qvqM?qpK?AQ6k! z0-W_Oh}oCZ&%trE@pr6*);rNpaAq&3Pg_?=0sanQ;;vn+D`wEt%HmL#2{JwV zMFGB9WAMpU82ri3E1(3ilb}M67ttjZ5IBpQGd1@H#ng;)2p0uO8~LUE|)1V0f5 z!JM$k&?oCaRW@e~aOD5Z@>yKxb=#odC*i?bi8)+81{aVCY@eRP*02Q$mJi>@9;%y` zxIvwr%FVM3=M_LG8wc>%?CjVW<#~m@;9F4fL;ym+)r|iH4TKn=O_JWXQ;TXfbAf_*wZzF|2o69u zAu0=K&8X4DCZNt4S^;eIqo+MKpA4XB*fzfnyy$G044@TC9n(4Qa^%2f`wd3I?RFN7FSediSzHcn3W$beEui60K{kjQd75!5XpklE`C_^{c0 zc|jiwUsd-i2c$at)-dwZknTZk6nh&)lol2jm3N05Y8QHWyj*F9QjIFc9R#UiGN#N< zeXO|hsj)WZXAx`>c2NTNUfx*6DTU~J+yU0_-I~G4)3!EwX(dI>gJ?F`_M!-*I}!tR zi!6W>y$hoRaAS}CPZs}eh~ldo{vZknpm7a!+-LGo?}aG8dd8=)&gn%yAB0&jLt%^C zi;muCTZID#oZGv%4#BXlkVtY{7N40Bb(^|?g6cy^L}DE&0m27DE}y2IP)GeCn0-l9 zwGvnU?>_hUDi84C5hbOi)srZ!0xA@OYgv3~bmEpDAgdrNg^9*Jq~?F+zf);cFWs?k z8@2$9e!I$-Y?@K--2c|dXoU3Sd%4EOY6EUam}B6l#s8g1b;83x@dX_E`YR!WLBPS} zsv!={8n}#AEN0$k8o`8wwF}BR;&kj@1w``;s3M0OLBqw#n!lyFd!EPo*!_Z)@&keTE;)yUPDxjOTymp|J>_b2cjug z*NQBT)oMu339v&E4#GyjEk+dIOHEGh>=;!X&U>bGWDoZWGrQJ*^Xnw#an&>FXRsua z4NIg7u**w(KX`queB5gV!hr^dd3x z7#qegD_{lm=={N2T#}v$aXS&pw{7z-kR?NURYC~%pax)XYHDw%sfZEPT5USH&1%VD zxh3LX9KFk@C}sXM&^lixqznhwZ)lWs?E3SPAYPXVj?EBBtg4-ULkl`WV{H@fg;$5O zfu@Np2q+BY=7I(wCOX>w0W2^u7%MWa7ls)zk}xRS<%eOc?I27OWbnZb{7LX>9P9+C z_c!b-CsHuYprwKxio_KV^X-|8`+4bKFRy5Oeukh|{KoL6B2n8hTwes}gKVakg zvNSQoo6w0nVw{ zK+@u-1sxj+feqTOWyK{jC)|G9uxiSFn@P~@sJNQ4(YI8t9BrhcZj_-G+wx;D1H~|cW14t z(E612x4k9cGz7W5(ZwG$_TD&q;ERVG$7}$8AN_81pfQ*R!=>MRv78+@45(TPK68)S;X^j)um}(5r-BTf^#B@&4OME&AyEJF-%VDJf%#S}@c+2+#>@-12vZ zYMVezbUyQc0nABlY4gRz(k|2#1R(kGkA1?ScV(cg;H5D&vmkjGZLv`jq75yKkBW0y z^tQ_V8xB1Y&N5%FrL7McFyi9+8di5pw?vc`{#I46;|o_kf7SV-^{Q@tll#?cL~hTT zKtB(m5RPwN9(;oQ-}5Sf;S84P&*U>fmAeD-i>x0kGf|6DxWZ`EvQE>yr;Mj)E#l;z zjQnvym)tI&tlTDTEq3#5I@QlrPB27|HP|PAhBHy$a`5KQX%)r1unY62xHK9PziF%G z#`NKWEdcxNp{yiY3>D`yVy-z(tO*u+?(s6sAb-idq7H33lm)XR@$_IyOuja%&I+5M z49d~BX94{Z$(SXrZZ8K<+4YqT&xjz!#LUpVe7r^C6^EcmKcn;E`b-{qU3B-f8}T6Q zkp#CGe{Kgdpe|tLC0~65cF=mLJp;n#dzm&&9Bc|S*>iTAGr^n6l6bAS_JnRvbf2f3 zB*-b{pYd2SglKkqVVaY?C#_LudXDo6-2#i(AxHpYXXuSrMirFg$nmk!wx2MqrvA4D zuJ*y~&R(QJ=})W~L`L$qClXA0d8whHAud3qvBgMlGm+Kfo(yWPI zWtO|+uB%aX4QzkHIIrnlCk`=-++)1I@+(t-S!cBF*Sub^IOgiy6d@vazRa@yCUtT` zKV|j~`Lg&=Jm%A_~%iV?gghZNhl}n|H-f zDKo8cVI;c(Itd`3V-TUB=;m!_m3oz-C6N4fb@qxY2dNt;u8<;jSmSn@d|PinYu0@B zrYZke&?2_r7Ut2qn0tYhx8@w|3iHyqto_!t7{qqrY(amHaee2`KAuwCp_mdp$LMc) zNAbs@1&=$b|nRT#FnB@r&KGY%ZPr4gzRh(mP>`tqUvP+I!h>KG{I zPDPIxS7`$$|D8`pDzUUr#M2N?jr;fD{qsxJ--a$qZI8AzGOR@F)YE5Tr>H282t zm9x3Dwf+(AM*WSo<8{!8G;wj?`>Xtf&xBO6d&Bt2=5UzNYQ{tj59AU^WaxT*iJ!K; zBQRC63|d$Coky3a^F4b`V!UKjm8zXjW;_waKc&JBr09I1Zc<{! zWDsN)>9BJ@+cvr&!13%^ph(&!#;QzsHSN>w#7DNs0mFDbT*Q0QFWM1SWQe01#4;7< zHC47eXu0#|vcPWw^a9$q2S| zArZ9hmL4wI@(ZeG8T=_3;L{~UEVvE+qU}q&P`^hBGi)57OyogzD(>zbMaTbTm(B&p zD9!!OuC8haGNm0jcGiM1a4aY(NpzRE$5k7yBdCQLKkz3$-A-zIi(zcB6j5_9|9xvt zA|_KteuOVUwBElXCz>GN=-ZBcQNIBKH@-6Xmd%;OkEW0)(_i1YY>p)S@-oAGS9*2R zlLc`)GZ8wc!h`gYe$x$CpJQzd8W)p^R?V&V=*Uwx;Zw;3`|F)X-CnJvX!6>?>z~LJ zKqDr*y(JTVmBz(~RZH^uTbb5cjNp?QKi}bqf}ej7UTR>dGezT|xG{+^qm7cgnoUQu zFJ;$c4zzmENwRvRpwJF^l)=4wGJsm|iomi-4N+SyjfM9bDUKWtD?Uej<0|$8eg*r1ZYE2HB;=Q; zkqb5mLFE*c*0%)egfA2x99ko82O?fIE0y7uNKsx;{y3w*pcbuSe!@#@Bu;oQRlO%b zFaWztnB|A^#9{DO>s|aMr=!BjhrT`>aOCkZK1vjK?V{}QKYp^5 z55sOXtCZmp&=^U`n;s!9><~I3E_AYgHw5tGPeLHcI5`hM!18h$H@JWQa1<&TP|Tsb zWv#I;&urHLk>mX~rZXXjSjA6_cNOfzrNu^`^tUkI+jfmB`2msvKX0m0Yp%7U!k81N z64XKuU<~@L!)ZrUHZvGIn0B+_3sgBWK`)zwxvOZhD;f7C5=;|TqT~H=sAUv(O*j}u zo8@<%zVyj{^UEP)@|ON`1wQF1G6~s6kGO(gE-a_xM?Fr^L3H_GU&;Ji$dA}EqCqMS zv~DKJh&eG#M4hO?@bN6|%(Vj}y5v#IGfMXKjhc_j{AOQXBFyN6=i}sxWZT&yugCk_ z9AU;fs@4%auSRb8Qtr`tsqykwCXjfb=?IcPcr+T8ilrn!mTeN>Pig)myfdnd1|B1a zxi()E;i{tk($zq@{V9fE8o6iITDqZT3G4I+ZRMd6)xWpxRmNgYn&rf!_mui6E$Fy9 zzC+0euunnBoep5(5F;`p3JD4HKORw2>vCuu;A(aJj&fHX|zdntZ2hNvOP&0+HO@^a4D^u38KADog z{E!*{=icX4<(BO`SV_c5#Fh+Gr$(Msw}?ID@MM$CXei$J3>liI2i5q6N#YKp-ORb= z;`h7^cZfJ8ye)v4^lC<&O82uebyP9lOxVz0O2DYGNrsB_rC{1K9tz)jSQ`9%P;#IME<(fs=Y=$KyM2|*n8xRBui86 z44Hq8-4nZyP8`=>dkyjZ4L^axnIIf9BOzwYmgyOoLgf^=S3Ax5tq?b1OX3gF#2scF z#^1#q>ui-o4Qu0?~v;^>6kn`J&(#--iK;8wsuB%`#ca9 zaOEclcL!K*lOh^TW^WqPXafC@?24`6+aFtBzCUo;3?dC_#y(+rcj}BNi&0r@M)n8E z@}O64(+2Yp8SehX>i^qH^Rk)&9~+7p%Gm;xDK~4?ppOQ33R-;y z(BGH2*oiwU(3@rCh#EZS$ddl`y@yyEd0Jg$s4Adyf%$pSqeJj{7IG}|Wgo1`w5*wI_wVB@jZ%&9Eo@@{hYYZSuMWY>tmTa^yDs|cxpTG z*C=g@x9?WL)EnJj|Lhu;eC=229fwjUQ^LveCW5%E^tiI0y$9-RFKSy???HE<^qXVS9$NDuZch zQw+O()sy=^9!k1UlS4Bo9!dE_t)z>Oi7uXof{4nz<=p}|B`AEDl#bd}0^xWTnuw?x zHXXDMPBOLX&{R#sj;N;b+3KncoleUG@bs07vNMAf)9eOP5_bKH6rjvgXYG^ZjBxoo z3aM96=L?$mX#IvJKPwq3ofYup`yXw4Ch!;j{zO+!NX<<8nE6TUTX$k5fjJ7z*57O^ zvh`Jib(mx93h9VhPOl#1sgbG9qhLqwqHHuCzdXid2;VP~c-)>(_;M!)fK<_ebLsh zAPkmmS+eavRpSm;*dWF4#2<4G%LqLb{c`0q3kzcTmpKhi4<#=8mutj5^QDfj5A7VE zN>g_-8jFZMZbI`Hn+=Ly;YCp23YQt#?9+A@`*DtE&WA)E8>v1B;yR}I0$m0roHfpY z{cLZd1}g+oJu;mhDmy{86ZnAy2wb1BzZP@^1T64P4&?CU(!V^UfbtQ|^r*hxo107v zJ+~Ml7^$fJ?SthWi97tBlZq;%c;AjIZrn=J=QXo_!x~`9(9ll$4R(k9|(&>e^WMtMOY!d5Vg6_hl(tmEoK6gg(L5YYsiK?Vlh%K(1q1!tpAGzeE^D%m0{hUyEfH`w=xJ zMw=5yuqqes?CqL^EZeJJo?@mEe@1QL{ImU|y95aCahsV?bD7}G3VOqExw2{89m+N* zueg>#`l?TKT+~!J%=2t16OZX0o|46gAz2jCTt+)ug$bWmm}{sQ$d}>8ljMi`%A7qm zrweU8Y!%+L7*r1-mCqpG40Q>3R)*U{pn5KxxY!~{Mt!Z#q?Xm^`pQe4jdTrQA4y@h%{e_ z4_Dv5G%Z_nlhzZD4%eRNynA(^n_9hFdXoRBD)w1in{>@VTW$TL;?yvz$Q~7guv22m z58G)@_xqL8(I>sey4nRvTX(mU6}Th3nErO(xf(;Vs9Wxxbf1cJct(M$RyVoa$)2HB}UPH|>ZA9|jYG~PN_p>a)@s=F+hLX`{{T>LSN*{MaU zg{RSpMf?0Pl=_|#IBp)H#k@bpj!K-U&I~hb{@LNKhfG10x`&7M31kmH$cv9ub3)a~ z%95SgeJ7!ku$2vy29q^^KRw8m9g%X=kU?v7+5Ct6uU@D|Whj)PsS%q~G^orUp);}< zd8;-;PRE~vCfkqJ9j~PN3S!qTk1#3z$4ti_EP+?6cKCB-iHV=0nOAPcAn8R;q6mID z#azBXt-tlpo0?nmC*hl;A{jWN@0E#8$z+4KSlW1Nn!;_p*w+{_(K_8&rtp6gAK8-} z*pQ{SnqnU^+Bov(R3^_kKd^g5kH#8ihJj=r!#!jaZ3-g=11miWWB@rnr;a5iT@Wef zmp@ZzOHSR=DJn=?-bAMeeJsu^Uw#`#hFf_iOS~&bik7=3xrTt}5r0e*@!cx_L1+us@Fl_E zgB-q)+zL*fA%6VR=YK?V-TiWj?jYCY&S&SwqTuxBub5`c#ZPI9mOE^7rTk&MO&>}c za*CM3$5Ls}pzBtfQ17v02YE9+5;D{nr!S(xS~FyM-ekgr8&K zp3ZST%M%=&l>8I)NP>1UQ=t7VMeRYN(=#RoaSSLfiha=!A?*+U(e6%P!iPqn(auEi z-rI8N(lWpAW}NKEwfq1KJyu$y`O?;SoXqInwgj}Lxs&UCO=2RKJ6O;I56jMf$FwiLTP2(bZ=U16Yj*Ib zkrgIvd?)A_bjn-l!op2!_GT*nJNatUiA6@`CIR<&zyI$nE;6jDC*3~iKkesAQG+Y-d=JOyg!MDCjiql>K2`Q>wW41h zZ~&Al@7pI7g*ra0Z#CpXMLNPccA}mwl|nieDN||=R;>8xf-tC^_&}mj^P=hoL5I^ z;eVqa_(X@buUY41c|l7d9r6gymOIjMnMAI)-N=Uh8`s?OPt6rE^zp^@NsI-wA75*t zyC+G!PufM1=HM_xv%znZffv1<M4)sNn5NftH!7-4d<4^)E!(O*1jJXIJv>|2o62Q738ogT}q8zjwR);gwTM1cV$vqqozW*UjXv32J}oHf7wv z>1Rccw50oZuhqBc6cr86EI@y8(qb>z3xWZRYB zc~f0){xS}M1Wt|}$5XzuhUEzoH_9_Q{9{H;DS6&^$No7QQ!Nz>pAtd>{%BW=_skf1 zEamJeR+wqgih0lfCDKxLjJVA%ZE&Gop`81+_uxxHHMftGYnt1Nz0kUktL;G1lv~9E z{>f`9T8+DTr49x9*YGoWWat=kWU7>|{A~1zK;kZDx&Me(q4U~(p7o%XLc4Kp{i6ljC5wV*LaD)S-&U)5l|lMyoyxd2(b54`*flO$^p0E0L#jyyjH?tHyfn z^*;!BzFd*E)@m#qk}RzAchPnG7r>Xex& zAeEm(e=9vI>`$Nf2|Fg6Q6pT6;(*4ynFJxv3p<`KzJ-{)mTd4P?b#BOc1ub)^dX?t zkZo|7%Qr~LzZYRc8+$@TQWNx%BH3lRH#= zYDQ-w!^`mGcw<7%v~IZb9iA(j-j;kB=iuZ+Nxbgu`|YMN;W5IF^8KQQEiwFmlz6QX z)Q|Ap(XVr7kQ6LkPFoGTJ?p)f zdHZ?O#Q7S-J6|`GQ#SnfJUxrk$AfZz$a#JCngn0wIgP5Unfg2QBoC#pn+lEQ^cd}} z2bypEySLQQSVws{YWy4#1=PLu^EZ^oXvUeA z&C?^p-tfoS^}2Qkc=gQj1~1`Se%g1DBU+;z>ueWpG9F!S!Sd>1Ojan89UIzwv9UU1 zY21;N)%6?inLKuAtHpCU?Q$Is&}&9~>FVmrG5tKbK^V~vEn{ zMU2wTd2)@N7&kHt7s;5}dzM8S@(Aaxv_kjwaf`3YtJB8UJ9Wvt;xfG{BtPizl6wpo zlDv*PqS}Zeics<*tgiC585mrI`1-BzMs&MLsPH3N~eTYwu0LBcEK z_67~DU;>`fXQKS*Eh-6TDZXc4eW+FNxr{<6FvI|wOx*bA=96!qMr8?#h+qKlL}2B5 zX~6cXn|NyP$hi$76QfTvt>J7e=ep_E<d{wYTlr6BYR5!+|h>To} zO1g)+{*HUP^>FRo@%j%QZOte_h0=h>1K*XlRIko*OmFK@>m08-*2+wa?Ka0cd4FDD z@E8xA5kCH!ef9EA)dh}*sLrK8nO>Tk@oJV6>EwZ)^V+Y!u6_W#+fO$8ZS|4>A^C6u zm@C5=cK)do`z~8?!_`!OnNz|&T$5O7+AA3E&9z0u-ykVc*$@{Dh)t3ob6%HR>%VQZ zVwPj&mQ%c^v3xB0+Le&;u}txYUWE+Xbgdgh-J2uAL?ML9v@m(4 z(dtBPiWBUwQ;bgKzcwu^@Xt>8Gcpy*TS5^K>$dRu9==oJFU9<<#w zW0`7PA5bkvlbvYm+U)Z`tQ|_NPLh(~6uDFN#Fa|p7K4wabq}uoMR_`TQ{9@><2A1D z4=%n&5Hb47*<&LeE}F2uMe6UTm-`G&fsMk>@A9_*adT2-#{A`)F@f2n$*NSE@C|1YRP>v> zFw9lAsr{R`6`4?Q4|)rm?nTbKq=O90ADc9Ft?53b(prd1WkR<}M!Rs^bX@L^$q&%DW}1 z6tj$%riaFULgA_-t)J*LFJ;FtwsgJX+TKPC*PBs~9P6Uq!>Im)a0p?QE2u)h4MCbEO#Dzu#|f+`IDPYmZQ7QTe(XZf$0H zHao(|WHY~tnUqcQn^0qQ;XZ4*^^e{tKOXOQutzYqSfcw4E?DEL9WrdUxb@_G&GkrS zU(nVXq8kgG#!6Hw#Q%2SK?F6l!+)NA2=$IYHQ{LTXnuK^j( z^O`GTHp`m`xHMdKKSa8v|0O0RvVR@<38IIq#j44h)bQ)7Rd5WuTEuf7jkKl&4@;P@ z6@89SbL2{sWU#<`>)Gy4tj2%yP2ou0?Har~xrElv%rblxHO3GvsBG{)Ge8StJcY*e zp&SBw<-+s_G*Ds7cz$O|`#m(+Os#U}n(kn+Vvc)0DZtFARC+6Apwb?HLJ%0{CWJ{h zxD_FGb!k?i4DWG3TPPV}EB<`@vgyfNyicf0cM(;i+WaIvl-$fKhdY4}&@L$8bh1OyU zdC8Y6-Aw52xWlcrbp0)Y+~v!yl8G_O7Hm#8UnuBSU^OqSeCdR#kNfRJBlxAkZ7H=el<`pBB@Rm*(hudrjPU0)a@Zs1n9p z$&R@8EP`*^{$t@w#7o=7sKc40fTN?-wPZfSYT7E2my6$d>b3?V0{A&&Dk_GXx1(~K zHlBXiH7axD+fVEfy5U^tO(bzRSm{~IyWm*+28E5TBYizwO+vbb;Um1CYfU%x!Dftd zrN-!-`a5%cIbuZMwbVyPBiq9OQBQ@B4h8Pn0#?-c*Ftljv~*B!o?x<&BR?U`8PF+E z$r|Q`Ap(lWuz}+6TenD~RRI9k1e1`CMcG?S#3$@2+RR2#y($(y1Fe}Z; zmmWopMrL#J7c2SR7>xIGqMh~n292p7v8?rf#?mxmJcXu|HXe+Y&tuCSxg{KrfqN(V z23^beBG~wjSJo-@68t0*omILq`pmu5n1otG2wWVVJ>n81AM0$BMjM%eeX>)Kawy&a zp%mVXZ6VfheLF2^J?Q9 zME8AHeF#;`37dvQPj6^EpmZbR9yg}T7lMKv%M@lH&pV0Xs=<&uRtX=;4wXARq3m7h zi&ZRE9>TcKi&rwmw5)I5J760g;r<4ZE){oW7uQlMcvS>>H_Q9AmN@$tf9-*TBIB~o$Rv4| zAK{OT>WdVnEOVyDd%s=x*Rw3poU9t0$tK^@eQB1k@iM_pzkXptoQBjIX^#B|@C@^u z5R;`$4CLOf{PS?qD!*W5Mf@GTu;+LM zk^5^={tpX$UL1j~3fgiXXZBYgMJJyxe6T9z)-$?$ZJ!7@B@81QLkl;mHa^VsxA(-Q z`L4WOtBQTt!ym8*7!uajw1KiMIN%;Tjy!c3!U zPSwb^Q8Z{3Z@h~02;i0H&O zqKC7r*OBLKsSp%w4t5Yw$0~{(Zp0hGkS(MC;d9M{l9A)2wJau>6(?D@sCKsAZKwN8 zjMopdi#(?J+su)Qz(u_*k>T^Hm))KJhXu(0oE-ZA=YJ@M#I0qvwf+Z2wlPe04^3P5 z??SVLM=-pbHK%*~uJXM}x9LU3r@TDe%;r>h-y>+lw)Q%v6z-~LlVD^}XfP^}w>>iN z4GxY`_IZOu?rWvoda@aa`Jh~U^t8CT?djv9_SMYK532uI>;`MkOfEP0nn!s1trUuk zG9<+ddv1R5NR10E6>Q@sHzdmJ^OiEPs;cHi)9S)h)5GKMc&-a}{;9g7 zebef@-`RM?NZ{v&qR$%goBNdqVfk18jb}TaDGaB5$)xfE&)Y+@etD105B9lhu!9P1 zp`fdg%XTc^Lj;Tq0*rC%V`7PrqmZPPWDKgSkF@$D2vUjjLk)s&T`#j_-rwA$LBA?K z#{MmNhyHO)YjqzB9htl)?nw59!f+t1Etg~Z*bYbW!cC(0g}Xma5j=qLi;M8LSPNZ3 zxOsfhjQ!kAD9%eh#i!EEDN7RK?lRoE)6wzvbi6Fqy7zpBX?d8pNo`}2dfd_djL1#% z{zykP>stRFk!Y3NLAJNZ+e0Q47$sACb#ohLnD*}{jn!kwSGeV4-bO1UDMATn!4r$E zl??CoR3F#b?q&=wGqZLex&w~13ig}GR*EuIeJ%waief)>5QO&88YS<{h7#1G9_GF? z;ySX|m??hhD0GuPWQ2OHtWIR5t7r4FJJR+|3C|aNUi% z-|X;Gy^NJDC8%yFPbyOIJ>gIP?JrS0iFk}(=MxO=^`5ar?Eb38yGriQzL8eBc3<+c zf9mmLW#zC{>7%bjN`be%{Dv;B-_ogidT*v8kK!!glKrxNU*uWEx(!eK`-C5s82jx1 z5nA$ZZITW*%nY?YuP%QfZLF?o^khEtJ)xHA7qt_&-aDnw_q^7h7n$DtsRr~f&IifH zycCGk-rS*%IRVl1dab~D9^-9pL`pf752m$8P1F+Rr76FP=R-;S&8*`HBP}6N77!lw z#%nTIOC>NEuSQ~zY*lLt3YSJCB)w+Tmd{#u4;p@`$rbU3-EhCq$Mv1qu)psbsOSu9 z`k6d^9F8pbWD`d}o}B()L)h9C|DHSM^s9+F5g~JS#27oX|G-ZcFL`>=D&=xQ1SZ|D z$4m=G{T-gZ`8^AXR^twXG#FM1Rf9F6e8ZW=ZcBL{t@>9yIluhYnMi8i`rO;jdM5oi zzgB}n)Di!FYhcN=wEy5`-%Mkdko)W7O`4cQp{Sf*8Gfo9l0kKg~bL&(LX&V zdUA`;OAJqqpLnGGm=#{3Kfk+i;Amg}V7$qF@Z4u$Ki9ajqpD;q>w4imLmgdR<{5;N zDw2i$>+K&~ahR$#rsxTO1EdeSB*ny*F#IyMz0>+m3GOyjf30Wm-0V_%ru|4kw~`R@n7)YWB~QYAb7=2W4~5-5P}Lr@l$P=r!<( zlY9NP_F@Syf2`JF@z*sZAo1vc4 z$p6S9>AlkNc*xYWx3XsE;(5AtEa6^WYW!S+^x>3iD?J8daly>h(^o&lSOp-qCy+4D5K7&*kSK=ExxhDe{v^lDAjx;SAul zVnz~wFMA(sEAw4tt|&YVtI+vgIpoq>wu17BRtc`eH%b1g@^goYN21S#>k!y;exJ>< zW++;kzZse!M@^bvC*o8+xjXMlOOe#jI`0yh)m>hs!M1iA+9_Gi_x82q$F*XF9>#cPWfh0nw^W`DY!8wg8A2vMdIiha93AsxY;c?|NWSCe> z1T~H>lV&_hy`yEuL5kSkHM7ZBTgBJs!WAT_%x|?4V6?Z{hAf9Ihn?S8y`r0jlS<+w zVOf{l8rsu4mg)Lr=izW#zb1|dt)9?B$*Fraj%B9d3pjU{GOLIW)FQRY7=x!>ey{Lz zzxmQSWUn6ZrZ@(_z{$YOhbMTk*-={=m_rJb;?c}poTfNYA7O797U#0GjSj(Gf)5ZNAt7jj2Mrb=K!A_{!3pl}G9*|6!67&V zcXu5mxVz6laCc{h?_uq|-o4NH-gVCWc&>T4fbOpDs=BMXyYBazZZBLny7g!{{FYnr zZEbXgnGE9dmqNZ~qIZ{sYu6dQk@(znJkjPSgBwOu`u?3}lK}gJME@(XBq6-DY?*quJC2Kbg1ei81c1$f%RJ&dmH< zyepM-1pcbY$JqI~HW3h!Aog+FpxzkL-$gH~)eZn8GprNsr}&^vQ;E4h(-((7L@6n* zjvQfT*w)>FD0n<_-{R-DHB;fpK$DPEQS0nxnI|~@Pb8BtKFTZ>qvNuPRUIu|q4__N z5E-g;0@#ev!~uO_iB-~39>qsS)h@N12}=dRJDFJW{`?9HVxbFWK5YfT;Y)S`MQW^4 zwL?d|7RR91?F{QL&7L})PVr%xEL@W0pu*U>e&981QSvkv<8?Gb#q&?Kj>)B=HDh$| zc_p4nx>{n&k7a;s9P?NMvnhvI(kQ51=KXVcY^KWR_xO@R4JeDJ#3CH0ej#IAud%Cr zC{*x{-U&}`y12Y^8uNw0>4QxwseA+L`*c0~ZzSJ{J@ngfP0!ILbh3p=Zn&TGv(1^$ zpO3@pgc-6bnQiG2effGQts~DG?+Pgy7CZFX11M1RCmPQAC?1m7@nR}p(P_}WDaAck z#$xb~@U8!Tj8RQ}OQt>hz?2u{pGCiIx@eoaz~zjk*!HV2iG8{zj^C~H@vjofb;&$2 z^txtD5$o(~)i#%^_ggiYEojctWy!wtb56;T;v(dUPjC&1q@+)p(q}n<|pp)!`F0G?r`0c-Odvn1biDmM^8{>rGfI>dQ7wNKT zTBAU#ISi)0s*1G{>Cg;>t?tEf**tfxnMz2K1>c{0Z|$_InJg)O;8zSS81 zh2$y9_IXH2!fe>=sATS&B{Z+fYzz9OR%o2pvBnN7AX&h|)0s;6tSur1M60N1ld6n} zU{^@Ts@gd}(O4n%1;2lGZ3Xm81gwL9-&U6J-x9+15n;+5UvrSleqXOmz(+dwe2KH& z9W~5B!^hXcDsE@q?FEUQwo%6R6xL)+>~`ICfck*|sIty!wf z^?B{4TCD@-adyl<9H2t5e>9zG^22H?m8BR~$^8ev3eu5~X_MC#`+~zP%Sij#Zj8?> zf0#x0ITv62Fn$sdAWnw4_`yG0l9#%OJOfvPmcHFO2*JYEnRkV=-chC(Fi)U1-fKFH z=^?@t*AHA*ToND%HZ!yNaz?6sR+bWgAeq2kWP9{v`BwsHkM!GvU3CUQ10l?Dl)Am8 zz$=bH{t4BnYPvJIRpl^WB%fJSYnh#zyS($Ku*`K<0Tzaj)f8Oi49cN_Hq=hF5~7qD zSm_vc9Ulqj-Qx-6EODQ-JA)i1m-rg}%BYzQi4(t;eHu~l6{f*MO(!R!kJlFpn(N3L z@;l>6=JiFhGE0Kvvg2)fynVewsGF~Vx<`uT4A@tFi9Ho&8Ht>ON#Ghx>iZ4%?dMFQ z$<;5?`8kxZw%Gc>vQPe@lu^^Nr9!H1? zQexLFk0=Exz+(g_c7rOZgUw_oX*cjgvuHkK61fP)WTNoXOrucHOe2FkM=DSB8tLO!>y&2U`JK?!zX|Be!?qs?qG@MOQhdq4bo2Jae(lH?eY;t zKO{lkn=kkQ^VsUNzBUsJxlQTMZ9%OTM1tsH4gw`@_V~`-zk-3n1V;H|NrH9mGo=!w z`hd{+iF9DPxU}o|p)<;6T@1Sf%o$66mWwd7fqA^riVv4?dd-*D4E^CXFU z)E8pfB4v(^5S3;^FRBHCvTHt5+>X~deio!vsxQpQCkz?DXe$1N7s< z^1ueXt<3SjnXit)=;j;gByDz zydA6zA+gaK?(a{ ziV_9( zk*pKf&A)qo@zm9gs^Qu923k0K^nnvA)&FdZHS2hNJo@&DB%Y(?++pFe>7}!syu?Do zC#%a-oAcn;jn>(c&#K3JJEHk{&O%%g^`A@Vye!K0E!-0BR0eQBG?tA9#T%xHHqGrl z$Njxo*lY6jUb+E^7-szRru5iBkqqD93j+=iupK!Xjs_IjJjRf~!1}+{g&%7geC$1%en`$;Fo-eaV+bR55|A3-h{RJ88i` z8M}Ze2VZ(dX9PYc&Qx-K6lWmnKbL7Y=^0+tIGN)P8|g7V`Kew(+NKM0N}iOA{uUvX z_r}#ad5C%<&4TyBp`2K`Q(m%5;#EP4MhXAIgu7qR7CnoY|0WtGUITcUYO(bB^n<^Y zB!)l22apvB8}LOxz3B@Opp+IYd`T>&Mz+0viB>SG+$qUhp^7a8om9!r8P9@-Yd2j|r;5eeppxoJ(BqHT}p19}?Oa>i)%kMKCUoc)s4`zB2 zc^-;}O>)%qe)Oz7^?OW__Knv!(R8u96zCJ)gyRev!#p2(j;*S(70(c;1%pj(ah257 z-TKc12WOmkZ4*kR0Q6Tgpgyj{Y5+7j&hEg85o~5V$TVpt>*+0e>Ic+LhM=q0xZ!4+ zKc)AO`z6X9!%xKZS{Z6KRth{w*d{m=0rL^^6hO9xPq<`BiD>Z=K9+5IuNPhOkc8X8 z%X$9HzWCOq-z{qwejqZmm>%H`vX`a!6%yQ{PoxE!2tN@)SOYf*f+X#F4cGj}nTn{- z@1e)v&fNL#A;-8lH_G)qLwH~k;QTUZ`5r6W7(7Rj>UrE&2JC(Bxd6m$=TkJ?Bd{oeYYN(4~ByNN{4Q0rbHrzS{JWFBL`+d0*tnI~Q}?Qq#|i??w76ekfzs zF$gZ_Ng?Fo&pS@>FZ=Cg=|4KVf2w!1Y48~>ejn=ZKnhq+>!3A(uep4IC?C+j;f1g`B>#pe-8YHtq2(u-%5-O z)G!>4VC59d9jZDj{pu7QOjBOvE=C@7gUam}V}k@yZ;gL65@akPrb=!ICiU7K9)#`q zVyVr`<44;YF!Q?3d2rB2ZV(yR4E)%0@YmO5z~gJc`Ta6Q z-~)m5b)Yil{42oAum?1^mu|2;Sqk*P<#;ZGu_`|8QweQ*JaT4zzfN^%eE|ZK{0}&_ zw7ge&Lnk?+BuwpN#C(-0jF%~EMS*}1C*(b|`^iicWfcqm6G5=250RA5z&*<~c>Z-w z0IhNu_kG?Uq9`oI_ohA{&vz);amuKgrERT@6?K?}jr^#u0is|1#Ux}ow5{V)Xunp| z9?gS^&f1!qsXZ6g*tY=^C`rU0)6$Vy7rdX)+7HAxvr>Q7S~M0{NhW-D4sa=hrZd%| z-nSOG=B66%641dMj;PN}NQTQMvUb5S?OY(JqsQI6_B}4q*uK zyRhOf@&1u042rP(cI`fF**A*(2eWtJ?pgA)T@yzp`_58y*3ZJJmg4u#C)m=m7Tn}e zV$*i#d@%`7J{zHe6XoV%EgZQ5AgK7&Sban54gSu!Ew3-S+IYDWMc`omevO#Bp)!m! zc!{&-y~U$cK4>Z*q2#MXQ;at>CscA;wJLf&kXUuio!2GruxCb~|K$j~E zwgkZ2_;eG7bK#hY#~5&#-Nhk3N6t3{ld^e#(t}a?n}XyNAbntAi}3VYT3gD@wC`;f z7pvT_{|X+~@U!#)!-j^thW|tZfKdKKB-#?}MW*vZbb*p&n9ejYj~lC;W;jnUKxd|Q zXZW^y3lXGJocp?zBOb6N@4?`0PL&hh1(#pxnWY@;pnO!2y2yZx!MV<@b!o9vu0Wy6 z1u9!-S?Y;aw(%K^maw4C1UJTd9e*&;f?eACd6B7CqCWqR1Te-&nhC>SG_#?@3S#|W zVFgT;D-Q=-7>l!eC{shZI8a z_4G5q!p#%xywXsrjq;R>!KbzPlm2bL%QWY14IgyLT6c{>GYxu87S0gv+So|=4+g$x zP%`gqimp60;H2TsvSqd-k08$X#uDb+I#CN)>_Z~9x^jvf1gtw)B;OA?^?K5|TrDk9 zGpy%|F{j+s#?m^wvCBAM4UJ7YkMk&y2?&LF9s=s&{PkJP_6OLKe4aGI{Gf6pG$37= zl6(OxZzVl=$7?akCxIVSMrCiz>aPjHk`td8Zm1p31Wb13A^=sq_VbQ1Z5BPZ@IhnUC)l$UsFh=y^+>>(D;(R3h z1Ox3?i()t6FZH`Zh0`X)!w+ALAhR}7tk}sz=&>9Uq}Bv6PZ$6%JD1oR>TAOy@yr$K z>CgNNslaMYM@e4r5=)M>&YnC~d; zM0Se~iXiNYSW}jAIisds#iyHkuRXukObp6KS*B7B-#hlzD!WfRDE{FKYEWu*!je!N zw@lq5*nYWKI?7> z==y(w90TGjdZ+OQK~NtUi;Dg}4}tS<)wqu?fK)@0-U?T8byaouFt`#E^$Cou1epRj z|3ce`e1#{S9|e>6-R`ph1dd-W+N^D5;4!IL1pk7E;x^Q=uF(5d&(PGcwKi=0RI5DbOvz;lHIJ1D-p;dg6zf^ zb&RM{_?_~P*sZ8lZCB_8ia<$+2L@nT+0Sa+ZJ&f30s^V~Da3be4_h*L6;^25K8Whe zhp$5DY(7r*585JITA|~+xj&ldzzt024V|V5As4fZTLosVmqu}Cpic^aE3_pPh$G^h zDq0k$0o!KETX5d$HPcAkmL#aK4U1kHJPCX=>K$_+X7TZ5;R86Qm!+O-P9to#W~;y+SLy3LSD4QhC?@k)QgB2}Dj(-EXUF>= z4UF*ANyf*96Nb%6bTf2C-XV-MYl;Eu)R=@-bE{2oU=ns?>nb{v=p7!vSfxlQeJ=A4 z_H(R|1A%|Wq+dPqgz*V>!DZ_7w)r1+Z&e)2=V;Lftc;Hxdjkd6FcMs73aQBQYS2jM>Rs{CPl7+wy=mojEj}O z;hbu7iPO=Z0}S+<)Zo>AoM2uzgV#I$_d!#@MA%@mNxz`|diH}qE{d605PL3Pxy$8D zckq>B8R;v_u<|fmJZ*d#DqxD|g-?xS&_O`L@jcjacz$((fm@?fHeX>9uo55+Fbhn2 z@#QZ|-ZemjjC_AJ0m0_KG4#Ew0RW1}M@o3~n(9`mpwHvLqJYa#aS75$y zV8+MijSIX`JSQq^LSf&YmqO5_Ki`99-T<~|MX*3rdhg}I*P`6aQV*{U)gS`E?ST_o zzFfV~c7{C`v1MJH;nZ}pn04rSkJtY_X9rc^NI5*l>`9eUG%o+QhAJ*DcmPIn?g1&jS;qTn? z3ig1hUljsT{7J2%7{}`9h@!Na1tC-e*dwyheN6ocX>i~w{&6}T|~VE0A1ndr zh+t|wPweqr>5G=Lc6=4Jzs~~vZu+WIEEr3V@++!KnegL*>;oHDNj^hzZz>q8^FiieXG56 zg5i|jqNsn2aiGYVzI~E2A#VQK4P(M^9-=yZ9QZ~erMB2!S2-0aQg2#&wsvqijoe$;SYig10+ig*hBV?$^Yg_k*dw zGhT+kM*4x+cA;_pDRJVFzGS0QrrOcjWJ!Z6SFXx_)5xj!Dg!Vg>TLl40aA{Q~$kO z-)|tYW8JuY48K^46Tv&UdaGT!if^U@f4UCUWVd_N17x(I{yS;E092m_WUEsNKWb~` zx^ml^88w0cd_ZTp9kyf6N}D*Bpcgye4^Dhn5Rgsj48X+mLciY@=?Nf3l8K{5j^?## zPR%^O>Ip5!-bN>wuR&X=uOMB40J98Q!I=7elcSxkn_OkZoST?W0cfU^hZy1nGXCP1 z3ocx~Hb7F+io$@ythm_8;aTlmRVx3bgPNyj(hUM+)QW#`&Zqv{$#fNzcosr#0j5?= z`*IQpcPAnHV6WUQNk%CBq1JX<0chl}M8rvrBM?Qn7ZsC%{|Ok-J4|*s&^SxyiLFiF zRCOb=wSdh3cSagAYg59vd2ie;Ih-$^FTwi2BSkIvK>V&XRSV3@k^%RhYa0#u=DQD_ z44-uizsTILhFVl-=@&Ou=K*LyayDB$dS>YN<_Fk_6NS*Wys|o4KXzTQVmA{`-osyV zUrmIwbZ(e|xIu4-+V)UiWc+O$@uaNnBG^VliKG;04^(Hx48i@m0%{HX+*6?jz5X(A zukpYZ<~BDLz@Ul^Bwja5)Kr5~*MS%Za~sEi#mvGSwpGk`pJ>)rvpv>?;IuRk8ZVD1 zyp|;ays_ZJznTLp&iXAu$3yVX-U&Mc!Cr$?qlpJAu&`hGS_;wQfc(T=9}8z1vnl?A zb~0%+Q2jAUK zP;)itWO+Sb@=_!s;3}0Yz9~I&MQ{M_l3(mZ0hj|oU`ic;pRtF+)=6S(2PJcXi{=UZ zmlb-}@t&qhHTG^j?bH=PFBkI;CK`b@l8Du7JWfak(WJ!2igIZF0a*1YN;}=hitBBS z1z5lO5!sCq{5*|~%}sl|;^>o`fx8Sjh+w7WRDRG>>C!g1c&c`55r`I$JO!fns4&-q zhH>9|cN4tS)Fw#^BmwF{&SE?wcrZ<^EkG|?F8j+!GfS|}`+d5}B%7lnz;i>5Lb3cj zB+@heKn;sp?Yq6}%8h0K%W8zJY$w572-q7g&(&Z{3^;jL7?XN#6e(2Xb3Fd=MS&~S zWPUf>?KeOU1xNoCOc^B~IL%sTqGjC>&3_5|#(84nakytaRHoeN>FQk#Ms;GbJ#1Xe z4y<>D*+x@=+)06~U$;2fv|3^O`t;5o;DhzM){0?Gs^ozT{cZT>UXlNltemD1uv-Eu zy#|eM?OskyQD)4_8Lmcm_XQE!Xbw4sFgHJ;5!n;)=u`Q$f-@qk)%Jptxbx}nzOGRH zZi2Xc0jTlLoJV=qfcx>+6C;4?EtXXSa>hcYu&%`W{Kx^s>%0#|%saHt3=X?oJn8O# zRHtM9%>?BeV_2$76Li>P&4bfN2b3r9)Vk@<`S;*a$tF3H10uo{JFl~5#6UI(a%sR2 z1*Em2yLujeHZB@2aEP5nEK+s5=F%`xpvST5>-l^~3uJal7U%Qvw;HfhV>n52p0-$c z#v!0YodP@+$z8Q5w!ou)S*(w+zK6yW@$84Zf;nIb$FJ5#(N` z9qgvjRGppYGJRmLXIHWBmg*b{eDu~N#1m4E=s(zvokU4Jk2Dy|Us(nEBhy(HnxDY@ z$E*Hu(H!UyZCnZZaad6dm54vBZA2)ztqcDwY0rk3f;Hgbo8{l=8~I$%4zP|{9Vl( ztSk!eJj1l6g|h!bjptHpIdq9NMW15-GlG31b7Sp&m`_Ql8l>x)BvkABLDv`dhye@? zpRT2hoa;Y4c6I0og?9MeV`|w9*hby`Z$Ti#H zBR<}<PMD{U)q3JD4R+o9teV74zI|pAHD1-WNrti{zYtW?wo7eh zn@JJZI!a0yKrl+~UA6Rx{IaX?nfQJq%IL_MQrvSeXON6P1Ceay}QXcAbSA~D5S#;g-j7Q;bX z3}4F|POBx1iitk5;<;qH2G3NnYuY=+XG9oCsr&{OhfqsRiT0I~9>MDerdfX!s&2Cs zK4UJC%;I#<^xyt&sdtXweeZv3#k^DOy-G3*9-7$+8zom?dSnv!dZe%9ufCA|H228R zBO-fhsu22OfK96LH%JNed<82~cf5iu-74U{#WCV&o1BSU-R-^`QkvStD0jL$5pOhk zHLKw#)^6>a1IQk(o&7Wd+Bx0gO3}>s`NET{Ky_y!5KyrWLy~oHl7d~6l$iJ>P-__| z_&b7uB_SAoj4@Vv3U6AT=rZpu#Lczk^NE~Y3;eulGD3I~xX^v(2%j?bvG+L{&?gKy z{Tr+5`XGQ;FxwA|06@w$3j81&A% zpJ|P`f+C%NzC=zAFGdkL{v2hR>7funm6C=LciFa(*s*!0&9=auVlsf25JM`NUO`k`-KW`2J+0k9d|g&XRThoe90cpsachGbl2V01#=u00V?cn zcb16x-)fvXH_7!3KD9OG>0sVKW@b#PE8Zm+8pUtMx_b+=ga@lKMy%X|KZu=?7VZ!qQE z6?0@Hik&=gP_$<-a5_N5{tpSJzL|hTpbWaG3MAuVeu z?2QjUssoHB2>N(riptF%Rj@v5%<==hu&W%B@4GIQv_L-J2=QFmFD6-iyn}&o{h0FL z_1h-lDvywf*=snoSvF&d*L5OL%usc>%6xx!C8=>%ye6V?aJi6uE-2;Lt*k&Hzslcp?&7U6(8A0CPo`@p?7S46j7DdVcP8%dZcXI*Mj&}p9 zj)&2SQ131iIjHVr3ZxK?Ip;J%OLcAC-M2D(tC+r?;;-zVed3e?r+$ifeP>V4kDvGx z*!hBE2akUJ%=6nbyPfQn9%E&ktj@fO(>znsn z0~LsJc1SWEo>qXoVvCjfY)VU!68zFz1OwzN$@_}=;*4mu{Ht&c=K=Fu$-M%eMwU?f zd82b~uAAqtcl}InrN7VhD%v?b1ij#>9I#JyrZf&aA#p9He>6Jpda?F%+l7XfxRgCH zAtR!p;7JLX;}a3GkCf@H?!zXXk{`c&Lk}9$UV%VyY;)0`fcDlmOPPo<^;~ECiqI-> zWj-S?#sPh|(^-E}5q474fz{f1z89AosohaL??U6|(4xuV*uT3$(B?g;Hh7+@` zJ+m!#dvUgA5Z7$F0tUVP$HweyQ99ox6XenNwOz91(V(##x51QFum>V5j^%mv@Zg)7 zS*%72U_i?FIkicfRT)eE2#eUA3;C5r;*)FSesg+Dizq;00DKr3KLZ?H0Lj=d3_^dN z43D?|PAGS6pP4chu2jEo-6WH_hK3NRaJ@zJY=!Xep25Q`o)26NF2opkWWT3Md0{zg ziJtRwnuO(8SL-FebC#&TK}_FfojEQfT6M-ww-avq+_?v$+Hf=GuAZakc6NugZzu@?~);^!!Qr8NA>el1p{^HsSp%HsgI;hqr7# z&(wAo%iON(Hi@#|i*Xr?PYqQTE8rq8&x@EUyYR-D!XTZa zeftIbX9{jCUS@L5k=070i_Kw^eEx(?cv7`d$B^oWHB0@>d$*Bgx?qJ?nyO1tv(U?g z;mOu!zg}TBD)!(F_3oF5B|G_!ug*K(0Zr^qHf8(oz77pySntPv#9=zC^vpDWYo`PC z@dk)nlmKF$dm;dUl?EWV3WH1bgwyWX(r4ic5YV`_Jn`IuyHG}NaNHVWa6DQ#YCA8w z3gE5B)JxrZE@m;{!)(}@8l0CO!W9=jKL5iVq7`BPWD&wNP~~`4)p^I`@Q{KHxyDG_ z55BOSzuK-?_!{hYGxgMQL{abT_(WxP*p`#3*$mNVE~xYN0j@8nm$OY*ViS(e@mCpj z_R!bvZ9~?a>_dy5yW`%RxfkJdU0ER-c5ImGj0c2N^XHq~CY&ibFJpISBX71V40A92 z>JujMg?tp~GZKDOwt^VdzymJbC$ z8jVkFrRR#Q=oI_)b1U?aagmRbuC|baTht)mh=i1vHk~bTday=|dEv06h{*hx`(6f( z_A^!4(19NoZtClgPFUWs&6V5EKd|lXF6x9RDCyPOcjDqIwZu=EreTZ)36z1-;wm{$ z#vdm&=Z`(2C{7i%T!Ec|FE|#3lTd%m?o`O5b!6;e)*>bxyXLY>2UBXs&}!_H_|k6r z`rV&$AZ!693;AJ-7Zr5ckx`M&C$Y&$f-Wex zJ}a7YK3toHv6>>hI;(!{o(&su&On3vyzxK$Wt-NW0n!RuAr~}H(kxWIBzAxqbtaP@ zm2^;qgbnU9uhm>(%MyxD2QZtp0Gv1l-^@`B0HnGf;+`0{N1EL)J$3 zO!pcxUmOXXP66Uqcgl&E| zO~v)&!26z;*=?~-bDC{)c4i|?I=@0GtnTz>V7TU6r}&7>PDM|aLUY^@4v~|is$Dqg z>i+ZJyFA)MgX~K$Keq+DD<)}^q-s=Ob}m?@N$5Rit@XZE74^tTKl)~4^2Wo>Whg(I zNti^_lQ|h4SGh;(BsSQWxaefOxLY)k@QU@^cHZ4n_BrNA3oPA>C`&_q%jq2mMs|H|XRR=ZC@7|vd;QTO#W%Wis8z;x)(jPs3!l2W|q$Gc&gTC@U>Y>0c zKQ$+4nXF57O&=c{+h;8lueW#9O4oe_>Wsa0!Q+q9)N6#oc_T|_q3rZrhMT%Gk}Rq_R(CImK>y;dhC6s7a`@-tj(FP$GC4EjyYvBy+P5=$lX*! z93-Fg@gNlbh#Onm!J-0EUXo`XjX$I1P!!*d zR-nV}JNlP;jseVhl@%3$dIE&3-J{`yqSZk8^{A+*h=>S)YizoW4wp&;sO@=Ab`Sbh zFLQmb&nLrTg!;?v0Y^tiZFKKg0n!2m1%>{V5OVhIG3U>Qh9a>sd9FNEOF;0J)$gRD zg51$g*2VnQ^#Su&P6mO#^XOp1^UYI1@-Qi}q!qyL}kA25C6P5Z+Y?njpOHHi3SPzzFadZz~ zm56Kg^(zWre&t<>=VjMhRUlgfiNx{$HBuq~k^1AgEiW&prs4xEH(2KySoP0=W2@gt zUR)JBUM;!99N%n|pn}X+-nVpLNq*X@gK&US~yp-q+1dh&!mFpYm|HUR&_r5 zu=$iz^X#oh--y|}4toiM^W#Y&MQhzpy$@cuH+{r?TH|%BVlF#bDU9VdT+7eB$FuUT==yWT%0J#Gun&`Ki*hxn9Dsg&3Yu6&igm zYQ@+6n|Xa^MGtt8T1NiV(Y=tnx1sqMzVAv=1yXdo+l{z@%c}edeT7~_Vh!#H8M62? z7FT$`d8kqt?#%4IY-UELK+H~#X~`YC$P1*Q%)Q3l4?#kZfq|hdnkR2^TR%J?B8iw6 z^D%15a*a6#Ia8zS>L<-6wQBB-$B#8SsB2*kds~0EccjWIHhnrGd3cK~E4GwxRb8kGzSTELG zv=VEZwN4T<(QjT6{u=sllfz#JdVW@vc3jAH5i507%#5t#iz<^>CYs*Y&KeMBK0d;pD9V+gP*8~>7=(95?iwo`V?3HuQuOyg&ik7O^_}Ual214ujtH?C9|dzT!cxG6qkdzH&^80mYH| zlC*&vGt)L>o$HVUDr?tMCIs_aVQtZE0r>%n-IqjT<{v#l^iEu>eyHxV zBmO_`Jlx(qvCMDwO0O#`>v7ZhCR>MSxf|+pM|5_6Zz)tabwv!oyR3 z2YU<7rwyV2!2elWVPngz!tp)z<=r_}bor_VKtv>NZ~c3Z)d6;^C=1hb{rSdJ_-ck! z zUuA+^W_~nw9Z`f3?k`q54vS~<{wd*oReEQk+4n+yc{(VZMnsL;WqPdfAqffN4|L3M znnlQJMTFg5^j1e3)!3s(emQd%kqS=N>C~pLs!tK@7sbf_B#1jt*zvY#yPgyRTUNk7 z`{FpoOp`>S$Jel2L*u89%XvOPI;{TjBS8OtdJ02w3NiQuhlBtm^l19~3-y0_c7WO! zD35Lly5~veF;gxJ8pjbQl8}(lq)QWacL2OPJUl1@8AdGqa>kH8Yy2Go2NWoZJ?OuL zr$5Z){U!{Vz&Q++fY9N+xMk9IBL=-G_EVT1okcNP5b$2u&fL-pP2+=`Nn(6UM9uRe zEF#F9M)zb6{i~PZQhy;1LsoB#ll4I+CMJ(&AH?<9{{wLJ3=I*SYxK0f|McnV_GB2< z4Ir5WIGOxJlGSFc`1;7Ou<5tqz|E7ttjoV15vdvXN1XrrXCn6->;L|hG00)#BQV|1 zGC{GK6?#;%!PmgAT4(;}Pp%?aV0J;v<%?d!oWBoz7VNsyf<1f~#snE4gTGgKZ@!BB z@Xe%}(Yw_!rDw<*E^ng)F(CRxv@CxYx6z?dDdQEM&#R$(68T^L%kG_mV*{j3wZClQ zaHRS89Q}P3fCdH`2&)5Wf3GSz?OC?GjnNNhTr$Hr2a5qzEm&KgRnY$##8&NP#Udv= z6k_p};VD~JL`2Qu)-ECz1UeB4`Ap)|99O&R!}gSIeLpl;WJ7Oo7&(bB{~j3M_A;>7 zRjg*eWBg~1Ws1+iZ1?^DduLf6V;)XQlnF=$^lECd@&V;Jw&-BDOeSHJ8IFzgz(M^$=l-(tz6 zrqGaAu1a!)KG^6`J_NGBkJCgvT|X-fEY8wGB+g6a=#mdlO>@Nt8pPN+?nj<{bSlKu zbhSB^%YEOEm)PcnrSn=_+*KLYFeUu~J9w$|%3@^*4*Zj&UZR1U#t(+&FedQ1F1l~U z^nO^qvm~)zy|aOa#z4ox!sY-4GDn;{!i1i|{}PCN{$4U$xdWaM*E>T_T9t)bn|{wU z=*?Wg^BkRF4tK5_JkVZ~7^KGB;7Q%=PRpeQ93B^nqFjHobtN`$CuM(dP~(++v!AnO z$O_Z+xm(fdM+3cpoI`xh3tjt2xcHl|_Mx@bnnE&>ce!aIx9^Fc7F|LPir=oiSU=*2 zUawa=*H%-a_lpMy4sf%Zuq>&um<>Mahx zJ$)KGKoFyjVSwgpBOaN=ez5OxF$jm}3zsdI%ka}2O{~^m5A~&$&RVCnY)`u0HLnaR zDk;`NTGrFowE6{++V;t$UX#zjx+2_bwMn{nizzC!VNyAufuOt7Zq7F)h>Ovvs1(-E z@^IY~xR|Gvj{Ww@9kL~BX^|=YMo;Ui-841wNV-(i3C?}+;R)M()!s@tT-&vj5z^6d zA=Ws&+uZoTYZepgy)Qdfd51)1l`n*bN;S^XoG|5Uskn=T4y_K+^l+}2K(988PlV5G zO@`hD55tDr2c*NO9_FL%`hAWj>8cVWV#0LKE!aG3oNy zcbyb9-nnyw6{gg0e@~e0zc>&Z5PRXNY;|kL4q7bB%JLubIkLs!K{dx9k@zMCoVfp6 z#HUJDV--;71n#A674kl3w_009H3b-^>H3du z9Chcs=d=_9BC$K*PbNS&#nxdWx&pgrca^db;9hei#vLN3^ zCf@30{Dq|#>@$~HF@Z_=V-}y{2cCj%({FD*thZBCNkgY4{_Jj*do3^LaEbcm48+d} zDBBz^$xb8iDXP?2QGRn=r71p3yWO)4&u;FLe)l~5skZtDZd7>eQLc@2`Vp25s?Xr7G^YJ!sqdxMGB9JgiCj_kh z3H#u1GF=cJrvXZFXF=w?`S-~F%k6EYvAC8t9h56&RdPe_{^+a(2C?||5vq$emDikA zlHrhRTdXI6*LM<|iO2~-3-Or9TZVg8UxbvNZ`_%#^wsj2aJnPl zkOT^<%}6KgXXrCM?hqeK>8Ly0v61DDM&Sw{zkjRv{Q=a!T{GuLALP)p*vN~Pv-P=G z_~8ok1{8AwNufV}EW2^%CdDVtoqq;VMDuvskL`9A>Wfw^Z(La4I=Ub`IES#7ehE=x zq}?Ggb7yChYKlCw46bU93(3*-c*^rHIOLmMXEoCuY^M-}&~p2oF?Y)#Kh&k0W!xN1 z$CFwYk0&~rp;Sdg1d_CAg23+Cd^VLVcLb3{Vmk8vnCHKi3-tGii*LvT@097wgTbpZ zSe8OC6yFAq<5jr zXKr24VY*5TZ)VShxoWP9Nwq(+c%IhzINieYg6Ed>WD0~OkGr)fDzrEHA-CnORHtM{~JBT zeO6U9jJ#Wx2j|>gmoR&NLV6}azj-Zv=?P7vnXSIrT%w9LboQ%SB7_`X5Rze+tL`f* zY9fPV#C*7JzNanMCRF0%+;k!ini8Aiyp6gJP^4G}g5d7F(A~G|k83+E4WKT!(SrxE zov@o*JOZpxnxfX_yVa&>uZ=?$Zj&dcn<(2ZL2cRZQrf*MTu-hEt1r6$^exktLVRBl zhCO$0ysRV)|B*~Ptmad`Rx9@5Cwn8Oa~=75h>WP$-b2rYv8#tD9M5?bZ_XhOeEag6 zkr~{vUWa{Y1gxJMM4~vToem0O^RFNt=gWGD>TC)$Y`heZrmM9*Q=3oFD(*Bk4uxE4 zW90en;@MGoer0rnZsId$GmJ4jAUS=XRQY>)uX9&FmO{PuYLjY2>tATS6t+MAQ*Dc| zxb75}Ifo`zI-tXZ%WS$j3h5A5gP5Gf!Zfv~gRk-!92IB0pwx6k@q67E;P134V3^b4#hY{#^Z}3dB>Hrt#{gr_i?4Ydge! zM{H-=f^!ax@%ho+&JIPI&vJ9@1vLGeV*F8SAHVwG8vJ=L{1DlCPHhYTXxqX?~99sd>Y>#8Dvwo)mfk`o%}pjXZ!>vcbeyOpS@&!uX$Sgd0IIN zd%5AJyQ8Hz{+8;q+Hm!`^iYNPirs3(LOPpFR|jr$`Ds|=-E4T8_wnoPf{UAB3(mpU ziC_GQ{)GQuQ2?-C|NjF1{%G$8Q9iU_ss)Yid=()DG)IhYZEcO_;%>GPI>T2YtaK_i z7;}@Fm}6StlAZEd4{V1$RPxr2L)#xe-v3M=r%y-Ku8c(jg$-u3oMT0w^Cv+n_=}Vi z-NJ_lPol|pf$WH4iBXz{08b6iBLp6Gr z6H(wB6$B1A0=8xT=QG3nga3bCK%mw)2Ea-8|9tpxR`CDx z1}an0ZvJ;$zJixQkjtRbmh0_YF~k-exd$g11?XMX55A>(-4iptk#aqNA=Wq{pAIzi zEw2EsI=x#=2SU0^fFJLB~Y^zJ4Nv1@upfV0&5 z<=-9kE#53eZkO)EngL?(MJGX>1C5%WUZM~ndh?J$(IRyq+%~qcDSbn$Z3Bw| z1QNyxf&8+*D~E}87V4`S^{du$*ekTjD zEOn(RJM+3BLv-qmp5Nud>_M$7zE?5-o^QI4MrgL}T>|-?@_~T9{PlU7`EuLFEuh+J+J)`5w6v5$8z^oq zP~6>VA;sOD;_e=-v;~5@TXAZnR-p9ZB>q1|D7%pGv|4~h2&hiTecI{0UKtiVa6{uW&VE}Wcw1WE z{qR8;%DKy=}5X1Jv#tz(=0f#$=19X+*70!gv{ z=Js*%u>MN((xGHq_H&Ox*CdUf#>1Ki|J)swUUL=adfwU!ifibhyN;4!bx3BiZ##? zUhCRJNbIjHTGMzrwlWZ;l zfL^PEcfG8RxJ(8~pwvhD^z#Q_EYx_U)~F}{-2O@HZTuFlP#lgiL=|G+i7m`|1gE#E zRGj-Ot57ql|L_~Lc#!((pH@Ce=zY2W0dY-@-1S(C>*d_Cp9YIOuz^3cx}Ikwu7jx9 zB*Ouh{=4K3i}i!eEeE)EcH`<5caaX#LDoO;A0ZF)qKrL*&nt{|cxaANHEe&O09x7qjEg zlzv-caQ(J_>l~sCk;J|O-(LW+e=dOQ=t-Rh@7%M#v-ZrI5y4v-~ z^#=!J-w>xJDL<)l*&O+y17rFm2@w$_J{rv0Awss~2kGw?NBr6Y`6GgHS&q|brrwl} zYn8cr-hCk(jnTup)0#CGHdxMUkQc>A5nHrv6Cpj|OWut)c4T-#$ylFtA3Z{ew`2Co zS0X0WtLM{Ov5#XKPQ#&>Zst{)^AY!fyl5hCs_8U*`#Qq81 zXTL*-8d^8OA^@CfZ8bU0caWXhxL8vtlDct`LUFZ|ZkTE+u+2X-Kizpe)3sis15=$U z;NMtj9&rxRe|>?hW63cE63vOCrI{!VtJ5{LnWH|M!9UMgA2$K{=R_*cC4*Q_RBRfi z>8v*hT<6cDvyY=WwG!9XYHCw#7H32Xwg>#LoH^KV-G#ek3Q_zgTQ%n;$a}8nDt-o? zm9H_K?zE*Z54q{E)zq{wy>67ZJ18oRvRO|u1zkY#uG^+cQYt1x~O6g6eJV#2$$$NF+r~H*3iTuJ#ZW$h3V{+41 z0y0WZn?we(d3pF*hb^qIYLBm-4R%;Pn`yg*KxO_ma{kM1fp_hrzka<*eKt0$BOC7D za%1tc$%E(GOLybe*v?(}u-w?Y3#Zh}!?@)Ljn5?Cm4jz?Wz7#gjg5m1+@z@7K)zsu zsGPnA$*_)1+5xng#HY$sgg2xsmZl|+- z{#UEWEBR%qvhHbSrlyN~X(|&hf43>8t})&Rt{6<+V3zz}pKnIMvun21+3hO^ZMC~o zIiIcCx3Xmr`&{b2yvX(NoFmuewZQ~~sff0B%G^t%W|wSFe|i`@+s_JqN_ye_DwVH< zPTA8b>-g7uwYcIr87rKTk;7jZfqhFQ!%(o;-LMru%j>as4z(l2;Dn^5#UC>QSZ7kw z==%mhAR&}1LrVX|H@&=3nYYBa)bCocxj9pcudqQkAYW3I3>Vb1^vWP&B5)(SXJM}@ z1wHqPvU~Hw6focP*Ig(X8&Og+o=#wbLGVar{-=edC9vg0sOCwXm?|ssEUs;<5Vj$hzXeq`@*-$slAG<%(lZa_%~su9~il_`5X-^ zA0-AKe_63^V0b6sf_-ef*ZoeyYqu=-Bn&z=IU!&9TB;k zi<>r1aLOD*pU0v3?=8@?*FnBQfhL^7?7wwa31|3D+Pp5#2JVb@3}=bg#;d zZ*1w#<@?<(`LLgSMhi-j4*-kT3?)fw+T&=mh#G!^9QO7P*Nk2;_=wqhrP97e>;q|h z6c6m|H!-MF__%QH?)-|~d_z%kOiF+ez`XOcR^lVe{eSL$HmNyxu^)wiiSX&;s9qaG z)$yW0-7IU5p8C_GzQ$&(bABa0*xMz9*q2kwQJj$Z!?=KWOy4T$jXOAg*qd2#I<{_8 zflL3Xe_UuPswpyQ_h=jgJx)FQbQ>5qs;FZkc90H-NC|O3EL`G65*o0<{n3IF;cjpO zfVxy9mgBWBi`ckBW%iE4PI3%Dyob^uW@DaN18{;JO`~JG6rLL`-i7rfK0V_DOoqn= zfM>Y@LzHbA--UU&B?+9L>Y6Xc;4ESUJnEAih{hYijQ~-o;6X1K0@$ZTqI`wY!wE(T z604~M^6We7uO)kQ*l)%o$nBvvu`Z1(Ff;Pyc-v1*_AX{K#SZI`c#C|utx#*Wmm-oA zlxr{yaQs>CaO^D2MspY6?4GXV{yRQnk{dV*j+YBw)Z8GUMk)gq{B>Z(# zLmiLoB9D)yx9mX(<=-x)&I(-k{ zr1fyGo40Gl&dhxt&@7ZudT;~VL3GXe(BoxMi17?mTO8oSEeTWR#z42Ri$JT3J;mN> zWBn{j8$GheM@8s^!%DrjBDB1C3*+IGg~4o)w29j zr*w8~nNRyNTBxRq8dz`pW1-q)tAA1;C_Cb$&X7hH`1-CBNBh&bBC(ZdKC-b_wyZ@~ zr|TOn=4x|_e;iU$7=m`-Pnt7R;vIvNVTU5zn zg=X+2C6a-_#{7}|sEHMeX#V~CeQs0<47Os-Wr|q6mZotr8LqbQq%0%7uk!|XGJ7BW!LNqt$pc`vp__jHnGwKJU>dtKe;4UfnWSiG@UM& zXTdgxgkQ?8c{iMz2=}Gx;AK^_$t}oSWdHYQ_gW0mDJI6s$tzwfDb*K@PgkDOW_bHN z7;Fy;MQr&<*Zh9hY^<}uTppf4E)&*e5>zdARaC=}MDq%ZcXD{kF)`kUs%4h5ddA#J z?{f6>DI(M-0G*L6aLaNFbI2uhLX3{3rb<=9G{j;(S+)Wus{;qii3;-dw+Y)?ahWg7 zvX}dTZSS*ocmVP|&g|mJMf;2|GhP8uj1^Hc9r@(TyB{dhD{K2d!mJy{`u1FkLz!dL z`2)GWgwfaMUwmSwzvpzXJzfi!-cfi*3fY;uu;fXR+3DoU@F>TRM4wXnO3ZIj+p>?U zE6cdnDJ*TNoZ_`3hLLVAN`VjNQkSP0?0@r|Fd|jc)9M(L${8MJrz4v`CiXl@r{29OH7|&Gto3?T< z3j>yO6`QLOks;IV>$(}vC@-+}(DsR@YUHf@wiH{@?8z&3ROD4nv~icKiA47)+UAD? zqjX1TjcWZ(&iUgRjv<8|nvR15bMx5?xrMh4aAd`L?GArw`^+~? zInWTaTPI}z&i zfi*WL&lDF6=I7Et@&ZOzzNf@yU2>Hg_?#D0V3;2R$+4)wFoYV!zTI3)MM*_8*oMBb z$PLjstP4F2xdF9~SP}3$roGVoHKE~Sa2)w~OVxyZRfofMkU;m9C5Z?{Se*O%h;HfG zz_&M=VP}XhOe4${>kSl}gDT$1HO5@a(>R?=q4iXn0=!@mBtW%!sk>#^8Nt_qLcHI7 z4KF69G>lR4ppWd~#9<=X1+_aQIeQIL$t%aSxVihsY_s$sIFOyKodC#G)FisY zoq8^0E5HIJCDxdCs4}78>x%@xKQ2HvQAzhQZK(T8x3u1$TLGqyMiU1@&IVCn)EvaR zEm0AhkZRdeG?f?Zh1qt91&(E;_?1p0r0gk@^Q5wT9hX64yW;Hv8$ZQS`*JZjD}caY zfV^?Kc~{8lnwWXWMKcGZc(|97itv7RqD{|F}y}AaZwg*4tDJRmgM$MT`xh-#U|_c9Hqv;ufTa50tAc(d~$FU zXWM``64ArG*GAf+C=8-{Z?FIWOdy%))J*TudArA?Cy4IdtF=?9STNOLY*(H}a!biJ z-vEWNBCwlCLfr2 z3M677di)&1!00n``$BbsI)$;9d`V(kgi+)^;CQ+|!t9o3F_j+H{Wp3Z0}n{lBQ13X z2m$gO4dYiwW$n{-loHaw3&$g4YO|Boo{}Z1%;6_cnREbv zctyWhm{eSlVeVW9t3@b{_*o{$+q8q!QwoUD>1rvFL{$0BO=m~id1f(psR@(NZ}fZ6 z@%1A5yH5O`bSdlh!A<-0WsI;zR9BahCC#hG$k>LP!DT5%WB>7Gf&{x6kOF#To;POF zHJudYO{$1H%yrToBnBJT>X{pq-ECIP8AoZbDkZm%zU0AAe3naKl}R}O1SWsnQE7yU z%=yn4Xd5R;_T)YaxIr4ku65b>d1!A8cmJwq_4BHTdc4?)Mt^_M@?40Chf;09d1}9b z*al5QYrgXB%ocOcE%5t{G0V~Yc*>QlH{q#liOKMt$VaoRgH!nls3P`ubMA8+Uc$DfG8+~Q3zcO1!o^DrNp5iw zM+qk}a-VqK5+1xDGzJ3QcSD=V_G!tc)1#ZDjZp&*e8Gp&efG}eM~lx$lp`%Q2BcIB zLow3OCwt8;E9#+>WhcVYXmkC$VWsc^{+>m!oyD;`X)-GIU#G1By7qQj3I`J?5?Aleo+pQ{_C^iqa5Dy<5Kf= zZ1GQ>FCsnO@7yga6zIpz4!rk{qd^Ide*>#L^?u#=`gvVmPmSg$WO26(1q5KvVhCxj zQbJ*-*j2IW;g8~^{n9&dsauoJ`?#A~FHW5o^G8eryGMA$FH9=poearkF)jf&SpFJf z{XeK?4ACQlV0Os1-iGa_O5L{Bd)8Nbc)`k@9y`eifJ(3Mf*<%1w{yUd!Cw3F+2UVi z$7M8}EZy;ClGVh=k4uz08_mUfZnuFoITei=1=N@h$X ztzy~0muK4R4 zdJ#jI{vop>Or72}ASxXrJA%zjcYY83$G^ju+ zxzJQuteR8=P?_j&l3Gn3nI>fljn7g`gG+fSQoUC2St&65)NXBcVw^7bbKusvELS*& z0MD-Tu{d|$sW)!EWu=tskB#qixVU)a*&W>Y1FJ$ZKJga=Q~Ey21oa3Eh^-hm?_l=S zu(uVAGE8g%wb(FlfwTx-v$k|6A~uk8A?whVIP}K0+%Q%}%x-ybfaG!&=L^(ba>3aq zdTJ?t$0H|pg4Nulg&_VxLyCyMyd6?Kzl9@+`~zZtKg6ID_VzcB`Aolfcl{FLDSelo zay#N(=t5O?dJR+Eg7Vz#wv6b)?w^S9NXuD8?Bab)a1xaR5=AWEfWGs;$~OH&Q}3Jf z|9hgVHB4LoXFumbO7jT?$woKW7s34wtOP_j9VP?DgOJL6N z81Kf&lFJp(n6Vu%l#^XE)gerKKm{v4>`G>aK2Uy@z_onJaEB;CM&(*dr{zQ1mc@L{ zGzRL__ssnCw#{esukXhH19TRKiKE&r(5B?1kV20|vYX&Hn}G{UPsy0|*AYMAm%Lho7KGhk4qhU(08->ZTJdos#P@bWyNy4_E_DZ%i($+>cz8u%V#BKWVyU@v}# zgzQW1X^oH>Hw0le+h3e;J^EcQtvsIu-nl-G_W>9wwB61_Ss;MiJ?aF?3=jLF+&S)4 zLwC#2xMUFqtfT{XSqFSv6$Di!sh4@H2{ z=%-GTO%vk#wm(3I0<65;`y^%3euB?riB(nnhH}gr8p(!!8BVW7LuM*Re17qX_YkQd z0k#fZc&&0f%sz~z!dy7yY4A^4R-Q@sP?-1?3)zKb!MQaTlr(sLt?&%dtVb@rWScRf zz4Y)7$6X0HnmSO=h2>cC8pmMy%hR$J+lBJX|ymjY)eXd;UL_r*nSIv$A z*wU>p7WK=hH{5rw$6|J1B_wp2$!$-~?``v>jkA=i-`!3+1X9Iwv8qKRf>wp75^$=l z8-UewueZKeb_j4#=4mtJ(yS{m-=U6Aq3cC4k`eGu8}+KnI|!&ag7Tt zyGS=$)caHlA81fi@C8^ zoVfg?w(CR(K_W~T>NLP$wH{NWu>+)V{Jl?|D8uP(Kj((KHCQMyU3Exhh6U=YwMcPz zGg(O2s?`wS?q9U71iq}`HHdxJ>@eRA-aGEce%_aFO5Cgtm|K1~VVxl|;GHX%x0eHM z%6S!WWS^zAdh~tjJuoXZWo~oqizpS&uNS~C-Mgu*U34y zAVX5E)W?Qz3F8Nc8Is1k!Bn>ajP13Ml^|t7J;jKq=o5H{%<(kE>s*@3NfM zQ1=cxA||9ouL4t!fYnAa9II(!BMd#Q$4B-kIjJYEI(sgB*(L!ecxiXYD5A6bfi|e$ z&}(;Ijg+2$oq(YU4Y9>+9kv3y2-$VN3Dt^k+D_u<=OmG)J(H#cC!|pJuaRCMU!t#E z`H|3Qm#0<4B<1?ej+k^`>qgmju1!~JeN#-falO=aF3^fKcb8I*;Hef4Zbp~Zp|_Eg zdW_*_yj9az{qdtix|~w3w#Gul(G*qB710{*?{@xR9FbFYRf-oc-s~M-Dc|8iq3E06 z7P_LR$=t10BbCkSF|bQ{K~bGu0WL}*I!oS?#~rFx^YED*DafzS)txhmYpz$pqq6jd-bw-6(O{&XQu5rr2R4 z)db?SXEDfx8JKP4;x*Pu?-7yXqH}iw=%-@jVg&f0jP=6h<~>TWxskzGxO;D5l2d9L3p1K5}CAUh}&=X3du+JNt93sD0735&_SC*RFZ*bT6P-8QkUrR0?hh4@&?DPaXf2^`D_5AVV3}|wjayB z_8(p|%^!U2Lec-|J{HaGf>?lr`NNL|f24dR6-s_kz0*gcoLUTEv~;e@lu51eLeEKG z+b==@U@g-pfSlc#hX+^QinB`y@g`AdZJw7OdbyyCYC0K=MY>P%nx%*}!lFuJdq(-? z3GLLL1j>F}?kXj*evCBXv=nX}XC4w*ksy^Cuh&J?*4Z7ROZL0;lQh44o`=0C?9W+l zAs86MDIRY6=oS^B$>0E+eS?L?LOMM&;tgzutKR0v?0m$@Pt0j#eVzDhXAWQU*^`{g z(PjJH!e^0DMLj9&?z}@a0oYqUZ|4M+&OhW+I|Lf-FXZrv0<#FWCeG%syf_(Qy496x z<7`1!ePX6Gdprz7sy>TWk)d$4AWZ%-d&OB!c$vnjmAQAjmkj*4m36z{i1 z;2TE+xjEqg)F>3~GNNi!cF}CiEn4E0kFI~<>-zzO5|PyLi47l|r|dpw(6C@hh@AQ9 zO`>e}5xlpPA~Pa$Rc5DEeS^oibircc>;;;%e>-ZT6VIzu%F`@u?Scg=Hb6vP^Wq`l zkA>TeHyCS`36`hpy!m4~rv4;Z8Z4r0frQ!Xie?$gS2pi5JE`7P)$x^<41aVNw2w1( z<0njwmm+bY_}WI^TVmZeOe8lV{gx$^DhZL>mC0towLQ1XdkcSz_`ev5T(AngLZ5+o zjE0rAiXI;ucMR^Va2s?5l(|ktexeDW*L79G$Y*u3chGs}y=`h%?Vew6KIGSx2meJv<|!x>ZiE*VhGXbLTL!(#~LNQf)9n3B%xE8g=QDKEE~ybyfNzM9%NL2e5o#m`U16~D9pc`Ma$bK`0imaqKGpQuKJ zUjR#H{+YDSSa!$R5zBb>ETCc-5|IjiM?>O>8X-m~to{2M$k7IKwo*jwidqQ?Eb;G1 zN4poE{6Q4@8~K)k=2%B4cQf;=_Agb>Bw+_V=|8nIhsDSz3AHf>F8FOk`VNf>7#bFv1?u>TsytFW~bJ6W>q~LN#uNztHEnHoZ0-cBRkVLmw%oy+*1&PeU;c^ zgs?$8jTkRg-Fnqy*xQ+iKm2dSat^YVhP*DD)(i_)z z^e$H^FXPP&!;BYp?7VrBH9o~EYK&QO(KEoN!uL+%4ZKNzS+U|>^bgqD@+GhKf2FKm zZsci?@bN)<3y-rd>|(;<@fJ4)v&g2w((j5`lV{j~e~y4> zqc4)>N0r>gku3Y{>v6@eHBgW+Y?_{Px26d}M_x)BTJ~7=!iAF@%NHXG-ooR@Zfa;x zk`WVn6<5Inqj{7jkJ5M4>t+O9zX8Th;x$4(?bM*Gv@OBK;|MiG*Rr$`4K#4a$sfkO zFbSpKLK$fMI;<+>leN7o1M1=2Ge-;xEI)in@Ve9m>-GevJP7OezV^-!&%N8ZD?#{j zUDw$@_`Ct&+oRmS2E{>-TK&2P^MF!Ut?7sAEKCSu&@+8JeKDD`%~Gf7 zQ^`M$9bngqZ{*<8BB-McO_{tD$?O^W4H##kI;BqWXrga&d!7cYp zo!Sl`B)R8dPYr0%Rr9uTes)3OB=SZ+0L)b+{!}>{9D4~u>e8-pcc)L7YmX9r@{E}5 zZD=RL-4izRcEIi(GYVog#xW*+TC3~*x@YrltOpXu`uUFA`y#^132uPEYmQs(vVzyJR$yZ*QM zVYFi+J)-tYfJaluXL@S>J)%ptk_p}ylc0*BF#kr@ErhpKrv8uS_rNJU`QXRGi9zGT z?Y9KCW1lxh#A*-;|(W7xMg(3aR_t1YD{RG0qPfh)qpD;FA|1^6Jxz_?Ws8BH_N!Gj_9b;dp){ z&`>w^BW0sDXyA(X-nl7t)$|tFcJH#559V7aQ(C{Vb;9F6OqkKLva((#s5#6iA3K`; z41*kLPF(!B+VVqgb|~6rxAffQZr0N*yplM4)hyHO<2@eNyzj8fdDK{LQ}1~416DPc zf%~!92Pa9oW@y@DtIi3Dg$ zq@Ag=c7^nJtLDgq5U4;_eb?q&WS2vWfZ=pEZ+B(YtEyu(v__-V9jB_vC~{DJwVo!T zy9PS?GE;)@mb&4RxLfKU>6USk2M4-a{EZMmO}ff0K`kOHh{5kf&uo|R^mr>Ld#%6- zFI!9zM2{a2R9LHRgw1XNtS?3}t_ZRwd~a}iPU)cqXUi7GYsoKXr54Q)9< zu6W?d!AcuKv-LD9?TE*KFWf?Yb7&-DYTOZR4CT_7=A$Sx)fn}ld?4_e)sMfo+vW_wO za$iTsb{IbvIwhsSMo};ri~)1e&_UU0C=T6VSI?4SA+Bc{=EahM0+He6iOVK@D_|Bo zXwdDZbJ9wD9tQxCB_Ey8gX>V%bu4X1T=eg*{_t+)z`K3J=ce_Rl=T1OJq6`%y?Rm7 zN$pZFuXia7{?)XjQ>Q48y+-Lb85;O;o7-X=={{u) znhhz_3^}2_&XQwO_hoeSEHvs>jjbfJeu9&!%Nqcrvjqo-wes-8<*oraF1G^4JM z3UhUf#UsUoo0-@UyT0^{?T&?eLnd7A_r-y0sSbnk{*GBQP0K;0;5>nbeOz@O_g`<6GN$k-o!^2Px7Dr?OR<>>Tv_4 zI1}AN&*0CZn*h&)UvlTHBy46`Z~_2E!k$FVu!%3zMlkO-u{tGtibcUWZajET56IjT zmnqc_#Id#G&iLNS*(8(H0hsmQ+ij3-fA{qXx#QtIzLoMOP730hI`p!Wm~iju8FzXz zonwm-DSi%~{>J^VmG+1aa6K{$X8ww^$LC8_zniP25so&7X#X4dHAQvRT4+md1lXY6 z2LWQTt!f7o@FK45v(8O^t3HG4u{*s3p~TqWsN^)0*uF{J2uC)A8A7`@K~DO0&*M-o zsJx9I7?OA=!=0?u`naW$CoT5O;n@^oWED8qTMGmB2Tq0_8XlBA>gc)s5*!P3|AVfrpUkk#-g{W zOYF{?GzYYtjZrs=SABGm@Ly|RxDiL@Sv0HX-ywh<4KG4$0*yRy4PvWdzX9ZoIes4- zh-g?cv+CHH9Q0blT&F&TVBqVJf>+M9_9MWEfckW#=GyGTR4Rm0^*cJ9%<&^>_mz%u zXdr+HpSsM8cr?kGRgS`bdGivkCDGwKd8)qrK~61+EwaZsT)NIbqtS!?gA{F_`OikB zJ-xP>gxCa1ax^4Fq>9l=lSKD2yt2!XJA8-4yBIJxFb9Ha%uJwVW6JI3(x9`E9BCuK zQSOFvwH7oq)d!Pi!2b(o%t$8Fj-6_LIOrFtT^8&Yawvl?+SjfEmSM$SZc+P+l1b204kNq3-Wz;fDo25LVDlDS7k zGIuSJHZB%$`2NT8Qstn@Esr@i`pX|LqmL9ToL}3_$Bd*rW2M5r*BaKey^ZBmXYyTOi;KhvO#pd{6A=pQFbto8*&G=~oi<{~l! zh=99=xZ2B7HNqI#o`W4tWGh4Vs++?7`=nI`4Yaq7*g=f1+%?#h!!+`)q%aU4ij`O& z`Y5WG*=kWq0g5!Ges6GbBT8^YHA=cG+;VnR3wg8N^$8@L0CzRIEH^?Z9E`-spFfgM zb)<`_$50#{w-;vaW+fFaRIob@6jqRQQ&e1GF-sd8H=?bHN*ypB`Qw5;Xeb`X&XGk^ z)5XP45;x>zL07uBt|ITPud{!*zT_ayPNV%wK^kr(C{n8s7h*c~jXhn(eY-FAKXaV& zF#v0)yB-|c9!GY-i)`~OVUDryqR{ER(yR7~5y^owgrQPiAnNkl8jCA@{>K?(9U9z4)TUP^_b#G9%WQvr-v)l*F8C+dpR12>;ByviO) z$hHS9v({!7tFIEA?`2FHvf+n>LTPl%uq|P}B5A6pr5;F7^~9vkbq@Ch-nLHR#;^3x zVr=qvrj%%8FM*|MM4!G6#0@HPq?Bx4V!-&1m)Ta0ux>v81I)U912f1+v_~xx-!~mK zpRg*y(;R@v&Mhys%&oK#{j$EH65I+Tf0i4PF*JJNP-{bR^Gf!q%I=_Ur1-*H2&G6r?Xm^&xk9c7jWY9m*EyiFMo1@1Pa$-TOyUmA9rXZla46JM1j$+wIlXCMUpB#1UKVz6>peCKqo{E?l~D{ zADlcf98yF4C@6$S(t8uW!~4F&`DYG*-@Re=JjDgiSwnFFdwW}gqzjtS-V${#1|hBp z!<>7#v>1b!5rzYsdKRW;6{4wy%0s`qvn6Q4zQ@FZWN`5V-ub>vpDn2RBv^zU9&@m& zMCHi*I`ycI(xZdq1#%8wbqP+BmZI{Dq*!vXmdgTa_`0yC|L#12)Rr?E2}f_pm)3Xz zP7d34Rqo7iN5k`BJr{k7SIN))bA^_|{Dnxuf*UtqdVeprIXvGkk?scAMV|f`nRS)z zwOSS#&t7Oue3;7g&yY!t^6QZ4n+%mbr?94FCsT2;n;yji-Y=6Wo}0_~icrcT3O0 zgy}=vjYb{bO1obQvvy=(Y*HgOcMU|`i35oB$M}RVwMN|`%(i-li=Lvp{hr9#M^pXn z_`0Z;I+1T~wu}5`CA~P78`ArFt|P*#>=O_>tu=k*{;*|>?#%TRDt{ITbtMv-QPW*ZUuB&rh*Ol41geI&KV&(kX5mp zs0Lku&xtErg}$K>)Y>%Bi}W8et7kz7oAn((1v^{Gtu#vlWv?Z>>flQUcEWruYQECk zQc4;VS$*FA8--4rGw@_n+#d?Kiqzl-x-3CiVT3!>UsEP(mJ78?b@lm;D5plA0^-gZYY(>2iQOe`^Qw|ZyR8iz|mPdwRZZGj1veqgG-u~n5y4*Tqi zT%9!OEXPps$oD|0SfkKkU8P{?U`U-{a4FvRf7xS!1*I>XAo>nawaZ&xf#yVR(hN(E zN)_(UB((jxkN<8*W!C=#>nnH#z$*%6aNAvBp3oCGOQvBUCvAIgnA_tGDmsp_-JEUx z*_cBFBjF?5yctcWuuQQEq*I`Xd8YfU%c*VyD_00eJ{f90>|6ee+QMWsheP2~g2`5t zfGg42TjKI-y+p!)?}LT(KW$H#gQ59VzlBxisMU_=gX?%Jmr&a_lRtUR7&XAm3*qBr zeX=Ny>?}t@Huf(Sb#R^bXWlDmN}`2WIGfTpN8r^KQ?4-uU2>N9LfajOVP;iu#ON{C z|HOL0X?E|rbD!79Jf&>rOoCK2zce#Fz_xyf12ilJ>{PF^?z*xb_58sJG9Q`re%H~Xy6Jrd!!g-%s8~t>^^~6flq+4%B zJl|reJRtZiKve)SaD>+_ydq2-xk&7T?}D%7EPnJE&l_cVPhrBtBohVjakXN{!7YC}gZj$_0h=`m!5;TRM`9WK^|q)T zEj)b(bK?q9hv;+1Rv8t8s4>rOzig64amC-UViLkoPac|u!>DWtId8zVE7;KJs_86C z0PxxiC{9-#8u_w838A7rc1tV1%T&ve`}vW-X6_NI7^E-G z{yueWc9NYf0cO^#HRs(=XjBJCS&!dUNYA}x3Pow?pH65ko-JPb8vHHw{h=CMwk0vr z5c;V|zejVUKREvMYv8qR@Cl5<+);*MTM+HsdYF-S0mrJYuORd)m3+z)T zvssu0i{d1R`1VYf6|V4B7W%O6yzqY^jDi14VXW`v(%*WPeXUT(U`N61PuzPH3+l)G zp<*ZV@}^(6a6NnGBC5ax5@L3*7bw*8MU|=>`G8R%L&q^t&}T~F`w8Ok@ZSRcU+w7n zhu+Qq%T)ei-mcSz^7w(Y#HmL6d-{Q6Mp_=^^+@%yJQw@U#? zi2VMCw#QEytPiw#^lAt!2hRM{#@kegJjVBtG#lDPcqhfaiIYhs-Y$tDhXUpB_4L1? zps4+9d(O`k4kL-nx|mvzoZde3C=)ccZ)$|ycrEPcz}y%9Qq4ABum8!0+`rN9it#r0 zKM{{f_Cv`gil`}<8}7UQuZ1#|z1P!HXWVz_jYlD~AErKK9fx!qf@_2MF@|$x_0=xZp!p8q zBSF~Drw7ol!uJ#I5s%iA2th543)@=Mhj$A4ZyGTs_k>zo0I*c)I+q5-ym+leH;KQG z{OkKK>i*x_TWiY@}v(CmN`)~fp~V0pN;LP#g(Jw@TU8UV6@C8 zt+xt_Q*slq+izh!lIl~wAR*``$am3w=%ZR>TsdVZC`W>~|1e>nUGt8mJ) zM!bj71Fuy3T_e+S97x(7)Z^7BBFHn}0JZe8qA2z*SB6qE9C!T;pS75?;DGHorJ^v* z7F%zRtV1gIcw5@%8-Dg9YeFm=?%7C!SW4S{@tW> zh)%iOZd7TU4&$&;ewF{yBAy9Mpwg|h8lGo!q@qIhVAAYQd-&|lX>6RFld~bh;I|px z<2_Do56pVkf@|L_z~SP*>X6wcE5ct|Fa-4+G%y$nsm#^577V_|7;Wbg-r2cXxn;StFbQJH|P z(%BMPlw=ooW@c0}4d^#fMvu5Cznfcwj0BAx?u*g>ouflZ2b7==xJs+HLjQd736aAS zZ$@?}4i@`JK3_s66 zUyT{+UpG3~!3hCJ<|h^2%d$gG^RP(QjPc9)l_zP!bq7XLGlH*OITs_UChr)idPGRG zsr|9rN0GOpMUA5azZG6(V>b|sZ@5jEh5gdcuh6?gfv%pu_NIGvZQ4(3aco1C*;i*( z%JpDU=y%p;abb7jb1PuwBVtvUke7;z=&15(oF}RmnWvLI=py7zB(z?(HbTao=)v8$ z4D?46jhb(^?V%?3a?){e5+#OTuIhN-j#`31FDB)=ckdQS=R9UWJf{{SjkTj!+8SZ& zRo>`|(6cI6=KcaaxzQ;!9>mHCzyb8 z%n>ZjXN=!EdsqM~4cdzNA;vb@8-~r!hrs2FF8ic)(yr8lJVd6H3f4Ni~@6 z@w{~g1Kje^Muh^MRiEJ|4W#PmsW~NTpI*slr@uIHDwLj`@@NjW7Lg#(243+sSRnuu zWjDv6reK0GXBPx$7$eTrjDf@c#eVtiBkDK^Ygs>Aj_OpnXEY5f+r8%XCK;mOf>z~9 zzMcLU0C89s2X-Cne%UKPZ=5Pm3Bv@o z7~Bw~An2drMw+qO?xA1+;WfCVrYFs?wmE=oZfeSSg@A{T7etg~&b%?g)!c|8@A%Wi zrhY+(E>S(FP!{BHjBI>qoBJ5%!Dh+3++>&$HGG_RpU;;*9X!_6`638-L1-{da=df} z1ePZaS*B9ks9aN(1~+FieZh$p>ACi~wa2U;b{IYu6j7$QVyuHS#R_us94>8cT5w2{ zX@vA^Llwfjmp$Dww;GxZZ2GG3Q5H;XzlN*?Yc5w!h6K7}jc255(wzR76~(KrQT%?@ zWO$T#v-?xzu|+m4KjMNwefuyZ1+!1`CrnDJQE=N`Sy2;Jag4lH(^!MWF>_f@x0WoT zr!(!Ku3m#ySpcgphIIX)Wp7e#b#d~ic5qCY*hFZxCrr(D5fVs{-tu0y|Wgk~C;pfLhL( z*}magEV=8zDun3d$I}4tunVSns<{8^wxa2m7T}PfL{Xm;xS8Y?>&pY!G=!>J`K~ zLdaO@-N+PDZNUrAa>Z>^oDb<^Y0@;@#0>GmFKKX=jMUq;a9YtjJpLq5nNv%-cw_qn z-a&Fpc%;SIq z$z8V_V(S>vYh8-iz$_uSAOidD)At;;Gg(DomN6@^Zg&AlXj4dyWwU124u8_^y3;MF zvBiDKq8;O{@==jBfzOPSLCxYa(1Ia}l6_{AzdpIcMS_&Q-c>Tq_7~{{8IAZpD>|vU zQ|^1Xd)+9oOyzQZM2bQelc})kRnGQF9skn=XG%ghAt3O=byFm<-p_+ltuR}oFCQPE z+aRjekhn+s;Gpr%{O`h!hKAvZcA`Kuy+l>#BHfE*^j2gOo1dxb>cw^3c?Zhf6;I6{ z1llugIP=RaGy&H=Yi$7wDNx2Hc7wOuLyM> z6jiWR4Lh6|CDu}}fB{1fVVh-Ycf}XV`AfRJ*0m=WhN~hpWK6Z)8A3wrNH|U8Oa4nF1Lhol| zv70wDqIj)Ph7!zjJ=EHHg(gFa35e*{M0_U56yKhkgD9F zu7nz|P~8NwI8WIuK0JHMx8K&=s~NGGs9A>aVt*uibh-Eu}P2 z+*;Bi#oeJT!QEYoyE_5eQXqJ74+RPoclRPG8Z5Y52<{T>o_^)M_s9DOylZ8_I*>DG z&dlt+XZC*fv*Xi$hwh#^1H!6prxD3fn9QUcP^Xd0pqu{0g*(7m$UcL@F#ApfW9|h)GllM`)V8{sRQjN#? zd4m?bnI2lL(16mml7-C`>msIUMF-OI^l5TvqD@cD`5L<8M&XCj!UsR*x~=j(o7P=f zisQrHN(l?CjrORaXz~|K-m$RxYXg&%v^tBlWG21LcK&kwTTl$4Z?dGG<(Fssnwd1J z7*%3Y32*D6s+B7YTbi*xmf-5^fvY-W8a4j4d(mU`br>q~D2A9#sDMpMRuBtt+1i)6 zWSE1xD2^TXHz^Up_PP0p9YLKGT}!K|7dcc})$wB;y$>tO7gQhI5yUzAFOOFB>ZnMt zc-Sp(-M;CH*iKZ>>*47w{Xd(1X$L(3aS}I(g*6t}u({?%v)I>8*aM_Cafaf69$eZk z&3trZ;ryp>&59w9Fitmxy(Vu?qL>S>Ns71=o~E7{bPT;qcd`!I*XYV`LTyYcr>c{M z6oEifitmK-#9QIg3I4}DzdI+S^;RzrEpyN?c;!=|X@8zrmh@gt|I}nG3;yK{tsCfo zWr5)fyk8MYw4fy^LhgsKpRvHZnLn;wQ>99-C{N{FT4NI2IC`!DMg3OzvU?U|leq`n zQ}%x9B80Vfpy2JThugY2R|g(!OeM+sYBVp+mbvC!o*w)Crz+KB%>z_I&a&y+Hz^(H z?v~|+CQ6rpvv&C8jyoCrzg`ffJW)0m{$;FDy9Yg?z)rZBj0^C zK7ph8tgX?93z=~?lUCVs+Y)^By^IsNSNA~Cj`r4@=7+zL;6X9aLfNRff#SjwU~;N% z+BT-T@rHmPLg-~2-_ctCm~Xu3(vg}-#W$A+w}Mn|ii1t|ifQh6(&Hz2jKfH%6 zQanK(V&6I1&wgX|9w?1e!pM13=ddf<+qNfiraX*gimfAkdK*osh`dY{c@bhcw8PH^ zy8864vOA4eF8ZF;zWu=6SYOxI5FbPZxS!Ba5kBr-J;h9pNHL!nS?*_t172 ztOeji+qk@wUg@fht2KD1!V=l&*Yx7z_X>2;iE^=;uIEog+7`1Ww(rkT0n;7JU;jCl z>^q#=ykCR?amL-S6Uk_XTWRfW<8byCNsU3pZ@a~stg*6C(M=JiLn33M4+6{S|A-do zENh!%TJN5HQZ8dNZesi8DVioPGjC9h}g*TB+bl9i z=>E(8@pm*A&4SPV->jzhd29>+8RdWdO8@;o7WeP9>(l>H1%EI9@7eJ0)t&#n`OcmH z9kBmhB>yWI|9{G0Uon#wJ*3J|C@0*t6_e5wIoi=S$(}iuUL5Ab zToh19C%zCf$0CiD7+Tq=-sMj2AD`#_{Vp0i_kBt$y*%f?SO8OwofD>_9rq>oXISR8 z)~Rdh#wpWjlSW4yIzQ%1dHrx-M^t^l!&lxR0q|3!Pup&d1J*pr0~%ILDZC9|$5vlg z_Lx@ahl@ll-)(cZ=I7yo6$Uj`y)J)Zw-i1F^ujQ;XV+c%&P_g`CnIu1+*0IeV=vD8 zW9L|8WXJZ!CjxK9Rkh_!!qHW3cD1q(_M@`r^pmcTs6QQZERWk18bmStoTN9x#U0}na|dDA%65A3@#^5{ ziBls8@$3R^%BRES+3Rs4!BJ=(ejumH>!1wrndE1MQk*~Tk!VdzyJ9KXb?3iXG6-jh zV0+HW)X&={`jrT0t{*?z(fV|FRF5_`iLYr!{N6c2nnmsbt74$XwYAG<%D9I5q!Cz> z5Rje=H|G%bx=3gK>~6twF73FkVgA^kld^^AnZc8{jEbsGF?%}n$EudSjJrnCcNXhM z$H%riOpm)~QFzcnP4UZA&I43Kp!clmLhwf%&M((?*WcRtx-&@9Zy8=<-Q_;*TE!z_r>e)EEbgx} zE+%AXH<2QHo_g14pVtjszxkTl9R2TKWwQlMJ^G9Wx8frL3HDjzCSdLd8(Flm`RVfq zRBvK#;b$s$u5g?*7?DT%SpTm>bUk!UU!wAe_i~Ig>cu6dJNEzNmv7VvhnVm#C%wM? z^~@q22J2_0ta`EY3Ei~sv`GENS2VeO)D7PF@A1KTc7$7IR}~zcEDK+`^eOfk$Q3r< zV!S^%!76u?G)q$aa)En7@KkpoqX5UEh&Hyz)LlX3*TuU+QS0$jg(@d5e<7DyTaKN^ z7sD_q9G?N;8&wuY+h>Qe5&dEd`Ed~n@bZ}=^CL!ZbZB;|H{hp@L@-Ph0bi^{(eek+ zCqEOlyi%Rg)nu*PZocdX9$sik?R{x|TrN@QB4!Re?_`di`ApK$NU>w!O>eNT2Jk15 z8?!mERmDM|BFi(%P3D&Qo%p-xELlx|%7Qlu4#``4w^<|+(<&^I~Eq3xxi%J`~B&qw_XKpmAHm9kIRsPI8f*vg(2%D?Bh~ zA{1fPJdxZFG#~1)ooZP#Tx05=fz!gTX1%LIeEm9KgT=P&;wIEV#W@x91P=%a`TZL%Eg(GagT4floEP~Nkb zI2Q%J8^&uZFI8fLf#F7=Dn<;0eM)KpWc$Ko%G)ltWSC9Amc%Xyu5 zhg~qq^0VE)O8al84xNxWh0(#3Iq6et^^4?)ozm$db5-`x2Fa57qOki5aVwt_u%A}z zOu18w5v`LO3DX^aR%Z|=ET%QM6laf!cWoe;LP=nOSuF-k`%WpnDXKci%|PI`DjKQ- z(T<*?e%qHUrL_J@O+U^;g>#pY&BCPiOVeq`#0tW*L0gye4kpb$a=F5%i*qTgIy01H zAuT4H$#M$K#(Rp>XGy@kU!2r;=Pgc$UZp;=2sPN`PA+Q6;HHuBwO-(BsMaL3es_g| zp*Pwj@`PPyHB||x>H#C*YRM5#r-O5Os$uJVboRj9pYc=|SaBS>cBRw7^Unsa4I1-m zJ+AJ3PVaaUc_s$bvcD%e9grN&co5NC(Q}zq+h4>JVv=gAq}w#%$}Qs2vl3_9b;o&( z`0BMbVKS~M&H!iH`Ui)t*HJgJGbG2yVtIZ1MwKalhqM?N(uK#I!=Yz(mZILk5MWLo z#>1*MV0BhCHPThA>;xdI{EUE>?EBvMX1>*4rzK|D3*i?Am1omM>%v&j0FYwd^y#BP zX+=rZB~Cl%;JhyoKC$&dVJ_(Pit?++e$%zA#0=Q-q@JBj&zZRRa|yg6e<#f-*?kzQ zE6spwUZ5KV)|pM~EfUFy@N-%^_e(|D0xy0#Az|*vNW|VK#Ch1z?2!RPU#3r~&wR%_mk4jv&@$f;aH{_|5EORsiK4Qqw)|B(o#`FERkxzVM##q^|@0t+xT<*x&1wz;Gj~)08 zHdvXN>T>;)9oc9U{<+f8IUcO*1UW5l>@yn`TQGsv#_FXosQ|GO-1-vi}sf<7A}1qJm|FCbw<#ri|{8O%6JspU|X z1a82<3MkKnd3+cw9Ug^ge5QU~{AJ+6M&}do(3`E1jk_AU%GY0V^z1SEA)sjS7vCa? z&TiE78MhdZ&^gN!L7g=S2_&Kbo~1rP%iGW#(&_mrdkRKLqL0-z zJRaWm>T*(AJxQT*<%{H_prbQJ@@(M;wi1kX(`qs$FhJ+R7yWB1Er!PBtHupq@ zUMMW$6d*aGrhVrx>Rw+}n9yj+u+AqEsa{e=^0?uCSZibgnNPOD_zHoHrk5BbU(tvH z#2R(ez~%QDCUsMH=n*0QTgP945RcH%jLff)t>EeQ79-F{9rLCky3mjLflMlki3RaY zaC8WaGWFe_LsSVriF(k%(^^UKNLVZ)HlBRqaCb;*nKN+(CbkPCMG+~BEIU#-(eJUA z5I?PV&<}?(?OwFX%92N3={`nxa@VfFiq6Ew!44F2)4xKGn`&DdMiboK#?k55l~t3Y zLmTYD*%=dpa92;0*wmAmoHNRR_SZwd~%%LHHqu-wga3yHJS(Sr61Gcr&6|4 z%TodjvikE%UeqnTuQ_QH_7g|v#yJY*mnUgS)z-HfNK#Wqj_hu0UtfPv?Ej6Uzea6( z*ce8B7xBJkNT|b#;#i0LaD%W){{t&=Dxb1~(gQ0c7V17&qNHr_;E5q39{e2fsbY1-kIG7hKjpy=cIKj-cgPWDCdJTlO3(UDHMYl zPt__Z97<=%34@t@RqB<1eXGpuUnma&L(8A{iDR7QZ?&6g#NJvR{Q1TEF^nOnUC!;u z>D!lqsXv=0nMX8*7+WGlXZlJ1S4~szn$~D%sXZ2TIn;$iVbtSClNXI8=7Tg5ZUTNSLNL|X*1{J`*n@dEptOP$EGIy2K+pm?fe2I6i!mu zM~B|K1?R2Emw@UsHcFK6fAa9yH?zS<4T0)@Jv_A796fu*AOYE4we`gzQj~UkoY1TO z=~q7xh^*!EE*taIUrUGe>;>g2a?%*n+Tc50x|6n&c!tHqy90-%* z<7qj!VE8T6*I9yLkCfiSXp>LjYQ=WO>D0_U0{mB zKp+=ZHMoL)G9Mt7BItPLtgY**F2lqGKlu&GIK4?$XGmwC!vJkBBeF9WDIE@+K&VQ! z)V+0c)Qc3PP0H2fqr9NtZ z8IzyW3NS->F0=zm^4vea$l|`b@*n2SQMGNOAI3}lBZR)@Fn*Cjt#hPRS61Gu%y?(C zF0!-bq>qTkxK}fWh+Saehr{`k(%N9@Ji2wTtZXX_Vd3=9y6N%7qjo2`>B%Vgnz80_ zwunobdzgOYa7JhsaxV4c^aZHALzU1*+t6EauPx@RwOlUW+NI~B?E@V43)vd|RaiHf zPYUveQnizXf8WmP;zTmcduy!!7WK1I_Yd<;#;-ic7YBkaZVUWMhn{d4AG?wWgTpUM z+=yivlV>d)EQI6K;&~@aIZFH->_b{xve?{{y4395N(Ps74q+qS@y9-_8d<>=mtdhpC=-vSFeev2>XV}mI zG$48|vwqTt1~k0rxrV79M3d`09SmHjYYJBv&*j6+=Y&gA#Uoxv`H`YL-26OiDlW)u z^z*XX&6h#@Q&d!gcy<5%7$MAls4D#A?M6y-!lWRANZM!7mkDbVws_m6uJt>ua5!V+MbzI{|mO4_Y5mv}? zpDm6kLDE0;75!eYOkZg!(@WjpQogHrjBJO;+_9xyDH&%=c25QZ zkvsNFr%!ZP%ln)y`{D#-+4Z7($g#*OaX#p~rBT_`n{e`(L}KIt1R@;MiBr-S*5!A} zlz3jl*E$#}pLnUlE@q@2{PXuHL`w8Mn^)H1SGsecFZa33OW?@k9|PB!YclKQUwD;aYd z)1Pr^SoJd)mXNcqef(k)y0vXd-)yzUC8HQdSA7vWJ|>**;em=23w8QzQq)@0w$*z6 zFcP*hw=glwSo4zJ{b%UKBcSG9X20fBFpcbW`||J@NCI+&IpiUn(54=l@WQGoh*aCiz<7B`z6rtV&Yv; zL6LwsUhAYg&@VL7CPvk`9pOF#b_r;5GBc$CWEf`3v%nm){Ka`CD+kTJU}W@1mEKl$ zXw(L-6;PDz${%-bARbiadxRTt)Zs@%qY+I_v=?jd`sL$p-m?4%u0v*tN&(}|sx9iS zS@s+yYR5o8(#sSq&8C4bCfPl%+FP?uPPY5-5o67)^@wGacc)v6=Rv(^i+}}FMp#sw z2zwGyf`q@Ce=KAp?LA~n)hT6i2pW+2U}gSWKM1sUozDXxB3KE-lpFNQ(w#iAp^f=F z8$E);3uRt<%y|d6IzvXjJmcd~u`sj20UzKz&{<1lgGe^SELB>!v`;z~P2p0f2SdOC z1GLhO<-Xc`Y~JFiXL9(|y%2T%5>HKy0NDYm0k{i&$9xF$-bt`OZd2=Bff^#*Ih7D8 zp&ek>polo$S$xSVq6nr!NGG*=8c`NXYunF@l)E8qjBj|!k>5;0(YQQ#t+b+ih9M%! z^&=?XH>HcvQ?>xR5p}WeOQUeCfB2MJ)+OdvJ`j}O7d;YoI5NEU62u-nGojhcR(h@| zJNAUR!BJSgbCp+8A3ES6=QT>lnYC?PxBR4`t91U!pQ26hhXi2j$&oCF$rk+>9SliZ zEvSTh)aUnQD3p1)JhC@G1#K29na2Og@>HxHzt@iu)Kq_c<=3nx zcZ#Kqe`p@V#7@&|D%-`aMQH0OQriNTMbJj7Yd#1$4WI#8DUPgJ#8_i*S1Xen(B-{* zfyS*t>kBSr(+)b>3qnb?^{f|#Sd~;}+2#DrYgp_y){Rx49pzVO84_4jgZM!Es|S&n}Oe2DD?$ z?crEwH3oC!etjR1wC_OTFwzV@CXy9PnW`1e5(J!OypO6;TGq6xGoDR80u5DlY-_vh zdK!po$-q{ZWFME^lzXoHY1iSfk*F>B*A%*oi0OND4w98#H1lhM>T|h7Z#|XscUHS; zKAHSxC^deq6DDqNUfAOK;`wzZh^}rhp;nqKs&Js|hHWy5b1((`-aByp)G3Qizsj{zStr0H4mMSwZ6GoPM}a z(M3u13h|xoEPLfun3QVjUhK?wZSKAwJY5;bmzRa2__HkpLco$3o^W||@tlqb-o&H+TMC~?>vEoP9q%a8M%^69DQ)1#IFR9CBjeO*mu-R4njL2U=O$?bDPy_F)>m zMP1p-@h}2?3;pVq{z|``68Ra@NYwP;_sJWh%4Xl>*yg>l=W?c{lID;LwJUe0A9=*m zJ}LP=boCpzA~nZ-SLf0uJ~&qa0B%d*^i{N42&^YK4Y!4|3fSz8#PqxbMgO3GOtLn5 z;E8z?MHIF${HqTm^hy9P^yk~`1C>?XF!4Rh&XC^n$UzLJwv$eQNYA`h$bK4nDT8@F;)megw?+TIJeNO5lyhOC{<~d_ds0ACuXcv~~;K@mXwHpfGQS?Qu_~k0uj0S~Mdw-p)T_#b6f2DnTUc7rXB;$HO&TH}k0c4{6n}~% zf`ns5yDM=GMJEB+r&k#^_EaY!>CH@`=#m!>m}Z>!mAZ!s$B{WrZ=#J-*n+e*q{wgq zW6h>r!%4GaP_h0nP|m%#+U?IVb&gwc@iS#v+E_BsRwdBa-#u;TK6h`m5fX}4^^_49 zjW|DvpFyk)#4Z2O@sb{pSTiZ8M20}(Zn{NXooK!NX9lBU1Bn|h8hlax{SZi8-Zbu_ z?O+G@Lyb{9PDm$qySh10if^faf8i4oJ`dP)7U4<5?Co3b{5#V#6hd;C{tK(#ttq5b z*KdpxZ1eW>9i_I>|0`5%FVbppR~~-&Rr(aC5&-5#A1K>n?cc@H8M~u1AJGwZ-H(yq z6Fn;^toxTF(MDqOK1`(U#mppVqb!tCKe-2IvwUTrXAr!3f+SpHERR~}Lg zv)OXuBk%9ouVCV!@lMm3YBBw3ymMN7)B&YQ9)n2Gm`&p^lQV`#^BGPUa1L$$d(~?@ww{95cqzq19zbYwN`!p!!3cA~EZn zwyKK_;ND3sZtp#tD%#OUX7!nldeNw$^&(^{(C2yyfDSiA5kGg)XbDtRPHyEO135KS zpVAb0$DHBPfkzUE*QpalRKZ8JYRjGzQwgk?#p094e$8!NO)izoWTl}^DOXO;tNl)w zHwH5zE?!e#6gOE&H=gwSttB%3oWpzEtS}?8^?8}}!j$$3!4pC9AhkG`ylSEX0`(OK zxJmnTw?s+}syySe@`;A$pR! zENnptmujReNph45?2wL-qBwnr0(%x_C^IN_;)4 z>AB${hR(QL4ZSZNu%1^f_{S`F?lPFZ@Qk`-_XWU)_W-a(+tzM`weEmte6A{Yvz9f9 zc|Et!R?}QPKIyJ!N~TH>P=JZkHpa^vwm8hqPMz<5ikJ6Ii4Fk z^I2Qx58gy5Z{1H3Hy(jW9p4FVnk>17YR*XW@t-A|k|fn;Hid7Bss0{^W>j1Mnh6a! zHkDxQO+cs4O*&XF%GX(g8l(seXtR7*wyCv&I zJa8C&Wx=L;TSkk(SxLW(4t9O@Va`ND=>(?b#g+5x8xmsN55)=!ara(;th#WBNo<7P zeCjHqGko^`kX`(WE53z5cD4DbWd2OK9K1)85Dt6JzirEcA4Pk_@>nu|!5AZSfOu(P zf%v46;enZOa+KSs;ii^i=d^-^SGiSBd8hbISB#iZH@(tHErp?{>z6Y<>z{Jgs(d`C z(!6*>29N-X=1Pdh!K9i=Lrd`8e4xw=1c+Y&Ka8v1jmK!tm6Yph)6j&yI_bGzq3-Z( z2dQ=ZVP{xNNHCRe6@F=Lf8)({qb1KAtlGDfd>g+1xY;DJG%~~XTH{7SOFw$Xe(IFK zwfNleJ`Ss^cB;E=B+B4V(>3DD$XkKpW8r`u%YVq9eT$JfPff1R_&6+DG1WL62z*!r zz;n+R9&6^!GwTzZRF!)o&Py34ker+g1FZ83X4G`xsMu)gl1OdHTJb@?;?<5`@{Q3T zrx3p1FA!)8Kj*`gbu|aD!1~iIE1a_IOTt8QE(7Z%oTRC(3)I85aB5#ZNnL?HLoNOn z3!sSA(_aciS)QAZmx|J!`|-INf)!kS3hm30H_-Nzbv>1g_8m}H!2O!$aG=}>trKH? zF>g$5qu};GV(ngnzlNjq;K&tgIDnA%Q%;a^X;V}kUZ`#2Z7M%G)Zhw#y(Ur@rn!Ch zy$@CCPc9nctU7J?D&b^x-$&J$krPRgES253iSY~zDPDoqsYhP&eGcAD^f#udn$ZrK z@mFQXeMPcmb{vA$iOMbUgzjtw9D4XBlHD4ry{BB%k|ZUQ^6$L*unwHewk@`e&*(^m zsm_MWH;QeKy&-~Y=8(9kAp4&oNh{$FD?I5uk`@u!gSi5NqGh8=^}}voiYPQw0~66+ zR3?nf@m{`_(A4BDA5FoIa_bpFd_fA^nrc?gZn7PxlVF~9H|A((q`ZIgixyJ(;@p)9 z^zsCnmi1u7(P&v_Xl}n7bgl`Yz+6MwIl&_-^AEHdBrBmrC*Nh4EY{(j%Xm_x{oVF- z+zPH#sDlRE0k4b;@pYO(fjOKD69>^Uga(Btg|dQEnGA ze>w~f)qL#xjMw>lV>WdE`hiXetG{7_KiTQqyzL?ux`{Q3rbewQ9`&5jnJPr+MHN7n z^QZe_Gl)&pGsQ&@BIbJW=^9v&gUxwr2G$AKsOF`dgCZnh-TG6#(Xq?&Kh9jGnozEj#`8)@YV!d8OI(#Cky(Tyc3KmLVAu+)^@F@K1B_`dT zJa%K2JqRyzWluS;tMr)Ov6Y_Y=ctKMvG0~zn289TtEnn8=_YvA?xI85NZ2zU3YnN? z!Lh3CSVBPLPSskhoronYSc8L{s`;jR*j*}B?+Pks$e*QX^fnDglQ9*J`!z6kl-td^ z2m)cbdRAUPSh>dh!n=t#6bFjHXB9QJHw=tER+j!ylE=+=gg|j{-r)F*TMKlB0|2mx z*i(&04RuoOT;EnC^q7XgI_-7YKWeA-Dob3bF~ONzGBf+~UuGn|;iu#oi7Bs>u_>RV zj7S=Fv%Sn{GV0vm0Y)vW%GcsY+mTgf*`?KQ2=s>!T3}x?Z`(?NUjev|#xHKB>(Q*?KhL z!pn6VEYYc_xlX5m5;~^Ovv1Hx6?OScqvQfay<-$KGlqDHp73_)8tXkV&ey1!# z`kXFAN@OJ;dhCLg;A@cSTwU}SRgcAmR821rn$cPd?c}X-)E6KP)8;ZiY_O4}ky|&v z8~cM?vW5Qw!jWz#41_fD18dX8)Sr%SRH0E6l}|jO_-(S{VMr+X1mJ^SvpN}gx?`@< zjgwcx1LI3Jeq=;gK%FuyQBy{mEe5w!f(jW|nrLIDviDqEcq07-^ z)V4LXtTt16+4toY)I)ls_6pk%MnE2mE102lIqZa!B(X9NhZpnoO{d6Jr4g`$9WQOg z*O2Wdz@_P%(^3J`v@CNAH#z_AkqVoO%=gH0sy;t_lnxzhPi)lz^ZcS0o-s6C`YyH# ztAZT6<48)#v>}wtF-*%r&#WP6fc* ziN^!sU0XayOTUvQ&_|K|bEWj>?5(B2^chcsS1?;gpm@t6H0M5k>mW(NQ|`Y-{BXxw zO9iQ;X01=G^~cfhx>aMyFF=E0U4T}u9(ivQ_>Uj zA@s?`d>z@uw58;A?^F50j8Fi?Ld8{p!O~Vr-7ww_1X+bF3sTNl7GY7&O)Je${6#_e z`96KTnou;~~^R>4A`!vh(VRwTM z$jit~HD+|0I@7UWH_VR-X55#tPgbTrGCsre5cq_6g(}>_8@BSf#SvX@<38TRGM~X%xPF z#`?6M_dS9s)IsZ2)-lp$XVg?0#c4)%`;nr*47kYQ z^#;US58Jyz(J6JhzNUS7=$2^w~(sEHKi51Iq8L zYW-EgTT#40%)rluZ?cfM6hV_(?P9S7E!d1xLXbw5>!G#-D zZy+BP3#z9pB7ND^i`vJjzB+jDdC}-Z1SJ+~Rug4l9rR1t0Hvy4B*yK{nbK6A)Jx#v z*@QZJD(5c_Pv{v})90aRQnAjJr&dDXd~}+0EcGt8^(-hc5nY(egl7(YqUTHWXnrbD zkTr(f>Mq`NW;@TGZ;F5u*YyzixCIOEE^G8pbZan+ocZd3jV0$w;PRUH?yyEed9Xd- zFOPmobW-Cev{v_Y#D$w`jPXTQ)A?lE*JUom$iAUa4b?7;w#_W?OeG#V|DNYElCSdd zM1PKembxFwYy)|N=OZ99Q5$}mx}=|{F9Z@!N^LOkkB~MsZM9qEUg)P5babCk`s;zi z{TU~5Ie%(9$TQVlRhBuv@?P-CqdkGG<&!=edr2Bam}g>3hy7&4ur~R#oW@jbhZ9nR zDe|MGlwuYH3fPSfSxyD&^2_RsF*>JG^yCyP1hzz#8gqM|nmt$Iq) z#@s8>JV7S74aYp&^*hgaY<_$CTviaJ-qxJHkGh|0#80?}HM&?w4@-MmDSjn~EQMb3%mQ=F#nUTH{FB z4-RV)p4XuxV#jO(E?{v$P&OLUWJHHMHfC8FA_(FL)Dsc*DcrBRI&EfZMRw*wzU8!P2y-WQo*&f;D$B&KK8S|I1pxN?T1c2W*8 z`Plvo*p7e0%ZJ544qkb1djZXO%WXVz!R~RAVpfW5hfy&xG1-_pVHNgPW3?jG0>#~_ zj3IGXpNvbO#otr(&W-+@OnEN~6N9s=)v`Qa#cf~zEU;d^j|_BJCPWKVA0MLH;$aeR z(vDwdked}<)L6OH$Y%IoF^7P1ZqVe|H%(6ZpLj&hY8dxj1TJ3`fk)lO zbXklQ4v3A&D@@jenNOhsKDV7Q3bFIZ`JpE@av21mtQB(5P#Ld+P6*4jJ?JPv7g@l zOTVX#puhx>H%+cP=A$fI8E#x1xBtn8x-U_l{lV)wJi3o+#4+h;Nq#(~7HTUj=#-rr z9YZ3>K?cACPn&n9((EeItv+4%Ms$9u!GCu14S^Cr=Hoardy`Ig^AoAw$hq6S(a&ds zu?J(1)TNA6CinUYp?UkgwCs{@I+^xX=FZd+))FniRV0tlP&|-c}cKd`eKNrwE*Y3g~wo>hI=utGvC>-yfEX|4v;>Gx6EiLlo*!O#c7qNg zLuSfD?gPle2`cpxVE}m+7uhNIBIiTC-piZC4dYzn;j%;!NHzDiVCIKt9z{6JbB|Sh z%K$s1%*2n-B1VSlws!)otKM@mPm?hOIXWcpfieGu&Jh4e@i%*n+wf;DMNy64@z;Up z09MFCEI!Aw`JMBy@{~%E@xc!3puqv(Y;i?cB`P{d3qeKz?3H9}OjD zBnlvi>nop?ASAUy0Htu?Zi%WSfd2_c2)z7YLNlbxL!8DqZ(WwLbmOY?++KN`xT|D@ z)|J0IyT13ZW?n1V@jZ(h)%aW3b%=(ty4R0^XnA|wCZXNcXi=_&jJ&wG+M=JE?Y2Hx#ljDz3 zu0!DGLgMW&&wj&*!}-{{zAzX}Ml_a*KQ6H^o3UrTLf|%`+M7{0m2*bf&1KO~Bh42r zq2;pP?a|NTB$7xz1w5eTV#|E|EbTVzja^Kx-N;5m{T@1<4uQTJJQCs;Mqi{0MOj`- z#DvLKmTs;!EMRcbWCi+!{cp8UYt9T8HR?w@+bT3!?&9X7D}Ha6c_a%O&2S8Zx!=kz z9HfI$3kO|__hcXfUscupf9f*~k^X`usJuDixWA-<471r@9CyBJ_M=ns~7NZbeagkVgK}5FHLT z_w4dQ>7g&IptBli~SU~IYI)?3h;0aQ!XqC7Ryo37rmH7VesR3D|O zZ_;;{q+?Vy)8MUr&YAW&ix}X1gQ8=&iPMO7iPE|~_##-ni-iuWprb88hAJj~{=$vV zY--I;HExtV9(UWLZWtP=Mr0lj@F+WX6#Dj^1xFs4FjW+C#K-5R3d(0Ua+H-^W-pZN zDi+3VS)&HTatN&*^eGTdyN3G=AWTTV`h?d}bk%8MdAx2fkerD{f{N8_>rvsHC&e1| zCQrIHpC5Sg%mSs1{c{>dbnBS)=+3*4U)LU8dzr0}opIV&tv$-dhpw5cbQTAf^0xH( za3JSwyf}pG<9(VAE8S6DQ%(uXOKZe5@%V10#^pczu@Y-USy3WtP;)T!~+~i7Rhb`1SIWagK~2SM~&# z_i=noRPEtD%!2ab5!X0?S8z(p*`7U5{_dZcX(KZ$vsHeD2u3)}I-KYEVZxLyVth@r zc0(KaDD}3ox$S5d7WpD8li;B(MEfW4_7CF6O|Vh8Q3&$xrYbf9Txu@O!QJZesiKvi zRjzH?G3JE}Ud|Vf5LONEC@c&R!!T&cXP$v~3Mf?le5IyYO;m;3S+f?0sz6 zT`~kQk5Dx@1sd#;+E|n!zlg+*qT57fSG&8WGA3ipWQpia? zA1`9JPsQ5u)lCcu#?j}TU3|6ZM$3Eb0hoM(cXAR;rw2^T6fz5Cvm2^sAl5BGfWCTDwDMFel$+yTE`WiAarObPNjjg zF3y<@4NQ}^oFB!LxEU!-bIalkLB2RbJMEvipsbc+QBxN{gK%d!IO?<>^13QTh zU+h9WbK`QR1J_ct$5NFl1K%S;i~OTACo`MnI(oJ{I|4uu$s_;v_z4#4x<-V`OuZBX z8;;SsjkmnvxxG`JYeRRsx4DQC?=In$d$1hUx5hUpk==V|{Pf!L7Jg*KPQ$w!wYRWo1poFs zQOw*@pfuQmli*8a#M$HhOQmo;VSmqtAJ9aiUXzW#IpH^-cMT}Y1_y~x9EEtD918=i zM)ug(7n;ru1@ZiKlr9lO_#Hwt%TJ5}Iyh8C>@B>9xJwB1dg{)Vf$+PR8pttk*4S!s z2| z5jfIq>~~}BxshGPY)nB;wK+fi;$LJuZJd402P}8scB1mnTewpGpk)clEFWj9qCIa( z&(k@6YqHQi56s&eGjtJo1M#nmzd!sI&VBz&i*v`4_`iHBKo&B~;eUxc?)=bS{U0W}_l%s2lP`Kh*V_K>&bi3plWGf$5q1h3zCx={Mp3G7Uo{Sn_5Y9NCxH!rf zB=$>RtoiLw557(?x&K+CzE^vrxAR( z{bx{*jPhEmt8WoVcWp^nII0ye>o$Uz~%FeFVT~iit3zm-M zd98V_4S^gzz)Zokak2j`{H@SPs0Umqo=mV*5Md9+4ph)$ZQO@kf_a;eaZVV!_F zU1&e6c68;?)%)@mx_Ri|r&@=0Fc3L$zCA??Qz_=1b=?=E?yf|EW4byS9OPdI7w`O^ z_P#T!sjcl6^*wry3K~&Rio6D;9zdii)e;0jK)RF=8=-^rnxLW>nuriWXb~_VHDG`M z5dwz}(n2pGw15Fa3oVr7i~8Ps|J*U|xcBe<{_U}|ch(-ye%4y^nRD&AGREyo$lV;Z z#C*|PX)MFMPTJzWp?&lynj|(ky%|)w84tIv(7U9>j5m)^V5|m&*!Ki$_IOd($W!_8 zGnTYDNyrxWeWFyxf*7>7{Sg`5{21iGH;)$vY%Rq&L2i^be%}bP=k`HHC?6&)T>YT* z)*&wY_Kv-|`hw1wnD-9W%m^P-TwQNxV)9N1pKOM9udG#NYFtGNO3zDje)v?|mn@jH z6mn2@N&3^oc6`H2hC}?qjrdj~Yzm1_q^hJ|rFKh}WQy+kass^axW6p07zg1O)kFQY zsr!i4ocsGZ<`HZ*qbJm$^A9fq-^n_EML14E+>EQCw9(n(O>G;)eglJyuVUF)bxHWzCW?KFnD=<12&W}vX6+PLIeN?h+*eWDzjvGSk`!w^`ArRz_hqG7 zfus^N)y#cunk5S|t-B^6G?8d}pCFjqqxv|bzz>}5L)<_22|mg$YYFKaj?|PN-csYQ zM8KFowjwo%y6a37_4PVyP=rD{A)7IjR~?(S^Pp|DEDIRl(g$m z1fmL=yJYJ)7WO#50U*0<@^x{Wp;~UXqXDafX;ZVD*UM(F zcTZfn0~(n8K5@TkQEK=@ou*;vTZPmTx!u;$=~~)7bP_a$TU?Np$LbQQF~c59AMF4B ziZ=^Q_1qAWjVrWiTx&-9X7b4Z`WnmZp0ecu1hRiEc_LdZo(8{nciY8m@scg}eM$Y! zDV1aHUsy7Xq}YoCvTNVxjoqqELHJ1ALI?3cM0j$Ax#^p3f_$|ZKq?(w(ABCY5u zv9uSIR8GWP$U)%@TX4E#pKY+DQk((Bic8P71r^vg{nPXp$qQpif0yfp=^^xpvHu>f z>TN=VV|xBpK|mi4YV^ELLVT`o+6R5MzDIfUPw^kxbr8EDvqen9`n?+Dq+2QsxjgVV zQrpIP=B%CUGeyNOUngFZd2<4>HkJ@)nWgL9HKKHBu&`*WjqQ0IGx{8IzU1tayQ%cK z_{7FqAaI_TKeYE^)&fR!@gOk_N-dJ>ydsetGHe0SMLlKFPQrhU5^Qn%Z=eKzpfj+5e5;eEjja8&O z+%j6dvh=IBG;05{yFUW44jFZJmsgrEEL+$Q8HBuZ%Y- ze#UcA0kn-Q0G^JcLh_^0K9=A0@`lctElnV5W^!}n|&o+ekyYI?hsiQIMh>d+LXQSDPdpVs3o;-nbxk5s&9c)D$o zJEWtjHK z?WGzH}i7Je@U^l&a8Oimg41%J!Mfx(dKA(T_=BLg}hxzz2|%A zX3TE@Rj=f+nUab>O(_O}Cgz`K&x>+Ktvgrdgm6};5I4H_5p)6Ws2AjD=y?79L`W%n zkiPeH&#=)|wlM*#2r=!ru5L=&K1VtOAY8aN5D%Aw1IQGhr%j@%bv!+!jw;|dD+-LRoDvax=O}AuaHIn` zmKBxya-Lj`(0}Xox4C)KfT?BLfJ;70rq}gqDD-?ab{h3Wa$~)Um7DsJ z*y?_0aNAxhEzU%q`tR%jJ@X1=f^3E1rb1i?>7;YgnNWMayBcO33U1i!(x^A-jJI$C z2&QNll~B*Vxw;ueD+J+Lk&-?hMHY2qIu4v8?}Zc0RIh}=u&cRDUb(H8{;4ao224r- z&s5aY-#*hjIb$kk;rSsqY#i&V?nEKR|IGZ;c`$T&;;~G^lS?Rw$|!96(OilHvHiUI zvNiC7iNvy1B~s#|bV!8P8@KK5R@@a2K!uys7ZTjVj?vcp82l;4Bn(-q3o5TKd$BA~ z&7W3nXV+n^6!l8~t&U%jW>tEvDl+Uc`CRN*=uqo~(pl~7s1Z7j9~-sEAa5)+hj|Xx z@C~6KuHSWEjKyhJB}+kej7V0*_VNHJfb^UUb6fBUCrS`Bz;4U0Ei9OE4*IP3DJ2Sm z!}Qc<-Ill3(IEd!2^zN-W#!L!%RfOxrBU8r$Hdji@W!%N(EJzeMDA;!;#$XW#6I8C^~E`&s#^=#o^ zIyPc^sS=^@t+;It%W@6(Q&kiuo>8TIx#s~E?n+=`vCZ~dG0(e(4L}U(!L$rmZ-}AC zms3(4Vcyi9=P~;7ghjiI!k|8j5Z@D}2Zs3HX zhK>4{1f-#Ooq=WQwD1U+=%$FQ^N2xIwi0CI{++!GQ;-2jKOV~|e$&Kl<~cGw7NH;S^|9fCYqFyhAo#tF zv+Gr>%@rHUrltYE%Ydow3L#{XP%-+iuE4aH5pas!`ayF8N>9=Ys%HB#3`xxQy9G+B zaQfJgr(u{eA#c5si2Vk4vy}goV_sdjXmmMTHbXADs+gU@+aY!8`8axjaug%)R{Y+R zL^6pw3!PlY>^nCmWIfREDGIIir=9hw zeuY2`FL_veogBr2n!2qWPOhxJefJ$0Fu(h)qskT@FrN$F-Mn)pWxbHN72e|+s8V`R z{8|ne-=T-fY->W6j$YczK=<{&*k*N$vK!1-AepS?zv7;#7P$s8D)nf?b4p@-%EzmH zzo*IpKXjJtnSEKuq(v_eV^d7_mj+%6YG~c%Oq0@UcY>cVly!q+>uwEXY>EwFbltiL z4_(jFR2GRZ5r`n-S0J$2UYlg~xuU_DcgBI~B$YZ;9r85IsMn9s_YRz{>EYt3vA4-e zWHT~)yu|*@6ge2)*pHaswU)=oMpxB3)b_EeYbQ(A9ZVkcRO3xmhC7qtCQo}#`l}XH zYb_}0COio^5L~pAZSvp^*B1C;x_(uQHS~ysQLi0(nWffa0?+WgkH$L@t+uWArh+q< za_{sL)rH?kalz&lWY)de9gwTZ^YxCofr_U6h}-k?_vh!o(Ks4d2499&p!eK^h;52p z8T3zC8HJcadCGXHm0_i{bjkS5RIj6`G6qZ0a%0E=WzUr*2sFZFeg*mn$_zaG4z&Jgq! zQM(cuR15XFz}{m#H$nelR>sOgCWQb1JA>fJik23uD%m6CxD#i_+X*LcN4PeI|^HA;<6BBm^k@a$<589K-A#`!+>eyYjCB69d+$c zr3{W|$Oet|hCXL;aP6Fl?b|$M#TXV8xaklv8f7~*R5UBj->Nrf8o-7E*NnopmUi}Q z-Dh$V*>U% zD`(XBqn65c0$JZGm=R2Rl$X=eaQ0{I*Xv0#-JY7fCfHqyouxOj&-2{Zbo6mg)#$FX z+2{sBYlK()xDJ+|d$-rj8jc^0nU|z)NaFGBhHSZ@YEA=fRXCBZ$DQ&ebmAfdtlm6G zzpywlXCeaMgYobf{AY)}(%_g=!ba0(QpJ)*<#!Y1276E5;hNr**5eTR+9*MQ=^(#i zH7r8U2%rJe$~>2Vd7{Lutcq)x9V|Q)$_tJ{WZ2c-UWrVq>=#oP%|PURAv{e08$^%N zPqp-Wn2^8pJ>Fc8m5M8TVy=FYny}iY^R)fGeDI}@MC>ZH?0bbIq2Re&mvyGUOYzya%UT_e6}K3m5V(x@)Hxb;4B=gQT*H z`b=8gKJWt9pL;WXwGQU@czBZD|29!~ces?%Q6zM$liEEO4eS_s?5?~;n|y3z09q%^ zTcgC|WjX$Yzoy)K>4~I-@Yfre7`P*GSUqf! zNe+4jT}Q&boED}Fd5_MZBw3@6kP+m*m`Zo}?nXz*aG+#sNwHA8LX%1DcgosARwuPM zkY_Kg@1>x+mO`eHa@)HkV_lc=%&8N-#VVNKjZ!Svlw&TBzWZU>7^(ij|5*Bf_A(a6xSRY9%D^6xRawKjV|C$&y3r?s#uA$LeT(G^=S( zQqOA)*s)D0#YO2J*__S6wmZplQ!8Mr5Z@3u^CsK*m|o&iQFu6%ro!CcpQ9d5P{6Z@HiO{Z!PlcyNv<;qyL+m=kZGCo zI$&$Qx$T&@9Y{y{J0v{Gp&h| z^d23r7b#Eea=JFduuQq0vXN!C$6x2|Eq z3tEp6BlHt@?qG6Jv$7Lt?cgv!c7nc%^F|jk*CI6+^eH7eJmZ{=Tg7|He58bP&G`4^ zYB}p5Wic&PzqPa<2Cbz`rgdWuL;zI&Qk?BCnLs|glD_E%WYMQdu`OaFomVbviyRNn zJZD-*xO)ejrnzKXY!3QCT-yQLStTEKelxBfD*vpinGNx~>Ze$C=CSHp-_#V9pLL8r zq53o;>Wi&((}d&5DaL*{kjr}KF=Y=4F1P4WMKA>2ki#!2v^Ww}@7gxsdC!E~Vf(kU z$>BeKbj92`*7z4yzlyu6;(iF0sU|w!&p5J9#cOcMKi|wo>+zH`CwM?jzaW=pqo)B^}h$5ku0VqB)U?%%*)jFvDPr3i66 zZO0I`a}HWIJi*`EweDb`w0j?KtswX3-yMIll`76mDddxFe)4#ePg80m9c*B>iA~z|cmO{ho))3sb!cG!m12kV?l82q&yP^^R!o7BS z$kn&4WmhPo=ZO^-cwbMMhZl4#4enV7ZI#W=NpP1sSbUEe%Mfi1P8Xr`b0c*bMbK)N zaIPEQzY5@P4-?PV^<5?IVy(|uho-haX?i=`%2VPA^02qtu5ss>qt!dC4X)MI@F8N^ z5|~YL;D~xTOJ5w4&A){OiJ~9+B@^F<@3&fVrr(kYCMUo+X$gPn2bs6JiZ>kke<)dX zuYt@LMhq^+_^#|K2V%2ocyoFl*0J?bUYAV=&3H9_^04aLlF6Y#1Q$ldH&4r5`OAVR zC`1nSX(OYqzIraTOb+shYGf%^{6@Ril?l^uuhIqmp*^|t+ zcogsmIAF^`Vo#q=+@C&yZ%6Apej@z^o6fh(A9n+_BAxdy?9tKNK1%_jLxXEI{c$F66a)w z(QVWVgA!!8U+H6fDxtf4Z@5wxcE0t9Fz%82-4f%wTd0=1NJ7swH8tG5z~^DwDuIsI z%c<)%C(uN+{VlElJ-wa#fv|9Q%ftRN+)opoDXPQ2zH+Vn$)!MrL|H^&p3Y8)-=YSRl$?sQ80_y`1z@rSl&E?5Q^+#4)7omt8ZC{lL{)VyKUQKwy)n32HwkK+yB&3m zWXm+_4I|LOCBV+_?)@2PpLCDfJ_b(a z?5ys@S*#nBqR$Lv^TiouocJl=0#jWW6VEBgmga{}P;;hv-|*o&hc32sVl|4NvLPmX zF<#-5w%ekJoivCU{=RJ@<@^o6>ZXfXo8t=2Cma1+;3p*Z9aze376x1v-`Bmi<( diff --git a/localization/autoware_ekf_localizer/package.xml b/localization/autoware_ekf_localizer/package.xml deleted file mode 100644 index e0e37f59d1acb..0000000000000 --- a/localization/autoware_ekf_localizer/package.xml +++ /dev/null @@ -1,47 +0,0 @@ - - - - autoware_ekf_localizer - 0.40.0 - The autoware_ekf_localizer package - Takamasa Horibe - Yamato Ando - Takeshi Ishita - Masahiro Sakamoto - Kento Yabuuchi - NGUYEN Viet Anh - Taiki Yamada - Shintaro Sakoda - Ryu Yamamoto - Apache License 2.0 - Takamasa Horibe - - ament_cmake_auto - autoware_cmake - eigen3_cmake_module - - eigen - - autoware_internal_debug_msgs - autoware_kalman_filter - autoware_localization_util - autoware_universe_utils - diagnostic_msgs - fmt - geometry_msgs - nav_msgs - rclcpp - rclcpp_components - std_srvs - tf2 - tf2_ros - - ament_cmake_ros - ament_lint_auto - autoware_lint_common - ros_testing - - - ament_cmake - - diff --git a/localization/autoware_ekf_localizer/schema/ekf_localizer.schema.json b/localization/autoware_ekf_localizer/schema/ekf_localizer.schema.json deleted file mode 100644 index 61fbcc2973aae..0000000000000 --- a/localization/autoware_ekf_localizer/schema/ekf_localizer.schema.json +++ /dev/null @@ -1,52 +0,0 @@ -{ - "$schema": "http://json-schema.org/draft-07/schema#", - "title": "EKF Localizer Configuration", - "type": "object", - "properties": { - "/**": { - "type": "object", - "properties": { - "ros__parameters": { - "type": "object", - "properties": { - "node": { - "$ref": "sub/node.sub_schema.json#/definitions/node" - }, - "pose_measurement": { - "$ref": "sub/pose_measurement.sub_schema.json#/definitions/pose_measurement" - }, - "twist_measurement": { - "$ref": "sub/twist_measurement.sub_schema.json#/definitions/twist_measurement" - }, - "process_noise": { - "$ref": "sub/process_noise.sub_schema.json#/definitions/process_noise" - }, - "simple_1d_filter_parameters": { - "$ref": "sub/simple_1d_filter_parameters.sub_schema.json#/definitions/simple_1d_filter_parameters" - }, - "diagnostics": { - "$ref": "sub/diagnostics.sub_schema.json#/definitions/diagnostics" - }, - "misc": { - "$ref": "sub/misc.sub_schema.json#/definitions/misc" - } - }, - "required": [ - "node", - "pose_measurement", - "twist_measurement", - "process_noise", - "simple_1d_filter_parameters", - "diagnostics", - "misc" - ], - "additionalProperties": false - } - }, - "required": ["ros__parameters"], - "additionalProperties": false - } - }, - "required": ["/**"], - "additionalProperties": false -} diff --git a/localization/autoware_ekf_localizer/schema/sub/diagnostics.sub_schema.json b/localization/autoware_ekf_localizer/schema/sub/diagnostics.sub_schema.json deleted file mode 100644 index eda9e7d06f6f4..0000000000000 --- a/localization/autoware_ekf_localizer/schema/sub/diagnostics.sub_schema.json +++ /dev/null @@ -1,63 +0,0 @@ -{ - "$schema": "http://json-schema.org/draft-07/schema#", - "title": "EKF Localizer Configuration for Diagnostics", - "definitions": { - "diagnostics": { - "type": "object", - "properties": { - "pose_no_update_count_threshold_warn": { - "type": "integer", - "description": "The threshold at which a WARN state is triggered due to the Pose Topic update not happening continuously for a certain number of times", - "default": 50 - }, - "pose_no_update_count_threshold_error": { - "type": "integer", - "description": "The threshold at which an ERROR state is triggered due to the Pose Topic update not happening continuously for a certain number of times", - "default": 100 - }, - "twist_no_update_count_threshold_warn": { - "type": "integer", - "description": "The threshold at which a WARN state is triggered due to the Twist Topic update not happening continuously for a certain number of times", - "default": 50 - }, - "twist_no_update_count_threshold_error": { - "type": "integer", - "description": "The threshold at which an ERROR state is triggered due to the Twist Topic update not happening continuously for a certain number of times", - "default": 100 - }, - "ellipse_scale": { - "type": "number", - "description": "The scale factor to apply the error ellipse size", - "default": 3.0 - }, - "error_ellipse_size": { - "type": "number", - "description": "The long axis size of the error ellipse to trigger a ERROR state", - "default": 1.5 - }, - "warn_ellipse_size": { - "type": "number", - "description": "The long axis size of the error ellipse to trigger a WARN state", - "default": 1.2 - }, - "error_ellipse_size_lateral_direction": { - "type": "number", - "description": "The lateral direction size of the error ellipse to trigger a ERROR state", - "default": 0.3 - }, - "warn_ellipse_size_lateral_direction": { - "type": "number", - "description": "The lateral direction size of the error ellipse to trigger a WARN state", - "default": 0.25 - } - }, - "required": [ - "pose_no_update_count_threshold_warn", - "pose_no_update_count_threshold_error", - "twist_no_update_count_threshold_warn", - "twist_no_update_count_threshold_error" - ], - "additionalProperties": false - } - } -} diff --git a/localization/autoware_ekf_localizer/schema/sub/misc.sub_schema.json b/localization/autoware_ekf_localizer/schema/sub/misc.sub_schema.json deleted file mode 100644 index cc36a5bf41ec6..0000000000000 --- a/localization/autoware_ekf_localizer/schema/sub/misc.sub_schema.json +++ /dev/null @@ -1,23 +0,0 @@ -{ - "$schema": "http://json-schema.org/draft-07/schema#", - "title": "EKF Localizer Configuration for MISC", - "definitions": { - "misc": { - "type": "object", - "properties": { - "threshold_observable_velocity_mps": { - "type": "number", - "description": "Minimum value for velocity that will be used for EKF. Mainly used for dead zone in velocity sensor [m/s] (0.0 means disabled)", - "default": 0.0 - }, - "pose_frame_id": { - "type": "string", - "description": "Parent frame_id of EKF output pose", - "default": "map" - } - }, - "required": ["threshold_observable_velocity_mps", "pose_frame_id"], - "additionalProperties": false - } - } -} diff --git a/localization/autoware_ekf_localizer/schema/sub/node.sub_schema.json b/localization/autoware_ekf_localizer/schema/sub/node.sub_schema.json deleted file mode 100644 index cbaf34de6eaa7..0000000000000 --- a/localization/autoware_ekf_localizer/schema/sub/node.sub_schema.json +++ /dev/null @@ -1,44 +0,0 @@ -{ - "$schema": "http://json-schema.org/draft-07/schema#", - "title": "EKF Localizer Configuration for node", - "definitions": { - "node": { - "type": "object", - "properties": { - "show_debug_info": { - "type": "boolean", - "description": "Flag to display debug info", - "default": false - }, - "predict_frequency": { - "type": "number", - "description": "Frequency for filtering and publishing [Hz]", - "default": 50.0 - }, - "tf_rate": { - "type": "number", - "description": "Frequency for tf broadcasting [Hz]", - "default": 50.0 - }, - "extend_state_step": { - "type": "integer", - "description": "Max delay step which can be dealt with in EKF. Large number increases computational cost.", - "default": 50 - }, - "enable_yaw_bias_estimation": { - "type": "boolean", - "description": "Flag to enable yaw bias estimation", - "default": true - } - }, - "required": [ - "show_debug_info", - "predict_frequency", - "tf_rate", - "extend_state_step", - "enable_yaw_bias_estimation" - ], - "additionalProperties": false - } - } -} diff --git a/localization/autoware_ekf_localizer/schema/sub/pose_measurement.sub_schema.json b/localization/autoware_ekf_localizer/schema/sub/pose_measurement.sub_schema.json deleted file mode 100644 index d2bc313d4dc75..0000000000000 --- a/localization/autoware_ekf_localizer/schema/sub/pose_measurement.sub_schema.json +++ /dev/null @@ -1,38 +0,0 @@ -{ - "$schema": "http://json-schema.org/draft-07/schema#", - "title": "EKF Localizer Configuration for Pose Measurement", - "definitions": { - "pose_measurement": { - "type": "object", - "properties": { - "pose_additional_delay": { - "type": "number", - "description": "Additional delay time for pose measurement [s]", - "default": 0.0 - }, - "pose_measure_uncertainty_time": { - "type": "number", - "description": "Measured time uncertainty used for covariance calculation [s]", - "default": 0.01 - }, - "pose_smoothing_steps": { - "type": "integer", - "description": "A value for smoothing steps", - "default": 5 - }, - "pose_gate_dist": { - "type": "number", - "description": "Limit of Mahalanobis distance used for outliers detection", - "default": 49.5 - } - }, - "required": [ - "pose_additional_delay", - "pose_measure_uncertainty_time", - "pose_smoothing_steps", - "pose_gate_dist" - ], - "additionalProperties": false - } - } -} diff --git a/localization/autoware_ekf_localizer/schema/sub/process_noise.sub_schema.json b/localization/autoware_ekf_localizer/schema/sub/process_noise.sub_schema.json deleted file mode 100644 index 37a8c248edd2c..0000000000000 --- a/localization/autoware_ekf_localizer/schema/sub/process_noise.sub_schema.json +++ /dev/null @@ -1,28 +0,0 @@ -{ - "$schema": "http://json-schema.org/draft-07/schema#", - "title": "EKF Localizer Configuration for Process Noise", - "definitions": { - "process_noise": { - "type": "object", - "properties": { - "proc_stddev_vx_c": { - "type": "number", - "description": "Standard deviation of process noise in time differentiation expression of linear velocity x, noise for d_vx = 0", - "default": 10.0 - }, - "proc_stddev_wz_c": { - "type": "number", - "description": "Standard deviation of process noise in time differentiation expression of angular velocity z, noise for d_wz = 0", - "default": 5.0 - }, - "proc_stddev_yaw_c": { - "type": "number", - "description": "Standard deviation of process noise in time differentiation expression of yaw, noise for d_yaw = omega", - "default": 0.005 - } - }, - "required": ["proc_stddev_yaw_c", "proc_stddev_vx_c", "proc_stddev_wz_c"], - "additionalProperties": false - } - } -} diff --git a/localization/autoware_ekf_localizer/schema/sub/simple_1d_filter_parameters.sub_schema.json b/localization/autoware_ekf_localizer/schema/sub/simple_1d_filter_parameters.sub_schema.json deleted file mode 100644 index 00679ee92ad24..0000000000000 --- a/localization/autoware_ekf_localizer/schema/sub/simple_1d_filter_parameters.sub_schema.json +++ /dev/null @@ -1,28 +0,0 @@ -{ - "$schema": "http://json-schema.org/draft-07/schema#", - "title": "EKF Localizer Configuration of Simple 1D Filter Parameters", - "definitions": { - "simple_1d_filter_parameters": { - "type": "object", - "properties": { - "z_filter_proc_dev": { - "type": "number", - "description": "Simple1DFilter - Z filter process deviation", - "default": 1.0 - }, - "roll_filter_proc_dev": { - "type": "number", - "description": "Simple1DFilter - Roll filter process deviation", - "default": 0.1 - }, - "pitch_filter_proc_dev": { - "type": "number", - "description": "Simple1DFilter - Pitch filter process deviation", - "default": 0.1 - } - }, - "required": ["z_filter_proc_dev", "roll_filter_proc_dev", "pitch_filter_proc_dev"], - "additionalProperties": false - } - } -} diff --git a/localization/autoware_ekf_localizer/schema/sub/twist_measurement.sub_schema.json b/localization/autoware_ekf_localizer/schema/sub/twist_measurement.sub_schema.json deleted file mode 100644 index 7b80133cb38aa..0000000000000 --- a/localization/autoware_ekf_localizer/schema/sub/twist_measurement.sub_schema.json +++ /dev/null @@ -1,28 +0,0 @@ -{ - "$schema": "http://json-schema.org/draft-07/schema#", - "title": "EKF Localizer Configuration for Twist Measurement", - "definitions": { - "twist_measurement": { - "type": "object", - "properties": { - "twist_additional_delay": { - "type": "number", - "description": "Additional delay time for twist [s]", - "default": 0.0 - }, - "twist_smoothing_steps": { - "type": "integer", - "description": "A value for smoothing steps", - "default": 2 - }, - "twist_gate_dist": { - "type": "number", - "description": "Limit of Mahalanobis distance used for outliers detection", - "default": 46.1 - } - }, - "required": ["twist_additional_delay", "twist_smoothing_steps", "twist_gate_dist"], - "additionalProperties": false - } - } -} diff --git a/localization/autoware_ekf_localizer/src/covariance.cpp b/localization/autoware_ekf_localizer/src/covariance.cpp deleted file mode 100644 index 9ed3a83fbf705..0000000000000 --- a/localization/autoware_ekf_localizer/src/covariance.cpp +++ /dev/null @@ -1,56 +0,0 @@ -// Copyright 2022 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/ekf_localizer/covariance.hpp" - -#include "autoware/ekf_localizer/state_index.hpp" -#include "autoware/universe_utils/ros/msg_covariance.hpp" - -namespace autoware::ekf_localizer -{ - -using COV_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; - -std::array ekf_covariance_to_pose_message_covariance(const Matrix6d & P) -{ - std::array covariance{}; - covariance.fill(0.); - - covariance[COV_IDX::X_X] = P(IDX::X, IDX::X); - covariance[COV_IDX::X_Y] = P(IDX::X, IDX::Y); - covariance[COV_IDX::X_YAW] = P(IDX::X, IDX::YAW); - covariance[COV_IDX::Y_X] = P(IDX::Y, IDX::X); - covariance[COV_IDX::Y_Y] = P(IDX::Y, IDX::Y); - covariance[COV_IDX::Y_YAW] = P(IDX::Y, IDX::YAW); - covariance[COV_IDX::YAW_X] = P(IDX::YAW, IDX::X); - covariance[COV_IDX::YAW_Y] = P(IDX::YAW, IDX::Y); - covariance[COV_IDX::YAW_YAW] = P(IDX::YAW, IDX::YAW); - - return covariance; -} - -std::array ekf_covariance_to_twist_message_covariance(const Matrix6d & P) -{ - std::array covariance{}; - covariance.fill(0.); - - covariance[COV_IDX::X_X] = P(IDX::VX, IDX::VX); - covariance[COV_IDX::X_YAW] = P(IDX::VX, IDX::WZ); - covariance[COV_IDX::YAW_X] = P(IDX::WZ, IDX::VX); - covariance[COV_IDX::YAW_YAW] = P(IDX::WZ, IDX::WZ); - - return covariance; -} - -} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/src/diagnostics.cpp b/localization/autoware_ekf_localizer/src/diagnostics.cpp deleted file mode 100644 index 45468abf72d6c..0000000000000 --- a/localization/autoware_ekf_localizer/src/diagnostics.cpp +++ /dev/null @@ -1,226 +0,0 @@ -// Copyright 2023 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/ekf_localizer/diagnostics.hpp" - -#include - -#include -#include - -namespace autoware::ekf_localizer -{ - -diagnostic_msgs::msg::DiagnosticStatus check_process_activated(const bool is_activated) -{ - diagnostic_msgs::msg::DiagnosticStatus stat; - - diagnostic_msgs::msg::KeyValue key_value; - key_value.key = "is_activated"; - key_value.value = is_activated ? "True" : "False"; - stat.values.push_back(key_value); - - stat.level = diagnostic_msgs::msg::DiagnosticStatus::OK; - stat.message = "OK"; - if (!is_activated) { - stat.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - stat.message = "[WARN]process is not activated"; - } - - return stat; -} - -diagnostic_msgs::msg::DiagnosticStatus check_set_initialpose(const bool is_set_initialpose) -{ - diagnostic_msgs::msg::DiagnosticStatus stat; - - diagnostic_msgs::msg::KeyValue key_value; - key_value.key = "is_set_initialpose"; - key_value.value = is_set_initialpose ? "True" : "False"; - stat.values.push_back(key_value); - - stat.level = diagnostic_msgs::msg::DiagnosticStatus::OK; - stat.message = "OK"; - if (!is_set_initialpose) { - stat.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - stat.message = "[WARN]initial pose is not set"; - } - - return stat; -} - -diagnostic_msgs::msg::DiagnosticStatus check_measurement_updated( - const std::string & measurement_type, const size_t no_update_count, - const size_t no_update_count_threshold_warn, const size_t no_update_count_threshold_error) -{ - diagnostic_msgs::msg::DiagnosticStatus stat; - - diagnostic_msgs::msg::KeyValue key_value; - key_value.key = measurement_type + "_no_update_count"; - key_value.value = std::to_string(no_update_count); - stat.values.push_back(key_value); - key_value.key = measurement_type + "_no_update_count_threshold_warn"; - key_value.value = std::to_string(no_update_count_threshold_warn); - stat.values.push_back(key_value); - key_value.key = measurement_type + "_no_update_count_threshold_error"; - key_value.value = std::to_string(no_update_count_threshold_error); - stat.values.push_back(key_value); - - stat.level = diagnostic_msgs::msg::DiagnosticStatus::OK; - stat.message = "OK"; - if (no_update_count >= no_update_count_threshold_warn) { - stat.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - stat.message = "[WARN]" + measurement_type + " is not updated"; - } - if (no_update_count >= no_update_count_threshold_error) { - stat.level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; - stat.message = "[ERROR]" + measurement_type + " is not updated"; - } - - return stat; -} - -diagnostic_msgs::msg::DiagnosticStatus check_measurement_queue_size( - const std::string & measurement_type, const size_t queue_size) -{ - diagnostic_msgs::msg::DiagnosticStatus stat; - - diagnostic_msgs::msg::KeyValue key_value; - key_value.key = measurement_type + "_queue_size"; - key_value.value = std::to_string(queue_size); - stat.values.push_back(key_value); - - stat.level = diagnostic_msgs::msg::DiagnosticStatus::OK; - stat.message = "OK"; - - return stat; -} - -diagnostic_msgs::msg::DiagnosticStatus check_measurement_delay_gate( - const std::string & measurement_type, const bool is_passed_delay_gate, const double delay_time, - const double delay_time_threshold) -{ - diagnostic_msgs::msg::DiagnosticStatus stat; - - diagnostic_msgs::msg::KeyValue key_value; - key_value.key = measurement_type + "_is_passed_delay_gate"; - key_value.value = is_passed_delay_gate ? "True" : "False"; - stat.values.push_back(key_value); - key_value.key = measurement_type + "_delay_time"; - key_value.value = std::to_string(delay_time); - stat.values.push_back(key_value); - key_value.key = measurement_type + "_delay_time_threshold"; - key_value.value = std::to_string(delay_time_threshold); - stat.values.push_back(key_value); - - stat.level = diagnostic_msgs::msg::DiagnosticStatus::OK; - stat.message = "OK"; - if (!is_passed_delay_gate) { - stat.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - stat.message = "[WARN]" + measurement_type + " topic is delay"; - } - - return stat; -} - -diagnostic_msgs::msg::DiagnosticStatus check_measurement_mahalanobis_gate( - const std::string & measurement_type, const bool is_passed_mahalanobis_gate, - const double mahalanobis_distance, const double mahalanobis_distance_threshold) -{ - diagnostic_msgs::msg::DiagnosticStatus stat; - - diagnostic_msgs::msg::KeyValue key_value; - key_value.key = measurement_type + "_is_passed_mahalanobis_gate"; - key_value.value = is_passed_mahalanobis_gate ? "True" : "False"; - stat.values.push_back(key_value); - key_value.key = measurement_type + "_mahalanobis_distance"; - key_value.value = std::to_string(mahalanobis_distance); - stat.values.push_back(key_value); - key_value.key = measurement_type + "_mahalanobis_distance_threshold"; - key_value.value = std::to_string(mahalanobis_distance_threshold); - stat.values.push_back(key_value); - - stat.level = diagnostic_msgs::msg::DiagnosticStatus::OK; - stat.message = "OK"; - if (!is_passed_mahalanobis_gate) { - stat.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - stat.message = "[WARN]mahalanobis distance of " + measurement_type + " topic is large"; - } - - return stat; -} - -diagnostic_msgs::msg::DiagnosticStatus check_covariance_ellipse( - const std::string & name, const double curr_size, const double warn_threshold, - const double error_threshold) -{ - diagnostic_msgs::msg::DiagnosticStatus stat; - - diagnostic_msgs::msg::KeyValue key_value; - key_value.key = name + "_size"; - key_value.value = std::to_string(curr_size); - stat.values.push_back(key_value); - - key_value.key = name + "_warn_threshold"; - key_value.value = std::to_string(warn_threshold); - stat.values.push_back(key_value); - - key_value.key = name + "_error_threshold"; - key_value.value = std::to_string(error_threshold); - stat.values.push_back(key_value); - - stat.level = diagnostic_msgs::msg::DiagnosticStatus::OK; - stat.message = "OK"; - if (curr_size >= warn_threshold) { - stat.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - stat.message = "[WARN]" + name + " is large"; - } - if (curr_size >= error_threshold) { - stat.level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; - stat.message = "[ERROR]" + name + " is large"; - } - - return stat; -} - -// The highest level within the stat_array will be reflected in the merged_stat. -// When all stat_array entries are 'OK,' the message of merged_stat will be "OK" -diagnostic_msgs::msg::DiagnosticStatus merge_diagnostic_status( - const std::vector & stat_array) -{ - diagnostic_msgs::msg::DiagnosticStatus merged_stat; - - for (const auto & stat : stat_array) { - if ((stat.level > diagnostic_msgs::msg::DiagnosticStatus::OK)) { - if (!merged_stat.message.empty()) { - merged_stat.message += "; "; - } - merged_stat.message += stat.message; - } - if (stat.level > merged_stat.level) { - merged_stat.level = stat.level; - } - for (const auto & value : stat.values) { - merged_stat.values.push_back(value); - } - } - - if (merged_stat.level == diagnostic_msgs::msg::DiagnosticStatus::OK) { - merged_stat.message = "OK"; - } - - return merged_stat; -} - -} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/src/ekf_localizer.cpp b/localization/autoware_ekf_localizer/src/ekf_localizer.cpp deleted file mode 100644 index 5638a5416e6ab..0000000000000 --- a/localization/autoware_ekf_localizer/src/ekf_localizer.cpp +++ /dev/null @@ -1,463 +0,0 @@ -// Copyright 2018-2019 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/ekf_localizer/ekf_localizer.hpp" - -#include "autoware/ekf_localizer/diagnostics.hpp" -#include "autoware/ekf_localizer/string.hpp" -#include "autoware/ekf_localizer/warning_message.hpp" -#include "autoware/localization_util/covariance_ellipse.hpp" - -#include -#include -#include -#include -#include - -#include - -#include -#include -#include -#include -#include -#include -#include - -namespace autoware::ekf_localizer -{ - -// clang-format off -#define PRINT_MAT(X) std::cout << #X << ":\n" << X << std::endl << std::endl // NOLINT -#define DEBUG_INFO(...) {if (params_.show_debug_info) {RCLCPP_INFO(__VA_ARGS__);}} // NOLINT -// clang-format on - -using std::placeholders::_1; - -EKFLocalizer::EKFLocalizer(const rclcpp::NodeOptions & node_options) -: rclcpp::Node("ekf_localizer", node_options), - warning_(std::make_shared(this)), - tf2_buffer_(this->get_clock()), - tf2_listener_(tf2_buffer_), - params_(this), - ekf_dt_(params_.ekf_dt), - pose_queue_(params_.pose_smoothing_steps), - twist_queue_(params_.twist_smoothing_steps) -{ - is_activated_ = false; - is_set_initialpose_ = false; - - /* initialize ros system */ - timer_control_ = rclcpp::create_timer( - this, get_clock(), rclcpp::Duration::from_seconds(ekf_dt_), - std::bind(&EKFLocalizer::timer_callback, this)); - - pub_pose_ = create_publisher("ekf_pose", 1); - pub_pose_cov_ = - create_publisher("ekf_pose_with_covariance", 1); - pub_odom_ = create_publisher("ekf_odom", 1); - pub_twist_ = create_publisher("ekf_twist", 1); - pub_twist_cov_ = create_publisher( - "ekf_twist_with_covariance", 1); - pub_yaw_bias_ = - create_publisher("estimated_yaw_bias", 1); - pub_biased_pose_ = create_publisher("ekf_biased_pose", 1); - pub_biased_pose_cov_ = create_publisher( - "ekf_biased_pose_with_covariance", 1); - pub_diag_ = this->create_publisher("/diagnostics", 10); - pub_processing_time_ = create_publisher( - "debug/processing_time_ms", 1); - sub_initialpose_ = create_subscription( - "initialpose", 1, std::bind(&EKFLocalizer::callback_initial_pose, this, _1)); - sub_pose_with_cov_ = create_subscription( - "in_pose_with_covariance", 1, - std::bind(&EKFLocalizer::callback_pose_with_covariance, this, _1)); - sub_twist_with_cov_ = create_subscription( - "in_twist_with_covariance", 1, - std::bind(&EKFLocalizer::callback_twist_with_covariance, this, _1)); - service_trigger_node_ = create_service( - "trigger_node_srv", - std::bind( - &EKFLocalizer::service_trigger_node, this, std::placeholders::_1, std::placeholders::_2), - rclcpp::ServicesQoS().get_rmw_qos_profile()); - - tf_br_ = std::make_shared( - std::shared_ptr(this, [](auto) {})); - - ekf_module_ = std::make_unique(warning_, params_); - logger_configure_ = std::make_unique(this); -} - -/* - * update_predict_frequency - */ -void EKFLocalizer::update_predict_frequency(const rclcpp::Time & current_time) -{ - if (last_predict_time_) { - if (current_time < *last_predict_time_) { - warning_->warn("Detected jump back in time"); - } else { - /* Measure dt */ - ekf_dt_ = (current_time - *last_predict_time_).seconds(); - DEBUG_INFO( - get_logger(), "[EKF] update ekf_dt_ to %f seconds (= %f hz)", ekf_dt_, 1 / ekf_dt_); - - if (ekf_dt_ > 10.0) { - ekf_dt_ = 10.0; - RCLCPP_WARN( - get_logger(), "Large ekf_dt_ detected!! (%f sec) Capped to 10.0 seconds", ekf_dt_); - } else if (ekf_dt_ > static_cast(params_.pose_smoothing_steps) / params_.ekf_rate) { - RCLCPP_WARN( - get_logger(), "EKF period may be too slow to finish pose smoothing!! (%f sec) ", ekf_dt_); - } - - /* Register dt and accumulate time delay */ - ekf_module_->accumulate_delay_time(ekf_dt_); - } - } - last_predict_time_ = std::make_shared(current_time); -} - -/* - * timer_callback - */ -void EKFLocalizer::timer_callback() -{ - stop_watch_timer_cb_.tic(); - - const rclcpp::Time current_time = this->now(); - - if (!is_activated_) { - warning_->warn_throttle( - "The node is not activated. Provide initial pose to pose_initializer", 2000); - publish_diagnostics(geometry_msgs::msg::PoseStamped{}, current_time); - return; - } - - if (!is_set_initialpose_) { - warning_->warn_throttle( - "Initial pose is not set. Provide initial pose to pose_initializer", 2000); - publish_diagnostics(geometry_msgs::msg::PoseStamped{}, current_time); - return; - } - - DEBUG_INFO(get_logger(), "========================= timer called ========================="); - - /* update predict frequency with measured timer rate */ - update_predict_frequency(current_time); - - /* predict model in EKF */ - stop_watch_.tic(); - DEBUG_INFO(get_logger(), "------------------------- start prediction -------------------------"); - ekf_module_->predict_with_delay(ekf_dt_); - DEBUG_INFO(get_logger(), "[EKF] predictKinematicsModel calc time = %f [ms]", stop_watch_.toc()); - DEBUG_INFO(get_logger(), "------------------------- end prediction -------------------------\n"); - - /* pose measurement update */ - pose_diag_info_.queue_size = pose_queue_.size(); - pose_diag_info_.is_passed_delay_gate = true; - pose_diag_info_.delay_time = 0.0; - pose_diag_info_.delay_time_threshold = 0.0; - pose_diag_info_.is_passed_mahalanobis_gate = true; - pose_diag_info_.mahalanobis_distance = 0.0; - - bool pose_is_updated = false; - - if (!pose_queue_.empty()) { - DEBUG_INFO(get_logger(), "------------------------- start Pose -------------------------"); - stop_watch_.tic(); - - // save the initial size because the queue size can change in the loop - const size_t n = pose_queue_.size(); - for (size_t i = 0; i < n; ++i) { - const auto pose = pose_queue_.pop_increment_age(); - bool is_updated = ekf_module_->measurement_update_pose(*pose, current_time, pose_diag_info_); - if (is_updated) { - pose_is_updated = true; - } - } - DEBUG_INFO( - get_logger(), "[EKF] measurement_update_pose calc time = %f [ms]", stop_watch_.toc()); - DEBUG_INFO(get_logger(), "------------------------- end Pose -------------------------\n"); - } - pose_diag_info_.no_update_count = pose_is_updated ? 0 : (pose_diag_info_.no_update_count + 1); - - /* twist measurement update */ - twist_diag_info_.queue_size = twist_queue_.size(); - twist_diag_info_.is_passed_delay_gate = true; - twist_diag_info_.delay_time = 0.0; - twist_diag_info_.delay_time_threshold = 0.0; - twist_diag_info_.is_passed_mahalanobis_gate = true; - twist_diag_info_.mahalanobis_distance = 0.0; - - bool twist_is_updated = false; - - if (!twist_queue_.empty()) { - DEBUG_INFO(get_logger(), "------------------------- start Twist -------------------------"); - stop_watch_.tic(); - - // save the initial size because the queue size can change in the loop - const size_t n = twist_queue_.size(); - for (size_t i = 0; i < n; ++i) { - const auto twist = twist_queue_.pop_increment_age(); - bool is_updated = - ekf_module_->measurement_update_twist(*twist, current_time, twist_diag_info_); - if (is_updated) { - twist_is_updated = true; - } - } - DEBUG_INFO( - get_logger(), "[EKF] measurement_update_twist calc time = %f [ms]", stop_watch_.toc()); - DEBUG_INFO(get_logger(), "------------------------- end Twist -------------------------\n"); - } - twist_diag_info_.no_update_count = twist_is_updated ? 0 : (twist_diag_info_.no_update_count + 1); - - const geometry_msgs::msg::PoseStamped current_ekf_pose = - ekf_module_->get_current_pose(current_time, false); - const geometry_msgs::msg::PoseStamped current_biased_ekf_pose = - ekf_module_->get_current_pose(current_time, true); - const geometry_msgs::msg::TwistStamped current_ekf_twist = - ekf_module_->get_current_twist(current_time); - - /* publish ekf result */ - publish_estimate_result(current_ekf_pose, current_biased_ekf_pose, current_ekf_twist); - publish_diagnostics(current_ekf_pose, current_time); - - /* publish processing time */ - const double elapsed_time = stop_watch_timer_cb_.toc(); - pub_processing_time_->publish( - autoware_internal_debug_msgs::build() - .stamp(current_time) - .data(elapsed_time)); -} - -/* - * get_transform_from_tf - */ -bool EKFLocalizer::get_transform_from_tf( - std::string parent_frame, std::string child_frame, - geometry_msgs::msg::TransformStamped & transform) -{ - parent_frame = erase_leading_slash(parent_frame); - child_frame = erase_leading_slash(child_frame); - - try { - transform = tf2_buffer_.lookupTransform(parent_frame, child_frame, tf2::TimePointZero); - return true; - } catch (tf2::TransformException & ex) { - warning_->warn(ex.what()); - } - return false; -} - -/* - * callback_initial_pose - */ -void EKFLocalizer::callback_initial_pose( - geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg) -{ - geometry_msgs::msg::TransformStamped transform; - if (!get_transform_from_tf(params_.pose_frame_id, msg->header.frame_id, transform)) { - RCLCPP_ERROR( - get_logger(), "[EKF] TF transform failed. parent = %s, child = %s", - params_.pose_frame_id.c_str(), msg->header.frame_id.c_str()); - } - ekf_module_->initialize(*msg, transform); - - is_set_initialpose_ = true; -} - -/* - * callback_pose_with_covariance - */ -void EKFLocalizer::callback_pose_with_covariance( - geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg) -{ - if (!is_activated_ && !is_set_initialpose_) { - return; - } - - pose_queue_.push(msg); - - publish_callback_return_diagnostics("pose", msg->header.stamp); -} - -/* - * callback_twist_with_covariance - */ -void EKFLocalizer::callback_twist_with_covariance( - geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg) -{ - // Ignore twist if velocity is too small. - // Note that this inequality must not include "equal". - if (std::abs(msg->twist.twist.linear.x) < params_.threshold_observable_velocity_mps) { - msg->twist.covariance[0 * 6 + 0] = 10000.0; - } - twist_queue_.push(msg); - - publish_callback_return_diagnostics("twist", msg->header.stamp); -} - -/* - * publish_estimate_result - */ -void EKFLocalizer::publish_estimate_result( - const geometry_msgs::msg::PoseStamped & current_ekf_pose, - const geometry_msgs::msg::PoseStamped & current_biased_ekf_pose, - const geometry_msgs::msg::TwistStamped & current_ekf_twist) -{ - /* publish latest pose */ - pub_pose_->publish(current_ekf_pose); - pub_biased_pose_->publish(current_biased_ekf_pose); - - /* publish latest pose with covariance */ - geometry_msgs::msg::PoseWithCovarianceStamped pose_cov; - pose_cov.header.stamp = current_ekf_pose.header.stamp; - pose_cov.header.frame_id = current_ekf_pose.header.frame_id; - pose_cov.pose.pose = current_ekf_pose.pose; - pose_cov.pose.covariance = ekf_module_->get_current_pose_covariance(); - pub_pose_cov_->publish(pose_cov); - - geometry_msgs::msg::PoseWithCovarianceStamped biased_pose_cov = pose_cov; - biased_pose_cov.pose.pose = current_biased_ekf_pose.pose; - pub_biased_pose_cov_->publish(biased_pose_cov); - - /* publish latest twist */ - pub_twist_->publish(current_ekf_twist); - - /* publish latest twist with covariance */ - geometry_msgs::msg::TwistWithCovarianceStamped twist_cov; - twist_cov.header.stamp = current_ekf_twist.header.stamp; - twist_cov.header.frame_id = current_ekf_twist.header.frame_id; - twist_cov.twist.twist = current_ekf_twist.twist; - twist_cov.twist.covariance = ekf_module_->get_current_twist_covariance(); - pub_twist_cov_->publish(twist_cov); - - /* publish yaw bias */ - autoware_internal_debug_msgs::msg::Float64Stamped yawb; - yawb.stamp = current_ekf_twist.header.stamp; - yawb.data = ekf_module_->get_yaw_bias(); - pub_yaw_bias_->publish(yawb); - - /* publish latest odometry */ - nav_msgs::msg::Odometry odometry; - odometry.header.stamp = current_ekf_pose.header.stamp; - odometry.header.frame_id = current_ekf_pose.header.frame_id; - odometry.child_frame_id = "base_link"; - odometry.pose = pose_cov.pose; - odometry.twist = twist_cov.twist; - pub_odom_->publish(odometry); - - /* publish tf */ - const geometry_msgs::msg::TransformStamped transform_stamped = - autoware::universe_utils::pose2transform(current_ekf_pose, "base_link"); - tf_br_->sendTransform(transform_stamped); -} - -void EKFLocalizer::publish_diagnostics( - const geometry_msgs::msg::PoseStamped & current_ekf_pose, const rclcpp::Time & current_time) -{ - std::vector diag_status_array; - - diag_status_array.push_back(check_process_activated(is_activated_)); - diag_status_array.push_back(check_set_initialpose(is_set_initialpose_)); - - if (is_activated_ && is_set_initialpose_) { - diag_status_array.push_back(check_measurement_updated( - "pose", pose_diag_info_.no_update_count, params_.pose_no_update_count_threshold_warn, - params_.pose_no_update_count_threshold_error)); - diag_status_array.push_back(check_measurement_queue_size("pose", pose_diag_info_.queue_size)); - diag_status_array.push_back(check_measurement_delay_gate( - "pose", pose_diag_info_.is_passed_delay_gate, pose_diag_info_.delay_time, - pose_diag_info_.delay_time_threshold)); - diag_status_array.push_back(check_measurement_mahalanobis_gate( - "pose", pose_diag_info_.is_passed_mahalanobis_gate, pose_diag_info_.mahalanobis_distance, - params_.pose_gate_dist)); - - diag_status_array.push_back(check_measurement_updated( - "twist", twist_diag_info_.no_update_count, params_.twist_no_update_count_threshold_warn, - params_.twist_no_update_count_threshold_error)); - diag_status_array.push_back(check_measurement_queue_size("twist", twist_diag_info_.queue_size)); - diag_status_array.push_back(check_measurement_delay_gate( - "twist", twist_diag_info_.is_passed_delay_gate, twist_diag_info_.delay_time, - twist_diag_info_.delay_time_threshold)); - diag_status_array.push_back(check_measurement_mahalanobis_gate( - "twist", twist_diag_info_.is_passed_mahalanobis_gate, twist_diag_info_.mahalanobis_distance, - params_.twist_gate_dist)); - - geometry_msgs::msg::PoseWithCovariance pose_cov; - pose_cov.pose = current_ekf_pose.pose; - pose_cov.covariance = ekf_module_->get_current_pose_covariance(); - const autoware::localization_util::Ellipse ellipse = - autoware::localization_util::calculate_xy_ellipse(pose_cov, params_.ellipse_scale); - diag_status_array.push_back(check_covariance_ellipse( - "cov_ellipse_long_axis", ellipse.long_radius, params_.warn_ellipse_size, - params_.error_ellipse_size)); - diag_status_array.push_back(check_covariance_ellipse( - "cov_ellipse_lateral_direction", ellipse.size_lateral_direction, - params_.warn_ellipse_size_lateral_direction, params_.error_ellipse_size_lateral_direction)); - } - - diagnostic_msgs::msg::DiagnosticStatus diag_merged_status; - diag_merged_status = merge_diagnostic_status(diag_status_array); - diag_merged_status.name = "localization: " + std::string(this->get_name()); - diag_merged_status.hardware_id = this->get_name(); - - diagnostic_msgs::msg::DiagnosticArray diag_msg; - diag_msg.header.stamp = current_time; - diag_msg.status.push_back(diag_merged_status); - pub_diag_->publish(diag_msg); -} - -void EKFLocalizer::publish_callback_return_diagnostics( - const std::string & callback_name, const rclcpp::Time & current_time) -{ - diagnostic_msgs::msg::KeyValue key_value; - key_value.key = "topic_time_stamp"; - key_value.value = std::to_string(current_time.nanoseconds()); - diagnostic_msgs::msg::DiagnosticStatus diag_status; - diag_status.level = diagnostic_msgs::msg::DiagnosticStatus::OK; - diag_status.name = - "localization: " + std::string(this->get_name()) + ": callback_" + callback_name; - diag_status.hardware_id = this->get_name(); - diag_status.message = "OK"; - diag_status.values.push_back(key_value); - diagnostic_msgs::msg::DiagnosticArray diag_msg; - diag_msg.header.stamp = current_time; - diag_msg.status.push_back(diag_status); - pub_diag_->publish(diag_msg); -} - -/** - * @brief trigger node - */ -void EKFLocalizer::service_trigger_node( - const std_srvs::srv::SetBool::Request::SharedPtr req, - std_srvs::srv::SetBool::Response::SharedPtr res) -{ - if (req->data) { - pose_queue_.clear(); - twist_queue_.clear(); - is_activated_ = true; - } else { - is_activated_ = false; - is_set_initialpose_ = false; - } - res->success = true; -} - -} // namespace autoware::ekf_localizer - -#include -RCLCPP_COMPONENTS_REGISTER_NODE(autoware::ekf_localizer::EKFLocalizer) diff --git a/localization/autoware_ekf_localizer/src/ekf_module.cpp b/localization/autoware_ekf_localizer/src/ekf_module.cpp deleted file mode 100644 index 02c9f8ee30e08..0000000000000 --- a/localization/autoware_ekf_localizer/src/ekf_module.cpp +++ /dev/null @@ -1,459 +0,0 @@ -// Copyright 2018-2019 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/ekf_localizer/ekf_module.hpp" - -#include "autoware/ekf_localizer/covariance.hpp" -#include "autoware/ekf_localizer/mahalanobis.hpp" -#include "autoware/ekf_localizer/matrix_types.hpp" -#include "autoware/ekf_localizer/measurement.hpp" -#include "autoware/ekf_localizer/numeric.hpp" -#include "autoware/ekf_localizer/state_transition.hpp" -#include "autoware/ekf_localizer/warning_message.hpp" - -#include -#include - -#include -#include -#include - -#include -#include - -namespace autoware::ekf_localizer -{ - -// clang-format off -#define DEBUG_PRINT_MAT(X) {if (params_.show_debug_info) {std::cout << #X << ": " << X << std::endl;}} // NOLINT -// clang-format on - -EKFModule::EKFModule(std::shared_ptr warning, const HyperParameters & params) -: warning_(std::move(warning)), - dim_x_(6), // x, y, yaw, yaw_bias, vx, wz - accumulated_delay_times_(params.extend_state_step, 1.0E15), - params_(params), - last_angular_velocity_(0.0, 0.0, 0.0) -{ - Eigen::MatrixXd x = Eigen::MatrixXd::Zero(dim_x_, 1); - Eigen::MatrixXd p = Eigen::MatrixXd::Identity(dim_x_, dim_x_) * 1.0E15; // for x & y - p(IDX::YAW, IDX::YAW) = 50.0; // for yaw - if (params_.enable_yaw_bias_estimation) { - p(IDX::YAWB, IDX::YAWB) = 50.0; // for yaw bias - } - p(IDX::VX, IDX::VX) = 1000.0; // for vx - p(IDX::WZ, IDX::WZ) = 50.0; // for wz - - kalman_filter_.init(x, p, static_cast(params_.extend_state_step)); - z_filter_.set_proc_var(params_.z_filter_proc_dev * params_.z_filter_proc_dev); - roll_filter_.set_proc_var(params_.roll_filter_proc_dev * params_.roll_filter_proc_dev); - pitch_filter_.set_proc_var(params_.pitch_filter_proc_dev * params_.pitch_filter_proc_dev); -} - -void EKFModule::initialize( - const PoseWithCovariance & initial_pose, const geometry_msgs::msg::TransformStamped & transform) -{ - Eigen::MatrixXd x(dim_x_, 1); - Eigen::MatrixXd p = Eigen::MatrixXd::Zero(dim_x_, dim_x_); - - x(IDX::X) = initial_pose.pose.pose.position.x + transform.transform.translation.x; - x(IDX::Y) = initial_pose.pose.pose.position.y + transform.transform.translation.y; - x(IDX::YAW) = - tf2::getYaw(initial_pose.pose.pose.orientation) + tf2::getYaw(transform.transform.rotation); - x(IDX::YAWB) = 0.0; - x(IDX::VX) = 0.0; - x(IDX::WZ) = 0.0; - - using COV_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; - p(IDX::X, IDX::X) = initial_pose.pose.covariance[COV_IDX::X_X]; - p(IDX::Y, IDX::Y) = initial_pose.pose.covariance[COV_IDX::Y_Y]; - p(IDX::YAW, IDX::YAW) = initial_pose.pose.covariance[COV_IDX::YAW_YAW]; - - if (params_.enable_yaw_bias_estimation) { - p(IDX::YAWB, IDX::YAWB) = 0.0001; - } - p(IDX::VX, IDX::VX) = 0.01; - p(IDX::WZ, IDX::WZ) = 0.01; - - kalman_filter_.init(x, p, static_cast(params_.extend_state_step)); - - const double z = initial_pose.pose.pose.position.z; - - const auto rpy = autoware::universe_utils::getRPY(initial_pose.pose.pose.orientation); - - const double z_var = initial_pose.pose.covariance[COV_IDX::Z_Z]; - const double roll_var = initial_pose.pose.covariance[COV_IDX::ROLL_ROLL]; - const double pitch_var = initial_pose.pose.covariance[COV_IDX::PITCH_PITCH]; - - z_filter_.init(z, z_var); - roll_filter_.init(rpy.x, roll_var); - pitch_filter_.init(rpy.y, pitch_var); -} - -geometry_msgs::msg::PoseStamped EKFModule::get_current_pose( - const rclcpp::Time & current_time, bool get_biased_yaw) const -{ - const double z = z_filter_.get_x(); - const double roll = roll_filter_.get_x(); - const double pitch = pitch_filter_.get_x(); - - const double x = kalman_filter_.getXelement(IDX::X); - const double y = kalman_filter_.getXelement(IDX::Y); - /* - getXelement(IDX::YAW) is surely `biased_yaw`. - Please note how `yaw` and `yaw_bias` are used in the state transition model and - how the observed pose is handled in the measurement pose update. - */ - const double biased_yaw = kalman_filter_.getXelement(IDX::YAW); - const double yaw_bias = kalman_filter_.getXelement(IDX::YAWB); - const double yaw = biased_yaw + yaw_bias; - - Pose current_ekf_pose; - current_ekf_pose.header.frame_id = params_.pose_frame_id; - current_ekf_pose.header.stamp = current_time; - current_ekf_pose.pose.position = autoware::universe_utils::createPoint(x, y, z); - if (get_biased_yaw) { - current_ekf_pose.pose.orientation = - autoware::universe_utils::createQuaternionFromRPY(roll, pitch, biased_yaw); - } else { - current_ekf_pose.pose.orientation = - autoware::universe_utils::createQuaternionFromRPY(roll, pitch, yaw); - } - return current_ekf_pose; -} - -geometry_msgs::msg::TwistStamped EKFModule::get_current_twist( - const rclcpp::Time & current_time) const -{ - const double vx = kalman_filter_.getXelement(IDX::VX); - const double wz = kalman_filter_.getXelement(IDX::WZ); - - Twist current_ekf_twist; - current_ekf_twist.header.frame_id = "base_link"; - current_ekf_twist.header.stamp = current_time; - current_ekf_twist.twist.linear.x = vx; - current_ekf_twist.twist.angular.z = wz; - return current_ekf_twist; -} - -std::array EKFModule::get_current_pose_covariance() const -{ - std::array cov = - ekf_covariance_to_pose_message_covariance(kalman_filter_.getLatestP()); - - using COV_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; - cov[COV_IDX::Z_Z] = z_filter_.get_var(); - cov[COV_IDX::ROLL_ROLL] = roll_filter_.get_var(); - cov[COV_IDX::PITCH_PITCH] = pitch_filter_.get_var(); - - return cov; -} - -std::array EKFModule::get_current_twist_covariance() const -{ - return ekf_covariance_to_twist_message_covariance(kalman_filter_.getLatestP()); -} - -double EKFModule::get_yaw_bias() const -{ - return kalman_filter_.getLatestX()(IDX::YAWB); -} - -size_t EKFModule::find_closest_delay_time_index(double target_value) const -{ - // If target_value is too large, return last index + 1 - if (target_value > accumulated_delay_times_.back()) { - return accumulated_delay_times_.size(); - } - - auto lower = std::lower_bound( - accumulated_delay_times_.begin(), accumulated_delay_times_.end(), target_value); - - // If the lower bound is the first element, return its index. - // If the lower bound is beyond the last element, return the last index. - // If else, take the closest element. - if (lower == accumulated_delay_times_.begin()) { - return 0; - } - if (lower == accumulated_delay_times_.end()) { - return accumulated_delay_times_.size() - 1; - } - // Compare the target with the lower bound and the previous element. - auto prev = lower - 1; - bool is_closer_to_prev = (target_value - *prev) < (*lower - target_value); - - // Return the index of the closer element. - return is_closer_to_prev ? std::distance(accumulated_delay_times_.begin(), prev) - : std::distance(accumulated_delay_times_.begin(), lower); -} - -void EKFModule::accumulate_delay_time(const double dt) -{ - // Shift the delay times to the right. - std::copy_backward( - accumulated_delay_times_.begin(), accumulated_delay_times_.end() - 1, - accumulated_delay_times_.end()); - - // Add a new element (=0) and, and add delay time to the previous elements. - accumulated_delay_times_.front() = 0.0; - for (size_t i = 1; i < accumulated_delay_times_.size(); ++i) { - accumulated_delay_times_[i] += dt; - } -} - -void EKFModule::predict_with_delay(const double dt) -{ - const Eigen::MatrixXd x_curr = kalman_filter_.getLatestX(); - const Eigen::MatrixXd p_curr = kalman_filter_.getLatestP(); - - const double proc_cov_vx_d = std::pow(params_.proc_stddev_vx_c * dt, 2.0); - const double proc_cov_wz_d = std::pow(params_.proc_stddev_wz_c * dt, 2.0); - const double proc_cov_yaw_d = std::pow(params_.proc_stddev_yaw_c * dt, 2.0); - - const Vector6d x_next = predict_next_state(x_curr, dt); - const Matrix6d a = create_state_transition_matrix(x_curr, dt); - const Matrix6d q = process_noise_covariance(proc_cov_yaw_d, proc_cov_vx_d, proc_cov_wz_d); - kalman_filter_.predictWithDelay(x_next, a, q); - ekf_dt_ = dt; -} - -bool EKFModule::measurement_update_pose( - const PoseWithCovariance & pose, const rclcpp::Time & t_curr, EKFDiagnosticInfo & pose_diag_info) -{ - if (pose.header.frame_id != params_.pose_frame_id) { - warning_->warn_throttle( - fmt::format( - "pose frame_id is %s, but pose_frame is set as %s. They must be same.", - pose.header.frame_id.c_str(), params_.pose_frame_id.c_str()), - 2000); - } - const Eigen::MatrixXd x_curr = kalman_filter_.getLatestX(); - DEBUG_PRINT_MAT(x_curr.transpose()); - - constexpr int dim_y = 3; // pos_x, pos_y, yaw, depending on Pose output - - /* Calculate delay step */ - double delay_time = (t_curr - pose.header.stamp).seconds() + params_.pose_additional_delay; - if (delay_time < 0.0) { - warning_->warn_throttle(pose_delay_time_warning_message(delay_time), 1000); - } - - delay_time = std::max(delay_time, 0.0); - - const size_t delay_step = find_closest_delay_time_index(delay_time); - - pose_diag_info.delay_time = std::max(delay_time, pose_diag_info.delay_time); - pose_diag_info.delay_time_threshold = accumulated_delay_times_.back(); - if (delay_step >= params_.extend_state_step) { - pose_diag_info.is_passed_delay_gate = false; - warning_->warn_throttle( - pose_delay_step_warning_message( - pose_diag_info.delay_time, pose_diag_info.delay_time_threshold), - 2000); - return false; - } - - /* Since the kalman filter cannot handle the rotation angle directly, - offset the yaw angle so that the difference from the yaw angle that ekf holds internally - is less than 2 pi. */ - double yaw = tf2::getYaw(pose.pose.pose.orientation); - const double ekf_yaw = kalman_filter_.getXelement(delay_step * dim_x_ + IDX::YAW); - const double yaw_error = normalize_yaw(yaw - ekf_yaw); // normalize the error not to exceed 2 pi - yaw = yaw_error + ekf_yaw; - - /* Set measurement matrix */ - Eigen::MatrixXd y(dim_y, 1); - y << pose.pose.pose.position.x, pose.pose.pose.position.y, yaw; - - if (has_nan(y) || has_inf(y)) { - warning_->warn( - "[EKF] pose measurement matrix includes NaN of Inf. ignore update. check pose message."); - return false; - } - - /* Gate */ - const Eigen::Vector3d y_ekf( - kalman_filter_.getXelement(delay_step * dim_x_ + IDX::X), - kalman_filter_.getXelement(delay_step * dim_x_ + IDX::Y), ekf_yaw); - const Eigen::MatrixXd p_curr = kalman_filter_.getLatestP(); - const Eigen::MatrixXd p_y = p_curr.block(0, 0, dim_y, dim_y); - - const double distance = mahalanobis(y_ekf, y, p_y); - pose_diag_info.mahalanobis_distance = std::max(distance, pose_diag_info.mahalanobis_distance); - if (distance > params_.pose_gate_dist) { - pose_diag_info.is_passed_mahalanobis_gate = false; - warning_->warn_throttle(mahalanobis_warning_message(distance, params_.pose_gate_dist), 2000); - warning_->warn_throttle("Ignore the measurement data.", 2000); - return false; - } - - DEBUG_PRINT_MAT(y.transpose()); - DEBUG_PRINT_MAT(y_ekf.transpose()); - DEBUG_PRINT_MAT((y - y_ekf).transpose()); - - const Eigen::Matrix c = pose_measurement_matrix(); - const Eigen::Matrix3d r = - pose_measurement_covariance(pose.pose.covariance, params_.pose_smoothing_steps); - - kalman_filter_.updateWithDelay(y, c, r, static_cast(delay_step)); - - // Update Simple 1D filter with considering change of roll, pitch and height (position z) - // values due to measurement pose delay - auto pose_with_rph_delay_compensation = - compensate_rph_with_delay(pose, last_angular_velocity_, delay_time); - update_simple_1d_filters(pose_with_rph_delay_compensation, params_.pose_smoothing_steps); - - // debug - const Eigen::MatrixXd x_result = kalman_filter_.getLatestX(); - DEBUG_PRINT_MAT(x_result.transpose()); - DEBUG_PRINT_MAT((x_result - x_curr).transpose()); - - return true; -} - -geometry_msgs::msg::PoseWithCovarianceStamped EKFModule::compensate_rph_with_delay( - const PoseWithCovariance & pose, tf2::Vector3 last_angular_velocity, const double delay_time) -{ - tf2::Quaternion delta_orientation; - if (last_angular_velocity.length() > 0.0) { - delta_orientation.setRotation( - last_angular_velocity.normalized(), last_angular_velocity.length() * delay_time); - } else { - delta_orientation.setValue(0.0, 0.0, 0.0, 1.0); - } - - tf2::Quaternion prev_orientation = tf2::Quaternion( - pose.pose.pose.orientation.x, pose.pose.pose.orientation.y, pose.pose.pose.orientation.z, - pose.pose.pose.orientation.w); - - tf2::Quaternion curr_orientation; - curr_orientation = prev_orientation * delta_orientation; - curr_orientation.normalize(); - - PoseWithCovariance pose_with_delay; - pose_with_delay = pose; - pose_with_delay.header.stamp = - rclcpp::Time(pose.header.stamp) + rclcpp::Duration::from_seconds(delay_time); - pose_with_delay.pose.pose.orientation.x = curr_orientation.x(); - pose_with_delay.pose.pose.orientation.y = curr_orientation.y(); - pose_with_delay.pose.pose.orientation.z = curr_orientation.z(); - pose_with_delay.pose.pose.orientation.w = curr_orientation.w(); - - const auto rpy = autoware::universe_utils::getRPY(pose_with_delay.pose.pose.orientation); - const double delta_z = kalman_filter_.getXelement(IDX::VX) * delay_time * std::sin(-rpy.y); - pose_with_delay.pose.pose.position.z += delta_z; - - return pose_with_delay; -} - -bool EKFModule::measurement_update_twist( - const TwistWithCovariance & twist, const rclcpp::Time & t_curr, - EKFDiagnosticInfo & twist_diag_info) -{ - if (twist.header.frame_id != "base_link") { - warning_->warn_throttle("twist frame_id must be base_link", 2000); - } - - last_angular_velocity_ = tf2::Vector3(0.0, 0.0, 0.0); - - const Eigen::MatrixXd x_curr = kalman_filter_.getLatestX(); - DEBUG_PRINT_MAT(x_curr.transpose()); - - constexpr int dim_y = 2; // vx, wz - - /* Calculate delay step */ - double delay_time = (t_curr - twist.header.stamp).seconds() + params_.twist_additional_delay; - if (delay_time < 0.0) { - warning_->warn_throttle(twist_delay_time_warning_message(delay_time), 1000); - } - delay_time = std::max(delay_time, 0.0); - - const size_t delay_step = find_closest_delay_time_index(delay_time); - - twist_diag_info.delay_time = std::max(delay_time, twist_diag_info.delay_time); - twist_diag_info.delay_time_threshold = accumulated_delay_times_.back(); - if (delay_step >= params_.extend_state_step) { - twist_diag_info.is_passed_delay_gate = false; - warning_->warn_throttle( - twist_delay_step_warning_message( - twist_diag_info.delay_time, twist_diag_info.delay_time_threshold), - 2000); - return false; - } - - /* Set measurement matrix */ - Eigen::MatrixXd y(dim_y, 1); - y << twist.twist.twist.linear.x, twist.twist.twist.angular.z; - - if (has_nan(y) || has_inf(y)) { - warning_->warn( - "[EKF] twist measurement matrix includes NaN of Inf. ignore update. check twist message."); - return false; - } - - const Eigen::Vector2d y_ekf( - kalman_filter_.getXelement(delay_step * dim_x_ + IDX::VX), - kalman_filter_.getXelement(delay_step * dim_x_ + IDX::WZ)); - const Eigen::MatrixXd p_curr = kalman_filter_.getLatestP(); - const Eigen::MatrixXd p_y = p_curr.block(4, 4, dim_y, dim_y); - - const double distance = mahalanobis(y_ekf, y, p_y); - twist_diag_info.mahalanobis_distance = std::max(distance, twist_diag_info.mahalanobis_distance); - if (distance > params_.twist_gate_dist) { - twist_diag_info.is_passed_mahalanobis_gate = false; - warning_->warn_throttle(mahalanobis_warning_message(distance, params_.twist_gate_dist), 2000); - warning_->warn_throttle("Ignore the measurement data.", 2000); - return false; - } - - DEBUG_PRINT_MAT(y.transpose()); - DEBUG_PRINT_MAT(y_ekf.transpose()); - DEBUG_PRINT_MAT((y - y_ekf).transpose()); - - const Eigen::Matrix c = twist_measurement_matrix(); - const Eigen::Matrix2d r = - twist_measurement_covariance(twist.twist.covariance, params_.twist_smoothing_steps); - - kalman_filter_.updateWithDelay(y, c, r, static_cast(delay_step)); - - last_angular_velocity_ = tf2::Vector3( - twist.twist.twist.angular.x, twist.twist.twist.angular.y, twist.twist.twist.angular.z); - - // debug - const Eigen::MatrixXd x_result = kalman_filter_.getLatestX(); - DEBUG_PRINT_MAT(x_result.transpose()); - DEBUG_PRINT_MAT((x_result - x_curr).transpose()); - - return true; -} - -void EKFModule::update_simple_1d_filters( - const geometry_msgs::msg::PoseWithCovarianceStamped & pose, const size_t smoothing_step) -{ - double z = pose.pose.pose.position.z; - - const auto rpy = autoware::universe_utils::getRPY(pose.pose.pose.orientation); - - using COV_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; - double z_var = pose.pose.covariance[COV_IDX::Z_Z] * static_cast(smoothing_step); - double roll_var = pose.pose.covariance[COV_IDX::ROLL_ROLL] * static_cast(smoothing_step); - double pitch_var = - pose.pose.covariance[COV_IDX::PITCH_PITCH] * static_cast(smoothing_step); - - z_filter_.update(z, z_var, ekf_dt_); - roll_filter_.update(rpy.x, roll_var, ekf_dt_); - pitch_filter_.update(rpy.y, pitch_var, ekf_dt_); -} - -} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/src/mahalanobis.cpp b/localization/autoware_ekf_localizer/src/mahalanobis.cpp deleted file mode 100644 index f7e56674b16bd..0000000000000 --- a/localization/autoware_ekf_localizer/src/mahalanobis.cpp +++ /dev/null @@ -1,32 +0,0 @@ -// Copyright 2022 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/ekf_localizer/mahalanobis.hpp" - -namespace autoware::ekf_localizer -{ - -double squared_mahalanobis( - const Eigen::VectorXd & x, const Eigen::VectorXd & y, const Eigen::MatrixXd & C) -{ - const Eigen::VectorXd d = x - y; - return d.dot(C.inverse() * d); -} - -double mahalanobis(const Eigen::VectorXd & x, const Eigen::VectorXd & y, const Eigen::MatrixXd & C) -{ - return std::sqrt(squared_mahalanobis(x, y, C)); -} - -} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/src/measurement.cpp b/localization/autoware_ekf_localizer/src/measurement.cpp deleted file mode 100644 index 63db7d250f8d5..0000000000000 --- a/localization/autoware_ekf_localizer/src/measurement.cpp +++ /dev/null @@ -1,61 +0,0 @@ -// Copyright 2022 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/ekf_localizer/measurement.hpp" - -#include "autoware/ekf_localizer/state_index.hpp" -#include "autoware/universe_utils/ros/msg_covariance.hpp" - -namespace autoware::ekf_localizer -{ - -Eigen::Matrix pose_measurement_matrix() -{ - Eigen::Matrix c = Eigen::Matrix::Zero(); - c(0, IDX::X) = 1.0; // for pos x - c(1, IDX::Y) = 1.0; // for pos y - c(2, IDX::YAW) = 1.0; // for yaw - return c; -} - -Eigen::Matrix twist_measurement_matrix() -{ - Eigen::Matrix c = Eigen::Matrix::Zero(); - c(0, IDX::VX) = 1.0; // for vx - c(1, IDX::WZ) = 1.0; // for wz - return c; -} - -Eigen::Matrix3d pose_measurement_covariance( - const std::array & covariance, const size_t smoothing_step) -{ - Eigen::Matrix3d r; - using COV_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; - r << covariance.at(COV_IDX::X_X), covariance.at(COV_IDX::X_Y), covariance.at(COV_IDX::X_YAW), - covariance.at(COV_IDX::Y_X), covariance.at(COV_IDX::Y_Y), covariance.at(COV_IDX::Y_YAW), - covariance.at(COV_IDX::YAW_X), covariance.at(COV_IDX::YAW_Y), covariance.at(COV_IDX::YAW_YAW); - return r * static_cast(smoothing_step); -} - -Eigen::Matrix2d twist_measurement_covariance( - const std::array & covariance, const size_t smoothing_step) -{ - Eigen::Matrix2d r; - using COV_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; - r << covariance.at(COV_IDX::X_X), covariance.at(COV_IDX::X_YAW), covariance.at(COV_IDX::YAW_X), - covariance.at(COV_IDX::YAW_YAW); - return r * static_cast(smoothing_step); -} - -} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/src/state_transition.cpp b/localization/autoware_ekf_localizer/src/state_transition.cpp deleted file mode 100644 index f6a50b5839ec4..0000000000000 --- a/localization/autoware_ekf_localizer/src/state_transition.cpp +++ /dev/null @@ -1,102 +0,0 @@ -// Copyright 2022 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/ekf_localizer/state_transition.hpp" - -#include "autoware/ekf_localizer/matrix_types.hpp" -#include "autoware/ekf_localizer/state_index.hpp" - -#include - -namespace autoware::ekf_localizer -{ - -double normalize_yaw(const double & yaw) -{ - // FIXME(IshitaTakeshi) I think the computation here can be simplified - // FIXME(IshitaTakeshi) Rename the function. This is not normalization - return std::atan2(std::sin(yaw), std::cos(yaw)); -} - -/* == Nonlinear model == - * - * x_{k+1} = x_k + vx_k * cos(yaw_k + b_k) * dt - * y_{k+1} = y_k + vx_k * sin(yaw_k + b_k) * dt - * yaw_{k+1} = yaw_k + (wz_k) * dt - * b_{k+1} = b_k - * vx_{k+1} = vx_k - * wz_{k+1} = wz_k - * - * (b_k : yaw_bias_k) - */ - -Vector6d predict_next_state(const Vector6d & X_curr, const double dt) -{ - const double x = X_curr(IDX::X); - const double y = X_curr(IDX::Y); - const double yaw = X_curr(IDX::YAW); - const double yaw_bias = X_curr(IDX::YAWB); - const double vx = X_curr(IDX::VX); - const double wz = X_curr(IDX::WZ); - - Vector6d x_next; - x_next(IDX::X) = x + vx * std::cos(yaw + yaw_bias) * dt; // dx = v * cos(yaw) - x_next(IDX::Y) = y + vx * std::sin(yaw + yaw_bias) * dt; // dy = v * sin(yaw) - x_next(IDX::YAW) = normalize_yaw(yaw + wz * dt); // dyaw = omega + omega_bias - x_next(IDX::YAWB) = yaw_bias; - x_next(IDX::VX) = vx; - x_next(IDX::WZ) = wz; - return x_next; -} - -/* == Linearized model == - * - * A = [ 1, 0, -vx*sin(yaw+b)*dt, -vx*sin(yaw+b)*dt, cos(yaw+b)*dt, 0] - * [ 0, 1, vx*cos(yaw+b)*dt, vx*cos(yaw+b)*dt, sin(yaw+b)*dt, 0] - * [ 0, 0, 1, 0, 0, dt] - * [ 0, 0, 0, 1, 0, 0] - * [ 0, 0, 0, 0, 1, 0] - * [ 0, 0, 0, 0, 0, 1] - */ -Matrix6d create_state_transition_matrix(const Vector6d & X_curr, const double dt) -{ - const double yaw = X_curr(IDX::YAW); - const double yaw_bias = X_curr(IDX::YAWB); - const double vx = X_curr(IDX::VX); - - Matrix6d a = Matrix6d::Identity(); - a(IDX::X, IDX::YAW) = -vx * sin(yaw + yaw_bias) * dt; - a(IDX::X, IDX::YAWB) = -vx * sin(yaw + yaw_bias) * dt; - a(IDX::X, IDX::VX) = cos(yaw + yaw_bias) * dt; - a(IDX::Y, IDX::YAW) = vx * cos(yaw + yaw_bias) * dt; - a(IDX::Y, IDX::YAWB) = vx * cos(yaw + yaw_bias) * dt; - a(IDX::Y, IDX::VX) = sin(yaw + yaw_bias) * dt; - a(IDX::YAW, IDX::WZ) = dt; - return a; -} - -Matrix6d process_noise_covariance( - const double proc_cov_yaw_d, const double proc_cov_vx_d, const double proc_cov_wz_d) -{ - Matrix6d q = Matrix6d::Zero(); - q(IDX::X, IDX::X) = 0.0; - q(IDX::Y, IDX::Y) = 0.0; - q(IDX::YAW, IDX::YAW) = proc_cov_yaw_d; // for yaw - q(IDX::YAWB, IDX::YAWB) = 0.0; - q(IDX::VX, IDX::VX) = proc_cov_vx_d; // for vx - q(IDX::WZ, IDX::WZ) = proc_cov_wz_d; // for wz - return q; -} - -} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/src/warning_message.cpp b/localization/autoware_ekf_localizer/src/warning_message.cpp deleted file mode 100644 index 0c1e127747365..0000000000000 --- a/localization/autoware_ekf_localizer/src/warning_message.cpp +++ /dev/null @@ -1,60 +0,0 @@ -// Copyright 2023 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/ekf_localizer/warning_message.hpp" - -#include - -#include - -namespace autoware::ekf_localizer -{ - -std::string pose_delay_step_warning_message( - const double delay_time, const double delay_time_threshold) -{ - const std::string s = - "Pose delay exceeds the compensation limit, ignored. " - "delay: {:.3f}[s], limit: {:.3f}[s]"; - return fmt::format(s, delay_time, delay_time_threshold); -} - -std::string twist_delay_step_warning_message( - const double delay_time, const double delay_time_threshold) -{ - const std::string s = - "Twist delay exceeds the compensation limit, ignored. " - "delay: {:.3f}[s], limit: {:.3f}[s]"; - return fmt::format(s, delay_time, delay_time_threshold); -} - -std::string pose_delay_time_warning_message(const double delay_time) -{ - const std::string s = "Pose time stamp is inappropriate, set delay to 0[s]. delay = {:.3f}"; - return fmt::format(s, delay_time); -} - -std::string twist_delay_time_warning_message(const double delay_time) -{ - const std::string s = "Twist time stamp is inappropriate, set delay to 0[s]. delay = {:.3f}"; - return fmt::format(s, delay_time); -} - -std::string mahalanobis_warning_message(const double distance, const double max_distance) -{ - const std::string s = "The Mahalanobis distance {:.4f} is over the limit {:.4f}."; - return fmt::format(s, distance, max_distance); -} - -} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/test/test_aged_object_queue.cpp b/localization/autoware_ekf_localizer/test/test_aged_object_queue.cpp deleted file mode 100644 index dc9ef008335ed..0000000000000 --- a/localization/autoware_ekf_localizer/test/test_aged_object_queue.cpp +++ /dev/null @@ -1,108 +0,0 @@ -// Copyright 2023 The Autoware Contributors -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/ekf_localizer/aged_object_queue.hpp" - -#include - -#include - -namespace autoware::ekf_localizer -{ - -TEST(AgedObjectQueue, DiscardsObjectWhenAgeReachesMaximum) -{ - AgedObjectQueue queue(3); - - queue.push("a"); - EXPECT_EQ(queue.size(), 1U); - - queue.pop_increment_age(); // age = 1 - EXPECT_EQ(queue.size(), 1U); - - queue.pop_increment_age(); // age = 2 - EXPECT_EQ(queue.size(), 1U); - - queue.pop_increment_age(); // age = 3 - EXPECT_EQ(queue.size(), 0U); -} - -TEST(AgedObjectQueue, MultipleObjects) -{ - AgedObjectQueue queue(3); - - queue.push("a"); - EXPECT_EQ(queue.size(), 1U); - EXPECT_EQ(queue.pop_increment_age(), std::string{"a"}); // age of a = 1 - EXPECT_EQ(queue.size(), 1U); - EXPECT_EQ(queue.pop_increment_age(), std::string{"a"}); // age of a = 2 - - queue.push("b"); - - EXPECT_EQ(queue.pop_increment_age(), std::string{"a"}); // age of a = 3 - EXPECT_EQ(queue.size(), 1U); - - EXPECT_EQ(queue.pop_increment_age(), std::string{"b"}); // age of b = 1 - EXPECT_EQ(queue.size(), 1U); - - EXPECT_EQ(queue.pop_increment_age(), std::string{"b"}); // age of b = 2 - EXPECT_EQ(queue.size(), 1U); - - EXPECT_EQ(queue.pop_increment_age(), std::string{"b"}); // age of b = 3 - EXPECT_EQ(queue.size(), 0U); -} - -TEST(AgedObjectQueue, Empty) -{ - AgedObjectQueue queue(2); - - EXPECT_TRUE(queue.empty()); - - queue.push("a"); - - EXPECT_FALSE(queue.empty()); - - queue.pop_increment_age(); - queue.pop_increment_age(); - - EXPECT_TRUE(queue.empty()); -} - -TEST(AgedObjectQueue, Clear) -{ - AgedObjectQueue queue(3); - - queue.push("a"); - queue.push("b"); - - EXPECT_EQ(queue.size(), 2U); - - queue.clear(); - - EXPECT_EQ(queue.size(), 0U); -} - -TEST(AgedObjectQueue, Back) -{ - AgedObjectQueue queue(3); - - queue.push("a"); - - EXPECT_EQ(queue.back(), std::string{"a"}); - queue.push("b"); - - EXPECT_EQ(queue.back(), std::string{"b"}); -} - -} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/test/test_covariance.cpp b/localization/autoware_ekf_localizer/test/test_covariance.cpp deleted file mode 100644 index cab09367d6340..0000000000000 --- a/localization/autoware_ekf_localizer/test/test_covariance.cpp +++ /dev/null @@ -1,84 +0,0 @@ -// Copyright 2022 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/ekf_localizer/covariance.hpp" - -#include - -namespace autoware::ekf_localizer -{ - -TEST(EKFCovarianceToPoseMessageCovariance, SmokeTest) -{ - { - Matrix6d p = Matrix6d::Zero(); - p(0, 0) = 1.; - p(0, 1) = 2.; - p(0, 2) = 3.; - p(1, 0) = 4.; - p(1, 1) = 5.; - p(1, 2) = 6.; - p(2, 0) = 7.; - p(2, 1) = 8.; - p(2, 2) = 9.; - - std::array covariance = ekf_covariance_to_pose_message_covariance(p); - EXPECT_EQ(covariance[0], 1.); - EXPECT_EQ(covariance[1], 2.); - EXPECT_EQ(covariance[5], 3.); - EXPECT_EQ(covariance[6], 4.); - EXPECT_EQ(covariance[7], 5.); - EXPECT_EQ(covariance[11], 6.); - EXPECT_EQ(covariance[30], 7.); - EXPECT_EQ(covariance[31], 8.); - EXPECT_EQ(covariance[35], 9.); - } - - // ensure other elements are zero - { - Matrix6d p = Matrix6d::Zero(); - std::array covariance = ekf_covariance_to_pose_message_covariance(p); - for (double e : covariance) { - EXPECT_EQ(e, 0.); - } - } -} - -TEST(EKFCovarianceToTwistMessageCovariance, SmokeTest) -{ - { - Matrix6d p = Matrix6d::Zero(); - p(4, 4) = 1.; - p(4, 5) = 2.; - p(5, 4) = 3.; - p(5, 5) = 4.; - - std::array covariance = ekf_covariance_to_twist_message_covariance(p); - EXPECT_EQ(covariance[0], 1.); - EXPECT_EQ(covariance[5], 2.); - EXPECT_EQ(covariance[30], 3.); - EXPECT_EQ(covariance[35], 4.); - } - - // ensure other elements are zero - { - Matrix6d p = Matrix6d::Zero(); - std::array covariance = ekf_covariance_to_twist_message_covariance(p); - for (double e : covariance) { - EXPECT_EQ(e, 0.); - } - } -} - -} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/test/test_diagnostics.cpp b/localization/autoware_ekf_localizer/test/test_diagnostics.cpp deleted file mode 100644 index 5ce39df484e98..0000000000000 --- a/localization/autoware_ekf_localizer/test/test_diagnostics.cpp +++ /dev/null @@ -1,213 +0,0 @@ -// Copyright 2023 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/ekf_localizer/diagnostics.hpp" - -#include - -#include -#include - -namespace autoware::ekf_localizer -{ - -TEST(TestEkfDiagnostics, check_process_activated) -{ - diagnostic_msgs::msg::DiagnosticStatus stat; - - bool is_activated = true; - stat = check_process_activated(is_activated); - EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); - - is_activated = false; - stat = check_process_activated(is_activated); - EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); -} - -TEST(TestEkfDiagnostics, check_set_initialpose) -{ - diagnostic_msgs::msg::DiagnosticStatus stat; - - bool is_set_initialpose = true; - stat = check_set_initialpose(is_set_initialpose); - EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); - - is_set_initialpose = false; - stat = check_set_initialpose(is_set_initialpose); - EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); -} - -TEST(TestEkfDiagnostics, check_measurement_updated) -{ - diagnostic_msgs::msg::DiagnosticStatus stat; - - const std::string measurement_type = "pose"; // not effect for stat.level - const size_t no_update_count_threshold_warn = 50; - const size_t no_update_count_threshold_error = 250; - - size_t no_update_count = 0; - stat = check_measurement_updated( - measurement_type, no_update_count, no_update_count_threshold_warn, - no_update_count_threshold_error); - EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); - - no_update_count = 1; - stat = check_measurement_updated( - measurement_type, no_update_count, no_update_count_threshold_warn, - no_update_count_threshold_error); - EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); - - no_update_count = 49; - stat = check_measurement_updated( - measurement_type, no_update_count, no_update_count_threshold_warn, - no_update_count_threshold_error); - EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); - - no_update_count = 50; - stat = check_measurement_updated( - measurement_type, no_update_count, no_update_count_threshold_warn, - no_update_count_threshold_error); - EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); - - no_update_count = 249; - stat = check_measurement_updated( - measurement_type, no_update_count, no_update_count_threshold_warn, - no_update_count_threshold_error); - EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); - - no_update_count = 250; - stat = check_measurement_updated( - measurement_type, no_update_count, no_update_count_threshold_warn, - no_update_count_threshold_error); - EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR); -} - -TEST(TestEkfDiagnostics, check_measurement_queue_size) -{ - diagnostic_msgs::msg::DiagnosticStatus stat; - - const std::string measurement_type = "pose"; // not effect for stat.level - - size_t queue_size = 0; // not effect for stat.level - stat = check_measurement_queue_size(measurement_type, queue_size); - EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); - - queue_size = 1; // not effect for stat.level - stat = check_measurement_queue_size(measurement_type, queue_size); - EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); -} - -TEST(TestEkfDiagnostics, check_measurement_delay_gate) -{ - diagnostic_msgs::msg::DiagnosticStatus stat; - - const std::string measurement_type = "pose"; // not effect for stat.level - const double delay_time = 0.1; // not effect for stat.level - const double delay_time_threshold = 1.0; // not effect for stat.level - - bool is_passed_delay_gate = true; - stat = check_measurement_delay_gate( - measurement_type, is_passed_delay_gate, delay_time, delay_time_threshold); - EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); - - is_passed_delay_gate = false; - stat = check_measurement_delay_gate( - measurement_type, is_passed_delay_gate, delay_time, delay_time_threshold); - EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); -} - -TEST(TestEkfDiagnostics, check_measurement_mahalanobis_gate) -{ - diagnostic_msgs::msg::DiagnosticStatus stat; - - const std::string measurement_type = "pose"; // not effect for stat.level - const double mahalanobis_distance = 0.1; // not effect for stat.level - const double mahalanobis_distance_threshold = 1.0; // not effect for stat.level - - bool is_passed_mahalanobis_gate = true; - stat = check_measurement_mahalanobis_gate( - measurement_type, is_passed_mahalanobis_gate, mahalanobis_distance, - mahalanobis_distance_threshold); - EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); - - is_passed_mahalanobis_gate = false; - stat = check_measurement_mahalanobis_gate( - measurement_type, is_passed_mahalanobis_gate, mahalanobis_distance, - mahalanobis_distance_threshold); - EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); -} - -TEST(TestLocalizationErrorMonitorDiagnostics, merge_diagnostic_status) -{ - diagnostic_msgs::msg::DiagnosticStatus merged_stat; - std::vector stat_array(2); - - stat_array.at(0).level = diagnostic_msgs::msg::DiagnosticStatus::OK; - stat_array.at(0).message = "OK"; - stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::OK; - stat_array.at(1).message = "OK"; - merged_stat = merge_diagnostic_status(stat_array); - EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); - EXPECT_EQ(merged_stat.message, "OK"); - - stat_array.at(0).level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - stat_array.at(0).message = "WARN0"; - stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::OK; - stat_array.at(1).message = "OK"; - merged_stat = merge_diagnostic_status(stat_array); - EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); - EXPECT_EQ(merged_stat.message, "WARN0"); - - stat_array.at(0).level = diagnostic_msgs::msg::DiagnosticStatus::OK; - stat_array.at(0).message = "OK"; - stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - stat_array.at(1).message = "WARN1"; - merged_stat = merge_diagnostic_status(stat_array); - EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); - EXPECT_EQ(merged_stat.message, "WARN1"); - - stat_array.at(0).level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - stat_array.at(0).message = "WARN0"; - stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - stat_array.at(1).message = "WARN1"; - merged_stat = merge_diagnostic_status(stat_array); - EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); - EXPECT_EQ(merged_stat.message, "WARN0; WARN1"); - - stat_array.at(0).level = diagnostic_msgs::msg::DiagnosticStatus::OK; - stat_array.at(0).message = "OK"; - stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; - stat_array.at(1).message = "ERROR1"; - merged_stat = merge_diagnostic_status(stat_array); - EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR); - EXPECT_EQ(merged_stat.message, "ERROR1"); - - stat_array.at(0).level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - stat_array.at(0).message = "WARN0"; - stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; - stat_array.at(1).message = "ERROR1"; - merged_stat = merge_diagnostic_status(stat_array); - EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR); - EXPECT_EQ(merged_stat.message, "WARN0; ERROR1"); - - stat_array.at(0).level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; - stat_array.at(0).message = "ERROR0"; - stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; - stat_array.at(1).message = "ERROR1"; - merged_stat = merge_diagnostic_status(stat_array); - EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR); - EXPECT_EQ(merged_stat.message, "ERROR0; ERROR1"); -} - -} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/test/test_ekf_localizer_launch.py b/localization/autoware_ekf_localizer/test/test_ekf_localizer_launch.py deleted file mode 100644 index 1db0863636b04..0000000000000 --- a/localization/autoware_ekf_localizer/test/test_ekf_localizer_launch.py +++ /dev/null @@ -1,170 +0,0 @@ -#!/usr/bin/env python3 - -# Copyright 2023 TIER IV, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -import os -import time -import unittest - -from ament_index_python import get_package_share_directory -from geometry_msgs.msg import PoseWithCovarianceStamped -import launch -from launch.actions import IncludeLaunchDescription -from launch.launch_description_sources import AnyLaunchDescriptionSource -from launch.logging import get_logger -import launch_testing -from nav_msgs.msg import Odometry -import pytest -import rclpy -from std_srvs.srv import SetBool - -logger = get_logger(__name__) - - -@pytest.mark.launch_test -def generate_test_description(): - test_ekf_localizer_launch_file = os.path.join( - get_package_share_directory("autoware_ekf_localizer"), - "launch", - "ekf_localizer.launch.xml", - ) - ekf_localizer = IncludeLaunchDescription( - AnyLaunchDescriptionSource(test_ekf_localizer_launch_file), - ) - - return launch.LaunchDescription( - [ - ekf_localizer, - # Start tests right away - no need to wait for anything - launch_testing.actions.ReadyToTest(), - ] - ) - - -class TestEKFLocalizer(unittest.TestCase): - @classmethod - def setUpClass(cls): - # Initialize the ROS context for the test node - rclpy.init() - - @classmethod - def tearDownClass(cls): - # Shutdown the ROS context - rclpy.shutdown() - - def setUp(self): - # Create a ROS node for tests - self.test_node = rclpy.create_node("test_node") - self.evaluation_time = 0.2 # 200ms - - def tearDown(self): - self.test_node.destroy_node() - - @staticmethod - def print_message(stat): - logger.debug("===========================") - logger.debug(stat) - - def test_node_link(self): - # Trigger ekf_localizer to activate the node - cli_trigger = self.test_node.create_client(SetBool, "/trigger_node") - while not cli_trigger.wait_for_service(timeout_sec=1.0): - continue - - request = SetBool.Request() - request.data = True - future = cli_trigger.call_async(request) - rclpy.spin_until_future_complete(self.test_node, future) - - if future.result() is not None: - self.test_node.get_logger().info("Result of bool service: %s" % future.result().message) - else: - self.test_node.get_logger().error( - "Exception while calling service: %r" % future.exception() - ) - - # Send initial pose - pub_init_pose = self.test_node.create_publisher( - PoseWithCovarianceStamped, "/initialpose3d", 10 - ) - init_pose = PoseWithCovarianceStamped() - init_pose.header.frame_id = "map" - init_pose.pose.pose.position.x = 0.0 - init_pose.pose.pose.position.y = 0.0 - init_pose.pose.pose.position.z = 0.0 - init_pose.pose.pose.orientation.x = 0.0 - init_pose.pose.pose.orientation.y = 0.0 - init_pose.pose.pose.orientation.z = 0.0 - init_pose.pose.pose.orientation.w = 1.0 - init_pose.pose.covariance = [ - 0.01, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.01, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.01, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.01, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.01, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.01, - ] - pub_init_pose.publish(init_pose) - - # Receive Odometry - msg_buffer = [] - self.test_node.create_subscription( - Odometry, "/ekf_odom", lambda msg: msg_buffer.append(msg), 10 - ) - - # Wait until the node publishes some topic - end_time = time.time() + self.evaluation_time - while time.time() < end_time: - rclpy.spin_once(self.test_node, timeout_sec=0.1) - - # Check if the EKF outputs some Odometry - self.assertTrue(len(msg_buffer) > 0) - - -@launch_testing.post_shutdown_test() -class TestProcessOutput(unittest.TestCase): - def test_exit_code(self, proc_info): - # Check that process exits with code 0: no error - launch_testing.asserts.assertExitCodes(proc_info) diff --git a/localization/autoware_ekf_localizer/test/test_ekf_localizer_mahalanobis.py b/localization/autoware_ekf_localizer/test/test_ekf_localizer_mahalanobis.py deleted file mode 100644 index 29afd4953520e..0000000000000 --- a/localization/autoware_ekf_localizer/test/test_ekf_localizer_mahalanobis.py +++ /dev/null @@ -1,229 +0,0 @@ -#!/usr/bin/env python3 - -# Copyright 2023 TIER IV, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -import os -import time -import unittest - -from ament_index_python import get_package_share_directory -from geometry_msgs.msg import PoseWithCovarianceStamped -import launch -from launch.actions import IncludeLaunchDescription -from launch.launch_description_sources import AnyLaunchDescriptionSource -from launch.logging import get_logger -import launch_testing -from nav_msgs.msg import Odometry -import pytest -import rclpy -from std_srvs.srv import SetBool - -logger = get_logger(__name__) - - -@pytest.mark.launch_test -def generate_test_description(): - test_ekf_localizer_launch_file = os.path.join( - get_package_share_directory("autoware_ekf_localizer"), - "launch", - "ekf_localizer.launch.xml", - ) - ekf_localizer = IncludeLaunchDescription( - AnyLaunchDescriptionSource(test_ekf_localizer_launch_file), - ) - - return launch.LaunchDescription( - [ - ekf_localizer, - # Start tests right away - no need to wait for anything - launch_testing.actions.ReadyToTest(), - ] - ) - - -class TestEKFLocalizer(unittest.TestCase): - @classmethod - def setUpClass(cls): - # Initialize the ROS context for the test node - rclpy.init() - - @classmethod - def tearDownClass(cls): - # Shutdown the ROS context - rclpy.shutdown() - - def setUp(self): - # Create a ROS node for tests - self.test_node = rclpy.create_node("test_node") - self.evaluation_time = 0.2 # 200ms - - def tearDown(self): - self.test_node.destroy_node() - - @staticmethod - def print_message(stat): - logger.debug("===========================") - logger.debug(stat) - - def test_node_link(self): - # Trigger ekf_localizer to activate the node - cli_trigger = self.test_node.create_client(SetBool, "/trigger_node") - while not cli_trigger.wait_for_service(timeout_sec=1.0): - continue - - request = SetBool.Request() - request.data = True - future = cli_trigger.call_async(request) - rclpy.spin_until_future_complete(self.test_node, future) - - if future.result() is not None: - self.test_node.get_logger().info("Result of bool service: %s" % future.result().message) - else: - self.test_node.get_logger().error( - "Exception while calling service: %r" % future.exception() - ) - - # Send initial pose - pub_init_pose = self.test_node.create_publisher( - PoseWithCovarianceStamped, "/initialpose3d", 10 - ) - init_pose = PoseWithCovarianceStamped() - init_pose.header.frame_id = "map" - init_pose.pose.pose.position.x = 0.0 - init_pose.pose.pose.position.y = 0.0 - init_pose.pose.pose.position.z = 0.0 - init_pose.pose.pose.orientation.x = 0.0 - init_pose.pose.pose.orientation.y = 0.0 - init_pose.pose.pose.orientation.z = 0.0 - init_pose.pose.pose.orientation.w = 1.0 - init_pose.pose.covariance = [ - 0.01, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.01, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.01, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.01, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.01, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.01, - ] - pub_init_pose.publish(init_pose) - rclpy.spin_once(self.test_node, timeout_sec=0.1) - - # Send pose that should be ignored by mahalanobis gate in ekf_localizer - pub_pose = self.test_node.create_publisher( - PoseWithCovarianceStamped, "/in_pose_with_covariance", 10 - ) - pose = PoseWithCovarianceStamped() - pose.header.frame_id = "map" - pose.pose.pose.position.x = 1000000.0 - pose.pose.pose.position.y = 1000000.0 - pose.pose.pose.position.z = 10.0 - pose.pose.pose.orientation.x = 0.0 - pose.pose.pose.orientation.y = 0.0 - pose.pose.pose.orientation.z = 0.0 - pose.pose.pose.orientation.w = 1.0 - pose.pose.covariance = [ - 0.01, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.01, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.01, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.01, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.01, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.01, - ] - pub_pose.publish(pose) - - # Receive Odometry - msg_buffer = [] - self.test_node.create_subscription( - Odometry, "/ekf_odom", lambda msg: msg_buffer.append(msg), 10 - ) - - # Wait until the node publishes some topic - end_time = time.time() + self.evaluation_time - while time.time() < end_time: - rclpy.spin_once(self.test_node, timeout_sec=0.1) - - # Check if the EKF outputs some Odometry - self.assertTrue(len(msg_buffer) > 0) - - # Assert msg to be at the origin - self.assertEqual(msg_buffer[-1].pose.pose.position.x, 0.0) - self.assertEqual(msg_buffer[-1].pose.pose.position.y, 0.0) - self.assertEqual(msg_buffer[-1].pose.pose.position.z, 0.0) - - -@launch_testing.post_shutdown_test() -class TestProcessOutput(unittest.TestCase): - def test_exit_code(self, proc_info): - # Check that process exits with code 0: no error - launch_testing.asserts.assertExitCodes(proc_info) diff --git a/localization/autoware_ekf_localizer/test/test_mahalanobis.cpp b/localization/autoware_ekf_localizer/test/test_mahalanobis.cpp deleted file mode 100644 index 3f867470a3c63..0000000000000 --- a/localization/autoware_ekf_localizer/test/test_mahalanobis.cpp +++ /dev/null @@ -1,66 +0,0 @@ -// Copyright 2022 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/ekf_localizer/mahalanobis.hpp" - -#include - -namespace autoware::ekf_localizer -{ - -constexpr double tolerance = 1e-8; - -TEST(squared_mahalanobis, SmokeTest) -{ - { - Eigen::Vector2d x(0, 1); - Eigen::Vector2d y(3, 2); - Eigen::Matrix2d c; - c << 10, 0, 0, 10; - - EXPECT_NEAR(squared_mahalanobis(x, y, c), 1.0, tolerance); - } - - { - Eigen::Vector2d x(4, 1); - Eigen::Vector2d y(1, 5); - Eigen::Matrix2d c; - c << 5, 0, 0, 5; - - EXPECT_NEAR(squared_mahalanobis(x, y, c), 5.0, tolerance); - } -} - -TEST(mahalanobis, SmokeTest) -{ - { - Eigen::Vector2d x(0, 1); - Eigen::Vector2d y(3, 2); - Eigen::Matrix2d c; - c << 10, 0, 0, 10; - - EXPECT_NEAR(mahalanobis(x, y, c), 1.0, tolerance); - } - - { - Eigen::Vector2d x(4, 1); - Eigen::Vector2d y(1, 5); - Eigen::Matrix2d c; - c << 5, 0, 0, 5; - - EXPECT_NEAR(mahalanobis(x, y, c), std::sqrt(5.0), tolerance); - } -} - -} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/test/test_measurement.cpp b/localization/autoware_ekf_localizer/test/test_measurement.cpp deleted file mode 100644 index 99dcc1744c33d..0000000000000 --- a/localization/autoware_ekf_localizer/test/test_measurement.cpp +++ /dev/null @@ -1,86 +0,0 @@ -// Copyright 2022 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/ekf_localizer/measurement.hpp" - -#include - -namespace autoware::ekf_localizer -{ - -TEST(Measurement, pose_measurement_matrix) -{ - const Eigen::Matrix m = pose_measurement_matrix(); - Eigen::Matrix expected; - expected << 1, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0; - EXPECT_EQ((m - expected).norm(), 0); -} - -TEST(Measurement, twist_measurement_matrix) -{ - const Eigen::Matrix m = twist_measurement_matrix(); - Eigen::Matrix expected; - expected << 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 1; - EXPECT_EQ((m - expected).norm(), 0); -} - -TEST(Measurement, pose_measurement_covariance) -{ - { - const std::array covariance = {1, 2, 0, 0, 0, 3, 4, 5, 0, 0, 0, 6, - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 7, 8, 0, 0, 0, 9}; - - const Eigen::Matrix3d m = pose_measurement_covariance(covariance, 2); - - Eigen::Matrix3d expected; - expected << 2, 4, 6, 8, 10, 12, 14, 16, 18; - - EXPECT_EQ((m - expected).norm(), 0.); - } - - { - // Make sure that other elements are not changed - std::array covariance{}; - covariance.fill(0); - const Eigen::Matrix3d m = pose_measurement_covariance(covariance, 2.); - EXPECT_EQ(m.norm(), 0); - } -} - -TEST(Measurement, twist_measurement_covariance) -{ - { - const std::array covariance = {1, 0, 0, 0, 0, 2, 0, 0, 0, 0, 0, 6, - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 3, 0, 0, 0, 0, 4}; - - const Eigen::Matrix2d m = twist_measurement_covariance(covariance, 2); - - Eigen::Matrix2d expected; - expected << 2, 4, 6, 8; - - EXPECT_EQ((m - expected).norm(), 0.); - } - - { - // Make sure that other elements are not changed - std::array covariance{}; - covariance.fill(0); - const Eigen::Matrix2d m = twist_measurement_covariance(covariance, 2.); - EXPECT_EQ(m.norm(), 0); - } -} - -} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/test/test_numeric.cpp b/localization/autoware_ekf_localizer/test/test_numeric.cpp deleted file mode 100644 index 080ce01f31770..0000000000000 --- a/localization/autoware_ekf_localizer/test/test_numeric.cpp +++ /dev/null @@ -1,54 +0,0 @@ -// Copyright 2022 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/ekf_localizer/numeric.hpp" - -#include - -#include - -#include - -namespace autoware::ekf_localizer -{ - -TEST(Numeric, has_nan) -{ - const Eigen::VectorXd empty(0); - const double inf = std::numeric_limits::infinity(); - const double nan = std::nan(""); - - EXPECT_FALSE(has_nan(empty)); - EXPECT_FALSE(has_nan(Eigen::Vector3d(0., 0., 1.))); - EXPECT_FALSE(has_nan(Eigen::Vector3d(1e16, 0., 1.))); - EXPECT_FALSE(has_nan(Eigen::Vector3d(0., 1., inf))); - - EXPECT_TRUE(has_nan(Eigen::Vector3d(nan, 1., 0.))); -} - -TEST(Numeric, has_inf) -{ - const Eigen::VectorXd empty(0); - const double inf = std::numeric_limits::infinity(); - const double nan = std::nan(""); - - EXPECT_FALSE(has_inf(empty)); - EXPECT_FALSE(has_inf(Eigen::Vector3d(0., 0., 1.))); - EXPECT_FALSE(has_inf(Eigen::Vector3d(1e16, 0., 1.))); - EXPECT_FALSE(has_inf(Eigen::Vector3d(nan, 1., 0.))); - - EXPECT_TRUE(has_inf(Eigen::Vector3d(0., 1., inf))); -} - -} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/test/test_state_transition.cpp b/localization/autoware_ekf_localizer/test/test_state_transition.cpp deleted file mode 100644 index 667c6b5ef2df8..0000000000000 --- a/localization/autoware_ekf_localizer/test/test_state_transition.cpp +++ /dev/null @@ -1,101 +0,0 @@ -// Copyright 2018-2019 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#define _USE_MATH_DEFINES -#include "autoware/ekf_localizer/state_index.hpp" -#include "autoware/ekf_localizer/state_transition.hpp" - -#include - -#include - -namespace autoware::ekf_localizer -{ - -TEST(StateTransition, normalize_yaw) -{ - const double tolerance = 1e-6; - EXPECT_NEAR(normalize_yaw(M_PI * 4 / 3), -M_PI * 2 / 3, tolerance); - EXPECT_NEAR(normalize_yaw(-M_PI * 4 / 3), M_PI * 2 / 3, tolerance); - EXPECT_NEAR(normalize_yaw(M_PI * 9 / 2), M_PI * 1 / 2, tolerance); - EXPECT_NEAR(normalize_yaw(M_PI * 4), M_PI * 0, tolerance); -} - -TEST(predict_next_state, predict_next_state) -{ - // This function is the definition of state transition so we just check - // if the calculation is done according to the formula - Vector6d x_curr; - x_curr(0) = 2.; - x_curr(1) = 3.; - x_curr(2) = M_PI / 2.; - x_curr(3) = M_PI / 4.; - x_curr(4) = 10.; - x_curr(5) = 2. * M_PI / 3.; - - const double dt = 0.5; - - const Vector6d x_next = predict_next_state(x_curr, dt); - - const double tolerance = 1e-10; - EXPECT_NEAR(x_next(0), 2. + 10. * std::cos(M_PI / 2. + M_PI / 4.) * 0.5, tolerance); - EXPECT_NEAR(x_next(1), 3. + 10. * std::sin(M_PI / 2. + M_PI / 4.) * 0.5, tolerance); - EXPECT_NEAR(x_next(2), normalize_yaw(M_PI / 2. + M_PI / 3.), tolerance); - EXPECT_NEAR(x_next(3), x_curr(3), tolerance); - EXPECT_NEAR(x_next(4), x_curr(4), tolerance); - EXPECT_NEAR(x_next(5), x_curr(5), tolerance); -} - -TEST(create_state_transition_matrix, NumericalApproximation) -{ - // The transition matrix A = df / dx - // We check if df = A * dx approximates f(x + dx) - f(x) - - { - // check around x = 0 - const double dt = 0.1; - const Vector6d dx = 0.1 * Vector6d::Ones(); - const Vector6d x = Vector6d::Zero(); - - const Matrix6d a = create_state_transition_matrix(x, dt); - const Vector6d df = predict_next_state(x + dx, dt) - predict_next_state(x, dt); - - EXPECT_LT((df - a * dx).norm(), 2e-3); - } - - { - // check around random x - const double dt = 0.1; - const Vector6d dx = 0.1 * Vector6d::Ones(); - const Vector6d x = (Vector6d() << 0.1, 0.2, 0.1, 0.4, 0.1, 0.3).finished(); - - const Matrix6d a = create_state_transition_matrix(x, dt); - const Vector6d df = predict_next_state(x + dx, dt) - predict_next_state(x, dt); - - EXPECT_LT((df - a * dx).norm(), 5e-3); - } -} - -TEST(process_noise_covariance, process_noise_covariance) -{ - const Matrix6d q = process_noise_covariance(1., 2., 3.); - EXPECT_EQ(q(2, 2), 1.); // for yaw - EXPECT_EQ(q(4, 4), 2.); // for vx - EXPECT_EQ(q(5, 5), 3.); // for wz - - // Make sure other elements are zero - EXPECT_EQ(process_noise_covariance(0, 0, 0).norm(), 0.); -} - -} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/test/test_string.cpp b/localization/autoware_ekf_localizer/test/test_string.cpp deleted file mode 100644 index b1fae1f88b74b..0000000000000 --- a/localization/autoware_ekf_localizer/test/test_string.cpp +++ /dev/null @@ -1,31 +0,0 @@ -// Copyright 2023 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/ekf_localizer/string.hpp" - -#include - -namespace autoware::ekf_localizer -{ - -TEST(erase_leading_slash, SmokeTest) -{ - EXPECT_EQ(erase_leading_slash("/topic"), "topic"); - EXPECT_EQ(erase_leading_slash("topic"), "topic"); // do nothing - - EXPECT_EQ(erase_leading_slash(""), ""); - EXPECT_EQ(erase_leading_slash("/"), ""); -} - -} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/test/test_warning_message.cpp b/localization/autoware_ekf_localizer/test/test_warning_message.cpp deleted file mode 100644 index 791e86c050352..0000000000000 --- a/localization/autoware_ekf_localizer/test/test_warning_message.cpp +++ /dev/null @@ -1,67 +0,0 @@ -// Copyright 2023 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware/ekf_localizer/warning_message.hpp" - -#include - -#include - -namespace autoware::ekf_localizer -{ - -TEST(pose_delay_step_warning_message, SmokeTest) -{ - EXPECT_STREQ( - pose_delay_step_warning_message(6.0, 4.0).c_str(), - "Pose delay exceeds the compensation limit, ignored. " - "delay: 6.000[s], limit: 4.000[s]"); -} - -TEST(twist_delay_step_warning_message, SmokeTest) -{ - EXPECT_STREQ( - twist_delay_step_warning_message(10.0, 6.0).c_str(), - "Twist delay exceeds the compensation limit, ignored. " - "delay: 10.000[s], limit: 6.000[s]"); -} - -TEST(pose_delay_time_warning_message, SmokeTest) -{ - EXPECT_STREQ( - pose_delay_time_warning_message(-1.0).c_str(), - "Pose time stamp is inappropriate, set delay to 0[s]. delay = -1.000"); - EXPECT_STREQ( - pose_delay_time_warning_message(-0.4).c_str(), - "Pose time stamp is inappropriate, set delay to 0[s]. delay = -0.400"); -} - -TEST(twist_delay_time_warning_message, SmokeTest) -{ - EXPECT_STREQ( - twist_delay_time_warning_message(-1.0).c_str(), - "Twist time stamp is inappropriate, set delay to 0[s]. delay = -1.000"); - EXPECT_STREQ( - twist_delay_time_warning_message(-0.4).c_str(), - "Twist time stamp is inappropriate, set delay to 0[s]. delay = -0.400"); -} - -TEST(mahalanobis_warning_message, SmokeTest) -{ - EXPECT_STREQ( - mahalanobis_warning_message(1.0, 0.5).c_str(), - "The Mahalanobis distance 1.0000 is over the limit 0.5000."); -} - -} // namespace autoware::ekf_localizer diff --git a/localization/autoware_pose_covariance_modifier/README.md b/localization/autoware_pose_covariance_modifier/README.md index 201fb8bb37103..53cddbfa981c2 100644 --- a/localization/autoware_pose_covariance_modifier/README.md +++ b/localization/autoware_pose_covariance_modifier/README.md @@ -118,7 +118,7 @@ the [pose_twist_estimator.launch.xml](../../launch/tier4_localization_launch/lau ### Without this condition (default) - The output of the [ndt_scan_matcher](../../localization/autoware_ndt_scan_matcher) is directly sent - to [ekf_localizer](../../localization/autoware_ekf_localizer). + to [ekf_localizer](https://github.com/autowarefoundation/autoware.core/tree/main/localization/autoware_ekf_localizer). - It has a preset covariance value. - **topic name:** `/localization/pose_estimator/pose_with_covariance` - The GNSS pose does not enter the ekf_localizer. @@ -130,7 +130,7 @@ the [pose_twist_estimator.launch.xml](../../launch/tier4_localization_launch/lau - **from:** `/localization/pose_estimator/pose_with_covariance`. - **to:** `/localization/pose_estimator/ndt_scan_matcher/pose_with_covariance`. - The `ndt_scan_matcher` output enters the `autoware_pose_covariance_modifier`. -- The output of this package goes to [ekf_localizer](../../localization/autoware_ekf_localizer) with: +- The output of this package goes to [ekf_localizer](https://github.com/autowarefoundation/autoware.core/tree/main/localization/autoware_ekf_localizer) with: - **topic name:** `/localization/pose_estimator/pose_with_covariance`. ## Node From b7b3dd6dbca8b7c7881b7881ede24a294054e552 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 21 Jan 2025 10:13:02 +0900 Subject: [PATCH 257/334] docs(lane_change): object filtering description (#9947) * docs(lane_change): object filtering description Signed-off-by: Zulfaqar Azmi * Move section up Signed-off-by: Zulfaqar Azmi * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> --------- Signed-off-by: Zulfaqar Azmi Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> --- .../README.md | 286 ++++++++---------- 1 file changed, 128 insertions(+), 158 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md index 601fb893f82c6..40ddce904e435 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md @@ -279,6 +279,134 @@ Within this range, we sample the lateral acceleration for the ego vehicle. Simil lateral_acceleration_resolution = (maximum_lateral_acceleration - minimum_lateral_acceleration) / lateral_acceleration_sampling_num ``` +#### Object filtering + +Before performing safety checks, predicted objects are categorized based on their current pose and behavior at the time. These categories help determine how each object impacts the lane change process and guide the safety evaluation. + +The predicted objects are divided into four main categories: + +- **Target Lane Leading**: Objects that overlap with the target lane and are in front of the ego vehicle. This category is further divided into three subcategories: + - Moving: Objects with a velocity above a certain threshold. + - Stopped: Stationary objects within the target lane. + - Stopped at Bound: Objects outside the target lane but close to its boundaries. +- **Target Lane Trailing**: Objects that overlap with the target lane or any lanes preceding the target lane. Only moving vehicles are included in this category. +- **Current Lane**: Objects in front of the ego vehicle in the ego vehicle's current lane. +- **Others**: Any objects not classified into the above categories. + +![object lanes](./images/lane_objects.drawio.svg) + +Furthermore, for **Target Lane Leading** and **Current Lane** objects, only those positioned within the lane boundary or before the goal position are considered. Objects exceeding the end of the lane or the goal position are classified as **Others**. + +Once objects are filtered into their respective categories, they are sorted by distance closest to the ego vehicle to farthest. + +The following diagram illustrates the filtering process, + +```plantuml +@startuml +skinparam defaultTextAlignment center +skinparam backgroundColor #WHITE + +title Filter Objects main flowchart + +start + +:Filter predicted objects by class; +note left: Remove objects whose classes are\nnot specified in the **target_object** parameter. + +:Filter oncoming predicted objects; +note left: Compare ego's current pose and object's current pose,\nand filter out any object whose yaw difference exceeds\n**collision_check.th_incoming_object_yaw**; + +:Transform predicted objects to extended predicted objects; + +group "Filter target lane objects" { +if (Object's lateral distance\nfrom the centerline\nis more than\nhalf of ego's width?) then (TRUE) + if (Object's current pose\nis before the goal or\nthe end of the lane) then (TRUE) + if (Object overlaps target lane?) then (TRUE) + #LightGreen:To SUBPROCESS "Separate object based on its behavior in target lane"; + if(can separate object in SUBPROCESS) then (TRUE) + stop + endif + else (FALSE) + if (Object is moving\nAND\nis a vehicle class\nAND\npath overlaps target lane?) then (TRUE) + #LightGreen:To SUBPROCESS "Separate object based on its behavior in target lane"; + if(can separate object in SUBPROCESS) then (TRUE) + stop + endif + endif + endif + endif + #LightPink:From SUBPROCESS "Separate object based on its behavior in target lane"; + if (Object is in expanded target lane\nAND\nis stopped\nAND\nin front of ego?) then (TRUE) + :Add object to **filtered_object.leading_objects.stopped_at_bound** list; + stop + endif + else (FALSE) + if (Object overlaps preceding target lanes?) then (TRUE) + :Add object to **filtered_object.trailing_objects** list; + stop + endif +endif +} +if (Object is in front of ego\nAND\nis before terminal\nAND\noverlaps current lane?) then (TRUE) + :Add object to **filtered_object.current_lane** list; + stop +else (FALSE) + :Add object to **filtered_object.others** list; +endif + +stop + +group Target Lane Objects Subprocess #LightYellow +start +if (Object is behind ego?) then (TRUE) + if (Object is moving?) then (TRUE) + :Add object to **filtered_object.trailing_objects** list; + #LightGreen:Can separate object; + stop + else (FALSE) + #LightPink:Cant separate proceed with other checks; + stop + endif +else (FALSE) + if (Object is moving?) then (TRUE) + :Add object to **filtered_object.leading_objects.moving** list; + else (FALSE) + :Add object to **filtered_object.leading_objects.stopped** list; + endif + #LightGreen:Can separate object; + stop +endif + +@enduml +``` + +!!! note + + As shown in the flowchart, oncoming objects are also filtered out. The filtering process considers the difference between the current orientation of the ego vehicle and that of the object. However, depending on the map's geometry, a certain threshold may need to be allowed. This threshold can be configured using the parameter collision_check.th_incoming_object_yaw. + +!!! note + + The **Target Lane Leading's Stopped at Boundary** objects are detected using the expanded area of the target lane beyond its original boundaries. The parameters `lane_expansion.left_offset` and `lane_expansion.right_offset` can be configured to adjust the expanded width. + +
+ + + + + +
+
+
Without Lane Expansion
+ Without lane expansion +
+
+
+
With Lane Expansion
+ With lane expansion +
+
+
+ #### Candidate Path's validity check A candidate path is considered valid if it meets the following criteria: @@ -424,166 +552,8 @@ See [safety check utils explanation](../autoware_behavior_path_planner_common/do First, we divide the target objects into obstacles in the target lane, obstacles in the current lane, and obstacles in other lanes. Target lane indicates the lane that the ego vehicle is going to reach after the lane change and current lane mean the current lane where the ego vehicle is following before the lane change. Other lanes are lanes that do not belong to the target and current lanes. The following picture describes objects on each lane. Note that users can remove objects either on current and other lanes from safety check by changing the flag, which are `check_objects_on_current_lanes` and `check_objects_on_other_lanes`. -![object lanes](./images/lane_objects.drawio.svg) - Furthermore, to change lanes behind a vehicle waiting at a traffic light, we skip the safety check for the stopping vehicles near the traffic light. The explanation for parked car detection is written in [documentation for avoidance module](../autoware_behavior_path_static_obstacle_avoidance_module/README.md). -The detection area for the target lane can be expanded beyond its original boundaries to enable detection of objects that are outside the target lane's limits. - -
- - - - - -
-
-
Without Lane Expansion
- Without lane expansion -
-
-
-
With Lane Expansion
- With lane expansion -
-
-
- -##### Object filtering - -```plantuml -@startuml -skinparam defaultTextAlignment center -skinparam backgroundColor #WHITE - -title NormalLaneChange::filterObjects Method Execution Flow - -start - -group "Filter Objects by Class" { -while (has not finished iterating through predicted object list) is (TRUE) - if (current object type != param.object_types_to_check?) then (TRUE) - #LightPink:Remove current object; -else (FALSE) - :Keep current object; -endif -end while -end group - -if (predicted object list is empty?) then (TRUE) - :Return empty result; - stop -else (FALSE) -endif - -group "Filter Oncoming Objects" #PowderBlue { -while (has not finished iterating through predicted object list?) is (TRUE) -if (object's yaw with reference to ego's yaw difference < 90 degree?) then (TRUE) - :Keep current object; -else (FALSE) -if (object is stopping?) then (TRUE) - :Keep current object; -else (FALSE) - #LightPink:Remove current object; -endif -endif -endwhile -end group - -if (predicted object list is empty?) then (TRUE) - :Return empty result; - stop -else (FALSE) -endif - -group "Filter Objects By Lanelets" #LightGreen { - -while (has not finished iterating through predicted object list) is (TRUE) - :Calculate lateral distance diff; - if (Object in target lane polygon?) then (TRUE) - if (lateral distance diff > half of ego's width?) then (TRUE) - if (Object's physical position is before terminal point?) then (TRUE) - :Add to target_lane_objects; - else (FALSE) - endif - else (FALSE) - endif - else (FALSE) - endif - - if (Object overlaps with backward target lanes?) then (TRUE) - :Add to target_lane_objects; - else (FALSE) - if (Object in current lane polygon?) then (TRUE) - :Add to current_lane_objects; - else (FALSE) - :Add to other_lane_objects; - endif - endif -end while - -:Return target lanes object, current lanes object and other lanes object; -end group - -:Generate path from current lanes; - -if (path empty?) then (TRUE) - :Return empty result; - stop -else (FALSE) -endif - -group "Filter Target Lanes' objects" #LightCyan { - -while (has not finished iterating through target lanes' object list) is (TRUE) - if(velocity is within threshold?) then (TRUE) - :Keep current object; - else (FALSE) - if(object is ahead of ego?) then (TRUE) - :keep current object; - else (FALSE) - #LightPink:remove current object; - endif - endif -endwhile -end group - -group "Filter Current Lanes' objects" #LightYellow { - -while (has not finished iterating through current lanes' object list) is (TRUE) - if(velocity is within threshold?) then (TRUE) - if(object is ahead of ego?) then (TRUE) - :keep current object; - else (FALSE) - #LightPink:remove current object; - endif - else (FALSE) - #LightPink:remove current object; - endif -endwhile -end group - -group "Filter Other Lanes' objects" #Lavender { - -while (has not finished iterating through other lanes' object list) is (TRUE) - if(velocity is within threshold?) then (TRUE) - if(object is ahead of ego?) then (TRUE) - :keep current object; - else (FALSE) - #LightPink:remove current object; - endif - else (FALSE) - #LightPink:remove current object; - endif -endwhile -end group - -:Transform the objects into extended predicted object and return them as lane_change_target_objects; -stop - -@enduml -``` - ##### Collision check in prepare phase The ego vehicle may need to secure ample inter-vehicle distance ahead of the target vehicle before attempting a lane change. The flag `enable_collision_check_at_prepare_phase` can be enabled to gain this behavior. The following image illustrates the differences between the `false` and `true` cases. From 300ac7fbd0e407d0adbc109012b645a304050906 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Tue, 21 Jan 2025 11:17:43 +0900 Subject: [PATCH 258/334] feat(multi_object_tracker): integrate odometry and transform processes (#9912) * feat: Add odometry processor to multi-object tracker Signed-off-by: Taekjin LEE * refactor: Refactor Odometry class for improved code organization and readability Signed-off-by: Taekjin LEE * feat: Refactor Odometry class for improved code organization and readability Signed-off-by: Taekjin LEE * refactor: Transform objects to world coordinate in Odometry class refactor: Transform objects to world coordinate in Odometry class refactor: Update Odometry class to get transform from tf with source frame ID feat: Update Odometry class to get transform from tf with source frame ID fix: move necessare tr2 header Signed-off-by: Taekjin LEE * Revert "refactor: Transform objects to world coordinate in Odometry class" This reverts commit efca28a40105f80deb09d57b55cb6f9d83ffda2c. Signed-off-by: Taekjin LEE * refactor: Remove unnecessary tf2 headers from tracker models Signed-off-by: Taekjin LEE * fix: move transform obtainer to odometry class Signed-off-by: Taekjin LEE * refactor: Update Odometry class to get transform from tf with source frame ID Signed-off-by: Taekjin LEE * refactor: Transform objects to world coordinate in Odometry class Signed-off-by: Taekjin LEE * refactor: remove transformObjects from shapes Signed-off-by: Taekjin LEE * refactor: Update Odometry class to use 'updateFromTf' instead of 'setOdometryFromTf' Signed-off-by: Taekjin LEE * refactor: Update Odometry class to use 'updateFromTf' instead of 'setOdometryFromTf' Signed-off-by: Taekjin LEE * refactor: Update InputManager to include Odometry in constructor Signed-off-by: Taekjin LEE * refactor: Move odometry.cpp to lib folder Signed-off-by: Taekjin LEE * move object transform to input stream Signed-off-by: Taekjin LEE * refactor: Add enable_odometry_uncertainty parameter to Odometry constructor Signed-off-by: Taekjin LEE * refactor: Update Odometry class to return optional Odometry from getOdometryFromTf Signed-off-by: Taekjin LEE * refactor: Update Odometry class to use tf_cache_ for storing and retrieving transforms Signed-off-by: Taekjin LEE * refactor: Update Odometry class to use tf_cache_ for storing and retrieving transforms Signed-off-by: Taekjin LEE * refactor: bring odometry covariance modeler into odometry class Signed-off-by: Taekjin LEE * refactor: Remove redundant code for updating tf cache in Odometry::updateTfCache Signed-off-by: Taekjin LEE * refactor: Update runProcess parameter name to detected_objects Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE --- .../CMakeLists.txt | 1 + .../object_model/shapes.hpp | 4 - .../multi_object_tracker/odometry.hpp | 73 +++++++ .../lib/object_model/shapes.cpp | 50 ----- .../lib/odometry.cpp | 181 ++++++++++++++++++ .../lib/tracker/model/bicycle_tracker.cpp | 2 - .../tracker/model/pass_through_tracker.cpp | 2 - .../lib/tracker/model/pedestrian_tracker.cpp | 2 - .../lib/tracker/model/unknown_tracker.cpp | 2 - .../lib/tracker/model/vehicle_tracker.cpp | 2 - .../motion_model/bicycle_motion_model.cpp | 2 + .../motion_model/ctrv_motion_model.cpp | 2 + .../lib/uncertainty/uncertainty_processor.cpp | 2 + .../src/multi_object_tracker_node.cpp | 105 ++-------- .../src/multi_object_tracker_node.hpp | 7 +- .../src/processor/input_manager.cpp | 27 ++- .../src/processor/input_manager.hpp | 8 +- 17 files changed, 305 insertions(+), 167 deletions(-) create mode 100644 perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/odometry.hpp create mode 100644 perception/autoware_multi_object_tracker/lib/odometry.cpp diff --git a/perception/autoware_multi_object_tracker/CMakeLists.txt b/perception/autoware_multi_object_tracker/CMakeLists.txt index fcea50235bf0d..26895428d4c7f 100644 --- a/perception/autoware_multi_object_tracker/CMakeLists.txt +++ b/perception/autoware_multi_object_tracker/CMakeLists.txt @@ -28,6 +28,7 @@ set(${PROJECT_NAME}_src src/processor/input_manager.cpp ) set(${PROJECT_NAME}_lib + lib/odometry.cpp lib/association/association.cpp lib/association/mu_successive_shortest_path/mu_ssp.cpp lib/object_model/types.cpp diff --git a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/object_model/shapes.hpp b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/object_model/shapes.hpp index d399f356136fc..84c0eb912610a 100644 --- a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/object_model/shapes.hpp +++ b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/object_model/shapes.hpp @@ -30,10 +30,6 @@ namespace autoware::multi_object_tracker { namespace shapes { -bool transformObjects( - const types::DynamicObjectList & input_msg, const std::string & target_frame_id, - const tf2_ros::Buffer & tf_buffer, types::DynamicObjectList & output_msg); - double get2dIoU( const types::DynamicObject & source_object, const types::DynamicObject & target_object, const double min_union_area = 0.01); diff --git a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/odometry.hpp b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/odometry.hpp new file mode 100644 index 0000000000000..37a11b6eeb1f5 --- /dev/null +++ b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/odometry.hpp @@ -0,0 +1,73 @@ +// Copyright 2025 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__MULTI_OBJECT_TRACKER__ODOMETRY_HPP_ +#define AUTOWARE__MULTI_OBJECT_TRACKER__ODOMETRY_HPP_ + +#include "autoware/multi_object_tracker/object_model/types.hpp" + +#include + +#include +#include + +#include +#include + +#include +#include +#include + +namespace autoware::multi_object_tracker +{ + +class Odometry +{ +public: + Odometry( + rclcpp::Node & node, const std::string & world_frame_id, + bool enable_odometry_uncertainty = false); + + std::optional getTransform( + const std::string & source_frame_id, const rclcpp::Time & time) const; + std::optional getTransform(const rclcpp::Time & time) const; + + std::optional getOdometryFromTf(const rclcpp::Time & time) const; + + std::optional transformObjects( + const types::DynamicObjectList & input_objects) const; + +private: + rclcpp::Node & node_; + // frame id + std::string ego_frame_id_ = "base_link"; // ego vehicle frame + std::string world_frame_id_; // absolute/relative ground frame + // tf + tf2_ros::Buffer tf_buffer_; + tf2_ros::TransformListener tf_listener_; + +public: + bool enable_odometry_uncertainty_ = false; + +private: + void updateTfCache( + const rclcpp::Time & time, const geometry_msgs::msg::Transform & transform) const; + + // cache of tf + mutable std::map tf_cache_; +}; + +} // namespace autoware::multi_object_tracker + +#endif // AUTOWARE__MULTI_OBJECT_TRACKER__ODOMETRY_HPP_ diff --git a/perception/autoware_multi_object_tracker/lib/object_model/shapes.cpp b/perception/autoware_multi_object_tracker/lib/object_model/shapes.cpp index 2ce23e5df814e..2818e6dc53bb9 100644 --- a/perception/autoware_multi_object_tracker/lib/object_model/shapes.cpp +++ b/perception/autoware_multi_object_tracker/lib/object_model/shapes.cpp @@ -27,7 +27,6 @@ #include #include -#include #include #include @@ -37,55 +36,6 @@ namespace autoware::multi_object_tracker { namespace shapes { -inline boost::optional getTransform( - const tf2_ros::Buffer & tf_buffer, const std::string & source_frame_id, - const std::string & target_frame_id, const rclcpp::Time & time) -{ - try { - geometry_msgs::msg::TransformStamped self_transform_stamped; - self_transform_stamped = tf_buffer.lookupTransform( - target_frame_id, source_frame_id, time, rclcpp::Duration::from_seconds(0.5)); - return self_transform_stamped.transform; - } catch (tf2::TransformException & ex) { - RCLCPP_WARN_STREAM(rclcpp::get_logger("multi_object_tracker"), ex.what()); - return boost::none; - } -} - -bool transformObjects( - const types::DynamicObjectList & input_msg, const std::string & target_frame_id, - const tf2_ros::Buffer & tf_buffer, types::DynamicObjectList & output_msg) -{ - output_msg = input_msg; - - // transform to world coordinate - if (input_msg.header.frame_id != target_frame_id) { - output_msg.header.frame_id = target_frame_id; - tf2::Transform tf_target2objects_world; - tf2::Transform tf_target2objects; - tf2::Transform tf_objects_world2objects; - { - const auto ros_target2objects_world = - getTransform(tf_buffer, input_msg.header.frame_id, target_frame_id, input_msg.header.stamp); - if (!ros_target2objects_world) { - return false; - } - tf2::fromMsg(*ros_target2objects_world, tf_target2objects_world); - } - for (auto & object : output_msg.objects) { - auto & pose_with_cov = object.kinematics.pose_with_covariance; - tf2::fromMsg(pose_with_cov.pose, tf_objects_world2objects); - tf_target2objects = tf_target2objects_world * tf_objects_world2objects; - // transform pose, frame difference and object pose - tf2::toMsg(tf_target2objects, pose_with_cov.pose); - // transform covariance, only the frame difference - pose_with_cov.covariance = - tf2::transformCovariance(pose_with_cov.covariance, tf_target2objects_world); - } - } - return true; -} - inline double getSumArea(const std::vector & polygons) { return std::accumulate( diff --git a/perception/autoware_multi_object_tracker/lib/odometry.cpp b/perception/autoware_multi_object_tracker/lib/odometry.cpp new file mode 100644 index 0000000000000..2d31fe876c329 --- /dev/null +++ b/perception/autoware_multi_object_tracker/lib/odometry.cpp @@ -0,0 +1,181 @@ +// Copyright 2025 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/multi_object_tracker/odometry.hpp" + +#include "autoware/multi_object_tracker/uncertainty/uncertainty_processor.hpp" + +#include + +#include + +#include +#include + +namespace autoware::multi_object_tracker +{ + +Odometry::Odometry( + rclcpp::Node & node, const std::string & world_frame_id, bool enable_odometry_uncertainty) +: node_(node), + world_frame_id_(world_frame_id), + tf_buffer_(node_.get_clock()), + tf_listener_(tf_buffer_), + enable_odometry_uncertainty_(enable_odometry_uncertainty) +{ + // Create tf timer + auto cti = std::make_shared( + node_.get_node_base_interface(), node_.get_node_timers_interface()); + tf_buffer_.setCreateTimerInterface(cti); +} + +void Odometry::updateTfCache( + const rclcpp::Time & time, const geometry_msgs::msg::Transform & tf) const +{ + // update the tf buffer + tf_cache_.emplace(time, tf); + + // remove too old tf + const auto max_tf_age = rclcpp::Duration::from_seconds(1.0); + for (auto it = tf_cache_.begin(); it != tf_cache_.end();) { + if (time - it->first > max_tf_age) { + it = tf_cache_.erase(it); + } else { + ++it; + } + } +} + +std::optional Odometry::getTransform(const rclcpp::Time & time) const +{ + // check buffer and return if the transform is found + for (const auto & tf : tf_cache_) { + if (tf.first == time) { + return std::optional(tf.second); + } + } + // if not found, get the transform from tf + return getTransform(ego_frame_id_, time); +} + +std::optional Odometry::getTransform( + const std::string & source_frame_id, const rclcpp::Time & time) const +{ + try { + // Check if the frames are ready + std::string errstr; // This argument prevents error msg from being displayed in the terminal. + if (!tf_buffer_.canTransform( + world_frame_id_, source_frame_id, tf2::TimePointZero, tf2::Duration::zero(), &errstr)) { + return std::nullopt; + } + + // Lookup the transform + geometry_msgs::msg::TransformStamped self_transform_stamped; + self_transform_stamped = tf_buffer_.lookupTransform( + world_frame_id_, source_frame_id, time, rclcpp::Duration::from_seconds(0.5)); + + // update the cache + if (source_frame_id == ego_frame_id_) { + updateTfCache(time, self_transform_stamped.transform); + } + + return std::optional(self_transform_stamped.transform); + } catch (tf2::TransformException & ex) { + RCLCPP_WARN_STREAM(rclcpp::get_logger("multi_object_tracker"), ex.what()); + return std::nullopt; + } +} + +std::optional Odometry::getOdometryFromTf(const rclcpp::Time & time) const +{ + const auto self_transform = getTransform(time); + if (!self_transform) { + return std::nullopt; + } + const auto current_transform = self_transform.value(); + + nav_msgs::msg::Odometry odometry; + { + odometry.header.stamp = time + rclcpp::Duration::from_seconds(0.00001); + + // set the odometry pose + auto & odom_pose = odometry.pose.pose; + odom_pose.position.x = current_transform.translation.x; + odom_pose.position.y = current_transform.translation.y; + odom_pose.position.z = current_transform.translation.z; + odom_pose.orientation = current_transform.rotation; + + // set odometry twist + auto & odom_twist = odometry.twist.twist; + odom_twist.linear.x = 10.0; // m/s + odom_twist.linear.y = 0.1; // m/s + odom_twist.angular.z = 0.1; // rad/s + + // model the uncertainty + auto & odom_pose_cov = odometry.pose.covariance; + odom_pose_cov[0] = 0.1; // x-x + odom_pose_cov[7] = 0.1; // y-y + odom_pose_cov[35] = 0.0001; // yaw-yaw + + auto & odom_twist_cov = odometry.twist.covariance; + odom_twist_cov[0] = 2.0; // x-x [m^2/s^2] + odom_twist_cov[7] = 0.2; // y-y [m^2/s^2] + odom_twist_cov[35] = 0.001; // yaw-yaw [rad^2/s^2] + } + + return std::optional(odometry); +} + +std::optional Odometry::transformObjects( + const types::DynamicObjectList & input_objects) const +{ + types::DynamicObjectList output_objects = input_objects; + + // transform to world coordinate + if (input_objects.header.frame_id != world_frame_id_) { + output_objects.header.frame_id = world_frame_id_; + tf2::Transform tf_target2objects_world; + tf2::Transform tf_target2objects; + tf2::Transform tf_objects_world2objects; + { + const auto ros_target2objects_world = + getTransform(input_objects.header.frame_id, input_objects.header.stamp); + if (!ros_target2objects_world) { + return std::nullopt; + } + tf2::fromMsg(*ros_target2objects_world, tf_target2objects_world); + } + for (auto & object : output_objects.objects) { + auto & pose_with_cov = object.kinematics.pose_with_covariance; + tf2::fromMsg(pose_with_cov.pose, tf_objects_world2objects); + tf_target2objects = tf_target2objects_world * tf_objects_world2objects; + // transform pose, frame difference and object pose + tf2::toMsg(tf_target2objects, pose_with_cov.pose); + // transform covariance, only the frame difference + pose_with_cov.covariance = + tf2::transformCovariance(pose_with_cov.covariance, tf_target2objects_world); + } + } + // Add the odometry uncertainty to the object uncertainty + if (enable_odometry_uncertainty_) { + // Create a modeled odometry message + const auto odometry = getOdometryFromTf(input_objects.header.stamp); + // Add the odometry uncertainty to the object uncertainty + uncertainty::addOdometryUncertainty(odometry.value(), output_objects); + } + + return std::optional(output_objects); +} + +} // namespace autoware::multi_object_tracker diff --git a/perception/autoware_multi_object_tracker/lib/tracker/model/bicycle_tracker.cpp b/perception/autoware_multi_object_tracker/lib/tracker/model/bicycle_tracker.cpp index e0380a7c33e77..32caf16b17a2d 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/model/bicycle_tracker.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/model/bicycle_tracker.cpp @@ -30,8 +30,6 @@ #include #include -#include -#include #include #ifdef ROS_DISTRO_GALACTIC diff --git a/perception/autoware_multi_object_tracker/lib/tracker/model/pass_through_tracker.cpp b/perception/autoware_multi_object_tracker/lib/tracker/model/pass_through_tracker.cpp index 45b3b067e2848..e9852baaa94af 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/model/pass_through_tracker.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/model/pass_through_tracker.cpp @@ -24,8 +24,6 @@ #include #include -#include -#include #include #ifdef ROS_DISTRO_GALACTIC diff --git a/perception/autoware_multi_object_tracker/lib/tracker/model/pedestrian_tracker.cpp b/perception/autoware_multi_object_tracker/lib/tracker/model/pedestrian_tracker.cpp index bc53689739439..779fba7376857 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/model/pedestrian_tracker.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/model/pedestrian_tracker.cpp @@ -28,8 +28,6 @@ #include #include -#include -#include #include #ifdef ROS_DISTRO_GALACTIC diff --git a/perception/autoware_multi_object_tracker/lib/tracker/model/unknown_tracker.cpp b/perception/autoware_multi_object_tracker/lib/tracker/model/unknown_tracker.cpp index ed01165ed8176..933eba820b1d1 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/model/unknown_tracker.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/model/unknown_tracker.cpp @@ -24,8 +24,6 @@ #include #include -#include -#include #include #ifdef ROS_DISTRO_GALACTIC diff --git a/perception/autoware_multi_object_tracker/lib/tracker/model/vehicle_tracker.cpp b/perception/autoware_multi_object_tracker/lib/tracker/model/vehicle_tracker.cpp index 749640ce4324a..f497df1f52c6c 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/model/vehicle_tracker.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/model/vehicle_tracker.cpp @@ -30,8 +30,6 @@ #include #include -#include -#include #include #ifdef ROS_DISTRO_GALACTIC diff --git a/perception/autoware_multi_object_tracker/lib/tracker/motion_model/bicycle_motion_model.cpp b/perception/autoware_multi_object_tracker/lib/tracker/motion_model/bicycle_motion_model.cpp index 1e71bf8548b33..b9518afeaf95a 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/motion_model/bicycle_motion_model.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/motion_model/bicycle_motion_model.cpp @@ -27,6 +27,8 @@ #include #include +#include + #include namespace autoware::multi_object_tracker diff --git a/perception/autoware_multi_object_tracker/lib/tracker/motion_model/ctrv_motion_model.cpp b/perception/autoware_multi_object_tracker/lib/tracker/motion_model/ctrv_motion_model.cpp index e10fbca073047..2a2d7ea80bae1 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/motion_model/ctrv_motion_model.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/motion_model/ctrv_motion_model.cpp @@ -27,6 +27,8 @@ #include #include +#include + namespace autoware::multi_object_tracker { // cspell: ignore CTRV diff --git a/perception/autoware_multi_object_tracker/lib/uncertainty/uncertainty_processor.cpp b/perception/autoware_multi_object_tracker/lib/uncertainty/uncertainty_processor.cpp index 36d48d35f74b7..bdd3a78a198a8 100644 --- a/perception/autoware_multi_object_tracker/lib/uncertainty/uncertainty_processor.cpp +++ b/perception/autoware_multi_object_tracker/lib/uncertainty/uncertainty_processor.cpp @@ -20,6 +20,8 @@ #include #include +#include + #include namespace autoware::multi_object_tracker diff --git a/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp b/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp index 333b301ce9fcf..b90c570e7f4a6 100644 --- a/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp +++ b/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp @@ -11,8 +11,7 @@ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. -// -// + #define EIGEN_MPL2_ONLY #include "multi_object_tracker_node.hpp" @@ -38,34 +37,6 @@ #include #include -namespace -{ -// Function to get the transform between two frames -boost::optional getTransformAnonymous( - const tf2_ros::Buffer & tf_buffer, const std::string & source_frame_id, - const std::string & target_frame_id, const rclcpp::Time & time) -{ - try { - // Check if the frames are ready - std::string errstr; // This argument prevents error msg from being displayed in the terminal. - if (!tf_buffer.canTransform( - target_frame_id, source_frame_id, tf2::TimePointZero, tf2::Duration::zero(), &errstr)) { - return boost::none; - } - - // Lookup the transform - geometry_msgs::msg::TransformStamped self_transform_stamped; - self_transform_stamped = tf_buffer.lookupTransform( - /*target*/ target_frame_id, /*src*/ source_frame_id, time, - rclcpp::Duration::from_seconds(0.5)); - return self_transform_stamped.transform; - } catch (tf2::TransformException & ex) { - RCLCPP_WARN_STREAM(rclcpp::get_logger("multi_object_tracker"), ex.what()); - return boost::none; - } -} -} // namespace - namespace autoware::multi_object_tracker { using Label = autoware_perception_msgs::msg::ObjectClassification; @@ -73,8 +44,6 @@ using LabelType = autoware_perception_msgs::msg::ObjectClassification::_label_ty MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) : rclcpp::Node("multi_object_tracker", node_options), - tf_buffer_(this->get_clock()), - tf_listener_(tf_buffer_), last_published_time_(this->now()), last_updated_time_(this->now()) { @@ -88,7 +57,7 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) double publish_rate = declare_parameter("publish_rate"); // [hz] world_frame_id_ = declare_parameter("world_frame_id"); bool enable_delay_compensation{declare_parameter("enable_delay_compensation")}; - enable_odometry_uncertainty_ = declare_parameter("consider_odometry_uncertainty"); + bool enable_odometry_uncertainty = declare_parameter("consider_odometry_uncertainty"); declare_parameter("selected_input_channels", std::vector()); std::vector selected_input_channels = @@ -98,6 +67,9 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) tracked_objects_pub_ = create_publisher("output", rclcpp::QoS{1}); + // Odometry manager + odometry_ = std::make_shared(*this, world_frame_id_, enable_odometry_uncertainty); + // ROS interface - Input channels // Get input channels std::vector input_topic_names; @@ -144,16 +116,11 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) } // Initialize input manager - input_manager_ = std::make_unique(*this); + input_manager_ = std::make_unique(*this, odometry_); input_manager_->init(input_channels_); // Initialize input manager, set subscriptions input_manager_->setTriggerFunction( std::bind(&MultiObjectTracker::onTrigger, this)); // Set trigger function - // Create tf timer - auto cti = std::make_shared( - this->get_node_base_interface(), this->get_node_timers_interface()); - tf_buffer_.setCreateTimerInterface(cti); - // Create ROS time based timer. // If the delay compensation is enabled, the timer is used to publish the output at the correct // time. @@ -279,61 +246,18 @@ void MultiObjectTracker::onTimer() if (should_publish) checkAndPublish(current_time); } -void MultiObjectTracker::runProcess(const types::DynamicObjectList & input_objects) +void MultiObjectTracker::runProcess(const types::DynamicObjectList & detected_objects) { // Get the time of the measurement const rclcpp::Time measurement_time = - rclcpp::Time(input_objects.header.stamp, this->now().get_clock_type()); + rclcpp::Time(detected_objects.header.stamp, this->now().get_clock_type()); - // Get the transform of the self frame - const auto self_transform = - getTransformAnonymous(tf_buffer_, "base_link", world_frame_id_, measurement_time); + // Get the self transform + const auto self_transform = odometry_->getTransform(measurement_time); if (!self_transform) { return; } - // Transform the objects to the world frame - types::DynamicObjectList transformed_objects; - if (!shapes::transformObjects(input_objects, world_frame_id_, tf_buffer_, transformed_objects)) { - return; - } - - // the object uncertainty - if (enable_odometry_uncertainty_) { - // Create a modeled odometry message - nav_msgs::msg::Odometry odometry; - odometry.header.stamp = measurement_time + rclcpp::Duration::from_seconds(0.001); - - // set odometry pose from self_transform - auto & odom_pose = odometry.pose.pose; - odom_pose.position.x = self_transform->translation.x; - odom_pose.position.y = self_transform->translation.y; - odom_pose.position.z = self_transform->translation.z; - odom_pose.orientation = self_transform->rotation; - - // set odometry twist - auto & odom_twist = odometry.twist.twist; - odom_twist.linear.x = 10.0; // m/s - odom_twist.linear.y = 0.1; // m/s - odom_twist.angular.z = 0.1; // rad/s - - // model the uncertainty - auto & odom_pose_cov = odometry.pose.covariance; - odom_pose_cov[0] = 0.1; // x-x - odom_pose_cov[7] = 0.1; // y-y - odom_pose_cov[35] = 0.0001; // yaw-yaw - - auto & odom_twist_cov = odometry.twist.covariance; - odom_twist_cov[0] = 2.0; // x-x [m^2/s^2] - odom_twist_cov[7] = 0.2; // y-y [m^2/s^2] - odom_twist_cov[35] = 0.001; // yaw-yaw [rad^2/s^2] - - // Add the odometry uncertainty to the object uncertainty - uncertainty::addOdometryUncertainty(odometry, transformed_objects); - } - // Normalize the object uncertainty - uncertainty::normalizeUncertainty(transformed_objects); - /* prediction */ processor_->predict(measurement_time); @@ -341,7 +265,6 @@ void MultiObjectTracker::runProcess(const types::DynamicObjectList & input_objec std::unordered_map direct_assignment, reverse_assignment; { const auto & list_tracker = processor_->getListTracker(); - const auto & detected_objects = transformed_objects; // global nearest neighbor Eigen::MatrixXd score_matrix = association_->calcScoreMatrix( detected_objects, list_tracker); // row : tracker, col : measurement @@ -349,19 +272,19 @@ void MultiObjectTracker::runProcess(const types::DynamicObjectList & input_objec // Collect debug information - tracker list, existence probabilities, association results debugger_->collectObjectInfo( - measurement_time, processor_->getListTracker(), transformed_objects, direct_assignment, + measurement_time, processor_->getListTracker(), detected_objects, direct_assignment, reverse_assignment); } /* tracker update */ - processor_->update(transformed_objects, *self_transform, direct_assignment); + processor_->update(detected_objects, *self_transform, direct_assignment); /* tracker pruning */ processor_->prune(measurement_time); /* spawn new tracker */ - if (input_manager_->isChannelSpawnEnabled(input_objects.channel_index)) { - processor_->spawn(transformed_objects, reverse_assignment); + if (input_manager_->isChannelSpawnEnabled(detected_objects.channel_index)) { + processor_->spawn(detected_objects, reverse_assignment); } } diff --git a/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.hpp b/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.hpp index 0472d67617f7f..6a904dc7e2ef9 100644 --- a/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.hpp +++ b/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.hpp @@ -21,6 +21,7 @@ #include "autoware/multi_object_tracker/association/association.hpp" #include "autoware/multi_object_tracker/object_model/types.hpp" +#include "autoware/multi_object_tracker/odometry.hpp" #include "autoware/multi_object_tracker/tracker/model/tracker_base.hpp" #include "debugger/debugger.hpp" #include "processor/input_manager.hpp" @@ -66,8 +67,6 @@ class MultiObjectTracker : public rclcpp::Node rclcpp::Publisher::SharedPtr tracked_objects_pub_; rclcpp::Subscription::SharedPtr detected_object_sub_; - tf2_ros::Buffer tf_buffer_; - tf2_ros::TransformListener tf_listener_; // debugger std::unique_ptr debugger_; @@ -85,10 +84,10 @@ class MultiObjectTracker : public rclcpp::Node std::string world_frame_id_; // tracking frame std::unique_ptr association_; std::unique_ptr processor_; - bool enable_odometry_uncertainty_; // input manager std::unique_ptr input_manager_; + std::shared_ptr odometry_; std::vector input_channels_{}; size_t input_channel_size_{}; @@ -98,7 +97,7 @@ class MultiObjectTracker : public rclcpp::Node void onTrigger(); // publish processes - void runProcess(const types::DynamicObjectList & input_objects); + void runProcess(const types::DynamicObjectList & detected_objects); void checkAndPublish(const rclcpp::Time & time); void publish(const rclcpp::Time & time) const; inline bool shouldTrackerPublish(const std::shared_ptr tracker) const; diff --git a/perception/autoware_multi_object_tracker/src/processor/input_manager.cpp b/perception/autoware_multi_object_tracker/src/processor/input_manager.cpp index bc461191af271..1e0a340b19d55 100644 --- a/perception/autoware_multi_object_tracker/src/processor/input_manager.cpp +++ b/perception/autoware_multi_object_tracker/src/processor/input_manager.cpp @@ -15,10 +15,10 @@ #include "input_manager.hpp" #include "autoware/multi_object_tracker/object_model/types.hpp" - -#include +#include "autoware/multi_object_tracker/uncertainty/uncertainty_processor.hpp" #include +#include #include #include @@ -27,7 +27,8 @@ namespace autoware::multi_object_tracker /////////////////////////// /////// InputStream /////// /////////////////////////// -InputStream::InputStream(rclcpp::Node & node, uint & index) : node_(node), index_(index) +InputStream::InputStream(rclcpp::Node & node, uint & index, std::shared_ptr odometry) +: node_(node), index_(index), odometry_(odometry) { } @@ -63,8 +64,21 @@ void InputStream::onMessage( types::DynamicObjectList objects_with_uncertainty = uncertainty::modelUncertainty(dynamic_objects); + // Transform the objects to the world frame + auto transformed_objects = odometry_->transformObjects(objects_with_uncertainty); + if (!transformed_objects) { + RCLCPP_WARN( + node_.get_logger(), "InputManager::onMessage %s: Failed to transform objects.", + long_name_.c_str()); + return; + } + dynamic_objects = transformed_objects.value(); + + // Normalize the object uncertainty + uncertainty::normalizeUncertainty(dynamic_objects); + // Move the objects_with_uncertainty to the objects queue - objects_que_.push_back(std::move(objects_with_uncertainty)); + objects_que_.push_back(std::move(dynamic_objects)); while (objects_que_.size() > que_size_) { objects_que_.pop_front(); } @@ -190,7 +204,8 @@ void InputStream::getObjectsOlderThan( //////////////////////////// /////// InputManager /////// //////////////////////////// -InputManager::InputManager(rclcpp::Node & node) : node_(node) +InputManager::InputManager(rclcpp::Node & node, std::shared_ptr odometry) +: node_(node), odometry_(odometry) { latest_exported_object_time_ = node_.now() - rclcpp::Duration::from_seconds(3.0); } @@ -209,7 +224,7 @@ void InputManager::init(const std::vector & input_channels) bool is_any_spawn_enabled = false; for (size_t i = 0; i < input_size_; i++) { uint index(i); - InputStream input_stream(node_, index); + InputStream input_stream(node_, index, odometry_); input_stream.init(input_channels[i]); input_stream.setTriggerFunction( std::bind(&InputManager::onTrigger, this, std::placeholders::_1)); diff --git a/perception/autoware_multi_object_tracker/src/processor/input_manager.hpp b/perception/autoware_multi_object_tracker/src/processor/input_manager.hpp index 189d7b7dc48fe..da715c39bb710 100644 --- a/perception/autoware_multi_object_tracker/src/processor/input_manager.hpp +++ b/perception/autoware_multi_object_tracker/src/processor/input_manager.hpp @@ -16,6 +16,7 @@ #define PROCESSOR__INPUT_MANAGER_HPP_ #include "autoware/multi_object_tracker/object_model/types.hpp" +#include "autoware/multi_object_tracker/odometry.hpp" #include "rclcpp/rclcpp.hpp" #include @@ -42,7 +43,7 @@ struct InputChannel class InputStream { public: - explicit InputStream(rclcpp::Node & node, uint & index); + explicit InputStream(rclcpp::Node & node, uint & index, std::shared_ptr odometry); void init(const InputChannel & input_channel); @@ -75,6 +76,7 @@ class InputStream private: rclcpp::Node & node_; uint index_; + std::shared_ptr odometry_; std::string input_topic_; std::string long_name_; @@ -99,7 +101,7 @@ class InputStream class InputManager { public: - explicit InputManager(rclcpp::Node & node); + InputManager(rclcpp::Node & node, std::shared_ptr odometry); void init(const std::vector & input_channels); void setTriggerFunction(std::function func_trigger) { func_trigger_ = func_trigger; } @@ -114,6 +116,8 @@ class InputManager private: rclcpp::Node & node_; + std::shared_ptr odometry_; + std::vector::SharedPtr> sub_objects_array_{}; From e15873654ed37663a3cfaf733d3ab64aa23b110a Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Tue, 21 Jan 2025 11:35:19 +0900 Subject: [PATCH 259/334] fix(image_projection_based_fusion): revise message publishers (#9865) * refactor: fix condition for publishing painted pointcloud message Signed-off-by: Taekjin LEE * fix: publish output revised Signed-off-by: Taekjin LEE * feat: fix condition for publishing painted pointcloud message Signed-off-by: Taekjin LEE * feat: roi-pointclout fusion - publish empty image even when there is no target roi Signed-off-by: Taekjin LEE * fix: remap output topic for clusters in roi_pointcloud_fusion Signed-off-by: Taekjin LEE * style(pre-commit): autofix Signed-off-by: Taekjin LEE * feat: fix condition for publishing painted pointcloud message Signed-off-by: Taekjin LEE * feat: Add debug publisher for internal debugging Signed-off-by: Taekjin LEE * feat: remove !! pointer to bool conversion Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../detector/camera_lidar_detector.launch.xml | 2 +- .../docs/pointpainting-fusion.md | 12 ++++----- .../docs/roi-cluster-fusion.md | 8 +++--- .../docs/roi-detected-object-fusion.md | 12 ++++----- .../docs/roi-pointcloud-fusion.md | 9 +++---- .../fusion_node.hpp | 5 ++-- .../pointpainting_fusion/node.hpp | 2 +- .../launch/roi_pointcloud_fusion.launch.xml | 6 ++--- .../src/fusion_node.cpp | 26 +++++++++++-------- .../src/pointpainting_fusion/node.cpp | 9 ++++--- .../src/roi_detected_object_fusion/node.cpp | 7 +++-- .../src/roi_pointcloud_fusion/node.cpp | 16 ++++++++---- 12 files changed, 63 insertions(+), 51 deletions(-) diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml index da30500070850..004e9c6dc75ba 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml @@ -181,7 +181,7 @@ - + diff --git a/perception/autoware_image_projection_based_fusion/docs/pointpainting-fusion.md b/perception/autoware_image_projection_based_fusion/docs/pointpainting-fusion.md index 92f62443918c0..21c2140075f51 100644 --- a/perception/autoware_image_projection_based_fusion/docs/pointpainting-fusion.md +++ b/perception/autoware_image_projection_based_fusion/docs/pointpainting-fusion.md @@ -16,18 +16,18 @@ The lidar points are projected onto the output of an image-only 2d object detect | Name | Type | Description | | ------------------------ | -------------------------------------------------------- | --------------------------------------------------------- | -| `input` | `sensor_msgs::msg::PointCloud2` | pointcloud | +| `input/pointcloud` | `sensor_msgs::msg::PointCloud2` | pointcloud | | `input/camera_info[0-7]` | `sensor_msgs::msg::CameraInfo` | camera information to project 3d points onto image planes | | `input/rois[0-7]` | `tier4_perception_msgs::msg::DetectedObjectsWithFeature` | ROIs from each image | | `input/image_raw[0-7]` | `sensor_msgs::msg::Image` | images for visualization | ### Output -| Name | Type | Description | -| ------------------------ | ------------------------------------------------ | ------------------------ | -| `output` | `sensor_msgs::msg::PointCloud2` | painted pointcloud | -| `~/output/objects` | `autoware_perception_msgs::msg::DetectedObjects` | detected objects | -| `~/debug/image_raw[0-7]` | `sensor_msgs::msg::Image` | images for visualization | +| Name | Type | Description | +| -------------------------- | ------------------------------------------------ | ------------------------ | +| `output/objects` | `autoware_perception_msgs::msg::DetectedObjects` | detected objects | +| `debug/painted_pointcloud` | `sensor_msgs::msg::PointCloud2` | painted pointcloud | +| `debug/image_raw[0-7]` | `sensor_msgs::msg::Image` | images for visualization | ## Parameters diff --git a/perception/autoware_image_projection_based_fusion/docs/roi-cluster-fusion.md b/perception/autoware_image_projection_based_fusion/docs/roi-cluster-fusion.md index 86d3a2fa070b2..e5c5b1d05e9c8 100644 --- a/perception/autoware_image_projection_based_fusion/docs/roi-cluster-fusion.md +++ b/perception/autoware_image_projection_based_fusion/docs/roi-cluster-fusion.md @@ -23,10 +23,10 @@ The clusters are projected onto image planes, and then if the ROIs of clusters a ### Output -| Name | Type | Description | -| ------------------------ | -------------------------------------------------------- | -------------------------- | -| `output` | `tier4_perception_msgs::msg::DetectedObjectsWithFeature` | labeled cluster pointcloud | -| `~/debug/image_raw[0-7]` | `sensor_msgs::msg::Image` | images for visualization | +| Name | Type | Description | +| ---------------------- | -------------------------------------------------------- | -------------------------- | +| `output` | `tier4_perception_msgs::msg::DetectedObjectsWithFeature` | labeled cluster pointcloud | +| `debug/image_raw[0-7]` | `sensor_msgs::msg::Image` | images for visualization | ## Parameters diff --git a/perception/autoware_image_projection_based_fusion/docs/roi-detected-object-fusion.md b/perception/autoware_image_projection_based_fusion/docs/roi-detected-object-fusion.md index 4dadae5531aa9..1a4652fc814af 100644 --- a/perception/autoware_image_projection_based_fusion/docs/roi-detected-object-fusion.md +++ b/perception/autoware_image_projection_based_fusion/docs/roi-detected-object-fusion.md @@ -30,12 +30,12 @@ The DetectedObject has three possible shape choices/implementations, where the p ### Output -| Name | Type | Description | -| ------------------------- | ------------------------------------------------ | -------------------------- | -| `output` | `autoware_perception_msgs::msg::DetectedObjects` | detected objects | -| `~/debug/image_raw[0-7]` | `sensor_msgs::msg::Image` | images for visualization, | -| `~/debug/fused_objects` | `autoware_perception_msgs::msg::DetectedObjects` | fused detected objects | -| `~/debug/ignored_objects` | `autoware_perception_msgs::msg::DetectedObjects` | not fused detected objects | +| Name | Type | Description | +| ----------------------- | ------------------------------------------------ | -------------------------- | +| `output` | `autoware_perception_msgs::msg::DetectedObjects` | detected objects | +| `debug/image_raw[0-7]` | `sensor_msgs::msg::Image` | images for visualization, | +| `debug/fused_objects` | `autoware_perception_msgs::msg::DetectedObjects` | fused detected objects | +| `debug/ignored_objects` | `autoware_perception_msgs::msg::DetectedObjects` | not fused detected objects | ## Parameters diff --git a/perception/autoware_image_projection_based_fusion/docs/roi-pointcloud-fusion.md b/perception/autoware_image_projection_based_fusion/docs/roi-pointcloud-fusion.md index f2ce7662da976..7727d80003f79 100644 --- a/perception/autoware_image_projection_based_fusion/docs/roi-pointcloud-fusion.md +++ b/perception/autoware_image_projection_based_fusion/docs/roi-pointcloud-fusion.md @@ -24,11 +24,10 @@ The node `roi_pointcloud_fusion` is to cluster the pointcloud based on Region Of ### Output -| Name | Type | Description | -| ----------------- | -------------------------------------------------------- | -------------------------------------------- | -| `output` | `sensor_msgs::msg::PointCloud2` | output pointcloud as default of interface | -| `output_clusters` | `tier4_perception_msgs::msg::DetectedObjectsWithFeature` | output clusters | -| `debug/clusters` | `sensor_msgs/msg/PointCloud2` | colored cluster pointcloud for visualization | +| Name | Type | Description | +| ---------------- | -------------------------------------------------------- | -------------------------------------------- | +| `output` | `tier4_perception_msgs::msg::DetectedObjectsWithFeature` | output clusters | +| `debug/clusters` | `sensor_msgs/msg/PointCloud2` | colored cluster pointcloud for visualization | ## Parameters diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp index e05339771f667..964974b96e73d 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp @@ -150,8 +150,8 @@ class FusionNode : public rclcpp::Node // 2d detection management std::vector> det2d_list_; - /** \brief A vector of subscriber. */ - typename rclcpp::Subscription::SharedPtr sub_; + // 3d detection subscription + typename rclcpp::Subscription::SharedPtr det3d_sub_; // parameters for out_of_scope filter float filter_scope_min_x_; @@ -166,6 +166,7 @@ class FusionNode : public rclcpp::Node // debugger std::shared_ptr debugger_; + std::unique_ptr debug_internal_pub_; /** \brief processing time publisher. **/ std::unique_ptr> stop_watch_ptr_; diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/node.hpp index 9505a926df2f8..26b4512e345f7 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/node.hpp @@ -57,7 +57,7 @@ class PointPaintingFusionNode : public FusionNode::SharedPtr point_pub_ptr_; + rclcpp::Publisher::SharedPtr painted_point_pub_ptr_; std::unique_ptr diagnostics_interface_ptr_; int omp_num_threads_{1}; diff --git a/perception/autoware_image_projection_based_fusion/launch/roi_pointcloud_fusion.launch.xml b/perception/autoware_image_projection_based_fusion/launch/roi_pointcloud_fusion.launch.xml index c062081fb691c..a221af7fe44d3 100644 --- a/perception/autoware_image_projection_based_fusion/launch/roi_pointcloud_fusion.launch.xml +++ b/perception/autoware_image_projection_based_fusion/launch/roi_pointcloud_fusion.launch.xml @@ -17,8 +17,7 @@ - - + @@ -39,8 +38,7 @@ - - + diff --git a/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp b/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp index 700d249831000..f7861d91b6712 100644 --- a/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp @@ -105,7 +105,8 @@ FusionNode::FusionNode( // subscribe 3d detection std::function sub_callback = std::bind(&FusionNode::subCallback, this, std::placeholders::_1); - sub_ = this->create_subscription("input", rclcpp::QoS(1).best_effort(), sub_callback); + det3d_sub_ = + this->create_subscription("input", rclcpp::QoS(1).best_effort(), sub_callback); // Set timer const auto period_ns = std::chrono::duration_cast( @@ -141,6 +142,10 @@ FusionNode::FusionNode( static_cast(declare_parameter("image_buffer_size")); debugger_ = std::make_shared(this, rois_number, image_buffer_size, input_camera_topics); + + // input topic timing publisher + debug_internal_pub_ = + std::make_unique(this, get_name()); } // time keeper @@ -155,10 +160,9 @@ FusionNode::FusionNode( // initialize debug tool { - using autoware::universe_utils::DebugPublisher; - using autoware::universe_utils::StopWatch; - stop_watch_ptr_ = std::make_unique>(); - debug_publisher_ = std::make_unique(this, get_name()); + stop_watch_ptr_ = + std::make_unique>(); + debug_publisher_ = std::make_unique(this, get_name()); stop_watch_ptr_->tic("cyclic_time"); stop_watch_ptr_->tic("processing_time"); } @@ -347,11 +351,11 @@ void FusionNode::subCallback( det2d.is_fused = true; // add timestamp interval for debug - if (debug_publisher_) { + if (debug_internal_pub_) { double timestamp_interval_ms = (matched_stamp - timestamp_nsec) / 1e6; - debug_publisher_->publish( + debug_internal_pub_->publish( "debug/roi" + std::to_string(roi_i) + "/timestamp_interval_ms", timestamp_interval_ms); - debug_publisher_->publish( + debug_internal_pub_->publish( "debug/roi" + std::to_string(roi_i) + "/timestamp_interval_offset_ms", timestamp_interval_ms - det2d.input_offset_ms); } @@ -412,11 +416,11 @@ void FusionNode::roiCallback( fuseOnSingleImage(*(cached_det3d_msg_ptr_), det2d, *det2d_msg, *(cached_det3d_msg_ptr_)); det2d.is_fused = true; - if (debug_publisher_) { + if (debug_internal_pub_) { double timestamp_interval_ms = (timestamp_nsec - cached_det3d_msg_timestamp_) / 1e6; - debug_publisher_->publish( + debug_internal_pub_->publish( "debug/roi" + std::to_string(roi_i) + "/timestamp_interval_ms", timestamp_interval_ms); - debug_publisher_->publish( + debug_internal_pub_->publish( "debug/roi" + std::to_string(roi_i) + "/timestamp_interval_offset_ms", timestamp_interval_ms - det2d.input_offset_ms); } diff --git a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp index ef03cf6c3a7cf..91142612f6e3b 100644 --- a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp @@ -158,12 +158,13 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt // subscriber std::function sub_callback = std::bind(&PointPaintingFusionNode::subCallback, this, std::placeholders::_1); - sub_ = this->create_subscription( + det3d_sub_ = this->create_subscription( "~/input/pointcloud", rclcpp::SensorDataQoS().keep_last(3), sub_callback); // publisher - point_pub_ptr_ = this->create_publisher("output", rclcpp::QoS{1}); pub_ptr_ = this->create_publisher("~/output/objects", rclcpp::QoS{1}); + painted_point_pub_ptr_ = + this->create_publisher("~/debug/painted_pointcloud", rclcpp::QoS{1}); detection_class_remapper_.setParameters( allow_remapping_by_area_matrix, min_area_matrix, max_area_matrix); @@ -438,8 +439,8 @@ void PointPaintingFusionNode::postprocess( detection_class_remapper_.mapClasses(output_msg); // publish debug message: painted pointcloud - if (point_pub_ptr_->get_subscription_count() > 0) { - point_pub_ptr_->publish(painted_pointcloud_msg); + if (debugger_ && painted_point_pub_ptr_->get_subscription_count() > 0) { + painted_point_pub_ptr_->publish(painted_pointcloud_msg); } diagnostics_interface_ptr_->publish(painted_pointcloud_msg.header.stamp); } diff --git a/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp index 37769ad73e8c7..8b6a4fd2b7d10 100644 --- a/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp @@ -334,8 +334,11 @@ void RoiDetectedObjectFusionNode::postprocess( debug_ignored_objects_msg.objects.emplace_back(obj); } } - debug_publisher_->publish("debug/fused_objects", debug_fused_objects_msg); - debug_publisher_->publish("debug/ignored_objects", debug_ignored_objects_msg); + if (debug_internal_pub_) { + debug_internal_pub_->publish("debug/fused_objects", debug_fused_objects_msg); + debug_internal_pub_->publish( + "debug/ignored_objects", debug_ignored_objects_msg); + } // clear flags passthrough_object_flags_map_.erase(timestamp_nsec); diff --git a/perception/autoware_image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp index b1eef00053946..ed2a0cbc5d68f 100644 --- a/perception/autoware_image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp @@ -45,8 +45,7 @@ RoiPointCloudFusionNode::RoiPointCloudFusionNode(const rclcpp::NodeOptions & opt cluster_2d_tolerance_ = declare_parameter("cluster_2d_tolerance"); // publisher - point_pub_ptr_ = this->create_publisher("output", rclcpp::QoS{1}); - pub_ptr_ = this->create_publisher("output_clusters", rclcpp::QoS{1}); + pub_ptr_ = this->create_publisher("output", rclcpp::QoS{1}); cluster_debug_pub_ = this->create_publisher("debug/clusters", 1); } @@ -80,7 +79,15 @@ void RoiPointCloudFusionNode::fuseOnSingleImage( debug_image_rois.push_back(feature_obj.feature.roi); } } + + // check if there is no object to fuse if (output_objs.empty()) { + // publish debug image, which is empty + if (debugger_) { + debugger_->image_rois_ = debug_image_rois; + debugger_->obstacle_points_ = debug_image_points; + debugger_->publishImage(det2d.id, input_roi_msg.header.stamp); + } return; } @@ -164,6 +171,8 @@ void RoiPointCloudFusionNode::fuseOnSingleImage( updateOutputFusedObjects( output_objs, clusters, clusters_data_size, input_pointcloud_msg, input_roi_msg.header, tf_buffer_, min_cluster_size_, max_cluster_size_, cluster_2d_tolerance_, output_fused_objects_); + + // publish debug image if (debugger_) { debugger_->image_rois_ = debug_image_rois; debugger_->obstacle_points_ = debug_image_points; @@ -188,9 +197,6 @@ void RoiPointCloudFusionNode::postprocess( autoware::euclidean_cluster::convertObjectMsg2SensorMsg(output_msg, debug_cluster_msg); cluster_debug_pub_->publish(debug_cluster_msg); } - if (point_pub_ptr_->get_subscription_count() > 0) { - point_pub_ptr_->publish(pointcloud_msg); - } } void RoiPointCloudFusionNode::publish(const ClusterMsgType & output_msg) From aa840ce0bf1f6f721c36f3e9b79767e8adea8da9 Mon Sep 17 00:00:00 2001 From: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Date: Tue, 21 Jan 2025 13:12:30 +0900 Subject: [PATCH 260/334] feat(autoware_component_interface_specs_universe!): rename package (#9753) Signed-off-by: Ryohsuke Mitsudome --- .github/CODEOWNERS | 2 +- common/.pages | 2 +- .../CHANGELOG.rst | 2 +- .../CMakeLists.txt | 2 +- .../README.md | 2 +- .../control.hpp | 10 +-- .../localization.hpp | 10 +-- .../map.hpp | 10 +-- .../perception.hpp | 10 +-- .../planning.hpp | 10 +-- .../system.hpp | 10 +-- .../vehicle.hpp | 10 +-- .../package.xml | 4 +- .../test/gtest_main.cpp | 0 .../test/test_control.cpp | 8 +- .../test/test_localization.cpp | 8 +- .../test/test_map.cpp | 4 +- .../test/test_perception.cpp | 4 +- .../test/test_planning.cpp | 8 +- .../test/test_system.cpp | 6 +- .../test/test_vehicle.cpp | 12 +-- common/autoware_test_utils/package.xml | 2 +- .../package.xml | 2 +- .../src/node.hpp | 10 ++- control/autoware_vehicle_cmd_gate/package.xml | 2 +- .../src/adapi_pause_interface.hpp | 8 +- .../src/moderate_stop_interface.hpp | 8 +- .../predicted_path_checker_node.hpp | 13 +-- control/predicted_path_checker/package.xml | 2 +- .../predicted_path_checker_node.cpp | 7 +- .../autoware_geo_pose_projector/package.xml | 2 +- .../src/geo_pose_projector.hpp | 4 +- .../autoware_pose_initializer/package.xml | 2 +- .../src/ekf_localization_trigger_module.cpp | 4 +- .../src/gnss_module.cpp | 4 +- .../src/localization_module.cpp | 4 +- .../src/ndt_localization_trigger_module.cpp | 4 +- .../src/pose_initializer_core.hpp | 6 +- .../map_loader/lanelet2_map_loader_node.hpp | 4 +- map/autoware_map_loader/package.xml | 2 +- .../map_projection_loader.hpp | 4 +- .../package.xml | 2 +- .../autoware_planning_test_manager.hpp | 2 +- .../package.xml | 2 +- .../autoware/gnss_poser/gnss_poser_node.hpp | 4 +- sensing/autoware_gnss_poser/package.xml | 2 +- system/autoware_default_adapi/package.xml | 2 +- .../autoware_default_adapi/src/fail_safe.hpp | 4 +- .../src/localization.hpp | 6 +- system/autoware_default_adapi/src/motion.cpp | 11 +-- system/autoware_default_adapi/src/motion.hpp | 15 ++-- .../src/operation_mode.hpp | 12 +-- .../autoware_default_adapi/src/perception.cpp | 5 +- .../autoware_default_adapi/src/perception.hpp | 9 ++- .../autoware_default_adapi/src/planning.hpp | 14 ++-- system/autoware_default_adapi/src/routing.cpp | 2 +- system/autoware_default_adapi/src/routing.hpp | 28 ++++--- system/autoware_default_adapi/src/vehicle.cpp | 28 +++---- system/autoware_default_adapi/src/vehicle.hpp | 81 +++++++++---------- .../src/vehicle_door.hpp | 13 +-- 60 files changed, 239 insertions(+), 231 deletions(-) rename common/{autoware_component_interface_specs => autoware_component_interface_specs_universe}/CHANGELOG.rst (97%) rename common/{autoware_component_interface_specs => autoware_component_interface_specs_universe}/CMakeLists.txt (88%) rename common/{autoware_component_interface_specs => autoware_component_interface_specs_universe}/README.md (55%) rename common/{autoware_component_interface_specs/include/autoware/component_interface_specs => autoware_component_interface_specs_universe/include/autoware/component_interface_specs_universe}/control.hpp (86%) rename common/{autoware_component_interface_specs/include/autoware/component_interface_specs => autoware_component_interface_specs_universe/include/autoware/component_interface_specs_universe}/localization.hpp (85%) rename common/{autoware_component_interface_specs/include/autoware/component_interface_specs => autoware_component_interface_specs_universe/include/autoware/component_interface_specs_universe}/map.hpp (76%) rename common/{autoware_component_interface_specs/include/autoware/component_interface_specs => autoware_component_interface_specs_universe/include/autoware/component_interface_specs_universe}/perception.hpp (74%) rename common/{autoware_component_interface_specs/include/autoware/component_interface_specs => autoware_component_interface_specs_universe/include/autoware/component_interface_specs_universe}/planning.hpp (88%) rename common/{autoware_component_interface_specs/include/autoware/component_interface_specs => autoware_component_interface_specs_universe/include/autoware/component_interface_specs_universe}/system.hpp (85%) rename common/{autoware_component_interface_specs/include/autoware/component_interface_specs => autoware_component_interface_specs_universe/include/autoware/component_interface_specs_universe}/vehicle.hpp (91%) rename common/{autoware_component_interface_specs => autoware_component_interface_specs_universe}/package.xml (89%) rename common/{autoware_component_interface_specs => autoware_component_interface_specs_universe}/test/gtest_main.cpp (100%) rename common/{autoware_component_interface_specs => autoware_component_interface_specs_universe}/test/test_control.cpp (82%) rename common/{autoware_component_interface_specs => autoware_component_interface_specs_universe}/test/test_localization.cpp (81%) rename common/{autoware_component_interface_specs => autoware_component_interface_specs_universe}/test/test_map.cpp (86%) rename common/{autoware_component_interface_specs => autoware_component_interface_specs_universe}/test/test_perception.cpp (85%) rename common/{autoware_component_interface_specs => autoware_component_interface_specs_universe}/test/test_planning.cpp (81%) rename common/{autoware_component_interface_specs => autoware_component_interface_specs_universe}/test/test_system.cpp (83%) rename common/{autoware_component_interface_specs => autoware_component_interface_specs_universe}/test/test_vehicle.cpp (79%) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 4fea7c85e1926..526467d0e5e4f 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -1,7 +1,7 @@ ### Automatically generated from package.xml ### common/autoware_adapi_specs/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp common/autoware_auto_common/** opensource@apex.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp -common/autoware_component_interface_specs/** isamu.takagi@tier4.jp yukihiro.saito@tier4.jp +common/autoware_component_interface_specs_universe/** isamu.takagi@tier4.jp yukihiro.saito@tier4.jp common/autoware_component_interface_tools/** isamu.takagi@tier4.jp common/autoware_component_interface_utils/** isamu.takagi@tier4.jp yukihiro.saito@tier4.jp common/autoware_fake_test_node/** opensource@apex.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp diff --git a/common/.pages b/common/.pages index 3c5a77c4d68cf..f49b7e1f6ba3d 100644 --- a/common/.pages +++ b/common/.pages @@ -46,6 +46,6 @@ nav: - 'Path Distance Calculator': common/autoware_path_distance_calculator/Readme - 'Others': - 'autoware_adapi_specs': common/autoware_adapi_specs - - 'autoware_component_interface_specs': common/autoware_component_interface_specs + - 'autoware_component_interface_specs_universe': common/autoware_component_interface_specs_universe - 'autoware_component_interface_tools': common/autoware_component_interface_tools - 'autoware_component_interface_utils': common/autoware_component_interface_utils diff --git a/common/autoware_component_interface_specs/CHANGELOG.rst b/common/autoware_component_interface_specs_universe/CHANGELOG.rst similarity index 97% rename from common/autoware_component_interface_specs/CHANGELOG.rst rename to common/autoware_component_interface_specs_universe/CHANGELOG.rst index 43590966602d2..cf03005715b76 100644 --- a/common/autoware_component_interface_specs/CHANGELOG.rst +++ b/common/autoware_component_interface_specs_universe/CHANGELOG.rst @@ -1,5 +1,5 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package autoware_component_interface_specs +Changelog for package autoware_component_interface_specs_universe ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.40.0 (2024-12-12) diff --git a/common/autoware_component_interface_specs/CMakeLists.txt b/common/autoware_component_interface_specs_universe/CMakeLists.txt similarity index 88% rename from common/autoware_component_interface_specs/CMakeLists.txt rename to common/autoware_component_interface_specs_universe/CMakeLists.txt index a4e93cc8f04f9..b07b84edbdb80 100644 --- a/common/autoware_component_interface_specs/CMakeLists.txt +++ b/common/autoware_component_interface_specs_universe/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(autoware_component_interface_specs) +project(autoware_component_interface_specs_universe) find_package(autoware_cmake REQUIRED) autoware_package() diff --git a/common/autoware_component_interface_specs/README.md b/common/autoware_component_interface_specs_universe/README.md similarity index 55% rename from common/autoware_component_interface_specs/README.md rename to common/autoware_component_interface_specs_universe/README.md index 9d9298a95e329..3e372df1d83c7 100644 --- a/common/autoware_component_interface_specs/README.md +++ b/common/autoware_component_interface_specs_universe/README.md @@ -1,3 +1,3 @@ -# autoware_component_interface_specs +# autoware_component_interface_specs_universe This package is a specification of component interfaces. diff --git a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/control.hpp b/common/autoware_component_interface_specs_universe/include/autoware/component_interface_specs_universe/control.hpp similarity index 86% rename from common/autoware_component_interface_specs/include/autoware/component_interface_specs/control.hpp rename to common/autoware_component_interface_specs_universe/include/autoware/component_interface_specs_universe/control.hpp index 03c93d75d674b..8c289a29c4792 100644 --- a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/control.hpp +++ b/common/autoware_component_interface_specs_universe/include/autoware/component_interface_specs_universe/control.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__CONTROL_HPP_ -#define AUTOWARE__COMPONENT_INTERFACE_SPECS__CONTROL_HPP_ +#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS_UNIVERSE__CONTROL_HPP_ +#define AUTOWARE__COMPONENT_INTERFACE_SPECS_UNIVERSE__CONTROL_HPP_ #include @@ -23,7 +23,7 @@ #include #include -namespace autoware::component_interface_specs::control +namespace autoware::component_interface_specs_universe::control { struct SetPause @@ -65,6 +65,6 @@ struct IsStopped static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL; }; -} // namespace autoware::component_interface_specs::control +} // namespace autoware::component_interface_specs_universe::control -#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__CONTROL_HPP_ +#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS_UNIVERSE__CONTROL_HPP_ diff --git a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/localization.hpp b/common/autoware_component_interface_specs_universe/include/autoware/component_interface_specs_universe/localization.hpp similarity index 85% rename from common/autoware_component_interface_specs/include/autoware/component_interface_specs/localization.hpp rename to common/autoware_component_interface_specs_universe/include/autoware/component_interface_specs_universe/localization.hpp index b2e41a179506a..8e9680fef4210 100644 --- a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/localization.hpp +++ b/common/autoware_component_interface_specs_universe/include/autoware/component_interface_specs_universe/localization.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__LOCALIZATION_HPP_ -#define AUTOWARE__COMPONENT_INTERFACE_SPECS__LOCALIZATION_HPP_ +#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS_UNIVERSE__LOCALIZATION_HPP_ +#define AUTOWARE__COMPONENT_INTERFACE_SPECS_UNIVERSE__LOCALIZATION_HPP_ #include @@ -22,7 +22,7 @@ #include #include -namespace autoware::component_interface_specs::localization +namespace autoware::component_interface_specs_universe::localization { struct Initialize @@ -58,6 +58,6 @@ struct Acceleration static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE; }; -} // namespace autoware::component_interface_specs::localization +} // namespace autoware::component_interface_specs_universe::localization -#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__LOCALIZATION_HPP_ +#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS_UNIVERSE__LOCALIZATION_HPP_ diff --git a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/map.hpp b/common/autoware_component_interface_specs_universe/include/autoware/component_interface_specs_universe/map.hpp similarity index 76% rename from common/autoware_component_interface_specs/include/autoware/component_interface_specs/map.hpp rename to common/autoware_component_interface_specs_universe/include/autoware/component_interface_specs_universe/map.hpp index aeb09e44c665f..ced71d0eb47db 100644 --- a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/map.hpp +++ b/common/autoware_component_interface_specs_universe/include/autoware/component_interface_specs_universe/map.hpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__MAP_HPP_ -#define AUTOWARE__COMPONENT_INTERFACE_SPECS__MAP_HPP_ +#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS_UNIVERSE__MAP_HPP_ +#define AUTOWARE__COMPONENT_INTERFACE_SPECS_UNIVERSE__MAP_HPP_ #include #include -namespace autoware::component_interface_specs::map +namespace autoware::component_interface_specs_universe::map { struct MapProjectorInfo @@ -31,6 +31,6 @@ struct MapProjectorInfo static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL; }; -} // namespace autoware::component_interface_specs::map +} // namespace autoware::component_interface_specs_universe::map -#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__MAP_HPP_ +#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS_UNIVERSE__MAP_HPP_ diff --git a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/perception.hpp b/common/autoware_component_interface_specs_universe/include/autoware/component_interface_specs_universe/perception.hpp similarity index 74% rename from common/autoware_component_interface_specs/include/autoware/component_interface_specs/perception.hpp rename to common/autoware_component_interface_specs_universe/include/autoware/component_interface_specs_universe/perception.hpp index 4f450e6a3ee1c..42adf7d1d54ae 100644 --- a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/perception.hpp +++ b/common/autoware_component_interface_specs_universe/include/autoware/component_interface_specs_universe/perception.hpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__PERCEPTION_HPP_ -#define AUTOWARE__COMPONENT_INTERFACE_SPECS__PERCEPTION_HPP_ +#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS_UNIVERSE__PERCEPTION_HPP_ +#define AUTOWARE__COMPONENT_INTERFACE_SPECS_UNIVERSE__PERCEPTION_HPP_ #include #include -namespace autoware::component_interface_specs::perception +namespace autoware::component_interface_specs_universe::perception { struct ObjectRecognition @@ -31,6 +31,6 @@ struct ObjectRecognition static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE; }; -} // namespace autoware::component_interface_specs::perception +} // namespace autoware::component_interface_specs_universe::perception -#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__PERCEPTION_HPP_ +#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS_UNIVERSE__PERCEPTION_HPP_ diff --git a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/planning.hpp b/common/autoware_component_interface_specs_universe/include/autoware/component_interface_specs_universe/planning.hpp similarity index 88% rename from common/autoware_component_interface_specs/include/autoware/component_interface_specs/planning.hpp rename to common/autoware_component_interface_specs_universe/include/autoware/component_interface_specs_universe/planning.hpp index 247844123881b..7e79a47c70676 100644 --- a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/planning.hpp +++ b/common/autoware_component_interface_specs_universe/include/autoware/component_interface_specs_universe/planning.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__PLANNING_HPP_ -#define AUTOWARE__COMPONENT_INTERFACE_SPECS__PLANNING_HPP_ +#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS_UNIVERSE__PLANNING_HPP_ +#define AUTOWARE__COMPONENT_INTERFACE_SPECS_UNIVERSE__PLANNING_HPP_ #include @@ -24,7 +24,7 @@ #include #include -namespace autoware::component_interface_specs::planning +namespace autoware::component_interface_specs_universe::planning { struct SetLaneletRoute @@ -73,6 +73,6 @@ struct Trajectory static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE; }; -} // namespace autoware::component_interface_specs::planning +} // namespace autoware::component_interface_specs_universe::planning -#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__PLANNING_HPP_ +#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS_UNIVERSE__PLANNING_HPP_ diff --git a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/system.hpp b/common/autoware_component_interface_specs_universe/include/autoware/component_interface_specs_universe/system.hpp similarity index 85% rename from common/autoware_component_interface_specs/include/autoware/component_interface_specs/system.hpp rename to common/autoware_component_interface_specs_universe/include/autoware/component_interface_specs_universe/system.hpp index 6ae3447c0786d..11e69b0cd26a1 100644 --- a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/system.hpp +++ b/common/autoware_component_interface_specs_universe/include/autoware/component_interface_specs_universe/system.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__SYSTEM_HPP_ -#define AUTOWARE__COMPONENT_INTERFACE_SPECS__SYSTEM_HPP_ +#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS_UNIVERSE__SYSTEM_HPP_ +#define AUTOWARE__COMPONENT_INTERFACE_SPECS_UNIVERSE__SYSTEM_HPP_ #include @@ -22,7 +22,7 @@ #include #include -namespace autoware::component_interface_specs::system +namespace autoware::component_interface_specs_universe::system { struct MrmState @@ -55,6 +55,6 @@ struct OperationModeState static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL; }; -} // namespace autoware::component_interface_specs::system +} // namespace autoware::component_interface_specs_universe::system -#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__SYSTEM_HPP_ +#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS_UNIVERSE__SYSTEM_HPP_ diff --git a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/vehicle.hpp b/common/autoware_component_interface_specs_universe/include/autoware/component_interface_specs_universe/vehicle.hpp similarity index 91% rename from common/autoware_component_interface_specs/include/autoware/component_interface_specs/vehicle.hpp rename to common/autoware_component_interface_specs_universe/include/autoware/component_interface_specs_universe/vehicle.hpp index 6c071299faae8..8db960f83ca15 100644 --- a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/vehicle.hpp +++ b/common/autoware_component_interface_specs_universe/include/autoware/component_interface_specs_universe/vehicle.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_ -#define AUTOWARE__COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_ +#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS_UNIVERSE__VEHICLE_HPP_ +#define AUTOWARE__COMPONENT_INTERFACE_SPECS_UNIVERSE__VEHICLE_HPP_ #include @@ -26,7 +26,7 @@ #include #include -namespace autoware::component_interface_specs::vehicle +namespace autoware::component_interface_specs_universe::vehicle { struct SteeringStatus @@ -95,6 +95,6 @@ struct DoorStatus static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL; }; -} // namespace autoware::component_interface_specs::vehicle +} // namespace autoware::component_interface_specs_universe::vehicle -#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_ +#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS_UNIVERSE__VEHICLE_HPP_ diff --git a/common/autoware_component_interface_specs/package.xml b/common/autoware_component_interface_specs_universe/package.xml similarity index 89% rename from common/autoware_component_interface_specs/package.xml rename to common/autoware_component_interface_specs_universe/package.xml index 4bbe62e7e9701..8e29921b1a873 100644 --- a/common/autoware_component_interface_specs/package.xml +++ b/common/autoware_component_interface_specs_universe/package.xml @@ -1,9 +1,9 @@ - autoware_component_interface_specs + autoware_component_interface_specs_universe 0.40.0 - The autoware_component_interface_specs package + The autoware_component_interface_specs_universe package Takagi, Isamu Yukihiro Saito Apache License 2.0 diff --git a/common/autoware_component_interface_specs/test/gtest_main.cpp b/common/autoware_component_interface_specs_universe/test/gtest_main.cpp similarity index 100% rename from common/autoware_component_interface_specs/test/gtest_main.cpp rename to common/autoware_component_interface_specs_universe/test/gtest_main.cpp diff --git a/common/autoware_component_interface_specs/test/test_control.cpp b/common/autoware_component_interface_specs_universe/test/test_control.cpp similarity index 82% rename from common/autoware_component_interface_specs/test/test_control.cpp rename to common/autoware_component_interface_specs_universe/test/test_control.cpp index db6e7817e7a9d..5095a1b1be4bf 100644 --- a/common/autoware_component_interface_specs/test/test_control.cpp +++ b/common/autoware_component_interface_specs_universe/test/test_control.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware/component_interface_specs/control.hpp" +#include "autoware/component_interface_specs_universe/control.hpp" #include "gtest/gtest.h" TEST(control, interface) { { - using autoware::component_interface_specs::control::IsPaused; + using autoware::component_interface_specs_universe::control::IsPaused; IsPaused is_paused; size_t depth = 1; EXPECT_EQ(is_paused.depth, depth); @@ -27,7 +27,7 @@ TEST(control, interface) } { - using autoware::component_interface_specs::control::IsStartRequested; + using autoware::component_interface_specs_universe::control::IsStartRequested; IsStartRequested is_start_requested; size_t depth = 1; EXPECT_EQ(is_start_requested.depth, depth); @@ -36,7 +36,7 @@ TEST(control, interface) } { - using autoware::component_interface_specs::control::IsStopped; + using autoware::component_interface_specs_universe::control::IsStopped; IsStopped is_stopped; size_t depth = 1; EXPECT_EQ(is_stopped.depth, depth); diff --git a/common/autoware_component_interface_specs/test/test_localization.cpp b/common/autoware_component_interface_specs_universe/test/test_localization.cpp similarity index 81% rename from common/autoware_component_interface_specs/test/test_localization.cpp rename to common/autoware_component_interface_specs_universe/test/test_localization.cpp index 18ec5f15acaf8..43bad964907e2 100644 --- a/common/autoware_component_interface_specs/test/test_localization.cpp +++ b/common/autoware_component_interface_specs_universe/test/test_localization.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware/component_interface_specs/localization.hpp" +#include "autoware/component_interface_specs_universe/localization.hpp" #include "gtest/gtest.h" TEST(localization, interface) { { - using autoware::component_interface_specs::localization::InitializationState; + using autoware::component_interface_specs_universe::localization::InitializationState; InitializationState initialization_state; size_t depth = 1; EXPECT_EQ(initialization_state.depth, depth); @@ -27,7 +27,7 @@ TEST(localization, interface) } { - using autoware::component_interface_specs::localization::KinematicState; + using autoware::component_interface_specs_universe::localization::KinematicState; KinematicState kinematic_state; size_t depth = 1; EXPECT_EQ(kinematic_state.depth, depth); @@ -36,7 +36,7 @@ TEST(localization, interface) } { - using autoware::component_interface_specs::localization::Acceleration; + using autoware::component_interface_specs_universe::localization::Acceleration; Acceleration acceleration; size_t depth = 1; EXPECT_EQ(acceleration.depth, depth); diff --git a/common/autoware_component_interface_specs/test/test_map.cpp b/common/autoware_component_interface_specs_universe/test/test_map.cpp similarity index 86% rename from common/autoware_component_interface_specs/test/test_map.cpp rename to common/autoware_component_interface_specs_universe/test/test_map.cpp index aafb33e73c9dc..ed7932eb5f3a3 100644 --- a/common/autoware_component_interface_specs/test/test_map.cpp +++ b/common/autoware_component_interface_specs_universe/test/test_map.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware/component_interface_specs/map.hpp" +#include "autoware/component_interface_specs_universe/map.hpp" #include "gtest/gtest.h" TEST(map, interface) { { - using autoware::component_interface_specs::map::MapProjectorInfo; + using autoware::component_interface_specs_universe::map::MapProjectorInfo; MapProjectorInfo map_projector; size_t depth = 1; EXPECT_EQ(map_projector.depth, depth); diff --git a/common/autoware_component_interface_specs/test/test_perception.cpp b/common/autoware_component_interface_specs_universe/test/test_perception.cpp similarity index 85% rename from common/autoware_component_interface_specs/test/test_perception.cpp rename to common/autoware_component_interface_specs_universe/test/test_perception.cpp index 8ad6d9dfceb6f..ddf84ab7f1196 100644 --- a/common/autoware_component_interface_specs/test/test_perception.cpp +++ b/common/autoware_component_interface_specs_universe/test/test_perception.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware/component_interface_specs/perception.hpp" +#include "autoware/component_interface_specs_universe/perception.hpp" #include "gtest/gtest.h" TEST(perception, interface) { { - using autoware::component_interface_specs::perception::ObjectRecognition; + using autoware::component_interface_specs_universe::perception::ObjectRecognition; ObjectRecognition object_recognition; size_t depth = 1; EXPECT_EQ(object_recognition.depth, depth); diff --git a/common/autoware_component_interface_specs/test/test_planning.cpp b/common/autoware_component_interface_specs_universe/test/test_planning.cpp similarity index 81% rename from common/autoware_component_interface_specs/test/test_planning.cpp rename to common/autoware_component_interface_specs_universe/test/test_planning.cpp index 8278bf86f3861..3eff1653d298c 100644 --- a/common/autoware_component_interface_specs/test/test_planning.cpp +++ b/common/autoware_component_interface_specs_universe/test/test_planning.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware/component_interface_specs/planning.hpp" +#include "autoware/component_interface_specs_universe/planning.hpp" #include "gtest/gtest.h" TEST(planning, interface) { { - using autoware::component_interface_specs::planning::RouteState; + using autoware::component_interface_specs_universe::planning::RouteState; RouteState state; size_t depth = 1; EXPECT_EQ(state.depth, depth); @@ -27,7 +27,7 @@ TEST(planning, interface) } { - using autoware::component_interface_specs::planning::LaneletRoute; + using autoware::component_interface_specs_universe::planning::LaneletRoute; LaneletRoute route; size_t depth = 1; EXPECT_EQ(route.depth, depth); @@ -36,7 +36,7 @@ TEST(planning, interface) } { - using autoware::component_interface_specs::planning::Trajectory; + using autoware::component_interface_specs_universe::planning::Trajectory; Trajectory trajectory; size_t depth = 1; EXPECT_EQ(trajectory.depth, depth); diff --git a/common/autoware_component_interface_specs/test/test_system.cpp b/common/autoware_component_interface_specs_universe/test/test_system.cpp similarity index 83% rename from common/autoware_component_interface_specs/test/test_system.cpp rename to common/autoware_component_interface_specs_universe/test/test_system.cpp index 3faff08734905..af2befc7b481d 100644 --- a/common/autoware_component_interface_specs/test/test_system.cpp +++ b/common/autoware_component_interface_specs_universe/test/test_system.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware/component_interface_specs/system.hpp" +#include "autoware/component_interface_specs_universe/system.hpp" #include "gtest/gtest.h" TEST(system, interface) { { - using autoware::component_interface_specs::system::MrmState; + using autoware::component_interface_specs_universe::system::MrmState; MrmState state; size_t depth = 1; EXPECT_EQ(state.depth, depth); @@ -27,7 +27,7 @@ TEST(system, interface) } { - using autoware::component_interface_specs::system::OperationModeState; + using autoware::component_interface_specs_universe::system::OperationModeState; OperationModeState state; size_t depth = 1; EXPECT_EQ(state.depth, depth); diff --git a/common/autoware_component_interface_specs/test/test_vehicle.cpp b/common/autoware_component_interface_specs_universe/test/test_vehicle.cpp similarity index 79% rename from common/autoware_component_interface_specs/test/test_vehicle.cpp rename to common/autoware_component_interface_specs_universe/test/test_vehicle.cpp index e9ee65e2fa210..53eaede43ffd8 100644 --- a/common/autoware_component_interface_specs/test/test_vehicle.cpp +++ b/common/autoware_component_interface_specs_universe/test/test_vehicle.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware/component_interface_specs/vehicle.hpp" +#include "autoware/component_interface_specs_universe/vehicle.hpp" #include "gtest/gtest.h" TEST(vehicle, interface) { { - using autoware::component_interface_specs::vehicle::SteeringStatus; + using autoware::component_interface_specs_universe::vehicle::SteeringStatus; SteeringStatus status; size_t depth = 1; EXPECT_EQ(status.depth, depth); @@ -27,7 +27,7 @@ TEST(vehicle, interface) } { - using autoware::component_interface_specs::vehicle::GearStatus; + using autoware::component_interface_specs_universe::vehicle::GearStatus; GearStatus status; size_t depth = 1; EXPECT_EQ(status.depth, depth); @@ -36,7 +36,7 @@ TEST(vehicle, interface) } { - using autoware::component_interface_specs::vehicle::TurnIndicatorStatus; + using autoware::component_interface_specs_universe::vehicle::TurnIndicatorStatus; TurnIndicatorStatus status; size_t depth = 1; EXPECT_EQ(status.depth, depth); @@ -45,7 +45,7 @@ TEST(vehicle, interface) } { - using autoware::component_interface_specs::vehicle::HazardLightStatus; + using autoware::component_interface_specs_universe::vehicle::HazardLightStatus; HazardLightStatus status; size_t depth = 1; EXPECT_EQ(status.depth, depth); @@ -54,7 +54,7 @@ TEST(vehicle, interface) } { - using autoware::component_interface_specs::vehicle::EnergyStatus; + using autoware::component_interface_specs_universe::vehicle::EnergyStatus; EnergyStatus status; size_t depth = 1; EXPECT_EQ(status.depth, depth); diff --git a/common/autoware_test_utils/package.xml b/common/autoware_test_utils/package.xml index f67b366480b00..4a7e0f15ba74c 100644 --- a/common/autoware_test_utils/package.xml +++ b/common/autoware_test_utils/package.xml @@ -17,7 +17,7 @@ autoware_cmake ament_index_cpp - autoware_component_interface_specs + autoware_component_interface_specs_universe autoware_component_interface_utils autoware_control_msgs autoware_lanelet2_extension diff --git a/control/autoware_operation_mode_transition_manager/package.xml b/control/autoware_operation_mode_transition_manager/package.xml index eb4d50b625f11..f82d610ba791b 100644 --- a/control/autoware_operation_mode_transition_manager/package.xml +++ b/control/autoware_operation_mode_transition_manager/package.xml @@ -12,7 +12,7 @@ autoware_cmake rosidl_default_generators - autoware_component_interface_specs + autoware_component_interface_specs_universe autoware_component_interface_utils autoware_control_msgs autoware_motion_utils diff --git a/control/autoware_operation_mode_transition_manager/src/node.hpp b/control/autoware_operation_mode_transition_manager/src/node.hpp index a24a36407537f..ffef5f5fe999d 100644 --- a/control/autoware_operation_mode_transition_manager/src/node.hpp +++ b/control/autoware_operation_mode_transition_manager/src/node.hpp @@ -18,7 +18,7 @@ #include "compatibility.hpp" #include "state.hpp" -#include +#include #include #include #include @@ -36,9 +36,11 @@ class OperationModeTransitionManager : public rclcpp::Node private: using ChangeAutowareControlAPI = - autoware::component_interface_specs::system::ChangeAutowareControl; - using ChangeOperationModeAPI = autoware::component_interface_specs::system::ChangeOperationMode; - using OperationModeStateAPI = autoware::component_interface_specs::system::OperationModeState; + autoware::component_interface_specs_universe::system::ChangeAutowareControl; + using ChangeOperationModeAPI = + autoware::component_interface_specs_universe::system::ChangeOperationMode; + using OperationModeStateAPI = + autoware::component_interface_specs_universe::system::OperationModeState; autoware::component_interface_utils::Service::SharedPtr srv_autoware_control_; autoware::component_interface_utils::Service::SharedPtr diff --git a/control/autoware_vehicle_cmd_gate/package.xml b/control/autoware_vehicle_cmd_gate/package.xml index c3697337e2256..6eddf68595c5e 100644 --- a/control/autoware_vehicle_cmd_gate/package.xml +++ b/control/autoware_vehicle_cmd_gate/package.xml @@ -16,7 +16,7 @@ rosidl_default_generators autoware_adapi_v1_msgs - autoware_component_interface_specs + autoware_component_interface_specs_universe autoware_component_interface_utils autoware_control_msgs autoware_motion_utils diff --git a/control/autoware_vehicle_cmd_gate/src/adapi_pause_interface.hpp b/control/autoware_vehicle_cmd_gate/src/adapi_pause_interface.hpp index 3ddbff82e3102..5466497b7ee27 100644 --- a/control/autoware_vehicle_cmd_gate/src/adapi_pause_interface.hpp +++ b/control/autoware_vehicle_cmd_gate/src/adapi_pause_interface.hpp @@ -15,7 +15,7 @@ #ifndef ADAPI_PAUSE_INTERFACE_HPP_ #define ADAPI_PAUSE_INTERFACE_HPP_ -#include +#include #include #include @@ -29,9 +29,9 @@ class AdapiPauseInterface private: static constexpr double eps = 1e-3; using Control = autoware_control_msgs::msg::Control; - using SetPause = autoware::component_interface_specs::control::SetPause; - using IsPaused = autoware::component_interface_specs::control::IsPaused; - using IsStartRequested = autoware::component_interface_specs::control::IsStartRequested; + using SetPause = autoware::component_interface_specs_universe::control::SetPause; + using IsPaused = autoware::component_interface_specs_universe::control::IsPaused; + using IsStartRequested = autoware::component_interface_specs_universe::control::IsStartRequested; public: explicit AdapiPauseInterface(rclcpp::Node * node); diff --git a/control/autoware_vehicle_cmd_gate/src/moderate_stop_interface.hpp b/control/autoware_vehicle_cmd_gate/src/moderate_stop_interface.hpp index 2cef0071b0dd9..bebdcbfa0e208 100644 --- a/control/autoware_vehicle_cmd_gate/src/moderate_stop_interface.hpp +++ b/control/autoware_vehicle_cmd_gate/src/moderate_stop_interface.hpp @@ -15,7 +15,7 @@ #ifndef MODERATE_STOP_INTERFACE_HPP_ #define MODERATE_STOP_INTERFACE_HPP_ -#include +#include #include #include @@ -28,9 +28,9 @@ namespace autoware::vehicle_cmd_gate class ModerateStopInterface { private: - using SetStop = autoware::component_interface_specs::control::SetStop; - using IsStopped = autoware::component_interface_specs::control::IsStopped; - using IsStartRequested = autoware::component_interface_specs::control::IsStartRequested; + using SetStop = autoware::component_interface_specs_universe::control::SetStop; + using IsStopped = autoware::component_interface_specs_universe::control::IsStopped; + using IsStartRequested = autoware::component_interface_specs_universe::control::IsStartRequested; public: explicit ModerateStopInterface(rclcpp::Node * node); diff --git a/control/predicted_path_checker/include/predicted_path_checker/predicted_path_checker_node.hpp b/control/predicted_path_checker/include/predicted_path_checker/predicted_path_checker_node.hpp index af19f87fecc76..68b879743c5c5 100644 --- a/control/predicted_path_checker/include/predicted_path_checker/predicted_path_checker_node.hpp +++ b/control/predicted_path_checker/include/predicted_path_checker/predicted_path_checker_node.hpp @@ -15,7 +15,7 @@ #ifndef PREDICTED_PATH_CHECKER__PREDICTED_PATH_CHECKER_NODE_HPP_ #define PREDICTED_PATH_CHECKER__PREDICTED_PATH_CHECKER_NODE_HPP_ -#include +#include #include #include #include @@ -97,11 +97,11 @@ class PredictedPathCheckerNode : public rclcpp::Node rclcpp::Subscription::SharedPtr sub_odom_; rclcpp::Subscription::SharedPtr sub_accel_; autoware::component_interface_utils::Subscription< - autoware::component_interface_specs::control::IsStopped>::SharedPtr sub_stop_state_; + autoware::component_interface_specs_universe::control::IsStopped>::SharedPtr sub_stop_state_; // Client autoware::component_interface_utils::Client< - autoware::component_interface_specs::control::SetStop>::SharedPtr cli_set_stop_; + autoware::component_interface_specs_universe::control::SetStop>::SharedPtr cli_set_stop_; // Data Buffer geometry_msgs::msg::PoseStamped::ConstSharedPtr current_pose_; @@ -110,8 +110,8 @@ class PredictedPathCheckerNode : public rclcpp::Node PredictedObjects::ConstSharedPtr object_ptr_{nullptr}; autoware_planning_msgs::msg::Trajectory::ConstSharedPtr reference_trajectory_; autoware_planning_msgs::msg::Trajectory::ConstSharedPtr predicted_trajectory_; - autoware::component_interface_specs::control::IsStopped::Message::ConstSharedPtr is_stopped_ptr_{ - nullptr}; + autoware::component_interface_specs_universe::control::IsStopped::Message::ConstSharedPtr + is_stopped_ptr_{nullptr}; // Core std::unique_ptr collision_checker_; @@ -130,7 +130,8 @@ class PredictedPathCheckerNode : public rclcpp::Node void onOdom(const nav_msgs::msg::Odometry::SharedPtr msg); void onAccel(const geometry_msgs::msg::AccelWithCovarianceStamped::SharedPtr msg); void onIsStopped( - const autoware::component_interface_specs::control::IsStopped::Message::ConstSharedPtr msg); + const autoware::component_interface_specs_universe::control::IsStopped::Message::ConstSharedPtr + msg); // Timer rclcpp::TimerBase::SharedPtr timer_; diff --git a/control/predicted_path_checker/package.xml b/control/predicted_path_checker/package.xml index e2f9d17769e1a..a6780a4c00519 100644 --- a/control/predicted_path_checker/package.xml +++ b/control/predicted_path_checker/package.xml @@ -12,7 +12,7 @@ ament_cmake autoware_cmake - autoware_component_interface_specs + autoware_component_interface_specs_universe autoware_component_interface_utils autoware_motion_utils autoware_perception_msgs diff --git a/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp b/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp index a743b8cead5e7..f199bc731e68e 100644 --- a/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp +++ b/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp @@ -132,7 +132,8 @@ void PredictedPathCheckerNode::onAccel( } void PredictedPathCheckerNode::onIsStopped( - const autoware::component_interface_specs::control::IsStopped::Message::ConstSharedPtr msg) + const autoware::component_interface_specs_universe::control::IsStopped::Message::ConstSharedPtr + msg) { is_stopped_ptr_ = msg; @@ -415,8 +416,8 @@ void PredictedPathCheckerNode::checkVehicleState(diagnostic_updater::DiagnosticS void PredictedPathCheckerNode::sendRequest(bool make_stop_vehicle) { if (!is_calling_set_stop_ && cli_set_stop_->service_is_ready()) { - const auto req = - std::make_shared(); + const auto req = std::make_shared< + autoware::component_interface_specs_universe::control::SetStop::Service::Request>(); req->stop = make_stop_vehicle; req->request_source = "predicted_path_checker"; is_calling_set_stop_ = true; diff --git a/localization/autoware_geo_pose_projector/package.xml b/localization/autoware_geo_pose_projector/package.xml index 6dda1d6418406..f7240c83ab152 100644 --- a/localization/autoware_geo_pose_projector/package.xml +++ b/localization/autoware_geo_pose_projector/package.xml @@ -17,7 +17,7 @@ ament_cmake_auto autoware_cmake - autoware_component_interface_specs + autoware_component_interface_specs_universe autoware_component_interface_utils autoware_geography_utils geographic_msgs diff --git a/localization/autoware_geo_pose_projector/src/geo_pose_projector.hpp b/localization/autoware_geo_pose_projector/src/geo_pose_projector.hpp index f45605968c8c9..cae37d4b682d8 100644 --- a/localization/autoware_geo_pose_projector/src/geo_pose_projector.hpp +++ b/localization/autoware_geo_pose_projector/src/geo_pose_projector.hpp @@ -15,7 +15,7 @@ #ifndef GEO_POSE_PROJECTOR_HPP_ #define GEO_POSE_PROJECTOR_HPP_ -#include +#include #include #include @@ -35,7 +35,7 @@ class GeoPoseProjector : public rclcpp::Node private: using GeoPoseWithCovariance = geographic_msgs::msg::GeoPoseWithCovarianceStamped; using PoseWithCovariance = geometry_msgs::msg::PoseWithCovarianceStamped; - using MapProjectorInfo = autoware::component_interface_specs::map::MapProjectorInfo; + using MapProjectorInfo = autoware::component_interface_specs_universe::map::MapProjectorInfo; public: explicit GeoPoseProjector(const rclcpp::NodeOptions & options); diff --git a/localization/autoware_pose_initializer/package.xml b/localization/autoware_pose_initializer/package.xml index de3ecd880ea45..693dcad0260b5 100644 --- a/localization/autoware_pose_initializer/package.xml +++ b/localization/autoware_pose_initializer/package.xml @@ -19,7 +19,7 @@ ament_cmake autoware_cmake - autoware_component_interface_specs + autoware_component_interface_specs_universe autoware_component_interface_utils autoware_map_height_fitter autoware_motion_utils diff --git a/localization/autoware_pose_initializer/src/ekf_localization_trigger_module.cpp b/localization/autoware_pose_initializer/src/ekf_localization_trigger_module.cpp index 089b941141074..0325a3d9a5e94 100644 --- a/localization/autoware_pose_initializer/src/ekf_localization_trigger_module.cpp +++ b/localization/autoware_pose_initializer/src/ekf_localization_trigger_module.cpp @@ -14,7 +14,7 @@ #include "ekf_localization_trigger_module.hpp" -#include +#include #include #include @@ -23,7 +23,7 @@ namespace autoware::pose_initializer { using ServiceException = autoware::component_interface_utils::ServiceException; -using Initialize = autoware::component_interface_specs::localization::Initialize; +using Initialize = autoware::component_interface_specs_universe::localization::Initialize; EkfLocalizationTriggerModule::EkfLocalizationTriggerModule(rclcpp::Node * node) : node_(node) { diff --git a/localization/autoware_pose_initializer/src/gnss_module.cpp b/localization/autoware_pose_initializer/src/gnss_module.cpp index b238100a764e7..3ef12ef66f0c8 100644 --- a/localization/autoware_pose_initializer/src/gnss_module.cpp +++ b/localization/autoware_pose_initializer/src/gnss_module.cpp @@ -14,7 +14,7 @@ #include "gnss_module.hpp" -#include +#include #include #include @@ -37,7 +37,7 @@ void GnssModule::on_pose(PoseWithCovarianceStamped::ConstSharedPtr msg) geometry_msgs::msg::PoseWithCovarianceStamped GnssModule::get_pose() { - using Initialize = autoware::component_interface_specs::localization::Initialize; + using Initialize = autoware::component_interface_specs_universe::localization::Initialize; if (!pose_) { throw autoware::component_interface_utils::ServiceException( diff --git a/localization/autoware_pose_initializer/src/localization_module.cpp b/localization/autoware_pose_initializer/src/localization_module.cpp index e3fdeec6934fe..e38e8f14c6dd4 100644 --- a/localization/autoware_pose_initializer/src/localization_module.cpp +++ b/localization/autoware_pose_initializer/src/localization_module.cpp @@ -14,7 +14,7 @@ #include "localization_module.hpp" -#include +#include #include #include @@ -24,7 +24,7 @@ namespace autoware::pose_initializer { using ServiceException = autoware::component_interface_utils::ServiceException; -using Initialize = autoware::component_interface_specs::localization::Initialize; +using Initialize = autoware::component_interface_specs_universe::localization::Initialize; using PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped; LocalizationModule::LocalizationModule(rclcpp::Node * node, const std::string & service_name) diff --git a/localization/autoware_pose_initializer/src/ndt_localization_trigger_module.cpp b/localization/autoware_pose_initializer/src/ndt_localization_trigger_module.cpp index f66fbe72333ac..fa3c88d04e7bb 100644 --- a/localization/autoware_pose_initializer/src/ndt_localization_trigger_module.cpp +++ b/localization/autoware_pose_initializer/src/ndt_localization_trigger_module.cpp @@ -14,7 +14,7 @@ #include "ndt_localization_trigger_module.hpp" -#include +#include #include #include @@ -23,7 +23,7 @@ namespace autoware::pose_initializer { using ServiceException = autoware::component_interface_utils::ServiceException; -using Initialize = autoware::component_interface_specs::localization::Initialize; +using Initialize = autoware::component_interface_specs_universe::localization::Initialize; NdtLocalizationTriggerModule::NdtLocalizationTriggerModule(rclcpp::Node * node) : node_(node) { diff --git a/localization/autoware_pose_initializer/src/pose_initializer_core.hpp b/localization/autoware_pose_initializer/src/pose_initializer_core.hpp index a0c1ed3a86576..2e152663dd170 100644 --- a/localization/autoware_pose_initializer/src/pose_initializer_core.hpp +++ b/localization/autoware_pose_initializer/src/pose_initializer_core.hpp @@ -15,7 +15,7 @@ #ifndef POSE_INITIALIZER_CORE_HPP_ #define POSE_INITIALIZER_CORE_HPP_ -#include +#include #include #include #include @@ -41,8 +41,8 @@ class PoseInitializer : public rclcpp::Node private: using ServiceException = autoware::component_interface_utils::ServiceException; - using Initialize = autoware::component_interface_specs::localization::Initialize; - using State = autoware::component_interface_specs::localization::InitializationState; + using Initialize = autoware::component_interface_specs_universe::localization::Initialize; + using State = autoware::component_interface_specs_universe::localization::InitializationState; using PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped; rclcpp::CallbackGroup::SharedPtr group_srv_; diff --git a/map/autoware_map_loader/include/autoware/map_loader/lanelet2_map_loader_node.hpp b/map/autoware_map_loader/include/autoware/map_loader/lanelet2_map_loader_node.hpp index 0922b1cb2bdd6..2e0eb14c02eae 100644 --- a/map/autoware_map_loader/include/autoware/map_loader/lanelet2_map_loader_node.hpp +++ b/map/autoware_map_loader/include/autoware/map_loader/lanelet2_map_loader_node.hpp @@ -15,7 +15,7 @@ #ifndef AUTOWARE__MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_ #define AUTOWARE__MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_ -#include +#include #include #include #include @@ -46,7 +46,7 @@ class Lanelet2MapLoaderNode : public rclcpp::Node const rclcpp::Time & now); private: - using MapProjectorInfo = autoware::component_interface_specs::map::MapProjectorInfo; + using MapProjectorInfo = autoware::component_interface_specs_universe::map::MapProjectorInfo; void on_map_projector_info(const MapProjectorInfo::Message::ConstSharedPtr msg); diff --git a/map/autoware_map_loader/package.xml b/map/autoware_map_loader/package.xml index 4d4eabc6e3f25..08d41466ec6ef 100644 --- a/map/autoware_map_loader/package.xml +++ b/map/autoware_map_loader/package.xml @@ -19,7 +19,7 @@ ament_cmake_auto autoware_cmake - autoware_component_interface_specs + autoware_component_interface_specs_universe autoware_component_interface_utils autoware_geography_utils autoware_lanelet2_extension diff --git a/map/autoware_map_projection_loader/include/autoware/map_projection_loader/map_projection_loader.hpp b/map/autoware_map_projection_loader/include/autoware/map_projection_loader/map_projection_loader.hpp index 1ca876dc035b2..6ae1e5b136777 100644 --- a/map/autoware_map_projection_loader/include/autoware/map_projection_loader/map_projection_loader.hpp +++ b/map/autoware_map_projection_loader/include/autoware/map_projection_loader/map_projection_loader.hpp @@ -17,7 +17,7 @@ #include "rclcpp/rclcpp.hpp" -#include +#include #include #include @@ -34,7 +34,7 @@ class MapProjectionLoader : public rclcpp::Node explicit MapProjectionLoader(const rclcpp::NodeOptions & options); private: - using MapProjectorInfo = autoware::component_interface_specs::map::MapProjectorInfo; + using MapProjectorInfo = autoware::component_interface_specs_universe::map::MapProjectorInfo; autoware::component_interface_utils::Publisher::SharedPtr publisher_; }; } // namespace autoware::map_projection_loader diff --git a/map/autoware_map_projection_loader/package.xml b/map/autoware_map_projection_loader/package.xml index ad31dfdcc094d..d3d739ea9ca7e 100644 --- a/map/autoware_map_projection_loader/package.xml +++ b/map/autoware_map_projection_loader/package.xml @@ -16,7 +16,7 @@ ament_cmake_auto autoware_cmake - autoware_component_interface_specs + autoware_component_interface_specs_universe autoware_component_interface_utils autoware_lanelet2_extension autoware_map_msgs diff --git a/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager.hpp b/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager.hpp index bb808484e10be..cf45154893af7 100644 --- a/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager.hpp +++ b/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager.hpp @@ -30,7 +30,7 @@ << std::endl; \ } -#include +#include #include #include diff --git a/planning/autoware_planning_test_manager/package.xml b/planning/autoware_planning_test_manager/package.xml index d5f8383913274..8bd31951ea0e9 100644 --- a/planning/autoware_planning_test_manager/package.xml +++ b/planning/autoware_planning_test_manager/package.xml @@ -14,7 +14,7 @@ ament_cmake_auto autoware_cmake - autoware_component_interface_specs + autoware_component_interface_specs_universe autoware_component_interface_utils autoware_control_msgs autoware_lanelet2_extension diff --git a/sensing/autoware_gnss_poser/include/autoware/gnss_poser/gnss_poser_node.hpp b/sensing/autoware_gnss_poser/include/autoware/gnss_poser/gnss_poser_node.hpp index e02c78319681b..d4ba9b994cbcb 100644 --- a/sensing/autoware_gnss_poser/include/autoware/gnss_poser/gnss_poser_node.hpp +++ b/sensing/autoware_gnss_poser/include/autoware/gnss_poser/gnss_poser_node.hpp @@ -14,7 +14,7 @@ #ifndef AUTOWARE__GNSS_POSER__GNSS_POSER_NODE_HPP_ #define AUTOWARE__GNSS_POSER__GNSS_POSER_NODE_HPP_ -#include +#include #include #include @@ -47,7 +47,7 @@ class GNSSPoser : public rclcpp::Node explicit GNSSPoser(const rclcpp::NodeOptions & node_options); private: - using MapProjectorInfo = autoware::component_interface_specs::map::MapProjectorInfo; + using MapProjectorInfo = autoware::component_interface_specs_universe::map::MapProjectorInfo; void callback_map_projector_info(const MapProjectorInfo::Message::ConstSharedPtr msg); void callback_nav_sat_fix(const sensor_msgs::msg::NavSatFix::ConstSharedPtr nav_sat_fix_msg_ptr); diff --git a/sensing/autoware_gnss_poser/package.xml b/sensing/autoware_gnss_poser/package.xml index 6414ccbabca3f..0a3d6391ac598 100644 --- a/sensing/autoware_gnss_poser/package.xml +++ b/sensing/autoware_gnss_poser/package.xml @@ -19,7 +19,7 @@ libboost-dev - autoware_component_interface_specs + autoware_component_interface_specs_universe autoware_component_interface_utils autoware_geography_utils autoware_sensing_msgs diff --git a/system/autoware_default_adapi/package.xml b/system/autoware_default_adapi/package.xml index e0d3fc0f9e21b..094882d0e4dd3 100644 --- a/system/autoware_default_adapi/package.xml +++ b/system/autoware_default_adapi/package.xml @@ -15,7 +15,7 @@ autoware_adapi_specs autoware_adapi_v1_msgs autoware_adapi_version_msgs - autoware_component_interface_specs + autoware_component_interface_specs_universe autoware_component_interface_utils autoware_geography_utils autoware_motion_utils diff --git a/system/autoware_default_adapi/src/fail_safe.hpp b/system/autoware_default_adapi/src/fail_safe.hpp index c5ee08643e802..61141c2453ebc 100644 --- a/system/autoware_default_adapi/src/fail_safe.hpp +++ b/system/autoware_default_adapi/src/fail_safe.hpp @@ -16,7 +16,7 @@ #define FAIL_SAFE_HPP_ #include -#include +#include #include #include @@ -34,7 +34,7 @@ class FailSafeNode : public rclcpp::Node private: using MrmState = autoware::adapi_specs::fail_safe::MrmState::Message; Pub pub_mrm_state_; - Sub sub_mrm_state_; + Sub sub_mrm_state_; MrmState prev_state_; void on_state(const MrmState::ConstSharedPtr msg); }; diff --git a/system/autoware_default_adapi/src/localization.hpp b/system/autoware_default_adapi/src/localization.hpp index ef4ffd52a6718..3575f6a027f6e 100644 --- a/system/autoware_default_adapi/src/localization.hpp +++ b/system/autoware_default_adapi/src/localization.hpp @@ -16,7 +16,7 @@ #define LOCALIZATION_HPP_ #include -#include +#include #include // This file should be included after messages. @@ -34,8 +34,8 @@ class LocalizationNode : public rclcpp::Node rclcpp::CallbackGroup::SharedPtr group_cli_; Srv srv_initialize_; Pub pub_state_; - Cli cli_initialize_; - Sub sub_state_; + Cli cli_initialize_; + Sub sub_state_; void on_initialize( const autoware::adapi_specs::localization::Initialize::Service::Request::SharedPtr req, diff --git a/system/autoware_default_adapi/src/motion.cpp b/system/autoware_default_adapi/src/motion.cpp index dd7d842c3f26f..36a08a5b0857a 100644 --- a/system/autoware_default_adapi/src/motion.cpp +++ b/system/autoware_default_adapi/src/motion.cpp @@ -121,8 +121,8 @@ void MotionNode::update_pause(const State state) void MotionNode::change_pause(bool pause) { if (!is_calling_set_pause_ && cli_set_pause_->service_is_ready()) { - const auto req = - std::make_shared(); + const auto req = std::make_shared< + autoware::component_interface_specs_universe::control::SetPause::Service::Request>(); req->pause = pause; is_calling_set_pause_ = true; cli_set_pause_->async_send_request(req, [this](auto) { is_calling_set_pause_ = false; }); @@ -135,14 +135,15 @@ void MotionNode::on_timer() } void MotionNode::on_is_paused( - const autoware::component_interface_specs::control::IsPaused::Message::ConstSharedPtr msg) + const autoware::component_interface_specs_universe::control::IsPaused::Message::ConstSharedPtr + msg) { is_paused_ = msg->data; update_state(); } -void MotionNode::on_is_start_requested( - const autoware::component_interface_specs::control::IsStartRequested::Message::ConstSharedPtr msg) +void MotionNode::on_is_start_requested(const autoware::component_interface_specs_universe::control:: + IsStartRequested::Message::ConstSharedPtr msg) { is_start_requested_ = msg->data; update_state(); diff --git a/system/autoware_default_adapi/src/motion.hpp b/system/autoware_default_adapi/src/motion.hpp index ce9cab6eb4bc7..6d099be0a5d6a 100644 --- a/system/autoware_default_adapi/src/motion.hpp +++ b/system/autoware_default_adapi/src/motion.hpp @@ -16,7 +16,7 @@ #define MOTION_HPP_ #include -#include +#include #include #include #include @@ -39,9 +39,10 @@ class MotionNode : public rclcpp::Node rclcpp::CallbackGroup::SharedPtr group_cli_; Srv srv_accept_; Pub pub_state_; - Cli cli_set_pause_; - Sub sub_is_paused_; - Sub sub_is_start_requested_; + Cli cli_set_pause_; + Sub sub_is_paused_; + Sub + sub_is_start_requested_; enum class State { Unknown, Pausing, Paused, Starting, Resuming, Resumed, Moving }; State state_; @@ -58,10 +59,10 @@ class MotionNode : public rclcpp::Node void change_pause(bool pause); void on_timer(); void on_is_paused( - const autoware::component_interface_specs::control::IsPaused::Message::ConstSharedPtr msg); - void on_is_start_requested( - const autoware::component_interface_specs::control::IsStartRequested::Message::ConstSharedPtr + const autoware::component_interface_specs_universe::control::IsPaused::Message::ConstSharedPtr msg); + void on_is_start_requested(const autoware::component_interface_specs_universe::control:: + IsStartRequested::Message::ConstSharedPtr msg); void on_accept( const autoware::adapi_specs::motion::AcceptStart::Service::Request::SharedPtr req, const autoware::adapi_specs::motion::AcceptStart::Service::Response::SharedPtr res); diff --git a/system/autoware_default_adapi/src/operation_mode.hpp b/system/autoware_default_adapi/src/operation_mode.hpp index fdfe9ce237626..43824b4f55899 100644 --- a/system/autoware_default_adapi/src/operation_mode.hpp +++ b/system/autoware_default_adapi/src/operation_mode.hpp @@ -16,7 +16,7 @@ #define OPERATION_MODE_HPP_ #include -#include +#include #include #include @@ -46,9 +46,9 @@ class OperationModeNode : public rclcpp::Node using ChangeToLocal = autoware::adapi_specs::operation_mode::ChangeToLocal; using ChangeToRemote = autoware::adapi_specs::operation_mode::ChangeToRemote; using OperationModeRequest = - autoware::component_interface_specs::system::ChangeOperationMode::Service::Request; + autoware::component_interface_specs_universe::system::ChangeOperationMode::Service::Request; using AutowareControlRequest = - autoware::component_interface_specs::system::ChangeAutowareControl::Service::Request; + autoware::component_interface_specs_universe::system::ChangeAutowareControl::Service::Request; using OperationModeAvailability = tier4_system_msgs::msg::OperationModeAvailability; OperationModeState::Message curr_state_; @@ -64,9 +64,9 @@ class OperationModeNode : public rclcpp::Node Srv srv_remote_mode_; Srv srv_enable_control_; Srv srv_disable_control_; - Sub sub_state_; - Cli cli_mode_; - Cli cli_control_; + Sub sub_state_; + Cli cli_mode_; + Cli cli_control_; rclcpp::Subscription::SharedPtr sub_availability_; void on_change_to_stop( diff --git a/system/autoware_default_adapi/src/perception.cpp b/system/autoware_default_adapi/src/perception.cpp index 3e858e7763baf..35ad31f437f80 100644 --- a/system/autoware_default_adapi/src/perception.cpp +++ b/system/autoware_default_adapi/src/perception.cpp @@ -50,9 +50,8 @@ uint8_t PerceptionNode::mapping( } } -void PerceptionNode::object_recognize( - const autoware::component_interface_specs::perception::ObjectRecognition::Message::ConstSharedPtr - msg) +void PerceptionNode::object_recognize(const autoware::component_interface_specs_universe:: + perception::ObjectRecognition::Message::ConstSharedPtr msg) { DynamicObjectArray::Message objects; objects.header = msg->header; diff --git a/system/autoware_default_adapi/src/perception.hpp b/system/autoware_default_adapi/src/perception.hpp index 61fb2c4667f1d..4c640894d77b6 100644 --- a/system/autoware_default_adapi/src/perception.hpp +++ b/system/autoware_default_adapi/src/perception.hpp @@ -16,7 +16,7 @@ #define PERCEPTION_HPP_ #include -#include +#include #include #include @@ -41,9 +41,10 @@ class PerceptionNode : public rclcpp::Node private: Pub pub_object_recognized_; - Sub sub_object_recognized_; - void object_recognize(const autoware::component_interface_specs::perception::ObjectRecognition:: - Message::ConstSharedPtr msg); + Sub + sub_object_recognized_; + void object_recognize(const autoware::component_interface_specs_universe::perception:: + ObjectRecognition::Message::ConstSharedPtr msg); uint8_t mapping( std::unordered_map hash_map, uint8_t input, uint8_t default_value); }; diff --git a/system/autoware_default_adapi/src/planning.hpp b/system/autoware_default_adapi/src/planning.hpp index 49584475734f6..2204b92dc3568 100644 --- a/system/autoware_default_adapi/src/planning.hpp +++ b/system/autoware_default_adapi/src/planning.hpp @@ -16,8 +16,8 @@ #define PLANNING_HPP_ #include -#include -#include +#include +#include #include #include @@ -50,15 +50,17 @@ class PlanningNode : public rclcpp::Node private: Pub pub_velocity_factors_; Pub pub_steering_factors_; - Sub sub_trajectory_; - Sub sub_kinematic_state_; + Sub sub_trajectory_; + Sub + sub_kinematic_state_; std::vector::SharedPtr> sub_factors_; std::vector factors_; rclcpp::TimerBase::SharedPtr timer_; using VehicleStopChecker = autoware::motion_utils::VehicleStopCheckerBase; - using Trajectory = autoware::component_interface_specs::planning::Trajectory::Message; - using KinematicState = autoware::component_interface_specs::localization::KinematicState::Message; + using Trajectory = autoware::component_interface_specs_universe::planning::Trajectory::Message; + using KinematicState = + autoware::component_interface_specs_universe::localization::KinematicState::Message; void on_trajectory(const Trajectory::ConstSharedPtr msg); void on_kinematic_state(const KinematicState::ConstSharedPtr msg); void on_timer(); diff --git a/system/autoware_default_adapi/src/routing.cpp b/system/autoware_default_adapi/src/routing.cpp index 93f31ff693344..66bc7a8f2e357 100644 --- a/system/autoware_default_adapi/src/routing.cpp +++ b/system/autoware_default_adapi/src/routing.cpp @@ -76,7 +76,7 @@ RoutingNode::RoutingNode(const rclcpp::NodeOptions & options) : Node("routing", void RoutingNode::change_stop_mode() { using OperationModeRequest = - autoware::component_interface_specs::system::ChangeOperationMode::Service::Request; + autoware::component_interface_specs_universe::system::ChangeOperationMode::Service::Request; if (is_auto_mode_) { const auto req = std::make_shared(); req->mode = OperationModeRequest::STOP; diff --git a/system/autoware_default_adapi/src/routing.hpp b/system/autoware_default_adapi/src/routing.hpp index f37b8a978a235..34cea7b558196 100644 --- a/system/autoware_default_adapi/src/routing.hpp +++ b/system/autoware_default_adapi/src/routing.hpp @@ -16,8 +16,8 @@ #define ROUTING_HPP_ #include -#include -#include +#include +#include #include #include @@ -33,9 +33,10 @@ class RoutingNode : public rclcpp::Node explicit RoutingNode(const rclcpp::NodeOptions & options); private: - using OperationModeState = autoware::component_interface_specs::system::OperationModeState; - using State = autoware::component_interface_specs::planning::RouteState; - using Route = autoware::component_interface_specs::planning::LaneletRoute; + using OperationModeState = + autoware::component_interface_specs_universe::system::OperationModeState; + using State = autoware::component_interface_specs_universe::planning::RouteState; + using Route = autoware::component_interface_specs_universe::planning::LaneletRoute; rclcpp::CallbackGroup::SharedPtr group_cli_; Pub pub_state_; @@ -45,13 +46,16 @@ class RoutingNode : public rclcpp::Node Srv srv_change_route_points_; Srv srv_change_route_; Srv srv_clear_route_; - Sub sub_state_; - Sub sub_route_; - Cli cli_set_waypoint_route_; - Cli cli_set_lanelet_route_; - Cli cli_clear_route_; - Cli cli_operation_mode_; - Sub sub_operation_mode_; + Sub sub_state_; + Sub sub_route_; + Cli + cli_set_waypoint_route_; + Cli + cli_set_lanelet_route_; + Cli cli_clear_route_; + Cli + cli_operation_mode_; + Sub sub_operation_mode_; bool is_autoware_control_; bool is_auto_mode_; State::Message state_; diff --git a/system/autoware_default_adapi/src/vehicle.cpp b/system/autoware_default_adapi/src/vehicle.cpp index fc35efff523c2..eb6f7afb03ff3 100644 --- a/system/autoware_default_adapi/src/vehicle.cpp +++ b/system/autoware_default_adapi/src/vehicle.cpp @@ -25,14 +25,16 @@ namespace autoware::default_adapi { -using GearReport = autoware::component_interface_specs::vehicle::GearStatus::Message; +using GearReport = autoware::component_interface_specs_universe::vehicle::GearStatus::Message; using ApiGear = autoware_adapi_v1_msgs::msg::Gear; using TurnIndicatorsReport = - autoware::component_interface_specs::vehicle::TurnIndicatorStatus::Message; + autoware::component_interface_specs_universe::vehicle::TurnIndicatorStatus::Message; using ApiTurnIndicator = autoware_adapi_v1_msgs::msg::TurnIndicators; -using HazardLightsReport = autoware::component_interface_specs::vehicle::HazardLightStatus::Message; +using HazardLightsReport = + autoware::component_interface_specs_universe::vehicle::HazardLightStatus::Message; using ApiHazardLight = autoware_adapi_v1_msgs::msg::HazardLights; -using MapProjectorInfo = autoware::component_interface_specs::map::MapProjectorInfo::Message; +using MapProjectorInfo = + autoware::component_interface_specs_universe::map::MapProjectorInfo::Message; std::unordered_map gear_type_ = { {GearReport::NONE, ApiGear::UNKNOWN}, {GearReport::NEUTRAL, ApiGear::NEUTRAL}, @@ -90,23 +92,20 @@ uint8_t VehicleNode::mapping( } } -void VehicleNode::kinematic_state( - const autoware::component_interface_specs::localization::KinematicState::Message::ConstSharedPtr - msg_ptr) +void VehicleNode::kinematic_state(const autoware::component_interface_specs_universe::localization:: + KinematicState::Message::ConstSharedPtr msg_ptr) { kinematic_state_msgs_ = msg_ptr; } -void VehicleNode::acceleration_status( - const autoware::component_interface_specs::localization::Acceleration::Message::ConstSharedPtr - msg_ptr) +void VehicleNode::acceleration_status(const autoware::component_interface_specs_universe:: + localization::Acceleration::Message::ConstSharedPtr msg_ptr) { acceleration_msgs_ = msg_ptr; } -void VehicleNode::steering_status( - const autoware::component_interface_specs::vehicle::SteeringStatus::Message::ConstSharedPtr - msg_ptr) +void VehicleNode::steering_status(const autoware::component_interface_specs_universe::vehicle:: + SteeringStatus::Message::ConstSharedPtr msg_ptr) { steering_status_msgs_ = msg_ptr; } @@ -127,7 +126,8 @@ void VehicleNode::hazard_light_status(const HazardLightsReport::ConstSharedPtr m } void VehicleNode::energy_status( - const autoware::component_interface_specs::vehicle::EnergyStatus::Message::ConstSharedPtr msg_ptr) + const autoware::component_interface_specs_universe::vehicle::EnergyStatus::Message::ConstSharedPtr + msg_ptr) { energy_status_msgs_ = msg_ptr; } diff --git a/system/autoware_default_adapi/src/vehicle.hpp b/system/autoware_default_adapi/src/vehicle.hpp index 9bb83cb1613e9..750ef9dd14c57 100644 --- a/system/autoware_default_adapi/src/vehicle.hpp +++ b/system/autoware_default_adapi/src/vehicle.hpp @@ -16,9 +16,9 @@ #define VEHICLE_HPP_ #include -#include -#include -#include +#include +#include +#include #include #include @@ -42,57 +42,52 @@ class VehicleNode : public rclcpp::Node rclcpp::CallbackGroup::SharedPtr group_cli_; Pub pub_kinematics_; Pub pub_status_; - Sub sub_kinematic_state_; - Sub sub_acceleration_; - Sub sub_steering_; - Sub sub_gear_state_; - Sub sub_turn_indicator_; - Sub sub_hazard_light_; - Sub sub_energy_level_; - Sub sub_map_projector_info_; + Sub + sub_kinematic_state_; + Sub sub_acceleration_; + Sub sub_steering_; + Sub sub_gear_state_; + Sub + sub_turn_indicator_; + Sub sub_hazard_light_; + Sub sub_energy_level_; + Sub sub_map_projector_info_; rclcpp::TimerBase::SharedPtr timer_; - autoware::component_interface_specs::localization::KinematicState::Message::ConstSharedPtr - kinematic_state_msgs_; - autoware::component_interface_specs::localization::Acceleration::Message::ConstSharedPtr + autoware::component_interface_specs_universe::localization::KinematicState::Message:: + ConstSharedPtr kinematic_state_msgs_; + autoware::component_interface_specs_universe::localization::Acceleration::Message::ConstSharedPtr acceleration_msgs_; - autoware::component_interface_specs::vehicle::SteeringStatus::Message::ConstSharedPtr + autoware::component_interface_specs_universe::vehicle::SteeringStatus::Message::ConstSharedPtr steering_status_msgs_; - autoware::component_interface_specs::vehicle::GearStatus::Message::ConstSharedPtr + autoware::component_interface_specs_universe::vehicle::GearStatus::Message::ConstSharedPtr gear_status_msgs_; - autoware::component_interface_specs::vehicle::TurnIndicatorStatus::Message::ConstSharedPtr - turn_indicator_status_msgs_; - autoware::component_interface_specs::vehicle::HazardLightStatus::Message::ConstSharedPtr + autoware::component_interface_specs_universe::vehicle::TurnIndicatorStatus::Message:: + ConstSharedPtr turn_indicator_status_msgs_; + autoware::component_interface_specs_universe::vehicle::HazardLightStatus::Message::ConstSharedPtr hazard_light_status_msgs_; - autoware::component_interface_specs::vehicle::EnergyStatus::Message::ConstSharedPtr + autoware::component_interface_specs_universe::vehicle::EnergyStatus::Message::ConstSharedPtr energy_status_msgs_; - autoware::component_interface_specs::map::MapProjectorInfo::Message::ConstSharedPtr + autoware::component_interface_specs_universe::map::MapProjectorInfo::Message::ConstSharedPtr map_projector_info_; - void kinematic_state( - const autoware::component_interface_specs::localization::KinematicState::Message::ConstSharedPtr - msg_ptr); - void acceleration_status( - const autoware::component_interface_specs::localization::Acceleration::Message::ConstSharedPtr - msg_ptr); - void steering_status( - const autoware::component_interface_specs::vehicle::SteeringStatus::Message::ConstSharedPtr - msg_ptr); + void kinematic_state(const autoware::component_interface_specs_universe::localization:: + KinematicState::Message::ConstSharedPtr msg_ptr); + void acceleration_status(const autoware::component_interface_specs_universe::localization:: + Acceleration::Message::ConstSharedPtr msg_ptr); + void steering_status(const autoware::component_interface_specs_universe::vehicle::SteeringStatus:: + Message::ConstSharedPtr msg_ptr); void gear_status( - const autoware::component_interface_specs::vehicle::GearStatus::Message::ConstSharedPtr - msg_ptr); - void turn_indicator_status( - const autoware::component_interface_specs::vehicle::TurnIndicatorStatus::Message::ConstSharedPtr - msg_ptr); - void map_projector_info( - const autoware::component_interface_specs::map::MapProjectorInfo::Message::ConstSharedPtr - msg_ptr); - void hazard_light_status( - const autoware::component_interface_specs::vehicle::HazardLightStatus::Message::ConstSharedPtr - msg_ptr); - void energy_status( - const autoware::component_interface_specs::vehicle::EnergyStatus::Message::ConstSharedPtr + const autoware::component_interface_specs_universe::vehicle::GearStatus::Message::ConstSharedPtr msg_ptr); + void turn_indicator_status(const autoware::component_interface_specs_universe::vehicle:: + TurnIndicatorStatus::Message::ConstSharedPtr msg_ptr); + void map_projector_info(const autoware::component_interface_specs_universe::map:: + MapProjectorInfo::Message::ConstSharedPtr msg_ptr); + void hazard_light_status(const autoware::component_interface_specs_universe::vehicle:: + HazardLightStatus::Message::ConstSharedPtr msg_ptr); + void energy_status(const autoware::component_interface_specs_universe::vehicle::EnergyStatus:: + Message::ConstSharedPtr msg_ptr); uint8_t mapping( std::unordered_map hash_map, uint8_t input, uint8_t default_value); void publish_kinematics(); diff --git a/system/autoware_default_adapi/src/vehicle_door.hpp b/system/autoware_default_adapi/src/vehicle_door.hpp index a75232a2b2c74..b0d6151ca3e8b 100644 --- a/system/autoware_default_adapi/src/vehicle_door.hpp +++ b/system/autoware_default_adapi/src/vehicle_door.hpp @@ -16,8 +16,8 @@ #define VEHICLE_DOOR_HPP_ #include -#include -#include +#include +#include #include #include @@ -35,10 +35,11 @@ class VehicleDoorNode : public rclcpp::Node explicit VehicleDoorNode(const rclcpp::NodeOptions & options); private: - using OperationModeState = autoware::component_interface_specs::system::OperationModeState; - using InternalDoorStatus = autoware::component_interface_specs::vehicle::DoorStatus; - using InternalDoorLayout = autoware::component_interface_specs::vehicle::DoorLayout; - using InternalDoorCommand = autoware::component_interface_specs::vehicle::DoorCommand; + using OperationModeState = + autoware::component_interface_specs_universe::system::OperationModeState; + using InternalDoorStatus = autoware::component_interface_specs_universe::vehicle::DoorStatus; + using InternalDoorLayout = autoware::component_interface_specs_universe::vehicle::DoorLayout; + using InternalDoorCommand = autoware::component_interface_specs_universe::vehicle::DoorCommand; using ExternalDoorStatus = autoware::adapi_specs::vehicle::DoorStatus; using ExternalDoorLayout = autoware::adapi_specs::vehicle::DoorLayout; using ExternalDoorCommand = autoware::adapi_specs::vehicle::DoorCommand; From ce3358e00f13fc2d241deb90f4ef3951e32869b1 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Tue, 21 Jan 2025 13:26:07 +0900 Subject: [PATCH 261/334] feat(crosswalk): add pass marker (#9952) Signed-off-by: yuki-takagi-66 --- .../autoware/behavior_velocity_crosswalk_module/util.hpp | 1 + .../src/debug.cpp | 7 +++++++ .../src/scene_crosswalk.cpp | 5 +++-- 3 files changed, 11 insertions(+), 2 deletions(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/include/autoware/behavior_velocity_crosswalk_module/util.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/include/autoware/behavior_velocity_crosswalk_module/util.hpp index 64c98017d3007..137f21adadafa 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/include/autoware/behavior_velocity_crosswalk_module/util.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/include/autoware/behavior_velocity_crosswalk_module/util.hpp @@ -78,6 +78,7 @@ struct DebugData std::vector stop_poses; std::vector slow_poses; + std::vector pass_poses; std::vector stop_factor_points; std::vector crosswalk_polygon; std::vector> ego_polygons; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/debug.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/debug.cpp index 757803ef35578..0ec5a2a944059 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/debug.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/debug.cpp @@ -213,6 +213,13 @@ autoware::motion_utils::VirtualWalls CrosswalkModule::createVirtualWalls() wall.pose = calcOffsetPose(p, debug_data_.base_link2front, 0.0, 0.0); virtual_walls.push_back(wall); } + wall.style = autoware::motion_utils::VirtualWallType::pass; + wall.text += debug_data_.virtual_wall_suffix; + for (const auto & p : debug_data_.pass_poses) { + wall.pose = calcOffsetPose(p, debug_data_.base_link2front, 0.0, 0.0); + virtual_walls.push_back(wall); + } + return virtual_walls; } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 754c14df9fac7..52a877f3d9590 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -477,12 +477,13 @@ std::optional CrosswalkModule::calcStopPose( return strong_brk_dist_opt ? strong_brk_dist_opt.value() : 0.0; }(); if (selected_stop.dist < strong_brk_dist - p.overrun_threshold_length_for_no_stop_decision) { - RCLCPP_INFO( - logger_, + RCLCPP_INFO_THROTTLE( + logger_, *clock_, 1000, "Abandon to stop. " "Can not stop against the nearest pedestrian with a specified deceleration. " "dist to stop: %f, braking distance: %f", selected_stop.dist, strong_brk_dist); + debug_data_.pass_poses.push_back(selected_stop.pose); return std::nullopt; } From e86f92ba55065fd76f9df40142bea4296dbfe31b Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Tue, 21 Jan 2025 13:27:22 +0900 Subject: [PATCH 262/334] chore(crosswalk): port the same direction ignore block (#9983) Signed-off-by: yuki-takagi-66 --- .../src/scene_crosswalk.cpp | 22 +++------------- .../src/scene_crosswalk.hpp | 26 ++++++++++++++++--- 2 files changed, 26 insertions(+), 22 deletions(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 52a877f3d9590..43f2f6617e5d0 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -337,13 +337,8 @@ std::optional CrosswalkModule::checkStopForCrosswalkUsers( // Check pedestrian for stop // NOTE: first stop point and its minimum distance from ego to stop - auto isVehicleType = [](const uint8_t label) { - return label == ObjectClassification::MOTORCYCLE || label == ObjectClassification::BICYCLE; - }; std::optional dist_nearest_cp; std::vector stop_factor_points; - const std::optional ego_crosswalk_passage_direction = - findEgoPassageDirectionAlongPath(sparse_resample_path); for (const auto & object : object_info_manager_.getObject()) { const auto & collision_point_opt = object.collision_point; if (collision_point_opt) { @@ -353,19 +348,6 @@ std::optional CrosswalkModule::checkStopForCrosswalkUsers( continue; } - if ( - isVehicleType(object.classification) && ego_crosswalk_passage_direction && - collision_point.crosswalk_passage_direction) { - double direction_diff = std::abs(std::fmod( - collision_point.crosswalk_passage_direction.value() - - ego_crosswalk_passage_direction.value(), - M_PI_2)); - direction_diff = std::min(direction_diff, M_PI_2 - direction_diff); - if (direction_diff < planner_param_.vehicle_object_cross_angle_threshold) { - continue; - } - } - stop_factor_points.push_back(object.position); const auto dist_ego2cp = @@ -1167,10 +1149,12 @@ void CrosswalkModule::updateObjectState( const auto collision_point = getCollisionPoint(sparse_resample_path, object, crosswalk_attention_range, attention_area); + const std::optional ego_crosswalk_passage_direction = + findEgoPassageDirectionAlongPath(sparse_resample_path); object_info_manager_.update( obj_uuid, obj_pos, std::hypot(obj_vel.x, obj_vel.y), clock_->now(), is_ego_yielding, has_traffic_light, collision_point, object.classification.front().label, planner_param_, - crosswalk_.polygon2d().basicPolygon(), attention_area); + crosswalk_.polygon2d().basicPolygon(), attention_area, ego_crosswalk_passage_direction); const auto collision_state = object_info_manager_.getCollisionState(obj_uuid); if (collision_point) { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index b9803207a1a31..cc9b8733eb6b6 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -194,7 +194,8 @@ class CrosswalkModule : public SceneModuleInterfaceWithRTC const rclcpp::Time & now, const geometry_msgs::msg::Point & position, const double vel, const bool is_ego_yielding, const std::optional & collision_point, const PlannerParam & planner_param, const lanelet::BasicPolygon2d & crosswalk_polygon, - const bool is_object_away_from_path) + const bool is_object_away_from_path, + const std::optional & ego_crosswalk_passage_direction) { const bool is_stopped = vel < planner_param.stop_object_velocity; @@ -224,6 +225,24 @@ class CrosswalkModule : public SceneModuleInterfaceWithRTC // Compare time to collision and vehicle if (collision_point) { + auto isVehicleType = [](const uint8_t label) { + return label == ObjectClassification::MOTORCYCLE || + label == ObjectClassification::BICYCLE; + }; + if ( + isVehicleType(classification) && ego_crosswalk_passage_direction && + collision_point->crosswalk_passage_direction) { + double direction_diff = std::abs(std::fmod( + collision_point->crosswalk_passage_direction.value() - + ego_crosswalk_passage_direction.value(), + M_PI_2)); + direction_diff = std::min(direction_diff, M_PI_2 - direction_diff); + if (direction_diff < planner_param.vehicle_object_cross_angle_threshold) { + collision_state = CollisionState::IGNORE; + return; + } + } + // Check if ego will pass first const double ego_pass_first_additional_margin = collision_state == CollisionState::EGO_PASS_FIRST @@ -268,7 +287,8 @@ class CrosswalkModule : public SceneModuleInterfaceWithRTC const rclcpp::Time & now, const bool is_ego_yielding, const bool has_traffic_light, const std::optional & collision_point, const uint8_t classification, const PlannerParam & planner_param, const lanelet::BasicPolygon2d & crosswalk_polygon, - const Polygon2d & attention_area) + const Polygon2d & attention_area, + const std::optional & ego_crosswalk_passage_direction) { // update current uuids current_uuids_.push_back(uuid); @@ -292,7 +312,7 @@ class CrosswalkModule : public SceneModuleInterfaceWithRTC // update object state objects.at(uuid).transitState( now, position, vel, is_ego_yielding, collision_point, planner_param, crosswalk_polygon, - is_object_away_from_path); + is_object_away_from_path, ego_crosswalk_passage_direction); objects.at(uuid).collision_point = collision_point; objects.at(uuid).position = position; objects.at(uuid).classification = classification; From 3138d75b55ea10a02141261366f95a4f5e8ccaa6 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Tue, 21 Jan 2025 14:12:21 +0900 Subject: [PATCH 263/334] feat(sampling_based_planner)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in sampling_based_planner (#9916) Signed-off-by: vish0012 --- .../sampling_based_planner/autoware_path_sampler/package.xml | 1 - 1 file changed, 1 deletion(-) diff --git a/planning/sampling_based_planner/autoware_path_sampler/package.xml b/planning/sampling_based_planner/autoware_path_sampler/package.xml index a4119b03a2dd7..98d0c4188ec3f 100644 --- a/planning/sampling_based_planner/autoware_path_sampler/package.xml +++ b/planning/sampling_based_planner/autoware_path_sampler/package.xml @@ -28,7 +28,6 @@ rclcpp_components std_msgs tf2_ros - tier4_debug_msgs tier4_planning_msgs visualization_msgs From 96708f9a92c728972cbed4dc37fe3913fb4e8e33 Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Tue, 21 Jan 2025 14:26:22 +0900 Subject: [PATCH 264/334] feat(autoware_pointcloud_preprocessor): redesign concatenate and time sync node (#8300) * chore: rebase main Signed-off-by: vividf * chore: solve conflicts Signed-off-by: vividf * chore: fix cpp check Signed-off-by: vividf * chore: add diagnostics readme Signed-off-by: vividf * chore: update figure Signed-off-by: vividf * chore: upload jitter.png and add old design link Signed-off-by: vividf * chore: add the link to the tool for analyzing timestamp Signed-off-by: vividf * fix: fix bug that timer didn't cancel Signed-off-by: vividf * chore: fix logic for logging Signed-off-by: vividf * Update sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> * Update sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> * Update sensing/autoware_pointcloud_preprocessor/schema/cocatenate_and_time_sync_node.schema.json Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> * Update sensing/autoware_pointcloud_preprocessor/schema/cocatenate_and_time_sync_node.schema.json Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> * Update sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> * Update sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> * chore: remove distortion corrector related changes Signed-off-by: vividf * feat: add managed tf buffer Signed-off-by: vividf * chore: fix filename Signed-off-by: vividf * chore: add explanataion for maximum queue size Signed-off-by: vividf * chore: add explanation for timeout_sec Signed-off-by: vividf * chore: fix schema's explanation Signed-off-by: vividf * chore: fix description for twist and odom Signed-off-by: vividf * chore: remove license that are not used Signed-off-by: vividf * chore: change guard to prama once Signed-off-by: vividf * chore: default value change to string Signed-off-by: vividf * Update sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> * Update sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> * Update sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> * Update sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> * style(pre-commit): autofix * chore: clang-tidy style for static constexpr Signed-off-by: vividf * chore: remove unused vector header Signed-off-by: vividf * chore: fix naming concatenated_cloud_publisher Signed-off-by: vividf * chore: fix namimg diagnostic_updater_ Signed-off-by: vividf * chore: specify parameter in comment Signed-off-by: vividf * chore: change RCLCPP_WARN to RCLCPP_WARN_STREAM_THROTTLE Signed-off-by: vividf * chore: add comment for cancelling timer Signed-off-by: vividf * chore: Simplify loop structure for topic-to-cloud mapping Signed-off-by: vividf * chore: fix spell errors Signed-off-by: vividf * chore: fix more spell error Signed-off-by: vividf * chore: rename mutex and lock Signed-off-by: vividf * chore: const reference for string parameter Signed-off-by: vividf * chore: add explaination for RclcppTimeHash_ Signed-off-by: vividf * chore: change the concatenate node to parent node Signed-off-by: vividf * chore: clean processOdometry and processTwist Signed-off-by: vividf * chore: change twist shared pointer queue to twist queue Signed-off-by: vividf * chore: refactor compensate pointcloud to function Signed-off-by: vividf * chore: reallocate memory for concatenate_cloud_ptr Signed-off-by: vividf * chore: remove new to make shared Signed-off-by: vividf * chore: dis to distance Signed-off-by: vividf * chore: refacotr poitncloud_sub Signed-off-by: vividf * chore: return early return but throw runtime error Signed-off-by: vividf * chore: replace #define DEFAULT_SYNC_TOPIC_POSTFIX with member variable Signed-off-by: vividf * chore: fix spell error Signed-off-by: vividf * chore: remove redundant function call Signed-off-by: vividf * chore: replace conplex tuple to structure Signed-off-by: vividf * chore: use reference instead of a pointer to conveys node Signed-off-by: vividf * chore: fix camel to snake case Signed-off-by: vividf * chore: fix logic of publish synchronized pointcloud Signed-off-by: vividf * chore: fix cpp check Signed-off-by: vividf * chore: remove logging and throw error directly Signed-off-by: vividf * chore: fix clangd warnings Signed-off-by: vividf * chore: fix json schema Signed-off-by: vividf * chore: fix clangd warning Signed-off-by: vividf * chore: remove unused variable Signed-off-by: vividf * chore: fix launcher Signed-off-by: vividf * chore: fix clangd warning Signed-off-by: vividf * chore: ensure thread safety Signed-off-by: vividf * style(pre-commit): autofix * chore: clean code Signed-off-by: vividf * chore: add parameters for handling rosbag replay in loops Signed-off-by: vividf * chore: fix diagonistic Signed-off-by: vividf * chore: reduce copy operation Signed-off-by: vividf * chore: reserve space for concatenated pointcloud Signed-off-by: vividf * chore: fix clangd error Signed-off-by: vividf * chore: fix pipeline latency Signed-off-by: vividf * chore: add debug mode Signed-off-by: vividf * chore: refactor convert_to_xyzirc_cloud function Signed-off-by: vividf * chore: fix json schema Signed-off-by: vividf * chore: fix logging output Signed-off-by: vividf * chore: fix the output order of the debug mode Signed-off-by: vividf * chore: fix pipeline latency output Signed-off-by: vividf * chore: clean code Signed-off-by: vividf * chore: set some parameters to false in testing Signed-off-by: vividf * chore: fix default value for schema Signed-off-by: vividf * chore: fix diagnostic msgs Signed-off-by: vividf * chore: fix parameter for sample ros bag Signed-off-by: vividf * chore: update readme Signed-off-by: vividf * chore: fix empty pointcloud Signed-off-by: vividf * chore: remove duplicated logic Signed-off-by: vividf * chore: fix logic for handling empty pointcloud Signed-off-by: vividf * chore: clean code Signed-off-by: vividf * chore: remove rosbag_replay parameter Signed-off-by: vividf * chore: remove nodelet cpp Signed-off-by: vividf * chore: clang tidy warning Signed-off-by: vividf * feat: add naive approach for unsynchronized pointclouds Signed-off-by: vividf * chore: add more explanations in docs for naive approach Signed-off-by: vividf * feat: refactor naive method and fix the multithreading issue Signed-off-by: vividf * chore: set parameter to naive Signed-off-by: vividf * chore: fix parameter Signed-off-by: vividf * chore: fix readme Signed-off-by: vividf * Update sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> * Update sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> * style(pre-commit): autofix * feat: remove mutually exclusive approaches Signed-off-by: vividf * chore: fix spell error Signed-off-by: vividf * chore: remove unused variable Signed-off-by: vividf * refactor: refactor collectorInfo to polymorphic Signed-off-by: vividf * chore: fix variable name Signed-off-by: vividf * chore: fix figure and diagnostic msg in readme Signed-off-by: vividf * chroe: refactor collectorinfo structure Signed-off-by: vividf * chore: revert wrong file changes Signed-off-by: vividf * chore: improve message Signed-off-by: vividf * chore: remove unused input topics Signed-off-by: vividf * chore: change to explicit check Signed-off-by: vividf * chore: tier4 debug msgs to autoware internal debug msgs Signed-off-by: vividf * chore: update documentation Signed-off-by: vividf --------- Signed-off-by: vividf Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../CMakeLists.txt | 16 +- .../concatenate_and_time_sync_node.param.yaml | 21 + .../docs/concatenate-data.md | 235 +- .../image/concatenate_algorithm.drawio.svg | 810 ++++++ .../docs/image/concatenate_all.png | Bin 0 -> 493592 bytes .../docs/image/concatenate_data.drawio.svg | 298 --- .../image/concatenate_edge_case.drawio.svg | 2361 +++++++++++++++++ .../docs/image/concatenate_left.png | Bin 0 -> 44393 bytes .../docs/image/concatenate_right.png | Bin 0 -> 44147 bytes .../docs/image/concatenate_top.png | Bin 0 -> 286968 bytes .../image/ideal_timestamp_offset.drawio.svg | 784 ++++++ .../docs/image/jitter.png | Bin 0 -> 118229 bytes .../image/noise_timestamp_offset.drawio.svg | 2023 ++++++++++++++ .../concatenate_data/cloud_collector.hpp | 89 + .../collector_matching_strategy.hpp | 81 + .../combine_cloud_handler.hpp | 110 + .../concatenate_and_time_sync_node.hpp | 124 + .../concatenate_and_time_sync_nodelet.hpp | 197 -- .../concatenate_and_time_sync_node.launch.xml | 11 + ...concatenate_and_time_sync_node.schema.json | 163 ++ .../src/concatenate_data/cloud_collector.cpp | 156 ++ .../collector_matching_strategy.cpp | 121 + .../combine_cloud_handler.cpp | 336 +++ .../concatenate_and_time_sync_node.cpp | 459 ++++ .../concatenate_and_time_sync_nodelet.cpp | 718 ----- .../test/test_concatenate_node_component.py | 909 +++++++ .../test/test_concatenate_node_unit.cpp | 539 ++++ 27 files changed, 9303 insertions(+), 1258 deletions(-) create mode 100644 sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml create mode 100644 sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_algorithm.drawio.svg create mode 100644 sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_all.png delete mode 100644 sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_data.drawio.svg create mode 100644 sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_edge_case.drawio.svg create mode 100644 sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_left.png create mode 100644 sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_right.png create mode 100644 sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_top.png create mode 100644 sensing/autoware_pointcloud_preprocessor/docs/image/ideal_timestamp_offset.drawio.svg create mode 100644 sensing/autoware_pointcloud_preprocessor/docs/image/jitter.png create mode 100644 sensing/autoware_pointcloud_preprocessor/docs/image/noise_timestamp_offset.drawio.svg create mode 100644 sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp create mode 100644 sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/collector_matching_strategy.hpp create mode 100644 sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp create mode 100644 sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp delete mode 100644 sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp create mode 100644 sensing/autoware_pointcloud_preprocessor/launch/concatenate_and_time_sync_node.launch.xml create mode 100644 sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json create mode 100644 sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp create mode 100644 sensing/autoware_pointcloud_preprocessor/src/concatenate_data/collector_matching_strategy.cpp create mode 100644 sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp create mode 100644 sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp delete mode 100644 sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp create mode 100644 sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py create mode 100644 sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp diff --git a/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt b/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt index 56dab521d7dff..19c698b11bc5f 100644 --- a/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt +++ b/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt @@ -64,7 +64,10 @@ ament_target_dependencies(faster_voxel_grid_downsample_filter ) ament_auto_add_library(pointcloud_preprocessor_filter SHARED - src/concatenate_data/concatenate_and_time_sync_nodelet.cpp + src/concatenate_data/concatenate_and_time_sync_node.cpp + src/concatenate_data/combine_cloud_handler.cpp + src/concatenate_data/cloud_collector.cpp + src/concatenate_data/collector_matching_strategy.cpp src/concatenate_data/concatenate_pointclouds.cpp src/crop_box_filter/crop_box_filter_node.cpp src/time_synchronizer/time_synchronizer_node.cpp @@ -111,7 +114,7 @@ rclcpp_components_register_node(pointcloud_preprocessor_filter # ========== Concatenate and Sync data ========== rclcpp_components_register_node(pointcloud_preprocessor_filter PLUGIN "autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent" - EXECUTABLE concatenate_data_node) + EXECUTABLE concatenate_and_time_sync_node) # ========== CropBox ========== rclcpp_components_register_node(pointcloud_preprocessor_filter @@ -243,8 +246,17 @@ if(BUILD_TESTING) test/test_distortion_corrector_node.cpp ) + ament_add_gtest(test_concatenate_node_unit + test/test_concatenate_node_unit.cpp + ) + target_link_libraries(test_utilities pointcloud_preprocessor_filter) target_link_libraries(test_distortion_corrector_node pointcloud_preprocessor_filter) + target_link_libraries(test_concatenate_node_unit pointcloud_preprocessor_filter) + add_ros_test( + test/test_concatenate_node_component.py + TIMEOUT "50" + ) endif() diff --git a/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml b/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml new file mode 100644 index 0000000000000..56fe6643b9973 --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/config/concatenate_and_time_sync_node.param.yaml @@ -0,0 +1,21 @@ +/**: + ros__parameters: + debug_mode: false + has_static_tf_only: false + rosbag_length: 10.0 + maximum_queue_size: 5 + timeout_sec: 0.2 + is_motion_compensated: true + publish_synchronized_pointcloud: true + keep_input_frame_in_synchronized_pointcloud: true + publish_previous_but_late_pointcloud: false + synchronized_pointcloud_postfix: pointcloud + input_twist_topic_type: twist + input_topics: [ + "/sensing/lidar/right/pointcloud_before_sync", + "/sensing/lidar/top/pointcloud_before_sync", + "/sensing/lidar/left/pointcloud_before_sync", + ] + output_frame: base_link + matching_strategy: + type: naive diff --git a/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md b/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md index 08f7b92f88975..f640608cf91ec 100644 --- a/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md +++ b/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md @@ -1,75 +1,224 @@ -# concatenate_data +# concatenate_and_time_synchronize_node ## Purpose -Many self-driving cars combine multiple LiDARs to expand the sensing range. Therefore, a function to combine a plurality of point clouds is required. +The `concatenate_and_time_synchronize_node` is a node designed to combine and synchronize multiple point clouds into a single, unified point cloud. By integrating data from multiple LiDARs, this node significantly enhances the sensing range and coverage of autonomous vehicles, enabling more accurate perception of the surrounding environment. Synchronization ensures that point clouds are aligned temporally, reducing errors caused by mismatched timestamps. -To combine multiple sensor data with a similar timestamp, the [message_filters](https://github.com/ros2/message_filters) is often used in the ROS-based system, but this requires the assumption that all inputs can be received. Since safety must be strongly considered in autonomous driving, the point clouds concatenate node must be designed so that even if one sensor fails, the remaining sensor information can be output. +For example, consider a vehicle equipped with three LiDAR sensors mounted on the left, right, and top positions. Each LiDAR captures data from its respective field of view, as shown below: -## Inner-workings / Algorithms +| Left | Top | Right | +| :-----------------------------------------------: | :---------------------------------------------: | :-------------------------------------------------: | +| ![Concatenate Left](./image/concatenate_left.png) | ![Concatenate Top](./image/concatenate_top.png) | ![Concatenate Right](./image/concatenate_right.png) | -The figure below represents the reception time of each sensor data and how it is combined in the case. +After processing the data through the `concatenate_and_time_synchronize_node`, the outputs from all LiDARs are combined into a single comprehensive point cloud that provides a complete view of the environment: -![concatenate_data_timing_chart](./image/concatenate_data.drawio.svg) +![Full Scene View](./image/concatenate_all.png) + +This resulting point cloud allows autonomous systems to detect obstacles, map the environment, and navigate more effectively, leveraging the complementary fields of view from multiple LiDAR sensors. + +## Inner Workings / Algorithms + +![concatenate_algorithm](./image/concatenate_algorithm.drawio.svg) + +### Step 1: Match and Create Collector + +When a point cloud arrives, its timestamp is checked, and an offset is subtracted to get the reference timestamp. The node then checks if there is an existing collector with the same reference timestamp. If such a collector exists, the point cloud is added to it. If no such collector exists, a new collector is created with the reference timestamp. + +### Step 2: Trigger the Timer + +Once a collector is created, a timer for that collector starts counting down (this value is defined by `timeout_sec`). The collector begins to concatenate the point clouds either when all point clouds defined in `input_topics` have been collected or when the timer counts down to zero. + +### Step 3: Concatenate the Point Clouds + +The concatenation process involves merging multiple point clouds into a single, concatenated point cloud. The timestamp of the concatenated point cloud will be the earliest timestamp from the input point clouds. By setting the parameter `is_motion_compensated` to `true`, the node will consider the timestamps of the input point clouds and utilize the `twist` information from `geometry_msgs::msg::TwistWithCovarianceStamped` to compensate for motion, aligning the point cloud to the selected (earliest) timestamp. + +### Step 4: Publish the Point Cloud + +After concatenation, the concatenated point cloud is published, and the collector is deleted to free up resources. ## Inputs / Outputs ### Input -| Name | Type | Description | -| --------------- | ------------------------------------------------ | ----------------------------------------------------------------------------- | -| `~/input/twist` | `geometry_msgs::msg::TwistWithCovarianceStamped` | The vehicle odometry is used to interpolate the timestamp of each sensor data | +| Name | Type | Description | +| --------------- | ------------------------------------------------ | -------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `~/input/twist` | `geometry_msgs::msg::TwistWithCovarianceStamped` | Twist information adjusts the point cloud scans based on vehicle motion, allowing LiDARs with different timestamps to be synchronized for concatenation. | +| `~/input/odom` | `nav_msgs::msg::Odometry` | Vehicle odometry adjusts the point cloud scans based on vehicle motion, allowing LiDARs with different timestamps to be synchronized for concatenation. | + +By setting the `input_twist_topic_type` parameter to `twist` or `odom`, the subscriber will subscribe to either `~/input/twist` or `~/input/odom`. If the user doesn't want to use the twist information or vehicle odometry to compensate for motion, set `is_motion_compensated` to `false`. ### Output | Name | Type | Description | | ----------------- | ------------------------------- | ------------------------- | -| `~/output/points` | `sensor_msgs::msg::Pointcloud2` | concatenated point clouds | +| `~/output/points` | `sensor_msgs::msg::Pointcloud2` | Concatenated point clouds | + +### Core Parameters -## Parameters +{{ json_to_markdown("sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json") }} -| Name | Type | Default Value | Description | -| -------------------- | ---------------- | ------------- | ------------------------------------------------------------------- | -| `input/points` | vector of string | [] | input topic names that type must be `sensor_msgs::msg::Pointcloud2` | -| `input_frame` | string | "" | input frame id | -| `output_frame` | string | "" | output frame id | -| `has_static_tf_only` | bool | false | flag to listen TF only once | -| `max_queue_size` | int | 5 | max queue size of input/output topics | +### Parameter Settings -### Core Parameters +If you didn't synchronize your LiDAR sensors, set the `type` parameter of `matching_strategy` to `naive` to concatenate the point clouds directly. However, if your LiDAR sensors are synchronized, set type to `advanced` and adjust the `lidar_timestamp_offsets` and `lidar_timestamp_noise_window` parameters accordingly. + +The three parameters, `timeout_sec`, `lidar_timestamp_offsets`, and `lidar_timestamp_noise_window`, are essential for efficiently collecting point clouds in the same collector and managing edge cases (point cloud drops or delays) effectively. + +#### timeout_sec + +When network issues occur or when point clouds experience delays in the previous processing pipeline, some point clouds may be delayed or dropped. To address this, the `timeout_sec` parameter is used. Once the timer is created, it will start counting down from `timeout_sec`. If the timer reaches zero, the collector will not wait for delayed or dropped point clouds but will concatenate the remaining point clouds in the collector directly. The figure below demonstrates how `timeout_sec` works with `concatenate_and_time_sync_node` when `timeout_sec` is set to `0.12` (120 ms). + +![concatenate_edge_case](./image/concatenate_edge_case.drawio.svg) + +#### lidar_timestamp_offsets + +Since different vehicles have varied designs for LiDAR scanning, the timestamps of each LiDAR may differ. Users need to know the offsets between each LiDAR and set the values in `lidar_timestamp_offsets`. + +To monitor the timestamps of each LiDAR, run the following command: + +```bash +ros2 topic echo "pointcloud_topic" --field header +``` + +The timestamps should increase steadily by approximately 100 ms, as per the Autoware default. You should see output like this: + +```bash +nanosec: 156260951 +nanosec: 257009560 +nanosec: 355444581 +``` + +This pattern indicates a LiDAR timestamp of 0.05. + +If there are three LiDARs (left, right, top), and the timestamps for the left, right, and top point clouds are `0.01`, `0.05`, and `0.09` seconds respectively, the parameters should be set as [0.0, 0.04, 0.08]. This reflects the timestamp differences between the current point cloud and the point cloud with the earliest timestamp. Note that the order of the `lidar_timestamp_offsets` corresponds to the order of the `input_topics`. + +The figure below demonstrates how `lidar_timestamp_offsets` works with `concatenate_and_time_sync_node`. + +![ideal_timestamp_offset](./image/ideal_timestamp_offset.drawio.svg) + +#### lidar_timestamp_noise_window + +Additionally, due to the mechanical design of LiDARs, there may be some jitter in the timestamps of each scan, as shown in the image below. For example, if the scan frequency is set to 10 Hz (scanning every 100 ms), the timestamps between each scan might not be exactly 100 ms apart. To handle this noise, the `lidar_timestamp_noise_window` parameter is provided. + +Users can use [this tool](https://github.com/tier4/timestamp_analyzer) to visualize the noise between each scan. + +![jitter](./image/jitter.png) + +From the example above, the noise ranges from 0 to 8 ms, so the user should set `lidar_timestamp_noise_window` to `0.008`. -| Name | Type | Default Value | Description | -| --------------------------------- | ---------------- | ------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| `timeout_sec` | double | 0.1 | tolerance of time to publish next pointcloud [s]
When this time limit is exceeded, the filter concatenates and publishes pointcloud, even if not all the point clouds are subscribed. | -| `input_offset` | vector of double | [] | This parameter can control waiting time for each input sensor pointcloud [s]. You must to set the same length of offsets with input pointclouds numbers.
For its tuning, please see [actual usage page](#how-to-tuning-timeout_sec-and-input_offset). | -| `publish_synchronized_pointcloud` | bool | false | If true, publish the time synchronized pointclouds. All input pointclouds are transformed and then re-published as message named `_synchronized`. | -| `input_twist_topic_type` | std::string | twist | Topic type for twist. Currently support `twist` or `odom`. | +The figure below demonstrates how `lidar_timestamp_noise_window` works with the `concatenate_and_time_sync_node`. If the green `X` is within the range of the red triangles, it indicates that the point cloud matches the reference timestamp of the collector. -## Actual Usage +![noise_timestamp_offset](./image/noise_timestamp_offset.drawio.svg) -For the example of actual usage of this node, please refer to the [preprocessor.launch.py](../launch/preprocessor.launch.py) file. +## Launch + +```bash +# The launch file will read the parameters from the concatenate_and_time_sync_node.param.yaml +ros2 launch autoware_pointcloud_preprocessor concatenate_and_time_sync_node.launch.xml +``` -### How to tuning timeout_sec and input_offset +## Test -The values in `timeout_sec` and `input_offset` are used in the timer_callback to control concatenation timings. +```bash +# build autoware_pointcloud_preprocessor +colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release --packages-up-to autoware_pointcloud_preprocessor -- Assumptions - - when the timer runs out, we concatenate the pointclouds in the buffer - - when the first pointcloud comes to buffer, we reset the timer to `timeout_sec` - - when the second and later pointclouds comes to buffer, we reset the timer to `timeout_sec` - `input_offset` - - we assume all lidar has same frequency +# test autoware_pointcloud_preprocessor +colcon test --packages-select autoware_pointcloud_preprocessor --event-handlers console_cohesion+ +``` -| Name | Description | How to tune | -| -------------- | ---------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| `timeout_sec` | timeout sec for default timer | To avoid mis-concatenation, at least this value must be shorter than sampling time. | -| `input_offset` | timeout extension when a pointcloud comes to buffer. | The amount of waiting time will be `timeout_sec` - `input_offset`. So, you will need to set larger value for the last-coming pointcloud and smaller for fore-coming. | +## Debug and Diagnostics -### Node separation options for future +To verify whether the node has successfully concatenated the point clouds, the user can examine rqt or the `/diagnostics` topic using the following command: -Since the pointcloud concatenation has two process, "time synchronization" and "pointcloud concatenation", it is possible to separate these processes. +```bash +ros2 topic echo /diagnostics +``` -In the future, Nodes will be completely separated in order to achieve node loosely coupled nature, but currently both nodes can be selected for backward compatibility ([See this PR](https://github.com/autowarefoundation/autoware.universe/pull/3312)). +Below is an example output when the point clouds are concatenated successfully: -## Assumptions / Known limits +- Each point cloud has a value of `True`. +- The `cloud_concatenation_success` is `True`. +- The `level` value is `\0`. (diagnostic_msgs::msg::DiagnosticStatus::OK) -It is necessary to assume that the vehicle odometry value exists, the sensor data and odometry timestamp are correct, and the TF from `base_link` to `sensor_frame` is also correct. +```bash +header: + stamp: + sec: 1722492015 + nanosec: 848508777 + frame_id: '' +status: +- level: "\0" + name: 'concatenate_and_time_sync_node: concat_status' + message: Concatenated pointcloud is published and include all topics + hardware_id: concatenate_data_checker + values: + - key: concatenated_cloud_timestamp + value: '1718260240.159229994' + - key: reference_timestamp_min + value: '1718260240.149230003' + - key: reference_timestamp_max + value: '1718260240.169229984' + - key: /sensing/lidar/left/pointcloud_before_sync/timestamp + value: '1718260240.159229994' + - key: /sensing/lidar/left/pointcloud_before_sync/is_concatenated + value: 'True' + - key: /sensing/lidar/right/pointcloud_before_sync/timestamp + value: '1718260240.194104910' + - key: /sensing/lidar/right/pointcloud_before_sync/is_concatenated + value: 'True' + - key: /sensing/lidar/top/pointcloud_before_sync/timestamp + value: '1718260240.234578133' + - key: /sensing/lidar/top/pointcloud_before_sync/is_concatenated + value: 'True' + - key: cloud_concatenation_success + value: 'True' +``` + +Below is an example when point clouds fail to concatenate successfully. + +- Some point clouds might have values of `False`. +- The `cloud_concatenation_success` is `False`. +- The `level` value is `\x02`. (diagnostic_msgs::msg::DiagnosticStatus::ERROR) + +```bash +header: + stamp: + sec: 1722492663 + nanosec: 344942959 + frame_id: '' +status: +- level: "\x02" + name: 'concatenate_and_time_sync_node: concat_status' + message: Concatenated pointcloud is published but miss some topics + hardware_id: concatenate_data_checker + values: + - key: concatenated_cloud_timestamp + value: '1718260240.859827995' + - key: reference_timestamp_min + value: '1718260240.849828005' + - key: reference_timestamp_max + value: '1718260240.869827986' + - key: /sensing/lidar/left/pointcloud_before_sync/timestamp + value: '1718260240.859827995' + - key: /sensing/lidar/left/pointcloud_before_sync/is_concatenated + value: 'True' + - key: /sensing/lidar/right/pointcloud_before_sync/timestamp + value: '1718260240.895193815' + - key: /sensing/lidar/right/pointcloud_before_sync/is_concatenated + value: 'True' + - key: /sensing/lidar/top/pointcloud_before_sync/is_concatenated + value: 'False' + - key: cloud_concatenation_success + value: 'False' +``` + +## Node separation options + +There is also an option to separate the concatenate_and_time_sync_node into two nodes: one for `time synchronization` and another for `concatenate pointclouds` ([See this PR](https://github.com/autowarefoundation/autoware.universe/pull/3312)). + +Note that the `concatenate_pointclouds` and `time_synchronizer_nodelet` are using the [old design](https://github.com/autowarefoundation/autoware.universe/blob/9bb228fe5b7fa4c6edb47e4713c73489a02366e1/sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md) of the concatenate node. + +## Assumptions / Known Limits + +- If `is_motion_compensated` is set to `false`, the `concatenate_and_time_sync_node` will directly concatenate the point clouds without applying for motion compensation. This can save several milliseconds depending on the number of LiDARs being concatenated. Therefore, if the timestamp differences between point clouds are negligible, the user can set `is_motion_compensated` to `false` and omit the need for twist or odometry input for the node. +- As mentioned above, the user should clearly understand how their LiDAR's point cloud timestamps are managed to set the parameters correctly. If the user does not synchronize the point clouds, please set `matching_strategy.type` to `naive`. diff --git a/sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_algorithm.drawio.svg b/sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_algorithm.drawio.svg new file mode 100644 index 0000000000000..0ca825f5acaa6 --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_algorithm.drawio.svg @@ -0,0 +1,810 @@ + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ Collector +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ left pc +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ top pc +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ right pc +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + +
+
+
+ L +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
stamp: t1_left
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ stamp: t1_right +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
stamp: t1_top
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ reference timestamp +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ T +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ R +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
arrival time
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + +
+
+
+ compare with the +
reference timestamp.
+
If match, add to the group
+
if it doesn't match, create new group
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+ Left pointcloud +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Right pointcloud +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
Top pointcloud
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ timer +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ add to the collector +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ create a collector +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ set stamp as +
reference timestamp
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ trigger the timer +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ When timer count to zero +
+ concatenate + publish +
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ When group has +
left, right, top pointclouds
+
+ + concatenate + publish + +
+
+
+
+
+ +
+
+
+
+ + + + + + +
+
+
+
diff --git a/sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_all.png b/sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_all.png new file mode 100644 index 0000000000000000000000000000000000000000..2410df95a74c7c8e82f5d1b133f205f46d1c5093 GIT binary patch literal 493592 zcmXt91yEaUvkq3QMT-=QyE_z@26uO8akt=ZEpEk1aCdjt0>vp#g1fuh&G*mT%rH!t zkjcr}clWW4P*IZpfJTG{002J7$^g{>0Hg^30C5539qca)tGk1+Ux*+HSq&7}!xzOY z9QOQ^tE7&rx}$}w$9ETVfTe?@y*UfW)WzJ~0c7RqdWO&~0(%k5e=qv#V*cIL+R=er z!`j{)py6gt&cRL&G&d#ZWas22XXg>%;uGNECs$DHr|6<3~>;@Mc1bGSl0PMHO++5d{;BZLJc|DLj?w9*u}j8 z#No+3ajAQJvjb#;$`?_m{_;FYebUBKPN1LZ0V9bO;-TOH6|wd~f*eYM&!6R+~f?apO4zDU{Wxr%65>>h4e0cZP-a z7@V;s$03rBjiS}V1uvocWLRz296CJycpG+%kD5R{ah8ah+IzupT z)}D3xGoWhZq;2v62m%!4@w2_FOZj{B?A5H!y16M^@eyG?Hr#p|nmKh=Zm3QmLd_ny)N}YG@e>>tF8$det(U_h%-z)kW(?Xu#NCPPg*xV#ilLf31 zr$3A7aqoF7??LNGTHi(&@ie*bD&^)|sYAW{+|8F+7mQx^I0Ykj0f($$1oAw7I6%0S z16+dqNF!crUdJJP!mY-c|4Kp3m$#L(<9^HurLDs`+qUEuf9wt0oe1*3T5JYf7b9}I z@K93hjjO^`O$+znNTa$OV9aFOk3`SK%by1x&)Tr>_`Ccg*8&x#kQVeocT~pnW8*IE zRZR8dMs+|9^p`y@%1u#J0(;ih@`$NnNmns&-nA_-$Uzj=6K2D5lQOW?m=hRSVUKWE7TM&sm~1bsq5N%9QXZD`?a!t zRQTS5-{TIH3HzVQIG&=!=<)uYrtrGQ2+?7oEY)=4P%aRkiGJ>v3D;7USCG!Ye1B~T zybAQ!=r(}eR|78R3MEMr5G0CtY5QFy8QgfJ3fot12w&HP-~7r6 z%Q)!Nip_3LF&&chJ@2{2rCa3xZwC@ANxbh z3UP4-hmwGE;o|}WrEmGODDSfoT<)asm+^^>o8ikcNdkWU$F_uvN*PMtqcI;>s{Y0( zlr`D~^q_dmo7aNJ05-RV*S&$KHs3`h)XK{|Q%MsXyeu*`QN(icNr%Q#AJ7U5fybxjeM$c2D_n-B@1VbJ2_?wIGOYYPpulDwgr~TZm-3udk z)z(#HAsNAJahZM7>pcFzJRrzjOf-0u z48O-+<{O0im`FuvoXR6TnXP>G2Va}jgk!CCl6WoFG&Cz-)Cf`HyT-++0=FeZt==j{ zMZikf&X#tVj>XrqEV;BKXGJ3F^j~zat@aQEdP0(={N1O>X3ht1lkbi9uTE2P(7_=Jz1JKJ2Rr@#TsNI>)J~ zRw#xa&0ht3+%y?uv?Tk7U!Zg_b>`RdNpXwEf7$)nW@k~P0{X9AvF3D$nz^TV_znHp z`fF*R;=1DR?|08-VP|Fs#3g51FcwrYthwW1m+dlhQK>}9`!#p2F+98T=v}+G+?zEs zcU}2%EjQ5*9KT1c{WIfS;@cQ^jT7xzZ7S+s%bgks(Ukx>RtCxfEv1We>ttzO8)J^3 zDv%ZFX7%L|?$0uZOS-$6#B>^iB($RW2YUCYf8JLL%H|5ewU}?>Cgv}MrP6-7ne1F2 z{|cQg%aT{{#W*bBJdSm}fsTJ>zEhFdJN8&DQx#3P(!BoC?Q+8iO)WcOlFue#bm;s` zF}&iR^U~(vbsweS(wZ+vCofq~wGzGQ?d^q{u&HNepC1aY0h7o2UEoHzQ{_G@S9*O{fWzU?y7#eP2wL{vmEGT4x2%Fe-=ukopWnJ4Zd$K> z9HL&qhkO;IZhPIklvLcX2^aEp6f50@LTE#ZS}J5EgI<}z1p;K!5FIBkhA3(vD9n4`c%jfHa4PslRX7=dDVOCQ{ZAi3@0 zd16q0aOsUc{U(*Rbhl7_4K<>!sAPmTHzzB(CoW>}BpXYqvuRzDdRerNpIN+AHRBD_R`Ed^;#l5d| z|KZoX_Qs#j(<|fsGT_BzW}s+m8%YmF0o02mHAm@yN^}5L*Y>;jlfC~& zpsM>1>lm}UeHS#H2Y1tVE1o;XbF8flK~pFSQr6ct4gk>wA@U!N`(!%RpD3sL`MB23 zMiK(~IF&+9lK#ys!+ksVJ%wYh{N_N5FQ^+D1LX?1XWspN>ITiDW)05H?{8av@ zz+3Vl>}O>RcV((dMx3{#9|UO>QWqony*;Nfp|n}0@`ot-tX~cjr=H%*xisRrGM>K_ z*Ya!^kA~jbLW6gRhw94|4pz;#I=I#)Oh#4zydk;ucfio<6!*)59_OjAXZjj>Bi4%E z99xmv=K9Oj8JzV98rM-}cFptWCIAW#Jjxf;P?|w0slLu6tcjaQ6ywQLwh*>)({0Kh z=f88WJ@DqE6EDb{K$K?C$(hm~j)lMn&%0<$lxugfxm|zx8TC%B@TLyH=mNK`zRT zVEY&zLN&(?-!cC*qjm-?u?e2?P7PW2b?xKN<+W41cb>!>N`&9!_W%O#^A8Qyq2IAL z;>Me494|uJRI`JyVQ`PX6Ao?x6b-&*#~E}%*%?BBUtM@U_MO z`ruw4I$ZFQCxh}Q7i|Z~4(mOkn^PG0*&>`_3!-|l>ln__v z8#3jDZ_hrqIH>ZW*DlZMVO8;pJCKHKEE}Hn7Q-OHRpDGW7K%KadwD@r1??hPD#rzF z^PGq}lANSP(_A}>B*(IlfeJUWiV8R16`ytjzS3cHGHl+%o~H``(LYO)_rdT%fnCCH zgFJpfw4`+gyX@f8iTagiz;FmjbW)S$!xb4T@W17 z)j9QVqVuSbtrGLNLGJruRl&}Gm^1V?Qr90pNiaXjnk=N>I?+0SP2&=Fa zl*+zRb1IGC+evc5AsvUZ+wM4i0Q}Wl4L)-6xk?R-G*X?1oG3Wwf8^!FDcPq6h*@;3 zyC24-Ie1a+Ihq?=OMIcxA&cqSOC+dI`GiYU=1Po9Of)}wBMAS!^m0DU{2Ma0?}PbH z9C5pR-`ylL!U9d-p5mqn=}}5A87snDLyr9H#bwqknHXce5i1*rE?4o<`X?^Xf@iuo zW$HJbpF@U!ED9oguTn|h@tEl!sDP&qcFdByC0a;w4%$Ho*^>5gx>rF49TScTIJYUT z`?UZm5GUvqQAw0X+p`eODmhblBlD=~RcO9nEBK`8woT`7byF{x?ohDD%Iyiw?+}_s zBcHjL|G4`NEpxmfGf!wD4((er@pbQK_}1yYj*sBwEaT=c={Sl7b8u5}CtF-B9{1vk zAMx$~s2_<-YKKG`Rg0G%2aVYQ@H(>_eTST}jXR8AV%gKq^N|9rew{byxpLw->|md} z_^pl0wCK`ITEOQf@RMTIpsa^bVDfq;wh(JOL|ddVE0f_|T-CQe{gS$l+-gS}di-6V zUXURxf{F+$B>fDF>F+epN^rUIw{6YykiH)|J?^sM(TSD>5-;bKvXs1yuD=?uo)AMt zsQgHCoxgd=h8r}zifn@CP-3+rb_cDjxPWheE6o3d?*i6EuD;2_0Or3u{`4v7I0BsU zo!d)0ZG-WC-8_B|nE`ZU_x)57h5$s7Y^$s@9~dY_`E&6ak4#ozXQ(m#IZ%mvFOF#@ zKRT~fz=c?-3MgYG2`Yv(5GDo)a4@Ea@5*DYDi`&__=+Un_(SH1n+@I5FFh`<(!9vsLx11$BU@~-8dCr2&Md=}Usf17FmeR3je84Q)}0C6bW+RQ z!5t4-D_sSJ(Fp$-vzzt9Fdkvqm3svMdW16|dS;~*GY@}Gcw;nW3kFb}4&6_0p8klf zuF3tne2GlbArmb=-FpRUX|mn5X=O5fxG5pd?|w z%rD{)p{k1&i8E_|+>KS1_W&+dz$+WFa-@&fRN2*C@)RL#q(`}{Mt$A-l9#zeTFN@9 z;!X@K;Y~QYMLDdk&u%fa4i&iK!g==wx~bR#YdM~S!O>pu@S#Gednj|g$=8&+a9>#z4xv;}I;J5kG{q{y*|uzn_BDUSbJ7xNy*~RQ zii`(Mh1YccvIpA3=c?W3!%L9qt!eLko@bHbPK{;29)@z@>}as+O=m#NjpFoR)liuC zppL$j!ry2@5Fx;Z#+E25@Z*SLfl6FCtZ4k$mvu&D40yF3B?oL%<$eoM=K@@(RW;_d zuHYJdk_5F&58}ekckTuIV^%pYtvq)7|LW4K@>iGuoF@0)-Rx-q7+3O2Pm;MjuXXN; zD$i>x4{!Xhon-I~s^31`o5sam@!rVnXG0dr*Lc%9HpWMUKe)or;=2@6`<4?YR0O8A zp==gWI?z*vmsVqga$Ln$BWxI8|MN7b*U+(`)@F{8Nk7TAGAzm2pG&`qB(&0RdfSjj zJ{uQ7|ABVS<9R_;KS(=U3wXZ1z}aQ|jJ;#TexEp&L|gS0aguTL?OcHgK#o5e-E2eF zl#zlsUggd#72JNZg(^=DYutxP2qUCmDU78kuLMWmJ3735pAONvM#Mb4fwmd`G+#g zn@HoDsARw3;I8}nhX45lGvz47{sRhOrHbn*4uZ~JB%YgrAF8Mnvw%OW-3UJ-z*kv6 z{+#Ll5;o-X>;9OI)PR|yly!lEQfMO@`C6*hY{LgJbg(XeJCpMMe|OL|S_@WZTogL; z!WF6`xhd|9?#&LUBEoUK+1iux9;H2Jcybr-(H+zayq2k zmsOIx+JYE%Z~oLW%vr*urS*W8sJ>@(N&>G6!*GG1oF>>s!x(*m zojx93RphRFgg`Z43?mrAaG5dn`yF)FyGrho^yr-eFUWJowI_QzCd_`m@#J7GMm|R=;*Lq-JMp2F3D=P9wd4HZS?%)9 zHG7Vi{Q8*|5GW|)5Y1T0Ulf-#B9`DTpN{UCk4qHR4z{}NeuRvXZ=A;?CwwPz%u*#i z?{9{-5l75-8^~`9d}xw4#hqiNbkTkrIvr0)DNE|qxIY~Pdly$~(>>JGuR>p zq#j=kj)2iVStxz~88mzrr$^QUKHz4%@|v?snpy-(BXJn5@?IDY&XoV1*c~FGC*b%C z`S;^)dV2=ne5drw|Awx4mNfWARu@$wbJxv*U{O(R{#)qGdNUeIjJJzFEx-qMiiQk5 zKNn8FY{EOdQgf{jxWQD3Ssm{8GT{a+y=oB(7c^KzS%vP|jawIWnQF@jo%qj7Y(l-= z&taN85Mzd#6`W5!jc`gLm;+Tm#A-xiF3Gl*0s}qX>!B{t;L}uCqV7dShZe!FHbX_Q zHzw=&R_h%J21VL+6w=Cr8z=$Z^Q2vS$-k~y!!a<4a&5r2V?Slx2_9Ha1xzUYB9pzI7+i^ zfr)Tc)?cCcwe+awZf>VKjC3cVMD7%Ug40=hkhKF)sZ+0cF>zJpd!2kn2Y#13!u7ScLc5N>e z{-)^j&+KG1|AfJth2q&vMljQF>0tbjj``{E#9|;ae~~uq65k>~8XLbugd1sbIp7n2N%;KgJS4qV211Uv4lm}HugymntRLc!1Q>dcU ziCdc(;bNRVH9rKYDShWj`D6tD5o0-Z4rd@3Nl6&kBMkieqsn|m%R#0M9I`R$_Jf0? zl58R??r})MYE8A-OP7?U9^tMxwhl!Bu_*Bq!~ohgM=m3%vGx9gy~Z#cAGWZjZ{+!h z1`rWBiREiS8gj|=ZoS5nWC;$F)%c3N_rzCc-XJ(Z$H`u zH--)^CpKO*B-E7q;xGXDrS_gU{$p%W2o7TI96AQqMMr9K@5I`Fl2@OHfbA7TeJKra zkB1Yqch6OS`28Spij*OS!UiS!#8dr%Hw|#}*87VMH9Q>L*HXAjOJkp44hYlX(TOlIa-9&H4IClfxL(W*4^hSewPyJGaxr_p z>9B7k+XjMUCJPc)hz-0fhsV%!pxYBI?*`k%UOpHmNw&ctmzbm_dE>jwsziM6g9V{6>6p|gc> z5Gq}lDnHvq%{2@D^QWU3<#)y%ebesnW^Q5P&%mf^z#EHvvt&* zIOTZ%!w*pFO7_`N@Nl`@Tj$3`y=jrCpe%+7;!J;T#M&*hzmPMz2=eCs!xeNc`{Ajy(f6svD@7bD>kHq?y_h76C^y2R%b2aM;?oC^VpqIL0i&-d*gWE3c$f1Rut`uM5RrNew)um%^%rQLF0ffS(4D4XP?H z!&u!zimG@8w|4EtDvr?w$_w4ZLJ8iIFinPu~OQWtE2Rxzru7QW%9@>@9 z`H*?n)3kS|KH3i!9sF?(I6nmau-|GRq+)15AO~O(v2?Or`pF5-qpbpZ?$X)V!iEd# zVtOZ24w@?S(2i~b?GrEkd7om}SocMUjYE)cUTWLA+Mq2YH*?{Rh5r_akeO_SJ!PFp ztwm3zBd5x|e?TOisy?<;OU==u#zgBI(`q(U6gGR-B4(Gq^w3W(gT(0X?MyLnqz5ak zw`!$tf2ZL;Hi%4Kg}f!9cGT((&+k^lSCCzsG%pud*OeEytT3x)OiV^j9mq|KU*0Os zo_scfO4qTOG1Q2>WGSK!%_feW`N=w}B9&Qk3jk!8Zd7+qBlyVeSy?Wh+i2n2^MTlg z#O4@)W)>Wa9ahnKU$_>FO)=b_6U_+*k1rl{erXs-BDPesJ0Bjmp7Wa=wQ3t0x7t*{ zb*a9j%MeoqO^2sbKek`AYMVO?ktJ|FTJ70`r{_hzPh`C{+_#0%HuV1_?+`1S<6zXT zs6BpXb)~pL7NT+2G+%C@4Ieqh-eq(r7@Hf&VhrgABZI=;D}9Lw3IvD-mVYJve5Aa7 z*WHa4_u7E>)v*Zx*ltd*-MD~Zp%oNkkFB|4%kyPOCEf|w8X(+RY?M&-)K(L?G$rFM zxVt=15q@d&KEAXBqVf@RnQyr4c zJoBPtXl&>JjeRUb+dQ7niCh6`u+zgv@CL1=?XuTt{guy2}n132zLYe3q4Hbb?5RvRN){lpAOF+KSSj#WlH7 z0~W>!Oa3M)j{0M7D04lr`=2V@J0k$*grW^mMdyV;7#GAsQV!jPkW)quz}t+d)IHS| zh}GvMXEV*TO3GxZP%J>KhbIi!gqwl1kWAt{aVsBgP;NKy#4Q-MKs9lv;Rwvw#9fo= zcpQ6gFO*uxc6fJqTE`R7Y6x*+(dlBybDz+bWJQ+GDaRbyg&U_D{nWH{z zCpyWT_6MR39n-T74ic{+&7l^t*p*1h5fBgShfIn+c z1u6y`5e0r&U#0}_fpo1U1HJtx<=X1M7Y(rWJHhP!9YM&(-A|EiSOl8s&c3ncKQd9`2j@%xc?Cl?U z30&KNzQ)IkIcC0-<3cZYF>^#vUuYs2zv~Z_|LgrLY^`<*k zu?MtjW`Ur%mkqlz&eB9B=3xt!&YpT$Saxc`=JLW15G5WIJxk*AX46>(Z(Fj;Ac3hPc~U z&oEAOtYVD>>)f+}|ESaO_k2S>WC7fJ6Hb_&S5qY%u_(OL?q)ALpyt-&7ET!Ot6k)t z1b$U$0sgflFadQ($8=_=S<^i~bkShRdDAJTPeEGcL7`s*d;Um$WO>W#K{N?q0X!6(UBOjk>lIKH-t z+snEp1EjpCZe~1Pin3#47RGEBNu+gQ3GC|$97fw$VqR0Dd!p-;QEH?FOa|6h&hSxX#=cA^tDPCE~+w;&d+ir-|u~({0KLBDGxxo5A(6e zMd2xXf|@mX;l7t-?D*=j@sO6M5&TusY`rnErPp-jx6D78>f8#0>XImKTAd-qafQHi z-VD5+M;=*T!9T7Ni^G2uh@*USCnYj5c}Cc;b6<6?Xr@N>yJ8~h{IxMDJ*=J5|1_kw z8s=~4Ru^1x@jV(r8lj<3!hGfEnY>naj!~^##@2Tzh)MG)5~)ctH@$J{uP3;2?e9rt zX(Ud_Cuxnsk<$7x-|LOrIBLSDuUk=%hm+ zxyK1dHwRyBlIiD^WCd+MM4UT(Hu1PJX4}hmJ*fBlurD-W7#(WH-44ouhuC|6>L_AHv@|)mFFT5ufUz=>rBC;UuAh{rlAuXCJZJw#Cnfh2DwkrMxPT z&!P!><*@M>SrD9C6g0hQ`r7`IcV`beNx=F9a?m%96xj+b`~ab&;M|1THj&l{!YD3- zn-)tPh|ARjn+q1iQJOYD6G{j5{{f~EGe~l$YCp=ac4cBMze+y7SgPUv`ixYh`KjM2 zyEQ^`%?2<9gYM_ogHM1!yiyrcO>S+f*&i+F>D<^u8%GXPXY_rp{CTZR2Rw$SM)wx; zocUH0CzH`QqfALxcrKWQFnq6@*V=(-LHhA)z~OUQweid2=N3{w?uQ0(Gp{>KmVN5! z-B|Mw$-OFVQ+fZ#)LqxSR#EbGv9cIv{cBZNjwRz{4p`$6{yS}2IqWfiYeq782*YUC z=F@*J!HFbj-gZ@_Wt=jC*%1&43npP;6DvMOBDiHRNRn^&6E=!)6+#8yiK;ysz?5E( zU%ba3XX#Z0J;Mb*HMR5J3~}AIHrcR%5zSq~vr^392^Z@|=)p2%>>$7;$*DfcNea$NFDfDY;KPWH|gs0c|S%7u(`01wm%VCgA zHX>n<-|2^Nh*F>5&WDvdwQnB`E_4B$^I|=&N$;8s2PPdo`gk(!6}rI*>>td3_P9v( z86*w9lj;jnHd2T>xA^>pb<+T8FHp{#BAsw&k8zF9Iz34G0t+Yp&*jG_uE36bQtu8?wgbHE$ zjWB4X{{06eG3~UUM00htbLp1hQqO!z4R4%4>x~z@m+zFVK5&U^`$qN4;m>QRX_9w- zSP`HB;8ZLLs#5008;4tWPEvv#9;aZF__t4}|>F2r6xsR6HcP!mCEIOC<1CmOH= z1bD^0dD}5uaL9Ym8rQg=3=>*!JF@i?1A=}Oc%MvOJQr*5`SN2Tv1lC)e z*8AoEeZbHm=wg#9_BdRQWk|HKuR9#T=?nR~M}TIn{ze=clH}ETuUDvJyBm!BGph=@ z#LesG%@VsOf{OHC=X;mD34*>+Q7#-b%&B>fWzv8l6cPAADvB+<94~S}Q1INdR!-L) zbbV%C=|^+A6~;GNbl01j*xF0}+yq$g%V*HIvc&CjqR>}y8Ho~1puEi)P(X{2l|ADdD~FP?WvlFuSE zsY`6*w~`(s%J#|9|D2hG#n(J+M15>ZCFceBDSbK`%1L)aN zG&zdcy1#$>J;;?8O(2bM0L%u|!Ttl5GR;?nFH56|SLPOV6?zh~!d3b?1l8$us$0Ln zi&}i-1c>Qn3Cam4_;Ot3Dy4wjKf;RkGQRj*pR%dikjawno|((W(P;)MM}$??w-m(l zgrZ9P%fNsfUA}9sI3<|EnyyN;kjG8BmiuqCW#ainR`K0nW0V(c-Za6A5*BzAa}Vtx zfh9@B%?tU`t_1&cn9&T=XWT*P_-Vv9uIoWJtP(_;+|_P~O{(10 z+Lu%75zEvopfW3r{rt|2pFWdaNs?$xzXmcy3d{noQT97aQrCC*&NrJMyXvgbHrSx| z8-p?_no6vQiK62#L>wAIH|Xm;O^i@dP_|e8hvBUhzPfn^g1fPF0Kl8|F7T)RZ-9r6 zb=XGS37yFtx|>+P!t6riK_PX}Oyo}LPoZ`1!>4oSY!p$iR&A4)kG2OU)b4CtCUYJ- z^Dnt-j$+TOg(t8`Z%sPQ3_Z!*B-G(t_|{8@E97Rmeify$c){rdrY-6HqG3TM7K%ma znc1myfraO_D6VV2$ zhX9IGiNtgUkB&A$@@H3uz7v8`oF@pbKXk%WnTm^(o;ryB1H*a{Q`d(c#9tQ(Ii|_d zqo8&eJzso-(%|~H*w}657ZS}g8#ITXkB=OJKcIwLvD(m*lj{viuKt&XK*IL66zeH` z*Z9*~qhX%K_7my~D!I!vbfhpQ!D(np$x}&;KI2jSKZ4!Z;y&zoB|C3D_xKBJbhP(Fx!qkD0u&kR1ti!jOK3>}5 z)|Cw_keLu6?$S^SmQ>dtXL)CNb&#Fxz$ibvG@E z<|Wm*sw77LqIdP#KonnYZu6h~3FzUHXS-B^Bt4ug@?F1H$=ymeR=s3u~#xo~jY8Z;IY&$oOtf6SZk zdm8|812GktRplhnKKFyv&&(b&Ku^F>QIKgNAF72q{KnPD-2;x#Eh&L>=NP9wI!cRL zQ4VAEMF^PD_w+ySy6|=y=0XVH_2(LNd|bnhj@a#g=AS0teN4$W<1Q2WNR zpDPXc2q)z0W!;ou(@Tc$I&%Ocjp4#0q^9--!@u<;Z~}1TzH?D+6q2Gkj;j*REjJP3 zP&k-VN6+VATJp(bCT6 z(!rDCrspSzQp&g}g*^_*Sf6P8sDk3r|1-BT-iS8-%d(-{64>=skIt2nzEz+_ty*Fv6+TDfX7{^a*SW!9MheCx+a~Z#X1* zm714JO%K+%Aul&KUFCGJ2pQlr6Bt1T_8#F@7=99}RobnCZSpdRg1EN-{CIK4{b2Sd zI2CSOyx6#5ETaCw5s$5Dq(iP>me-i5g6h2cvDUTE}q;8 z{MH7g2bU*ww5oI#YfeM${L1rYmfUTdM$fPmnydX;8w~zS4Fw-CK`3_oXf$F4_6s6+ zZKwqzWUASK+16ZaU656S=RFanN-?g;SVZyKF$f zQa78m9~CE8y#M5bWJ7oWJV56oLOcY9PpINW?d7Y#N>(!-6(OD)?0mq}jWh9}jbQQv zp=>Cx=yW@&H7miE2|loBZ*k@u+PeLs^Y#@umC!FYq9@ar;H3;5iHAQqxPxL~LvJ^$ ztS@H0SN2Q-ERi+j@$Dt1+nrzIW0gsRo^1AL`C}89X~ZBssg`hTenBb^WN*?I16z<;DQ6TS z7A-Fs4GBvUJ+clG7@tipMBH9aC7xLhIjMJildnO3PI!Eq#PIv=ZPZoK z+_EiD_XJ)keUtvPsE=RQ#yV0~sAg6~rg06PYY*z^!?bC7Oku4X#bnfdb#Kk2>`N`f z&19f^mTB`_yy}Z{@`4?L8WiYP0l1vGzv3RW&n+4>kk9t;^ZmuU7Z+)p(%0JFiN9mp zYqAo~dwQq;?M(H{5SDLn5aa&i$94z{KPR~1|Ctr2k|<6#cN#8AL4J_Pac!J}AmimX zEk`y@fW`g~fS_U_D|!?&A1wK_8oPS9V`4FrtLK~~U)b$Pt@L)tZ1fg|cfY(qaPA>$ z7364$Qyaz#6Ca!maVSm4QP!M7PJUs1ntU#`fZ&El^H8~@51zd(b8ixZ&r<`SWf1pP ze5OCF&5~oh9pfGx|Gw7OCW%+wA z3@@>l8F1!`(_t)TwV35L@!z_WPf8_Gjj)26297$$n!VuA7zwY|EpSpKB8aBKO+H;^ZxOi`KL$!B;=S zz014^1&!~q9VD$`d1SJ#0Ki!lG;K*6W7=SKds6O|u9{gmX#e2@&D%hS5NS6nT)7sv z@#sg=lZ;p<#XIpb(u$n?a2K6FS6(=uV1b#&zf$twqjo(TQ5Dc5cFQ|&6f-p5H)4(N zd_F1E;-abg;59|^Uy>*hmb@_!bu%k8={ET|KF9m2h8n@upuW_Yu-X`%)dXWIVwSym zeq>p$e4+ng$JjZUaXHDpLPqe@`xn}N8P69st@ZS7{;2c?dZ$dv+jmL(eRzhPMgczj zdOpct!nAa~gt4)(KILPlSt&_#v9)9P-s58W?+}9kftG5#imgCUzMEX`mEO^n=J9Lv z(N2B*G^~wA;*6u~{@Z4hZd7e{^ku=z|B}U2CT#ybZ}|^12NSNQ0@$kr`gIPNU;`BB z70{T5#{T8-vpvdSPikyZI;MZWKndTTWtYs3~vmOn>_<(0da03(IaMj9N_r6TO`8{CJR6`PprQA0R z7`?{o*j;7TQF1d#mhQNQm(66`&1ka{tCFv~Cj8m{CpRP%+vX#3cH57?%A{W{ylavp zOyxkV3tTw#+~OJb!M41yuLMZZnUmavsX9;&8)ue*UJ@)0|6-?32McOf4peB`D_V)} zi*w61^hu;fVetMVQkC?;y~f7N?>SW-Pn>GMbWM)PE#c@;21TzHmdCbfe`AHrwA_`~ zK0Ea+o*NXJ3J8702NWIl>+~vtrqujmOAhDxm?1Fd10gC`Dd+e$efsiXwaqf|0?Y34 z0)YIM`pR&P=+o9rsXL$P%LTH>Bt(wevJ=Oo{zmXjtKT67D?PX84xP}e#PRIVi!Ny> zI(H4)!GP-S0gsN$3QbI}*|&jrXgSxE>RIc^M`?e?$3D{gCgosulF{ILpDYj@)*A(|7V0&!PKFK>U;kfSz%r)WN)IMbyONZ#1HT_t;Ru3zs+LiB&t_? z$2Kb>t}a5vGF{B^w|KfeLxtZr)|SmBOKP75Q-aL%oLp+7*$9k;Bjy>bG`Z;mTXeXO z>`l}Vmj2#f|9OEn#cW(c#p?PK*5DQsjhb=PA(F^_&_B8`R>l)HPv#x;wZMdf!4ick zL*Q{Oxfgyu?v<8MB@OA4;@-PAaB^%y`rNefr^0;Zu&If>8mJF9P z`u}XFsFiPARN|K>fAS{LwGAQ&-B)5vJH}*2Fa93JYPH~R<*0aHUzB%?nQ6W!?Arb$6WG2Mm2H7zTLb)Tpl+p z+_e?QX`UXX?&OmguVy~wuZ_aHAr13KA{F*xVW!dWYHZC89ycmy)~XNsmIr;bvfBM0 z$MFpt#t}bdu^vN3pdA6#hI1LIVP(|s2=#+u9n+UV`QLcCBs7sLWk$qYQeN7)_5=4x zk_n@KlHO9J>>3Ys%43*B)RRw!$0!XhHuLvjg_S?J=3quWw!%^Z5~F7dtjI#5hY?ImXO~W-3cz0C%D5TBz*72#zW)gCw)(G0Dn> z99Or>pVVtHBNoW=F+q+#20PK`Q@ehjh*n?YtOuxGvE?B!cySgM>}&p=wsMO}6ckH_ zwSK4rEN4sWN-f)y7q(;*?hGvF%UsbyZOs2?+o@>;bDxr96|||Qi8&~Rg&`v{ivMUO66|v=tLYvzC=ZV!%Yvv6|7Ut=~Xr=K38fVOquO z#XIBQ(%Wrr_6w0EcI`m#t1!f9XqBNZB~{~*=}5#POQ<1b@>Q=}5<#Ux31;`zQT^|1 zM~P#j4bY(5PL`(Qtmqi!1d|-b$O$&Kh;iGuzK1^*;fHz@tq4vOKevg<3_u(zT!l}0 z^{AqhUN~lQL6tdSW0Fn|Q7GKv1d5q)#md!vlg0rik1Mx(P9>4MCZ&$TX}|6Kz1`ORH-pL?^{n=IZs2*rjgftjEu z$sVLoQRkv5cXIOejF3bohws!-nauQJrSYxKq-I|_sskWMkQ#A?2#XzDW?LoA{0J_^ zS6c_{=YmFF6@Q(|1&K_3r5d@@Q~=oVFm=kFcXNilWyz7=L%Mlm{yfk=xAW=M&+lNO zwS`CO(a6luzHReHeb~Z2MU<(VSndsw727W!xw(!ZAUIzTwTAm|Npv(Oqq* zZP0m|`MJGZpY&hq$c%OR=$8l%4kidgVg3R!9?#!G-cq()fg1gSw(vQN^NK)~fz~(7 zjQ243y??d5;MaL;i>D-yBS+57c^nuztmy+?i(YKC)7pd&e8u@iKB5rt=*Ix_QRqzX zR28QU1l06QWb{76(_n;j32LNRVUSnDe&o4Do%JFx_S*0`)R+J+$d}3?sxX6OV6$-N z3^N##{PG0rpyluPTwR6{(m0zVHZUxjDEO==)JG0?Un51~02R&$RFiz2PfQ1Q*BO-2 zlb@ezVM<%l0S0HK9p7_lJ1hjrqT59J|5*UV`wR1^U;bLbi7?g8`hOeV$VoC+4pI`1 zWh=A#+{p3&!KIwP)r|=UwG%|4kRrQuQh`)|$1K+cgtVms-)ijfL@zrPF!zGFdfM$* z01RYJl|Q_Y`3rKj4BqTk6BG3WylrVAcJst7y!C&5UVHma^SVM@dH*AofDrg3GGcm@-Z|sB|TyNwTpf?IEnHyLD+q0Q9Sdiznx}6)37}WO$@Mgml zKzp3i_e={Z0-fiHFl7$A5L@YHrb1c5>=&!`;c=A!Z3`_Hz%QV$F(O>p`QQ;mtDE@Ril+e+HCCi zxDD_NIlQJJAG)W=nDC@LHiGm&!pihZ%U%wgKF7lBJBr4+iXa&?Nj6B1?|3^_D8f(g z`av&3r}vpBu6BRS&U_n@%VWaY;ffXVlcf-Eaq`zVF@{&+vEpEI)xj$z*gt*O*W$dV zJcNdMpb%EpPSD^BHONSO73cy5(eH$h*;lvFo0Wo*Jh$>kwnL}bMd-69bY^;j^uz}a z#_;QnDLmzI1&x~##o(^Gi@o|_Y7$nuR=lQXpO)&u)RME89d;yYrpy*JR%|l zX}_LkpJ&wAHx80wVDKMqd{h9N4Uu#qHOi8uLxyOI9!VS;=e31yGLyRxynFyl zY7H-D7;i^If()M5?QImZJOYrD-&{ZbNyq$0r{HZGL-Yr3STW>2YJaI-9F{#Yr7}#M z%QmckR00DUoe~s7QEA81;v3}(a7YlqZ73^FFyt{FdYIG>~wPph|0~{7Yb$JTQrE)^?$38|)O{-ny#K-+pg# z(E}(}u&Q*cVfW+&>xffKwMBOco5mWl{5rQ^9;eN{tR-V#L)()l89QHC=4+>YG?F}ZLikcCuxCZktf69Q{a3)w*6Dm{!iXX_{OH&nDDUe@R2djvm z74vk`)~gWXJ{m*1I-#?z6!jIjdiZMDbsKIi|OS!gs&7of} ztJPItw-)oUF=BbCbile8*aPV^OVsp><%}j5x+?yEFZlM=ew|cnJq?WO)F6gEthIH{%7K1kE4G~7V7f8PL*dl9^IN2tDz||u+9n=*?%gfjD9eW^qam@q50!#`x~wj$2Ywn(@p3#>OBkJ5jf`6y#u}6#N%G(IF~z&erCN zPgzVL%DE`~dXQcRb<%x=&va=Ruj`d49;*1K zgOroOK9sf9F0j|?7mUi3#U3$(lOG~Pu=JoSB7c5OyZtSPeYL#G_&KImNvEFWImdSo zDVJ%mtUa{(e=-3u>j@S_B|)H@c%Dk$8e)!vLo7~Mws^pc3TayB_hli?j7X&6Y*dlc zWg7E&3HVM65xO}#Ij$?;+D3f5MAUw*TL;z@Q_CCX0YXpllp2McB3~*c3iI!sWM%`S z{whYhW2!j)#hSDli8=pz=?QW4;T`bOi*q#Bvz#oPyN{o(T;O5`?u~lT5Je?8gOnEw zuN$NDd6dmS6T)-jeqf*hVheO;K-&N9b%%hzThdq6io`#Ov2+_XQ*22#giL(Pzm`bn z3dnKV1j*;L^?}W`?L1%_iO%={tS$QpT#6v@!7dDDNplI^t_G3-A10tar0>9NRjAi9 z{Q`pfy%rb|{f7Iylbfw~`Ib)%KpW;Ps24 zI-qe~=Y*)b@x;Hzwt)ql+OYcq{!zD3fm5g5A^N9cqHKe#tQIG_`$Jb_x;XQ@8zC{6 z=gJ!O6}Bf10(*xl`5de_q(^Mm+l>ClfBE)SfeTLmb%|f^do`gHXZzajM*CLZG^6+T z67R3~T@O!{9Pe)+!f|j73QYz3k(zd;XE6^4qSC%N{$;jxv7jfq}R~z1Up$U zdEmg4qj?>&N@GwY`lmt3$^IQ1mU(q^Y-R3_u!b+`$Vc9PY)$nCsbHUssO^ODBMhzi z0c;(MgXQ$Ibf^dm*1IBj?j^u!%81@m*ep6d>Wa7R3`|0Fhp(0t(^dO8(Rw zxQ%wPVrL|8O0jR}`DG*yPT07&f9spMR467{R%{6R+PEv<=n$M0IwPgT8Bm$7{AabQ zs_-ZglsM%LrlUL`*cS3YEw^6+D{nrH7KhqtzOQJW1J)yG57?eExx6p~gGnMpT6Bb< zADDHxb{>(lzjJ9hd5hIkOxN;J4%U1!drJoed-5B`=-%fGFZQ$SQ;-}+nfWN#7U;LW z1*$QR8vqR^;-YY#;N2J;Rwri!YAs1Xl$|NM^g zZhIN0B}+&$dt-|NYa|m?jvr;@N{=7evfO*rT_6@Ht)8DOy`K$ZC5-QWFQ!+Mrtnu| z&+l^uci`RKw^NdV`VIsg#^^?bq7Xf_`iuAwI zN!?SWfBn+*r%##*KvF(QrIH>lBaeVQxAgG|x zAZ0?ITUZI)%N};N10NBCb8omwJIf8B&qSewsdkK^pMDIj=Hb#lHM)YSTSqj~9=IePxPFfA8;hg=XMLke{QP zFN^eF#>ZY^6Nb(`NWGxEuZ5Ne&oS7rYTx}Faq-!NmHyM1jbCrq7(OM68wFK(6q9&> zDcV)TMGK-%jl5ralkB4;+z))*7JJ_J)7a~*i#;r(PFD#7XtKwjJq+G-_z($-E4PI% z+BWwT-dXHICf#2UALAA>;)+k=4EkVV6XP6&(frEIcfV!6l#ZQGH^8@0<#+zEs=R(8 z-DW6_gb3`9V*wssq91H*3D{)rl+bh@)@yE7sSWaYyj6cD zhP=Z-T+v;O#gUoR|GelRD4(@xib33VwWzgTO%`#M1AhJ;Wq!J%W$xns+Nbv+Va(Ea zC86(t`ukq>)QKNe>tdQ+Xb^0yxi0+8i)bYI9CC zhzAy>8EU@M&ac~zJFnZ{s6c?Y*H5>;@t!3hl*uY?tGGLrIOpi~VxJ8IUoL9utcuZv z#=J6M^n+f$hwQ972i}!t)>%ob{S$!8qxWtp3*ahQE6rZ5%wDa5xOXu*`9RM29p_$y zxfMmx>p)On=wLF^e4wvVPus={@LMQ*t?P?s@%IEkN;*za||xh$lhCd^F(3g%g_;A^)Z;X($4 zof?;xa2MB1_Vk_LzD59T0UofTkAN&yq7nYub}cN25*MSoes(|L_uj7cm2rX zIK#ATlCmW3&Z`H)X=1eRN%dWT|B?CBJs3^+0Tl!hdIigqYyRRv#X$(p=F_-;p}`rfA8}F+kxjF?5(bgUsBcw)XQ+-LM#CuQdMYejuCIynhj)1#=l~vx7X4n z@OQf6F4IJUwiBV@P;9BHx0xEZ+45RNIqzYTu%gV?q$+HRWp%hzFrs3sBMa{V{DjyIG81-eC4=#hf!@2; zFSnb5OW5#0p%{TfyA4t&>E*8k({1t<6m|Jmzca8p+m^7(LAf05Eye$VOE8}G)I%lT zn;Q0?bq>Bgbh-2PJiQ-q|w96uyq>q4c_~zHrR$IPD^Xl zT#;D%^)+(yH{qzf1$%H;;d`V9RzPM-%tL-*d%D>d#A~dVKPy5=hLz@CWqn|TtW{PiJ7+pLc&(EwY@gjzc#|Uc z8zr~dURa+{Lf#$eN!zN*U*FSc_}zI;uvC`v${YWkn^{vOk1M63oppxy zJ=fgK-7myv>d0aYBn4bE2!{DV1uJSd74P`Zqfxp)S86c$)`1`(4p5Fo1=U~7Fd_bp z5`f=<=Oo!?R3C*_IrWa_)cVrVBAs?F>pPLyR>=ASsj1l$qkZaAU)mAf0m! z+2HnB`wknAv%^E1#C)=0NOHIc8QB&vc846jgPB5l%YzaF1B1jPPhV0B?DSZ&bqsVo zGP8@kuVA7l0+~5S&lX0RlDa=f6Pi8Bn)=Y4H?`?}N85DMlv{Xp)PefQnkao2$3%yl zJ^`2@Q6IrHUs_rJwLpYnR9jyGy~@9$8qKWtRz1*pCn$!zL+=wT+D82=lXd3$PB+az z9$Z1v^YP2QFM{^O1;0pGLocJX1%u<_1UZYrJ5jh%YR^w7sdsJE%4@;zte6YY{WOQF zH3chuY2Ckci|g&>xR2m z0kyAJj}=K{Dt%B2^FJ#x17Gwi%3#Vp)&0808R>j@O=4@z5+*QZd6(P_IZDq z4zF=ehR`lGwEB3uj%gG>XO}Y2V7x_I=_s=F6;3#bfaNKS+Pqesg;DY3a5e`lTw2uW z*-!qYJSv_Z_zxGqlzs{)bZIA^f4{i8ysH!%PgI?a@qH?EuU86%dsiAZmx1}wQx1en z+mhN)k}86Z3!N@xIGlW(Wr??PhM%90^XGN6y1|a46t~x2X2se<(4?$m|KCRyiZlkJcMt%P%~Gk~7U@ zIXb4DFx_4{`2sCI!=3Z`GFG81SRi|5dJ}YWFzRSb2zS?pTZQD$etr~IA)R=KIpEJz zc<#}h^I{6&xK+F>3VrDmFF{$7>bqVL-^s9#{R%sM+5WIvyJUR0m~@exuyml8 zd+s5X^ID9RXQ3rTppq{sE{4_=nri+lfc`5ZoFgrJ*3-648Lj4wCe z3C#Qc&8y^HM(Xop6)Qc&-u{bRvUH@Cg9z4A%Yg=wVul_g`@X{2XhH6%RRk|7!3{_( zeMw40M6Uk!?K`ZaC6%h0)fH%g=dejli8p)ga2=V|>cOZC;7=b*GrMn*YqcEx5%RDl z*pYaujQ<`g4V^AopDCq_BPUlz#X`~5W}v>F$=toE{Lk{AZN8N`+HT&&Lc!eAW=?fy zMu3aE!^uc{gNf2&UX9>%UT(QN-;`qN-&;%LksK89(RfSUxIL**JbP$K#4@T-{i-Oc zl^}$x_t~JYn~87;sVlNOwdR<%o&aG3z{SUuPagpOuysnNcNM-_QFK8;4Iy7z(}w(@ z0@*EBvUIV%TOH8@$=`_hry*$R65ks0u4n_4u(hcdzB7fFVD?YURt`Y>Q0Aps55yn~|SS?){a&CaqFy0&-8k z8YiLo*tDQvKP2bZ!J=#lvGS$ZbnylgYL&}r|Lx4(=mL8jUL4U z<5h_Ih8)d_m$AL<`r*hIDK>!S8qSABd0zk7bNSADYd?dVosZi~>Zhz%xKCFV+&87) zQ@a}oFC^BIspF-b zpl6fDBKjhogrgaHt;gEX(j<8!wGS_ofZNFlgZ_z4 zj|-Jl&Unh6Q$kRbND1mde4|1aZ;7CM88;Tj@GU>0@@xJJe;{8mmMgyciM4V0_RXSu zrfj7qOF)XCvLY8p_X3(D5KFERoqpSh3Hjc_GkS?(7{X5x<~2-6Y`Y&bZBP)v{ZDdL zGBXotiF<6xI%?#m3n!YfO2{UjsvSk~DCxtKo;DGxu6iBS&}el2HvI{_@>%Trto zq@_G!#ws=vIY<)x?Z5`nxV|UCVl2_u$oRH|iw>bu2&4RZgiGB(`c}L?FP~Qd3qhaM zZ%4qG2y7`qDKXL*gv-dj{E&wd68TFMLy$xU3-SrVMhN~V-jqBH&Lwn@9kxy~MG^Hd z!g6`EW{7z5Dk~GKZ4PUs^q7hsM%YrQ`Pj#W=}RQ@^|n4A@PLtpq^AWb+AT44K5UC( z^!y2TA@Ayv*DVD_jgDSt+2Dav4AKx#x)!sZ{#MhfR=g5vN#SZ~k}ohK7AC24hq`Fwu7$P3qt~3FtrjRDhHWK3 z;NnN@y3%&kBvQ0EQ$vid;qr*!=BWuKXmyJaLi5tYLNI(%Z)6#kHJSYH;)$J_0v@H^ zMFpPP8rTb@PS#7}IdhKR2BE=S#s@(q!9*j$^x?Bn4IT)V=0u3i-ROr(%*t1juR$6$ zUx8S%9{p!VEP^Ey1PXX@40gtP*=%-wIb>hVF$IVJS;k5+HTY*CCn6a?N7rDy0Y3G5 zr`1ShUT&-nQ;EKK?k0z{!lYo-rX7UUUZ9kB5|iXgfi4+pvK78Dh(Ak16&qK}n%s3l z$ZIcQ-FMnF>~*JCanAKDIB6m+`hjY?&C?HY(m7eBo)yA6t(VmkM2qh_YileU1vQ&T z`G9ujCj~VSsstp5(sM+A8n{C`SfX5zDLH5+Aw#S6bYE>oP=oZ%#nZx%Hjm+zFn=+` z8n=r~@j0p}Blm>cG6f~vDm!Bdte!;NT3-ZJAj^mct>W^+&iX#MqZ0m~t8#Cvn zc+20(9u?pQHoeFYnmG0)<56TM}as%SIB%)6745o-b}; zfU6v+!I7JZ?t5N{4ktU{knJ_ahzkC6EIW(TgkA9d}a9;t+9@jcaZ9S-&#m4uh_B;IA5JA8n{Zv*B;y}t^& zS|2_?Q?9@}2_&6AP_iQ@dC7+Hby3)-2LKDqB=e35Ym!zAsnx;gZ9J&%=1{`|c-ZwO zTs3v}l~SUVP-gfU`8sHPQM)H|-2MMr00x_l>OmB6CGqw+2%_b-6n;=J`8sMqxSm z*{%IdV?O3k9(tey%o52Fy<)HZY%FmXU5_=9nQ5lWx$RR$h-_n!jH#_D;So}fyk*a6HYTED)}KJ(|}}9N%48`n*a&ZLPL-~Ya&q?^{yr87fJh=w&vP)KEF#xM~Q>l#PQYUl2&B>drr4R){pvE10Z3$95H*3LXG{Wy!f}8UzGPGm4&;38qc`(oJDl^xQz><1v|(I$03XG zMzFx7?2jz$f#6?d4>WCC;k=#JQshA$@nPol{}l8t#A~M#-SiKTrxq_xBW+X~D|bpF5f(r+W?66aF6Cf%DNfGdD z^_951qT@dt4c$LgK?`_Gx(WRYzjY=mrF~^{W3IOZBw}5tNf5BIB%AgqBHbXvb|LV% z!L*~an7W;NY$M`15e-c8MjRQz4a_sWFu$MXO(*ZnQ^;s}kDSxGCulRz5>#>J@tUg_ z&~`?-j>HSB(A2dga@Wd9Cv|&q@jyt%5NvD+Lt?pw#RfD%#Wc;Qh~IHT7i$bG2O@&M zm}0FKw!IsP9Htc5t_2-cm0s7`@Z&x0%Uzy5M3@uwWhA? zJ0EuBG{Tuj++839{272U*p7Oy1tX>I=;=IBqrl8Q*lzTL`%eWw8-;HHbC-Bs+^QKr z($~T~(Wg}8p5&w2sH*VI8gr3gIpW&iIz|{vbhg{PVfxcl+>}wj@i%|yTY>B5)rNb~ zY!Q{CVJ6d2Tz)4?wUP8wG@}Hua(j$RS);(qY7IptOegN3y_TBYhKX)Hr~{Qx>JiLZ zm`N&&M931`3zKXYf#N1Ro|(;10QN&H+eMjSE@U7=n!C3-&aOu)3?kXXj0=?zp2hgd zUksY6i+o!C8jC)Bi`#7H{teV=v0FBG8HRTuon~4^I^u;4kgX&P)xuo>WisFDCn_W@ zW6~A=q&|w;CX@H`SKs!==GeOx*ZtOKMK#;SXIb&yM_hG3K>+5|AY=yAB6m%RCS44c zuy;fl)gJ^I)W9JjI3gKOV`f5qt_CL>I$hTpb@I06h9Yie%U*;Bb=FJ|nBUw(NAgJ^ zYqY`E3YI8pq5;)L_(USH-CnuP2w#@LuU9GfRxklV7{BN`GTpOrZo^f?Pys`Ys9O)< ziCm`f48p^hdg1Xx>uM*)qg_}&iaQC!)Fx-IsdzHbi2>uBN4J}X1s_aZf|3b0vQb6m zDn=R07j7FXl}c$U&J@{(1eLX^OEcCX@wgoBJB3rr7w!OoVSaB~a5FwVa2pXKlWLHd z*%iEC;sL^#kEOkk!R*+RPQ49B9KH$&aU~78{bVY9;LBPncU?CBN#UsOS~3zgEBG?n z+=X*tJE~xW_|$f)9q3LJFC7-bS4e=ffYg^l_QeW3C0E@mPVrIu;%ebQZL(6$+_u2- z(k1SAeTw(obeBGTY_o>9>O_A^pg$$Tw0)O@f!p};Yy2wY4BU+e5Kcv#08tAJzeA=h zkbcnAX;+{iypV;ONH~6XzD&h2f3!Xb(~s?Ht4Lv-6mO^A7WEVtT0gw#MZ62l4!EC< zKybhiznsG{_nCi>b)o2D=!s*f2yfMj{+z!NdDJv_om>sgtbEOZ@!u-^+|_N*7FBVv z8~e+H4MXW+laS{9*GlWVP6}c$rC8ISl3s=yI=F{;_APock&H)!SPd7=O;RO%yfhk%>|n1K+R(0rE!|%P-o-o(XKhO!p3%B zRex_qRRYx+pf|_`QiSWNjsUCNq6Vr`lGE)J_r0xipabilqhv_p9@({kSjqD zwU-8Y`J7IbMP<+N0%tl2UdVRwKje|?^b~dfN>SROmDOuj^(yeO>71#RG4D6lx(|F- z!@v2fKNQupnq)EbTmKwa7?-%r%7_+U=AfQL7fyTk>sF>n7}GqKMyNk@@S{7FTC2B>T+ zlU$ZaZCD*aG?Yl)rji6Bd?E($1~i+ zO?9XNWR@ViE5~#I7?!}FdC!3H4^GvNxIVYLbni>d7My$54hMBkupJEt?LHm9o^V-d z(%;;}4Aic5u&W?=R4YY)){Sa%lNl}PJS6^my=0ZY+-CXhqL=AXc~p^&?xjg*dCI|Y zte{@`QnD*z<&50bd?XgC)oFl;baxSic-Ld{T(f>riFM@HesjwQ5PNNG1^>&mf565W zTut<^2YG|Qxd9h41mpaWM>4ZS^?Ss|k~pY{T?BEyjw0_Q)8Q*iF>|rwA-+}C@SsYc zns*!2Vhu4+dPQ@yt~wR|YySqTQIkxZAvZJC$dUZCbrPBRiVL62jA53z(ux_y+G8BM z@Y(%dn;_Zoec1QOzKK){YZzo^PCCErv#T(^(gQsZj)v$WuE|RBx=2W6)pM13Fy&un z80@d(Px-Ie`UNof`nWJtowINFj2O?Q>#~cTpahjY!7cK!>@sc^LL3+tyoZ4i#<5sj zGpy)+gg-dg@D9A@NYeJh4cmaBpTI(X=g?NE=+DSX5Gw{JhV3_D9+K4VcB&bV5_vp9 z1P~8)Ye$;z?fh5Sgbf66hI?VEa{yxyy%U z#>4QO$K#l~CqM^EXtWhn`4w|&*rA+_fO z|1#&@d=Yrs?6uu8c(PJDMSY;rbX&i8q3UI}WO+RY03${&8kJuK>swmYR;`ZXmoBvp zveozK2}zoD8_qcO9rtqD<)u;;rub1Q)tsp(1zHmLr1yP6`D?V4A)bT~p5R9;mWVmb z?;9b`UmLr0Dbd+oaJGh|8f0(*jV1Iq#viDFDV+FAlXZ#Tv-t`YrNAK(sa-f^MG&mTah{8wnyV-Y&5^l~2kbvTuP+A_cAZ(2Z(wSHBE`#9xXLT2NGv`yrCe24cd zC3^yDW$qwW*hqgV+DXRM!Sanv>U|jMNd>E{ROA5#$G>YOn)~&fsksL+E-ZCg=-Y;G zFPy0d9{aiX4Rm$HdlBMbX=&=gEl!4VZq|4MZ0L7R{I795Bl{?5xpntp1UdSsPFhLR zFy45yEn#zSSQ{y%2OE_?8N-eUHPXmxdBcn8ZyrX$(}K&}EyYGF%w>Rhx?7c~yhiX~ zOws9H`g+A+(z4G^X~gK=<8E>2~v@ zHds8tu!MvdD1lI+8>_>C7xns$g-e20^ zA?g}?HfsAyI&x#nDSV~ujpiSNH6V}xg8ij(Zsz>g43s%%0@-TeeCZ6nqCSX#tP017 zQCtN(r#2ZjXZSfw9#q*}1!iNdC>=Hm^>>X}3R z0---uno&M&=;Z@G7%0WKfRbD=)?aR7Dy?tnobe7tg3eb-L>}=H#u{m0Eft4-cdqWn| z?C%?vuYCG(l6RHn(+q>=7sc>0=5 zTBsam6(z^oKX5$X}2-?bpG z{|Bnv_6X(~h~_GK(nT8_o;f}n_TbjDn)M(7aG@f+q(&Igl_j)%Vio2^%790e-gaj! z8?_pW&POP;xIYcsmJLnU(`!&+a?<&Gw_-#aj)|A-qVD<>c-(+kimHgKl@7&0?sw4T z;~!1hC0!JdRgTfE@imI{9=CGIE(6X&Fa{no!*pBx^*BQIU|K8P9;@U>6B2w})U!C& z4WZm@gd^T=U^z`PV_PpHmx)$79)XI#WmHuNcj|$-g6Jbavl&; z*H6DFCm}Odno|$b?{dFy!f|+FNgC!Tf7TIJ^Ji?N;jpcn@sT?!A4Y(yL4asX|ICQ3UAi4(=SZPP?qEjb6iOC%Ti z4;eTUM%Dv@-)_tCNJBBUV79F}pYqtjDd^>?TK1Nz9n6p=&^Em?uFajbIK!}Xkhd}r zAYBIjIi;%n$g-$Gg~pD9git5P6OSo@BV25nbtRho+%-ZJwCtJ6&pCAZSX&^ugz!v$ zNP$IzVd=s|`uVHuS>Flo0rfZ6R`EN2E)IuXAIq)TmTWHce2ejqr7RZ$oj!z-g&S?T z+hHf@{z4=R{OJh6urjoXr=SivD=@IGbIEH33{xZH^yl}N8OP{&-j+cbjv6j-PNy8LV zW)7_aLOGAi=D{^&T}O=!9xPM%Zo7{9jDQM!(x&SW4G;sn~;>g0YtinDC6FMUTQh<&pqClM~X*u}8o zZDp&RWiMm`A*2!wROa)iT)&!p{oVeU+#feij(6H>k!8n|!=X>I=ABC`7XH3U+SAv@ zAtJtw;No=cVy~r{f*J_V_FgIZtU8BimIxIh+AH15s1D+(di5n$f33SO=KJDyY}^R{ zm@v>y71b_$P3F3Y`pK89Y^)g5fo5!>^m%`tTOXGJmf&%$C|L1L2kN7$4{t=KxS|=) zUVOht@<*%17T*3`ENR}W{Zd2)CSLzxR1)k3i5R3%wXvCGWCP7h50~{t_mQqdSZTmz z0(^`i3JiRij^Gd?RSkyft<-VaR?p~Gy=sufO@}!9P;{e>J@U{cCqHipgj69{LrD$j zOZy`YsaIZ-orcc=83bT}ec~SPo>@QXR_*Ek)$jesZt>qPg0l9H>6RwFzjAQM1~@Rv zE1!kQ%S!Hv=q4ZarM|abw-P-o8KRej$f84NO}#c1fNLhQe>6?KhqqfHi;?IO9I8%) z^-|5`oonz1YjQsdD7eQzt=B~U)2I6o)+Ot3JGeo9(%9x z{r0nvvV-$CTg(U(SxGppw7u(IY)+Yy`}mAL{-{(vfC2t1C>ZRzU)>Gl{x}%#!sDvrN%B#YrcT<(4ObYwHvGx=D0`j2eO9KKaavfw@AR9aBzwtPzVyZh9hiCM@@qO!+M^L=mP zpM9tw9ldIg!9OwHl@^EzbWC_!q>7-MhPBAOoumQp@+yC?q5bT%N21yS1$sxrBRY{^rb%bE;DqC;66Ja!&m_`DRT z$wPQjDU0)RqPVJ%K6S(Yy@lAW;Y^;fu_fgI;)Xre22Lec)}#Cs5kj<4I`U_)jpi#X zvh~+qF4DO-6`7B$4?mhRzEJQ;1|jRLAw;{f+ne*6+%PNhRqi&1^m0Z7TyJ(}&+gR_ z=H70($M$|v-1WMPVlev9Y}mHkRAo+69nQ3$2eZ{{JHKg2e=<3aeZFM>cVvGrj)8f$GoG!Y zwT|Qb=elx1|In`KtP-5cdfZV1POeEXS2r9e0jeSVk9wOkys4fhnsy;>7pOBg?fHoEhy5v_9K;@KVvv8R z>8~uGt6;!z%BRlyDX3$zKCt)QWaK8`n8!%RX~%NT94N4&SE8vVMXri6N0cq@W=yAxn+VbG22%`$E5A}h zc6EH_3^9JH{-rQ_D5UGzh9*#U4P)D~0O41N|JGRx>X#g5P&M&h7Eiwg`D-LIQnUuz z<`yKx2DUI=^i7*P%%S^2a#`#byJsmWKVN)-85`Vr3Gg9)3MQ!z`qK@r%% z2r8hDJ&eem}y%yg6QeSc77jM0&wO#S>ZLuJ`L`&-u7r@ICI*}SruvDT$F$rBgMz`)yO z3phrTxGaeM?J{6)K$r&uhE@M1R4Qz^kv0^1MHeunf?m6P=p!N$e);aeT*giC(Xz&n zA=r?3K@6U9HBmu&Qn>R{M}CdIkiz$%AE&a)-EHngSm8Fpf9Rwz#?-6V zYpY7)7;35p4YI_UE||V+$jc4(8-TYFm>x~5)g-;#qZCG1=K?w*+cgN@sE@eegtH1U z+M^WOQB7)ijf3w8=ff#VW}XVkRJ2uf1pl31+5vHN&z=G|vH*uosMdPMSs9-T!cC6j z&2icDQe*4M`nKMy49y%71kSQtE8$IcJSV*7_5*mYEL^^|qnz9a%HDSVOEZ=a{Hq$H zz3orY0Aczd4nJ}KMBBL0uEgVbB(e1Cd5$Lhl^le1)*= zEltu9n6WP4gr5sjyBsMn6|bD_$NX>E2JFGVf4h-IJpuP)TOWcEs*}$`R=bb4+DF%u zf{7qfjyhZ00|dN*Gl9)rZQyeYC6u`$s{H_F`z5od9?WqQ3@9-5#H;h$ zP4Qr$jB3GFf7Z#ExTVA|%tQNvN3Rm`lW(=fPjHi^!E*ASiO!|lElxa6>rCsxms@$? zoGL$S=>(y4Hu<12Zj^>_JX_Vp#%FE|`SEbZwWF4Fz=*6*=Su>WQ$5Ne&42hAcY9AU za+G_32Rxef3hBe%YD;~jag)!qO%W@SaS4G8%X)y3msPLI7C8tz~ zInY;+wIIKY?Fw|WT|0DIdB%ZD0@j8A#sn%~hhf4i4Q;FC{!La2H#8NQ{>B|OmI3H#dg3tUVguO_JwVyA*Kn)3l#i!3n{WA z;ToOEaSJ)G)+Rze#%oC~PpuXWT#m4jByh=Mi#;kWN!Z?V`!Fg=u;6|zKQVM2p=JNo zxQsKints3$rjm}CAh5IcW2hu54V1)=VCX4ftA>G~B65x+11fu7uL7Mw!N0U!P7;Yx z4V}o}7#1z@EQMBADM0dR1M9G?I3b>f)Egc6!pAl8)3y~c1nc48y&$U^6?Wc@ldB7> z(LK3|HiV*=lUXKSx)+#!lhOm%s!j}qAHNwzJv*9dW@~uy(S(7hJxKbf6Lwsnk-^O0 z)uYm8d!>4ojtaQ&Q}eyG?=LoH@!`o42U+Z9 zZQ(~jZ~>A8(3tqbH6~$%qck)48sj}x!cjqpq%V7f5TR3lJPNUYwDDN2JpM_N9d0~D#E!Q=GQ`ia}@mk5^&Wzc&XAR}+?AU-Nn0;|_1cdi1Y^EvqJjbha;UJLGE86#v9ip-B!FrU#{Alep-?bfBzzEhr(`I-ilm zZ2;5e+v;IBmN{l`eTB;B;oyMI#qL1|_U~vxzJ%xQVNlYJz~*JcLkO{qBG6#mUeQO- z2x+$zP4SoF(V=ayHPP>^2`|pCZaZB{y-NWa6>f^037x=K6B&$`{={rWO-dJZ5Zv+aTm}_T&7L1 zlLvN*c5Z&GCN&QJ_bojmv3ODW>+S&fzG-pyQtkz)owSB_=o0UJ4p8jgj)^h+^=aWl zknjg>p1WE@+V@ZSXQiEL>gLmG$7I)ZM8XPj8`=~~#ii7neu+z?q^yBuq{VPRLupXj z5+tyJ{e+Uc&WLh({8iDw{!UBOuYPyYFs4;Q`pMq!wC#0OQmo$f2`^li@ z*I1n|iNKIE8?1_eplV;=+Kg28s*Fl5V zooaI2Ti4g9c(yPt5AnuW;d6p191kfGDOjsWFO;gC{_s+ABhzmJ32^*6+diG!_h`qU zMB&V#mytbpj&VQDi9nC430F1#mS%{Wbmu=ah}qQpID5Z%r#{p|j_0x^P#W^sea@_( zzxJ%*Rog0f4g+!b*^Dk;X--Jy#VyMpB>hNj8{C@ySLAAbIS{|wW z25XaN!mIU?T3nYAoHgn?iOrg-_Q;2B2#pFha|DtiBCM&-7Y)q53>S**XOu6D%R=V5 zSGv(!#b~RN%W`Ep5SkQQCAtwCwR0Wq_2BDY9m6ecewhyUkx8;|o z38Tf#Mmt+07heDVVm)A~r!I4O9Sy{3K5mu%xj)3>8(+{W$p;ESVGn4Z`WY+ zf%G!e{d>mo$G>MkL1?v4>NV8w;eS&q#7 zm3oe*RpZ$#eQ1zR0PvslOu2t0fUlqZ5=Pp7dcf9p+4SAJ#5`VRSg9DEpR6_~R{Il5 zl3V{9VQ1k(>%LfRU`^L**)ttW1iCL(omYUoSlp7DCeanGu<+B+nW!wPoisJV%|M7Ipk#eEuSB14?3xpp(d+<68lR^O?jG$@u`OYpRL9PIv* znVSfnH2+Td5X#FH(i%E%#rbp?pvZSeO)Ovy{Wq~fJQQcJmv6vg&jm#9G1Hm>%BJEjHH>v=oW;6X1l4=4S++vX zpjly6eH*ubp(}y&+Mv{ExdyDDb=CA=M$kE+rX_4p5V({c#GG9TOls*Rxf(cr`yL#} zS=@><*z-gZ16Q0ld76c=NkQ~h=DA$Q%_~o$hFS4uj+j*46x&4^Ehn6aYKkknbe(bY zgMM<o0E~LFkNmz<$Vk2akADy3*XWI)!W6SZM6S>p6l^IFKB5Kv=8jd2xv{ z5=Y!vujPHH&!zv~Kj6aAPdwPGt!&xA5j^Zo;Z~f%CT-=#3kSw=wog+pJ|n|Bk-|yM zmwl->h0u97hU1J%l%IFw`+s;3*Y7%UJmQA*xQyGf6R}$iY7>+A*I-RnrC!XSB=^>) z5F0K3waI&lDPL8TA5w>m@C_IEHN>P2E~UC$+9o4>-Gx^^GYUE708$Qwud8ZazJVZc z(QUGcvCEsCGLNq(CUyB#`|EJreHdQH4+lc;`+SRt}epFT78{5$O zKYYVw`c9S9^cea(?GL&7f;DZxUb%1FUMcl$#B}mBoqerJ(c0u>*5h@RdXuU~mwYn9 zahLx6K>@9^!)M*5@BCT<@3IuU%Tg7gz^1D6QYymvhX|tg8GW2A7mh!GmPCEmUErIE zuDqYG7)hx2gF-8^?GU}s;MK3($GfNJhn2y>XUA~7NOe|dHG47D@iCkCwAms&;F|Xe z=VGY!t0*tLD^nO5bCf$987Rf71OPehWQ`~WFPBs1l`9C>RCuS?gJ-j-)cuyAbxi1z zDNv^!sIR#ZWY5+a=MMl#jhL~G35B!nzuBU;4Mg3LeD-A&)+i8~6#UT_N3wc)C%M(O z+u!&a&|~L1Ot%gF3vS zcr)j;J$|kQ;cVjw0$1E{^!dPCm6Y*35u{z5{}BgNnU(?V>w z^uHQF_dI`0l<~1a`EBgOmqIKQO=TXq?8Z(loe6FKOU8b7*__u8wS6vzSbY+M{{PvV zY2Qr$+aA52>=$LdK3cT41Au$?9SEMMlYB(~tb0GVroHI1DKmoc%6Q?eD$OegRAKBt zqxRKOdY4mpm#6T`=SLB{*eg1086dP=v;5b71Q)F$!mog>rEA74)pylOsX zHqT761r0*ly;B{hq&D?C&7(E1#%=zyY8%z2)cZcI3+m_I^P2^x?Lhuz4GyxVeQAG~ zP8vXV)p#W;`il*#QZ$!xl&UX-SF|=g=`no=pa<5>_B=Zukgd*wms$OfqFAc$=^)t8 z;=tz8sF7)1jKs9buJz?rD3<&DrAD!d>=&QBH>HT_cJ^1{t?Px9dwdo}j-lmVI%;)(jELfzi zYWg4KX#?~`7J@yS-H6e8h1%831UC(V9?#9vRwk$&-~F`&_zrCu`zaRPFREn8OoQ&` zgYzL4Nkg5`353ZUW$L}i=*0RPuPy@sFrgF_!_f2Y?zQ@7YO}(G(qwHe!rVH!G9Bv} zB5p8!e}cqN%Msi$Z2PAlryp34{ye?3u9+hsqWY3qbKX4bJBUa0&q>QUlN`}4Xsq@y z$1VN1g(J2WGJqPKmBLu&rYtv#?V@bDPQ7;~^*-~Rp2hl@^xBck@v6t4F1Pi;OKL7Z z!9dZyHM^}$75Sl%79K`|w3O)HqY=kG8L?p}4xex%7-6x4T7zhF!u~!FFbTYQwq`~z z6m~>(IZ0e<6Vr2Cyt!X`oq<5)7Nzq)ySnY&*QPAgEN}zW? zu3k%g6Vb`_2LU{*Sp}^vZ<*gbtxkgT>xk)pv7k>TTw=>gUYGm)4`2n=ThuR8}cVfga!rD{`CHz+{yGFXF`|rPOsQtZy88*Hcg_FWtoKf zQ-%hT_N6}u2Hdz6cOrV&yws83Y*9`d$W5!KdXj4a6FLJsu)V(q+pF5CH193!Yz`BO zXy@ody!L4@VO1p`IPJzDfKyrrd~dNzHU=-M?J4b-!B6-gJgVmB^oMHMPW7+BJG~yA zaQ3F^bVZNQpcKSg&;O~%q~M;4G(BV>4vn*6*_7;d%JLVwW=_so$@kfi@jX9UfS|!5 zr01ul@k?VYzEQ3z)c%eTYfG#%Awv+^tx^5+jomDgoH{HCO$zpE>8I*kSozs>87X0Y zKE$GpBYNA@wrt5U)3{AblkL4|+MZZ5iIEVC+aVS$PogO~Q z)@kb)=N0wkU_z8J$q_Ii7ON84aTju51K|*>?_>0q|MJ06&>9t*6jT3gsY_vtRz73@ z`ncDFU80O9L>awH>IkoD$}xR+d}+uzQZE{eb$FLo34feyL6h`TIOGB5(^asW4m6JWw^c6~$1z z7n0nr66NJXu4gXmZzH#~fTa=jJ{`QmniT3lTBY9o#QdAEeC>GV1adh+{m5$-_1U2m zp5(zx+Vgsu{G#dkrR|k7IbRACn@G-uV1$KGuaraquTRnx`CP^J2rt#S=NbvmZy-fc zozj4sg-n~SvMqGF`C_gS_rY_8zoxohm^;rAm7u1sR7j7N=YH)s@Oyvz`l6zq%dvE2 zU8W~T4)8vbVZu(){nZ3|ew;sf!M76x`|Q&aHmiX!g$5-rQb*`e5IB>4KTI;JyDoyYnQugv#a zz!9vhOW`<{fbCUp9N+xH82;|(g;`?x*{%d!NZaI02kSWkH-HJKWc+l%ZzNeGzYF#0 z39xT(AHi!Mmyc}VA0Y@{FaL7q`3hmRqLZFRFYsLZ6&rj5u?-Rl00(!D;q~JSA+^i8 z-NA0$ZI zW%xh#K-wm&fs{*(Z2fP(gKs7kVc}8=NIPXcu;+XO-$DvTpz|9Df)^i*K2d7$n}~@( zucC@7Dj)o2l3{6VLI4DIdhtYcQGz*R+h+Fo_792Bn!zR$v8U-sFQaG*= zw)qA!h-zsmU0($gI-T)5bKe}?(-J`IiKwx%JX8%!jLhZGUJpXQsK6PmT2Rc(S{^rZ zL=TiYHk!8fh~8t+A93k{K4()$(jFP%f!PIiqCqFeMjdFY$sPE!(@>^Dwrz?da9G9= z8dUT0dkowhK{CfUWb7LN@HgMSgSP@TdOCyWQ)uCc9spJ8df1jow+0nmUYEl7r~^W) zg45dgL<4}{i!+EtTwo$eJ?)yN6c*P`;)WK8GqTG8CgQ+0QO0#Gf3%+%k>m)RhHXi1 z65(Ffb`oQsDC2U(g`JNnxEf`!U6l1eq+3K8v4{%~c~e+*cM?I(@@6_gcC!WJky>QD zdqtbIOhGlB3;7mjNrHw{Qhk#GLKD~{lBBu&;#RX?+VvHrt1U8eKV@4(c-F{`Me7|7PQ zjN65J1${I)tl{25KkETXvjm!+3-B^2HGt+8Sr6b@3FzLR&=u*$K=_(k)^Y_6HTJWE zkB{N_9G`&67cC2u56rk8zFL~TRgU0@g$$NitiYT622#|Zo^t`k2s}C+@S8|c^C0b= zJwH%vWaDqDs3IF;L%FY+8>J2oN>Nvr|FXc44Y`voIHuCI4?x;42~btqMhl8uNOBDs z+uU#bIIm-k>M@~F0cjGEbgQ;0heF#`TaP#}ay?CQ9{jvYu2BVM%H6B`ZSfO6eCKD2 zXS{@i30=tgo7K)mXjCAyW}b)bRkz)8_v#8}BRbanss1@|+>O6}YaxV2#ne7bXb_LD zOj}JTUwjVkH~tMT?K-Be0tmTH%3^A3<9#@@k1V;VE@p72>he+}PiIN!2L^?*+j_f}&d&S0wSpr!aL4&bU`<^a?ea%#L z#^kV2p>T%SjC727Q9>+~F7?_cVlBS&f0zT&(7uu6RsjHh@3mzR+S67pyG7ZgysnQ8 z0suDuz+B#@ud2s9D$4k+KfI6OxD(GkHIBf!GyzSq{N?n`-g{>f!X^brdOcWiXA((n z5`imjB->R*_VM^~v~mQ(CI#n0EV{LE<+EKh_$X^idvBe&E|Oe&kq}+YaQp)`Pt=kH z05&X9_X~$uAeD}-kgZ)MA@>q1qsOg3oF>gnrZCpxZ}>0HPi0c6V6_|xUS(%x@lnk7 zr#3Lux15sY!2vbTv@HI!9t5tr;Xj*c!!i?muh+bK!kFf4)2Df+K|Jl0>~`m<2FI+T zQjxDBnA-J8ysZ0&)Bh4Lo4!{XXc>*F^J06B=Y#M$^~Lbu{;5~d%@*_-y`$U#EpavDNPW4-5C+ zWaR7$iJ9^@#YQFB$nb6Df99A9<)|-d3ftg9V%k{!=^kNVH% zwA<+x66gs`PpxWae=;3>_bVg#-cM@5w-VIepG0lPr0$QDuQgCEv~vV~THmr-nD{t? zlOYz8AY&xz(0_aRcgAqxeHU8xClP*^DN7KF4vyfVx)csiqi(IsVCc0WJtf2ct_Mjj zg(q%LATZ#@GEv5zX||h-BbcCd*`gp2p1NL)^>4)24vykSuP*`-7vsC**YVn6l^kp8 zT8b-g+|Ag314nStCLKEqmp!74B?|O$&FVc407}<#xZfC_GXF+6If7J(#U_s6e27H{ zN3i_PB$n<-;osiWRP>fU_Vum={z0>JDVBu}znUO;tu)Fn-b+leH%dv?&j;wXA8qoC z0!Eetx$Izo(pjez61i+wXrHe3?JBC6dwAt@qxk+WitDSH5BT+@VDB9HfZDi}3lEB& z$${Qo~!5%2<{ziZYHKQD?0` zy0{%uXB7OC1j?`j-eoD>!X$c+L2Nj`B?8&3Y$QcQShIq;5oZt^$ev!3bHf==0#M1a zmR%FLa%3dy{wc%xn1~v1ROnRD|40Lz@%tby5lkwAm;OM;$s_9A$`j;*$>L#wB4UDx z;Om_mvBYy7eM2q?_3E;5=_wiaK59VB8OMqhDa7tDsGaaZ(atOERuCOz5R6X$MtwPw zz5noS1hJcH9$)>B_wlaHL;c~?ZV2@XRxF;xyI~K)hV-)a**1fv##GDwj7vkTmKcvL zPa$@bK{)Ed=Xc3C9$~?A1lO-KI395$7-EaQl+f76t@*x^qi*eBT?RwbJ-fjHCgOxM z?m(kAiRdi`;}I7Ya0C;EV}uq3iyBh68D}7DRB(CQ1XhhWF*fReutCA)zVv|C_)rr4 z4NKvS8`Pg|3Zgg7dC0aj=hSgEEhb_nweN;9XDX9i3T<^sjMq+LEY4t$C?m3W5jH+H zhR9p#V>faHLtZDY9&zd8n$qAL3+P9k>PfsNi2Zp9gRy(!#?Gq@2~?R+lw8TzcHkEH;t_NEYv&(8YC2)>Dc-!Op| zZxZ3_E_jz_j*Z2Dv_a0e={+dRmuCy9O-A^p%hvXz(!j4tTd>6LF}8h+TAJ`{GD-8< z*pr+9sF8 zT7}xU9N0FFzA{+3Ok(X7A9fGG>u;I*Lo6>%JxjeNA$Od6c>6iXlmrfR?pM)_=LJG#O4fcP-xiM##r(6ESJ5o zz3IU!V0fuaSk8TDkqc+FZSSoGl4#Harw%Vn-<*X;1%ZohY(`qKEi@?zoONTrmREjr z_9aX&zMNjhOl?p&!!;x{C`fWHz1&R5i6gxp+z7E~dd-0&y&h~!j-uuQut+=Z+s}^R zLWl(ua^OGw*YqTn`;F^3X((qW?qhXKO;_o97y$6NDC6ialKMWsI8q#gy}ye%Y%cN)-p2<_z3_%JyA2op3?_y1A2~Z z>iDX)ArWf3)(RLvx|~3+1!rD7IaTorA)3 z5xY5K+AuHp4_9t~@vbb)`}Axu7pz(+O1)}ezk#>vuyCYC``g)KO2xTR^_&mF{RY)! zJJADxW}9^&f(RxWK{QsHSqbBen>A0)QB@7iMAG&qn>hlWo4}8Mu|Qouq7lSGgMt;_ z6k@j+@asv2@_}z6rXWfA28o zg?H~+L*sBr1s~LaR)j$f^Clxd~zbc!Jt3l0>6$Ra9Z8} z8Bxa8h6%i@d1NLoI!ZnpmoF|&Q+aNMqb>y)f}jebj3u>`7>YA^T$CZUEBN#R3uoMc z-+z7#pIl(UL>MrUv?}{XoWXukMt{Vm_w!bd8nCpTBamwx7>cXGRe{_=BF>y(vFhbz z*pRx9<1|QS8^KvkB_6%Uz!^{Jh`6z`E`_mC z2To`n*6RV{45GIg zv~mPP-V_{h29b!%R9@PT{^0pBbZno1|6R3@ZCybM(#N`=O&}Oy5xdQpl!1i+?0y*r#|MsR!a2p=Dtb(R&P}opMV+EW8F2sUr{`RS@`1nn>n16SS~NEb%3AHn<%! ztF|w-hLL#ardNUreBoNPrc_iD7dcMU8vt8h109eKmj2rr7YgYm{LoDt`ToBePh-%}@%{YUn zxe09JC(w7+l`$3{*glTGe}4gjr!vP7D|ny%IR4#(BRH&C+8Fz@@kKa#pTT#f5!@Sd z6oeS0q&Wav!n}&y7*W(dS8kG4YF7zz-F8L$Pf2rqzg8JucM8X^xe>k3=xS_Z{;d`! z1u|sbhDTl9J~XwC-qr?1Vmr z0JUu?m*=>#k4QUYJwNje^qH&@Nb^c2f%5^aOKDf>CL!i>ea#f~J-TS=7un*ZRFL+{ z2oJc5#tjt0s>PIE5ed?H$&WlBC^oroCCvdKVi6;L@#Qg`J5iix5htL^>5YNr11i!bmASw~E$5j8o{&G*zrNbOZ^|_6z~0KVII(U!`oAxjzIS!0q@8Zla*BnI zBdD!WOU%SV2x?^Dz|cGBmNJ*~(50HjvKyD5(k18s;2!%S05zCka zfAs$Z033VuLjXVsok()(a=CR+w(I*EZ6Oxc)@S4^RksuXpmZ$(0DKT^008_dzRsNg zcFj6OYySm`2vHHiH>u^J#NP)e&w_7Otz4K14gk=-Hvvfz5j@QzaMg{|AG$$YC-LXo zK5sgQ|D-3wA|+ou_gV9@Q_;pwq)xM@cuJHZG^*`Etv`(D?n<{`V8D%mn@)6a1U9@5!Fb$>kAJWb0FdmQz?FZvjZSOYhGPO3-RO)t z!G!Lm(`iuf-~Vp09@zEmUJqXXg_>p{>c%sojPS4v@Ai7I`DPZ!JXNq8sba z-$Wql#+SPi@c-I_CvH!`wPX?_j03k8IB;kM3yvfBpx2}Kqreq6I*Z?E0UYF`Ba-~CS`xD#U0vTqzhg94#h!8t9kXOdflz$G^x6J_id zW$-?NcX~Z|^Pg1(Zcw`(rG0Ap8^sBHY2UbBH@QH^GOOLo_g=3}?_`-==QpMIee1NR zAi+VswdG&>HdjDxKdhfA%4KEK{ir&Y`uo)DK(}2nSgIUoO^@CFa~_jLiCw-6ZDB(1 zy~VJvnaYl(iYlroJdDrQK>GRHeWS#z+T1;5@fj;}9${z?%%l(vPmy*&0Q z{*Nkmxql&1F54Cg?~2kqzgcZn3yo3-#VmAr==*4;g1$!=E&T$k#HGDu8n-?y?zmM5 zs}@swXW4@HW$B3r!*Xl3m`j!|g#_h0^zT{tm4DIrC5l2?wK$fptjorQ0|2~rDa34u z$3o$iZ;ayJ9VdGJCDT8xQX=cRIRYgQU+Ag8Pxvw>CG56Y@xn9X_}SYv_=`Wjhd=ti zmLTcyftk#G%#=_>kY@qs?LjzVH{pyA;pt8P1;48KN9<{S6x$c};G=#Qj(_OJZbigV zcQ3ksCxM=ST%h`V8(v!Y^#rwK5`h6X7Ek!lj5PT!G$^J?73=qMVxK7EbcoeSaiLMk z8hw{c_1EVL*Hgxzq6G88z#_G${}jf%++-43*#jUeJGu)RZ5=Id!u1_R(%RK?z) z;JvnmV0$N!XB_zbFOK0@gvDuZ3Ic$Mvku$7>s^&XRI0)E+Hc~$ zzpO#a?j*v$VNkath1EO8@qd4N835qGW8--9gBnOr$nYOB*H4m5f(fY;XZuAN?`U~U zas*6>h0vs6!KO*QKM4&A;6Op6MN5y#@PCl|!HwTYfC->hnVi>sxYEGa+XuufhetNQ zh9Ee|>i=`@TS56Q<@w89#wv;nzKI}sg~f}Hj^n4lsWENK2NEa4AM#A=m?~xtX^U(k z)XNR)GqiVk3bEnhddKEM_cICfyj?sG>uxcDp5D@WWCH--OvbPWAnR=l>~kxDLUa@g+2I9q#`V1s;HvUA?=glf4{W%1?K6E?mx@5Bw}Q=u%15M zUreY05*rCxYLobX4=+IQ9BXTHQLLpJojckwbnS*|o3Ks6ih(VNIpZc91EF3)|3w4w zt68tm{0bWtMDtuC6m$On?7e$@8`pg=_yq<4MG1OZ5+PEQWQh{>Bt|bwmPRi-M#fH@ zIEkvJN$f?^`0j11^=^0fZryHtZ}$`5-gL8jx1W66{dAi)WpmryUB^jN=TVeNLRwBT!%dikKkOwu z=#aX6{@efKD2B%DSmx-$v9KJpapUHj2;Ec9iCn`YzDb<#H(r87d*J2++b(JRaVv$V zMfRZH;+4>Q+=Yp88$9#UIQ-d3ym{O>*b2MK_~q8KB#o5wcXV-vOqd^64(& zJ~C?Ov@d!gTmlL?UERBypY68=r2G=3t=0!PO=|UW~Y;vbAIT4L9*yBv& z-4jikw)=!nz`O&qvDH0+&_yQ>3@7jpKbnomD1(-^G~PPhgo_s)=>63!urDNVJKBtk z7vvY?@C^sJ^&%qFawa=9IeCq$zbCv&Y~7kf&u^O0Dy3y>nI{Dt3pL4BGzJz~1pE`Z zK4695o|`FXujN0OK;TppqQeXxYn5=J0?P~9&zuIa=9qyN#Qwv`0>tY2^2|#kE~w9c zV!cB8VWa+-UoTsskk5LQo7l1VcO?u};AZ4s%$DV0Ys>s*0pY>wmb!c9Yuj6;II?RJ z=d;W1*%flE8NEdui9vH@_ax5W)NW%}N?=zeHFk3BN(sDIRK@|sijN#iZ(~_Eh~CwW1}kl6cuqh#VqW{^_nDg>0UaZ;k-+a4 z5WZ3W{+8fjzn{X{ICaEI+6Z(!NHf3;Cg=ZYxd#~;vzH38R3tjWV9~NPGM&$3eBi9= zudegLsx|;hx}^oSaV@bnczX!kHW6XBAI$wTc>aY1eioR8TU!@l+w42aOrOgu;o8S8 z#g~xnl+b(4h2%a7H_y4iCcDr(tR=qngs2|R2wufEzEGe{du#|8Scv8bgOojn)F)QL z*&|!FMChP^_n3mDx%k2pVEV3s^-AbH>r$@Wiq;g~9h!&GgYN?XJn0t1dOyVA*oB-l zzV^kl_`$E5(e?*VV$GE+h>S6qzw$7C8t6xKkU@Aztpn20=?T5_1%e?KBh3L_P`Ru} zqY@k{JJE4?vl`4(*_ZP4+TxXz;E(IFK_&qpF4zz{pML-oeZb%ghbM9If|~a4esu!x zy{}HFL`E5$&PGiq?IqOj1YGh%(6cnH)D6E`$g!)LE~I%ea2=vboa^wV7ZNyY!pe?f z2%U98pxR@;@&LddpMV>ac8q2{&LblX)_iL&CO??Oxd6aEngkYPu&XnPrbGq@etQCg zCmdMRnpWCfw9g6KxVofusaL|q^I4VsY7rZ~Nu~3r(dCtJ;L1qs0a(q>Zx6B)I0GqBsRcq&e{L5sk&*e@rHQ>*1MA2y#7%S!m*t5aq-_ zyq*C{>ENOS)lSS1qMVTN4}+IEnb77p32@KKDA%7%V$)F@r133wKyRpOi4PF8}EZRc<0lG)*yL(^XsBEF*|jIys1lyZd0s|;7f6m4>> zpxyzOArYRB9M{LgVOL6ES0!^uetK-F1jN)$xO*1J@l$4Cj0;gmU3|uifhNtZ@*po2 z>>Bg)ujlifsz-*G+3ep@X{ythSGzw|XACL+BhnX}7R34)c4{9c94rGIaY6?-p?0hAp zIXOA{r6_uj!Kh?|J+1}=)z7q5JM(KB9|yl%K=`HusU=;oPsn*KT$;w+3+Dg;ad!s8 z0}Sl3yP5%YDtjTK4;bv-Hi<`0KZ`KakL1B5m_CORKvPrR?2Apl7j-(=YHC&&?8*Fr zQ0=K0wxnASwa38p-@?mB;|TU@mw$_y=fT)yTa=V{0WzLd_jLJD^5g487x~2ymh*%U~r6as)LUVGdZNW|M>($XPk(|w2Jbh zUz~tw1A0HM%mN}h#DITFKsdWff<9ONpkPSe6A+@tvoMYDki)d#zB7UDHH)tyT}v`IEq;`A}|o^onxw-RQbZrPUHN8BW(1+b+Q~KMj7f zh|qw1j^y|7kV9z`T&sxQti=TV93yoQ9&{)KI9)IN7L{aI$m~IfVGwniVD50s0U$#W zry=o8+ozFz_34!gqhkmmuHQ~?qd$%EEVV53`5T>UIO`C13?bWdicHOWv<(wyMP6O%Y!p{TALSg8t+ zj565IintN2O^fO2Xcoc)*0zlq(tHLF3mS#M&jH@fPU}SQk&Br=Y>4!OF_mf!A8*=xp)2uk>7uFyjF&gZ2O? zbz)WB82OD?a(uPvR0Dp4kT<}mS@o9BmmM%aXsMMTD+kzi34sb!Uis>?oO&)co-B8~ zS?zJt1*M!n*@s;vA#~jd|G@;h->$vSbfcqD+maRI(Q;6WdSN@HnySEw7x;Ac1g~|S z))Q0R_gw$(Tn#*rq!GPWzc>kvghq*vH-j0}0uO6@*K;6iy%Ij|b7G5EvednRnKj$} zryZ>+MR`$78KbvpDWp>LEJ=ggE~29?1y4GS$QXl;=9KIWPN{Ixb6Q}N#uZx@arN_H zhP7mI%KHfHu>^q9{htb{8KU+W{QD9JUUn&iL&>)bL&xtZ``GWrlyV;4G>HoaiZ*(7 zm%MD-W5ap#O*>j(OB;JK+hg~X?~&|Gi9M?d@7OEiK4tA9E%AYw=tsEUfq{=1r1&U2 zjx=I#%fIJbr|frL^dZdjW0-PeiQHol9b{m?7lUVU8kZ+N1lKM?oMlry?r8-Snd#?t ziHO`{;8~K^T$4$A3@@?kAa0bxm$uuIbDSdoP2 zu)(u1jo#}nc-qqNNOHUT#vjEoI&4F9h{4=B87xWVF2}P%=@T7fG>ZA@tau?HD)Ie3 z0XGV$&k2}*27@Jd^aEOt^GatACEr}Q+~dd?_^#`f*CW~dB;RZ>{SqP%7`*a_alHG1 z3+WcXHZBi--4m*ssh1iE)5`O5uKksdv-j&h0q(gO96OWyau6A1G_$%#pPRs<)-(cd zHx=|g2V}B5nzek24i+yL+o4W)vg;%)nwzOub^b7u=6aPkt!maQSk20dpj>+qa=hNJ zoKC0K>hkbihe8PJ^RBiW#2Y=IFMFe_%KeWg02?$O^l`zaQI?l;z4Gl>PCXRcx6(Ro z^lM=?@}0kt624)LF46*HCMW~Y~v{$6YCU}_1o{m5rf zJ!+w(E*B32uVe)MdEd|SHKp=NmBKcEaZ9Guo!M3iq1%-DGLIr5-O>zuETJmY)=Tg- zr-398I9pwZRxRn`^9ktbX(||Pon0xxoz5UQ;DY~)33UIzT9uCf=>$SI90*--f@>8K zx7kcr;IYXr+yFGnZ5mvsh~Q-xc+rP|tEZ$icYXB{ocOzYkWxMzTJd;;A+mivJ%J^_*^ zjZ5E`|K}bR5iDalBdy#f;5LdlwLF6aRbNJRO7Qr9GlAdyy{u|~^@TBf&cFKs@j36HMwK7YHKQ$e+IQjAvH1ks008AU7P8*8wvGRpaUrQ-c${^)v|qLE%7iY zv&~dAH!7yO>YU##An<{C<)13b^Qoee$WLT*6D^y-(72ksnUiYMiBM670B^8 zF9f|3D>B9yM!vO;C&BL!5WFleJMX>bLOAL$#oKw~x+FT5rV6SZiKjWB_15I~2^ha( zlRY90)DtAgWORg4RpjS#D?Su3^7Pj^|kuH6>$0IxesK?Hwz2g3H1N# zEWG-=V>tFv6U4X;5u^Sr8+Skn*jwg(6Q9tkg;uOfDe8xpcgNwLlR@~Nqu{+l2Lqi- zUeH#+ihz=|syr^{dP^JqPe7F9Y^zq8ZWP$F*4Is6S7x^zqAu5~@(HF=J2hIhHI>Rg zgW5yWKT!QQ*CwJj;?k(Di8`Hp(%Ysp6t#7ogLM*+GFYtwFIEOif`<+>U^}Fm1(*a> zwfoUePN3I<$$&;cE$cHMtoA*(T6KQ(&;)udT$K|p5L>GfSfTRg_XzN0%nh1qrAn6V zluC9cD28yP{s9=xUOmF^n;J^?MhXz>S(46qC$4w9n1L3*^Fl%q8y;9GVKI}oBt~9Y z#5o|Vv7;jlxa}e$ceFMXT&sx3+9kM{41(F>f^Du* z<>fGZr*L38u1$n%zWgv^*GmXqP|2r`)hQg)Dc(u2JZ_7K-m~()bGR*#B7@34{ymAj zKHQ{3>u^=Kn20lX?rO`OwOj$9kmhW%3sHLvT&IW+Ka$Ud4z#u5_vhm7 zNm2QK&m&J@AaMA3zC`lc*=f+ zYZtL`S5gUtNgvO6C1hfZN}5yt<|(g@%nyO7R4_dBxU+=w&> zatZpP^=B{%s{Ga=AwFVL2$kSX7sB`Q+k3IgBn@evZ@(E7ho0D`Q3~m+|DU8s2y!b3 z{c_;nmB_0uC(lK*+YWv1Q)xnnJkQv6spKH8Gnhdk6tg=b<9B)-PrkqO>2aL6GCdVn zO0d@K^OfH&2NSI~k*+UStqF9cK1>eoNl4yTKR$Vy)ZKlE(PB z4GZq8mbsU1IV>T~0if*lJfR!%LnL_01<#^10N}-aG65I7?UI8)M%4!m2|DWM63Vth z0cZ5y=1kwcqQN6+1aG;NWlwrL1UiUm%G)V#`=z`sc$PAlA3Cjkm-hJ3eO$I=@b8q* zft>fzFHRtM(*|#<&s)%YFYKRJsY&=)SH_&ZO1{pFDM$%<_1uGSa8vC21_sedwBn^QEc?e z*EsmG3*1_<$dS45e@VTsxpwvVasr_8Ps!JUUfmJsX@X~I+AuxVtKK(&YzYGZp|eh< z48Z}Ha&MFWC0`TLEor3soZt>j;^=d7zs0UjD*L5d)O>=MUEuc!aJ)B(x6fv3T)6naI2UR7M~>IUc&|1iM;3SAM&EZ<7D(0nfs8 z@trI{;G|q1>>6{={Tn}?3$~-S_32rZmMto$F^=;2$86I9R$9{VyQj|kBD=1BebICU zyS_eks(9)++zhWbZRlJ@603ZNKL_t(SBSQuE;YA{6fv>5Nf5Kd`J%RTj!HZnabS*5fRxRj>yTFl)Owbg4(1aXWw2;L8Xb#L8e0#3t$^@- zM~>2bx`J4pkWW$)jSxi z8DQ5*2=-Y|$oM~rLWU7I@m(@Gqu9+bAqh`P=OO-;apl2|HeAwj^ z;C5$l&!QlqWfA9uGzWl1Od8QKreu;deA5ALr-&7{R7Ed&+y)WX+8$BJ;YhY4V}|+> z7i`$DSH#_c$|~u^RTrfFJ}@`r^V`^&l&u&>Wip$Is^`rN_8X>AD#G_17}Ke-32DAw z^ud;ygNX{%+RqH^SFBs~u*X!T0U^!Vb@D@y?U2xWT^>K_M3=~ zF_4&kMDx_`mk*yn=#o<*&4JvB06-;~XxkerNOO7#`@{4yT#PgaWIz0Xeel?JSu+((gbp;!;TMe55%&@FW8;kqTa+C(Q|AzKcmK{_CaK>F5Wz zfQDh`x}cs`E{YHOX3#~mJEchR0>#~nySo*aqQxmvoZ#;6 z?oM$H5G+`}+|M`fzfAsQ=9(+#KKEM3+MDg#4>6vr^p{%V`IielO4%P(1+29}xqSoC z;42IcT>=sU7<&+Li$x4jOGv$j!~QWxim6Zxb<7KAIA$UsyEZT1UmeJ|sRuyGZ=C4k3=zzH3MSd!$XVPOGfTKjVNr~IHKQuAP(1GKc z6OymE>ok%ca_aX@@7aN7lbsYn#d>Va{<}$FM**7*J3&c~9X`6=5}1(CFqy@^#x(I{1)(9k16o3c15|yjwfY(_~xS``LV1k zC?>r`L+Yfy$w4VUat*g$p=GuVEj67^k&Z%(_OCZQ`sbNmHTC1~%B* zk!-GR*r-N(%qI;Ey7T!Y9sd;x78c&vfE6^&JmHG^C;QNNLoeNhrLTuG}}6eNC}^4T#L)3PONWm}W&Ort^>AqWtvE z)2{2r=-Qc`Hmgd5dwwB&QBO`f3a*P3fZ+0S#_PcTaP#_ z_^$fQvw!v3xVg>v2NV3=kNABGIMR2wm5vR-wdq#4W8Oiv$s2b+yl4pk=)G%fyuiS0 z^&NEAVDU2_&(tLKI;p*F#eH@2 zjPQL!2b=1}D~Ke08?r`Dqa&-^AqzREX>3s8LbniO&v zz*glC0mbYtM?I}+|2%Y0Zo8a8$-hQ5X&LocSy(9cj&u6sKiWpP{%Ov_^CYJMYA|d` zm#pRawDmyRoIT&#w+gz}6a`fZQ=0#Sbnf@|o@JZ6(P8241EQedTn8i7JFbBrI z98?ZiU z(g*ARR(XE?1g$VLLe~vDR6n7A`26?C2v^~R`Kt}%dtRHbmba3o^|0pPQiP$G4!v1e zny=y)R!!R{k)!QV>rIFQ9Fu>9zu$6A3pnefZ3!$cAULLhAG`BrkEl3BS4-gsXAg^! zhx6#u5K(C1KS7-6Qya&MrFX^dyMx}0E$ztj2zQ$+=?Ewg+$)fo?tn?>p*V-qq()H} z%U`Hgd7Rti!E`p?6;tc0lao2V_4ux&tROr?U_qm%Qaa>^rkZ)r1-XB+Rixz(-|4A7 zi*JoO`??zR7)rFM!1XO`ppa5h%wY+^TW1|`Bgy!u0RKca>`ME0@5D80i*SIo03A;% zNZ_RUSxXje14*DN{`JjgAB@$vbTR{h>t6<5Ggsdj1LTvuvP_($lZ5|j9@9M?eV2Jn z@Q+6cF~SZ(vXOY5USFgq-El|0MGmMzi1ZqFXjhZZD@THq+U`)*+EqJ1La?jy@3`Cu zOK~UBu58jiZ9+1`Ej>&S*Jj)_UP$3!wjdUc#%Mo=%(Yrh6`(E90frUKXoXwoZZP^W zQ?h>;Y_ua$MZK-57@m|`Tfx8n<2|xvmfoSunLdv*#-%ha^t}_URREpy$q^|6XDjbA zK4Hn@{c#=ZwOF{LFg4h-Z_N!3<|EkO`Qh$IGvBAz4*aJpQGpyWW=rxGwLySa!;k0f z2;p=kq#k+i6E+Gm#5@b)!UUeLHIPr?FEa%W8y|^8pXkKB?q-~A{3P-cd!nb2Nnfua zdGWh)9KEo$Ek2$6E|aORr-w?74roE&Y6r7Q)N8YgW2j~?v>9-oBiDw!s&FoR%g;v7 zUiYCUN_l7Z+H_UvtMl8^lvOB@0H<}c*dH$5A^USiLpswC)^MEfg8m-P3!&MFIyOPQ zapu{s06I#Jow_)xC}<%nVRi2q?*z-%c=d^0YA)KHmPGd}j#Q#O;|p&+g#j(Kajr__ zb54vU2VqmA${2EBX>jk@x|rfBmW{%C%ZC78IKW%1$9@OtZ|urT6|yZA8SKEs;NF{I zpPeiYt_`#X%H2nFl+KMOhoUU6J5tfjvgOdz0@i)VJkk@7Cp<9}J|fLk(cTU)_fO(qq%@e1Zvfz;P};6oSwC==E?1RlWq& zw>KSFjdf`JI)i30dSS;}48ZK(eVVDf$6cXjQ|cHZx2r*^g*jQ&Q65|$1iZQPB?Eejs)Ph7i9xjU5-MMmaZB2^wSH=a;ioFT-=5bi^lOdzi{N!>D&>AZ z;gv`?XxsFL49?yFm6+Wb8dg$g2WID`mZjW(wPnF&6k8u8L-= z`dcJ?iLM4eoUL-!0&DS9KU8Z8Aw2|t4_$i@Zmg7~C($#Rs6($Ic+-{Xu<84}R)QxL z))v39lh(U~bp?mdu1t}4TZ6pdRbJJpLEheLz{VcXKxk1?tj!ixPMMq-(!hvlbjQs9 zff+!dWPIw0u_>#TX;DVxCQUWmaA-o6hSR=GlDit0)#YB?*)V&rEl~FWPu$(B5Y;uc z8}zYbNw&^Z^Pw^og@Dr*p=m6v~!{Mc@ACoZ4@GBL9vvc0~N zNqXky=);e4I@07v1nP*$(g_h|`(0svR325NsCjWieZuon4!!?Wud)9UHPdQnbNY$?ul6FA@wMHI##9sFcANlh>w z7e2VP+BW>|*I}#KVHMsb8e@go2gJLEpa6K3V z#DatAkJFQT(8&X1&P6UZ2d;W(CINHMLN?fGTzMV^qgmwcVBu>tr7e^?s5V%rg|&S1 z@_cLtBmRkBM&MAo66}nb)w0q_%hfv+v9}oUzSMkwL_DCsSy~RkeWHNtZ)x%{Po(F* zYiZbvS-;T^x{|eXL;4CoXNvR-7wH#t5(c$&!y|HskrWg@&Pt;5er*qV>o`kbY=(&vn4#xAWo$+`5Hb|8eCC*&LpeFPk!kDN(xloQ;@llQARfY;;>#e38wuO?1v^%&l~k(1cfP6Eg< z?=OsLilBST4utp9V|5yN<4@k!Q%BJJhy%4CBE1v0pmzV}r zf{-d*fz2g}n*QY`dIsZK!mar*3UJYf0B<739~Xe+GZ^lNby)K3r=K=!)PzN5;F&xgmZ#1a^|q}wy4^pi_0 zURGOnNZ)N3!l6EYI%g7nj~q--A{tQ(=gPw%hX0ecTPiS3y8D4mOWWgsRoiWOxdigE zH1p(3GzKO`M3`so1B;cgS6YfF=&yetceVD62%oiN4$b7t%o#)s4P#m6d6k( zyF<4V@h$tzH0Yi0N+I9>Gc_yX4s*U-+uM&Olr2}5kmfe6xo>X{KhLrd@c0yVstU?W zf_HvbA0u6}Glr;u`g-IpGddC{0;U9luC&hVDs)G9$-efgL*B!0B~a&;18MVv$$Irs zjj{sr7DBq<1C)hc&f$X^Sn03r_mSCXn>j2ZsC%k!#+AmOZfm@!od)qrC}D*rhUVax zSG7_@p|bsE%3n574s^Oz>!z}%cm;ONtEO7Vab?0 zFww-<#1Jnyb;s_#;m-@>5sPhU45CuCX_}!TJ#eQ9y4?7;gT$xYKB}rM!MYc!MRBtf z4w5q62R2!*sfrSk)?AuU#&~jZ2l-@dsJ)WcD7Tgfit$E{?YoO75>2M(j-~D0yun*?t$KPC7@KkS?I*|A z+-bDotzXO}&WoTXRPVt3aQ$%@(vPbU=SI8sz_q62Jw>VxJuQ{w3=-krOaYgo=<`wH zNsoWv`IiUg&DwSTF0$@gvrDc=iMLu8=@cy1e;Cxd7=4iM475!@5-@91N8tp@}e4g*$%_r z0ilk0vsvR*Oug-GvAsGOp=^jcD%sL{$@XWp#1C16=T1{B-9_@dUZ^NJW$(g^!coU@ zQ==GG*Um*oTI?E_gR@&_lhFW;iyuEtvx1;ZW2M?91Dwa=ROZnsK8&RZAuGutQNV zeJF_->yTz!6IX+*=ID|4?AsVKN)P^E%6Q}ZBi+)6FVt8Fvtd6oHP+S4d3L2pje%%9 z#5#~H56m1+qvCy3ic3*9QK?CzGR2c(4+1I{ymVPb%tD1EC~(WV17)~wQ6;~mYNNk3 zly1+MHrzf^DHOa^udB3zHV_e1ECH7U9~VM4pZ|`~=SA2^N1k_(B?l>$#Xbst7W-=2 zfO4lkY-klq8LNU!GSpd4_;=m{p+`KiH-iA;uXXIZVR%wTG(g? zy(iN8dOhC>m4r&reZ1D%?=+q);Cc#!`}fxTGmFhZ zCI^^bLg9UpOoaar*Tj8d+Nl9~w3M3DgUhfnB;x0IsKU+(TpsolSy^W2G!rTX4lPqv zft$hCmmOsJph(ia&*L2(3W?*gx3lbsL!z6o)j{+f)Tmw>NPi~kyW}{RObHc68tAH@ zqA3C#;kq(%V!VW5Y7@W4lxkX}hCo{IvJS0e#edkBhQCZKe6K2X(Lgk}=mOLjmQp9$oR~^^y z)G}HHzfM*n-f*w16zLw{jcd4c`e}Bpd=)<~I=VNM<+^1BlsE~&Jb5t^)OV&HTk(B# z5jGMQOu%1pLpBGSIg>1*zV)Qt4>c?Pyq9WTa1nU*vo!X&9dp9PA-;%0=cjK*?vau7 zo(*X=(Rl41yEzDY&XjL%(;$@|CKJ5g+3zO%TKM;RE>2HmQ=)7Bhd;gUhyIguh4pYiwjU%j*QmrqKt3k%1>+Vvl=E499#R5@ zFx`Ns4&tzO#f|@LrmG1KbpjcDa#kiQ5Mhet0-TLlYxFp*9FlK2BwahmgZ!J}A>e}z zp`K$6U-@i*=R9DDvpfC=SR|#^yMkP;P-V}(15xZ8{D||vAI?)eWOxeHB|gy7S2@f#I(Z;aM7L{Fhy9*W|0~ zG@#CTO^%4bp|itbyeSd_>^2rr47QaV{(O+q98SHXSQlN66#w@sQ0KE28EG}sCo#Yh z-ezd0RJj_v+7FT@`P++<{JwihA#)1FTfm>t4YsAWWJ*gRYx-4>WXrsDo*xD}<=fN9 zJX#2~xp4cruLTCc`m3tr@oSdPUM=cBOrx|0KjpJj#y3j2@q32>e~ z-a!|)3JR~?Gd)SYiONwD+9-Uq(yoDv{7eZN`Cx%gn&z;a6gMU>nLye@iirqhs%IZmYlkqhb0nM}ps zD^D^b5O?TdMB{Y;5Eu9<@N5OEA{2~E&HKYF8|l(mF=cbZH9L|V*b$>NI`n;Y3wLWveveL%VO%L@MXA>LlZcn!qCs*20Q z^Z=xsC-lyUcOt%Qu-H9;(Ro`U*bRnXE9&_*LgDL8RD#=O4B^)Ay3n_E2r#qCYa){5 zjoB^KOS-vn7s@}4ISmZ>3x}%8wFMZ$u=>XF^abwU-f+DwH~Qa16b%Q%B!5-g7WT`E zDBk1M&9X9H==;e@$(OcKaW&w;X$pyNdvVr}OWfxtR!#gL{s9vM-9*I;tBC&V=)peA zw>an4vk-xgM14acp{GutR<{uK^ac=bw3Xr%<4wy*9;Pm0PkK zZPF!fL^T$gTzx-J|xcqNdR{N@6~;sn>jhP*|VEtYrZP=i+5 zjn(Zu^0N4hQ+3c+>OaHgX;}5BpWQ0;6HY(PB5-k0f`TqVvIt|Q!M1vp?~d)G2R&mi zM+%PD>TVDltfUd@{7sa7zK3_L{R#oauZ>GP;G`CG9TqmC&2*ENmuhWwa!Ik!hC)*h z%Y+_R55Evq7B3@MHxpp0o3400sTgMHcnLaAE8QRWq6OUPArT=K2pNkBsl1oAxK*2N z+i8?tJnvY21(l;eum1u%sx6O)b52ZXeObxLa)AlXfm99&1np|&DMJ?|p0>GYfNJ5O z&$;H;dH7}7TWbcxlwGETvPpy8p+DGAs(VX$0<;8()67-5{)-L}=PVtNaCFF&4}7=A zPd_&2lhV$C;sZR=Ch%dGsTJMguSVyu!miMGsZXtYPY%-|m18>4ZrITPa8XRm4X=7zHoY^F7xh{1 z5}v2(Y9cP9#<6AnOY^VKqDIj262>R8rH&i$t*xcT+LY`@zU{RU$Z{D!#!l?!U$ZJl zuiVY6a!!EctJxTrp?Rpb^7L+ zTm1CyG9hy(d*CWJO!6gveUtAsTo zpZ^K;cO>v)APJBBaLuMPkUP0MrP$C5l{Nw|`U_=j!p*S^NZfZ1b8oWn4lX{S&I!W* z=aj##`>x;Q!u3DaZ{M$px6cP=70bN*)?NTE=s2`^{~rrr3IBcPwk%?M^+2d>M$TA3 z%TF3aj@X+0X&l5LJU*JYUbO682K@&5+ui~OJsH%VZD%qno%8W|El~1{&`slK;O$c5 z4r!T*cEyZ^XUT`b#fFd7YeW>LyAny?;C|m4!S4Nrm!r%d1Xt~Rdh-)Ab>B%o#`NJQ z_Iv-H!r2$C$Z;ri@<@+!=JhX)bL8e~ZJ3U_aNyRhVJ^2^{-D@Mrgv? zt^35Av`UjUOeKci^Qc&@mcuqaY* z{f+9;tqn>lUvjnG9v!BOEb>EQz71wYhH9RkeNG*bWzuvYqR{HV)>|V&6Cw0SpHuSZ zo9OQWJ%8Yvv0s11a!bX(&@2C;_j*L5E;aUv7fA{hwEQJ(^epwHw;&tNi%tYu8Qy*xFxsAa?zWzt8+XOlL!>wC) z1=s!ZU{4Rsc(GdnN5l4yO+O*A z8eisi-XOaB0+eSOBh>nxc&!iX_kDbrSb7-cH5^>ljWO1z%v3o&Y%@pnO=akl0YVgG zEyScVf(AR-AyD|ndm7O(C2H4)xY$r!P<7M>WEYV7EfP!DkF}gd$bRcC7 z>e3ngAylB{tisu8&>p;bq)H$@BUN%rJrB@j5+tB-pJ?F1oCzgJLh?=wmTW}5vOsca z!GuC*p?wy2fv23e_)m_KSd=<3K#EH~qicg@l&Bcb+B~{;RsMZI4}a)b2Y=_?k!WWp zPYupyF;J+}1#b@7vxLglUEf4$e9|Rh2A|Bjn1&ZMrTG(Z=#N0Ri{%zrIb(4*oqA{U5300j(pUx0d8d zdxK-0x+s*i!P@9^BE}K4bRg&Wo&gTETp>Fk1s>y{VDW0bG~yj}jvXuZ@Ff6WomFn& zD}#0W#O)~dhvR}1?!zHGP{kE|-FWG`2eF4!#B$?Q8EWZqV#psNXv zUpTp3>EnvsVYNeYy#`&s^m{AY(rJ0ss|{-t)%cmnWj5nBWqh^J?Z;f4&(&K&MNsN= zC99=h98cpy_qV?7`j9>B`!)9d(=L2Qy}hqTJ$fAx)jTEk@4Y~8s5ZS3uaGW>E&30U zhdCqiV2JbYuXFTj1G`=p1Vzk#;Odj5=hTDGq7U*;Ag@UrIgt?sF?DUlb)&R3ZkIk3zve-i z@LObtG4%Kk|8k)JAIdax3%co4r7U=+Rwr@j#cfIg2`;#%c#*l30zAau|w z7fOwyG~KY|?IqkokYdWra6(YxpBL!<4e_U5M90{&r!4FZa}$PXruSW6z?l@+ttB*= znSIeO*+8sRVf-a4BPP9Bxs|vF>F22&!y00?*iXO5JlU+%NS-DnGyW-PbQl^2u&-C# z@7YHAAwA#u`_a1u!JS>+P0A$W+)gE*T-lvi#9C_hJlX}qh=*dBCL;3Y1T_UNV(2#A zEUA=}M_7&Lee>%R6;KR4Sc==;4e&%#bOg=5+=+*+WyaNqnzK0!oa?6T$AFnlC}-;g zBb+CHJsKGBml+kt2AgMOK^H+3Wauql<>mfDEwbOD+~R>%gDZ5Ye!P6_d4`D&$8_oY zX)S_Syl^WXDWLMNKMB64b20pc1m2n@?79|Ss{iM9c7?6Mm%>Hw{vmrD3Ago>0G1G( z&4UKL`OO~MkXZ-DLUWA&c@ot<-A&_>NE-~)?i0G7Y#bS)1cbi@RN>+k^9qkMAqY_q z#ruy{Uz-C6UjMSysiy3$0bi~5#|)kgMjMhC8ppWjaQ8{D5Dc=J@EzNAu%FFO-cEKv zLy=5~OG%qr1|4Q+cV<4W4m7^V20{ly9SU$SKk5(UPtCZp=svE5BrVHY2!nZ9gJ_fP z-ttoe=Iu~vrAE*S+jCr#fW;W@x|0twr6Br)Y|UdzQq3U@x*DaXQ(fgO{3IO#9wv-t z4JjZWh%i(u`3CA^h%)|GAS z(GaLnr5BU8z=7L`ed6NLR!*W38=-R`)({J?wJW{$;--7rT)H#(`Ke2tag!hWZ=P z1n*jK9>u^Rd1?QVM0(%zb;Nq)dfSp1PCM(G_?77j)zcruF3_rln+LY(bWzhPI|g-G z>C=UqEdY%w`My#qZRA|%h7S968YJyQQ&^4`yelB4Fz4X zY9eJG8y{W1MNwe*1ZLlVXjxCNKspK=WG`pv{>n|FyMlB5pa0nyi0Vz-q`Zz*Gbiak zFj3ddO4wAdS=MwIlW8JSlEvCK)jP+?c)bp=Ug;pgL~f{-A0PJv1oyry9dDg@GFc5k zA`sexEE0yM-Ro?*$+h&eoiAxZ;jvY-14#BD>d-J%*@gHPs9gR7qz#-Nh$)}b5KA9^ zB@A*@hXuo>rJ+r*~5eSG%NI zN0_8v{y|>QZ#&{H9DCYa3^AHjs^6`e#!=35*A}+EO=vAb`oU|x=k@v-n)GCTl=?3` zug`;$mn;GcNkC|q_)Z=h52i|ze~Zvd*TVIBfv{V7yh{9}8?{b%?9C1%Uh>sNMF`Re zK-R!S{a6W707`?W;NUPnD0kpNuhEsajOIkF?zS-9=AeuO{+w!Lhi#oG`j z!|Cl1>ui`Y`$uOF-==%@Z;I-5^PN@KpBZiDZF)Ls6PyBm7;$OQC$gzc|3@i)f8jsM z%zz#l%=jbsz2CD|nTXSH{w=hLQ+g8kVx{wNa5b>GXTGY^&%RAqO(C?c3HqAA0lIkf zzZiiMQBm&r`FQ^rVqbS4AgJgpFrbiXJNjq2nxsF1=NK8T*SXK-_sUhisc6nq)plQ% zo;6vnC@OqY<=Ok6=53J&>3}9V=Q?;O7yfIb{E_0ZJY&OW*Iok%Tco79{`CVtP>cix zOl7sQYTip;nAsI>;Ds7I8EUN^8CBiB{0BKFG%V$rmM;y zJMf_Y((M?R%>Cc&F5u(kZC{}3gZ4_w(FGp(!y1u1^-ySwVe6S7yrZro!3rSAi~{E4 z9<D^+aNn?z_4O!u5usY=#D06r$qn8?g#<55sRwj%))97$%#ZPtatBSy1FE)%FV znpNmF)6Mcx2~d_%)VK$lLk7*uJTgD7Lp%N{Yq8IHMfT9W$OfZwSt;%O6(DFh{kd?~ zjq6%1<+hXVnr(JlA}?YHSn4_xkOsKIY(7F@RbW)JsJs{XXyqB%djuR=@4`5HVA{IX#I z?Y|OwtN(_EYtVbb0&dNpWKA6V0)Eg_^vHipuY~X2i%;?1?`InbfbE^3pQZTD$OcVz zp9BKh*KVc8#eK&lR#^JGxQdtol&?sisSEBDtRPp=Gq9Gw9-59hhwT#1TcqyM>itV7 z|N2~o4y`sH^cc-{iNe0|do!rHr+AJu#hB=)pvdN+U>-R|0z?T%1cI1%$mP70cbo8+ zn3G3i(j$kGBaB%;Ue`4_44>^5T9vthr!NrX3AMO~ObEw})wiXWx~cv0kj`#x&+CW+ zK74y-!BxDSeyB^kYXV>7TXBWCLV+Az+jDiSRlelI?L#>%<$w1rlg9Ik0}v&+t)AL$ zNCkp4vz;Yrb)%NrI5aoh9;6ijj;4=JJF|rnJC89Ka3iHix_pKvB`ll&9a9oElYX5z zRq8nc!mIIkQpA6+eDu`ot~0JY4<%L2Ym$Un)PVIDaE!-DH-=fNOD? zkRG^{WwJE(yWrr!n6SD+CNdaI+X2%G`XowJ87nk$Ua^JwkdBpMtrk0;n7L?Bf%0sTwqf$^vVfJHpIE$7EGpsg;`dj?8{vXLS1!0>D)q) zv%;!L*wMU23NEEG4xg>=K#|FPI%)O9nX9AI<()M&SVUU-6Bdo=)G^B~kcK}SjU_Et zsv3#_*9N-?g(cD2{Mp#Bxv-sn48t z(fYL&qsBoC69)-Kx;S!CffgMXd9Ia(5+<8mSPnXjw}B14*ju+1_=)T@)zh?sXonA; zcD=*t6adS7;esv!lXnl07-wP<_4zsrJqV;vi-XS}P9?azlO$zk3YtAgLAD z0psO1oGO_=bh}I|T!j>Fx$+y|{yP=h^{a=isEwMl>Uu@Eq5ca@VT9yaXzEVn z_}4IySl`v$2jF%XeWIuG3==wqSw>!MB-2XWx!~R3Uq&#o5>Sl7S_VEZi9pKZ^cJ_A zC)@Ab{)VhZoT=mMIlN0$YmDtZh5OQqZd9yGGi|IdIyjDodIq+^cv3cfNEwgJ<)l7L z)6DHt`)HF zZukhjRpm;JZ`9-+`w&y&1~@-_&}hEd4~nCWmVklD@!g5obsks6^Z49 zFChF2W&FLN%n*dpXZt%VRy6+6nrl+h81iT@g|I*P# zsWPA2ibc=WCLk9`O`K2XGx1D2@Wx#Le@F`B;u4)I2T@1zyFn%0ZO&i&F6mW5ZeKo$`HfP=o|YGoqCe-m_QbN`Bcy zb&fw>K|asmRi#chczu7MhRs?#y@yRN2;)rxY^2s+iE*)9zj3k?#U3;F9uLzsg$|Z* zt{9t5%-L}?lK4Jq_VZPibtXDZkv^S6Hb%p&ZZ|J=M|TzLyareKn*hxnUC-J_kGFB) zaO{OHWvGDR$qyAcnAaJGm3DlD(NB*^s%jH=&vUb z5Uzfp)}}?~^~Sd(5MuI=b0qJ2j)htJ*7uH9Fbuhe$d5_8k1s`RiAa3^>SR-c9l0sd zkb`rM7a+KQ7Q((3p_ER*c=*pV1|{!1Xs2C!P!1??HPATsO|=8QD=kD5cJo%Zdv=*y z)>05Eg6^3j{Sm2O8vEst;(clj>Sf2j>3RO={R|`?dvW+ZnYsDx_HU?(>x6WxAt`+; zAZ=G06~#asl$%iOA!gcS7^CYmYx6rG=q6VxfiPCrC#mtAa5v?O$2JQn3p=OQVN=|! zMrBR-!;UoBsqWP})YJA4Hm{*Q`40U@XW0#vG5%-4ZPt&o89idGr*&{})R%!!-Q&;s za1W^it8W6*=`V-)D5*ZVwIw{Ll8Ta3k@$vC=dtI70u@zR>%EyR4oxgg)bNTI#!Yh5 z`p0+kv<4JnNm#kk!kknPbsQA?f%s5KyPP9L>c7mCj_%IqaR>TU%w#G5nF1G6=-l-* z69GjJ#yRV6RR3%6z%Q#5;;>W?P}_l-#=Gdb+uKx;Y=B$jA`R-O+V7KMd8(Xl=(e=S zpT?SFwlG`gr*wG3^j1a=n7a!Yz z0e@T{OOI(o*|}eVYJ(+-pJDQoSAa?@<;d#rkMWi|=IaK2j2Cp~2B(0&rRw}&c{f%# zhqGU*hK`7Fa4tw3yqe1H3umsv>)2~@6k_#7T^5AJN)U2Ho zhdgkFubOHSe6UFQ&qL}Ej zjuh6)@9un_u*)4<)V`lV3H};o>5~ecNZ#WX^sL={Eod$!1Uoww_^z5>D!QCvxaq2< zCNN*zwie?qmA(M&DLS|plbXJb_B`vGrx%mA|Kl|baHRjsViWjuQ-1SK+?fGZ#vJIcr$W?j>fy&o4%O1vG@I> zfC*z?l?5>ag>~_$g4oM+W(*(jt zLTYc%lsptId-A`2kG&WN%YEv`^2R zNANI4+mv!6^90@RoVO58$LwA&)fs*^w~}3LG(Ot4DTEGbsUJU%`fL%a&|Ym8t)M@= z*{q~y_Dg)3X|#?xM0^E$c-37Q)vC7{slW4SHD#B>F>+HE7J0fY(0`6nMEUT{RWZCq z2$Aq}qNHo_IQ9vwtglz6ODXmavmj(n9@4M!ZI?k!E~|XCZxP#a%xdy5UO!LCMC#xW@egmu{m3JznZHMP3 zVoORl^?uUtXgPJ~dzX%Ko{Uw0!nhJe)?F)z>FG2?FzNoV8 z%{H|C@zR?$E|Z8)s(sPd)eQ6blhKiqE#xjEJm}LD@C4Ejyq%dt8=4vF69N2-CLScJ zBn+uYrewTY#-M8^RK*FftU}^||x@_Q)H)WbLVNJE-vOz{5{-ixG8-b$Y zbFHr`;3eI34l0De8Ctn;2@#GGdaO^#UpM zYyB!wT~vaD{69fz-%N|(ZR^iLS-`eXFQ_Md5f_JH;=b6QqRI~h_{rLLE`?lEqzOg1 z)vx~KPOG7ST+b3D#32(;0H7lPu9ACnwwW!;G0l^AynP~`HmKfdo+W(x31^l%Do9>( zA*ezEVsUS0tR#MYpnZ!>OiJB{$))M*iS&Fv<;pT3NWj+F;BABLWCXooT`P@cTx)O=do}iOW7iC*&e8FZ9~&fCR?6D;4MEmcjaY!L1F6H^S# zE8v9+Iav$YsdjXQ&MU@R1x%w`>Q*}-C>}B8V|LAjzRUInU`jCrmL|3>lXk6zzT5T% z+y^q?+mrr&*<}4Y!dw;01~;A}gr3Q;E0s79F_kj%?vJ>AlxvXwNSW3Vf(`~+BsBfSzNi*ZE zOnG(K+J?B-R-#>-?A}b?sp({+^k|uOPe|Q)&W{Xw=m*yOM^6U=@OGQIDG^H{;-yxp z-%syk=SDw7kYhON5loP&y2WN}99^3J^oPSsGn4+iKlq&JtoQOAlxaT^X z#2f{j*QG~_Ws8iyP1l5=jpHsf2uczc{X5 zY0ypzw~l*X{|N=_Al?n+LtimtHl!`5&p~;>`U$cvJZ(C;EQC4Ud(9Vh#C^`g@S1_* z{oHm;Ts0=$&T;!j!1r&@(V|F7YhTqHwU?Jo@|0)d&stl}7yDyFH;-UuJqJ&3@4h3Y z%kU!a#vFM%G|KZL&(dX8zHDd{*AOnZ0W*Jy|38|}JDkn$|Nq(=MNyktHHzA+cI}|8 z+19Fvnu%H^R?MPi%u;*PYE|tmcq?M>)*iJIn}|JscR%0j_lJwih}ZVZxehdeIKY1d4JGsmY|4!aN{dl>1P?E zi5%PeEQ}jXF-)(1Lh?hiij+xoY(SDreFh{QM)~1~kM_iDK77F3N^YV`O ztIZ50L&uni!qZaN5SQu9=*%t(WU;kVX>#RUyr`2WBYM)bH6v(`XHu7VTR&)?YA7|i zTSoAnbuDHLKGgaya7IyY=a{P8ActWzi&7>f)u}2I5~{ORS2;~Q?KFH|>iJ;pJmW%+ zt&-W5fe3ri)j)U~9X6CI=#=EbbfP26w8csyY z8ISm#Ia6^F?$#hNhXglQ!nA`}-e<*r^^us(hl`6iRSmqk*3}8KC;UR`%Z!^y=s4=h zB)Fw|CRv!0;CRe%u5BxK{~R9lFGq{3?wL)WY)F z0Eu5rg&OiWZvFE!hpw6|hAhSnI2;SJ`mp$)=+VZcovfRb{k>2&`_zLPCn#^A--#FG zztR~v3X?YgHBKc7a6T>kpV~pq6)?6;hFr&>ChZF5meRMtidzvTYX#o8j43o89I6La0N z=KjaZub8`uJ^63%IS&HS*5lXX(EgIbhV7)pT`gBnx^ZND zf%o~nIwLJNVwFavov{t8V%H}`CJIiXp`umL^l@E=!>C<_d>*6sQnB~D!maFWh)&5d ziW*uB5zCDIpX`00pCvB|;iJptmP$=dBP|SvGPB)iF-Am&hP&~{*RKTmV?m5bY35C@ z>iwH#AGGy6Xxkg2hmM~s=ZwnCT+t^7X2z^Iwyqf%|9%U3e%w@Sv3eg~z|xJ+t2Z05 z#IQ0;*s7ZukqZ_4xO24QbxTva=Rq~sC#kN_k!r6ipY6N=9-!}LDh*U(Tg2@9U&uAx zBHki{OLgqG2_zvvI%bmb7=dXuB-gK(9YkO<{GP2%fJ~%IkKCd#1mICtg7e|)`;F{c zJd4Wv(fEAq<8nvIj$OZUSnK7c48hwJSm4i*(^g+|JooKmF4~syILRxYo20beCvHDQ z()5qnIx>I>ErgWe?I1VHnL{P1*^jcSm_%W0WBF+KfXP{^yC#8hB1QU> zO6oK8FEb9)(3iu8)IZt=*t+op&&4Bk4Y(KSI}Vj37`x{zPP6K?aR3zA?xAm^kgO|J z>?h3M&l(}lT-yB`C3j(e`@>hC3?2~NRguiE{QGCKo5Bml6{V$^=3Lm2#{R>Y?A<-> ztQ`HfC&*IV#V#2C?uui0Jrj50zAFJcne09d_ZiZ{3zN_eZv2crDt*eTG{JN4=T>~| zXE((?`H^&3+30$J&98d#9B&ZZH-bpw_q05-!kIZMG+L~D#gH)H;zDO{3 zJr-vd_RJ&mWn7F5;ja{iq`~yOqL`s}wXEW4@O)+S`&=55qgmdpF|bjvEvt@#ZPWm# zU#F15-Zv7%tC%|r1#$^x+6g=tC8fF;AJlyiel#WWv+*eFhx?h2X*@S@gvXcvyVu7?yOm6(t|7|1^D-paLcGp`*Gj zwq?6!(&WZ+cSd~bY2ofo`7xX08#j)c$bIzMsu$PvvRN`HHkdwpOStJu>MwmAC`OCM z4C4?3&7a*2P?j`5q!Vru=bUEgr}4-UN(nPjM4EJ-(AW#rm~Y-T4v<4=^?2MCJnvn8 zi|MPT43TNhS}XJ;ZQiMg-bZgJp0LR3d~oT?w9K*PRhr-GT|bUoEnRnL=1<|#aGz-V zI=opROWWSEm;P|~D)+i6-f@BZ6NzVR1gG%X&d&bA!?#25l@7(8lyeFs$!2$faNPxS z%VYM$&Oz-H+ql#~GsbEcUCnRljsdBMXk8ZH=0ArsZWl@gZ_Yg8%~f7sfW_PvW*34^ z+fs-!Qb@YKGmkV2ja)5HGMXEE6@Gv=D;5}`nD#IhxU7gskv`9%Wu`Xmt#h%q@)h4uD)+(G6 zU^A0s`o4>5ay}c)QR2Um%lphf`(M&+WYCb-Zc|rR+uNXoE@>SF5`wgbPw>V5=#tms zh75Dvj{?eO{gzkID70XJ!Dj(IoosLAexvw11l!k!hvqLvl5Q-_ms2b={TEa9#+jAb zlc;C7S-yB7_qux@xIGTm>)kDc-4#3{!f@mPy9epwdwU+KVL1GduU&aeR4;3)n}nPT zw{0N>T!N%(6g?F+t?cCE8gKW5#3Mco2j4j{H@qO2-x^5Wtu;Wo5M$P|F4DbBh|saH6ngR~fHRUejLaa8o0*FzW;X;{LNdyOs%DUm)9K@t5|>iz@hZo(G!NFX zos|9y1Z#JpOV?#5bF;N4F>R7uTJGxHFnSQ}%VqBL?`xBsf!b@d^6{ZnCWW0H1?CHD zk2DMB%j)FCsY7v47f4b}RQ_rd)b2|-wjPl^3YFhkt z`q*uflQtF3q&$rs3f-=-g53Ad_Lqz3$j$xrVh>MS-1iynsnpW{>$G>>28|A$^hvOg z9>80pjlch?a97s_v_o1$)}5B_U#EnNJJX7}q4EYt^YH~Wk4xHOqWa|$=9lY8_xuSy zW(=Qd4OQXUEg_L~4I8(}S2zyLPi)I6@L)w7eru%_KA%03r~H;1={Js?KHK{|f%umv ziVlmUmy_{61J!ufV%w>3#Mi5n)^lwlS60usJ2!(jZ_t9n;cZc0UCOMN$ImXL1XsWo zCS6m^2n+f6o%GK7#Wxu}sGS@`f2+0Od`noHdI``>|G?hJfKxBxtFKMc*u&}bw4uX? zVkzLO2Yp>PU%m$zgQd7_M0(z_pwB!O<%UgVBl!vX$eTJst|6C<)(c#PsA#wIp$MBe zIe3TP(mb@OI|R`vlekWwqN-#GXUd_VqhWjgqJNrQh2XyZ6$1noqwTuaP|u${eyW(mYA@NF1xdWd8{LgUDswSXIzn zWK4EjsP;cKVS1R{hsdrM15;4qDgHADzGX%RH3{=4tb>0aT{H5;? z8!C=9Ww#%=>^!J&9@L^CQtDNC`n71#zoq{%>OTjh_RzJ9R#rfNLhe_t409(YzKnXd zwqXVu+n#Ws{8)A@)01wn8UIx)2xRqL7hu2n{P7aLA!E(-&hA*|X6wsq0T20<0 zW|lAb^zCj6p>28W@*4BTMY?!q4OtI) zY=z7NN_JEZ4(P?J3q6|nRl{ISpjQmkA?%sW{`|X109Rc zZga+D83lJLEqC4zZzJ*J=3^39qwnZ9{GR!0#xr6fU(HR|ZkgFMBUa|cDCZxh@e$3t zJXuTUqj2^10qglFw}S!XM{kufH1~9t75)-zr$%s*5T+@L5Qf}!FxmIx7;-S!UQ0@^iH}yiiUVqAP z2whu<*O2R^3fKk4Dr_qA1v!OpZrA~i-R0u()3$(e%SGr$ltNokHz%2`^ZYYk>45&iSVBP!Ub1o+d(A1AU`6kprVcsw1DZiI>XC+J zn@cbT)%n*8q})N*ZyTl*jN!`ViXN6&@)a4)np8~xF(;Vf2ZE1=fu=9b5??h{K*94B9Sn@s3YO?1T#^_QIV z_Nz%Gd#;tuf_SDSO6Y0hH@`vRZP7)$_wgpNL&F>LOWK@4xx1;yEsi?_^gl~tw2pan zdQE4}BxQI<1Um>Wb057hDMoBCGe7&gMb_38a(!_dXv+Bo%i2#LQdRv4$ElvUwxPI8 zKKSzV736#kDL~y%j}Vc^X3CA!iW(c7Ybi~40VBn7Jh6Y;woh+l=hfdoC-bnM=S2Nb ze*C&7WNfiFkwlN`x5ajrwSmMW0#(HMjzn8uSrWsy-L#tRDN?%vZZp-Ma}X(n0gYak zK&%o^OB~aJBAmLwkvBsj(!EY{lr^&ZNVnd%Zi#9B+=_FH)vD6NBk{hs>+IQi!>(QNJ|bGZ9vg^rV`TXwbn z`h=4I^zeETgN*W3 z4f7zzTNXWf@T!?`H%M!ymSNAqKq&Pe&wg%haC2kG*pCeb_VH|nL+=$iuL=}yFD3;y z&xfqO=CFV2o4q*?tU1JZ_YQ^s#w~`jR<}Jxru>rveR;UK$#g+lTa zaTkrW?hxCOVc?2HD0aFmglS#PAYWAIgo^cbdbbti8vdWfW#1A{Zdl3h5&y@nM(06Y zaLhgG2J3Ta7POnvMXqJdE#@k~JefC1JRJ&ZW|IpH+pW)2wtR0{_)y}Sv+Q<(ilSP} zy-2!4yI3u1dQLU3S%Zn+dCJxMfz{`#$5UbppIon?MdXHIeB)f5B*2TOdSm2unU0ht zOAn87oR+p;IUSwue(}BF&3fM|xhsrimA?V2HC7-;unzqcKO99~RfXf%{!}2xro;R4 zqYFc`@~0<*UAmy8I#^1B2E0Iat6fN;_zrKzo%R9&Qw5>hVG-(z&zB5EX9nr(TPD1G z$kY2?-gFl>+6DVrTec#ghrc|9q{DZsz?F06he?c(eAJ}_)npyEW9yQVJHydiewIq` z@5Uo-c0b+>s1Oe-Omp5ebtTS+^1lEIa@vo7g5Pm}EfV>+68lE1T__3I6rV%8RQG#? zpw^Ao{_Voo%ys+4fUiVS0!G?Z)uqEkO78O!(3KC|%_R|~RA#+K2|fS!Q?Z31^@~sb zZEm177Zz7+zVfU43`E>y6PCUli;Hg|ql(TpW6qsylfNYE)RTLroq-WagMLaf19dI# z^9~#zj;wFn6gGXol4j>E>jLVML^nbpq1{0*WmZhd!pFPB&Ml*Vj0%$QL^=j8PTG+J zOQ}%-JcIadc&fZR9kM&0y;iqiN=2XBm9?i6t#?<_mTKv+hu+9AAQQhdl7>?1o$6$|NF z(LWGQVI~2VQ1yDS`Uc0TvtWFHCt&%CFY?pcc~W2y-%$>_Js73bpUU_|a3C#G`mN%?I}nWwG=afXgMNdBVxLrFtY|19Cg zX0Nd@jryp*dsThmZk*RUpIqwZ)Ur|C6M|{pTfRy3%E1a`Zk^vWg0py`zLU%T4bcwoy{$+QZmz8m~y$Zx(wS4lBFlZ^Mk#HK;uTi0OwZrK66PiK97t3>046K{~jwi49Sy7;23()c`RoW^LGAwa=A^A z%pWRLV#l0|N5WmqW^HLsml34}jnZkC+@A5VI=u5?2ICjBGZRE2G*pWuh+R_;c+F@a@>6 ztgESUA8`30in}I^deDrJeBS0s6viq2lWASd(8ElY_`)%2#|c08Pzv|ZomQyWXckTX z$xYu;9QX98*j}LCv%-L#>%P+C4c(lxMX8g^mPLymvC%n}E#SXyIA3=6vfysZR*KAE zJ0Y%)x#b_6sBYG4EcF@@`7$0Kk@dPO^NKa12j+pm=ik8s$$zdZ?dC8YhN~0ZWNOwg z`}llSyu!@)FlUevzfLy39+yV;H9o)2qi!F;;iu<>ANJL9(B_C;eBOy!aF;q@7fBwg z6CMVNU+83j;3_(F&*u^)4b5N$a?B}ySNoAkXA5vpDa0g`{*U|lIr}bPtW>OI2~}Ew zpXt>YpF4{EcsZxA4>BrYl3ZErwTrhi{1=sUmdaF(g}WIp*bT2kmPLqX9((kJC@uK6 z_w=_66@K`ZDhtLG;F=l`O%vwxORBR<8fD9F+|ybYX8zH+f{HM3EDLswruS1<*+95c zm6eX{%Fplg$!LaPr;6QBCl48M|!z&8|KRZE}&q8b<_2mTee7w6^*8NJJgby zX$>1N`?_K!M=V$QKGigJ)hd_d9qM1Q9nCNT;jyA`vm!E}Y4nM=`ABY(r4Nmv&S$O6 zf&!iOmXz0BlH*Ll?x&JK4lRmI+SSxVXN`~ut+ypYEnT%_G;0acXP;7f#Z37O(@siA zS=(g6{gHHr!hqURmw7Xy&ljY2HZ*AGfAVKKJ}dHLX`NLTqxYu+&9+F*=E{&U7WdT? z&uIR3#gc{{zBK%L#LLpgFzuF))I#Y7LkgHKDmw=XOc6@vjrkINA=e95q!*Ov3*+hb z?9Q^O#3*ath0uDr4DzoP^&=^gbp5Rx%vRFk$t?{?T;3JI-)QWDNtNe=FP6nytb8=S z%|us^hQx_)ca9tP#GPLsK@Q={d)Lv?@AFHD0(9mYKTgWB&IQq9dLd;ted?zS>34GK zVsJ4q!dM7(I-3X=arkzvAxg2s;u~H1PPVZI**sS##)Td;s~Yai)V&H>(3|Y-iHt4u zK9>h3yYEAJ$o9={rmcCDqIGhY%89Q!9tx}3WE#+q1ClOA#ytsXax$Bv(w zT}8hzJ#K0r>~Ar{G`vN{9X#~uT70;C1m3w7r_GkSF2WMnzjMMoZLMx*7<&EgR$ugk zffpN%-@92-40q{A5u}?yue1`-+Rah^pWyQ%Xqbjw2$UDW+B3DN^B2>xq@43BG51UN zBav5z!!ZL-vl2NaH@^y?c{{grqreVHk8sdk{;Sy1r|CfN@G=rZP{c5J>n`2J zb%kNDce82ySssk?A>jI!dZv6iL>F{QZiK1?$)Vo-e->b3T1^8kZ~G*wKe+lwgpkR0 zT*lTmJ#b46M4DHWwaomzG~~BmB4&%S%HLT^bPMFlOC3`ZUG$EvVH+On$7TwF=_}d4 zI{o$z&lSRWM-^fBo*S5=W&P~b8n2Dp1Ik^#X+8*YW%sRDC(bOdO!J$&Shz?xk%BIJ zZuu#rtarg&-o>|1r#1pln#m2NNG?+|=d}qQY<0>eMqHOvxA}tLJNdrH=f*6D4A4vy zJ}X ziRlNboPK8~AnnW}9al&JVvcz!f=aJTUfJv!*M<2p3MWAR40%pKUZ*vK|JP3qHN|%rE<8vY6Oj(1{-Xa=O)*~D zF67>fm>woys9e>|ivrz?x=25{!B-m0&(CW&dp>im%)4nNsH)w4UEU_6WI8pemVIB# z>`$$J;c?DO=&8DCUj^lbx}}v z6^;=;1{_v}k=v^qPa9?@Omq`w-UwHMsop#ZV*74xW3(J-t$N{0w4#qK3VdELE`EmB z5;zrA-dE;WlzeA}nP-m);Bk?&iG7zZD72osN)MA<&Cl#|t|}41fFr%nmLu(Nu@=k0 zgP_a)em-|GhBih%T~#%XqMz2yTm|DU-9O}}oe$0y@283m1`*fBt_~rYo29>AyBC|9nt4$yCDRVSoHMamOi7Ym9lj(SPWUn5n6{M5sX1=w^cwOlP5{Z3Z( zHUpfh|H?n`Ps5tax1S2`PiL6rc#Y1P4oJapOK{1r&_|WCgl806cq-JLArfkN9YoU7nWR_UkqS6Q9a~ zZa(8Ij~T>aq9Aw%DUfj|RtcwOYc(VmDPrq@`W$h*wto?jwJ+rRjH;(LXXDQ0MG`S! zgVg61XuzxDZvq8gN)=Oew_PP!DbNlEtZPVdusN5OKjrp%WoUqw)?YI4l)PEgb!NjF zl7}eO`Oz!}`Z=s`bR@_PV#CX7^Kw7q%d&yo#Qs1zVT6L=Fh1K(FX@Gu{klCl=Cvr$ z1kE!K7no%o%gT4zxvir=TZ-IE)@dWm-CyL1e-zX%V6ydH5o z*Yx-B&2E>u6;jp>sfcMnLt<(XK79yVwP+$#;;u7RhHL~?r+UkqVwfF5ciCvFlr+iu-xr5kh z#g1)P=6VIkQJ?GL;DvikUW;sy@A2kRB&(hof?+e4mNbMGvkeNbc6XkYa^N}D{s(@j zNQl@uYjp_|_mSD7gL@Dg9Q4-IgS~H{bBDBHrrmKQ9+{86z=ps-g1aoj%8?&xvGjuo z`FFj(IQ>60(HIrzN?+DrkK(miJtpeYOmDrjz@e_nw*C#iY1jqB>4acLH7s@F#37jeTIkA}y65=qmG}G>`)JmJ zUGVl_1IuV7MCgUQJ4rNzt85G|BFTOTh&$am#$Ci z2G@t_)J~#m+qXywn4{EzX8A0Z1Mbm}**+d~ShQu#!K!I2_Qv|hV}UuvHMiuzLpmu( z0JGFTCS{ZmT0Gx7oSFsReeXf|D^HWAyQ8f8ZdqEM8GOMpdT?hOqA%mq7Pz8)`9Vnu z1_8*V0u{7udlv%uA#>4heY2LTVnTDbER5%Fe-WNuuZppw>-j(dAV24sL?bOJ7w;gu zp7U!v8V5C^ewvzmVlsdU4IrNK<%8>N3T_cOpHfv0zaW>}{K#UkVq7S?bW82)`+ zxTkOR2CD4DVCZkknHKfgWz{HR92k%+@T9^|-eCD>mG}|uj^N1$xL@QLg7|2e+^ohw z<02X3Ek^^Fc27=P+ytnu27TGjGWFOSukG9E`;n8Ec<6ZDHZ!x8m5ayK+U?}eNAma7 zH=6YRSPC@&4xl=O#KClw71of_&v8WPmEZ@$cTim@6VVf;gW!3ML5f-1Yg8f1j{xf< zXnQM3ZH6NB`gO45khg+QQzxQn>Q;jcGSb#@chrC7Unq0d{A_pOG zYvtYgJ2{cBvHEMx=>$^IA8sc|7)LOo!C~eMs+;t6`vu6?m^4cqqSE=Mz=YH}+=s zS1uq(-B&yoVj+eyuc5+zZ$8>cybZng+m+xqkvrbK{Gye<4s2DJC?U~A?`cDi0bvy# zVz5B8ydctD3ol+5l|H`8GZgtiJ5NJmRcL|+98}V!V9;Uxh05MiTMX9>-Ka>sbvB?h z-S&6)4WIO7oKpx;hCOM!D*W=YE0)PMx-D*X|^yXpOJx*idX zE!{mvSMT2!0CnaTsj4`~8jzA9t#SR2QxT2WkghUYTieL?^1OUaK{52j+nC}NUO@s_ zZh79}FefrnGtzkDqt?w4@K9|cQNP2T!uUXk5!-cEsKM_93g-2!vpNr^+4oE)e!tD3 z_5P`IJX3l1&``S|{!kV9<879gPrMclNX>4x9vgCRRxB=xnIq8|I-omM=^E?UXw`|1 z$Z4yOohr-QUHfWCUjCHXzb*T-8-TJ#QLH?_WHDhyU>sV5^8}2n!lXOYjHkpzq85!m z(OL8gu=Eu?ID9qTrBR&lq|V${YA~cxMk`Ck3Z%u{^&CQ^H%>6`@TBo~hnn=1LCQp4 zn|Y*Nc6hp0hWms<@VzN9JwFE!YVhDTM0ivZaJx*a4S9Sn!gwf_~2Fokjl zOQ1Bol1qId^=#4OZ@Qn}@f5$_koKdhD7ttMY4qWTe+iWXT6~@96N@vQ@@Gedo`m?0 zh_CNgab3^6)!%)h+iE`3Y(J)E*}J%l+4*>=M=G2J?FrS1JMoI7IZP6{{oHuEva_lI z|DuO9XY>Q<8W#~hZ=dE1C~|f|8WGtRNTgzyZzPtABPJ%8q#pt=2Nw@_9sp#pY7Om! z-h^zjTiLtyZz1axJb8YpW<__hLG>CA$~x2rhRcy&N!g3+IIBDCze71Z-LNq$w(vk)q)64*5YcKmXLWK zT?SmhU4aKP&rmk7;rs^CUq`d;F?9M(np zV_)K;G1($A^LCzLupx>5TT)RNMP#YH2h}RET-gc3?Hxkna+uy;MUk*biL&M0ZTS-s zIPQ7JFr9QEiVfWifQ5=MF90sPMUg=&(&skljzUOymE`__Q4*X>5+yv9UJqE3H15_r z?(h-hkgvX+Resa=Xb=3g6i(b?3C@j?!K=A<_Ck~pvnUPt&X4v$l4yay8)3k+=(hYf zDx(5!WYYy$5C_fcR5gQzv-UenThDEII@oiq^8%T%it9x80Z=B&hv8wX+9%(eB(|W* zv;jU5)9SN+y5VJE0s%5R!^=PMNuB0*Uu!gfsb4{SOesyoN4W4+{L18d8{%n@Z=}qA z1>ENqH*J}ITHXd2`Uo=2%-|5{seZj2ZHXBj*?m;GjtA7*J=xAU1wyW9s6x0V)KarTG5 zViYf4pSx8o26GX@lzU>OC$*WX^hfp_hIXPip>z1Lphp;={F|3L&H9R-*$G~Nl{5YW zxzDpLdwJ1eQgQGSkJ!mBM8pKFvPxcGB3~t5U_hJSQi|MvD+HI-<>l&QmVk4);9}{zVHB=U(tCh+`S9yS&TNI~G^t z%vah2HQttN`9E@U{zOH6z&`g*T%=1N&5pe4ylL0e#_=q0935 zZ9l`*{;&Wfe}x;$SjNOcb^gWH2@{pl%l7i1ky49iKh@B}86;7q&z?(>5UjW#=y@w^ zC=3q%aMu`9^qMW&Mt;Zepii%Q=31kSq*o<4HBHL~H`zS*)!t13^Hl|ARdqo2y zJFH$Kp4)oYy{THRjAx+1p{NLdt#R#_s*^tdvD$VGu!sXe0yLuksW9y zN`CJm=GX_c24KG@Pp4gET6hO-;&no{?=GYok6!-G_UGV(7I;ssr&!CSkvML@RyG;U zvdUSxsrCZCJ}f2&TkDznb@itA;AkPYWFoibeENYc319uQeIy=^c~Z*Sh)6K-3iZ8F z!batZ8~}loJ9n;Wrm;p%Z<4G9_Co{i{-X?Jv?HKmNyJ_>#KHY+@m~uMScft0*~5Gp zK|6`hlm1;xhw_a!kxcBHY7IC8c9}2ZPTHf4J9yclBzJ$uEdl=QXT>ADG-lZtj~1dU zDo>fRJg&TFg+e9mrP=|x-?^7XM4nGfi4FDE5Au?-RprH#C_f%|HeQ7>EPymXbhJdB zj06;$X1v{T3Fw?Hc;YgOepu=6aZI#ri6&5aFEoWa7Kbxr66=)Q?}y-M8-K&SpQfP9fe z_?MzFR8??Cg-h0%LrQW?7ldiAU)<$?9rdqVa#L!H0bH|*M}X_F*YG&4&+V>+-5FJl{hQy`j+2@!q4*OEW*yf zUL#4js(yvLJyv*+)3C4vP47~Rb zyPIg*qd6;lNlMtJIwBvSsi}avElXg+vuB&}P)H*&t8unl??gtpZPC;Rx0}X+ToK)P#TVTz{YO79#pUQM*KW z#so0tHS`jnz_zvT1MvUboSik^p`;e+7@5K&BQx_*gfyFdgiFN9AP;o`TvJo#U=P4> zZm?KA!=-E>BR;yjI;-V`3X+O<=9Z3&pc@J}QS%Lus0(P~YV0P0dHxO%&4iUvXvQ<$ zS7imMFh;|M3d}y%?mZTfKaL2@2MQ=bNsy_w-S2zzn^9s*b2oWmvSzAd->hXaMX5%? zkEPj3j~I+%$mU(#koKHg*=~LqjkekDJm3#m$v#@@G3)>mNOx2SHR@8%s7Jw{Q5}-M zUF+#<#(BrRQ$&a`O{`3)JeX4ESfBR;3&)xQL&sGsmN9eLE=gXO%ALCTMq#-sfZFw1*har+{vN(?_up$ev% zsiucLFL z@kA+sRgpgmv!gJE)^B}~7}bgI>)O=RJIGDRfS%=D*We+ZOpWApm+eB$vEsONLmAg&VE zh11lchl0*bj4QOe&5i4}5AK^0yyh+To*`2}$I9?({x-!q$&~h^EZPmy>!}!eKT%UK zd{>kH<2s+RpwwzFdoEjL0aTh0I?)&U`V~Uw@oxMRzcg+c)IO+@4Qm zIuew0S(ijlP9G7IsBLw>lC{9vXjy&COV)2qUtN?qBUPW`w9Q1Hby8HxAlaW%5 z+O2u3cPveRNvHZ_U%2}3V5ryG+I;IAT=m3EOnE0vJn@9S<4Nu9tE1Zk`hNNIuT(dt z2^u?`38yA*phYZIgW+zdT`$z1kn88(H`?2TJ9t2L%eBZbgpmDFosH!h@P5$6^^RGC z7Lzh^ObhV#2D#WrNQ9FYw-Pl=*Ro%T2w=g4Zfnla#szYg zbeAEG4P?{z=&ok_eOn8Ub zVD&}@zH+lBdR$(8UCy9(A1I9OpGgJm1>qa`L;ZGDwo+&{`8pQN!`a|{=bvg{ zd;06(cj%|aR!NCdn$)~3+mx$+`4)}rFhb$4D{CbV&AKDbCr42F#-xL2_;gYF-O?I^ zmhZ4hcvWO%I9Q5$ll&Xo?5zP z=p;;q4hP8eyfzMJmJ|5524DxXKR72v!Yvl`chtr6lQ$!a zU?ye4+GYU$#NOq#9SL_EQ)X2Bww_J8#*82Bl~!}D&THG=Mv|)A2|iVTpuvnu!M zvGkR^fl+5K*o4J_9cGJ}$bzc|#`6^l7%!50jbs=VS=X&P_d9?W{BS=GYG$pDDjK8~ zt*UUy0LTM6<@BYd8}{oO>8{I6I{Tfzo=JZ!e9r4E4v(lT3hG8tXcZv6z z<+rU80N!31?T!=Q@xe|~zG3U~*_G{i$zuN`BFbIj>LuBeap`TrGf5L)}mlw;yF%G|HEc03+gO{@47}VUj zESNwg+|1B4k3$AL+;UF4Ri`jP)ztCpG)yVRGOZ<-aD$4r=xSyu%FC~dzJKukik%+D zpiCaikX|SFA9c@XyC-R>@P~J#0j_%FDFZrAfl&fuS6se=Juli)&|i;bKo1`W-s4fN=J-POCUH{zxAgCJfg78_Y1R{IOB&Ph5UAy#BreDZixWx0eQMVE@-D7u^Y!b<+F;LxG^gEnXB1uXp;}~ zAKf8o+^@at9oyl^SQf2}dUa2@MG#JQB-hogWRIzmy7`T{P#^7gy%b-<=;kEq(H;r8 zAaKG~*HQm$T?vmUQHhRM zU_RfWZ!W}GMfAQpQRiU9NA65@U*)I9m*xg2Zq^95X{SECdP~h`NFIL>2FpsU z4Ha`$^K)(J`Y@x)UI|CXUi6+;v5a?%j~(&h?zvl=I(4?LYtEjhjd_m~K8J%Eg^GqdDjz5~DgpK@J3Sc>8jUZTVhWv4zy+u|l`!|NP@}?#jA_3&=8lrEme`z>8ek46!s|^w6=x4}!0NAa_Ek!35TaKH>DU_{|p-Gq{SY+&ttda{_R%w^Jkui^qV8R zi`wJgb3*Xxxw%zebJG-rrZ1oGtzB?*KRZmj-9FFi&3+f1;p@`sG&=AZPG8?NW!i2Ln+W!Ev;o8GMJj_*ctNu?=OyY}}k zPXI9O=AI?NZ$X`6P|+@(ZyV87{jF|gH4Nf6%EK^{<_IJ^lfkKG#$Sf{Imi(_QKjL9o=FEG;H_t}`a&3Sa+ME$rAdr)YW{OC!VN$32x zq5_o5kTKCQti29b zYgjBN5<wt!&gf0F%W zH1<#x;0?}P^#Kjf;_`h7mkWaX104|XV#O$DuL#^mKN9#l=((VqD9nt@1Gal@b3-ky z^$xvcsGBAjhR8nDaZ`?Fm8G=tf4pmG-kfg;%(=m{`}MG#l;vE4kI@(cE?~=Uc5&Xj zo`TE=4%_-xvk#xQd|35qcMjE}HdvuL``VByR&hH|m2+#W{}95tkD9K5NR0YR+ZIad zd8A%qtMU?V0hvC)eT3u!7Wo%TA$J>#DaQx=kf_D#PV|W4;uf9cRR!PcTZRPuxxhXY zz6IQIw8k2hZywurDZ!8WihM7A|50PliWwd~LC1G+|7Q5}cu}&~72{MB<#{_|ql!Hq zRvPgC%z|{J_+GlqEKD;Tv&V&=WsN;x-B z6h_0KT{jWHtw3r?Z#|^gF8KA+V3bl^=5g$U&Eg`E2Kk|08WuFYT;M*`R!pPIE5S%Q zhJ5-shf_uoKHB0VIo6Rk58yw4>{E?cM}-!ab5U3Jo?IfJ)RGU9DL({{UaFNAl)vd=?THqg`zuNOTjAoWg(oMd793wxhtz1~h zkVALBnf7BMHOmW8d7{vC!KVjC8J}F|+)`DgOwP|_34W=i^aaQ~H|ms&>ODFTx+rWe zZ`cFbSs)pJBOrWs&l8^*u@Pmw$#eux8D@_j#Uk&OUqZlP2@m4bXB3t_2BDww`J*+%#a#hcNtls{wZk zC_GGPA~^4w*mWuZ4?=yoi0eVe*9rNDE>FMghggj5dHVRRBU}p_E`0`mhPkCg=4d|J zSoUEhzA2JCR`RC5ZDShGuOiYbu8i;M45LTZrJ@61jB-Mnu?Hq(9T_qj%*Le$D<}mm z8lUat6HOj0W_xe{nF&OxBKW6Uegonm_=_^d#M^etzv8~aehoQ}H*qhsDLFMFL%3ZI z16UyM$~O;9R4J*SbJ31nfB)H)^!}7?Tw$nT3VLyoQLhfha3;}OtF|vJ|Sdx+;s8)s2#(oPTGeS#h{W{S28~*r>L=UUg-o%ac9?43o z0b9-0IuC!HBsd#n&8-dywWiGNaQEvs<7Hp2K|>E4iz_t-ANAu!`YE1kSSU&ZdW7wV z5bpL{?W0l2b;lwiJ=3A!P==p>GRTkHh0inZXe^ zkKm}|+Clo|U8_DT!kiA8eG}0+DGgtcjHrNn@ngS(}QzklTyf=xLD9r!2x3pek z{8}T718{`ufA{YBK1;p;?);|)qEw30kiqz{DQzC>Izp>AYxvVG#T7hzyE_ZRRMxG8 zTeFVzr@gdL7S6lp&NEGP9u+$=unrVM6K;94rle>il9M5Lc0?hL=6NqyOju>JKeRh~uA?bRqu5=Bd6&t5NhqRb0nKOTxbK%)m5jMfKevJ0 zenR7kqOr2TAD?Fuw~Qm}6-#SHpJrRB_FnQ-_og72{U52kdq%q3b!IoYEOSH)1i!31 zhwC_7>nQFKyPvPNB&{sv$no2fPMYxv-76h=PYd9s(PQ~9d3zwf8u zWL~DhM3F@0&rQ!P`;HT{2%4nr!|9w&H2$CA#f8TyZ z025*2!V+k4y_5J+{{%ggGBxXci^hG}rt-2t**Nj89YA;PX&nhdx9yclx@Xf~PT(Io z02mir+XA)ixX;RyB4Wd-;2->R>9{`8r*3Pw$va=w$~X>yQ|4K&Qu4IaqotI_S0hqi z;W#hO0)IuS6XO&_RBPOwhUj%nbF(DN36;_2pX$%+7gtk~x)nK5Hm^EJa218dJE{B< z;Loz-^^=w?Hs;Y6!np#?DFerXbl@gQRWES0k0<^{aAsa5F+CI=110`_y32XnJi<@> z*{gzXcgmR(8e(mg^6!xi`tT)g>h_5!AjiCU;Ng$wtTX93g;yc?9!lHKaYqeeTI{R+6Bfs)KeQo&NmtMH#HN0qyKE%JD49G zE-Bu7_QX3srs?h-tiClPZmbz`tLlG3{=82CQGOKJI{kCyJQ;@KI<4c<-dL1b8yg+# zVJJ&l^{`6X@`)N1r+kq!lVvHXq|H3 z*n@6|?xrS9wQREYzaR&sZgl;;NzPM&d*tDW2hJ&bQJ|<>&`R)R;2y#nwO5urn&+f= zH2bgMR8*<&n$~0Alt6VE9uq#BYuF$5TZYQ-VvR8;8gZvO)@u7bzaHY)=dDl`(iC8q z#^cU;&IPn_ZDHyuD(3ULvm~w!i z7pFU2jgmaP?c23Cgdls%t*>b^0g!aLOggS&HJa2tsXQZJ7Uo;RDV% zEQsz--+eb(5#uSD6c8GU6>CF6KDilh`*_JY&3?Be7xKJUq0~-9U(4^6ujOK_m&5bM z1?UG;>lp8SiZWll6G7m1^pQ-a|NfyMFg4;#J1{~`);um7+=RFmd?29`fLCIw{^>t; zQGR~K2m|ft(ozTYUeFY#UitotFaEIhJP`n{N^X0;iMr!(aNwUDqzq&-9&Fj;$Yz=r zt(RqNs)uAgB?0Bd9Ex4UC6gGd^t{zRVw0+AeBzBAz$rNK{!7fu28l;(1=d?B(|CqX zeWHc**3{Z~z5>&Ekro<}+Rr^%9RYC)M+!PO^^=7ExwLbTR@4WORb3 zOI!gs(RWkM)sHBkhTO4tK|KKPus{BvLfURR*ReMDtEK?`;H&ev9 zBimaM!Qs2JCS7+I7VoN!Q$dfk0icrebu#e;?U$36;z!DHrod}k_6mgM-Dj=a(gHEY zm+T$sKz_i#HXO-N<5t0UBGi!)k~#G)(Dd%mZjA^K|Gm?AN%hy_l`vq>BHb!(u)~`Z zJF1n44=9ZwIw=%YsRh9RDb3VF2I_ofcT_fh z{RFljg#6@L4D<(voz5fAY-P8`W~YW@JR}}WdnvicM#I~XpWVNmC1D`ZIYw~w3I2cf ze%|YtuJ>R6C+~qnHT^8}hDAD&8ZwmsX*#mGJ~9^(>E^mmhqOg?fsJTH{2UlZc$c9H ziQqL$`n_}MSTzQ}1(o#Li6j15-~66`(V`g7`|K}%=$eb?VHgNay!lAeia?cpn1Vg^ znIuF)p$#_sl&80%&>nCKY_JMqJ{<;Jmj2+ln_xz>d9QA6nm=2OZe>z)%<`(=Kz-L4 zP%x~1i1GD#lMG~;7|+nMujB7|G_nn7bY+p3y|qz|cR*RcFF6urs&LAB=U&zROe^D; zR+E2@^t*Wpl$#E!-uF3JGhaWi5EYqFC{3zs73u_R^H>pZ^kLUN-$p=3>(l8f4_I0E=b=%u+o*iC*%!Ye> z_=s)Z6Yji8oCLnj(ope1b!*|YKX+Q0pLW61SxtCHY^vb#I$+qzzgA$Z4y;VT?W6BX zIS|mSQQdR2ILyVmS4H4RZ;28>!TE4+SSwxQ>-2WlzVF94&t+U-%oZSu*bCmV- zL@PC?#1f3&O+jP&ezMMumIe92W``2i=Ad=>qXMV!aA={lo#m}Uqf=&2Q@qAdQ~E#8 zIW@R9?}wR4p19yAop4z8jW|QoDpKzBn6_hMx?A+mZxIr!1){Yrv7o%kE;4qYd`MuQ zf&;|^=;=~{4Y(k-f8OoCHs3aNSZRIxJ}3SSR_n0`k5HKy@Wfl5X$D&>E}P2jABDR$ z^ASO;izgMShAQKD5&T3a<<)Kl&Rey|Cv!F`GY{VWPjp$cs+0jL=wT9B;Flf`U9tF2 zsAN=Zr7Vh3PD}s5>Chv1*1sEm9k^Eg7Va&Pow4>o?mn<5(8cVpCzdzh)N;eM+RVuJ z$jEf#-VNGvo!NPabxQr`uwL~ zqSyfvNVm_E_vJP$0SjJxUKLv(^3<&_Nyk&k@{AP`8aFJd7ROND%wieI|G85l)2DgH zGGEGUNBC8~G38)4{;GX*bUXi9y@iM+2&Xvz4}+3yA-w%uZ;X6;WX`XD{?x;~!g@Hw zd_|oO@#xP)Gbu@@YDdD8b%Ba<5H7QHl+Of=QkXY<=Y;M3N?kgWyl9eocWzTU4#2|G zK)OJ@`k#OP7b5h}RVYEd?NsbZ1q&2RQgzQ&Dar_AIEqCcKgf^feZ|@^n&-7l4t*AMt7@FV>EswS%X`OTsRZVym`tG6i?36xxm) zY7X?VJ8SzLyw@7xldb)iwZmz04CFG?l1Kk}q2W&*1HrBR@LP7c(i68lW}|0`p{+O4 znN*rCRT94wcXQW3!{PcxY!XgX@X_vsVQ2p}mGl;Sa_b*_`dT;3uDg!`FAW9RM3xBU z5!&6~N~!I+uY<*lbFmIJfZfJnzMk5$C80Vm#z*pd6$k6_s-&VX$wLvBm*PYuW?m0W zFYj!Iqjjlw1-7#>&unsX^)!46tqp9QjIjXP=OFul?d$CHys3@@5x(fjroR!~;593m zV`^lPQzF<1mimAuwy5_uvuYux_rDd*qt=yl7R9)XcXA-S^Hl;Y#?<68d9 zVz8w(Hr?yCzK^3ans^!JM32lPo)xv{-^~CWxXD*$BLKzRkPx;**N7&kDmw$Zb3kA2 zpzOD0!A`a}##5R>8I3!trYEPc(Hu(mB5z|VnHR`5{>fcgcpbkqb5kK8 zVaUz!t)GWG71~R?iOmaT0J_>KOo~C7L(D}|?!IM|DZ+%vI+4)kt<#$D!fmJTX+BV9 zp3eA`T!9woz`!5RgYXBQ3l=y0GDf|IH$U9T1{PN3itd4^gK>8CKu#4mD`1i&FR+^a z189MIn3XX(GWu8-_&0ZQEQhueU*as|NGR4_JJoP!=7J)`4`^$IhZ2z?aZym8-Br+9 zHgc^=VJB4POy$c#i5dmXjMzl#s9@$R$j-^c3p!u#y4uTB8u+ul2s?_OB+z)o*AS4 zLaS+GtH2nL78A>5$iEsb{ZN?p_bb3>tl;ZHM)+tjO8MPY_kDCXo3Qvt&-abd$d**= zV;>RQ0_6(v-pB91edcy^=h-52+vgk$oHQ0%clAzJlVAZJsznAZ0g619z;#iu8$ntW~N5fL8b z%E8RPm_^ZNXE-p+M$*npTZ2*PjHi>xzl&RG2FIv5IN%gn+zmVQzi|L$n|U^2&0UjG z5$3Qqeo^Q}@FgH-mLMdJ8wtyf| z41+GcKwFaxuURY?)i+W21P#*qCecb1Ch9-=N*rNc1|)hj=aP0ydIw|a)`cm6uC--T zh?>az)@pV(@;ae}1IPkp(mi{Saxy@NdCx9j8FCr#I>f~Xq^thV{QL=~A=h?sTLeOk z-YI0&Hl$ExC5Sm#byrkV(AtkmY5gUyQ?%D-zGr1(OcT-SdVo53`?M+-FdD8;nJ$p{S9b@!R*?K$J$ERTqv3DQhi z;=|ZG`Pt5j`Y6r;ISo{J7-pYV;MUJqzZh|?JOj&EbV#`f3P z^=ThJ6#^xBORRYcn)j&0>siDhTdO_(X{EnxV`Vvq`~#S(<$^V;UplSwZn_o${j@ma z3%h!7Pp7HI`5PZigDC=6m%G;buNg)-ZS_sqh)OCx(=6_dIeW;t=5{?+v1c}gACV+q zWOEdx*#48ghHu8jYQE1r7x)+ZP9>a8`TjH6#J@x${MaBwuE>FB4@5cP{+|=jW=3W- z3^MWvfvwI@3}y|>wBQxgRsa`ZiS6bQ@6uuwqey1YCYBQ^dQ9|4avUq$Z#2i&=ba-R zzvC|t;ZKoJS4#zW!=XY(p%dMn9MunG1g2BLDh7>LC?;`%ApL z_P=eK9dhR=+06<_QGte!ykea~yz67yzNbnpWk>-2H;$@uEn@_5_1E5}_;jmJBWgdp zE%-cTV;bSmRgQLXb6M&qTdq%H(P^v!;t@%Apj@eFRb@qwB9wg08_^CfN{WGfMc7i85-vG$v=PFvj4EC*I#$~_5@VM?rYFhFKIGnnmg{(F$PMf-Wyw5A#l2SyLtuOKVUihNsnUbo=c1iMr6_pXhmJC`aM( zDVmqMUJhO>3m-n4xevZv<55Z2l1ARz`uSmJvSDlryub&cGlC9hX#GyVVaW(e%HsUpu%QW z`3@KW;T5@#NUd!X-EBP)E-_()3_TNnsH7*2Dnej|P;UlJn<%h(8L56)2Sk8?*is=3 zyrm<+i`S5&tg2?N{k>OQ>}#--W9ugcqsv_K2kCC1pU59T#c%FxlZOcg8?r#FFJs43 zk(3YO!OIz5IiDAd9x?nsE~s4hd1_A|$X-)AynEFY6xKR&p#voy+ouN%ZC56h^G$Zl*gSJ%O`^AA zT29+1^v9G%xO}N(7!fOb)`=ww=bx^2e`PUXF2X+@x={3}ha^pG`p0Ds7CC{t9r~Fe z#-K=Jyw8`A+m-q(s-`3maNjJ09&Z=*J?}>ioG=9nYR^k1M+&cDbQT78eEA^N`01Fh z<1e2AC+S*mF~Qb#oz@4w|CF zg+8=yz;rUj9Nc#u;0Tp>ska;t8-pJ!-(t!7o+>w#+DPxG5tgvPXogudA=}|7t9RC{ zoO7%^t=pEW4jrogbZSOJ**1;wga(6gqln)$~MtlH_^`F%0HllcE;6xlG&>c zesmr=uj|)CuJ!z2@$t!P4t+i^y5N2thOnEG9~3X8Jh~s0yuVFEi7% zhQt^=PROY^*`BN93gAje;M7;%-22LE`$~#kdeye1exZ`e1td~!omBf#Oc$0p4_ALb z;Z|Y7ki68zJuHlq5w@2syO*vPZj(bU z6c1LB)0m+k_2XQ-$`)9X8J0slG$I)`zT=h&socXFI7<=Om0V)F6RqHZIh~xr?Ds0u z;0{)sDX(!+rDFBQj4NcMI5L5q;#(0BmR@1-Y|_+m*?3CMTL zGoL)=ssd&5VXhycp78aNAe^N+>`L$ml$KU)Cv?YwwiTKz&352ey)Vru?^%Zg<@DaB zi0Jth#*d;lq}dHXtHKHBGETFb-QP0nwOwxp#1lkfMN>l)xMB*9Bt?#fmJbeOyx|T5 zRFgvULq`e7c1N=t!^TO!oB5AY19#*IFdNQIQT*sP*CByJFGzOwWU+3gKT6+}YIBV* znD$(bHoRBokCk~#hfA_h^QXfjrsx(!|mZWTHYI;z?ww^qe2b1+%nZ`Rk z<%U4sK;j;}9vMszV|L&L>z$+?H&}K^i5{oPMUc^FHTc3od}+BR#jciyi$Th-7Po#% zX5%bweLC#KM&y(1yxCx8Hv9@F?cq%P!dk74oKc13;pSN6ya+fZWSZ?qa_8*ITMzVi9pT$ zui{@p_22>|D_6n!e%;!a!pEvnFxfT}*xhEKz_g3e1h!fzAmbo~J~*}d01;ynewRxU z`M)>BP|45ts+_-;L~Z6;p5nt`CXM4>ZSC0(JhFgsbuY-j;U)ir9FTv({9kXSNn7h$ z`2rxGp?RBK^gPI;WM1b1sj&`EPHO)C=;b&~>E1+PQ{6O6MnmD9=lnOxmFmlIOvE$DN`C+?buN&ohLkb^=@zZo&6nmUfBn z9(+>n_5j3$7*gO_ebQ%%=-stfA8)gFIsl<}fwB-1X`fFGo8UtxY#sRSnd5gwEPBml zZ)h#rmMj%=h)*Bj(fKOlZy9+S@)hQ zcrzaFQ0B_2j8)(<}O) z4;8@z$4&Nm?uqR1j#=ZQ3`xY)#EJ1hei=j&%+zKjRSpRIk5r>!<2Dn3A4663`7;w3 zh7s^l-$-@R$0Q}WYv^Q$I5HaP9l{}n7LbGUeeEoEgjq+dufRG`CUz3-fpFl0-s}tU z*ckjl0vUE5_!2=!L>>$vQNEyQNfnvdhLWodE(ghJljTA9@zJ(y84}AlQJsKKrg?6; z$yg?cy|ufWiU0Iwqy#^t*)oizZjmZ}%W7(n)+FJ$*T%c^M0~z)=6LRH1xk{8JHerM z>2KIxIf*uEBBA0g%K%hix7(`X9pIk}VT#--h-Cp}<0(T+no&VI%mK{K@s``!Kd1Pvp#HTjS>x>sZW+jJ{uA55B!Hq9&uplC6rGkFLd1u=#sWg2)K4SU49u!xT)edXNKLFz{F{u~IE^lId}1X!J`gB~_y@7ujM z#KPs73xCIaGTa51=P^83JoqVIQ|)bLIXW`;!T%gAjCYV>kv|r4m}&lVR;C~W@)-o4 zV*I8$`K);Y)`B0RM;YlyaeDZh9YcLJKuW9o4w7)!ThloRH52&(6DJBD?2(|uA_%^F zQa903~n|zHjvp)xWcO(ea1t5+);Z$+7$In zqFP-6NFB^1Ney_5UVMLI5A+L2wE4-RYV68|Np3q#38%66mhtC<Eag?$j_8#dgD4*Y=V@0D*}E?VAMO9vP;oenDOnL~WD zPR<318QJ+{<4(Mlou@mODdU2gf(qc3&jq-<5Z-%%E2~l269Ugm@v5nlu-DR_v6X$6o89o%acH6mC};(Z6LRd*$yVkTXCKaBQXsMAc`;lrpZpvzcC6a=#*o$; zZqYumB)A=47+0+21RL&7$N86yY1$@?%9tF8_3rQP1SXbuN%SANifC?I7DQb&7V=$& z(|Hs*IaK~70v#K5=jJ(S5{a9d?)+P$xxpqun@0CP3oO7L(_9Tc=0aVFM5IqVfI$1!qeWx3d|KsX+&E~A<{p5X}N$6`O>A)xAoti%q z6;%dXyQ(724C^SF2mU4z5{+Mbtd?@vU;H9__LlXgi)PdX1g9%*2c~9}k0VR97Dw`@ z;opmI-*oJfu7b+i{**D+&xTxEIt0WUDX$jeI8m_=>RD%1w7%mY3&mK3`^fw0O!J;2 zppsrAydLg9H;zN;JXjv@yY0T3ML8LOBK#8!f3=*~%xT?)bWGaZxt-Y-#*SWQwDGmL%h9X0bTC-v>|-RM*3#p)U7 zQ3~{}NR7gfAWxh3_feM`Xj((gvHMUy+w=-tC-K)r*p^LB89Hm2;_zHT%tY0Hd*uN@ zcMa`ox*c6Ip#NnZIm?n$w%U0_34M^>v-%kA?0w`wOEU%k)+4&XuzpDZe&vm)7+f6u z4cjS}3dcz1kIkUSfIAT9_I6X;0;pve5RaS;srSBopoh`=@&!xU$pk&fVSkrbmqX=x zDDxiE2|ii$oAC&}2=%cXr)?1Ky78lYu9FsAn=#h8_TruX{olW+9Y%IiX!}tnBO4K- zrLz4;DmKy=@U}20P+QBzm|JnRz&SZTEdK>bt30Z8zA9fvoz~b)qqt}6&0F^TY%W}s z=JnnTw0TUgRBSK}L-_#ZrwMS#x#a?Z{3$6kbyN~*zMJ@LTM|@TceQ$-Otzy;~hXa!r@3(Rf#YDv1)=fD9T$07sicGIzTO3%pM`f{GNSp*uxFnGE*L7|dtDdjp zYbWSdO?`S#c>gu%JT=zm(tI9^fpnU#n!sai9_i@PKCAPqfzl(9zGe6u$C4?`-iwhd z(-*WSM>}`RKfWk=-tNHB-EpQQ(@r9Qo-WT3373DFl*V>ormY>^5!>|R!9gBfkL3VW zj`^Gv$nD)PiX&MUc;p(W&&MrpEPA5p@vOH&UE6F^XWq%3(;iwlj5h8!?buUMU@Fpy8B0O2O-E52D3QCLiL`SlB&O1NSr8?0i9cot?udW~u(vvFCbJ3$ zr4^UqTa$==|01M4bZ#PPE-?EnYe zND3qx?sDK?rwPe+b^9)~K{*8^>QoQMMN)GM`A<0wx2O3`2f)D%Uw03T9-T6<1m!RU zXFg7}Sm!(C*(SmXS5r$)a9Kemd084h>)q0Rv>Nb4Q7tUR`hh8MIqnLlq6rQglnDzu zh{-LsV`QQR`pffrwlr6bIkE3gI5ypK%U($2eH5;&=;P;mr6~T`YIaV@!ZdzpktMVe z5BA9zfcsRg(^UPPX9A+DZ>_y{qtCJU;W z?>2jV?T_AYOib}*h!Bcdzp?tE6)w}TNtW5ebS%iq^MRXKHBoH;E_M6F5~uam0p9xN z>Xf_t(}+~5ufpa-K<#E?XGN%6L#*l`Ly-O#_p2}uydkdceGTDb7eNh91gk1Bv(Oym zYRjG{%prB{Ly5cnqd9rrnbZgGM9dINQEg@;VVDlgk)w)rLkk~vXVb4HFMi*Y`a6;- zWp>mlGFJlZ(sX=Qp!6FO7V#*I-$%~!)X$)WId_$0k;_@q>Bn`W5$fW#uvI`qQ-*WCx#wn1_#}4O*2-xMepU$G5vvkPYop+?r|vZSoc?-TcjKA zIR?MuoO8R?2ZnI%xtI<_H@7z%o8lrnD|IWa5Gt6!=iB|u03u|ay)E(|2d%tO^sbWf z^>`o?Y;!Rw!8K=}D7|oiUfh-3`p9Tbb2Ts$u!qK25u0M832API&D5<2;ZbJF(-Swv zzskfE+s0iNxv7mG_5VtVH9bO zaPf~a8PEJsN(E>}sbv`KonH*o&VOY!n^H~Zk>6W8Bg>N|J(>x@8h=W>-U&xhI6+Sw zCs9UQ+XmY{6ng4u`a&*z6r9UEhww>8Xo}LX#!##^^|>8|zF645nGF|DW|A=YikJZ)BcczyUSi;eTDM- zEbhUI6e3uk&I;Q!0%?kwO1g`z)4cqcjsDEDZIj_snhG`2&s~OTi0Vh# zXbD2ePgz-Wu=Z*s!2%n&hATc2j7% z+Eu$ZBHV$Gp~sUl=zRISp2<4{u8P{MI(vP>m8~1PVg-uIS;JdtWF(}^uk+&3s8k6p1YJufYqi6JGOY z^87lZAdLT|uRtPx%nfdvk2uxvn&Se_-Zp{Cv++6|A$<`^GCaihX`e!gd3@S_fTJ3ZSV^ge#>27-(%b8u2 zHkCcg9rrSb0gco@T`|Y<9>d&tbYF@eY#T51xH?F?pgD_eSufY_XAY@CL*c9GziP;zWo^^0aM;>;ndP!8cWHw{ zSQ@-Z_0-iIFfSWsT-V{8lOq!C-7>x_KW{ScS3uy?RONKcct@$5#iSLu|tVeifkB4Ql(n}ch+SAO}@cz3#sQQbElg3 zMfq5_epPIuAFx@k>XZYI2r4Kxd&G#4>`THa3TIr1kfr;ad8wX6;{)3oWdAU%qy*A* zXTW9h9X=mtJ;ad8O`&m06(H?8R$)>5!ftwKM%m{sp-@a}4PdT=$4u|#$Ht)sSEt;W zz&Cho8MElipOk15LZ{c5a{+!awp?U*SbP8$*vK=FGE;Hsjs}jg59E`}(X4~v?A|6B zQ4@j@W-F*gakCq0=suA8c9mHR)&+LPw?x%~$NjwXRoc2X*8VL^fbO&; zA;g~s|C16k5y<`7v}A9SWwcJMu5b{JWK!4Zm&dO}@BpM>s!3S(Qj9++=N4Hbsv<9& zxE!KEB>GcJlv#3=%69;i%+gM9vl=Lkd%bT@_Oc}5MLepJhGkH^yc&_Q*_$}8b*IsE zQ5XbeNo+Ux#y-Z*oRfON1$Lcb%Sol(23@EdmjHd-?WN*BHLGd)aY}8kHJtS%-UxZ0 zO3eEzy7u@=VmHxzreu!*Yr)3kC9XVnsVn&DA$+xniKAEujZBh@@ z1(=~p(z=^pM7(6ux^t9Ovn$7lD^1A_7qNqh_4x!>`&u>Kj>2uXgAY~ z`8CaUJ6;JZsp;K*+{4eDY>w&!tJ|%);MjE2H)+0!ZVIS&z%Z}L)X?(H{OTH3KOfB1&sK4sa+pw zheEsW{U5IHJm)>_003+jubSTCpqKGZ%8c9oa69u@2woC)vFixAjPDQuMwAv(BxYee zW;*3{!qjH5WxsLoOQqz^8gFQlM~R%mniy?K6icDoiWUjU;&f2;D5on8NDkU^!%2P+ zZCx?eCC7gfQd~OKbHOXiJ+EXea~SpXPl>GXrL^Ij9D@gCI%AKW_?#Pm9J`Ib`Pv$k ziz=>3qBKTiK8C>-B{SQXNypb2NjC*>{*aTAlb=4Ft6I}o$zBD*#0*I5G+o&m-bkP5 zpZgf*nCJGm-&z?FA^%PYg#Ox7r|u=raSyo|v!)qLr?@2ogN3h=ZxzLvn?-rL4~Tym z-AP}j>m~1w@U?0#*om~k_m^OElXi0hbBTTGD(uZoLC%oEM&qEr#PhPwo_e>?Cf0U( zI@I8q!LT#VP4XSNBKe2%+vPJ5sDAQ6XIZ!Np?V>MQ?z6BY{*3UE#izW($m+w4@{vP z^}23?=ykBrX9tvm^i&r$Uz{g-uG)Zj!QGbpp4&;=PYIG=ozhYgqvWTXltZKI-ZHtK zw0!8`KuVsXp?&Pc3cmZ+-n?Dy!iRt4GL}0X+@^xUotrF8h9jQP zP+F(5j@uAnEahNVR=6LJCDG=7SW$c_wjAT}dN6kg6<73q>xBuQIxlV#{{h9lPsW?im{9atE*F!YDdbOo z-@hi@xfd~WtA0LoIrb{;UOwpF(tUg%-NfarHt~GE+vwo$)5H{ZHD_;G=WdFT@alLG zi~J3gGj$UOo2I#0LQp@;7XYmY?^LTJ7bjH93b@p%OX$6OUcBj@gZs{>k+dG){wq&~ z$(+yTM3)``Hs-!4BXDlpRkx}DLm-8w>0GhEfK%{h-cZo6tvOvdlXAV|UbTlfL<+wjs zq5%2RD1c#~^eg-MGPtG#YAt!)(ILPf>?UOM=~!Jg#Md5l;D7$E(5q%Z{nqxr+myg% zJz<)+$=mA3{p4Ne{3XW8;d%`wMi#scwZNOh=wEqVeslaaHt>z9CU!i~s^HKyEhHtK zw0~h*c-<=y=tuTtM4VFwDfZLKy{Ne*{{BN1*{)b$5&Ausvxbru&h^Lh z80T-dLh~1%ch`Prdk^*3VF%a4(>&_Kun}nxi%<>Mint)14{dj=qGK>7G0!ml4GnX{Yfa z&LCN}`%sx(L3x${J=jB=`E_@blw#PA{l_8>$u68{=$yK`?#mtqk)P3`x-x|Z@qY1^JU z;I4DUIDW-C`qzCtrE9318ZoSffn1rIMfo*%^luLpS2Rva4d0%CrZkspd0XUD3`auM z#TJY^5_ZiDNSCR|M}Ee{Y6PB%j|Qisdu<3{(l{9IxwB7qSvuigsh%0T+I!3Y{a4vL z^ZZxwx928Eg21@*fIZB`A}0kg(MI;Yf8gYN$})ZRa4J*nX{=qYv<29vD3Up)PdbdN zJ-?jjvM7qmfvUHyana593`ub^UU+UcCa021DuEy6;dziaUrM>5J0wbdGlG^$(&o9j zq#0#IPU1kFlj4c0*Sf-*gE(D!M#;ufKRJ2pNji2=qA<6@^;$4db72# zn#>dZ*~cD45A5UHX+Avq`}?99UI+?n@VCVTFylQp9oWWZz&3v26US$`gwSNIyj1ey?x^DSZU z^0XLFvP+(xtFrUN_rfgw@3rfA>Q9_4z9^_nwAFrpD-=e?>a=@e$v$@rc3%jgejV%v z&m5MvBAvh)u-9;Q)zQW!!>~i+#!WLmmm;tn_JAJvf8;0}pM#S5r4m}PNx6(K-C$Q@ zA>&zNX7koQ^ob6@Jtpynj;l8JGflKPqAbc&X+~j7KWlJ|RySo&TAtRg+P}CP2@L`f z?wAjH6Dd+xsNX`anecm8O?E;h`3yJrLIG6p+LK8{f`5H-YlM&YPj)wW)pXkyXFCJH z{%Yq?sCVy(3eaVqQp-m>rFthM3JP#6bR3GK#WRS?_BkBwbSo)U_>wH&-pwBFUF78S zGwZl!ONmI7e?96R-KASu(q^ghU3T@@W0&Lr2pM?q)cDQ*$gFXTbnYHJ6mKsP{aJ!H zE*Ypi!b+T4M`W!mtNFPxc3eA&SsjT87znSV#XgVXDfRg{=klylN#;=B8QRv{yt!xh z5#c$`z3tbn#R9CS@$Y%WGTYcVdQvzQ1&7i%-?rD%*8rVBi4J}8oELNVql51fWrFX0 z!MV>PTf4fk0r!RUvCZ9lN3aFY8B}oj>tBN6#?FN7kGwN=-%Z?+YOqrx%vGln{-#G< z+bw%(@uT4+9p^n~xr5{B$4(?bs^pfxE~xJ=Wj@(-s$BVKF=As~WDfLX*h^U@!cXg5 z^Or@(>|Zn3q9*m!f9R6M^9G@XKrW5%I#1F5C`PGeQ<1x z6O2@wr*}4WH%A~+$L4ttbckT6>x^!5-x>tU4p_k=PAv)9Tw;?_)pMUjZDIbCHum*h zo1S;Uvk^3+cQC3-{Nwd>Vr4CZ_H8sF#{H4Z#1`Yd&2^iaj8(~5ao%Kb%%7{o3IMSh z9mgFG!kKHm6C0{*fF2%UCLsOk#>aR0f56&AhPI2Y?m#eb)<155$K((|K$vIjoK)ID z|DLSNzBU=V2im&jyaZT(Go9ug3L6~=9lO3gI8aBTtMiN)Z~}iiU;DpWkZzb~K%oJm z0(Ez-j@YY*=!ze*$6(=Rxxsm&Tx0k4S+Mldkn-`L={)GUg5c*h-z4dZ8gk-TmZU<6CBI zbh87;eJ~nfBmM1)0;4W^SMo!rdHEJpW;eQY|2b9c6N0Tc=Lai+51Bfs{(eU*KKc5- zXX@~Yaz@KulVTI)&S0qHulV@2{&e30GIP-nTa2P5o~4RErrrtz^q!}Qpk(U&l&=O9 z*sWf;b0>5de^x55PLtmfRaS@@=z{?$;e{K`Z-;4y_`k|~Z=2HWDB8G8+AW(MBI6`# zbLMd=5Kl8k72Qbqta~5ifA{A_)M_&+fLlsT4NCD#jJu7BLq2w11Z>bdP~mtlwB*z# z9T9z%p}M%_A!K>AxIqxW9s8;f!D6^nVn}u>?hZ{UIF2&S?5`QZw%JT}~&y@R6);ffKZJZ;Yj z4o#ANFal{~x2PDWN3}x2E5dMPebxk|d^TVl+}~u4zC9RdXNGuw;3CR-6uK>Z-`A&q z(ubV?*})yGZkX6n4CpBsZMU48#(gqsonqras;rO?hI;^Utarml_2jq}dlU@H-YX=WaV@d&N{ij4c?U7B zQC=esq=W|G=`M*;kHevma!7H$MYXFT_!qny{E5#RCqU@-Kg3vttyKlEQsf_7v!0oAO&~!)R>y?*8n2XbGwy6x7E5ME!q_yJOG)S}K zCH5=72uwb7m-P}`gLeY7QpH-1l#+L8_+#s~5HWy;bY~P$cu#iHe00P9w+rA%DjHCBj8 zf9UkR{Ywwp{3X`N-pTeT;WlQ7smojZr`mNfy*sRcZHJEnId)4+qxj5ug4qUn`mm64`W* zXY6z!ne3{cAa(H_P-`2Ca1&Ulb6hWz^QI#1y_>}Z3`+-%1jfnTEm_1!`!4)}ETi!z zQVjM?KfztGyZGJ~D43EbOnwC^-sjVd2Db{&@_J1A-t7RtlfZ8*&9C}w<03Cq}!8x5`B^L#|kfrhhdKAt+RL0TcJ{ks)m%n!=3e^ZRs-NMgF@N^2Y)F zN8~-K;HDN_Yw;gL!ZOakw=@SlxiCOayj;!)o#GEPHx{a(a7eW2(!F;}J-*{qOx?B+IFMpoLO*AcN|Ag#QO}k%vWe zM%YjqTh8L7RI9+SEu~063o#{1#G=gPAn_$}OJ9X)hQIg0lM7U3y;KoNS{F*%c}MmD zoTZ5FpD$+zJ->-QQ7;@2gN=B_B4vfdzUSCt+{v}3`7K7P5%516N#6xa7Aqy_UPM&= zH-&9HH@eZPRwHFVq}Z zKyx<`0lMK=S8)VOu`NhBAKDf|dl?Wsl3J~d8WhzRhDZm0*FiaXA$4fFk{D4QXFZQ#*N9CKvJeay4|TxoF$< z5)XvcINJphIQ4w0%`mx`2VW)gUw|t>?Xj@rFQ=AS3P)U8&TlI-r}p_Rngz^Pc`wGN zQInTOLE#s#vVJ_&8>GLV)sJL=w|M`~+0-X>MTRyPp0i3mhjrZnhDrw(hk9cqgq*kw zn)7gad@Mz^CgYv*eaG~CfC#z~6Fy{Wd9fQwuaEeW0gY=-6tv| zZN~Q}<$T~*@r9?9D@MK0;@?G!kK2^TrAIXGN7WJ=0oO*QD{nMC2U6-`4BAKUb(e)4NGPI>tq1a zQ(ZSx{sYH4tj1&KNGA+}d1T{U#T4ekVBglACy=es`PV&c)GFRDP|XR0I!eEe^(BB| ze+c6_;bbuy6~Y&q16F8B*HK7!n7%35T6YM~b*0u6kP;sdsfe&{Q71>-_{J#{d6ows z+9HJuZ_dUKCN(>Z19b#cPYJY*1YY7nRTR!Nh7EzUFbuldCx=(}#_IPEyfb3unXMJZ zC^@O&J2~gt$1V^@<&g)$!;JB$z-J7ekCm9){Mg|Q;_yH4gxK3PU9$at{7LzH?zg#= zwoDz(ISmyMI>$@j|9HDFxq!3*f?q-PF^&fb!P_n^Wdo=#b|EudgN2C`SnP|; z1a!aCOli-^SGg$vEzm2cfJMy``p^HR2oZ?dZTW?8#L$Ea@1>vQ`&I&iy3@BL@RCWt zj)8{7twBHfLl*Jq0akdH23)k5?g0t|xQXf-hx9>|kA}OtxvT)I;Tj}Hfn>n%cpxWK zl#wVJr1ogc%-bKa9f#{~P9r~c5w-ma`=j9U4s55RJ)>3+0J>GNH~uDwL04$j3XyQ(eQkis-~xRjc+d<5P$cqQ@9*$$!L zl6^Aba1Gqs7ZuKqRF1?+`P;@Y11x`}iCWejW-FdiZMA&9TAt}T&RzFW?gsNpMeTsLNn~}1?*H6Rc z2Fxc)OLu-2V6HgxAJx^*9Zlww(x}Jv8U4z6u+{sv?#Y}>|JA~4Zo-$YZwC>w4z*^D z&6iL(qaJa%Ef7ZP&Pv2GFK#dMLgKAAkU*{q=6?piV!)(Mc3^73=cB&Ij{qY&nz19B zzSjSYdVHN$2#=Y=tR`k<7w;bv(689GjaNvA$4txxaPz8B%-$%kUiW~4dN$LDaGN+u z^3x30jz|Xb#h-l2Shr0_n{Ma8f)VS*N5#Bx$4}lcKLY~$0~+($Rek^PflIsHjIobC zY=`6up@?JBvl5e81(yttB{RH#xAyKSm?Z4Ebz{(u%~QsFKD5_w634Ga=z2xD32zd1 zov4XN(rL?diSKmaP>1AS^XYEL5>K;>OTF3p!_EMJ7Kb0dN-b*h7T*g)6cw_~6iCS* zYJnHddy=>ZtZOD~g%$z!Nxlrs!b0fvk;JGcU6rB1!kG|5q!gDP>{Yr94YNiNh*xLQh=T5f zk`tvk%CJx;)=bIA#8~0=A`CQ-Gj6S_exmdTIxJqhh^=Sx2QBa8KRgIU82IhQjqnUh ze(Fn(C$`&^qFVPIP=viD?jBsyG5tI_L;A*-QVN{w)YW)`Gmv-@7^r0yeurQn2zP~-{<#b zJneZp0?)M4Hqa@Gq>C%(WIRpk_}JaXPU;h{K#dUtI#aVT0Z0W;Hy$QJY2bthMVmRGEQT@ro@pE(Ko61| zsqfw>&wVX%WBcIPo~pC&pTS6!#!(XU=o87mbf`^3q|ZG8(@4%;v`8DF{h(E}Zf1HD z^^+z+6Z2uVl3MRb7umtKyT9)cbR{C9(4JE6!fQE_(20!q%R-i}7JujY*FuOqi8BEW zfBebABx{8MYxj7MmNyj0X94#5eMV-9( z6M8|24*r=sc%B8^t1s5Fy%?)x?!~KIp6c<}5|#=iE}N)AMf`1kK#f7`m5fOMqyF!s zZiy{JXU6*$XwMcBpp=QTkN z^_$RD5BHnnq_1i&DZ>Mso{uX*xWDO*#oFly5Z4D5z&$VrrNamZ;=((RJmITQtX_H~Ngh>x zk0*lBNG!}4AegZM2hmw1qXH(>M3ZO7+ia0!oiclSP4-a!&N<%b81#?t?-|^84$U=& z8e%9`tKI|wjWd65oj}g%Z|6Lf`eYn0Yt?{`B?iYM?o!raelKb!j}-u(D*o_%-I= z?j8eGqA#<`qw-jhqKD5jRxjNUUu8Ryxz#&(`Vfgmc-)J{PH1B>Z=i@6LtT zlg7#yPXfS-i6gePuRN~?!qU=$sJj7)_Q$TYs%daR2#gY)ozR34RLS*(_C~Tbm12<* z1=0;&itDXdMIZ6S|05BY7oyv@*^ivKj7u8(vs8(f#!tJc1tr^%9smJcFi z@WjdnJKfWpE{;x~y?gxSObOhky!=_HO-uJfy_hgJ;0gL1)%)yrwe#|=9iYs#jmiHt zsIQM>0b2NtTb3?au;cLoq>-@fiShcl@~h7@|7OlUf}&N=@*HsuR)YqOfoFBq!o7UR zmu9q+D(BSt1q2Zwu*z?!M^E9&Q34<)yS(=%PiNN9Enw zE3|%N`vLs6^qsvrTJS`3m}jk$P<%jFoLLJ0Vl_uuHfSMys_1$vf`6GSn3xrDyH=d! z<1_3Bg_ zG}nEWZ4(oJ>`X6Czy;F_#BSnF(enpPT~l*zdtI3b`H{jN8zswaYALdQ^<^t~%Dg(; z1H34S8&bUG)K%<{WGouC+N1^8v1kda&Q+gYx1xcAx z^L?(Ea)jp!jVK9(X!&+O@0PTs_l1O;AGD$E)0g9NUqj%;j=+3ZUrt%dMYme_-bk-eWn5}*^=$(L)XZW3TD1z# z38kA>O!eATg^Tz_B@Q|u<5Orcs3RqUj(=ZG$w7t!{RZ|h(|Lc|mIR#sISmnpIc{6BMRuHo^wx$9gWJ47}8ExIE~VU{1~glWc^v z)8`7m2LssRgtwmG;Eq?*(@T#C&+lfL#l_Xrt+*ohqPC)< z1T#XXZQ&mtmkv0KEd>l>%HV!PnevnJX}EIhraOXnbG_)SMGG^0gx$0hd>{wNN~(oc zpfH9e7alygubQLe%R459G3`qKS_xlYk+`PG22eZakveS$-H|g(e%0s>p9I8fIkCMO z6<@T|{Gkk}dP} zd!kWX2{uBltmGOCu6&dYkoDci%YErEVUEwrKRm=r6hKHyxpAJUHQ9Kmti}v6CwfZz%Y$`_*H$lu#~yyrz(g5GAzQ(=kSRR%2|XpxKq_e z<*M(<%gaN<%bpP6k8*W~Q&JHPoOHokTEfU*QI|91zccRjJX-STVVn@|Ak#F)rEuc> z-f$y7soD#W_iv&o5|AH$CQ2nV;p3Wb&@82^U}&yhHBua?C3ERoBZn zYUwa*a9 z#S<&X-khxoF1zjZZ8q{wTwJ>GN^$bOaAA$Pr#;Q6>2R2&&OCQOb1Myh!T&#ns7`6w-=C{?gHRw1k z>w67TiER33j0pBSuI4FqvauA{+D2HWXMVU{n5%+tnRstGuIsV6}h zkl$2KypA6)y!Yx5e&8CFF^r9?H({1@z~S0U`n;9>O~@{281oUHg1~3d`AAS2AayO9 z#9PkCaS(~CHn&GnY@*=1Syr_@&3fN6ny+3djmC^cMA|(HxSgQvmDZcP3Q~rZzyS}c zJ^hO~qAzWJ*>OGTNU^5uJ%Rf;j!$>+f#&ihJIPkvmN1RPk#8|_>&Q$zarzpdp4TIN z=o>K;5)2}b`6inptzu=v6MGn~C8TcDR6C)Bu_t)_=x)E~MoM8s>w>1RKN|)~ORR>fP~_&HU!*k=OqWju6Me}| z%2ZP8>`}U(40(OXx{CQCwD{RA`0mdsn0(0w8Ph%x`9V(h$rsv1o}|3Am#6Jb!r*TK zQI2x13?%qqx;mIP)a!JRa3bMM@i>Vk-e-Qns9XM++#J%pKa|M&|13bDpDmW~*TYol zj$1GP0UVm7E2}TIBSwa+Qmt^{LGll;I{t=8c>GYo<*Oy_7Xf6-QR}-m{Y-u(4X0VBD;Y4lt)~NHjSZi}E{Du+c`7n0g5L^9 z6Dx18WBzs(zWHb_y`W$fDZR5L>bIo+_R#PUEs=e+HN_%9psS| z#|BMsiBoWtX&4`w{#(ya0&b!sYI;%ex?HO1Byl;rtYBv{N>IddQ%lAn;sc}D*ka7a z`?gpDw|F;a%dbK(_OR$`Z`6rkswdKw^g^ZM&Z7ywA7`%LGfd(Aq0DTnpLsj?hE%cc zN||WF=70oSnce&+stqqNPl{Rm_%o%pUQzeHwAjY+WC3pmu^Uj$cJ3YR;p1^!^Hanr z+99(_4s}9osey?IFVa0p8Y}R5_YY9Hit2E2#JD3=&Tf!UJ1veSu_qHO+~BSZcM1*O zt>yLk2(?T6G=62Vq#%PoTbNEGyKY;vG(~)v<35`_>qPTvt~B@X0IQo5uZoIl(f3P? z;Z*Fc*1(m!^H0>Rl|yLP?Wu#jy&I3uJL0uBnC54KI#SMebT@fXt*Okzn)UB8Yw90t zy#sL8TrjM?$?u=T64epw0z8eP@-fg?|kNwe%?o-yFJ z=#YB|JF|&*`v&#-wQvB#ms{7_voZdz*X5^aymc{4c+?dL-5(qOZ}fF?owQa^D0Au9c9>g^lFx5nLn8ivKB&3payH}7mV>E%uVqViFU zSXHRVrEPI30L5!uN_7Sa14kwHucWt);cJ_j|ZGID(8n@T_(zgUh6y7K+i0IZMHbXR~f5%=Ye`U2dY_DDF*BE&^(jk*o z_nu%07UggUVp@ae?MBdLFiGBwzdE*Qi+=jzPyD^El2FX;F8lU?0}=Ai+d4!|Y*-u~0u<|X3GRL1%mfKrT>ow*2lh7Cx(bG@=@!o-1Bp0BW!i(s)lKUHk-M&tsou5zU0L^!dLi@>n}) ztl+euhE`wMymL+MlWVCCKJ>cr!mJ_#?&>4&!!91&6)*8i8o@+UL#nOmsuNs2oNIU3 zNt*V1yb$IvH)37d2b$!C!c^&*{kC&-$z&jVOn8M5W)}kwrkfdHv2w0&cC+5M)ph4$do?~h`@bnrR*QDVf#h7$-{>91`>d9wm)k4u zl;~puOTP&?J(R46q&4-OL3(glffFvKEHLODx{vzyzats^GG_EgYlPz(UR_i2z=pRO zpQ}kZcP{IC9Y{kpZnT}Q5AWAUM1inQOA+^9y1QRp-tJy&FPpZ1`U)`nY;GRb_i=D>E!b8B+D zmyuu6g`Hp+P=>kf;h>jOO6q52e(YWg-nc*U-R|zFMk`y)7=#<6pBj~TpD~Yj4Dg&wqAxI`q)M!(yY?vZAj~9eCT-kdC3ua5n6*V%LB&n zwSAnzpEr1Q?`*6q77xX*eqAm<=}&+TLG3g9z5Y|kVVxK=s~-Lh0KLf4pufUI*8Q(K z-gbUK-YOzf!(DJ6TQ0WBH>I92FUYOv7ncbiNVBhGM}9Mn_L2Tgy{bmdDr_2X zajUFLRv-R)(^pJ1Mb}063gT+#lFJM*6S{3gSGL%&pDiLYDcnuX=d?ipDN2Mt`s9Hu zU6~m*{wHs6O77k{(*VSXL2r)GXgy}$i)73pDmYwm7h+FMR={+hS$R60Ag&&6b4 z!Rbn%8b<|E+UulqVTj*95L)#-t&;Y?Nyscq^4@cX2JYxeZ>QaEQbyKd9LZ}6cjuuV zxzbKHdPQbk>QqD6_Cnrgeb_LgdNu2&g8)~Jb4-xiGtB>RJE&T5%Pvjs=-_4e(!{}* zFBr1Xu4>$2piBm(pP8<=5eyGaFAlXfFzb;y4+{zN2tsiu(W^h1gK^qXw6=9cbjk&F zGz>~mYR=Zm^!y9Hq70r0m=9TI4D=%+By^tJ6Ie3Ko_kmvv*9cb{#|XSQ9O`0U1VK95NwjZ*TdptEGvk9(p%sONk6 zmdO4laFLSjda3DkGhj|qFQt-HcUFff7QVlIsX&xPSHr!A7qTT%`*gK#B*e~a=Q2h= z@y0w*UpS+ak;qpX9uw339<`3Kr3m`SE4@_)Pdu5jX|RdgN1IyUk)A*V^n;_6w<0r+ zJyguPO(X+vL>25{@o6#4E55eyK!(GzgAb_=NVgx$8I?EzDB{5Wde>FILq35+Wj00> zaajPA*}lVz{P{61ke>wlo%O8mtahW1nS~x#LVdRWQtR3~L&!ZUYF^uWUdP_xNx6ma zYe5ux9_ZV;~;I`vns%QL;-t%%muEy7lA)7g}aPH7>w%*B&nQFZxmnq@Q>EAcs{S1Pupaaf zW*bbYl^e0AOE}fcAY&!FWwJr2n$w%2J^U~657kVo5<53!3XDr~snT4lZUt7tf>{xF zwa7)=-G6Ur1Mx4v2Xywnc-c2+B6}q)(ZZnL)sPQAL}Esn5@fV2;H2npPt>;6BdfzO z+)Wv~e^_xne{YnR&Bh*KOssuWSQ!~wA1Uws)hV}K+MZ(O8n!`j=Ho|=HyPu&oL*$O z>*1-f{eYkA12Wo53(Qc(Z+~seWmn|tqkOjQ?ZkYAk>RRI8)v`56YXR`ER9DH+K}@$ zv!_jj3X^D88`jmK zId{i#p&io89~0{*z6#!F|9Ja>a^1|-W_sj=Or?Ki=V3h&BTJj z5v~afNdT#i4FaxZEFE*Skiz6IOawGT@d^*Leh&y()~_{MZBdnx&f^zZM|^*T%C3^C zkfj^2mB{ZGQ=6-p|n>` z&ogg{c!PFEA2$sJAG{NqB=icDEaAlr(|d$XNB-E5TDXfd8< zp`qTJkaTqU)ky6T7BGIx!(c56ztscy#HkXR+3f0T1(H5Bmun@~*{-zHRbou*WYjNC znSA%QO?^?i;Eg)4idTXTZ}SsXXV=U*{j4T%FI2hVlJmd!VK}bIUDB4n5WLXe(r!Pk ziq|QrH|5!5^-I~UeN8aTqQawzd0e*jxtt5P?fUKdffl?To<;AKLHfY>9)^&jV8~zE zU#bG;I-aHNr7f@f%Iu5~$X_Yl(nA#?0PYY z?a0ErSQQ%0Xm8X#pH#Jw`~;fI8kVMLoi=3O?fIOk$3=5`F%;y^GI6DjaSr@Gr}D0E zj7KwTDE7rZ1SAJ0y^+AwSwp=Ei048{Tr!~&l~1>g%4E-9LhQ<$Df9=hO}09!NS+R<7b+GVspW-liX#l)-b}xak>ugT}+5OY2qaBh=;<&&HpRNPOC0nCs)Pl&imx zUA$_ls*D~TTzAn3LxjW3FOLgZ?=!~UJF~;0J}MnVBZwT8pGv!eYeQ#D@j-A$QHr487!?T z$syah^1;oe@oPb-r4E5uiGR-GCBCC=1BeLhY?36}Z8aB*==URKnC~TKfJ8KEPm!i^ z6Hu%damLl}Hg$(v;mH(Q?G9O=mFm8kf8|P-K_5c>zu|!@tmYZ0eLWECcj&GOQN0rc zId;K0FI~FcPIT;=b~TeKX^s8^waZ?Ft?S#F!&5(7=eNdRq?N3@B=!(_A(Fw`F-_Iv zH{{94_76=7cG0oCPG{oFzYV%`oa6Q=-wmz@wO2kF_;cLPrXv0?xqj5=ZZk1zGiAMg z_vEr{wVcUFw_({mwQstBsoeXDXpQ{r>1-!P(Z!#+JtpuV=_R=o_DB70NN>|wZm2y~ z5#Oq_4!9D&(##ZsKlGKfSF0RT3*B%bJi6d+-wB{as{x4_ZcPdV^q*pOGa@K~cyITbf#X%&< zu-(O!Ev2-Rj3DHy{^lGw03gkOCN`7DLhN)F6V5WpJ~itarhRem zh^n5ttVK9KUzM=##=t~0I`4F#v!l%p76Wo?QM1j50Lu_7QDc@z_dh+=y8J+=(K^#+n98ut< zwn{wE^T~a;TCVM?7Do7W4#)3wtoZ;43!<^cc*kBgJks559&T!32yBS*n?4EQr5^SX zBl@udCCL$^y9`?&IxM;GdLaiZ<* z+?o%KU98Xf|IDZ3z=#5bQJdbk40t<#U8NBiO0#1{1>*We(m`gD`7hL?_wJm))0;|c zUVz#lO_fqmA$nQgkry(oYehw6Vy5|f;5m28TIR1E{dJ&L06D|8V#xa9``?1=BpavW zkz3E0eakG%XLs}WFemKdeetzGQmBWCk0o28$70|2-66KUN!aozq3)e5I`mGYb?uY% z%@VessSR+y7WxQ%<IOr>6_(Q z?qv2$vU_^%$0`TNB4Agl2deh1GFiot9}s%~BW`Z4M4;3l)23_?x6S*N@oGF%^v2iw zsaj`_*1@xk*@ylSS|C%D%{Oa_4Sw%h-MrBkwdLslDB-;K`g%WK(9aamoxGCb&pA&6 ztLc~;m~BSbZI>_z?wSikX(4xtxa-mp_Q!hYRoMTnR>a(3gfgm` zi(UnEOFC)K6wz4(6?7zF<4pHq4%q1K|&J}W88T`H=U|1Y_WP!RhB4i zg0tEvp&c>*SFHc`Z#7lkiCKCWGMaIsqMWqbf)_dmYi;Q0`MMDk6>1egz`T-AqkUuu zv*YaNztH04W{h#t>iy=GB%wShnBu5)``Y{9nbW$%nB;CXy_JGGY4(*}GTjgHv*T`Nay-DWA;!H0mo8W1qHj5ct zwSVf|c>%xz`x_3X>;H0fYigI8Xjm{CFHf~LuJ_B5OA+#CJ<$obxVMGz{|x`w_gB5Y zUQOmna=sEHiVNagJ@05@@h9xa-^=pScVdb>EqHD&X-q#hGC0||QQqfx4Zc#xRIU-6 zuX*-#D`*9YFnkkzzwy{xBL7|2a@vIVLhmRD2xArX6Mzc^{qS#JlGM z&{lILXS6W58T?ae9nsxZK(i3n{Ve%$1$=d^OP*3l_1uAImy)QQ|oS0$o%e0n4_ z;EbPEr0&WEpDcfSz!RNN`~;=@JRYDyDz}qze%dlE z&AFCr9@=Y^OW%%kHSy?xYKJ}j3ga@BHWQSGw* zOM}!8iJmKmRGEhfU{zSVrWKf(kROv$b$_JM(JQ4eGs&HdNkFn`Ki4Oa#30AA zeDBQ30hxf!#IJialps}Xb$SE(C1@@|aNkYcGgqVIt?Li#eZEF3_1*BC3UGx@AB16K zUj6(VB(5u8lXe}(%>~*D*1gS{Y(}rdlT10%FI2`1uXV!<=M@aS+`{$hysDhK5c zy%*ybdu-`jhBjQfOg^H^lNq>_`t53_ zhR?Q%{>7ZpE)65WPNEABt!Kl=thv%;IZ%4D6NDniu90%%zyWvj2}JoC>tsTc%lF&s z^Ux7ONu!^}E@+byB)_-jRvbhiZVnYt@Vj8S;RSa!vBx}oekMQuq*LfKBm#;G!g{UE z1PXL);a{eeRmHf8cPf$t;>!PVW8aQmG>I4oz|)Z^`ynk}=)U`R^TS7Od{18~{2IL5 z4`V+Ma5!6JommY{tIL>Xob(1=vfJ2`v&OSZRpF?uVd*99EZYs_d$ORSfr!upl_3#L zc_(eVss}$a2l2VA12v|35ETq>Mrnj1V=8zjWf48UfIXjm3$?{WCtWp9?Z`qAs^#?h z+grRscsiW?*n`xUqc3|=1WT?!gfvJl2Md*G%(^Go&7K@s)_}P0LuY{N{M+v$xB=1m z$VJbRAtIdsoCEBcm@_51PMWlSf?UhIQ4cLiUod(?6tk>3NwM?Xi?IjHV(J}jr_-cl z3G|7@xIBi~UsLNmsmMT>2cWtvCKZVNws)L~9l-0y@$PyV{7QlYDA7koQY07u0#?YA zI8#|4%8u1~K68fu#eop2za&0~8S7W9DKl$N1~f!xh?G-^hB5y-8r~Mg3+YJ`%}t2<)b!LL z8oAb26uiovX)gX=oWdsA-0~eO$;?;IN1qsHqg4}?Ro*4U%cwlxS1y-%uxAw^*0POQ73)KM)L9d^%_j;${q-w zmA;(9L73IPGI;+Ap1oj<_?%!_lBGK3U)`AFl|C=Nb8+FjB$-)8$(v{GQ$o8zkfN6L#V-Vg<-jSM5}MwxHai_*$ob?%i>M zn#s1Tza$VHB9I`qoX%10hbO}wB8`>%1o0*F`D6Zu0{9D$X_-sA4c!h$9n@um-{GJ=~+l23V>py=ip>BsJ6sIIRiv@~xy;L7LO1t_fT18#ALU->BD9;t_c& zA@vH3VGn<#@-=)Q7$shUBP>LX6l( zzxcWlW_R?nje>?eR3FmQ4=KCCIZcU~m^jC>M3-SjWjGz}dYrc4&DOIMUBDL+w351}&wbQ{{Wft8lQ}nL{0n|t_!#z`HC0f6i zW3$gE1&KHD0O#o{MdmMJ>^2q6g$+ug{DYFZh-K{eqt<6}d|9Wu_m7I`2wOg{gWYcs zON)|ASi~jZ;K}8cJgm;5GS%=_t!|6GVm6pJ&W|_KuVJ!PS#Zx1C^@96W#8b^;Q z%6#@BzN85&l$!;XEkR;xg=SZS9xd3zUBBa)XDrlcxHR;&JAS9ij~KkpE~(^kei{%* zwYjmHJsz>%c~UPFXU7z$47V`n2#70x9H~mN;b38A)SJD(MS}9#>3b707rZ>)7(^CR zuw_u9rt5Ur#>Ms%{LQZI#_4H}=|~#3m?Q4FZas`kD*gYyU0+1JlNw@WH!~cYacEo) zz6Ch_5moA;{dIaIS4d@>el3%}XPaMXEaEZ6#Itcdk1go1JZ=wrn@(x<%qW&Bgmec6l9oxsxJbDoljh&#pbuJ6ddp zYQIsM+5hR177RnSR5IcTHrFA-uPO!{N?BF2Wb=jo{7ew!^7yWt;uP6WZY;@ zg%N+x)#C$%@Gw1guE9_(E@Mk#sZ8X!=MnXV{niP_{O>t8uA@P+kh65QhkQREJlFvw zZa6W|Rb+qwO|Oy>wM0h5Et*!xfY3SK&oH z!H;J(OwRNyIfsl^WX_U#O57)n5QJe0jAFLD+7%1I6%E*{?=0t(>c%68i`3&IH&&q2 zIKe-lIO~Subu_EPe;!ebQV#lOI&nOF?vJvlOziJ5{t(_xKs)e6-wHQZ9oj{6FrQV3 zli~?U?1*0dJ#ayM9v#5NAF%6>^Wz=*<@Mzi>79fzg)xoltCV4opC9&Q;6=-To3E=+ z8ElPU=%x2B;aDq;BMlmbC!P>-j|H_=QvF2dTS85sib~A zb0>t@-YUn&^R?JLGq*aelo#4qVA)tW@^ybD`9?=Od)YLCX@$pov7QCl%Rg+g>33^E zdJH2vhVeGLcRV0^H{OW;;l#B+{}JBL7#Jf?g=(W$^8884tbdLfk9P@G{nquhR~r`{ z#|1$!I7<5LHlC&rfml;-@Ou?gK6ExqF3uwhGN-d8wZ*LNZWuwV@L!7ugdR8JB#yL- z=L{Sp^A6B|6jD>T6(M``albmJw)$QLayRvJi?t6JwNVLuY9kzg#su*=x=6j~s;3{G zuwe3sj$*y%)q3H$p-43AwcBO$Bt%r7pS=b%)Y^$}q)D39eDJu;Xw#{ofAv${QJ&Pd zeB(HW$NdFTUm>04c~liMofXX#jn|68*fBb9jdlW0k7&U%v*XH$A)I3_qS>KzUih)D znNfys)DyG$;a}=jT?kW~FC?!ePS}Y&PPtv^<%Ogg+B&E1n(>1)b;@k5Nrq^QvH8s9 z_4R{Je>9e=Jq;StNrxzCR`0o$E{-IB?U0AKWsZfYS#h(p_)wUM)f7RIK?ci;W~)I}N7uc$&+7{fPy zTUX%hC1yjaE@hUfL_Mn~S`>vy}e1RSdm)iHY3HJy?qBvbZay*{ZiTTvcJsyy>Gxk>UPuaMI!q ze-wT<9f6GID!$1KLj;+Ye6~$-t8_^53N`F%-3*z-1GsgELU+3sP zgRl_lrPINsj#oM6an63P+eXp_YzdAp%*{@;Xkb_Sq&F2|KO8^d9oMq#vXI$9%N^~g zcwpF+2}V%YSI%2e{~WhexLP)sg!T#+W%t28L6@UAQ?P=<7~dzp#pF+$8!bj7oyP(3 zcW7u`k%V@PPiM{&mgd#Uju`&d@_T+HbWUvWyBmtZ8BTGnp|#wv^hnnH_zo}x<$C;D ziv!(P#n%HVk}3WyOROshDwS)n@?hq%&(q=<%sI#>_i;>5PmsVU&%6%Ive`(frIO(<0etXfUka98=bB|qaJSLL@pyx*JdEghFafgR44{X`uL?pl>KF&8lFG zfi2!mD3XeTT$u2pU$>QDlS>otXnwU)dMqY+__o^ZE`LFimbJgUak^zeM%qH|Dv36h zQ|Rlu#r`3;xoHQ)=Z-|`mF$7T+|gABe@LIlX}!^W2Ua9_OiU&j%n_n9cJjXRjn0BA zoi`NU1#9f=VD*7U2-(*=|cx35c?BJ1Wy#8p?RmBuO z#Vd+JR8qyxi(+~z=7>jMqY|GFxb*tR8;S+QIrGi&Jl5%0nWa_im`O_VsTkT9vFGol zS&g_gweF{IXN-y(b#p*IoLf|->HbL78F(gT6KF3a>3d;G&M;_={?hM_GuPo$VffbE z=od$1IUBFNxmJxBDD4>S+UnT6iyq#1le#8_jdqmOe0S&HuqUc#<|mipL>D8-aZhHW zFs84a;VJnbv&W;Ix&7H`fTC8#m!z}$u?n5oQGCN9#TYoMsJ^N%2{h07G=}ta>wVj7 zq4<{_6j!dcv*)RT%zz1$nD1vUU(?NeT>Y-83qH>V*_v5;!-9`# zHj03>bceKbNq2WCT_P>b(5ZBHcZi^r(L0E;!O1?W`>%fN@6vsXU!~3#`<2vYXSm}Ko|*^8x85-_X=k!9t2{x_^H_u&-7YED!b|kTs!D;#oV(g-XsyXPXmwU}b)s^=6Q-9HwUHa`D+2 zs3hLhw0&l_nurLJxC!j1*x@BXs~?P*G7rCuEih`w;FkPYMy9!9+NYn$xI)Bgk3IiM zHW)@mGJa=9HvZsy_-#cMm}lUxc_e6Ivg_D}b>0mXOn^U#Q8{2oZ=K>)idhJ~UD_x| zxc!s}bRjdpSLUs;ED-|Bzlo#>$#|=D=$>R5S+^CMDTrAT20qL4hAG2+c@6jPRO4JV zGIJ+t2DwJ?-Fzd`PO1vxC|Cq1;x!VoGNXvgYB4P7$au)r>`30=EAke0nGz8OGcCs( zy_X}~q387gqkBljZ1KnnjBX`DMZNh9X}YJd$RKpzBORNHtEyxWw(z`fP^-T|8DWa6 zeCf@Ga*bw4#ke^WK@9!+q+yIj{dEQv`gmjU+&{KB(lWhW@y0`<{5~zqI3v{Tcxat1 zg@6*nJvfp}TS&RY|CNCx+IOzNnJ}J(H}Cx!t?}R$#5w0Od3X{!cZJ>h?^P+&n7V^? zKiBZfCfY{hyH{d&6CUYOp&B}OXKffuw2sN`L|jQQucso2ejdoj^sK6#Ed-K1 zc!rZPKR+6)9C=6^zLWP|yuXUEX?bJ5+i z>K%L*6|BAgi5&#Z0lTt?*{KyIn^;T&a4$% zcd9Slqty3IipuCpYA|XvpXD{&$ukzCH(HZ3h53bhGLN^Xs(w{XiXs-YzQ81Nz11}( zS>_=YtKk*YXP&H9`#V~I>mm%7ojD*O8LI!ZDE}&?E074N)DN)BA3@X6K5sZZDIdNz z;6z@=Qj^Z+tgxyuLwYc~;cYHPX=%y1S-(M#OVNKPR>n$>+0qAwGxc_1rjqF>^A@4Y zE+NYm- zd@-$R+XUX95udLc&cgU2#y$PrX-S~-dp}0!I)`0a5jYY+>K@MATL_CB_q43=XZ^cA ztvD?x8M_gZ_?+7LU;*|HFA>davCHL5++5Z;X?{I#E~d|iZdRY61Am3K{C*WDB?SLr zLtS59Z~~K}2TD5GwAvV{e`187Z80!qM~O|D;EDt}hrhv?mDPitCBVPo`q&it1IwMs zkE}0bEzHX@?5WdzMqhxI2AK35zrobDX-1C58DbvIXhSuiWR_!_LQhX<3RwHjjq4l) zvXqLcpOg}qZ(<=v@;Pi%Ev_k~h~0)}8%X{hxARQ4OMU-W~ zJdmHUxzIvwr{HXVd5)xY=_QaddJgvq4g(H?wF8Qd%_ z_6Hss>2TCPk&{YTmHYmgtudFIl|9U<^d;J zS5*JqKL#x=)`{VHEqVUdp}6<_PVA;T@j;7+S$u%L81FGv!7@g?*Ked_JD8v|x+^-@ zwNUdJ#%HK>8c${mk^oIhJh#e;#3uXcfX9LFlH_@*&ck6JjSA$yf4H!MuWUpMb7WzwoCr!8n_cWyplbZo7uIFVHlgVyEtx(BX+8Eq z>4o1wBdCe2z#JxOL&fF=zmkKuW7|kMig9x%f+hkIu7{46e-+;Ka^R)27|pbAzUhqE zZ!(os0@9zFkBt8duvch=)I(jVEeU%~wY$Y=YNQIxSML3Ph*NxC`#U<5ZK7Riu5GKX z2IpnQUJ}%h44#bo^O&|9{T$* z8kFHvdOVL26HE_x!Yjtjo-iZa^GDHiV;l)={ayWX#OLslynFQ#WEjQRN>*!a<%1{L zfl+3GS$X~${Q#w|FEH!+VBL#u06Bu?-`mJ&v+)-6Jrg`5p)2I<1GsP=n*+B)(PYO8rX@CB_$JhoE7+*uQbArLPTAefEA+Xm= zxS03)_9ceq?}6&5%~>LYW z=LZ2~(~QORJ>%#t26&5R7l0aZ2yFkbTS!{Wi6gQfJcYQQ+WAWY_2!)XS=V0`7Q_WT zR;sSR0ISP-q_am~Q>)iW`YK8Hxa}5|e*@Uk;Yi4mAs%@7%zt}InfS^fK@zd6xUI!C zm|hYL@&83$aZP^xS+G7u*t2=7S<0=P<>?s?@erC+Z{%_wg-!uAe~|5)-2x%e3u@l|;hp|xLC7LNDC^J-n(&(k{5C_qo} z9epvO?ed3`!+HFs1WlHQ z48!CHuIg%H15*`eMM5*Yn*oOA!sf#X_*#GlE@gq}dVcp8v6!g|O$!eiG=|z8`4W^4 z?zW;aJwtIks6tpy!|pKe%(UFcMm68lv1q596jcE(_jv)|t?>!o&$<0dIW+j(Y1U&m z#fwJrC;c6Qo7t+bXKB)e&M1aC&Do)VvLH00*aFB+=iqu4D15QpL2~Dd+x(5l`|Cfh zBiQy|nk;XsroDj7ub!Ujit!@JRA4)FkYJ;c#9zuQ_79Ck3xCtm)eC$YiZ@)|SNTho zs&myXGinoJr>0kiCqO(6L^lFHibwx2gB2f#wfXA$7x#m1fNnNEa{(HjNT|>sd2h%W z@#Rv2sNheqiI3PzAhq$X6U9ny0jB-;9Q)A@O?1w7cbM|3-nyIHJkkQgHokAvWPI{S zXkF0IWsgg{nN6+X*Zv_?xfoIR$e_b|W_*!(4&!FxV_7yaCIu=v4 zv=(y6e?s!OAF!kBZ%QJw^s(5Z7}I+CMrQ#hkeV2{5!a1Sty1Gx1@kHN)^nyacKymt z=U1fs69l7su<0$ceS<4Qi4!{3^WNPW8;YH|4Efx^Pm9g?3}9qWil4O<4R`Wh?iaT= zRA*xoDfaC?V%bc*>oTZAIjlqLlcX(cC1T58LJ`bvryc)R_#*wjolMjk)W`+Z&qna< zI_D+ES-U><7B9+2;i<)kI}5@@Y0MJ(zu6vl10Q%5_<&oKCEs(l;9Q#kvKUv{d`vfY zYme6Z<0HKPo0dqoCMfDT*TE=(V$tD02}K`aLE;d&FA@@@lF#I-e2arplKS&o*sM{U& zrV>&2b`=CgIq*z;h38B=F*Sly#F?*OkIo-p7PD7|9P(^FFUtFX15z&xJ{%Zvk7l5p zlPOJ<6o`gDD&H-Rwiwt+>)iqu=B9@Ue2|mkHk!TQrj)nfUK7$1OK*r&FyCFWMXH!x z$0=jxp2GVJQ&UgtPT~BjRrwP=7eldG$ryoKld0&)?>OItGryT9MQg_uhdYZxY$wTD z0PEddCwjNjAyMnt`My>y^MEZ0T@-T8mik7k?G~hSsnZ%SZ0e%MAk4wqo~X=WIYHfp z&%ybOn}@D|BKl)Di!FDfqsXMj)YN88vn$nfK9dRwyw74`&lqiU8KxU57(v7Jo!1Tq%P+;uD)+^ zRL#BjJRlZ-l4nGh?g}ch5gvdzR(xoGx67<%K-MBsV=h?vQQ!0`bymXDmANcCuDkPYiX@9$q`mT9vYeHkAPD60qP3~4raNXx2Byts=zl;q9 za%d|ZD;zjx=T{tgw79aj*k|u{64S)fYw;}Gr(t!ob4@7H-CF4Uk4?;}+aHUB$lb3wJ9fcoO^qJ|ty+lm0&z06_d^ zUeXg}{sukM+46F1)@(MYFkak9+v{%-Y6(7hAeWepr(Zb)1)4zD$}-zQlJncn%~!1} zxA*@HoRRdw24zk~Wz#)MmxQiL}V5lU_#RIp8fw)0|vOmsz35DYvA zSoe!DV#>~Yv3%TJ#uXZSo^_1I$-THzF~Q@A`zjxlPDl`MOqhOmgq2BO9E_9 zdAyVsjoSKU;!jv`?2V01m(wtQMmYNCZoi%8IA9}CB678BYgGg;JO&qDBRCX+V<&=1 zMJ`nQm>G5J=uENRL-CxAd5iPJUrcaDU0MCS*5CpUkTZq&OG9(8Jp$@O#u+T%I}^(Q zx%(2k8qaT&y`X1E$Crt~Mo%B&-}=6Z^pjktRF8Ckb0l*(k42y{#Ru-ohT*NNb(ej1 z{6_gBlqRNDByz>AZhfm8P4+?suCt~bq zVw%rlqJyRO=8(Y8iD0&sb4YrLdNSi6bK~9JtRNJAE*|`ggH2+=O$@pRc@9d{_~198Qnr$;n~#A7i!X-j6EQ{XWJFiim8&kF|CjR%H80yX zdE`uEGc_h#sbyHjW8a5R!ZDMrzVHrOdm}IHh+(^A_DZE&>ylcY1du7Q0;fC9A)l7w zz&8Xk!kwu!g*z_+@0?m0Y3|4}BXIdoMbZ|_!D$#?U7_g*JvKEV^a%%?DQ+otXd>HB zXVwQcE?K{d2f5;p)0lQ`&c*wTy6L0-SnL(iMj3C!%b1|@fLgr#b&f}{aMg==U|Q%# ztvwD9^4~r|r}XW-SR2yDyAk}*8X(|o)kv|6v@)B5iM-bStt*xRm=h*kILmt{*T9XD zo8Jixyp{}96rO-LosG%iz2|3UBXPzAmq4cUFW7S$C_TVG)j-sS8)m@lGN!xPqivgV z@wEXX<{?KIlbR3H-qw|B$`BByr^CGJ%bkE}=?V?kzgzxBcRi@6^V_+l1Adm_PV zN_F(+ZLXn~Zu@LvX$ZRcf~q(R^?|y&2PQC&wm)?e3|#z#L8^I2BWOoCSk};8REhQ2 zc$gl~i>GYI-D94|@Gd$xFoH1$S)*eyLsqijg59+>ni0L#$7bd@D*B`i7izfk%cNbg z@-6_1xKJgnv7eL!d38p<&H=|nuAz?$=E&iXe#rv1FhkG}atuQMV0)Aq8ozvxAIz^x z@76jxh(U3ip2T-pjof5%#{YY9%h}}i;z`lIcatTgXiZlCYF86XI~MSYNO_ML3UnFo zO%NBg=HygQI7FAw-G)#BLcyJK$fC5WrmH0@0i2CdSXp#^U?sHUD_rk;oW272B6$<+ zf^NN{EvnklYMD(-rTaC+E%LWBrCJXtt z5y3*_X|bHRJyFEo32@(GowF>2Z{{e@qp5Lg(s=+gpQ|s0g9nSS?*n)dL%2Xc{viHx zXQgN&kO>G({>ls~x!P#9Drf!CucC5tv^Sr&-4Xt4&6DN77%wzRjD!7dz~+Pwp>ksrGziSlUG}i#rJw2n@TWg#$p!M%&hNGz%!!9P5fD8{6X< z|NaF%)NvF?fnytuozx;-NA$G0f%~+WW_<0KrZHijTcLvkf9M!rz7+V*_mzCtjt-bz ziWgy0=*+z424*bwDxUB=sN^pg>8CJ#U-DH(rnY#`m`{>%Mp$Y+CBox-m`4ujg-Y~0 zLL@KC$}zgt`YU71j`swZ?*+~)PfW#p`x=tc1*I-7aYcydiv4{2AT+6L=sg4!P3oNk&u2CuROFOh~Gk zLGHVVk)4>WYJ45Y!$FYiaydG5mDO1`mIqT{>AB=r#@29YuleX`7rgMN(&@bHn7BO- zqjoJW>Up^xw{*?1Rd4!00n^5{5^;%GlB2?mgA_ydH4T?aKNRY$D5*kiaE&l>-=l zzXB;03{FS@(9=!4&xBGVvv!=M;GBB$)eGX()iO=u(B6w{`|+QMdEE2l4^H@c`97oK z7ExR6@ZPV{TW)3~GTwQqWdi3X$6;IxE;4Q88j&P_ff9;4hdDd4S>xXT?9QwW1NleR zM4XRiP0PBW&+igLoCBbN2dKE-t-r$r)`Gu`7A1Jq9=cKETHyEc-4d5H>RDY(C^4%}p!wU?WdAzOS20bviEPUAFhMIEG-WGW_{zVCJz~l<+#=j% zz-89tOh`HATB90yqSgG@Uj%#m{dz95Tm2BK;oI=33#`v}B=x{R^xt{Tz#+*!L^m1K zwMY{s$js!BKRefHseK;!Rkg2yUuzCH31ydlR6_AdqaaQqYk8vEZ1%Xyd|EI}>lSFJ z{zdl76h^eYK}sm9zIQxvz`L(NKPX={uiO?-U{m$~BdpgURZ~^b)iQq4e3@(! z{VmAdkEC1EKk^M~B*!t+=4zbX@nL3B7w1&TVYw7>#v43-g>Lg!6>uvFa zAN@{20*uQRoS=viE=?S(2JCxB;&V<#SAiN28OgoJoVE#LlBaNbAQ7r7L;KQB&B7ZUvhg4e5>RxB zEWqk6Nu>Imn2Z`5TqUy>JQl7kzx!zr%}ug>E@QC9|3Vz``@rH)lm!5D{Y)}J~(ome4YIyloYBpy= zLand2I=Q09^p*}cNvt25aH$!k?V7K6Ec(ChBky$pxVql0gvf&(6xd#i zvXl2-ubv5Fp1Y-~;^V~MD|?M7Ts1}`=kM2lA^ZAqRjVEr@enb0@k)LGXzIGdY^>5g zYqr143nE@Tr+eWa_+iy+#i|hd{%x@3Th2-Gu>nHrkneE;ZkmDqv8M`}l*jGg06Z1A zodZ@-o!@>VfD3V9z1N~luT^8F(yilmY$^O18gl?3nfIUmW?rl7%}vw}#D?mpmFbeM zAHE1`cACRw9{7wM`2MoYc)+Nw`IVih>-BFpv8&QDHxhcC0n|38EO1+8t2TFLR44!z zxHS=+YY+esNAFSFfJ!>9*w!RV4HrW*GSd9oB44u8J8n+T=TsHF&~2CDGuan&#^?~3 zO;N{`nR(ZshA7dRuTGS)RIRXyEQ=y#f>Uh>eIiSYY+(+Nv4jy2^xXDW=Srw$R+{69 zeW&B5fDTC!^}6`Y_RCdzYw_?`-S&v1wH6=4hzK8J5*2ngN3&X@x;YAkR>jnPh!PnG zBdQvU&-IG)U8sU}vI6jX8CPBgjTnLf2W9KeZbPSbpP|PM<2haFlQ6`%;wEn*MakSm z{KibG^V{N%B?9Q--~|$FLE2xlFX6fdcqn3#(!aq-lzTYt63QP z^U*d%7_MCu78G?>9a&_@^CR(Ya= z^7dS8weK{z8iNnBi6-F>N+n-97=QJ+-@hjY7|Jzv9VIp` zS~5;=_VY+e=VGQWWfZ3%Pooui*&ru%TP$Hpg9V^;rtu|H)`~6R4Z4K@P30riS|>*} z)V8i%8S zK)mIVhh@d=4XkB9Ai}Xp`lzX>>IdDd=sQFQg9*S`5=t1`W5Ru%9Z~;(fl|0rZd};5 z!nblW;FSQqB^hZcSrX7<*M6{G)rJDnu)DtP&yVk#?8!R*7JD>bcn?@I*Iy56Q2O`z5!dwiifNN*1t*n|oA=_rI>P$-#<)FVdCM*5>s^&*o>Y#Ixz}?b2_RbzL7| z#03@CHNl6wSPFf-Kxdk?HE?12goLi5LS#mqYQY3xs-Wie{adXoQ=-2wL;=J;7(4Pz zfpCxF_9t0O74yn^rS9KE3hN@jX~>&WBL+;F4A?}in~{Bhm$^1PhZ(O-1gR9ne;l-C z^eXKs{_b^-w>uwY`b~<(^qP`6zMf!6y_DynAbFPlm4a-LPT-)RuF!@&f18(0+ys!v z;$j;h=T5XG%x_ya|K$T`@61ZBxhMGz1*2GfPscyznjUqs+yi|esCa7?gQ)n#3L*=m+;!m<2)qUb8E5XvD^(RCcj2gPg4Z z8=ecZ(sD#lO-HS_RVjA88%A#?jPD({b5>hGvAlR;XIoq?^>D8it1=-!rvwJlxfwy< zrUnaJ{_IRsVdILp{`*GROJALEkise$=mR!g&oWVe#KP?|YCoKSGr4ZS0*EI)=;OZo zVlq|^zca-Nwx=8q>{y^nd2ItBF`zKO4tF@FZ?Y6zT zz-2==cPn`{`sa&leSayS1lDg@Nu1)34!Q?>+HiuPn-jG*$bhU@)UmSurqrJY!+2>^ zR(ntCpXIaTv@e|#a33I{xRTZr?cbOj8!gJcvAt+}9bF=9C>nhC)sR1Ui(s=Q_7#~2 z*pOf}yA(_{xiYLWDfZDoPk5NkTnQ-cN&6(z4;ALv80^?P!}})J^^=>O{imo z^ie##HDAEMc(1(PXG^QK)>j#rj#6|z+p$=0-_0P%*cZDCB*sX2dOI%1I>i$n42dLHN9#_lc=f( zo8VF)$OR^jmoP5KmtdBkr$U#A&Y(o#6t^}`pW`WnJ8=f(EC zJ{e3jNJPkAe(Axs%Ei8~wlY%D_)+#y3Cf%?HG&3n|1s_iyw#-lh(telk2uF1glRcfH#gat720x!FSr(a1Ig<0 zJ5UCnLEG?UCV#2KP&nl4Gj`IW=K}_rwCsersZ4VucAmN6tKbxUP3;mbqt_~zPNX5| zE~`iX9+W8qze6e)Dh-Az2+xltcJwDJE3S>+x#6e@Pdpv2qj>v z2q=Q6Z#P~f1Y~M@=#VzTWXrf~G}~(#EzEMCV*-Ll_^S2;G7~#kcyLst*s2+##iIIy zn`u3w7nGtlC>`J>BPj64=K=Jg3}TxSA3 ze4%pS=Dfo?;DR}}5b7ox+(B*L2ok6{J>D1muZror$|aLt-u-8YOPz4Sjq-$;DrN zqGL-8*cwjgA}r$!Ivv`{AERsoknaJn%;REhetk5KjXv8?K$Cu&h)}}x`(~-?qT6}D z>Tx#|w2-l{X5Pm0J9b~iY$=5nn4$)-`+&~Ed-yRdfJS{Kwt zjY(U*$$MS;kK!&vShQJ`X{)M0p9>xI_ys-1orkx|aV$ixI`(1e4CV9xUC3RE}>kt^IK;0M(ykZ zLj+J6f1MApNh;5b#I~RE(v8J|>o14A#raC!RJqbuIcLO=X)hudZDe<9n+b=?K5*iN z+az;-CY;RG=9&$86 zl!%qNvnox36`Ly=AU}KMU5pIQB?tgQePZtQ=#>^i5MK~f%eSzC;ye#woFlfg3ag^~y$ky!H1d;YDpDz0hb*3r-q zA5fuC=r#7mJ)-KbEM1EJQBE;HPSNLs+UIkA!D@OCbC)Hp?fkvOL)dro62s7?yCu1% zZu#XP%n8mf8SsI!wqQrWeuk`DhyMyU_T!ttITV0_D8qFrAhCj}OofTqSpdrOloE*w zz3CI+&Q;+^PlA}T-l{*gSzkJ*K>f%-PyZGdtfXA z>up*B5Hrhi;hs1#{AH7}Dz`BRx7~j1l;}xNEy+#m*Da3ycK;Y-Nz7Ft<|nOoFi1yQ zKYN0+DKiQ$jn?J)L=#gZZm*pSH4oeF!n}Sgif3p;oI5z-f@RHc%{5z)u2h4;P3lzO z9CVQWT~lCgLNO(<@RcBMj69toClhnIIX#$|Iye6z z11YHc?J3-s&hM|U$)SZ{&3+)laW>@I5>4$cRcaolE!PZGO`Aki(Vk#5Du24Ip8wZj ztx=}?8%h$yH|~2xU)|`DmnuP_(u~oKb7U`*g-D2*3cKdi_zyrYuMTY~1kIDJID40Y zV@?SR%RhTe^c+__4rXqtr}edR>x{L0O6+RJI3J#D+lY^jbC@*Qsg!{d29d41W+Q9V zKqPiev=s0+J~25sk-qU?|9tW*Dg3JDYlHIz;bFCuWM()|hCRjP-HAVw+uA)R>Fo3h z)S`&JcI{tBs#b zv)6Zx74WQTL7hQUF0xSaN1xYhj@$arB_>q|LW)M54l`KXXE6O)SvsjZ_LQI6f~nx2 zq{dkM2VZs7n0zS!z#JyuFw-_t_+STkB)*TpypSQI5f2)~|4DtIGosk$WIRFqXwd;L zPj90B`HgF5k(k+e+uaU5N((;$S)3K97${aGpEibKKs+f5GduxtD z)h#W-b$Uau%=|xEGGKY;(|4qBV62ByBT&?DItty$)5&JQIwdR3LANj$IaRI6ymJH> zqTT%kA&^IK=A`Osm>Ocm(QGSBHvtrtXg{VgKeNNW0ifOw5{`m}N+7Lck3vcq_V}ZK zOo;@lV?UtFVFQa?eDfd8v8$;8f3-V&?w*V77ioy_?y$odvCdGPG@)}-tPz8Au-+M! z5yPhrH=IX)walR(lu;An=t*5MH<<3qv(yix&iBGa0h7G=T4wrwe0kiHP|`7h?DzSx zWhT*9`tszve&wa_Wumjsf_Wtx3f;@UX2Zt_sOYM_KUd&c*7!*=Gy~h(vFYQriC`v( z)%&f13h32pF4(SSD>N8VB1ayeK`R(1T_b5y5 zShrnSWlS;!*-nDjvySebi3NMC!d->I?H|2$6?@gqS3W2YpTYri6*fk3mc4T z?8rYL9QZ%r?Cx;K(D+5PiLW-UH%|Pg6AiBQko~pbY6-8DBXPX(3SzTZz5aS3ySWpt z6yYZd7bS?`xvrXB1oR%o5GxJMBOm=Bl-gOFPWp;K{;P5h0E%e=AUusHl=}zE1P4>& z^jc8y+Os8#l7J3+-KT*7juhU$^pUu6>kyKRKGV1!S`tK>Qi&{89teb8cvREdG9Z*G zJfJ}_wEL-K-I(F7I5B6UlVm09xQ+BH%iZsCrepKY^`PI=-I0AKi^(6Zbet`v+u2!+ zG_%~8wdJ`Pg}s=ZlHW)p#P)?_BphWB(jK5!i6ALXd_TVAEu5szd6vi|fHCFI(eE1I zSc6jc{{v3XF)+8%js#i)ssFmW2a30&5wgam3!3^3nRRO4k5oHAL2~RE?^*|Iwmyg% zlHD7WQsj%Y#`{<#b6d!`@L2-;^=62ltEc?O$CSS<2|wg6&foogjJEW>f_}+9HQ>AH@e1gE#b+~lAan+-F@DLOgZ%5XcX?qQBhK1%Xz0O2d`hh7Y-FjNpBxMuEFH3-{p#^`` zSUy#G^3I0XGmm+ah#FifeDE_|JoP0g_v}~gSr$&t#8?{}vat|9XJ!LzeJb9@3ZTrd zl9~k0aT~syvh#5eO6Wfdn^C_x2M$1)KF3 z&8|m6f}wEDyo9r_d1uNY5+7v{K|W{5^Omx~;tz=DwU+&{#%5_EoG%hVTTH8W$G?OM zDAfN}PFa1Y8l)@rC__J}_aQOSUVYt|8YFrgQq)chjHinY0s4P{K@`NP-OZynKf#6K zc=V@vuUD#+4mj)z0CtjPSD;4?wZtEP{HXjf+@^jx;vvWn(T`~rYHEx`_<4lSDWrs1FoS_#WR2`W5XwDGV>@dv@P~eh|49{HPjYSB&-EBCc;8DbcvarLS01 z{ht!1EkwT#qHEkXPvi2XgZfE_E$ME$X8*{ql4rffQxGbb7Ud&xl7(EFrC6HaY}iQo zqyzPUDaB}Z0aHxc%I>SJ*V(55anzH$EN|~~ee1$sob$#gxbo-yI-bUl`#1VSSx zmXs>nL1uI$FwHEPHvM+7ujo35LW?V6iDZ#TH9&A{9`9)dnik?EFYl$%MgCeEQu0S9 z89QzZ_O!fWcxEQ!pM*x#zO);Z*RSG5&^=*O4%NrVn^DJizl|$rA zw!H}Y;x)F9Y#nYk?E`+UhAV&}RyhANJi1lCivjYG5N$LLtU~WCKY)PhD;sMzRpZC9 zHJ%yhow}widH43^lL@e2&5DQnDdh~lSt;S6-iO%&{_C|unIAA9Khs1ID`(jfc4|rU zlsvo){ST<$sRcYwcd(bWf<`5-`LTBqTH*zzrZNfb(W(FC?|^YgPrJq|%>C7rZTC;U z;(bw8EY-Wy>9!x>?Dx%IJ_3&CtHPLde?fUE%G)(nqzHmB)~N6Q|kB)lDA@nZI+~eWj8|L(P1+sAT^5 zonmJOWL$;H-zL<+xf9F#U)(G&DLayX4`2&75A?lBQ@Am$oeG;W?>+wROghV}HET=? z;kg3K(JAB5TY}(@zFiRTQ=We$2!PDlMANYKcFqnM3V?CA@jx!beW1~nOe{FG>gCEDIz$4zhao>7>sFf!h&IMTu2F5;?OzK@~M?R^0A zT&nTZxQpkF$+#LV+^q%%Q>8Kk!@mSgx>dFn|LlhCZUsfL&E`1^Jp1Ko9EA$vD@Unc z7EUa@FE<%sJW0H?5h-j%Y<@>$Mk;D1WiejVc}__EL(0%BAI@t_w#7SaLZ>XS`)|>t z9PqE*kFo<^3?phk(WLW%4Eo^dNZGM7U33H;PGYa5Dx<(sCE)t0j#UE?%(xQ&<`Z>3s@t(GLPZj)F4SZZVk;5VQ6L*($? zM+d6~&i7818MJ%DY|dZA>f^Dfc5uI!u46c?)DLo>VB86_&Q)bl{v5rjgH<4FlcmaV zfZ4GUcB$fT(hUe#yLuFg4>dP3Q6>0_1#Yh}pr+C%wLN#7-EvU=-e#l#;y6cQ+jUzk zV1SD(P2nZgo3*!ey$)pECj5FpU%l0`PnSV0=}fdHTt+@h0-vK^eu^9*pZmg($Aq29 z?w-pp%owRsDP`=jVNB*Nu9-~8lK_4@Xu;-T=T)oZmKN@mnY28pHDjCrgp?cu44+wE zVgtTWHogQ1z1s>w2W+dMDV5(efUed-4oqx^^Y&|IAsUcVj3cg&5lcG!k*U^WNhQ9g zufedh2SVz~5d^f$l4v3^N9fKF9>6kzF_47KyAg+cDHysOcy`h3MxiVMOjmi<0Tn;2 zb+_abI`s~uZA%f(py)-ij=%EXsn9wjjtTw~E9vjWeptdD6(mN{hRD0B13+MTu|J8n zB%ZnrJQZ6Uvl=H)aFG02pnBd;ZAV6L@O3GLI`})h55pyytj~^FaMqt5NPA7;6%8mF z_pc&>q#aTjAolaq^5a!HZOP5_RYqX27teMnFc^*8bS6mdEYw@0bs+)XZ4IpXMB2XY zJ{Y!%$?OTh?|Ah@s2R1&l@uL&bvB5!lb_ry_!cH&7V$76v@gVv|lVmh5Ew zx!OUAy$wAOmU5F<{6PbL6t{?vBaA^xemB1Fpf4+0ms3K7k^CY-vbFagoh8zp=!rJ~ zsxsU0z}6i>c+O|4bqkl{y;mb1im~6etrv6}53*SUdpSNdrDDxbsLtm;RR2dY7$O8a z`ojSCiF+yF%=T|WOO)h~t~*IsXf_s9Tea?h-CS*IBvrqgcql`&ip4(Ag|`5o?i=$m zDsLATAX#Fpto+_!+|w&a(mmW&VrBxDj;g%(iC^tDC+~lvR`(jD$5#6#0hZ#? zCc1X~TRH=m0##qrx8oa(n3Wj)1{{tb;pg+kHo1}LPtY&+vZVwK+x-fjCuc@X+vN_#6ZRy z(o9jn(_V6o+o7XHf|U^}5zt9t)$h2%_-9Vcc1jv zczW`R?CZT|F(9C=B#^b!CTZn+otWTr(nM>qn=L?|HddCli*Y3>uv@1anwSHTy_$ zDR@70la7C|oA)SkBS5pN#xBhREH+&O@mA>_1zn146OscVRbY!nrJ%sL7n%9YvdGgy zx9@hSEha?OHZn#=2uA;03{vkYmmDjh02GJ>FMqhB4eISYJJ4`DZ!jd)2i9lWXx|oL zmf^Mn|GiteoeF`2!rKQ+8DWHXWe^ov+sz}%t?7Y5D6s&0ZXYlrf(ZaqH6cu6vyZ{z zvVqe=mo*LXZj8wH9>ir=ZJ$0ufUj?P2xLR20rgeN&=6%_Bz(%(H}Mr3;OjA>A^)F$ z=SWbST-haWqu~YP=8O_Alnit+oD1-J^6HRlBI1EL5^**y8O0vo zFwZ|nPi23A9}Z--xr=-K>LJVQ7YVSVtfe*%po|j`{tHYdLtM_QgDqeX4o!OJ%Wbr0@1g>_eukiO|(9~H}D_J`KP#AtyvQR|n zeYYy2kp6^rtg>q)>rJ(gRsiqRF`7H4s>paiYn<()Ew6b8Zfsw;q&2&$4?r*pr>O)t zZPCq+k3q*cw{SH5S7t7j@ZB$%5DY>vwmNb1P~ta*3%gk{sZpZ29l>)x0p7Q%SC8EwK35+hx4_(`5EZDa~gseDjZ*@yy$8US_I zNhSxeWHs}CYc%aC%5RsO(EpF7vjB?f{rb2fAt6XNNF&|d4U!^V(jX-)-HmjEbcvvJ zv!sHs)Gi%MN-f>p@AdbecLrvdS%%@>``q)K^F5#QeZE}2-%zJ6Hnn{gWGU8IPPClH zSmL9`Z8xR(;W*Cjq+QaI2VacLn#Wr_jX@`^OvK_y(4#8iRZBSjjkNB32%XhEfMch} z7a8@&a=$f+-MU!sS&rFbGtg4X0X7iXitk!&Q|a5@L~TodjzyQ8*t3bJFrNKt%^#7# zdf^)tUDPy5A~8*+jwlCObLx!)j*BV)e2^yL7$~m1OM%b8#`5h%$8-I3v77LN>prC| z8!KzY^(5!=FI6IvAq`;4oY%z&-3+k$St2?fql3M`223R8Z-K$4enPl)Z|m2Nwzm#H zHD^BHpQt=(jzY)PX@6O0uZaaZ?_jm?08%m66tt`gP%Q?!A}oynYM?d1Zb(~Ise&X6 zNDH^Sp#cOcyx87fQp{W99f8>@U=pHpYVaMFdO%i(9PC(*v>X_p!?mLZ;D#~9PKX6^ zG@}LZ+*}zf@cNsQ^o(N*goU{i&T9Yb$NOukAeRaMnte+}K&5{62A5sMg;1d{2Lyj7 z_l{yLp0V+&#{(&KTHrjEyHbpU7>O{_lPG5r2@Yr$$=vkuTxG%zIB<^Nz>R|S0H@`nuRS0Wf8Ny{A{tUTW4*q!I>b8pn<;-&Uzke?mJ6I|XOYrXEpcVlKg znO{Yuchh{euWk*gkf z`y!muXCk4enK*??xL4_&IEga2>)C2!fU$*`;A-wUe2gh&Jmi9TNryz2$9Zw*KZQvK zg_5f%-gl*7WfZyq`3I=Kcej@}cR=ZD2}2)YD`xnKA}{~Fwk34!#0vdVr5dATF^kO0 zbG3x9@C9?;D1Dd2L9P==#Muq7>5$BdSm*ml8G?tb+rPi?twBFv5^w5ec>I`kzG;*@ zdpb#<&$}H4v~C!@;)KT82e0$rlG(fGpS~VlIt(jgrpWxomQwrB$N52QvpiPH81vw} zTDfUlIf}8?yp9zyn0k>Ta`-@1rPvPp4L86NR|DT^qW7C-D1^}GpK+l&eV;nDFb6P1 zk0lo0&+TqJt8iG#Z2v=(n!cIcjtfoi`t*0bDb(4`INWqTWY|?Ohneaq{=QYZ&}amh zpzbTUEcUJ>?xhw2|5a89lFXVFr&1bU1WqccrkUsT{WQ+@>|5*J^LltSc(|$H3fNr@ z{CKQ@>txK}J;{AY_70QZ+%Bsh)3BDN{yd+w|K)I5z_F3~Vk&n_Sr_Jj?XyQiJuN$T`pp!c#yJ(sElb9nWgh@Em6HMlLgS)&d~9Up!9w7d}T zgkTpVs)c3)M4~F+O3SEGdxHqtftTd*Yv@B9FVz}Hz=wOk(8VUZFi|<6gZ+{w`z-fq z5#Te>AUvYyL^2pd6Mbx%}KB?Zw ze+@BGSb^}!fiT}Gal$dRu2RK#kmX)>9jt=+)BGK4z^CrMj1|ittrf{0MyLT zPnNiMd0ZS`GC}WP{CH7M*X@GGM^9@Rt+C0UcC7f%2POiQuHx&_$S0i#OhM1zX&e-0uG zd#JM1gFUSrqjW$_UrZsjYXhxURkv{UtR5741~1!N*e&rj764Wj+0sCGhX*>14Cvb| zuatsJfT_yAefZ))_>w+q_;j<~zo~lQq6`95R;w)nz(}Oz+*G8xJvCFL_6+tmZCTAG z0GKiAN2!Bwh~n(fF{;@1*>6o`af~Uhv!-%qKNtU4>>jyt@-L!GkoT8AaTn=N8y2wl z1BywmtHGhoMTI1+3lPGHnXk6(P=oFv)*YuR4i7eU0ernq;?Mp9%JjkG;yZ);G;xl_ zxMba_>QSmuNrC2vd{H3ACw2aYB}crrcg9EOoMozq++FOCt>X(Z9{Vyl_h-96ggd9h zJ;lKq4k;;4umyXL7>7liZ!3|3=^F6=hI5V=LWCiuy&_aC!UmSI-AQ97T{Dr7<~+k) zBy8CXuj+W?8vkrJuKjqxzrKBUxFl*X$8ozT`3&JCF4oP2N@hkRU(2Ffbqdm78X zacAG8^}dc()2}n;fT8QJ+Z?R_ZfI_4p-}-Q?91VofqV~UbMK{38ugJp>1bp253uo} z3>LBgL8Sh@y@0CQ4;XB_dxHDjZ43PrJvv+X@} z&Fpa1Q~Cs^)aPYPoka~V|0H@w0n-G;!WE%U;)t|ertZ6@O+0mhju0RJX_7^ zr8~`UW1&)F1+a9KXP5k!jnH3TkCgP9_hh8Zkn1;#_k`(@L~0H}RCAq{7#b3gBSVMklYR7`tVI0k<}&xa<*NfN;7EWG#lv}xRB`g}6al6?t`eT6 za-hwfZ-R$ZsTVm@@4ml87(sa6|g>?u>gMJ%zOc7ojWyr_W$(ZJpzNg#( zjNx>mM{I-SK&%-kugBS@lU^|npf=$3o!ADOVV6gcO>vw;}^27UQZC#Vj?fxXZWyN4>r{mZjqw~Ntuu0=*zhxLP z)IRUYZK#mtk>%=`m%3xkW>KjdU0D9f3#sZx(?xW=Iboy4$)&P4+(sd};BQIFvA@zp zxQ$#gXYEp;TG^~b{bKlcMVfb!>w#O0p*13^x?jh>cO)vd)olMD+0NNwwKVs_0$Eli z=`B!$m6fiOyfKyH(D0w&=pRJdW5j&-Pd&p}ozpiUD zg>-i)JnW=COjzJpLw|z2IdeImXhoh!UsRNPH(Q8p=7+8!GUc}OXl_N}t zihTNtBVO-9D4H9;HhhuyDnHwY`?*^cx^+9YwcnXgFCvvPdi|F+rDkGZ;rZ|Z_t4wp6{{$`?aAhG z`p$)Vm~iFgtndMaTgB%l?Qg70or941lY-GMNyBTO9^HQ79j*XeDEo%<3%J%(pkwm4 z!3aBbd_#G0lcS&r^ox$D?c`W6;=}xewXa*wT_>j@c*nB^c#SnjuSKb>($O#6D_7+e z2h$l-#(DH2)GP83=CY=iZ|-O$A;oZ?j}ZELy)#+Zo*?IBCVFdn#2p9ef=iBTb&O}{`&(q`N<`I>G z$>LN6@z&4(_%~@fk0m>@hB@XcIGd&gzlNfi7ka_5PA#?UY>ShI7{tyL`l30i*rY`# z{bxgZtdQq-nA0dl+>RRX2Uo-I^$FaDr1V_SH`?qsmeucl~cE?ve^z zFLD+?vt9;x;6>TDON#%o2VTQw3$t8>SfwQf0!AV)B~BuE3Uw@P7Td!7?D6M{bqgFNl*tE9H z$}K4e$~ka*=OJ3vfCew*&xX3`OgU(kWnWjyYA7>%`@RsqR*BoKsW6M$W=X5O+@g1M zm$L?w>+uZ*v5znOczsCFo^?Rv8F4v2Ud{>LmbSde%h;~m=PM^3X^Pbz?;-+XW0Nm7 zn;C?-=RjOLKpgR@?l zUc2YVxA`b9If~`s<#cDx#jAH0q4mm&2+BaS(HtBDOPL2Qq9Jc0)&()g0J=`bsr%Be zcyAU-r*|mj%a2-O>@rx=_E?3(vVNk;v2H!o^$r$hGrZ=KzKxYHhZyC&mt!(gbuKYV zYj?M!ZqXbKxgbCB?f4a{fQ3cMWy@Pd+^hWIOQt};-m>yNlyhI+S18)7?wIxT&yMh0 zk4$65-*dvIjWiE7ABzPs@2>C-$2l=+ObkLVxgQ2-1h3&5Gv#|iM|;^P;wpU_;pR zuDs+Rg=5lVF)D9ep4{-ResAr{;fb%vTKpB`VJ`hbh*d4z?suHy=P$z`%1&_20Bb#5&G(9wK6kV0~E?q zqAPf}T{B^hT)>W`xl)l^kukjJ_7xL36a%iE?$@xWEzB7ixQu<_jTKWVo17yJb~klI7V>~cy6q&|VGdR+|D|$1XPBeI$dOeGvnX5?4f{S5J1MXk z0)1=s%P(kG_-kI*s%DLv+ozMDr=@OzQY;T5la>uf?Txt}@382ch>vD@DZ*76&of=2WKF*t2)9YP7 zz0O*GKgdVS$AojlhP;GqmYk6eq!V$M`uNzcb%uO66%Ai2d5f^NHCMXboiH5C4wAYm zUS4$00okP5Wtg{iV!Tu>Nk*`9@*rcX|&VjsK zt&}Hy!p03xT00!SjGaeAFP}yqe{3^&tK34{xGC0`Uco7+3HeAG?XH|@eR(QTw#NYdg1Zuq+>T@l*WRoEAfScc<|pPD90=s-VR!SnAG(dX&O zeRSF0u)meg`RgLqlj7uTooy7({?wjbdmewTOXXN;e8wd^lhsh{^OgAJry}DTSzuby!HTtBht6J-LIgf)hY9i9lhCzqmO^Ge`t6Yx`E0H_tv8=(wKoA8^ zfY;lm1MuM8rJv-}o*BV$_fzQ|8S~N-L)}6&7GUr1BUh$nt_axh48@uHQvgH54gB~c1@%1=y zc8CbP0Wtf}!ay)Rude+>;8E-~nN!^WwgfBPL_sRT=tr5pwxYLaeR_OiY6W+o?s zi})q-;Xr;2ogYgAnhVDp17^B2nZ6Jz8#Wq6aiaAJAM6jvz^((zFxirl->_5$&da&5 zi&Oa%ZA5i@`2J@du42NUHy(a>RSacV-}Z#+^1hsT%AFZHJ9Nu|3f-!*y@$K*=6={6 z(%1K?Evf^M4m=Umb7*9}Q&Tr9(83XrJ^M~l%X7EKl?v5r z@H64N^-Djtl&+s&idH@MO(i3kG@6BPtLt?Y5if%JMjnh9kFV<(x(-Xo7)t4Q*IWwH zJVY=Qm@dsIHjZT=kR$NhCx)X6FwZ z{>1^(Z`D^tb3g9dGTxb}lad_8u-zVog^6Ip7iX6{<;70Id8KER&ARISFeC#evOJ|w zRgHW$Oeqd75;CRUl)pLxOeR9b%i0f^ESsLCSt{oW63^= ziJ%TL+APhc&(ILAcBpb9`USxgtug)>Y@{MShj43$kM|=)Rs7Cnd5(%{NMVWhf1}g{V5aT>M8|wz-7pu%dOq@r;b@FHs}7k*69nsVXbq}t!luqNXpE= z&4#0Or5L;vI0xlu`Ha`?wxKklv+SdZ$=N6evMxKjIbzrn6UFmt8f{x}&sq|vu8&{3 zQ%eGR4rZ7llR%UkGX5I>Y5aRhQv0h7rftJ{TdEbF|(JLir%T$&9G{4YYHx`yLV&GxCwTS?jj>5P0s zv)>h@=<(tHLdb0P_UMLREUD9~M0i|u59vA}MjI0Oel@F|l97Fr6?^o)RzfGizbp2f94@w0r*1xbB{+X z?GK;v4%Q;oPO{`7U*yxImp~ulCd-L_`87u71kA|ty!()lN6pRH1QTZ(i!nHvpb|Wh zi0{7w@^CssZ<@~LFGV=p)d-RJL2+Klvp!h1gcx! zpc)`vM94h&FD+wAw+tr^ysB{}1Iof8)_S}4MS>k#je3c1R)ZXHzJ9jZ8 zw=_$4ud5th4$mId%ADO&8+6sTtIn&H%ip4nyR?8OfTM~MsO!RXn}vaBOu2scO`D#Q zG##-{(CFfHF8$X9gFZ+-RC3sNx)4~2;u4@N-{fJQq2D=-IZ_P(L?N>3XJ3LMh z@G~i2ZSFJ_>98+$S_0bxc`lA}*ss1=$*{`N)Nr>ZXn0>ABIO5h!U7~e73p-oCyJE# zM9g7r8dW4oq|%+RAN>v|%6!*|eZUugA_lJ>!WuwaEZogpFf%^O8)oH4`d$zHn+w^g z0KQ(CO;Vd1s-UrWyuO3a~)HYif-n)kyIiD$5$TuD%K4+#d z*r7b;y_!B@GyiPCDfgAu@R<}GSQ5V8x0YH5d@hVXO%O<)%10~~+dn*+3%Wi?sfaEh z?Zkj1ig=?Q#51fW`?u@mozm@a{aqJpVjVrrn^D4i^pSM9L#3(@X zb|!&5O*>s?n@!lMyQ@XNMUzF--VbKyu^H^r2+G$Li~A?o#|e4jH5^J{lj*LAoz8P) zB(~Q8to04TDjMA*6e?X6$;MxlfVQ9x(82e=Txe#7FUe^_G09~0{~&75EhTo0Vn}?W zyV-O_!w1tV&-MNcjEp02(SQXsf5Y5(wvQTxmech3_$Kj6j=*x>IPt$N!8 zojZF}eOFKHLh<`$8z_vlY0mFxIk= zh}J@U%o#DXwSU;_%pr*BvnM@nC!MDAJVWQV=mV2H)&p~HcdY$t>}PcmRr<^fd9AV6 zQW-g#oZh0~htJuQL$NgxsiB2H6{^raNv=h}rv#i+8s6u`@wzs&u><))29&D}sP#V@ z=#3F^NmOhW@D#j!Nked1MepIEvfHSO7j%Scv4gIxskEFYX{uPvw~ua~aNjj&19D(1{;1DyhwqgI`&~fK;<1f=+lC9p=_EJu zwb3XpXBie7+_;%N|LLX+{r)0^A@;G|#7n?M$l&8~J&E+X+KYB?ldmT+#3y&Z4^YG| zEe=|Uk&&1*iDBuRB0R+R;#oe-7%aI6;)Tyzd}TE5sj%1@ns&CAEKQk(ga?>h@$Lbv z;vzg{c+FS#0n1mORg+p=v^@{bFG@8O86lS*gB(`z(ey(_?%75sY^T|=q3@M$Nf`me8zojXoNIM;w7ZkRc2- zgP@8R^wSS8`b7)@7vQo(W86v;Mj-x6a@puihwi`Ej(7QRa_p)D2UfUi-_5x}dzE;t zv&)W{k#Ik5!(;ALzHB}gFY3E$J8T)U96st1cM*M{jzV)``CFF>zh9NliLfw3JUI!Z z-tER@{T^~7mJtc4tWyvAG0=H;|Jw*-?7bEiWCx1f78*tW>+^i6%0Mq2w{j zaSd>=93Hu){@D`0x!f$R`=Lt%M4{hTVOM=VSFo^C5&MiK!CR7swR4oF?3g(le-I1s z%=xIx*Fpg|r&9&SgyL)bipdeJzOs=r?pP0P0lI*Fg&asFDV}ja0spR>E9Cs+X8w=G za#_*Y(2)xC^4_{(Igmp&)U3mfXq=*TL#oEJSnsLIP*X!aqbUCi&DndTtW3N&dO1o# zT`xC@DDS#Oo^Q?^n-$#mlkF9CyP&}xX&*{00Lf+4l9Ry}urO>o8O=0p^+Q_#83c$& zZrq$!2E*{a6?6(jB%6dij%o>8fBYB>JE>%d1NsJYoqj`?&6kHwK_k=8vF-CT`^Df{hvxd!CBM|!t~&3d<0c`y z1{vP(@&=`JAQ6(HD1|OzR(;xryaC)*sv5aQt7Vt_j`e9*Dx#i!0VZ+ADecugqpuW0 zR!j1;i+6RJ7Y;N)blV*~hC&MAPZ8*GYRyuV&JnlO&|*`X0*62g`K|$RRH{3t)A~hs zw!#h!nr6V#t-ab5ZQnE+rhE;vk#Dl0f#uvjqE6}-S^G=S0!JSXUvQ#UKfLH(=>K8 zSK^@}gU{K>I^V~?9(pL%eg0unw=*U6(UbLCI)hape%D=m!3W#PR4C)sny^L>P&sJo zQ<>`up|Lpaw+EogN?Pz@mnF-;+LK0Ar60|BF^p=%o+-q<8y{vyE6BPA&h+FHsVL~b z+0*@X>DyK7-{k{E_G%y*XYQG4u`^OUU62;+;ZP|{Sp4AdfP?y_{=K4eiaPlq4}O#+ zI)Yvg$Y67hmlOSIc6aW+O@<3>29ihYyu_HiG#gHtf5)t<=-6b$s!)_4PhQ z(SqRgQ}67<+dcOUj>g-rg5k?{X~jdag)J}s3_Fe*?j&lLMPM9NA2^LwiE(JGzqsf% zG=0yVeqm@JU}O|*fmUj!=-fC_cJIwcur(!Pw^cF*Qv`a8W9^QNjSuH9>c_)9IWRUA zC{Ky-HM-^^dp;oVwsUVtILaUPzS|1#@I2Y8CjkWwCPFFAz!0fGHViQ27q1IrVg48C zJNlSKCDs9c#!D=9X+b(54JZttO;BS$wH$|^9603s&IqyJIK5xO1ez-w>dh9TTV=-x zbcy)_>R6e!dgKF3&n>%ue{lBCs#hp6GBK^-2&`^Kp=5hrGgN?VLD0SQWnYwKX;mmik z*@+E(qRdKMjP`l&H`qKW7NCPG+j~h#He^Vdh12tv2Q{Se8?qB^?xBHnZ8&>z#Cf*n z+3F6CX0#p6UK#f}MGl8>&C5)%V48*w#b!pke^*6ER*Y9<{3kU2XZxhNJ^D1Xx!VFj z=0q=O94GD*GRmzDq)l%5FM@$V_>r19C*I*hm6?yfQ8X5WRZ9x3eO+*6HP{|i5r5vA z95pn}vzB4GJ94aR<~{0z@(G#1_#L@5Y$IkNUOf~yGR;}}bbs_+^R+>_so410J0+OS z+7MpbQ0m$~&FZma)(Im*nqgHtk@o6Hg=E%NYHcQU&_!+ozKG!AgML{J$9#f`*1vwx zoa?8t?;m}QlCh9zv$ioqEYDZlF})unvL=_%H z>Y3IwSGM+|5-7hBGMp<&Mz(mGN(;1Q+z9;W9V=~>+0`=>_rcsfxWub#p^t&rCpSFzNPviqWNr-;- z~uqN)k0S;q3XlPi(m?iAL*DOf7yE`R*wRtjRVBQ$FLr@%_=gE!l;m zlZF6SmA^P{nm5g7vPNWjXC=K(wb62B47abTF&2j9#1~RrnqIzZC}iH@qr{xAzGA=# zjR`Hp*1UDMazj5Xk?f%u#bYedsaR$-HZm;cinQ>DsBL8PJeO5 zlEhgy{$&Z6i=&3PRU}vs)_*RU4cY1`8p;!y60{tXuz5O=1@MTQjs&Ix7fX>d8&7og%aL7E3MV`wL%fd2Y)BQSP(yKA?@1c|xM-$N?NO~5)){tta9M5}TIvK%WI z_B!ZRyg~4-303ryY93A8;!%vZGfioG=+$lgEU?5LIP&K z!uK}$D&u2cgY9Xo`4M8KPhvp~!vjDz%GZK- zQ2Rhdu3~S_el9$n_K90;D6{djAUbt-TJLx3h~Cc3rj~ zG4jUo@B@mJd9)%uT~UOw0^T*J7nyv`*C>1}M4wIH?2CLJJ%dSFZduq;J+ z6>(Yo5Wh_5%W>n{H`9l2fURT^`EifcX-p#8;;BGYN|3fEB4KEbWQ(qKFMo(O%`>uq zd&ePXmF3Jhn`5=BhVZ1PV&AlZ>S59~H_zUj>CRu1$02H;$P}3DY@Wnt8!=&Ad8qXF`No9bRhS<8(%V!FCHQ}^7Y@%+~un7!OqP-C7)A^mIv6*&!^?F^7K0ZhiT?L4=eTh zlV6URd~Yq3oN%IIg}=cO)6Sshejk8iMj5)oD|u-=GLp3Li*{0}^&=!QJ<^Wv$z98j z`rp*>17F8;t5y%MULt#x!xUDYn$UBF;PdA`+ZnQEhB~31*`5C5eE_zS5@2nWzqx)5 zU^o$*xQH{@paA~v-hQL&3boqWub`cmZKMsgYhqHtBjqc<(c)I$LgMNmVi`C?8bR%xyp=LsnD80mMEN z7Q$UWM-yHYq`wy2;|>7p#{K+2733QQXe1Lq@pwkh8j^l2{s7@F^vD)z0$^h;ZO;d* z;j5=zv98A>UF4-W1O3nWlNed3;U^|ttMNo~2 zpEUr34tg`SjVlSr_UY|9ETXvV#GW0#@D;YG8_lkzCcA3)NwabHJ^vQqWb@B}fkUvb zzzkQ>Y&7rEg@i8Z`uAGkEFN5_f&3Q);lO;X3#YMr))_~31znxNIK|(EbO-r{@K>z) zD6curZkPqPNp5vSr>-m-EG;*I_B~sn`!2~X#M92!u+VX~$Ps7D<0p}>ajcuDWWW|f zf%sVkGSve$B+OYst)9-6el%0Mxo-WZ4bai#5FQPq_i0vL65juV+x5CJ;@)?mViVTP z8ks0E5F_bEj|xc2Updg{3ay@s62==YfB%t9@~yo%wWwp!56Qox8;X zGrqhjwpfJe^6T2qd;4V}pL3%~@{ND|m&J-13pt6vsvJQ~3AU>OWiJe@WyB90_fbOo zl7RMm{K<*sJbFhvB0Z3D{)VXB$CG-oLuw{RQzNqC*AJtCNEP!BKPtkDf;t<&tn9DT zek8B>_&tJfrMQa{<}hQC1ZC9A+DZ%zpwM`%j=w?5edZ@GwAE|zynP9Xkb`DXO!)~! zjV8;1Ti!wc<5so_{F~PAuPP+foA(-D{il~(?6vytn3XIWemwDA3l}%b@A+L2u{EFC zRr6&Lq%{ip2G85WggVgVqGA10#X*8^tp}xaF%dGQ?t24qkxv&zTzGQQW9Kupk;@yL z^HM4qg@ipcuoQmA6lM_nkfDCD@DVMD-%mn3BCO{4>92yXTKSFs_8;x~ucHKjtbbURnPW|tOMgt+kD3NYdN$jubQtuH1Kim^6l zEc0>;`{NJha=lRZipf73+_~;qnxm2H-e}Q;<30H1ZUEk(Y)4cZo$in?JXBq{N>C3A zzm+hX<&*>nJYcWmI`9>A({KJ37p8IY#HcC$ud`{5TMoHyok`x~=-=a_ zTBtu_O%*!UZjP{@v9Q*6r$c3znpl>MFHUXjYxE5`pGQdE?b1J9GQmdWi7?zx*MzQO zh_}3xP!uXo+#YBj7*n=}iimzJiJTgQtYn}`jR9_{Hk_Jf+^Boby|H$O&B07gxiN@u zlY!Dm6FVk+dcL`YoS$!f%D&Z95dfgC;NkTN04D#7`^Bl|Z?KAeZW&!7;`PJ7jf{=( z9>`$wDB>3}qh>8@h0C~?A37F45qOI)Db{L%d zV(rvRK9)vg%1Z(uh4Of=4Yzu}JV;6i_JT%ft4*&=*uYt)^Vf`QhRMD{Au{d`?MKXi zA}aCyP?KJogS*{2yQbtukVI+|;}p*Iks|*P&|z~qmK+U^SrAiI2SseF<=Ivno4q~7 zklOf)nN0@B1KE2jLSNBa&KBL0SVZ0J%8Xh+7o_f~I?K6dzysC^^8NW2&lXt!2dfCS z-g`*a!w!hbjpG8Y)YqPs$`l6QNnitv{zmG;oD0N<#F8s?HZRtA6@;UjF*dKjQRs?TJlKl0Vtss97DVxf=Jzn&-v zUoNJI6BZCc2@TM|&90->@${m2QMo)xJ_!X51-A;00?iRR0B#`u6nW4>l<(gZ|Fa?q zRa(f};bhD!(;~QdZ{h83G6_J0rp#Xg8^Nf|eTbR6rbiFco=^q#4dOa92-ux)+P-S5 z%Y%eB_YDTy4(I!z6prWM58IVb0-@C2u6ZlRQNLFd?J$;P_^!}sas^3Rki4rb3OzL; z9R*TD>E|3BS&4X>qk@Ou)SK&AsZu!bBS@c|c~o3#aS8$nMJ_Ns_$UO)hpnk10cUOL z_l#4?bB=PDqXy$U3$aDR&uS8E?HPZ2KXu{*Z)Q;!agImMu*0ilTaMSp^!q5X?2x>A zV?|#<>T$bDQ5eAAQ{1CnE-jumIWFz-MB#aV_M_Rh87Zn^og2t_Az8%wVfbzD+2wBZ zk$U(tkl-Xf-POrIJ*<)?1c}}WyEBJyuI%{Z4%<^N`a=#~Kc{-+3#S!|xa_X#Ghu5 z8J1EfgV+u2Lh--J5I_Vpl?po7fSio2)QQ@r<%#fUpgkE)(r$<5Lc?dj#QG+4^2HiW z%w^;_`3Jb*t_1Z2pn9?A_9JRFYa6L(S>#?Tgs*pmFtdia=Db+O^iA1hBm`_f#a@{IBYBYcGUcZd~=H{XTiX^J2=K{`DCFo@mBHZ^@ufpM2Dm~ zK9u@V%m|yMh4~@t5~F!&eOC#=-obx%fB%E^nziN}mD1 z_NG8HErVS$Wwh*Yixj*_7XI6r8hBpiE`JIa`<%(2{~e1)o~-U1nMBt}P@C7MwV1cW z9j;wf-0xSU!o2*UXu+SDnz@z{_*cOjux?%u*M%p0FMZAav>1bkk8?yH@=%|&rX=7? z#IHK}c(XjM6uzEoZbyJ?-B+cKX;|&mU27El;mtATe*-WKsPtIe>>2A~Y!B#|R(ZnY z_B{>1eqwD)Ava_pI<6obR$H?nv)|+ZDjLqC5MEfMBe#6r z7-R5xj#54=nkjt^8ByLAALW#@_jxxpMD{7Us)g8&s?7KBun zb5UQ+Wp8y8iYX0xL$QUm4lpd+tw`#IV8Bcsv|)g)idkB8g{SN_^XNm}aQ=bzzt|9i&`khK zz4@#FEGoCe=K#DZ`!q&ncm?)l>u=o4WlHm#qg1@G!wL`$g`VW&xU3n`d2dT{lpa32 z5Z${Ur63TX3=}YI2zn>Ld3bZ*P@`VFP$tL(q=eJwa&WRpPf6y;w!cw`S8_a*j*rPAFuIl76bTR__*8qj}-s%MV z{7r^%gjCM+OPM3_G1E(rHhlIr`d-ElAXJqyjjx- zmt@>gDo{0BPP5=>BE&|D^31cR)Q^=Ihisg=-bzY*D{NNBjaV?6nP6Fo6=G}Gq&FAP5409vo;%K){(?Omf zcJ4hcVhga8R3^k!Wewzp>?|kTK@h=L$T3& z2c*P9(AF16WDSW~Q~<-j>Q_JyP``e}KOlKoYqH|@_iuA7f_txH`6@3?uSzM+x2Lth zXGFMU`owFowRca;!MunFc;9-L*EAFVh_N4g<0dT4IFQ^v7pIhcxw1+(Ka+gld?5)- zmWQx{HuEe<72+A&5@L*WF6-ftbxM&S!3% zv4>w_Vgm0r;~$mh)tv?vakI^p%&m_R&=sbdN9jt$G_YMeR-!mH4BHb{m;pNaX-VQ# zIGw@9Zy$wCTxYwz-lpbntuwu@RRtD2&hqGGALVhKqj+(y`XDmSRslmqR`@ z%Fk3gGGRTc$HbudB%S>c(lR~~Sii;;j^!dGn>okBYT4pWu@oQhF&|Ab<>dn-tn$z= ztgv>KA2D+Pgu9&WwUz0+5nL$BYNX@ZQ+BUtVrLrivvQZdB(^l5KOSOCp1+=QQ;pC1#*Sm?uAz&N1!k$mOwIh%wdWq5@`iHp3h4_IcM|c8w=4xBl+WgI+ z4J9nMn$8tZ=UXF(6~33JYN+!-?XTL!{T|cMg{@q%Q~1!nM@7_|>A$7$e>8n{R22XB zHyzR;ARSWD-JME{(%sUqbV{cn-AfB7-AH#Y-JMH!=QDo3zvnLwhXd@qXXeH$?w#c% zb`e6rAHN#<6t7uSRY#^X?;6QApIlOGC)dckV@tukyjw6FtWmpf-+s5iF4$T3@#UdF zuaL&QJn3;O?&S;4fgHzA9=clWM)^mL(cnJ2a=jv&jICE=867pr8-&+q%EJ-ubFm|8 z=ZA7?&I;O}Q>B&_=xV7Sp)?ahwhGmFDc0r zbL#ia!ba=A%IJXa&KGpqo|h~gW;pKN!J8#SytI9Lx+vs5dL2S=;etE1#UD}})KKG7F79TsWBK76qJIX3qS zUgB`^TF&D4%c>tdCVdZovb?N(UX4|84BFCKbH3zGy0@u%jA0}-JriYgR5rUGvKLIE zK+L6D(d|(MEBE1P8~=syYHAz~_?Vprq`0JidE;{tJ*^hVyMQZS-_#)z$$@eVF%uTy7Vo8SafzB7h7U*u=C|!!!*A3ku(o zdfvUj$tug`X4y$t&!Dp^YGeld)83RbP+eBP_7^RBmbc+$JTF1b$q4DFwb}}z{k=F~ ztG^L1(z6WwC)vn+F8$8x92>A5$~oO&G7cGck3^DqU;>mRiN}k)+kjS##1`^xhny_U z-~3jG#WlspiKp4zsH5lL1ea4($S>>P5grKNn!ftoM(p0S+73IrAwTbSNHPQos$VWM znRU2im9Z9~Z=@2icLsI|q@9EFMbHWPkH40gM#(U zH*a9!hlPebw!=O$WKTG`S`&{^L`aP;koY$hT?kfQ-$?zJd;^Y3?##2RUg&O#Y7o6B zyafav8xBtA7aXpkg-oBuMZX0&N5zaNpdP*Eqr!AtR`lkAu|b1alZGE8g;oMbfW`2- zEQvxcW`3joVu69ST)AzKT~FBuCAD=3lHr z`s{;2lw6xYOjvvK^sHr8WUqZ+XH@En)iUe*#@5gfyA4TkDMI~Y4|vV22kXKs~UEB-exIM=Z9n0*)4CUeRV5Okg1 zldIel!w=4w@AiT;vY-ImqQG`095m+tc#_okogrq-naet5)iMi1ZB>j-&OKBnSj)xI_}3jN z90obt9_{bPWl3JmRon?>xuzJ0sy88T&X>uUg_I3ZS&=O8hTuUWW3o1%(0_ zei=iE;GACL$bLLIGaQciXx-+)G&<&sS2>EYOab>&o^&18it{JU=DEQcx@6kn`9?RS z1a+KD53x7b(&*dP>e8*#xf2c)cL4M~?mmnjidlV_WBHXI`8)Dt!W{(L`^26=nqGq4 z=O3ho5#&HR64sX&vSi2q49%`0#* zlkM{E&PUznjk9H}c{{PW@i5dZq}xH)0!`{;Fl1^-BsO`yCZLhKPXHTcn8eSraORmfc$xde}Pk(Pcu_1sOr0W8u zW>er#B||By+M#oxTWhm~^1H?ZNSZj;CTvb~bFf-Uh+`K1gsYBYO26q4wF#`MI6Uy4 zIR2Q{2;`k1MzeXhajnXGFwinQ8zi>Q@>`|@(>TIvLu5`* zM=j6|yfzTz#V}_WEsd=V(q!N}09?Pj{gMJZSgT)(&3r)ow?P(u7G6BSLnPWd(<3I5 zf=%s(k+}4Mga1I+CnoM+??(_&`@6@*7VQt@@_!g)Rg(vG&*cLGi}M4{+{Tx^YqUcx zw%L9iCl(2clzaXN;&^qWzGmt+x%#s&47G8UZa;7k6l%+8?vHawsIVIg*~z}`y#U&c zd&%hupit-4-cLwyG74C3n$5|mq-@%&%pYUYJRI=tvM@}?iRaAyArmJwddor8N>_`f zcI7%o$+sB!#BT^~kTJaFu0`{yZv||X5l6aC+qFY_33J5D%&pxMz~{aw zI}+gKTND0a99mA5pRe}sNo>I#-&{X)WCEfi3!e&&+&8^?V5KY3)_-oGHao_?%nBTRbR`36inM0IIsuOhH>J;PuB2~^l(O?oP1S^D+_(QO! ztH}g?kzj1l8gJpYcZg5Hiprz-H!H%2y5z>Um{UTLpvZuW#n_O4o)h0c&L_IQXzH(4 zQstagze&vfc=Bxr#rz|uU<=$mjFs-%Ci`|`imp^NicOHLm!HED{_$KbX*zVFM6 zgJV|-I;FF2u+US9Tshj&@Nnd|w#+DiUjV%NF)>9;e!=gEL8={CGyNIKR+!<%1hDW7 ze_XA435ub|5sPMkxzh)|+KloKkFvB2t`crvI01~j10%IN>(Ezew0+*(m}+lkfF&+i zlFexw7)$k%X#z}79)XY1ZtozgocKWwshXzUCj1_M;n#$^}q$O9q zRzKocF{gVUi>#Fk{5NGdzi4!|LUslS2=dXiqBf1nL`Egc8VQ<@fVwM=rYt5lJK?hH z+fyV-7ilZ?#ZU(Pf8w&$YznJBCDaW)Y-{-<)ay+5xGWwjJ$wW^(E)3`1G%FSi3Y7a zPa^p>ot|-rd6wW==3s4ZO+Y4pIYRNI2pdbLjI>OBqiR1*<(kA^BIkJ4)MS!?J-i@y z!a;dU(aJZQznY4p!i-H zF<8TYNfq%2E8Ibd3*eD&I*a%=BuJKayWpvX3I9Jqf^PQL^4U0n&IW~yQl4Bt?5)38 z#@&(MHtL8Nv@Iol#Yn~IewPr8z&d*SJZ%Svr3MS&b&lr_pEgLcLsI~&-ALqK^7rzr zh|QkIiC=DcMeTY$<70O|_3w3+=z2i{=HG2I`T`8y5LOb0jb^^4t?KrSB!#9Pc07`2%{5&9+UAjJ_*girwi6 z)q+w8CMjA4?Q7$V7>Y?H@4n0IFx5t(>PwnF@M>_Ncv>?V#289mc?|t z=dpL1jI@GpZ#04N`YPf^?*FtNnUld0rXM5-HW}DZgs)Iu(<%Sf?DYOxRE}o0$F6jk zW{tGJd+qHUE})H;uZ>RQcG>^(}1&FoRx3c2WPp*4C4j3)R z9F_GBO0z%)Kh=T%g;<|Mo1Wlz>fnUh-y~iMWA8ll?3RJ7hCMyRlcGs7;MWt&pLD`z zvS%gaer$lks4clxJ@h9+7!8uVl<8hz4w&41Dg+V?@CMU3t0{V#@WI{bHujxc9J!<5 zr6Nk#(e<7Z4KstRjBCuZcP#I7qL$Uu&_ZZ&s9bobW zrh_PxlJsm7rMz{M>Y;hsqqbE-9jR+FP7FwbCO0l>ZQSsc8d<*strYMy60-t~(i-}#V`zuw1dPqgT;JKUV(eEFXP7xVg<=*_9z*?_Dh(%e@eF#!}U*EDP5H6%FLjQLT5iXBN27X~#hF5i8DSK)kn zX;9I^-j7B)>@Yj$AneiZh-&pBLAjkoiCz}vExUIc{0@|6f7jeN!~=4O3+3c?zp&eb z$f;K7rqx942mZ%(j*p&^nb*XO==wnDqbkiZEx3EP$*A&aSZn1*HavovG>lX~M( zjJN`{yYf$Obomn8H!L_l4}!oEi*1M&xjAG@I=j9*$S6}?+k~zbESJz+GG{=6jfRrG zSy@%@|04hu3A)vhT*qWytfacXGMr`WfcndAyn(K_n85YzPNl;d0w$@Ji4BEc(-b0{ z#Fnbt0Rw5Q$6ql7>P*9$m5wDg-Zdq=XE%8IjLJ3R{!?Msl2(K=hDssW&VhXixx zjQt(;Bpe;|!W+64oW5mkf@Z{BK{iPz^bBmckF`+tfLzFb_l1O$jqc}*3C^}on`ymu zoF^-6wJY%urXP3-P%zG4hN(;NnM%~gE^z%hdg1mqO%g~HU(4bGyk}@yKbBGBx3&HK z#k_%0j+7a(Qt_E%PE_e=9znZZ%u2uq`Z}Svu>T^!_z&~qtxKM!A|$h)E>F!*dn9+e z2q|`0()cG?C1#sFC!WevlJ*rL_Z#N}y{)DIXI}D|C&Vl-Xbjk(Z};CHjQKcQ-VtQ{ zndrL{B@hOtGyGGr2n?-VTT$WX(JUCq?$#jyO2zR;Xjaa0alWdp#LX!Gv^!Mx^vtgn zuTtt|^IGSG!||q@z@?0FE0kr*gNqRC{h8;Wis)f>jPh2L;yD3m3+hn*ex|i5S`a+l zF~I8=HM1cdgVc(XnA>E2|D=2lBnro)_d;9OqYjFjw-r^idb_=sTjtXw2?4Np`L4Sy z)B2KtQOx=kFzhSN-`ThFRzm)1oVy`oDx5}~o})M(8MkN>5Buaci%a<*PxNnZKd6yT zTTZIqBCj9>VEu&j@uv`H*@!k9V#!$dyKIp1WC5GTH*}R$&n$e996A-D^+P zl)yMIKfmShnP5O81S8E(GIp_U`9_I0{q(h~=g8j%`XM%ZMn((~PHX`Dd!$T}HvntR z>fgu`2F~ocE-y2%0>Ci^*&46uXOl(H0IcZ9dIpS2+hXX7(7dz9A30N1TLNWU?k12e z>ie~4a{Y#UN}?Fj2xHAGfi=Pk{Hy0(K7eMv)d}I_qdg*ouh*@uCDvHw^cXTHgHvls z&|ltuma_L4dO`~$GCZ71l7L2~u$A&WS( zbeRltfVY-D4B`i6H;r6ZQBR!f1vDo#)cul2nO{xcnGy}i2DQ3v5Y+);S`EdyD|?|3gT<5zN-4*dJ_DiqZJ~~RY5CRgKdPoqyAvt zE0)0lmhB)IdP6oS`46GDZ|CrVngZ8yQ$&B@{}ZQn%Jzj+$*&_h{A^>GMKQvOKuV=H zh@Gw)13lGaJ7Y_NPf9$(8g{wlOv|Qf|ECh48}HbvC-OXD&q^aCGfLIaA>@Hhw_h9(O+?PX1*|(GA&nsF?*;|^wToM>;JtfZ z(Fs3H6<3vbH?7ZR!0i&zt}T6OG2%>kh84@fvi&JRw?V-1zK)tX&r|DPcd*s2(^dAE zeFd!GsoCHD6XN#r*}$3zm~l7OtUV8U#4muP0U0!n^ajqaa#I(OsYr=Agn0=Q{Jl#C z3eBU}DO6U@u`s_$%<3Pl1F_pYM@_7^&p5g`oCM5r*eK~iz0y$Y2_HX%h-HP_cRK@d zsfVd}zyQ0IX8`1<_M#0Qk2%R}6_MoLFfH1L-c@dA*iehm@!dYQ8PowRxS|mUGB+6Y00VJaR;elm#MkvY>NK* zPs#gC=qeTbFNVy;0&c}58>9(64x}LaKuQD#;3bg-3^&y=Yz-()@uxGF2Mvy0bU-0E zSw9cj`ZBI`7CbpN*Cd?H-k3O(P^I1PKi_K#d^o7XAY)C87!$vHJdf4QjpRcS!=;mJjF zm*VH$QY*+G8*piJBHnP65fcj#^0-yjv@=fv?d)`A|#fllbGcKHe8O@mm-52OPQskA#}!hrX0`x zu;aL3gb_ER@lFFP$0c9HW$VOt3EcPvhmtY<3UMFs0?mHIJZpuiBr?lK1s+@)v5yeJ z(e9()g#6GB5ZTXittY?A=4=*;S^{7?h49U1To}hQ!^NL3pX0n?^+gEasXO5PM{eNy zlaRc}@N4}lrzAyigS--1I4Fu64clklm&?F5YxRPlmY*pE6ScnF)iQ<8f_{w^nbx$f zdD>@fF}Hbk2^wq`0Qpkw9jL+qT5wyf3C$xGJ5fn13Yzi{-dcutShhIcNzf;%HD(e95KnE_lBK;hq;6TJ3 z2nd=#1D6pZ8wNguVwk3*aTx1N1QcZvVQe(l8Ee}eyt)y9AV0A+|2t04OS%1XPng&!YFWxl(aKcKZ)wd&vKc$1B{|zP=jw1T!6K)PV(ZsvRBl!*bx|E0j91F2 z<63rz$Ne#XEhtG~w%Jw|Wj8Rrr+H{xRQpa?)r{=*dZsr-bYBnEGiU|G08pgM3|mEP zwWhDDs4YIhV<0NvG?oYd!z>N%M4El~me_-qy~}{29CMMu`;yDoKdxy$x!a*~hFsz@ z5B)%%Zg^Zae<1cNWX-HPdIAx$695b9Y#-}~SpI%TZgD6`SB%mfg6fWw1xx_RQZN9f zj%g{`BMuc+GC*i;dm}EF7uX_Y)7jn^BR19f2P-zP?{DP&Uof+5x0GW2u}`EFihVF6 z>QC`FOeVI5%kYQh=Y#2k3}kaA4lzD2rw-A=us(&QHaWZ@L_4uf9bkp%b?d>)oSQt% z+m)?=H7tJn52wQ44ki(9=P>T;Tb~$HN~K-&HJ|KbW0Aa2>Hjdi6R@Z0>Iq?V>K0|- zG_Qxydqu~*4=t=xLsJMqR?4ap>!ZK$#8WC5l|Kb`eaLTlB7wsCDK4L-31iz{!2|uD z@~FB5fS~anWpSi)W14{%D-+z;>84#YP>&U&y&hV|!Ql4c`Zjgy*|EpCgIr}#60;sD zEAL{ym*HBF52lNw9yVXe^9Zxy2_5?_mGp)rH*IIsIVJJPJmL&ovd@b0v=zXayeV;(R z`#RPZf4zqqr7tkonEQiu0>fC|>LvtG$pj5kOBg|{v%P%Z$Pp1X&O66fS*&@l`|znC z4(OfnCyb5>y4aWE5(RjRAd;J?3mpX3)-jf5+jA{*SUi*olbbsZ&%gfSnb9|m(P37s z?!3v3Tj_J61UTO8Zg|tu!BUKa_DEF9+^*k@Y$iJ63Bg9%7lH2h(*~2B`=2{k z^Fm&c&i=%HcC1xK?q|W+Ycfdv49D*w8C#9v>+#eEyk|IV1c{JSsb{70mqhKIWS10m z;%{%*q45sB8ZOo@y?MX$F<`2IDw+8W>XfFYV-N9szRW;T%s*WQO%Z-8# z`(aQ+!LW=lAIJws8FLz(Yo^JNh$4v4G(KI3lUZ?25ZF(0zN#?+YSi*3AswT1maJ*$2*6Z z2uz(ZJPf=}tme8STEw{FM6}F)v!uy?o&g#nOlRV~HS!CiD+c-s4p`>%+9c8)a!O5x=K{e0*EqQbL(~(UFnsO-2O@>lk9`_TlPicy9x}4lb4J ze0iu;g8F=z3;+vD1N%=Y4Yy+VHL38%u_);i+p_J)t+0aRS$<>E5&ZD9A170s$12q=szRayy@3r{o z-e@aC@2)$!BvBrE)+7w8(|9K}#Tv&tWKGOr5X?uQND7{ifI1oJZgcE|<=GXME5VaY zf>@c_2ch};!1WjIt#RP*D)W_Qhmc)u?YQHZMA43Mt!p6%hHyx=Tou|kVtjBB{962^ zf6%eDTjIxW|GWRnx4Sh3+%J=4syqhm0RLF4>xhSTRzC`m3jc~ayzL399`&8C(e&YX zzmQt<%x*a>CyX4}wCU{Zp?e|nkug)2lHsj01bZ7!fM92MUbcqDNH}~qx+pk&cME;E zHbS>BU7U#NiraoUQ^*z#Q82dqW(Q)%M{CX8G_*h;18KzI!-W&cg8%MB4>+5yxkTzK zP{3GQ`@m;ckY{M9+w*|?OFI^nZi;mD)P#zmr1M31Cdl9G7qU%?=XzraQq7{suTwPN z7p?ieE6m4qmfOF5PxmyPvw2cG86_Sk5#UBY72)}sIT$ahlp~AqO)K>v5vkmxxHdCB znfm#3SEEmTZmT#bc!&yqcf?Y`LladTkY@!aCzrYG&PR=JKTXxzdU$@z405o9{1Lf3 zTHGClnY$D3hJh*C`R1`NMlpQrW2&cPGX(p5jJ#(aH6M|1Wo?zWQ!QPv%M3 z6j_VRXU4~1?ak0KiG>iY{e1(ig&Zc`l6GSTUA~)557Tklj|iYHE7ab2;LWYPb|QST z`(C6TB1ZbLv%kot(OEyJEcUufcm}IMmp0wfKxdi$UGqgp=zze^Qu3`yyS^}W{;YBU zxWCg${Xx(7b*iVwrp0&sJK0j^-hqaUZR|1w=bc$bhV|g>x>tn`uQv4iC$}nw8(9{E z2MxX(iX_cw^Z-i2HK>) zlMNrM=e9v;v{X0j3V}>(M{n;>EWKoHS9D$cOqPwddhObR)Y`g9VMg{vVTPPC!hnHI zJGGt+S1yd3N+ zJ*>kY1p{Zb?uWmOUlvq=>Q4r?u2^W}$aV_dX(3fDHA4uXWD4_)#I5*xp2LpPgd&@T z+0vjAuJ3k*-D}!EQAo?I*-5q=$_$2i)jo1GeR79rfZLxQLj)_Sr7mwB|a-Xj@tOz{b*U8Z@ybs8j|QqxGJ z*}C0!&c1Dfge)7B1i)~fq8Rm$(QoX%Bim~t9pb&|JXSOI&mu2WDA0!j4Bv%70tfbj znrQUY4F&me?_)nMw6D%^BJU)SV1&5A`P!M)hIfo=OfBewVx)5=4cfsrDm$2{Yae^?rT-tkM2|$t%wirLU z;h`XO5upk|cJ@%r+0>nWNQ9@5EHASA*`Ld_0Ap&Cnu#PTGSr4fM_;KqfO zX(K}yw%I-a1=szgP^f6vY^l0S41WMSfeCe{Q07ytTAu0B@1>L@Iv_xD;6?_fh6}Ww zLk=|lu9HSusagN>M6swMnVs^IA=`2>R(1LOIRm+S`~()5SC?z)2+w+XUWp?9lYZ&s zZ7if%&}chiE4M3qmd5K&C@A43vM8h*=f3LyYXM}q#g<8$P8lX2-)DnrrNNu{X$5N} zY_=?dm6nW0PbH{3vHcDF-XGIr9DWOK))Bztq7~dmMFH}WbtA-qWQiadO$wC)%J31B z`>#Y4k$Nk;pIrAC$*9xuOkkz@+fUX1q6vVth?Huh7c~lQ23o4vu==t?UNs~mTiNU$caTi z>?}6j-L@ZTzlk9^NF}8Hft)0!g4n7GKCb;2cT@UPdsoY0Yb40+sQzn-uthj1aBvCD zu7clq;Ft`rFL_FZloaGZ(fvue2sU!&;}0czgDzaQv2lkTP2O%Xc206k2eKDE;(77K z;zk7t{+)@my;a?Vvo{KmMx|!e@5p`l>3q6qY{f@PcHl(CU7^2Cr3{k%Jiw>WY&SgB zgMoe|@a9VRrEz!`SJ++&0;4DbEBuOD5b7Yl~9qOBU9bqFILhe ziv0mR+3(D@1T9t6a#9A|?Mpf-vmFb=R885*Ey7V=m=p(__e-KW2V^>lV{V-SAK%uDMe`)U`z_bRbWdzu z95EfI)aDR6Io8s;KfWz^tX#KeJ0hf^5c@BfVQ>Gig`bZ<*5Y~u#Xmd;_jH!JVr^5) zZsl2MG%^m_`W#z~cl0L@&%c-&2h){>5QSr?b68flJ3b|fGB%2UVRpV z2d7$7pEF68PF+nNS0Fg84$SV2rCC${nIFa{NL2QgBixq3C$&x#Bg`g2KzUfMQ**0)`b*MW=hH#ZD!BV;_yX7F?!_aK0 z)Xtc?+Dk~>N?aQHr#U(?1Uy%K^r9L>SOkDR!;D|INP?7NO2e! zPpUB^!Hnb>SsH_78OGoA`KZM8yTT$lf~o!ee7qM@vQG6m!S~r*27w28CYV3y85LQs zx?cFmY?TBn^?mwNpWh?ijNCat$0UMM>Z~qHjGGI(%kzIV`i^ymt~(_azf5>3d)k8v zqxN#W5I;$NJh{sSo=lhP5~IOuBTc&}$co43w$+fK))FH&wfQy^GcYeIEsVy~sLd^sc49jHJ9r35I-mJ_mA%u-y&Lfu#)$a_X6!{}v9jVFi>(Oap@hhXHr(c?D=qbFx%^Un=#_~>bq0IKcoX9P z0`CrG>T$J_X+~|ztq9kyEILa817F^~o%4J0P2QRhdyzOGTY6$SlGn;#gii7B8aLdu z1N-FP>~GhP2Y5ea^99McT9gRcchP%){EM;cB4(@U3J*7DMLNt!JYD=yg^Gb(tHsAh z(j0>j^6r<1t#a`}Y~Ng$)_sl0_{f#b3JS zaM?_y9fLo_xfi^d=aO_1MyP>^SQE-yc}Mj99oa=#%Csvmf}jh6OX;sr39VlCbIJJy zXBZlyN8k1s{2F)UWS$Qt_}h2DPf-Tsvw{D-SX~rn@3)!VJiOLq=Mb!Rz?0p6IkR+sK!us5mV_pek+MGuE_&Kf)1X>hqo>Nu3 zoHuLeTnHEY(D2x2Q?T%ap&OkfSQbPBoe+Ityo^~?{@12Bi~qu`q6@B{f8A&LVrN;! z4zeHcK8}imR>m4l<{O+8Ofe+ZAJu$|gTkv28om`A_Zs9#H-zP9`TwS+o}^36c~8U*Kr&p9&}-&A z5mKR9W>~Q>rJ<9=8;e|F#ITK@Ql+}wK-R0QjxZdEek;_r-gDyH_YW(9U8wr%1FQMr z!tCWku4(gbBJ9!$AshL_1I~U`B(1NRDLoJ=>IujI_&$^6!_$jlFIp;G2X`6UrsZgy z<0#hd_3dWEcOqi-7kk|>Tdpyd%k5?l%jXQ?K8_d-o0UF8ilS-TXev9zM67#+QQ0?u#?o)qj z@G6ZPQYyOab3+eD-3^jy&kgy6OfJTAV;ZbY+HRF0-B}7UwdbH85Tl54EO)7j?+DZ0 z3$0VG7zihzY%DJ9xvcTYvdQVF{v2}o)2iI8UsxjTXxT1MhDrF;(8nfz?=XWlvmS_t ziAg9cd&4x1K`fwx#|*pS-jF+_W&&Tbj@i%WPzQ9bx4-W;&hB?~$s_$Cw+Ub0rE;l* zC$!jJY;lLO6CGyn7rzd+D<_FH1*Wu=AumhBV)i#r;-M>aRaxfuqxDZ--nF$`ncoMUTea=Y(Ge&d1 zdva%7;X6yEorAA8-?k$V{JpD2M`X|;Lu9)@vWziZ|a$(s;{!2#XR=B^GEn8 zOflZT>^`mvH&VrGA;vt5*mQLyZatjHgJzrPcCP<5%lD>wVZgjHBT;_;4C?Ck!+1@SZL-zgqCEP(3YgwOv7~AbfSWG*13S z-52)51R-$AOChJ}=>Hll>31`@xKJXMkBY=n;pFNSwL$4kaz5i$&tIC#&#Sr;8;v11 zmlvaD6rl}4*D(GWT3Cmk4FfUU)p3C86<@v5rOcTE8%o^N8XPqGl9)rK+`c-s|)5txSWPoin&CX6<8@w>zkM9P0 zlxbz^qOX-B%{KSGFiqMi6FRD~Y`#wbcrPvOR_ezO79}LRgMLR7Vt2v`UG&;g6H13`t}i!DgkU=GNFAK$1Dd#6;6tQf zJ2J^UCuZE#!X|g(&=fT^=vnEQKUYneeZFqP*|mMGT;kH^*GXzN`t)CwOVt$p4PRnx zTU-T-)Fbf6o}%sSOEByqzd5rSS`{64fRV-RFZGAiKZe@FF1FKy~@2uhg@? zUi^!}_q$hc`)g)EedFoeF69z@0xFpc$%IzL*rEz(NsV)L*}KSDj^miWLCAA!{M6)a zx+6;VAk;^5xb}eVKFS|+>gR~h08{U964CgRQzLh>2uoI>gl^@#STo8}Lo}r97rwFP zx0p*+#i+^U-5r7y6B->!Lz^+hxAjzl`McWw(@rM5_>hEa=F^S<*< z*24lC1-Idnt$H7(9spNwIW`_ddr@NBUT@5O=K(gre(}EG76US8y~udfV$^1T%@of? z=B1fYdpV*=2E52H+9MAODH$V8P;SF|Fb`J2IgKm0Twn$I_DO-N%8!aicy0VRv|$i5%I9kJUyN8;O!zVn-hFjlO_QD0-LbFwO6xgY3mhf0wy9jGx)s zbuOKykLE?r$KFRaa@#)rqd^Sk&B9~s0qq)>z+CKeQMaARn3~7&W!8ZHcK=*^3af|6 zDWCpKo{J37x_r7_$e3$(s^oR@MblL=p7OPy*8e%@T5!XR=oLqJqi|tO2s52E6==}Y zIg#8V>T=c+{J-YjS$^Kv=95d&kC6R8c$Y#_GNNg3C4sW9@<%>i+}^vcaIC_v<-=Wp z!TtLn&c4HktkvhSn(K}B1rUDf<4R?75>KW1$*$a4B_V@WEFyh402)CuIzN76I0&-K z&2w(TWJMuno2RqZBaMpFI#@;UcPCh`VaQZr3ADjI6T{rUtY75y5&fmYSM2CSo-@mT zw#s*W2K;ovUIBDM)bDu*P5>ulw`4fvM^!sl#VYN;X7?<} zpGOJSQU$G27AMhsRWCZAak{;|6#FE#4`*CExa-~f*g90<79q;ID~ zOGsD0=IbN=(GwfqP1|D3WOG5j7V`o*|8?9boc2M_Eel2px6%9hZ`E8ZX6;XSOR9$npMs(Bew+BvGV!1qs;2_`?Wox~e*5in+U( ziy77hwpxx_q2IidtF)Dk!)IA?{;-B+uxxH*k`hd3O(h$k>D zZiFR$1@Ebht&cl?MUxBDiCfCb5oRXdAe#PrSYJ%^(kJE`?$`G;W6){pEjAg|*UViT z*_=>>*n?~uLo)gNyeSmCh6eLhgQngNU-lDFw(;vJ8P9m_zs%463fi*Rwuv4E-+`tw zkLA>UJt39OzM#7aL_)uwzN6g={$E-c1UhHWlPlFW&jBY^_aTa8x5!GUY{Sa$H3D}Q?N|mWy9)!K;%b?Ue0$)FX6EQ-uKS(?R(dp$i++8?Z<0RzhF>IaU7s*!tNTlscEWOwe3 zvk;~E%VXTqX6LtIpsyX2@DwwxvA3dszeh35+IT64ta%GRt;VhipdD14cDgxV9h+Bt zj>PlWL9ZDX!Dh^_wFSu)>D-{{eEuRlpDzyppu38fonDe@y^5$q1qY?7W)}4-ecU<> zlYTp4@8+E=RDX*4%P@r2KpE8tJ!iaSTPn4+ytl5qH)C$(OQ+lj(w}X*lhUNbC?+P?er-h70C82cQ5a!Gck4phqP
=zNW>WDrorp$c#YN z$>QwQrIk{Fs^0rq|38|}GOW!mSl3V-iWCbj#f!VU6?b=Nad&qq?ouSU6^G((#ogWA zJyQJ4h|MtD2g~0&Zk8Wy<#C6t^cHW+xiqhzVQKmR7Q3O zkB3HCP{z%f$d69mjZ_5eT`5a4*yet=o#1nI8*8ARjuy@dO&@LlA9G!Vj27>)i0v=C z*tzoL`vo#YnIiy87LvKz*iecJNKiI&2-0LcC;&!m0*M(HuF!Jd8N%oHWhWtqQZ30W zx(~y218=Q6^0+ED-m0Kuv>QWxYBBDNX&A3T7w2dB4M=otVl?!0s>P z7El)e|AU_fo-u}4c7z)}AKT(>yS+K(lR*z%(`BHl%S6z2aMJ?_JvLk%H!>ngn8ab|J`DU zCRvTR_uY;q8L`oJph-kF3k;YRxNuUvgTz_FI|Ok`>=yz@1%QzQu33wayR=_{la{HCo)s`gTK zj^o-ztOOa2w5oag0gbu8-3@WNDh0bG-Q?Jo;dNB z|!c8RwwuQ>R3mL_0UGJh! zOQ4c~EQV(i7tPxEhQ?#ZH*sW}bRW;%XCKnD-pWKnc_xDuZrf}*f%2Csr)}=x$Z#pt zCP8xlB@wpP$KM3w-rPh3tUQ-8jE8|7A{)EXWMbW-|6|Ee7T``ENsuEd!Qv^^_82il zg~z2N{&1}+?th(lq5F7P-0SU*7^~JoK8SCZ+Fwkkzkl2Q5mR+#1mcmF0h1hFUJocT z_|xb%S3qtFtsvFQPsBdF-b)t?qF9`Id&5F!2uki$l5Z}q?e3f9;Nb3}7pY%NPpx|1}NDKJ4 zX+4=ieGyfn9}$r+8NB}MhYJC!ao?%neYgZ}@Y<$+FZd#)Jd}~#%cJoFUHc%e%X24F zM?HDA%qW+%);TM#3UeY$=~%NRmfE>u=Jnm%)oc~>22O&bD`E+$W223 z097`ppIh1`mP;4r@oVj>l((zj!ddA3oWfhK^>mmkRUqDIH&w4q?Sq52zz;Mb``@C~Lwl*?l7UAk*86`!JM@a~HjukO)PGv;U;HINsQ`1* zEayN0kC@tmhkZWj2;Z$pj#5lg96@~DbfiCtbp26$@240VjkjV;KLq{R6VE~`S%+Gt z*A;jbUEYv9axuddJMl$ZHaXf`^r-)qiB z2~d4u-l>aE?1T1$=2$E%K_zFVqZ7w6TtVU*Xju#qd82D;}5ANOXKdYYNP_gg3F2IKji zoWAD^_sr)jOsHGJ3SYgBqbN!<`cpN8H6s>PI^l2Dek^_L4kd2pZtTdt)kVr_m zClEBfNmcip?e%7wpI?w`2JTo{uf;O+=98xGk_pziB5A2|Ww|FpJG2$fXy0IY2&ZXZ z)D_I;!|4gzb01x55jk>E;hhwh6y2i(u|^;0BqVjteyq_<^NRcr)D%D-%hfDAQ>!on z_#*YGVHve4Qq@*PnW}AK?8+nm)*!!~>vwHzuTW3B_x_-uhropd!olLZAg?KKf(E!_^DWb(lXX;ETV5>8s1m@=uRlwWru1)fFAN#DNa&l0i!hSQG z-T$!wu?6x*v-(Hm&8m{%25ElIJ{o128~IVvb`yRuYwrMO4LwTJ|v?k@<|W#@W3 zGD0S*LoPaQ|FQpFq$ts??&|Ph4*l(T?AD=j!GpOu&hoHlCvV) z`@$`l;q!{pgqA5#kBVK%1-SqpY9UxuH0ik{@*-AmB%NT6_(Oh5S=d#iK3)ow{H0UF z-WM;0(1T!1q8rm;!IEO%M!BY=UB?Xex2R73ff*(vW^n>3_v+NDi~h;23@G`^Feyli z(+~Ju@rbYTOu1!Z=r)Zg&Hk}mSe7B(OA%SE_xXAHibol-8oTlNc zP%f<@xLC$LOw0xi-xyyq`v(J3>ja@5N5%|uLPUYiHzS3?f9dUxW=8uq|Ef%YG{edK z;6_5bRz7Ub_TKedm|KOA{|btN$0J7=7=gT-d#QD8Q^oLaPSU87faT9$F20J_*ZR*J z)w&HAjKtOOBj9or;R-L0VITh{`o<-Z?uUQXmj`R*-eo2W^7z(kH`%1@G_?`W>C7C6 z0u`tDjNH*|RuPSQv;|!Yg*Ja(S-36SLqaq|QT( z)({$EKEGvCs@&C!lRTA#GXAZ3*WjMth&__Yl4bBMn%XB(>;Pd#5^6v%@ACoO7%C)- z`(^$6I}1t*>$R$?I!ew|ueX%$c_NA|&g6+0S{&LzV-7^cdjMnWNN4TmXoxoJw)q_p z>hrjh>(8g;5ec2;8;?M)PDY#OJwd%JG{~E2dLHygFLIGb7ImBZJf8avc41%JmqK($YSB;y1(PkPP*wB1T1 zdp}(AN$)>-#g;=N+39FZ`r`;w-9@_-$vFo#N008j9}p9)$P{gZhOPs&mE2Pa*eX@T zoGP%?W%yR)LSox}3F8`A6_gQxxR>jw} zA7Mm(Hz_^OSRi?K+<>=4jV0iHk;bQ2yD!AgT;uwq+5R%@E)98Y@!nKg$5WLc_FCb{ z#j$Bf>mu34WI7VkXL;07iXNv`N_+ZwU4#*q%5)Mk>E1UdnGicU$xHvU9uxDW6Y#LhL6!@`-bsFd0SS+bB`rV0ri zF{k6YSHu&ToT9$G>q&s!TgWUc6xGOYYvtgSFsK4OUC(w6j)=PeMxv#EG~7#b;e1B>nYo08{Br+%5Q znw$a-pDgu@a5f>Iq1VQ^wTX29>N9b#rGei$)ofx6j(44-@Ei)yIXLHwW|sdpPaO$T z6mI(y!45~6vfJ>l9G~E3RXu0H+QpNhbJ!nQ z!P@ONYgs&E{wBWO%KfL(_;R*8J}Bnbz84;W!o=*jT|ec&cB2>N-Qt7Kpti$G zpM&=rNQ-(4a7bv-tB5ffJ>r7B5|uN+Yc#v>ekX;y(dIQNNNccAsOf)c4XBuCuROK+ z`m+V)OvYZeJubYq0{?tayuCGI&ajRYROnH)598t`URS!<#gQ)QE-XI;Apu_Cir!4o za^9QQAa;B$XY^BVJNWDP?bG-55~T$6pa5>MPO)gZ4Jo4B{UIY7o0&IM;Z;VWsHZKl z%l78v4T(?W_KJ?J8+Iv{-+v&JlO)i0e@5bsNQM(kPsYALKsmLgz)2seKd1(IJmwEZ z-bm5Hu*9(@xGN!AcmhHORwFr$+eFI2X}q8K~vk?+u);`y7xE(#!Ci*0r;F^eA+1u#C8 zxlmDi3dGU=Yb-RrqQg=gwOnO34*0`%om_J>xb5)4gQ`b*(B93h;8y7BukC3*rRI2l zI|P6PiUt#XtkNrhu;2&VP8Jd>Mm4;hU4e431r)Kmw!^7i4{5=6X@P%(kf9@ozdXOJ zZIPsP%|!vH@(aG5w`@JuSb6Rl@p(3eo^RahlKI^<$}HdJbzJ@{e<}QOcs|fJ2@pIH z8q~*-m=+3Gk-L^HGZ|)6)RWIBa;n#~=Vxt&V+GfAt_p zWxr`4Gl8ujLWeZjzy#8!pbjVbo{m_;Ft(V$G+s=}6;=BeSg)OyK~m713r`07d!B`l zQ@awXbOijkf&Frg)eQEYOfbzIzJ8}RU~US#f0MxgO7>FwR=|>A->?|qoWZ^kLBGVY z>~6$t&8$|-|F^6g7aaSj`3&BK5W3VxWQRkTjiWaIt@-G?;3s zutgGuS2-a!J`Ck>&n1gQV&vu3>BH~LcycoQ=YlNg9s2(Mz9(YaUYax1D1vCd-pPz<(8oHcnM_D(H023PL+4Z^beO{+xEVb6PTTpaQI*H4UvLA@2 z%&x$g)n|JDbAYBtMbr~Fl>X&>UfEIvwFBtpNqEL=?Y*;%82fH%e`Z@ZOP59JK{;@* z#B-~yaXu_0_cmT(NC8#oZPTv9NrW~@SovJ)bRX*ctE3n)H|O%BF|##-B%sT$C-7+0 z$MIVGnxAbBrq(D?%ZQ_*Ct{V)D-y9}9*W2=vYkXx?|ATS>Y>*~3}tQb`o{S8fv8%* zqno9E75i&%V^lL^=RoXQ02|^aKb{#Y&9lGQu9vq4DR`-7PB~#mocut%mosm>fMDqn z>xxVihz)SDjIBqvvRjaN$CouXizJMV9cjhYyM5+EHF*=MCcq-{_IKn=0#3-Z)vmxJ zSLOsil=+iYta}LxH4khFp8+yhEll)9QV0p)5dex=)LHq3(96AmtMq;pEP`iB@M!G%o*J0t0kzGj;xVtm-3H*lZuknu3 z0qS$t)~p@~hPz8Nl@GF-rPOcn{Gy|y=Ja%nlffN8!a=}TZQvkzlO(z9_`z4%c68a& zSTkxqAZ&MJ0d*z#1ImwPtM&0Aeb$5^1;@_iOd@)w#^7If_$m?K+nVt0m9_DdTJRNY zAZJC`(w33!3AO+PsgTGyfXc(76N2C+?}ple*ieSxP9(|lSq}tM60@+3zUSUbB*W69 z@dPHOOa|*m!rBW~6LViSh(_A8PWn+7o1f9YPb4faY1q*%i25K2t!*9_Pp?;4dsW~( zP_qCTxZsL5I!^quS#E^J_ZmrPV0i8=jFYBAqK)fm{QC&{E%2fMZH=4H|2HJ8 ztjG*$5*u*RfUisWGIQ`PdE6b6;&Aa^OBH?{N)~W1|55gwAC9RLHl6<{ui^k}(}VXr z)jc#soO)b3G3l<9gi!2{HoCQdV1TxCJN#pXE=$EmEw_!+Us3MuU3XXOf9I2_4QD)? zlxuKTt`$kAMa6f#5O+&v3vCZNS%^$-sFio4X4y|3;G9?LW8$y?Q9D$|9gNf3ZWQfU z03BosI%}KRCquhBhHu;Gy%0LKQ4s$}QR&`hBSbm4>WVu0*0hs2flkg(kD^s$F!;O8 z`~LC1prM^mP*8Aqa#YIP9A3Y(v&FBSn65+}#G!kvs+y1nghwqFU)&$b;P>ESsL=dM zLxTWdHVmBttl^ba9C2zZpC7~`J>@PI-d?p`gYzu&(-(PFT)q)`Iq$NCX_1@;HfvqL*=OXy{KiWW} zN9`(i zTd^awUwnzlVGUYgCz6n|gyA8it@&c;hS`u+#6j&sDi=NU4g~^NZfg^-BJ|A@L!MJw zeLi|YASbTNu}}e)TQZ^f^Y*0&OO&7k!{e=l3!O9{c^${bEL7%pK$bni)6iUnel6#z zaq2*X+4LA|jQxA+sG*ErJo(9ISsd15S!~oVI4Z@NMcxLdwlgCa+rv(d;^x zx7!UR{Cl?s6hA2?Rk2VzSv)Xx>+--EZ~ zncSsg{lxMB_$MQ_oGV!dY&y9gy3I*;CD`rp6DME@+n=OAH5MIw)OhiSiS7aoCoU}* zIB2qYw=0QxqGOny!xRrzncP1*+Q|y&##s;!z+v`3%B}O<`IKE=GgLlj;dp#);weBh z&dWQTEr9Rk)tVvjlg)m!Et13n-Fe&`Tah_5tzg>y40pAyZF=V+A4?=cGg>nq@NJIL z)*ED^4n9)44x1e^TXlzIL0PzMCcj6!FFX8yk=otvGqWqVCFJT{${%^S3j4C-Eb)MU z_)QsoUUnw^zA_dq{`G<}(8>(MwV0t>|_Eu{t9FKjV$^U`k zST8SXlKJ!9x;_u!XnaP?V_(*5m}lI0!;I|u1>vl8=d0KG;B{Di$tH_+Q02=n*ZfLt zV?oC5Xx(RBE%h*UGo-bvS-CV?yl)uaxQ{!)aB#nInQ%hvqLf$o_`jyiYLswcn@q6LJsw&viLpfLfbPO0dzmOg-oy-3Fldn$3Z5gvG+O zl@Q_XS78vylF{4SJ0UGCJPZYwjDiA2w+h!FC#S{hj@o{s11YLt`_v`Bxf$>ciVi#M z?VJJR?c?p-WI*pI#2rIK&GXBAl;8Fr(8J84C3*WYu)1|MA>GQ*p@ z)|fosh63azPgG4rRiQuu-3(nkKW<@-M^c1@6}<Rpcex&xk|b&~s6iT4_P9@&WwC4lB1zyp~p4dv?L z#PT5BbsWu$C%4X$+JZnrF@OtMZpz?nFsL+%k}*c%?{Pw;K6WaGk(A(_NmjT~ooZ6X z7y8jl9MX)TPpj>)P>v_ppi2-(PN{OsjYf*@i?JoxgGVm}#@c8!DYPl1Rj(@!y-COu zTnC^%2bHL8|Ke^PxDycnOq2FY^vK1Dzx3pjqNeFrgW>!aV_yJ@lz4s4RsBTQWv&hV z2%Q4JvEEIRJ$irbNJgbg^S4;vAy|lKWvDM(;Do`vDN$^&Q1CnPK3}PYGmFxr*^z_% ze_6p(M{$Q4HIPB415x;SCSbe!4;U*Nz!chf^HqqycUM*oi&_a7^Y$h%p3MqlmJ0Mp=1ja zRN4vhMW5=O1eVsu?nIv$dD6lBqx)r7*Q{=orf^euABmyBT98##6Bga90dv~QY*oAw5ZgJzT@ zVj^DXW$TA&nX?YK#f{w#E8JoT_vs^II_mNg9)jeo0|&B|l&lcYrtbh4AG#7%7ra2dPzdGqjdfIh6298fx;0qL4TX#|q-Ni)mkuzdvGTb2HA$V?C&2-D)_; z9ibx|5Vy#s-+d_}EsgNcA;)so2$}y>H18dxb;Y zhFNyyWM~i=CMbjq&)E|w&cK2cTu(PD#i!8f$A@$eLB0uL@`{kj<8At~OV;M$MZ^7@ z@%`uNWH;nvlEzZ^>)Dol2il6n`5ds}NDR^1|ge&+2htTD?K6s28f4|K9D?mgTh{<0Z9j=ei2K6Ge!)n*g(&pcMm;vqZc7--_CE*xG|G&uPO+@-= zpltc9r7CD6ak)ce>L@p;1dPp>xz`Xoq4wt3mZa9JIJb(ZU`Ah}5P(ZZ7n|W_#Wh+o zzsKE3myx>_h`$M+eeR7%a0Le?dIT(_Xj%(uj5eYqYEJf%&nkV{IoAl%xd`XomWIUs zaajZ`9_=%Z`q3p!sOMVGL#CFmkSZa&t&YFwD+I#G)X&rNf-hTUzYp=}UcdG-xcAFH zn}J)+!kG4d92lcM6pyS6Nv;TGG~TXAliTwy>SV2mQ09TGnIGeAV-NiTQx662HAw-<<6f%kjLo*)qc%VaWxOmEdEtaW6c)0B@!sw z%)|axeDAU>3h4;CRD?^th}j|1!GbUp$Gb;6eJg7*DQ`Y!m(pHKj=qJXzK64=nUw|9 zxIKtL0S|kZpp0fbZ6aIJ>(Mp(Hp(uFJIj%z?Uie>y^UYhBjW8h z!j3Mhp`o88Yf#bx!rLkN>2-rXwchXSn3$-M(Nr!I1t1rsKq~%`R>{$0tPN_@Yafk2t$< zNXbEaP4M9hBtInZq>JpfrT>05f7ZVd8ugZs|5*aeXjEg`-~X`}DNWj&y(0NtNlE&m zPDxZn7jl<`vM&4r0!j2cy>aa9xVN9~25)N{vacXx6uN}aS9KloT3g}l?CdP2{;3cn*Yi-GuEgY|z$%UXy}0BK{G>?7x)FmFJ5eVBZTY zyAFH1`-D_3#0?Jsr|WU)#yX-aP*SVq#{kWf}VaLcL#Jb50VJ8Zj`N9liwr4B@SJ`zn&haImeY^yBw2X z=3`c^=_A+KxtdqbT+pypS|)u3Xz&pw8Nv{J9UXJfcYB@2+l4ZGOArf+*yQUnm^9=;qIhhDQ=h6B9(fb2&lCA#H8N z^0GDE{Bm?$qFT#fZlyKW>&$`v>t~Np}1q>ok1P`Y5 zd661xG}t11J4}I?9iB6iZ%ARw{)7yasGUAN-m39{4>oTE-HyDY!L5dvlfVI|Dk-Ck=!TI5=makm#_}d+#4V zfA0K?CA@z2J3c<{DaWFj_TBkJU0g(#r_yi9)|-;acewR-`$}!AvmVoHgWEwYjgRI{~8qJ04XtLwvFBCvVy3>YF+1;*r2~)4RmiOWke;qL*s_CaGbu^ z@D`3pIY2jeP@e$ucTmE=6?@-i{uoYi7;ctS?j{vpc0n z%QCb0|oDDDv=1VZ=&|o=FUbt-T*aopu!#Vhvw$E2~Q`h&_>=d~f?V7cT6<`h3#L2ve<)_6hX zI!Z`5Zfr^*?*{rAU8ikxF&+eq{PR>g?7l-ekV5Xn2w|~yw|{TDPv%nl#qcPpTvy}r zmBo19gsChll3!I`r|pDPIzk#bp4J`HvwOvB2qc0KGbB*}J+@qCrzv!Kf3dwg4CNghG_dy;U#>)hb%;L(~0IIl;dFs9OL?f^H|Eod-F#n7TE z*o>2u&{4byRJ_*&ay{B+C1$|iJu2Z#S~A8HTvx{v0DD}q?#2crGI3-w5OL45l*80x zN^vp9zk5=!51|_ghKZ0mJ~ffxHNN?mS8K%TIh1_n8AC9ed_-><9wa(SmR(OW<#Woy zLJa+mjeg?t_`tjwMiTF~C6G2n5ypuGE98VVSw-^@6>DdbHloCETbcz8Mf!1SE7qOf z%FntMY`un{utDdmzSmdo=WWSvTkH2H#OIdV72Pt8Z?0QyaOrbM#Kl3pG;PCaf>(I84>Q;Pl@Ki>R}iZUCGRjBI#&;SGZzB5 z%aWoo$1D@^$v<+VGbe^oW2+7ePM6P`DO|IlG(@ zsGje1I~ypFJ_FZ%+yhscpl8ye_{J#GlATm$cNrlES=2xvDN*yqrk%t}Nuo41Rn(s? zLQ&>)_XV2FsH@Wa+uY*j6YUI@@f|Fvrf6*7gvZY8*;}2nTz8>9L-Km|9;stubmZa2 z>pe`o4T2=$ugG%!#YF+vx4m6UC9TnZ05xv-Co>Pe{iv&xB`4FQMx6(6XDhTu~ zJyM>}L4yh`=Bdj8K3IC{g+~4Q2g3vrwzelf%vt8%n9zM+sHV5TR@YwQk!5Gz9ayV} zl{vY@d<+CViPiX?!VSZM-*%`sqYW45b_WlWM9a{V<$R!?C5DEp0&Niaa@At?*1dH% z(X84;g!&?}U7-=m@>+i3dh;QiA^FXs1lPyva(q@p|7n*7C|Mv$sXFQ3)D?`1dD|2F zHu>|YrkH*0Bj9mTpv&$B{K34EL`B-_O_!%^ z&{xuaj>PTpM1JzVh5D+K_VbzIq;Tn|cqwadLDIPKdD14hh00ZzHQ;fd1$6s-bF!?a z?fV>>lA9$*8#OR~!p`EfE0Lf{&t%XQJQ=45`|^nlu?|H6Baob+?(4rg{j{SrELjWQ zL@8P&>=CmM>ST+CAQL?KY?d#Od+V1(-*L-q(BveVr;m@xPrM9T0<}_klKCf(=B(*; z`;?!*Kb|!j{rBn$N) zl7Kz(1$kY3ms2#MoLO!t+Y^(654B_t)5?~3BwccE$r#q`a|2;Yd~TyO?YLs zEItU@yLQ(L{1sKrSdu+Rf0$`(?$q8NY(^dtD?Bmv?Cmp2aC6W{M&hs8Y1l{nja3Ee zx(^42Ydw|kh$JEVpvb^_s?D;xurN7lbd(HeUt45gUKZtorXI5t=1xq^8-hE@&S-p; zaXW*x9D%jB)4#2$xf{D;^u0ZsUH$jml$#-84B!XBsIAkVPFyI*!gombXjlAo1O*m& zbh#P?>%D-rAt~iX9+o1pE?md)WPp8@zl^J}T}$uQm4}C)NMYj;M!<(i!)Ojl_~w^t z9B2l2w7JnosHBXVV!K()!UL<48OIGX=7dapi@H*^<-3%UW;IlwL>?%vY&g*c9l%&zHC0Doxg#JHK&Ui8uw0c6`!Q>!6KUyXdbRYl$_j4%r$Sg!=Yf=yPf()8c z`uZNZA9+O~5?G=DS$$(XcsMvXS_XzsLr!FLm>lB$w&ob0;Y^w`Od5*1MW9CfDeH zyLuJSv=Luv9NpU7Dt{xxC+^P2D9<3manIuKxBDyWViI7YdPwH2K>!A?gNdrw~bY; z7Cl0mok}xrUi3a6A0JF%Q(BzGFB@XPKa$eYleNUH=V3GCu9m+Ey$yp;Y69fjW5(38 z9v^~sz2o71td9fQw>8kAq1F-PS>Vye3>%c%Rk$uPhVlMCB*%CF2%G_SO#lfFjqjdhEkYRa zdx`$euu#)eOpvA|40c>aF&3+JYr$@c52Zl=kG~2UWC-(TE(2s|aiv?dP;j`=Z&9rE z4^>R)ft5DVQ!Xja;+n_48j`%@l4d(d&MmVuaP0kgQ)iM!EKnh$=VBfnKGU22ys^gB zyG%;tDOfTeWhRZQP#7!(gP&5(hGN5dEhYScsMwN0EO;1)p39Y*7_iEGF5#!%@O>UO zw{<0|nA&3j?6?|Z#V69ae|M@FiEmD54C}XF9XfyXg~OVxYe<{vH|yhl9NK%8 zfnNQv!MB2~YMp^|7 zwGb*SH)%!@J2hu0s~1doV?OR865TaAby~!$mg)ZHCl@yT;`qW!Xg=|I2c+o)HRq>! z%71MITiMs>SKFybe>?ij1(Q+aySv|)2U%dg_k8{~H&-b@q1mua$~FTbpJ;-f4w6SF zQhxg-Y5ml9$#Ey4lxb2SoDY6^#XV8L4qyL6oriQreDdXqch%<2kh| zYKGdeSDeSUqOBY3Fq#0eg9L|w{$N#ECdH3^B~3~BrP&c8E??El!_5Fix*zp4bOP$- zLZCec)hp5mT#JA#j@O-=`mbg2LMHvqqy*sIruRC?eDRbx6}0a$*oNOc1~t$wILtGIqc^#l&oJCuEM5iwQIY>|rmA1y4wvdHLjb{Q;X2EA7 zb0tlJYjc;-Nwi^soexfqvDXmK@8+wnsez=?+evhy5D9#+89~J97h2QbXibq~I}zot zwB1|Vy(Oi$PMb_oTh8H3ry^3jda8<)$bhCIV}Yl-C%d&j3J$8E-q#5MNRZB z-$YyR#SVM@i5ep%$oU!S^<2gz!EH3=-j?;Ze2e>_+wtRzV{rr4CnyS;eA=z>%}XW> z*dRxq&(NQCA8&Y^-Sip5sfx9M`ZOGaOwB8{$CsDkGh}U(_?f++n?W+zp6_@fNtCp+ zh=sjS(JL`dWBjv^cQ;G9?t_p@leobr(qswACmgJ<^90y)gT~L7?HZVW;&X~? z!DuHBKEQ7SO$hsgWOqqGCa+eVO$QStRnSZG!R{SQJWfHQoIig<;lJRCkCGS+wo=-p zO;(wA_v5N`g)-egmx18>_!JniNOc3OK(pevjEu}u;vl|6*URUflE#e$cAAn_%1@hi zVjc{-#VR`cSP9bA0|TxO_kw`4iTd5#K-#}UySkW1Cy*ow^7wM#Ywl!gI0eSI6U`0w zLRtLo02P?2UPdp4Eq3roY50}FzFS_1rA{Lg8 z#Eb4bvv`G7v}K*NY+r{I0}}OZvEYu_4j$H7L;7osn(|Cd5ufnYP%NuqTsgAzSKM63 z_f`MZSGMM(`?hu*Zv`cvj#V?E2UqfcwR3?9qyMl?X6#q~G|cx5BRZ5750wQEb(onpu-7<{43P!z z^Do3tmYML9DxiVJF@&aD?DdC@uN`kxbRutwGC?xWZI)0zb5$<@&xi=3j39@0tmSy^F{= z>r}<(670_3Y-kfjc?2g(ZzO_O`qKYBM}=bvC`V^P7a~c0F?d%lA7v8nK`RsIr0n=u}|Ya8mx}*-lh;=T=sz`?se}V^xs5(OXJLQcg|@ z{`fPoE(wtd^DoI)DK-AT0IBU45uyaVNWa(T*ExFQs+`lKv_&Qg$T6|prNuxkQ-Wt{ zBoqOoQ;OZVEQPFh`4r5o1>92NP9{6s|3tASVzO2K3 zp-$96WJ*d(9y7rdW?@SaZ0DvSB9vzw!cVp!4gwQq5_B6hsI&(UZcVxQSGP%f@?B&u_ZfRa*ynvApbm`*Q;^pQ!7IV*E z&?uut=`|3(eyIKNa-1w-3fGm?K+~`@lhXtSjDEpM7IS1m`Iid?qTTBtM^si-N&NBT zcXrS#ZTne6Jvt3pQS*w}@2F%)B7n{K+EOQFakj23+$B-FMSbj5Id+-zIMJq~p9$2U zfL(I;g+cbt6@N{_WMjg4$MJEXmf^Iol>t#`P~a>MVnqKo4_at% zpfOn>of`F1!@u$62WI$Z6v~??LWJA8XOk0dz2;hUjfSGiyE?zw#sNrFc2|1P?J$yp z_$@{?3-#uf_;2ICaHCBoQqPl#bY>T0(lF$#j*X-E=pLQ?&0Hn_g1SRLc)6(5BZ;Ao z`=b%Mu#=i(Gr!R#kMnxVSvNygY5pVKquACFbO#{^iI$1L*ULwfH{F9k8N;6#HE(=M ztO4B`n_UFnF@L_cUa~FC{P#S2vfMUFq3-e}tbQSMiEFT+YeAcV&h#$O+VwCH$c+p?w5zEZ?_-_KJ#cRGC$R_<0dryy+rleNA4??Rm^=hk|@!RaPF^@r6LyzcN zJx*VlyQKHN3oE6!qRrl%4W{{YEI)9;h_q?8pv@L|8dm!=www~6{m4;WUVWg3kw!*1 zyzpfP-F{u^cm@QMon@w?pg7N1FA>Iw(K=kPKqU;!TWN*$rW+N$tgMI-#MbIEY>Sa+ ze8=2FM!|^t_ZP8FVVo?D%H*p>uvfjo#?jp%O@AUHwPGf0%@SaPdW6`4nIyLYwMWfo zA7;u&>AT$}a0_61cI2}+$9(y-wpA8$OfHII**BWw;%yUe{W@>n{_?d(OkE+VJvV(S zg{+-zt2wP1*3WN4uou1-8}y8^KBA^-dDrnVxl!N1-# zvdW0lgNyzLK2)EP<1Xs|y?cMeSH~0?=ct{ERJF^zt+kTQpDC*?w4RRGd0 zZE!ni3t1H5eb0_{DfgTsp-($uKr!ui1A}5eUNlZfwWi#_Z_0bxJ%eG+LvNPhUiUW^ zL$+v;ci5P4Fs|z^lWcK)8sJfYuHHd7+Lsr|H6X$Gvx}zTWW`tEoWd``%yAh-iu%Z# z%#xSCW5I0t{;}Bf5tbxgzmP$eN55#4RjH_P3~J~z$t0Diz)OchrDW3In%94bw83pH zG#q$e6nCt1F;wGyG6aM^*DI3r)?L8SgPbdTUkPdTm%IpkpJzb=(sT%qF>h^u|1iMT zS5pYRyLTe}*zjMNnhb9myFi5h#F8K-@!6yYBYbKP8v2t|2((zHHZGYc2kBp9V3%&$ zg0;9$mH^DAZC#HkD+M-k@6}VZp=)qYXvKMkklm^=7d4tsX0S~|iXd1!2Q`9APSTjv zy8z0lUD{P+iRfpobL6~Xmtju)sH_)Z=O9zAKS@O z+nc)O#97+a&d3Tbj?jy#6|m?_GK5|nCHwS%EiZHNRa>dIeeN?~zJYEM(di>nnC`Apllrw>XOyJIwBhxz0$G-x1g1NZH zt+WG2REzj{R^(Hy-w9vUN(1g=?s{iV@qK^HDiFR+N&rIx#D;D zzMH-OKbpQeDyndMd+6?N1VoVT8oEP5K)R(HB!*7uMgi$o>F(|vDd`r5?#}Prdw<{g zduGjAXZG6fv!B@S>OM-sq8vUCOMfI!16;Id1Ey1YIlEyC_Mf{1`0IJQTxGoTi)1AC zz%DJWSI+U}=Hn*yVz?*$*BO5brLKe&=Rmr7d%WGAO2#lAFDO zcb9r)pp)6Sg}4?MB2ZB!>$1jJj_7l$u_c$8)h(Jfj4T@n;`eCZlx z)FqpN*I3y(uwuRcg)?!v+VHovlUmTnCPP1{_QlJ%)2I8Qf74Y7eY?J?@Yl8GmXH2d z^Zeyq%FoSct_NL6z9I1TDvta=ArU?Pua(AX#paDS$e)e}Hj~!E1lN>9eP#MS;rC!c zJ>EEfBt`lr*_^3zCQG%O?}M(T1y+kSMf@)>o>{6m9uxO9UVZ*$c|%PAWv1U3OmN)*h2PuOPQC$IRN@LM5imo;RqPM=r~MYw zFB&pCe>uHxt}ImKf;QwL>%HT^hHNl|cb6PmUQ!#gk7DJkYdXzK z>>Xm{H4Pz5E97@OAj82YDIkh=h}ziN_Jm);HV==(p@-W4(h2N{uj-44M=kI;qh1*; z>XvYKA)LGjzOHD4aa0leGuGW!b#DmK^XCtdhJd4*zB-*u*G-Fo5Y&virNMB-jE=MV z9t{dT;e9@n9MaD6vC;25HO3R$WH$)0{iF*=w9n5yy;g%uzsZSeq zY>->mb6u#)Q0E={ks)xCPmT)*_GC>GG_WV6W%Dy?$d)NhaMrHo!k$i zPwX#R+X@z$g3W>y&Y5uj@=W!oC3rSG1?E1eM8$8^Eh*nCNpBo5|M}MAtqKVY7wZUL z+Uq*_-%N!mj?n7fXdu^=xRpg6_Sp9_P@7)&>w%A_{n%W7HBAtBk$tQ8r6uN(w?>=OZ#?bO4~ z+s$@i)SE2t7fRb9AzHac6||C*riBXKTgJ*?I>j}|BmzrvV~PQ=T?`o^OXqZf@P(jbRZoB^J~5t2lLmCB2om*U@)35_frDb{tM@Gf-yAOzu~jp4OcS^V<}1w4y419-N*XUqw$jcbWQztjS z*!cfFo}`H`YX|d<(iP%{);#Vw%Z}#qD_l{bkI87*BBhZx!{OedxIYE#Ttz)_LEViz zsw;*j+|?^z<}>o$O|7>Cp|bgN!L7rO24X4K#pHx8REMt}M{j?x+mOLRXenm|!)K;E zKAW!3wWu>s!|*Fm&GbF$PDFpj1tUptU_WSBt&WOS!y0bG)aY(Prby-r_!twEsoFSw z@o^fXdJP%l0RK2SSceX=N z45cKHgmJ7Pn23cl8bSWQ7eJohS?>|$e4mO#@2o?9$FaGg4^(@iwRD=oObOlmlYcwq zvoC%1#TOSH*_12OEMB-V4w;_xYw&=1cy-T5qQ+A!FLhd~5Wx+f(IpHk@PD zZWEf65;dCdVaKpF)3foW;!-UB7k(P$K?VO}s=&GpgWNQk`?e-R^FGImn>xSFcEr6&63-u!F6|(!ZwIby17;qViH9b<)UQql@cB0*c-likpf64K zGR5&9JH}$QbN|SRV}bOSvGhpLjw?!CUU0*2GgVN}5C_*8qR&o{38Wf$hi!5owB#dF zGU12mK{>G<-Zm2!BS?xK0P_Ys^`VTZNh;f#4}Dx>0_Ke@KT=2u+!jAsS~I3?c`&-n z>+~AsGOR75y!w09V}S)$U5U~fntzZ&cnD)qftg zapV%f>v?gBtuEOH`8yy6F`&1t6>|Byk^0?xoI~m^!5d@8=e9g-EfbF{iAyw_E{Jb( zP%J@%#KgTa8hI*P0f4Ft5G|Z?RDXCsC|6$A4~jUqeFRy*oNk!=?82&uK|9 zr6R*LJ{p35KBo*<>LbUc;%V2(Zob67GAHk(Jhl~aG+z@@G|J0b-4G%@vbK=kBSo|u zMfAFvwXlwaRl~y2D4f1wth$f=^DprY&_nIhzIcb%*ku=dm|V-&D$3~BYPb(?t)`x? zU$RExp39ft{ry2P;+T&Z{3Y|@+($Qbe(|Heh!6~9dinX4aAZ6hcTeQeMNDPGO~OI> z>rc~34ua+B4^wn?Qld!0Bi9oQDs9H4HJj{R4mm<7?5>B>`-d9;J4g0n!Sw7|BBfTu zxyfipmd73v?y{`gU_3s_Kw81dkDhl{C1Wyi{wER7B6*sfw;ykov!a-CMm&XJu)o?9 zji0;3ANq)ix%IsmxdfgoEov`Dq7Czl+mAe03KMqhba`jt8*Le zA2!lQdyIc(U&;ypEk`w-7eh`sZo*m)GQ768(pp^!9PcCO(!?%tY8k?4RBR=#x+ozo z@oYEmN$Z*}dmvv{*fj9;D6Pn!`Y$j4Le-0Qw)3_YQbkjs0m%h>wKdEH88{{9hAKt( zZs?>AmQt)GfJoEMs4c+ggB~ttut^3BI^r}9v0J1n zWoZ{doUMPoNulzR>^K?Jv5kiDn^Ae}v|B(PoXVxD6XlcT9nMAW~PCn#o9ze1*Sg->8 z-it72i9}H8P*90KZwdPb=Y26Y>X=|+6O#J5&bff^G1B=8eX6Ujkn$Sv+E8rvc+K@n zzjPjr{dt?iRL%2kIxnXp>hOO>W0O#RlH-VNYyQCT5yWj*~s?G`Imw2~puV zRoAfqq}kHZZhl)32TnR#^17oOEyh_RXT7PzG`vuYnKzo<;k?1rhMjImj>pHSh@q&+Jcki? zeqvc-{^ajev%1f>-<^%Ju-Dhu1Ae1IAp0bvb#{AuZ`Q!XvxhRK+<^J1iV(>T78u{d z^7@wO0K6(ScsZ6UY}fNc$+hJNJ!a>F(63|1Rm;AFE=H_bhjojd!MA8tuT@yzcBWqz zURsgXvzck?7q063!2eQBlyT-+2F_mnb0p{Hlq8?`^?Cm4FegN`^89+#Q)VnV-Tu(| z{<`L2cG;?2zcSl?sZm^a^QnkG=fE7`fj-E4SZkAxX_3yCPcNp7g3UDV@1V@=DH(xXyM7MJfrSiTb>)}Vm?E9-l^@{4K z6~{*XmsFaXBGW@Iw-PG-H~B`4@ZZN-wSJBA54V<$pYbn~kHmBcmLg&f5L#MB?2qv> z{Yv0nr|# z{i&``v5V8ceEJCqxBtbO9!Vhu#f4y{oGmI?CP6TZkFMfQoxvMsN?U z@B~~CXQX-Sgq3o%y@pl#kb-9#2{9pXfY9P%78KSI1jC{3#Kpx4y6<9QQ-gu#L{c62 z>TBagLFK4Tm7WK^ft3NfisH-d&4JgNFB8z*762$+^AiiUNgoa)wUR*(! ze-CM4uFb?)C|sl&n$dAd7YOZ}L&2hW@>v2)S(%nlzc)tW3s_WLe1w`%232EEjyOW7Th0Lg=mjl)YMWGGQUfd)R;LN>9W(p;6S zs4)USI1W6W9uN05&k+z_<_26EE%E}#6ZR(SaO{WfC#G$Cf^l*Wf3fqmLaO3Kx(19#VgzSz5=W4d!*x`4%DE=wqg(2Yi>#~*|bye1&%C16LNrs5&tBI zU)1#y=` z!D?!=0tv4iU@GfPe-_)IS6F3TK)Cu1&r61mmuV-q3JmxboPo7@B?28=!~YUj)wYA8AoRvKpKj zHer2uq?pL4k+i9_o&?dnpYh@epa>x#LSjPGrCDYGrbu{w4QYYGq%~*sc=>s^W`Ai4 zx^5u?FRACeAQ4A~-c$lG7sS$tQ&T6P^q8W8hv@&1bQder&~?$$NXbap+A^1@L=o?YivXL1dmpibnY z)pBmd&sJsj&+CvlzXu!NWELSBm+xb@juH0 za9y+MB%}rTM|DsCxkWwKM`uj)b-o+nGS(#v<7hpofqL}d68)9FCIomC z;PdJl)Bu8PCd4jO-C z9taGnp0=|5CQUDKD9IV(o|1@v81cDi$BthCg*>)wUQ`z7{wtcS52KYPKz0q_Ee zzo1+W^hmJUSt)k+#E@#K`+&xz-tUidRJSxQ&**m-HMNj2m~p*y3OOrlW6#?sh81i9s%K(WTlyJa$m^?FWM2 z-@f?iJ-qv^`bL12Y>^B&pmYryT!z?dIUPx%^GghsxX+$Zol6MOt5A_KXDDw}(B%fz zXN|Y#BU#uf5)U1~x_^_@OC4MO1V1Q(P!K7mY|z#5e{@V190u%&NHoHcVWYAt_BC5k z3{pA#?b46)e($Jwg{We@e!&{kHvln#RqYuyfRSvkCCIU4!!X@vd2#oO>@Z_PSeSQx zfGa%oaCkT-TR*`Tj^XyVs?XoR>8ktnkMDeeB_Bt!OX9|G8&_`&84+LpR=!YWSR2IY z8YXwjb@#sgb=z`C8~2D^)QpV=GN~kN(ig#srprfB{ithhk76QbY)N%mhGNC*XN5!!r}G&6&{xR51jo3fGd(wViS znOk)D&$RQa3)elJ2Qww94@}(W_AqN(-_TT8C`~wa&zYdW056FvlOguwnXdo%+I&(N zFD{NuAb?UyNr}^Ul2Rp`pUA3?44`l23i15?fhzK+#Y7y8r;0h>9>lU+|9L)JM(pRA z&mi0tAZzDr^5OyK`K(3wyGhKx586d5nsioW!I(k%^2Z-dR`S)nFWy-J>2vNq@Dtw^ zA8U6}L!%Fi8V^sn%ucq7=<1zk?vCJ#Ndq<`FBV))IL)pr0ODoU*u(7l+MiKSr})Lc zNz73?AmAXlEbm>1smMw*xqRn3F+If)COZq9jYAVA?Dq)=Sffe^XYIPc6-{;Y1z6Tt341S%cP*jl@tDa61 zz$+5#ocy2)TTeuss^H@v&tZ#NRerIcisYRxnd6Yvu8Lc2qh~ax8KYDP@h;y~@83Yw>h^78NQ6c9J7nS96r2onN|-|j!V zU?NmBADL4&<&A_l9Jj0_9!uV1KRq~rABxKOx9LKfWaHVgN0$)2jrhhYW5_N+?o~Al z8P}_DDC+%jKo<>zVnKBt2v{owaDAxZf-1m$eUnIU9ivN4xeZH=Yz{F!U621d{+uX?#z)P%+rh1bG{d4}41oX2~z+%it(Pq7M z=Iil#N>hgm&4xlW?cy~$LX1+1m^)zM!~o4_XwD)FtC}GviGBQc?axd7QAibJI`4!m z{%rN2kJP7l&0cqe7L+t-46be_rZef*Cg@EU;m5=cs#%M~fe{F<+R2&nxXg@6k}ehP zI1A24xMX-AsTyUjJ+J@9kK0kk9bWeQq45}kAgj8^&X3@I(GowINA-T`f zItZL;`~E2ZYakWeTfO%-kpWXuuIlS3@@}o2hLIb^wodKtBMO#TB8*rQFsl@IYL@DZ zcn9%;EjvLA- z`AS8q6u#+x^KbRD#EXpR^QjRV>2Jgn1WVl0MK#=dPrL_0?5#^Y2OE$0f)(BUO&SCd zI}Hc2GkS6L85;v?y*9kcO~1#$jOn?; z9_U8dM%>mdw5XA#CGRjc65DqQBApam3Ru!&*-$_sw0TukI6$#bLg`5{^Ev*Y{3tOi zu>H6AwWQi{XOL^*7Q>bH^Uyl$!o%tG`3g~L<6{d#a-{CF2v5L0v*M9wHjkNfIK!IL z1CGhlX|A}%z-XAwo3zY9>ypvsC7C)yhXxYav;DWDo!v*aquXYWVi@nW4#phTvH=zK z+TP7Aq>GIOWp^S(1^j*k-MK>`^Q@0lxry3 ztP{MmU+>pL1asdOrw@oHGmNB%eW+42#R{m?(qJ_KDj}@f$$ka)Vc5M0?D}QQ+?|;4YaQuIg00V${m)VlCTKlQC8|Vp( zd*@^lnzt!I??>I5uoeY-vg`f{P+)oV(UVrE$(8U3seAb_Ug`YfA)1tZj_F(^rbg=T z&1)G=Qe&K-;#lM+k5;l{o?kT1%a$sR(&}Q1X4PL*8?muHqtEatb0gX3)$*&(9Mlnr zs#Io+njXQt1w~mPm*V!%EtpvM9w{o-xGalT)LN8O#P{A2ZZ!kog`;FYlSmg4G-^Lx z7}&VkL&E~4z1-N6BL*K$HZ@CIJ=2n1U880lG;x=ZsBlTbo*p ziXjnC?N|rEZ@whqxQK{I&n37wNkK{#q6M&=QiN?59C(OZND5K9V2n3t+aGn6Rk%rL z>+&(o4P)l)Bqb%`P(emUtJRC;KnCM-cakibE+16=iiA$IJ>Yq>(uT<&sOo@%^Hh&p zNfUK{op4gUxwE&b#g9&Q_dUbK97ov`OK8sSAiF9np}0) z8@Z)a)i0o*`h{TY+ILLgo5WV0EK$|X*_NwEH|WbOtN}s3-glD1cGhrhfA508=GTS> z7YiZDFDz>XUI%XTX?l3E>q?RnO~$a_DlWOnH*GaJ2{Hc$eQYIUtE~fK0h^z9M|^Ob zq`tEkTbxTKT#TQT9~sEIW-ugDHmEpu#_0b}C34H|UP#$`qGp<4rnFbM`_dmFCHW;+ zY|zQWilcNbY7SZ@PbjVx4D;zyZq!yx9eGQ|I zD?DE}iLrv;pUAKVtQY$Ttrq%p`AkIcm_`K0LR?fR)(#1lQ|}ur=8cgLPgEmyY4aje z%_x`+vj;tLDi`)*PN#K+G@rA?_QQPYr4^Ih{L6?VB>s-1aa05U_!!2g(Xewl^vg*T zL=!PSF{s!l_P@S<$Y=9FM<858O!Nrla67qt#M_XHl%WIsddP)v0LA;Cp*ZND+sTbL z;Jsd2>c>RQg+}mLle=u)p#dy@&^CVE7@k)gLCwlH-G54elw?`c&*xH%APC9%Cq=S# zc=hOicK-z67hGD}@k?4oe7TVBROS@d9Rnt-+!2Ad-WIngH3^e?8%LFK6p&^o$U+hE za}+-o#{XapjaPjji73brR)5MghaQU81E+y%LeeaL2^IM!3swx70UHR^TNHeuPyKME z#CS@EZr$oY!A;m-N3;_`ek1kD#nabg)5{pTJqSl_h>U;z^K2RmEhKAyZfO+ z|6ybLZDC2FzFYwl6JP>;X3Ma|hB74^!s^~#{Dyri+vj8~amhYi>g#S%G3vIUU?$8` zC;6+^kQnLk@x`g_Rk2r0jvd``;d_E>*$%s^JTp$7=0iC$`eD|EdlQqs5-fOUB%~A+ zWQPLEYBvRn$;iV1WmM#p3IufrO2^cOoJ-jopzFMIqyc&8*Ulc+SF@grNG`{Aci>L zf`vRAazb0F^Sg6hPG@RF(0mnZ#6WUeEA#rR6?N8pl;i&XYr{tAZH&}IK~;R;psx(q z#TSIAD%sbyhgdAAUz^CwORFcrd!>F)efKa)rXI6Xw;5fJ!r8C6J`?b;>Dlc$(6;-*Zz>W`op|%jt(d3@5F*(x&uGZB z#xXY$%4X%Bt`%5uIsd;GfMN6pYARnb^wa+=t5alT$bKXh*XB8Wc)z&uYuHw|;-Tq^xlC*+4)CyTVnGEaxFy?(I(|$6#o?TMXxWMfl&tc>9 zMiT_EF`IAO(KJ45cHC{NdHpkMlVST8#qswzmw*_((I2&K2w%dpOY zTeI%;RYXX(LYir3Cc+UV!R$ZeF@gvAyx<~HL-t$}P(g6%DjzeCfjv1RpQWm*NZetQ zvH$_N3(bruDB#lFa*;tnK~4~H=ymR*eVJUo)pt2{P$cc_V}JR}heGP-SUW5JqgVOZ zZM*97d^j$7`F7uHytW`ODdqxN2c#N^1MYuoZwjCCy+;~-XP@dH_Cp%8vsrJ^dHI|K zG^8J<#NIPZ>$lllbC+Z_iqTzDu?AR zfhbtmgxKXrk@{6$t^Z{c=f-=WOwcwTf);k0mD~*_5@cJe<(XJ<5IQsVskWjDAb!T7 zXeV--?dd-O3G?UMR$$={fzf}04A$N*dm4Je&zz>4em|ojyHc^9v9Pb;kCsK~;U9hN zw0S1$h(zi}1QU{2TSe|(E~QaYG>!dfA2TCmh9LaaY+8el&0RYS#OTZGbwx&u29zl+ zk{IjKcyrSSTsHduX7N=cJdw#jc@4`y6*n&iaO$^5)xy_y>$Z2X#8`6(2iIRs2U}Z~ zSmE1tTe~B%C60VDCFkDFA+>!5_!`>5;sgTS&x&kk&-)Mz{(!->i|a?HgV4M!-9X=_ z2R@OfH{EGGwUA|F_2`G!Ppn=mo&F1mR^bfl*>;RIXK=qB_16{P9*Ztv6cH-4hpKR( z#-|?SJkcF5QYO(3V?eR=?l2CbHRaEo+CJ}wU2ZL$Z+pK!-%hQpz=O`d#8jF~CUTF3 zN8Sa(bDdM1D}0wZ2ip;=(Y0a^%eqg+Qr8s?WgQ{oBGWwxNytRzLDx~1K1)eTz5zHy zmxpoNyXOGXIEKnEUp6)#X*M?Ur3E1ey!!g=bQ~NU){n;`T@wkf&lG<{ehZmXyy&!j ziPgy!u#hfh`WSdQ2L?arG0V3{eeX8_2nz8P4y@+(z+kC4`2F;skj$ikhI(WEjc11K z{!jsCqg5hzLGY!C(!1u<+Exs2TXKYG|BpVB9*6Gy4gnI+QRMT+LHpzj9%~db- zP$jD=HpSlV=D2^eQg1j=0~xXtp7j{S9@v8tO%?-lD_tCEo~{WW4w$)AzXq|A{9kdI zUc*laKj%fk8r|P|!?-y_i7HEyqR;?JQ0sG+$dTb+bC@Y5Y@|R$8Cy)8mnd{XNbO6O zwQ|XSiYg1EmPGE6rFw*4Q?DsJpB3|WM*4T)=)MvnV*g}-#{je>MhqjnRlbV3g5QO~ zzu;Y7u<&nsQJn%iZHffsiDDE<&rvgeG?6;I_#rRTf?^npCpD3S9AB%qV7BJ;4?SSAb+F%8U#t>&-&Qr~y;+K@L}LaE?WH4^rFakS^R zm%iq$qdo_D^|8qQz-hGNuScV=z4gvio)<9yDMY)#qzEjN zBgtl!EE;w`^NSo1aXj9iFX@pYBe$GeptbvKu+bQre&ZkW*0zHWEv%Hg%OxT=KkvkKMT<|{R9zDdp5GTE>zY3W9n@w z%W#|s=(5}vY+6QMb5&gdq|n74!MTVOmCnpV-J4z}-#5uU0DpgZ>be6<86Np1H}xIUUdx9^pN2xq!FxJ@pn%c$uKH<`~Du1 zF6P0l;I?Nj6!2J!l0ibTlu6F2^4oM2Q7u2cS5?8AFo?h$stJPqii3T-7f>TrR_(~-tt>S9^VK)0-46~k$X@JJ-k&=7(6>-%mxH4E-FhsYJ+9`w zQkO@OjGZ^kYtU`t!*8d{&Wf#5a`!HG$1UFvmf-gH<}GiegAZ$T6~3JZCJf6^46 z>`l?$)kVm|I_JoIc;95%XD7L3yu&9m;bw|}u-jbUtQ+E682n}XW}RZ)dK~JJ@s3B! z=|JY|g_oYrR2P$RhqFts3wwca@>KM);X4t-2wNa(YkMNFa^=vu+sI7D=Cp3(+H22N z%arlgsV`Dw(&C@N#~8i%eM(gmLfJpc+4}?PfP7_rqIkRoCgLw*r8^Lo=+pS!ZdDhT zdhlegAbxj2Rtu>^0O`%sW!||89QVX`eeTE>l8Q> z5^c-`})INGjvpA_?p8Wl9~`{~*-^(w08 zkA>jwiimYAhZ4aZ3vQiqH5stTVa9#Mzc$8J3KI*a6T$RZfmG@)vLpvEWSMRlO zT=dABe^o?*7HT2BU_(Z%A2M>kx{HBm$dvg{8GB#F-TB|a=r0I*w>ENKEeY7Q#FO(A zV@6lO?sg|msle^N^dH;Ze{vZ*QKa@6#`O@RYSVKy7C)$anmdhK=3u-LSdP8qQ|1{< zq(Y4!S#(rx@U>Z;o(%7ilQ&9bBe1U$j`GbwrJQE+?;)CURQ!=haT4Sku5X@r{PR* z7_PIfoIf!S+%*_rzk2+`zLib{k+p0e-0=y1Sw`uX@h z_~Ll?q;VjEu5vIC1e4qzQARTc8A(y$gFAyrA#{=OUjoeDFcBb0;+k^QSWITMFtIbo zTc;1nI-*9(XuEJFfSFt0=9p1u$~`sc-ayP<|18u-U0OKZMB+wOh6Lf_ZRJ|j=xzr# z)z<^UdLl!V?B#B^sftmvTeV>|>9*=+)Tf%&SxU3BYiP9Nz)nex+poLU#{x70-=fCr zX#-yBhg61u8Im_KCVHI`51FEho4ZICFA=Yp!B_$cr|aiB7}UQ%y2cVn$mTqCXkySU z_~l-Z+C{(_*F9*G%<);3|43@Z(YnMg95zmKbpDZEv}rXTgV_#QTA&8JJzechub6i= z@6gKI<|7D-x48PX;jd=Es%pF&YPpm#6zCn1TFAlN*uAXOKQYa5EMkV50L=`T3d8+@ z%Q{@AXj%63G{~ijWJIw2|HCxXcGwstGpLJK^SftPHLx{g3F_8}t+t9Q?XllZN&c;< zd5}5j2hZPAqGKVt8Mn`96vS!JHf-gEnsFjY%_Qv!drgk0Vt$##0(Li9a#+1XJrzzB z@gfHaGP;^()-A6uqMu}J0TQTG?qQ^7w4j~#xQa~7IbbY2j=Ioh)V~TE7N3h;Q|ZJH!%<;66MlKks%NWV8}S5Oem}BBroOxZrT}BMtx5rdztR3 zN-N2fKzu={k>HR-k9MelJA#)RABm)Z2kfF^Z)GY-k;4ZF$iXm$@0FG8z%<8+N&m7A z{(>Ow_4E_9>%NA`N9?tg>@jB#1bX_X$HFg<;x(D|_B^n_@w_Z>B0;{^;kgjYUPoEr zk|WDfolEn8hOKra(Bjro$*RaTm-CJI{zLwE+kk(VXkJzAr?t;C#N!!x4$^>fzBza? zJ3oRpqe-%k6f_+&TUFJjh9TnlPc|_a`FXR3yWGoPTn#7C-ANu+I8Rv|*@N-fntgJIfVNR=b zZ*=^J^KkYw5DgTKB@-nqXvO11ShkRNV#4RW;X8MFI$;>rQy46rw|XI2B|4zi)=>7j zQvjjIpL46#eN+Ci;E#!!cJ^$&r~NKI-VoQf85OOs9*pZt=dwsl%S8zdjvUI5>_>ERjgCa$ z1Ig4FDB!t?nmWC7g+y<-*;1tt0y!j=-cDHhEPNDyL3BN+_kN*v5E}Ky0%Clpr-gXOY*~{Q8 z1FCR*()vmn)Ag!8+8fw2k#|L|m|l4w)bqROWv>cbeNyJL*D{JR?># z*hk@bA6jMP5%gKH(It2^$m|v{=zkFC1Wy4-qr}zbn7VZ-%zQV2}4gBiPG||UJwTf)d?{HC^BOY5aeCP z?NGY>!Vem)L+1~rX>t33axvx308W~x0Gf~<+UV$LiR2>I93+Y4_UuHpN@7h_22}VCA z@U`dP4_x0qGNX&Hux5|`LLZNh(q2$(fpJ8B7x9AC5LzHZ?uI0}Hy1!OE z_6=uJAxdIw^dYzFy>DQt{0I*GG_L4B@g+C)Mz$bQZSEs#S~wo_cDMGyAQlx>cJNd# zXHG@TV9?{ygW&zbOb-w~#HPstoD{A+3{{w>7sF&+Q8;MfIu}HO{ay?=kAGm1fi)8DeTO zdio7Z)cEw(`gC-=km>Z6hexEY&I@0vc4bqkxsG}`>AD+1=Wr@l2CR>#vAk5!pwA+E zT=fhwt5~92l9rXJAS!H>{UQq&jHIP5kOc>icFPFo=5&*D|IF1UBC<%I`B{MMa}M-f z?$OF=`=#+^I}~j4ryd zN{vGgIT5$V3LONI$?K6qVs4Z}?!7G#)fHrTUTNvl`G_>6dS9@Oy?dy3Sq~@gSIm*h z13%U`iK!f&z%7Hy;V7b~G>ohPfG`B>a_lek!r0lRIki0>AP6Z|9!O&y9gKc1ZpBL% zku84*#1n9{eRJfc%A2wnG{m%(KH_|!b@1Nwry7NRJ8Am-jrgfn_uY{Q^7opk z$Md#8=U$%McTJMDRXW=R%;(n)tMaBjy!R@zd`+XUZ#6tyhR)cMCgedUE1(xhj6!6} zP*BYQZu#2)!%IK*fPGr7Um?BaT*gmTrBwa*z5S?q?~Z0PAd^HT)(|=EkF+ed1GTcj z@JL2-jYl8Ej4D*^FX}|*)ntbaB9xjuZeOxGOdqEy<`s|+al5uW*xiS%2tTu2SQ@^~ zQCyI_a(obeKgol~G}~EakErDpwb%ml-HMO9mQ+JtCN=p>bpGqlVuP=FSF++&>fK4@ zt&er0vWxmM1Eh$aD68RuNtw!wj5yI~ZPnU+jQvARqD2mz^;hi}!$UYw`9g0mH>*siB+7SbNeV|*~5MgDj zl8Euaopt}xEbYDo6&IME@|S`)J?>=c(px=vqo9rtx#B7?8UlcWPJE5n}*e&IaOaROUo~2O%d*3VV zEl>ev>ukL&y4Y7-wdgZ3JR}j4b48f!4`YVaaKuDHBqiDW{7nW@J_Mp-be7rhXSHl$ zq^@-otTFSAASoN(46J187@f8Gt)?dQwKe5=+v=-eD^Rx)O?vg2UH(eIEUWQrMFTl2 zE6HE+CjkWFXBmdBCSkIu-%mLs(^2HoC^#1aIQG?dBwGw02AWuvh7`ss+;QSi@Vyf_ z8tiLaKA98U(Mn%Pkh;&@hqwnTj00pI(@mCT*ho(r1XaC}fIDDj|(>z<_@ z#6~N);iwQ?lQQr36NoH?1J+$iP(^jCG@N-M#f-Eqa~{iW{J8)DeTkFENu`A&U`wWf z%O6APxZP7XCj5zRlD1X_XhVyA2i4Y|zZ4vI{6@^-I@FitcDu#pUMnu zWlpN3Sml(x|KuEmp=YuT=4+jcFt zY8h*pi_5la**Iz0eD3e>x}N{e`Tujj@zVQn-A}(RdH_d6&fyvp1tLcL?ixqHLe5!M z^{pbQf0S*ZWv^f!A5(9?1UT6AjCdaWPZDmV#rsh<{@OD%B}sl-7Ars zjUrG!A&WKX%eNVXb;PtEg=4GbhouSpAoakH$=^Tn{?>Ns@_I#Kc*J4`LdlmjBxtlX zNz)^83tNlffaLgqJPcwql*UXkUtdAMGOV2zu2}&`r0F27zJnDd=Nh~ek9}Y=tG_qt zJ@Q66C9Sc)g=GdslO02em`ID1Oe;3Wv@Wk0^e3>ax185h4gc@cg4fFETGF(kg%XHNaT*>2q3yDZM{e{AHV z?}#%J22DdiHy+hW-1Sxupm9a6#Db7CW+{lM!?9 zdf<(5`JYW8CX=Et{MCfg)+$Ul`w+}Rr~|jrN#CG_7+-&lW*@H+xpN>cqw=(8RB4Ht z;>$v@Z2oAlar$qc_LABW%0Q@Yk8tp8L4IU^YlV<27tIe;^h`8uWG)J)28Pk=*4ew zAN|?Gy=LW`8-WLKd7v<;GOy;fZR7oE{H>LEKV|N>-Ew_&Pf|)5Or-$EEME=ltv9*P zKvYEpEh|^G6n0?aAkH?Z_Mh91bHQ26gF9P0X^j=RXNy>UyI&(bWHH(Ta#yq9WwG{l z=rVzX+*98(vtMNPS=E2lkhtgQ;4lEPcrKUGlnW3Zp}Tz3sAyfA7@<9YG7^+4t)_+( zfkDAqIyvIB^`$>~zn6GsG#f!Q>iLS4?~8J>^jj?X5p@AE)#!(q5V>M;2M1Oc*K2l% zQ@(81$yUNoF1S*0#7H@Yk?m{x87L^C*t9M#E}}`MI@{j)+v=f-$RYh(J)s2?g~xs) zfejBM=V2}lm$vZxX5pM~JLF`QaJ>)PY4ZIpMr~ROC$oVz&bPF6o2N!h8s8lQj?{0O zf5!}7^r)Kp%{m<|bw3%4fSG<;CCX}^WFkwHZ1$X3_{LQ_g46xDI#S@+x(AcqFuFU`qrRhI^sQM+)?erBB?OB zP-Dxd{O?HoMWVqWr!3_2iwUn0H-`xg+Gw+Jy9j zqG8o@xQ~1wyKf|<`yADy1S~kfMRkt*6Jdx$_ioDdjEsXV2^mB<8`ACn_c`O44ibohGb4n+o zK!r8ns{T;$_>koTJ7zk}PfqBaqRwAKY!>xq*!pAO{FkP5`q2dSkH+&T+RFHWD0F6kj*wrDcC@HYs_){_&v?Nm*p5NQsv)y9OTHgw9YQcl zR9wj6Ge7(dqQgv&i)?LcrVhDO)!nME>j?j}H%&2_vt+ktowYO)sh4BS#)2^?T?#`dJ$I{Zx4rkNf~H|^7(jE%DV*7^^em#$rLM4?3Vi+lS* z{T}k_Xs?7Z@_%Ix;kk-Comv{RTuQ&2ifKI6?He4Wn{7PbZn?TR8DpT`mGvdtzr}x5 zrbDX_8E8d7Y7i<$(2?yESV{O*a)UT|NqGYYa|ae_uUHuF+C-Zm`q`_VFDf=QLln%6 z5b~&?8fl4=CfkvRAUBTsSU8mIEdM_Kp>E%9(ey*A(TdNp^M=OFJTX1iouizg2k4ORCg!W_0KAOXsleUw}ZaD#U@bi&rs6q$!wa0`tQh=;>7!iS}E+bNoK7u zL1}lBNJn-(-iZ80UZe(gpIm0<>UGvinD`1}Kg%UW%e+ zMVX*B-^RP#yqrwImm(Lqk;XsfS0875Kkv+V2TAFu!GxFtcbjxr8bdhdRI@keHnFT%DOf^QCKtubJlR^ zU~Fyf2o8ewaX61PpmLh)OrwSt7E;ethyOzxV%g*BnsR_CD!>V6$xDYxsY8vnR`5B553N^Oz6H?MhLiNV-i*6VJCkt}VRv|*S z;RF*`8NNHtnXdRfevtN1)Jf^OnCQgr>^XYzcc~LA5z(-B7-$uvQv?;+PzutJ8a~8S z_~{o*va9N=o_xkBJVw5ciPo{-t5=GD!kl0RYL58w-_RU&w|00kuurD?@$1d(&N$Jt zXztl9Qu7Y*Cz4SM;@J%tIA*ZGgr~opF%GeW`W&w3SOiUd9&VWJ5QNA_PN&%#E4OO@ z9Ht{Hqtud5MU4KyJN(H2SQd#5CQ|K?ju7<~f7&e^fM`e8JG+w;8frZX1FWqHuAD~T zSw?GQs+2v+e>(TsM@Ku0QdUjb%YK0lXytYG_IWgi89o2TfOmWFfa>?potQ0E&fg5) z@jLnRz5{%@;?AGQH=F(r4x7j85dqjScqmZ(yc##Ts-+Jav zz#o)|Ut-uH`!Pc&;XTHp5)v@zf9JQ1716xN4~?cNQe$GM2KYJh86Fr%Caw`bPGU8> zMQhhhGX*nKkTe++@w?Ev36O#R{Zpyer<{_c2Fqo@IJJd?Z5X$Ol+lL3NI)Jt0;A;+LyVD@Ed)zRZGQHEdbU!GxzO+{z;AOV>rnIJM zzm(aYV^A*_Ye^BG0E4Lrfr96vAIMGzm3Nf?e7>jGT|v~2d@wJHsBlnlkp1M8hT(k+ zi`)Ti($O5=yS~^|H1HFC2D|qP&j$5T?x~WDY=z4>bg10u4%@FEC=~VDj0(H@QOI7m?f|L zB3uU7)9D$WacLu#ag%vJpi#+Gw~BV!`1AXP*X?cUj(72RKl0iPaK|4lw$}J#sY31} z$WZN4aPB2PZp`h>q<>*p`z1mw((ZS4@3ZD@J07N2Ffk; z{G(42^|xd}5tS)=wf$sa)GIl1#ru&Fw!{E)J>CCqA?)ZM(qR0D9%n5Wz?cmkAZAXE z2;1#U`h|zPdu{_g&D?}13$C6RT9%Be5eZYgR*5_+@emeDnHK4L4EFrK_p36e1?o5q zd{}}6s!nxm@;;V^cVVYe36A*82TnDK67d_MVd^C~ zHhh;I#x|G&&**oHas4!frkyzl#Ki>cF?6mtvz0scRvHbDTD3H3y6s;`?6(zw?zu_% zH!izpR+hq`+U+qzPp)0ye)?g50f|{V`QrDdiD+H`jWE5eNlw{?%ba&V+a^GJIQZ1F zxY?Q&!EZ!vUs#cwIw9X-E)JT^iIzmbv3RQ8KG$v7cYSc z!ocGcXC6Yaz8SUUfd|CSeuDvOmR@2t+-Q&c2m=CHq;Cn!B>aa>vf<)$6(R!PFPbHPrxe*X#rW)sbtaJXS|GFFQKZ8s81i?F0&FoeB(cKia z*78;}DoZ8H)?c>!&C4j-_x|CeGMkgeflo>+f(JLl%2=hTl&P7Fr#0A-KhAB%n!a=CzcGu`+@g&iPJJg~%2`&SKzK&Ah-r%QK5Xkf8Of$j z;Dog`eeUL_0$`ZJ=(gexhIqqDP|eTJBZmFaMN1ih4WaCjs5Ll z4OXe(@R~M`{-a+rCth-bnV%#|s$*!xhE`A9R*n5>m?)^EydTV}C+yhj=S85In;KqvFmFVjtUG z9k5A9{>$-WBvg{(sLtv;x>}WCK3^D|)}S8r2j%>&=SVjeWvOvQ_fEAm=O)GuJVqG= zBAQ7qB1-jY$T4Dx{M%1``Z~L;U)MRw-8{ceKHDhK!!WO_JC5fZ$Ugr$f`xC4I~NYl zj#p~27oUPI)s29y7grsTbY|6hztA4<=%2~&#eYU<;p?dAI?B6Un7R6nYx`9l{xwC6)?z2{BSA4b z&o1xU4ZXVaqajit>leAS*hpBq&V$BhFNHrYGH%|tJfA}5BBj$q=isFRvtGr#C^8X6 zl`G!QhuN^QdC2tcr)v!o1t@K_I9&P>Gf|f5C*cq@9+dGS8cqUF15{72fiqfH|y}C3==3 ziolA&%GhFB@9AjS{oO7${(Vyu8&t|*Q`H63U4&? zML$c0ghCH%2Tix)fPbLy=q9#y7du1FU>aN93)z*&zA8^gA$SYaes{}*ZPIejk@?5^ zh=#}meChQpKmPsvQ^D7aiqyTZ=6wsqNa}zzAXvIhv>NnI^o*0~{xkP5MW5LrPW2jZ zqw5<|4n1NlebAPl4H8i}a!{+K9)CKHNMDvOR4s5b_k||&_@B_jAGFW!J6{I6O}8R0 zO)6~+8FA4)@@zV2h?@#+{%Cn^`DzSCTCSU;j1mmmJbHFffc>xA zm>n3>p+J1O(grywW*#Eeu|HLsaM0AMdnT5esI8-Wh5fMi$+E=1Tcq9=e~rW0SR?LtQjpDW_LJ$&50&y2HSZvR4AtQF8xxQ2fxE;3FT zxvfHu6V_B2S}Q7~Tp!iUBl~OwAt%oBClPUId%YwDdnkdi-j1_$$D8Ti%FV|2_B3Vn z<`DVrCI!T(lny}gMgAgReotKVw91peMpXzu5@1Tm!4O`XVK50X@u4F=HkGKtIn*LE zV7PjLQ)7op>9yrw@|i+g*oRQg#c2RQHSxLMau6?u)~7#>ZYOkO=2tPpR(#6vd$^uT z_DAIlp@F;FUa&zdJ{&UcFit%(Ix=X?!=}C*dkWV_&z_u#453<7ncbX|(Mros{nVGM zg1QNop?Gb>;OhA~XrtbEB&~S#2WG08n9Wj-je6TYR%#{9o}DAiFx&9{57A7RAeEH0 z4N>$Kt9B!vsRe+axfD_@zHdzNclukpGdB#wtG^gQjr|PPI|;c@_w3bCG_!ba1|{pwxxukiRT1)=@@cleL!pxihXid# zmisSQIpF8UZWu?Mt^WNBpFRc$0&Ww*N|uRY!!pJ|_e}#}Lhn!6l>9ksF)8RM56bak z%KW(_ER_^s+%^FskmwBAwU>Sly)f~gf?U#`uP#?c43k&=va<%MTWH5Im2p~bTafxt)> zdL`T;ir9?>vp3YFrMC+h&BBdJJ4wAkETV_D;&0`&f7CA?K_eRdk>ti;i=monZP zFS`Jn!ud|aIQT?HBJ$Mmowd#{aRVYsXX_hTP75iFU5w6I9zT;K?lHqv<77heNELRH z;o0Ubh-u_tw0TE^&>Y0kA=dUxPu1cP?6C{ zyJ4P~;dayjoM4j%ctE05%Xo~5GpeQ$UWR;O)*Ef=P$%NU<)puksSbE+lYh>!Pku2HXO`@^u55#8 zWeT##&pYi(P4s=*i^9hUh9el(a$nq`GQZV7f3Co~H()4_&ss$SHWz2>hQOkTq*FiD zo#i%N<;324^T++@*KDXQQZFp#*moa`wMj4Y!x(qw4eC3&zdv00UoPCs$cFQote@9i zsKaD1l|fzr))tiCzUi6K+X|m##YV(N?)ftw`Z;|O1cH&iP_`FHy%GKs^Swe?Og>hI zo@aishXUFwSNc8V4KvD~d@DGGfn@s3L7E*iY~(9!g-Oz;2nGHaKO-Y!6!vN~qHFUi z*_*BOXW1{9-L+{JFIJ1_<14K&T7Ul<^D%f8qVI_3w<>c-S?#UW?X|X5p?P~_wc+F4 z_z1ygB8b*3QsJTo1MTyhRH+XB>(%uP8ym0LV;UmPH|UwxJsg%Mp^w`4;MXSfeH_@3 zh8%31Kt6hQ$ZPC3uNPJm&VC(9nr3a<%D8aS@$f>W)8wg!49{@4HQypdxo*~1_1HxR z+b@FaC7y{$(H^TW;PE#xQ)S+IrlYj3^F&a&h^T`5h8y!l4k)V>f{zy#f+m+ zA9X}qUCEH=-hhD0Rs}Q+>Fu#*Ydga}Gbwiz*1JC@ESF{v-+O;wq@RdtAlp-F91Sr7 zH(f8j^(i7D-Ja!lBo8JU{Q;=n?!pD1h7nrKJZL!N`h-;o?SXNn#H)4EscSN6&3~&M zrCH_h+T~S6yDNi*u;LvI@VKa=1aS3@Yo4u-qaD5f)W%)XHQ+3FeTZd)=EP$4 zSS%m#Zt-MRuP@_Ehas}tWIa#Elve>gf!IEBvf{gVMMN8Wjy|`JV!1RoM;p&9Ufp`T zf3kR&haS7A7Ai^ea3+M8T2VmuUE&lQ@Fc(uSY5(#;tP$0luvf7jqJ z>trKX>HBv8kUNzVdH&@DJT}e&a_-?L21a0-f(A`L{3fych$;*HM zf+81X?C;qZfC>~%(HAZ0Pvh_DdkiDUm$Oh!6N3!K1 zfisrM03`+z?!q8W15~6y`i-=#EXRB$=BY-pDi9=J)Yymzo(fgrBIL1SWMuM9Df?(f zf0ZyRu4CAmI{>GJ=x#bn_FCAvZQH3@)Xr@;vtx15H)BdvQB~-4&n#x%>DGu(gCLXV zjYq|@OVT`W-*tX&xjTFzZS-kts(J8ZHJL9_#xsLv`V^DALbhN$*F#f;)MM(rQHXk_ zCC4m&Z;16(j`Hb8b-zA(H1tvY2=)ciF!!IeuN`t|^EHv8_V+aEa=|1DeRb*4Z)oMW zCM$M9R#JogI{@mOMR2^ARy@SK~Y z-nqyob-f`eyM#3IS8EoRBf3BACcmc-J^p~Uj01P7%SP;o^;9k{QW&f?BE6gE*zTqY)S>}J3~+~uBPN|vb8lk&))3SrKz zBqMqMf>ssP@Cp_sn@!FDPmP;Gtp#+;0}PBoE|82AMAaI(G$n9K;Y&c0zG~e<6JaeJd*~5LEa1 zwb^uc@N`75}nxQkwi7PGobz;3Z#HMZ>xb8La5iZAVPscf(x z%9Q`fjsb^m8EPv*-rb9ho)7ZzJR12Pk*Ctk>DK#lcXv(f(%yGK6W>!mrDa3-^%rZ| z@mg!v;1Wvmb3ROvxjsk(fsyjo!IG|0;zbr_@$y-tcBo;YFOV2kOD33P%6OWJ?TR6K z-+aZ6Tu&1;q(l7G0CCO&<)lnbq(z*`ELb$9rz=?Oi#4U(l_m6NDuj(;7#7-LadU8? zsF+cobBnFnP)y9}ZR2u;!J~^*&pmGa3%W=Ol=yF?SpMmv?r%pS$ad0JA#f0uj9B+U zTkNwr;N6@(rFqhomYN&y_|*f$lX}iQEgvH&BhG+?*&`g)lYD};=eM02Bt`hgh1gVD zaSSPVatbyJzg1!~jnPGmehjHel>*Si&=*6A*|Q8qXCmH_jdeoaCC0vGh;-O8^{hXK zxk*;)CYu0*bJLG94F$)V1>>#gJ)3>=icc-xCZ>72o8Xe6)~5%L=6Wf(H>#?y>#-Dv z7kte+^pz$fR|xDAH)B5g4$J?_)CKAU=@1C&n86fP;2>*M#T&f<~oH z&p2UFGH~U{VUZpV4!A+oM=J@x!OIk@7_jVh1|J_E13H-P>*st6Lf~3OL+iRzGm;Uk z8|qUT60Gv^b^bi02NVZC;==<2yWsuxhCK>J3{S4A){)N}nV%jo3ZfKFLIE&Oy89%m!y$*I>Z!t-T_}wpozGI8GKxsLw6b$s#cOxrdV{!0-Bo zlkDJ~y>kPAp)$Z6-dRm9ipLx+uDocC2!wnFR3d`C&SA2pd=w&c29`3pz*+(Gb73>SVvHF8z#F%ZQX)P!UX5phWC; z2}Ot%o>=$e5Epb1rmL#d7rb8ql_)__Bvq#p-M%r6<-YHQh<;bx;HF0T3$j(Ln; z&!xm4R)GpgwP4>TJa@80I*@((jtyHaI6tTE8Xz%c+8LGD_>S)0_)WcN>a!Sp+*qgT zYdbO7AYzt)$-z!*LK5oo;6Xa;r0?Eyn1cp+8qse~S+Ph$E$bEn7&+FkqO(Jdx>>*v zzcF3dyYszQeP5I!;x?&M;kRmXrI$)PmVY^VBc&jPE_#0NGq8-=%XeXIDf)8~sk|== zm2F>A9&TGNjY60MmxDH2k9RTHVRvzlKk}AwjL?5k24DUn=Vcy^W<3`y?0s~1pV`+E zncd1fxh@)m=nVXU2oZrOG0%B9qydQPPVizt7IrLxp`$C88uKFb=fcHPnBOEvbh+yV zc+G(~lb8fZy2#Yi&0nx7SUk#~Lkaj-Cnf?#DWj?)XvsCriX+p4A+W zE)$H9ke}O_6l#ydI6EzhN@+bcXZS>qA?`%UH^fZR4Y6IzbCHJwaJ`B%ZoqCnr% zVnAF2d5TU=&TaFVd9ao1l&$qM!W9qTs8}%}`xj}}1%|^!#?7|Z&iO^$#*647AM-|& zG~`nlJ&O3phNK8qM8k<*JgvXAn9}w82v2W1)@pj{B4N(@VBAI>@u_^m&H}<3VZgw{ zB*ri`XK^jBYj}r8m0e*Q`9Tg98C{FNr7m;d-sT5KAxa~>+BLjUm%G!n ztQ}GisZLYPC~R)aug0m>ICZB_=9@rN%h{$`f73hv@*_YfxB-)RW9FCZ^P&aj7`HM8 z4-fzH!A7-|1Y7d=EU1JxMvmqC7i2PvsVIhndvXn+&?v6j#=7%qv1xo3tgwFhI&MAk zM_!3E{>`v1en9BGBFp$K6o}~ZUzVfS6wV1Nl>lK@nz5y;e=MfBb8tXD>3eLH- z37@&J=2ZDXTpnngA)(ZByTr9>V+v$$^q`yZuQXA7>QWTFK2DJv=HJ> zVIm%O+09BW8U=`HH>gPN_C$tRhm~y1>VTVyvX0HR!by5+*r<(SA`=#NlBDGGn_h z9F-4Z+{0|qhNJE_Q|=%LeJ_O4849k%$!!I&%!!j-2EJ0cK=F_@fx$eE8doK<=zr(7 z`BUsFf4htji%J;fT;Y)SBHZSekFZaLg1IE$Ib46S#jky_h{KC@L%MVe$zxKcPh%qbKs9Ac7M9p{Ie709#ZI<& z7qx7dt2{)gpqQM>%CYRu7JXo=Ek$C>H$jZ)41LmfRIN%g=S{R(&O-sk9R|9~CN`h$S z*=X-~hosaO2!vSwts4aD{zzfXQF~dMSZzZbVG^>_eg_*a+vN8Zr$p&*L2EG@DdM4< zu2rLM5CNj~g=khA8dM<2u!i8@zkkLH(XR?L*EeeXXHdo?6NaQgZu3qy)K(im(Z_WL%@SAi+Hod zZxMIXLDOEt1R(ZOBq$tJ85*3OTL@39ROr^=LGd>5>56v+cJT-k?w2*@MK@GyLTzL< z%!@luk>M{(GjQ&CzY_cM*+2OHNggaa=Qo)NNDVm>#_04?jBJvBMYJoz(ybaS@ceM| zQDeKWQJ3^3qPv!#N%=cem|VDM0oLc?8$@&?%a}GPdYCXDsKe@;9v60Z(aq|@2NJv( z{jfqFt$b07C=E*nHD^yr=MA!~)Jep%g^GoB>SmfD+BP;x>*_59slg~$-ztHkFwb9G zl_*+UsAZGBV~hIG=+mrTpaGb8lNA=T?NZzt$B$=1HI>y5nJ|~Z()MPbsh1D(mX9ul zMj&Uf=L(DEbnCCDZS(7YBHcR1xVD`gHVY>Cuu|h(JrKrtvWe1^T!t&YCc3Vq+0A-% zs!{YTED4V8Rd-t?b=4HEh3>CR9(91-f_jQPVDNS4P(oHusf^#{;w&AM62KH|$t%QL z5A^VKvQfeyuQw$r{TGqwk^AOFD`O(OK)bU#KUbImdahGg1cr}|jFt5H81a*&2FdLF3uP{}Y zTzIcK_i7*jEK59PQu?A2;tLV|ltck$JcS5){Om77=BdnCxVdYinww*VQ#|Dv5SWdg(zZH{k!02Z;`kPRN46tPjj_tx#inRtH} z*7WI@H8j=56BAl>hqm_p^?=m4h!&$S#gN~vryuVJq}f)t6ndLQXi&MP^^eUzDQR}^ z3r1)ef#D4bY~J#*ZGy1PRZF8g_q+p(zhi22+V7m&#mPW-3(Ab-Nq*2p^*Q3dWBa#Z zKZh5kLGk~^kp2WS_f|ciGt7cU*~}eeW~ox!^aepleCCKFnrknu(cBI}W73v>PU5AB znj_wl_Iwa+5$9{r$JEl#ph^8$KAX_3fUjOm@y1`c=`~Su=qPdjmoTSK^ruAXzj z-xO9FwUJ?n)N=0AYP^|Ci&i=IH#kWjs-g5YmT8tPHW|1pg)}TnT>bhh!0Wc|s9>8K z?C7t8DF!unb_nMRkr@E&e)Gqsvm#LfbINX8q1LALoXHa+cuTcs7fEfI;mW^^)m=@$ z>~XI$-l5(J2qoPMni)RpuFUy5(4%2^1-lCpr5Ys*fEYoif-C$`&0jyFlrulRYQo9D zj$!*P_rWy3aObKAUU`$@k0)Zs0&v6Bx9`b`fqv4FC8V)*CowC;MP0n=oYS?1yic*` zCl~$U8Z-MNd)Bb>B`}}{Y5fafT38K?@F3%5bx`+P(GLwz4`4b+^b)%8Ufc4bWZ)%$ z{a}~^@os2c-MUBEx<>IH|5YoBq>3A#)GNf$U>hAw^xWlW=OuY^wB2s`M3GjCc$7QWj?3?W@ioDhf7u5f^E4EY6=2{V}5_j9a|26iK8NPty`k7*$F1#Gl z^)8kH;*9Xp9t>YC#41}YTw@P*eqpAbfXW|`+$nmu>iHhQ?%jb56v=peyp|-|K{Dj6 zDqf8Y=Tf{uNr4B*q3EA}PKla3YIV8YUQ!HbE;vpmY(#GL%tzr4hel#U;5-kWu$R$X zuK*L*D~ge9DAPUljW9~R`kRpvld=;}j{vvp?yy2`1im%`kOMGQRIQf5N`pGrFQ0w=VMEN}NB-b9r!EOED^P3mQ2qfsDSZktmjsBO z@P8@`k8d=%>ff`VK;IXbN_kL1Lc3n2W0x0^-i|8%mM306D5Y%Z(L3EdsO)7b}Ex zZGL8mdE0Q1#j}tN>T|d{0}EwS#ZUeNK~@&aP4a?WJ8jZuoCLb+4%SWwb-#(7f;Jqb zsMUbn$g2;RL#V81J2G@}-)*(+e4cRet5Sr21AzJXBWWegi}n=-%fSS$!>BX+uzQa5MB5Av5_>M8AZAr#-eRrIE7dHJK zG*|dY__kIuKs-CCbL4BuGq^|;FaHR-u>ZQ{EgxDIK}ovs!`Bi~qn6LR1A~NV@7X;U z8qSi2G;*#2a+J7plq(NN>4hTwHdU!gC%OJ9%ri~GgPj(4SNT)3I9U%=9R zneXR9frPnr&7>0Fw|Lkq&bx{EAyRn}MY6h6c|}bm+f^?Bs~`U4Wzz&5A3$L;nUqK1 z!Mt}I`>(Rtq(-Do-AyRGB04n(xsztEIwnu+;3x%5DoD3frZ`?rc*2@2DklzxPDlvi zXLBcMaAyl8;z~(@41|UvX+V_P%Z40{;?Mhd9W0%OQdE;)E_rWT&gG6iFDZAD_0+E& zUcs;tId5V}ieJrW0T!KXLgun1^xu_;~T$PTAdO#|jHYEw^>OwSDP@g$mabI@B+V z(>=Xhfg*1@-1)Ieod1b=5Yp}vslB1-O&$Gqcmn@&OLbWh5w}XHJ=m|k&>+Xv)Fdg; z^LtN3cg-a!mA%Ss_Q5KEMqtNDZD*vQJafKbs@03PrhF=6*ZGtbuxegK?-uftXY-AzAJiGghCVpN5@+sEW>omIE8X{Td_xcc z5jssrzWzfk9R)#iEoi$+l9T!pjq}mY|IAe4M}3VWzOhkpChrLc_BQJBpMi)3iud#} zC~Gu8hgG>{kbnp>0ZN8%(w=r2|B2u~4L`AH#OEG?@)^{8LoJBk%9?{Wt{kVUVUS=# z@6??)@bJ8~{3lZkxyHyL>yiRrJN&hL*l5?$Hh#o2apMGwu}Hw^sN}EEkD8hO*9DUV zRTwRYzt1CtL6|(MGyVDmt?rIJ;$-fIx}p1^#EO^J!(>A&4QY3*Cy|EF>&*;(|vG$v~Kwz|X;f zTgEEvDYns8HX;-OBczZKi1nAxrE0eg;IHLilf8Go zZnp}*)I-Tr;L2P^0tk8zLU?qFQdeR;9s(*}-hJ{X-FCO%gh475g6T5JV!#s29i^(-CYvgYPVAc2vL?!5^OR!kPzkK*5W_bS>=%9 zo#?c)*WkU%!SFenknpgv_i_qH#ncqnL1|X2NVDjfs&Eg5t{`Fs4lF-v{7qLn!YZe6 z?jNUd%j~Y}Itr>G!julpsGEvB3EY-c;fE^cj2aWh=@gAdLl-F3Bi;bE191^%)pq>1ZVzTY3Iv zYo?l#Owx=VI#d9|k^wW%KT;R}XTe&P?pY^u-Da6Sr6o2XkqIhh6vPqP)LP29Dorm- zL|Wc%NGTq(Wg06fhgy~9}UO9eRrUB>DA zmNmwi7pGGF*}%QKmvOh@$R8-;FQ!v2vv?wRF^#rFoGRcF#{`O=dT0=6W;Vk32d2W! z-Ox?T!BY|_NKLxqV*Rb+=Y1N|Jh?D*!VpX@q{o>Q)kjDs1QR-3y!NZLjScirIG~RC zMw)`8dQ^6kD+IJR(F=YC7uOVcB)HF4`Us+P(Z~9dbCf_zh$trMRAgva% za4r_WOlN9Mws5>hzk<*yLRSN*{EjaEJ{Mkj9^=-5728A~IsnQ>{v1o=K%||Q;F=9@ z?B`PpcN~nA90Mkgmh2ER5b8>R5=dJm_;InU?qUe(IE5HVXo6%Vxyz8{Rlg-K7SdMt z=#Ey|_nJKP;=N>el~r<68-LN)sz;~Y*sqYw?>YCdz+6VBu&t06#%*+?^TZ>x$?z?2 zS4{RJMis`eprUEFKJV4pUGQSk(wN#q#N5uX8I-~^76sin4400!eAvr+y|^}hVC?>s z%0O6Xlm-0*SWC93ZViEupYP5x0Ni#;5ZqM%>#{D!HwDePKUog`LbQE{7*Xvqt*M{{+u2R@4oU7l|-5!?% zYZ(n){oNiP@dQ9SkC8kS_!tLJqLhYOuaV+Te@YKui0;`y-IdZVmwRt|$s1bq(`T1k zOLe<5=B@=qxRSvtT+=5v(h6e${@L>?pdnv2%fnTrB1c6a_ zY}R}$M6m;#bZ~u6tMT)!Yx8cF1b@ZuU%mwHnZ145sqgt{Z>h_D={^Ql7Jzp@D^L;O z>5Q-PN(pyYcxidKr1N2J7jn*VIs2s|Jc8ng5?%D2oAeVZ=_m2kY%SvMNJH#&H2mD} z0gMsyziaL3imP@je#^E?S|NP#1+CQj7` z8{!y%B*yQ3da>W%$jB%-q?-DpV{p@U=QppERSb*2MQkZz;w%T_i5EvfuMgIC<#vOa z93t|ie1P{xV_74cZI!rY{7}L9%;sOfi~@s`rL@~ZbNg@0O#=$I=gAxOf`w1&Qlp#q z3+0lmP;!EyYk1u*7=IbHhG)wEbKI~hl2Jjf;6ap69`%EO#rdo_8Y%13>hAMp44bz0 zpd0yz`30HY&FoCjtB(+htIpMxS}*NJQ)7%&EpveQUN{|-LcMG#4V(8M#VtK>0nZxy zcOb8L{mVlq-i*2Br?~W*>S)&YH+P}4Y=+bV$mZPkSq0qHWe1z~i|5wcVSqhT5@i-Y zm0;&U-BPP9JNC1~a!JKR!*3`91 z8-AQrY+-?fPo|Kp%4J>tle^|ji%W)bCr`jgw<`6`Im#xt@wTG)+shsj4*9FKg5go{ z6;dJZdz7=O(9%)ziYfDB4SvD~%><+u)=0ngWalJmmo~J5fi@mWS%BJmJ@Lu$%)=tz#ZE&Z_86fag9(%kbFPCP&(UhDX+W;6a3)s8Ei!Kl6#EfVk+kR6HG zvglH0@YRt05=R$ElYTS7_RadButL_2E`(+%VKzPJp+Czs{|uN}`+w1eApSU88Vjn# zIT=5=#U<5H7-ZHP7Nb(&ir6Z(sNE|6{oD#jK}CT9+(k-iQ|neD}E5 zSKmkscFs{ZvlARbc=n8DFv#&$Z+RY_v@gJamySeGE1lG;w7i@j--G=4&4`fjLe=?Y zrMdjFOAQAnHk7`e$xseiR*cY{fp%tfenPj%3e2;#l#y6C2hrWTV&Q&!X#PU$h(h&aSK=C;tR; z(!NR2AR?}3e5r{&nS!Q;ZfF=26W3^M4Vo#2nny$ z0k6J!wY3JR+A_MpLE zthe8~_UItyAR2et;|)vaok(HAN?||OPGofv>?sOxbV{47UqA{JAPGHO*tw=U>F3;9 z8lzNa62`ENPG$5|=V)14bS+%HZy=9<-DW$)6~qHd6C?1BnueF67F98aqej7cwYa%N z$n&2mvre{NM;tj`uhvqZ`GNI~T76C<$#ZcNjD>WjZm;BDWwy?6n&w|Na=ZvyS7|8m zKjS_%;M{gZM5>w8RUZvuIgEqXp{VE?hEoo#(RabyRc4-PnwCC%Q08nu% zmNQ%Ym6T_Fy_|{Sh8%FFPAY%Zx&5)azS@&NF0Cg8c?6P)*4i%K-#JW6QzulSmIRZ&vzQ3pzeBRtBB}7HD3P0*=KrNvJEg9psJR-D0>gbgRRQC25y*tGK{bHTK-?5JoRVr;NT z`*78H2nkP5KCm!i7h5K*%t0}u=-!5Pp#$NX+sk&#EO$qC3TqQ}p^_S&C+Hkx^1_Qd zZzPgC&yKbOY()RTO`OsKBV6y!G=L19P8??$6|eU4U+D=glAg2Qa?L~X0GbwkF85W! zo|8dqElV>u$jlit?)$8Btm|*&cdv3H$9L(Jn-mX-191`CWf8xhU6YKf+R=||bUbMG zGv2C<`&~_C5WHQX^V)=oeg{Fb;RXdk=Gue*zO4SKy|nQ!0l7rA?@+K7F}LyMxaa&% zbR>;-ms3d35nATI*fNd}>bA;x_{z~D-_-xE^KPfsJ zIB;A0<=*5P64&9DRpmEt3oc*b4++~tMgP3 zpBR7FedKw)tG!?-=RHN={cXcmVEoDc<#J49!T4#)-T6ezk4Oo9@jOl>;A@}rh)aqT zal#(zleN5H(pfS2v_puKOzt4T@fQ+<-9vnwkZqhJXow8;2Gs8 z_a&%M`JJJIj2E$yu#rJ-42FMnw!-rR$Z=9b01nN*(HYx{RMob^a<35b(c}~~%GtL@$=|x_-{``3- zNk$*1`S0uQ?A#WE^S|QDuMbVMyKCv2f9X-l|2$a>#XHcL5Rr8EQ#>d)envP!Jh~+t zBJ#WVfHKyym&QhO=DFLE?ymjf1YD0FuUwGsQ7}qncdSl*_o54NOtMAqrpU#~Upo_0Mc)*EqR@%t?0qZ}+2kbT@K2UDUsLhUw2) z60z3sJSr$>w`IyK3oC)F?s4j=?z9{U@@MBR#o6ns z#%GT0yQG*AAJ@u|2&~2NpF%iq2ghmyh#=8Usy?xrG(#|w! z!|&QmfB`ml6GC8fPZ z*|uHJeSYWspX*hhUe>-h)?Rxpu1kDmV6C#S5TZxy2PR9^l$Iu|a&U)&aiG&q7^H)2 zYe>dAKX2yRyvgqb+Y$(q3%z}+A(K024Mx-uKW)aU$42+*({ryLigE)l*jy&3|5~f- z&fn_%p~;KTo`Cl$i<;R3?jH0pX@SLUY{%f5ySa3rJ60zSPwpt`UaJkd1Mo=IV{z1B=^>sS+hetHNBJ!}@>rnv!EqJ@q z*T`%&*J7pUko``JCumZ$h09vzdQeNxo8<&h5UDc=<{<}J!#Ht&BK2xADphH_%>w?Sj{@mp7D)&^gQ z_ZdWjO(W8+>xx)m>tRfCi*;0-EBl8`l=iVqu-u#oxY#Si>dAU<5-%ZZ~^J+YHU+)RxduG-{u4=Sf6>mLv zdw-@^kL?~701938(Y05?B`I8eT5mWTw?BDSIS;UyjXAu=b3x>POm_1H1Qk-0>UdgS zk7*GJ32VNzc)d^XV(RSv9~S^|dV{DkKWF)t0B~fw?yb^cxb^gXlaGWkg)x37&x!r^0J1R8WynrEt?lAo)zPpaL*EVlx9gwPoGN3MsA#j1x~UWd7f&`KCRUE zl}_B%*MDwsqzbuM!&_rSBd`17LO&Rj?FSr+0+;W~|6ol$&ON|==zaIR{6FQ6DGK-P zXx+T(t^KWWQzyUH6}e$EYSbk6Zr?!!mI0x zl718N{KWN~uu>)pCGR@4Q$fmVgf_HBReeZr*mLGMd1Ev`$%E74Fb)f5Q;BvxG4W^M z{d*?S270!mAn{~tfYX@@_s!=ENxdoM0tM3`Z`F8uMu&r~4iy^B5M!#tqa|3bpD7KF z-fFjZO9YVRWpSSEOcw6y#nrF)z*Wn`V&L*&GU7{&vrYWn^bf2g)XWDms6Zi__A%Wj zwaBMV8_A||V9<}(?JwTZy)d_52@r=jV-g%Q(7P5~S`L zg=x!uwZ5~-&a&QB)d6r&mYY&6#|P!=D6j<{VRR*PTX*6tGmpZfj4NRLad>%)e)Z#P zs#yA9U<t7QepN>l&UgWEf(@b|SjJ>x(0mqA9=n_5N!P4aFs3OFhD$LsoWp1jX z)X$cp8Y>!Cr@4i7ox0`Xr=s=K7Ak%DBdCTaU|_rJIa(xeaS-ez!~1_dT}*v^Wn4_D zYFn2O@lyV}ck1|O8k!!snPi#rPd+?(iGC9S^g&L|u~@VC2~=5OKyr=R@WfPbh?0$@ zWQ|Hf^a*ipHqd&f6q3|{Z>$|O>l{Z;LlN}+JloL3gpimA^cWV)=d^(Cu5O=W47D`q z(J6`Af_HbTmyCe~z);llMb)8sgkvPnHB#E=*VCb6U{69}7p&3 z-}~2oh8rR|5$>Sha4$rxG$H6dl+nGkYX8bqw5sU%VP`m?5ybA{B!5I`COh$S3Q<8rU#1z>DEe#AlNAdJT42aj4HKf7 zrWyU4a_jInFd9-dOS2~ra770xdfnLw!)0z?qBC~AcjY55ddV&i%QGy9B(0Sfk67O9 zm=lH=-4Bx`Lk=R2@~f?V&AG+uXU9+e%~JNxA zJXPCfBjS(x6T=o17nA)-3thbOe|Q1Bjbt->F4^8myetVkT-4Gj$e8LnptwU?Qb2aj$vuR0e@TU-0`*(*l^?I)G2#H}*9OmJlX zU&)ycpBmwg5BAIi2#hw=@fZuD;Jh&QWnWTooRJ1QH9$`oQunR}ib9T-$8Vj_N^n}D z`II4TufGTG*z9U%GD^)U*TJXX9P4L@c=T1EOJ^YA)7bQ}gP>~yy+_N8ZW+(2+2wB75s>ID;UC@#{2Ms1r!4^BR z!yo>XKT70OU3*Z`##CMYF}ZB*OzTR7=}LTIejp|67CKtOqD%baIYjxSbG1=^FYuqc z%+tOwj!cqnfr0S+*|IF}57xO@Zqwrs^%bS2ayLjy4E>dJB(3A6D23*4b8Ixei`-Fz z6Bw|M&f4Jwayn_CVgWAQ{eEnBjBR%|mB5DQb>GUCy|IzR_FCTx1z)R0?gTlv)_x`L z-~8St2b7G$ezVCQzSf>F!FgNnL8G(2JU$VAvt@v8%r?B&P(I|i&M1|w%k~{(Jx>8I zqtet|{WuY>NWJ#Tos&+HpIq59yTO4~m0bvO)R(L0Ypcy2xLsqoCOspNwzWv*OM^K~ zsOG-AeGY?<`k@ng)42iB{SWaA&~jULKe{V-_0t#Um;92DK15abD&tm%RASKk3c}^P z_)<45G!#BAFOpHa)rv!%zgTagKJkfhzx^Im=oJYYj8S{y?KL1}dbPkaQ`5qYh8`K3 z=aEhx)WQNN`wojJ)nkWRO3L74_QCN4hZurk(2sO?^AWl&^Kxc$g_L^Ws*4G{@`8D4 ze&}dcPKJh~Qw8Nutl4k?4zoW4KwzkTOGW|x24ci0f;KjUyjg!U3BDvdi_B3V?SRXRs7VF6tfujB?8Wrz%CznqWT!kUY#2E{|I=LX({c>{ z#~wcl)t2hYB>(o{9!8?W9=yFZ@B>JJK9`(|R&VDeHGz@)(aDroX0X%WiK9moWC-i8 z);u~(#LhkVRt5H=9Yj>G7^n0OOPp?iYF5Q9O$R)P$clM0$+C^pPT3u*;jbE9=Wujp zXu(T(jtCvWalbecRxs$ieLWCKAp978`eL+&{nG(9HHX>&v+E)$~=Dkmw+K>)J4u%)dWG0ih-OTiUF(9x!xJOH#&=mpXZFrW* z7OYRFoseVAeX*#ukob5L#J=gsh%g17q;{B4C5FkYSnWkhRD{$WbHU6CZ~SjZPt|MDA}7<0zH*i;&I{y- zV#*}DIz~9&pW&1jWtcML?d~NHm?ys-ZGS3i+1=lu++xyuhOH1R%g#OC@?ecqY|edk z33VCO2&?hV*sm;EIEPzdhIUT{mr&XU2=rRBt+BP`A>D~5^YIPwC|uPiEv2%xv@NSY zdN+&bUFKV&Vf=JscyhEF)4FR_GnB`8W^4v-S-H5q-z;l>+t`xXkM2@J?qh+2*u981 zukd6;8}GV$wH|LWp%R*2u4Iv<&woKyVK1iI&yp4r$oOtvx!GTCf`K3<5=3NWWz|Gr z{D8Ci*sF7&_-I}jQ%VDcbz*eGDy2vRaZ zj|(X^H5K;qAH!@XXJ>zXvnsm4crvlRH4|OV&E)>w>9y$tOhh`uCIyB;RnaH|eAIYY z_xW@z8GI^n|Bu5vCtjCUt71~tG9C^*+{C=YgvGCM0&0B6j&4ywqm;r?uiU(PnWULF zsKH==)~&#PGIXhb-{e6y)!#aOv`((aLr`O9bUwo~r3hSbXtqM!g}p&Jr$oaE=9PV& z0e_YvqI3p7(`EU*EMu@sh0s=ppr&mCrUDoDU9d_X(j101W=d~l?_`*fxT|9zurw+g zUQqmh@1Qd_efvZ6WET$f~;^#lrw4YNs%+%=TS;Zm0e@<4f8k)()?kk=a@52 zh?CFO$sCaa)sS7>Gk0?}h@Sv;oa?l@Cb;RN1(O5eC4QtMN)mkq-z!@d`_Z=blK~=M z0X*al?9o>U&YI-@sIolULG`0SYo$5iT~G2OX=2toku; zQJR7%t>=fNI$40)W27uTO+49~b*Q=8WTf^1py~|~BeD1_L$6VTjgSEfG#YM=gJB~L zLscQSP|N9+^E)QKd;%x*-&@P1U;D07njqMZ3K0EnWnkS?bzOwG1soZ!0!!ysaQ^MF zKF$hW>8BPlT9S3>DPj0l_3G-gp)M1wVu(~sU_5xd*o>f2SxS_|=xStpBNEk2{4L?g? z`<7?sVQ{j)*UvC$*~zpy(L5b|Q=^T4&8Qr?Whuas<5usH{=jS0hwe&){w1kRsyD6j zk6bw6Jk$KPh~7CXsB5k4>y`X@)@99u4qv#ts#M->O*W+c$F4BQFT2yIOZx#40`$it zypKRV8yvLm_C)@vgN=6oswje?7(S2Kk6Z!;(w~G&SWv_*6DANmAiz(_1YScO3+Sxu z8y9CX$>+fQ#zq5?*m8#e3nVL#ft;wpA~(U?yVF13$F0i<-1~#- zc)>V)M04^Y`tQKNW(Tiwq{o_W4RNV=73`I{eY=GSYi;kHe3QJbLj6Y&lMzY25A}Nj?4*Kl@ondDhwa7wqSu?MPn9@HubERddPY zJa((w_n-wv9w!sT7bE)bXyKf41&$=sp`s}+O}0`j(eIMvS{7sRiDDl|4B`TE>(9gq5@ z;-dZg)lXgH0qytWG7~KnvSY8i2T{661NfgxL~l5J+g`>$=YEWD9>h|g3^-dRPIsSa zLt@30Aj-+5Ff4Xj3b1YNj~X+-AM=C+3Fvz2D?M^l=un0q5?QltP8?C?oomuw-SC!{ zmI|T-?V{SSOaB-#cpwr1(o`X9Qx{;mAxw2 zsan1+E^%r`zee;WQ{fuvlSg+|!8GD8Z{j-(44)cz9o!EZ=g*R|b&r(CTUq72ecfmB zFKnLz<{|u348V+Y2#a zEcdNaqn;H>Q3Hi?W)FX4)$#itURu8h4J?6r_>?X2sx{(a6_Q9m=`4{~!Yi~Cj1X_eE&AAfL}l=Q##YP@9^LZ{nH!`>Y6VK*${ zezD@TWW$pb^Me!ZYMkJNLV@8k zh;tFc$D70w(}Prpf@A8mv~*xxqmB^LNF!$tJ=JIfgW*{Q}UJ^B9l&t!qu z6(`Ql^(+Z2Nf!sXyvr^o4-PNlyAUtPT`S$ATxP5 zfNTLJPmtcqWY<>(k!cA5DSpg{KZ0+=~w}x3q^{ z5w6hKM!e0xGz2Th(O7LQ<6-KZ%(;0HQ0hZF33#h1zR^ydK{^59aNkhA&tRy~!0qwq zB>qW{pnSeMqC1NTn)$D1^?erQWW-HNOJ3i$FNwsj=NV3n$XaNteYm!2M1XF6cYeI+ z;5)u%`Hqrib=&03xl!zh^Gtx(P9)w)dH*&;;2j&mu$HwPb}T|R@nSHa0ITu90aHg} zq#zLXC=8pou5#;y_kkW=DX#h0)s@?prv(Wk zuC13z-_OPehCX8$zi#`a59@rmg{$f8R&m@s0pT#pdfUsiJIdFuA1MawA--VPA3h-l zStZp_{>=x$#onQ5J=p?J$l(GyO4wOGZ-q)J(^pWS&HAro9XGA&Air^TEXH;LIMC(J zhJDla3pO}t!5T&0PUT~z9$4WyIlBZ9xBLu3ivJlDkr$@N6b87{_MY7I?A-a2OEhWO zi@_Qhmm~yY`1|UQ>bq*&SL3;+_8ux* z_x)2|URHkw6o1BPLX7JWDI;!+_mnDwoq@CaDP&bO6ZZ9x)@EQ?0-SiNFS@8BsEQ%^ z991~W58|c}seW9ug@*u(n?(8R-;VU&1w=87@f)E(iKNrv&LMUf+@P`cCB$6M79g@- zGz=PI|1Cw_8#2!nz<`yKmOEx#|4-boWxD4{_TQhHG76<=e~<(y!FP4sn~XVQO&)q0 zxlp6=Dp*B(^V}Qx!o+z^Ok%bFifwZu$wdl$mx@zQ>?!yIA*m&cYt2pbTg~42L!Ghk z6Frp$U5DUG60Ziot42|2e9uVaGoi}Th75j1gTmCO21A4j`pKS%&ca^qiU-rS@}%z7 zfb|v8QR$g0Wqi%#@fUS1SJm4+73ai}V*EIf_b#n^*h8kz_BZ7<5*D^(S8LC5m?v5f z5?EPj+L&4I2UKEX-h$U$jq^-Q2uVM^Y#OQ`w+x$SYAm2@hej^Hj)pH^+VZ+zVS&0V zEd$-QvYt~0(`doJfdQ*IfY6O0+HJ<#lVB1LX{ivwd*Q%M5lgW) z)sL0>FjC?OphqrI(r-A!8?>qT_(*4AFnW+p-LSQ!YoONFhe4nfYVENKJYlP(Pt0yKhWuIbsLCGP z-c2)0jt{|do8;O$S^h0CV8MH&<`nNS*AHK4Lf69iY!)TZ$gK7X>3<~bu67NX$eS3G z>65_?XEd!ZV>FIORP%4ME`BI4Ot{KTQcgsgvZZlrdKu>B4V zhT|%IAqJGEKkH^-N<)FZ{Xt7MsF<1vdaAB2D`a55jhHS>hI>MP7wnnc+S-w-{9}#< z_>S})Chz8yNT8%0_vJ*w|Gc?ez@77d?AR=9Rk~0mfIqpcrE0mKKUn1skZZ~BODK%- zi|kvMq^uh^YM)0hGzu+w_=VQ@<6#{0&WZ|ppt`+^rXFtYeT8~uQ2%Mq;=_nOmu)oO z|7(EW-NbG_?Ie~;^fF(l3rx7aVPVWlE8|1XVbA)g?p6Mh+iR{_%wMS%+5XtN#*2vc zj+%L%Q}-lxQq2%tl!e_LR)#?kowzntqJ@C42G#Y;Px>64PaACCi zF8r-JL;j~l0~ynU0jSHd(_Vk+ZpIM+)}QPy&=a~|h8f7fYbm6YBWjHvR8%*@TtXor zzxfrJ(;T;Xrcy@$E}&+voPal@zO99rm`8}zTueb`LfS17Xm=`CF=5K4n)f=Aq!mlp zbQ|R4l~kbR5R*bF|o_7yl)1?8F4ar9TJ+P8NcsV!Mk_ zMWD|#P3x?olAScVJrKrjFmL}!Zi6;?&yv(i1*kFlcbV5U;_nF|#vG$};=?eMyt6y} zYVB(Qn0(wpNEeD5A3#GxDI30?%kHFjtH5u78U3`5guu9ewKQNtue7^~6342#UgArgCch*t><9d>`!{Vi^$a;?55Rm4pZGIN_q9 z;xp-(k^Y1Ct;F}S*`FW_j7t{8r}g(#P2UoBsRR9pn-R0H)4V=`z#m zDx!1n^yYWt)!}Sy0icu~7Y2n!aYd=tq|daToRVg)bImwio767!@qim+6fWDRV!1{M zIH6VwpClH)gE!!QDUZ6x=qo8oB3gurscHY3NlnJRL?s<#hyK9zc|mR2dfjIAN`ZqZ z&zRmm!V@RqQ{h+1qj+{>_w=u_G%m$2a|f2^MtklwOJ+UWc=Oho(XE`nKDa?Q?|33vvLtun#9uZYX_Nym)K zqgd6DU3wN(EPB!L?+FEz*9&bb`TYF%*PUVAg} zujHmQNBN;$jsq0N-pjO#!4HwtN?np@J7%ptCD`L!XKF#T>2!(Dt>wBwly7(H|3PMO z8*j8H~r4EIySZjHaK415!X7r zJnr^Q9QG{&KYi{OxT@S_kNeJNBHr=5?JLNv%JbdE;R8t`%K67H%FaGJPE?xn@~@0o zaC56WE+$VkAb!g6wtaNg#p_X6(Py{SA)1xfeQ>vWo zonFXYBcEFvaG_Q4@JpX87t$~D^Jx3qCUwo^-3upEN}`J19$*;Ms3cBSKVlJ9Rp(H2 z8qT8AE^7on<^$aw3(a=R3tR0+gA-CbHawNC`V2}~&aZU2QB%06?z@Y^Dj2A=WQ&a! zdn8=wf&VHX8o+5R02R4}kfg8Aio50DLc*twC6y1iN{;}6?eVwXiLne*ERWR=<~{BW z!=_){4XNyMx@5HKZqArV*nBZh{~2I(_GhS6d|Dj162;tABKeBH?K|8W7NZrlW7 zCn{v8SRoW3uLonL*TTW$m`OcaUoO&j*}tolt)eO=?uow>tLrsppv7}YVKu7$(zF|$ zA5p-u70Ab5s&dH(i)2u(sI_SXi=|g|T}G;f)X&W8Sd=9sQQ*~G5@TdMm~syj87?#7 zeN)Ch?^p@!J;RD>S8&h16}>fafVy1ku~G2(nERHBd-uk#FwvdJ(4#V()1v<51QnJJ|~x>K&p3i*F+skiV=k2@`$X2f7| zhyQ_-`4y~8Ievz7E|i%Tivz0iX_@duU*|HpG9J! z#b}7bu+ra(DVpp+k9Ao5iV*uzD`crtl+%7vR{p-8V%E&kcTUXw;T7#1CZcCsj6uN8 z(@>MbmHTk>^i!Z8nT;vPH+nKz3Di-ukv;^A&03J$*AFlP)RH>qw{mtKo(VypCRtC&peSRTw6 zH_FzaK+WYz4ZAV=V-PXruil{Z%a5Qe^qKj6L zTekSjo3P;zj3@Pdaute^YL#s$eKQnNCy`HA}~&n5!fEu^}7$-8`` z$~=tW#%0Fd{Zh}aThgq9{oO8LCrAv-#2OfN>jZS1r>9m^tcb~@(R%Wr$(ze2J|-MR zRVsMYp5}J`?I&&#DMDO>88@zxw&yy0f1T+8(rgt%UF;Gs*^A{$o593+2emn2J>O>v zV2F{{wvi)@IH!5@q{C4Y}k6pSUWnk<^+S63SN)J*T2dJvWa z>bK86LY>pd4Yb1|8B}CW$=>7t#KVz2(rs*E#E*nPBn;?)!RDl3bHSQB>Z}UwQM?ni zGj*7~^m?X-HHphYnqpb2_byUPPBhCe9kRcl);^GV}@^6rQ8Q*dNB* z!_)z!Amzo`6dQAu@eOX3>uwx)J6r07XaY{ zyhUgTm~SXk(@S8L;ubK#aNd{$?QxWj$}C~yo4AO##!~NY z$zWf-b|QZMPF)V4P7F5-U(WyMos&zm{1%Fzb3rmGtfbD28S|P6^V&?S&^o;m#nTeU z?PD?gh;8~y0=y+$hHK$7&VcGy=1EPXukyNF*ebl8+hE2AMx>-|G5>oLT{*fzH#Hiv zj_bSqPu@2pgc7$ZQ#xJ>4gtkKIaySC#V+LB*4l16C;*#diE~eHNlM&Uqo8vUk$Yva zjECg^;^dEE9aZT)IlxYM@cIt6PS+qx7dLEw5 zpBXbrIbW-6Mp4jVL}lVc;^WU3nD|IW#jy$*qG_990&&E>tHj~3ENeH6un zQ4#0la0)X|y2~`LN1lu|nLln_-fpP=*d~gMm3q+_C;sZU?2`Cx6iPL?n5d===l%6u zfM5uZydKYi%&U4Z_T=Lw_yB?lH;U8ikqJOCvL49z_y{n*3u8b6Uwc|!*A18-vE8*1 z8D}7Q+$SfLwk3!SCaTw2UKC15f2|yo(y(h!kw1;PMUUn8E-V=g;Pmvz>~hxh(Hn19 z@8>kAeqs8;p+Km8Sr{E16&^jBWx_$+RKxNSKn66BnW@jph+$DgPzhsU01q+sRGiX{ zWB4QU5tmHo7N^XGGZwvTx~H^i9d%CK+J&IvPPRkDilaN4G$9(XF;kD&o#0z;?55E(J2ZMQm zpXepC9)Z?6-LkW5$ytcXBcVk<`Faj7p&-l2et(RmdgbCDpT8I0Nz+nitvb_11yD&wzyHecod75rSn3V=!qP%S(+rZru!ljIa-MrT*SI2BSgR#I_4c2G6u>>tV zD3lQ%fZ~$p8)G`(MNaZqK?Uh`uInB(SC(fnpVb>#JcOpMBi0|DY%fxo83f*c2g$m= zdbmFfLTfe2Yfo6QA(S4QV`yQDrg-UE+h3h*C_S#fn)J72zbPt*U$Y`Y{&66co0&y> zZ#!VhuX1HxSR`iB(RgTX90w*{Fp%370m}~o+RW@GfKz<;|ob#HfIse=@vSJ{X`rv?+t|h>!eeP6&$)>2D8$1~W*4wf_x! zAWu~qTV}1O#egHq za#D6YU&7mRE1IQil68!a0H3x&ca7$}!T~Vo*mNkM8P6go{5>zK`pIf2)c6z6Ogzkf^#1O*Ugalu&8hqaep8muuT^{20xlju=k>pwYmMADT`g z2Ci`_EcEZq|1_xL$%79v*be=_efEucxK`OJ$c|kZ7;#FoQj^Nl?hYAcBFs4qp~oC} z?AKQK=~{Kr7_xoF1KcOa;Td0~jk(`1cf>$l%W{a1Co?~e!iP;hYf6A-McOV;}@j z2>3*<>|d7C-}|Ks^vb>JY?SA=-1y}8r}|eHzIZ)(?xbM>ez&afyoAVYK7$fvTw)|~JQWe3XO`TJih3a;|NOMkU{DPHo z8y49Fn3+x@!&@w>tn7-|!96=#WaV6i;8%OM+juA)0sk-CZix_G6WVlGeE2I1{lM7c zD8{(`EQZ@?$|kB!8KtyB{%1+A$KAPD887|!QVx2H+-8rm( z>_j}Ic($W~gvk{bX z2VF_ekwdo?dwzR6fx5ankX2wI12#nkz@ZtJYc;y%ZhCkI;CDW=#MBXeTezgt%OFn) z?Q`HU4E<>j9tawH=RUR#hP>hPRO8HZD#+wyrrh^IBkp>6J3MyC%dJKo|Nh;MM;lOL zxqR}5g$z{eQ4Hv6n$Aasg`V0slN;s&_uI-N&safX9*Txle06nz@I4=c`zOvJmej1nx47q_ny>{Ao5^ETfVK zV=b0h9c%JTH@CQHbBxFSIilP~Pc0jP_4I7Hf^y{Ef`e8k^8Lj4g_Bd=I&#L(g@-`s zuLVv)dVOoGr<_=2d+L(H2J<|4=%ytV1HL6GC045(rftKC62g!@v>{yhJ_9U_#_OCcs}dMVSsHG8F1G}DVG|+Y&c*bVZ%U|#9D=b zm?rxj=Fc>_YmBGc6Ia8rHoOf@Qt-}fotGDdG3D#M4R`sBRT&r#Go3_2ZlQ?z_e84%MS7+$)PBS0UHzB%#SS|HtxruN zQQN3W4%KL~(pK3dM9dhoj-{8(!e`3g(z|M{KAP{|2qb>c%dPLu{n^9|XN%YiOme&a zQM})GBvI!QU2f>E_6lKX6!N3QV(Q!sp_Qy*?fViXgiR~G&*1IC^7;i$1NOW%~)m7bH!#K-)EL>Ncyp$rE{b)=wb$jzD2zUs<>IfF6ZvBsL0s9&ZF? zb~qS(rl`F*c4ow&co1h-iZzHMDR6Q(F!qwvbO?pDp1t?$5IBOc8eME3(~dMK!H@7+ zI%wK3=1UP*5|prl9e1XgV_o-|3q&4l@n|?8OCX3LVpLFU_#8aT%r8Jh{;lWWE&x5i zu33wi=2N$x*T$;|mxD&f!E0U(#ME|z=-8`Op&6fbSk0@lSGkp^^X=uCZsVw*CYFcF z4c5kQ1peQg{RT@)IMldh9gC$%(<#339`DO{(65&V+MgZJI6Yv8D8Pp{#y3x-pvS@C z4wy;xZ5=_MYgU7cRIrqlYY(aAyz%HT4PKXamoJ*C&*jYj2^1#;|5c?4edB7DqD6Ow z4k97bTO<=(F6{U9u`t+Mvy-ELn^iBCL)EP|GcyawK;_56mD7@FteVW3tp1+V=M1U< z=f_lchve!#IL{0!TqvSwqX%XcEXud|#JW>Z^2{`v1{Tg_qQBAn^=&HzS;QAcrB;P{ z(B7PBTtTp zE>Yi)jp0xe2yK2Esjba_x#U^y3(h#HXd& zZ-^EnV_1EhEx0#br^pT!aKwj+(Vv=LkNH_Fo15QG;FC?%o#R)uZxV+Q4P*zssZA0+ zHE6Ib7%*^zUO!?u&NhAw86F}O5w$UI_@Kk^_U|1BK95%1SePT*_w=Y(BD$wa4UR34 zd+prTK{cioY_O?KTJ*v^B?x?}JdL7dvfx@_uDD9l1~)w*5Uz zHkGqyrq=|zQ#Vq`Yl(>Kx2+2m<=UZ1$?wH+|5lV3m!rnUj%|B>I z>7iRS@*Vs2#f=)a0)BhTn)u!DnRHW+(&5pm23U_GggRM&|Ef;ompTHr!o9G^Ho9*= z7u8NON&KA7f9Mog+iGhf2AbN0XOrJ(DKvye((VU8ZbFd#+1c6PX&>&3O)lDsjqSg$ z1h_(%*)a@|9j~s?As1z$8*j$4tG9fGopk^da&-s|xvztf)o9WVcd@3Gt9G%}IHqP- zjPL9t{Uk*9(x5fCZkOv-zOGKx^<}ga1j6ILG&u5F(rwTEf%bA#-a2KKijwsaU&Xm! zO)2en6WV{>_3#R-bpS&N@yq>}pQs4TBGQNiz4^=Bg}y}~YSeDnliax~{LNN=nKXQUp-bBu>- z!H)6iGGBtw8cadJwk=Ceh|4^a}u_x zFHaI#HK7m*FuLanTqm>g+E>o`&t5+aR^93t?|Oa>>bs6f{hpxblSwoL6$hmU?UyQe zGWR2F2b5$yeFS7fW62OD+|c(eiA5&LsDhKxq)RKxOBne}0Q+$%N5$M(YiM z|4kKr_?jYyB)a+bWv?LTiGx=3rOsyZY;`{K^2gUpm&lGQNR0+f6r#EomeYr`GNaAI zEknZPAB!NA0nhyQgm241#2vVll;k?;+alAGvXO65ZBpm^S~5iZSvYuY=yjN`P6AZaI8kb6YBXgIrZahT{JYWoqgg(JkUL{T#{GXWB7N{IQ;d142hP|zWI zZ$NXu?KdA{q9&6W&LzXsD@=7q^OUJpq zym|9P96@Rp0zF#8sh}IWu<*ml#ieJ@2@C}g-fiP20^&?WAqeyj>J~r@4hdK(#EG#G zgPQnCBxO1p#(?V{DX>of9zu!qv;Vx5-FN~_k;@KDOT?ZLm;v)}Mm$|_80x2<_79H3 z_I?h|SIVBS<5j(CIB)g=olM)M@ZH;VQ+V%nwrP&HKrk~0nw4uWa z2wWy49lV#BMruWhuEKZ-x?53Yl20VfZa3ETrRrBbc=x&rnb1n)>3N7>(k7nMS_T6Q zju#C^{-0gwL6=9ZMNQkS#ToE`?O4Xy|DkYJ&+SQ!gvIpJ6u+FLwh6Oh~&tTs#$s~i??jLF|A0G;x3B4$Y zCSN&^x2VI6`vb0E#gjw(9Y9RrpTYFVr?^`%l_{ZO_JHpWE@ls9(;YGpY>F330R#2$ zQ`ea@fWngypGZj3*+SBlC#cyJmJdA~^v>9T$%1pjjWwU3V|X73G=1bYUOiT3^|)R< z@?fo9Q>BczPA@D+xQO!rEHy}l2wl_9&{W6ARh|zvf8{a*R`#I5z{w>8h$R55xONHB z*Do|1*$)J$7lL<#IAesFP(mzG7Ux>LaDD%En4F z9^&Abc(&UdJR+N`@=>)}-I_?iMTHzs3!kJ?sc|{Bb}R_?a&+jt7jZDF&nLGY!mQdg zM0%9<{O}^CbrUYEK`f*{+kQcHhE6Nf2@*IzQ6xB|GDH<;&(5C-V)^JNCn2%92yf|)c+9OYp#!z+Pd@}lFN@i~!CK7Zh z0R&jHn~OpG)^LIZxqE5eIM`-tS>4fKIxW`ZjhT)aygorMa*Fr-v(IvjIY+|8k5My* z<2EZIm=iS}$Cr8Za*sZ70KZf7*;^V{iAQKa;y%A#^gRn}^_sN7ViD_;BY##GeSKa7 znD&#M(F`-%3XV+2ui^su6=@GY%MI;bh)ihq+ZAl&Dd5`c1|`>r-LWT{*tYHD_1t&w`T9qH$-mxpYFDjVwbuQ! z%>TFmyy{s%WcT)I=@K`rbSo|NL5CP&dxiH=>diN`?>JZqBrx61z<4y41|;whe8g$T z>tkViqc~T$))8;aHE28b9PwG}qF`c{_CjNirK; zPcPTft*LM1t&bVOGD|{77T*1GJ!~;uJ&^)3{6I(v11CIa%rhhk1f`N;bfx+w_dd@3#DRkpLcCi%a!>vg*G2N8pH6EW{CUGF}exmXK zBaB{%AxIZr?|HA^yrAeEuT7!XIuMBYB-To)-5?a-_QaO-vp%Ai9ot7KKp$k%zk<)t zUeP=IjSd$k_piWHEY=o_yqGvUe2308JA>1J##GA`kvl>I`@6f)UE;&t+bD>?ybZpv8cSL@aAV)%%JDE$Pzf_VhZW zvp1)QA+%CKv3=FLXJZ8s5l@OJ0@;(tL9&4qN?>iJntSyb%e53d;(3Bqd>Gb((z3Vu za2PK(L9|P%u6y;jsm;OTKHdCg-LP`OJ^~yh^>Z!K!hX@;!k{_iukDM^j)6I!hmI{> z+LzBza3}T<_UBRDjfry3uRHeaAI~Fn)lRK9ZggS2>wUjpkOfSJ8>q3c?-z@o@4nFZ z4_BPr&PJlW-X^kc#`zbby*ShKL%lLaQP0+vF2db{bp;Xg8Dnm*x|YI>REERK5mECl zmIU31^!+3n?leD*vBp0sE{^m9@}e~I<4tB&0^8K-fods{JD2XRf0gP$kqG+wE*?pE z|1DSt-ZhfQgXiRfpBeTA^pSs<@<0*eBTNXxBSawf3I}ri2>kU;=<=KJdGU5Fd{K8j zyc|{bEYMvse+ga~W&6f^`{BiqMGHh&$jy!2{c1C0IHkO|jvh$C1@0l@LSe-~0zU*J zz#ae?uaO|4bCy8%zc1ZHpG@G`aPVVV6kN^C?4Y znST?a#9^@4rO3zrw##cviu?p}EnNG{sQ-~Y>N#hmvA*J$xl-!Y6?@XJ&YU^);M4!y zioT+xxqb6&rqfU{)fSgYKV|Y=7>syVp7!8Yeo=@Ti0u~{eU|V|y@{M;%tnNckSCeY zV;o`_3neUXI^ORM=TfuNt~aor>Gei)uOOX(t> zSj&e|%N6ig(|Cas(nW74i3HaB394wZMo5tZbv&1zMLmzTfRR z61x;%2;p}bylnHHOTK+FHZ6G+zRX*3tr8e*IfH-*_gXRsn`tIO1eG0ro9ARJXl#TB zs$P;r+S6gNe*ex|a_k%q1yk@w3=E712k45SnEhJ~|q( zWebu~ntxeBYA5J!*4Mh+^zPz+Ujagg?=Q|ih8v9FHJv|R=ox7hTd)_aSSqTt^j8WP z*D7Tg{fJ+`s=?g>~R=EYW0jv61&mP)w zKyB#Yo!BCHQ-J?}=UK^nRbn~iwAwB6>0Q*XTS7pl9=e+-2W^yoIY4(BGoww>Dfz-9 z;cf`K{2Qp6LQedqc#fY=usqF}ERb%P!U9;fW z1O}9tMd(JM5tDly)>zk{=goO-l88A#n?t1$bB|Exlhmwcz`9S{2?^ra^D?0+aVq}x z-4XBZ=dg}L=B_o*VHgniYU}gm zU7+eCj^a;^uL)0{uc`L@UZEYmB|iRKG$rY}kefH+s65yY_?VVrBov5kS9j85*x)KE z)GFkn7gts(&Zw!qT(0Kn`1k>NS9Y%1ljGp6tBC2N5a7(4G|)`54go&8WM*atM5h$d zfcP1&{9Mklef|3FqreIesu=WJ3hcKOR188i#m+UM9Stb5bD)QF2s9#;u+Xg}wipVC zW^{OEBOw(Y{?3ipj;nYpi*$NrwR869rbtnnRNgml%dx`2I#TloseAnm@$5 zs|Evc(Iu1F>y?Yd zUOLcPFQ;Bwd|$(ZIr?8AcUV9115_%RECiPxF}tF%zCfr_lql@dO|7^gSw2NX*YkJ}c(%_Y4lorT=pzAhS&$Y4HC#TJ{YWQ%CN|5pt~6&hEppyyAS8e@r)zynS%8SG zT7RV9>MMLUZU^`sPNGIryNOOEULS3}*Tc5zk`lt}H6oIe0ev#wx&OWo+i`8jp}T#y zaC_AgfUJX@g0g`auo?`wtpB59Ma+R(tO@6k%_z-*?otF9W(S(^$_F|*I&%8- zb$&PkP3_t@fLjB{r>DUqd%`x^;LRiPMzwatkC$uk5d%R&BrwS(z*Y~qQqbp2@W;H7 zqGnDRO<4&-tdQ5n496;q1SSz8>b}Vp0hbSk1ZD;UQW#@q*%OT$C=+(O%%b`C@Ae&# zHBs>yN`PqRK#JKyqf?nS9TO}(Zn3_=Uo<$^xbSd2C~U3pl?TQLQuP(9qSX!3EBmEr zaDTqWuleMNS9Nsr{3vJ7^)yF~w+*wEMbBB}$#y$qZw^y)B4=&Dt*RYLy@qnhNVK)$@9HLL5E|;Drtgd+>%EIuOC- zog`{9jlSyT)a~4kBJeo(%q(8|x7XR?tCC_)`Ol}@HG1G8vkZ&FwJA55@1*26UGJmk zYuCvU-g?6_-5USbV=F$-*83l2Pj&=EeB7Qh_LMry?5CSlOG)Whr3pg?Cl@e1IuV*AQ&2s`|APH#e zL|pgVV`14N&bi#ArFHt(?@F70>Vi$p%|Rfb(dI(Q7?$BdE4C8e59X7YYnr zMj5bn7?%EB@y}^PW)dn37${^Sh?JGsz7VM5Vo@GW|8n$Pc`AAK{NeK$i^54%L0G%* zs$%hZXJFsrlXy8eu7HZ{B8=rk2`FIC0*}fGO|NnEh1z}~Aj#nTq`lfK-a9CDT zSejOnx>&eXHC*iGX*`m0?9ETZo0=oEzO)6J+{hu#Cey_^%Z=*vp*y#w&Y)cC#XP1Rh;cAcw4Xt~V@@D$lifav?^uyodO1JrMyO zUMa?#J`O~}eM1dDKTk41A%>@671qE~Fp~z)kDYc-iaQkyKOz6#v=F?ZZFS2lH(r<< zoD=ZWu*G3-~vS>e_tcvA1v~2M=6FGtcz^X$uYPB;ZH8vKaMA!FZlu6799j?#V9)D`9JE+7dKa`CI{XZ#_rTA72HE_V%j1KMDCRt43h< ze*pE2C@X#uvbTK9+ho2Jfw7t^KAjbP{i@&Q=t%LM@_hYt_-zho?dDG5vDauP@LG|_ zuu~l1jy(6Aaepqjm#+Jq_NLyn40@mrGI%eGa`FaIG$thvX-O#Y5NPk*ID9mxDRaYq zdpPOxeE3LBoHG$Ylfd!FpdA{Dt&jrkO}rH0BiE^Fu5X|HZq94GTN4kt2){vy z1crKBtcTRX=zPXa_S>tT0cqSrAg1OjR<=pHOYBHWiJ_iR29If}U6D*Vw1L2ObP-0- zU^T(0gn5%%O0{aCKkh~fqT!8lxSnkP!1oBB9qwCLf->w!t}jTboJUmiF$EwFXHP_stZFCM6}s zS5?vfQl+Jafuu+*s4qknASOwYB2AMa1qGr*Y}$xT+K3o%l>5%OX7#=s9o+8~^c!Fu zs$_`o`STadOJ>K3RdU0Dpx{6sPSP{?-@F8RID+16JbLmum7Or{IlZGv9UtM*kALVirq?(val;rd^S{W_>Fx_46z1`1#co4sF2EyfnZ z))%4&pjf;ET_xx*}vHY_k2+ME?=lzP3s5q13y6vXoF4XtRe zY>LL#;{DlaXHQ$;7rEo!wCE9u;FJFM^etims+TkP9p0$#RGiE$*^ksoct!D(LDSQJ zb&nDpaG>^7Pg%Z}ICC8pawV*Io6cN&QSBWPjSKv_%$_xn?P1>Ss!4=U`p8O06d(d7 z`myKg0Fk;-Ub&Es&Qp*8m**b=IL^l-t-j^KuDKCW#wRC?lH`HfLI8cx$(}dThe`xX zq=$jbM)t%p)8k{yh>?RJ`)fnfV^6hLSiOhBlRq~nW*BxOtp#o4k6ucV|* zqG$qjzLPafUCBfTA>M3XT^I;lin#QT-R)YMc6s8zYTQKm{unj}M- zF;*~ZS)fEsqDDQl{1>iNCah32ytm7Q>XcF6bhWCBhFgk(qOvEvwQ8#>*o6Aw zjY?kSX_hD4GJPTY*g>#rYf$&kTMf$}LS++47GeizTR2y1-%(s?q=4s5Bu{_}nL{l4 zq4O=z*#%Y&e+(}P?B4C;v0mZ|jFfe0qI*Kd65)q&jiPJ9Uby5HQtUKTPoTi*Qgw-= zfox5&Bkmd5e;*Cne*f_p@FD1S>;w#+#k<)UVq3zavc30E-5T5@-D17>I)?o*%(Ini zBu~+@n8vm#_jk?c$8aO3QxGnSSg^98HMFB=4y~~Isbxcc8sCwoZl&c6R#6z#(poLo zm}}nbDmCY0*M6q5&PyM)<(zB4@LX73&D|j(+>hT0GlkejjxQ3F>4GTQx`I9GhzgNa z_W^7O60>vnzcM@)E9;-fgi|?Q;;mx?-X&z#0Qb68fE#=n9lH>Olp16#qz?z6iDSF4 z(?@8YvHM?@M3Q1Bj zzC`gX2?GPBbsU~`fPMQk(0>p*VF?`QLYUvG!-hPVF597ZuyI3=CRD0S#=wqwa)LW! zW}0a49t8ok4#36bp`a=UMvC#MA>r$Ttf+<$Zx(N-V^;&5XarIaP_LQlOdzJ+a%!*@ zzhdbxRc$d=G{A?)EkD4V!%e69QzEYGeqvLdOQMI0aizNdH`Vdm(Rgd~=tRNQ+!?1* z#za1*e=p6@#r4j+5lxdf_U4yr+^}@t6){O5+qy ztp=fsE+V;D^`;-THEpC1^%8IH`3=FCK;1w5^0B+=>E3KhFnl#gRq~}nji};m;IRdFym=^yeJ-Kzes3UZj6gezW1=#}ia|T3!b# zynW#p4#+F;1u0;|HlrjsHm{Cw}ahJ zLWck<{~$_cfFHZ3`E=?X>enVb5{JF=!IyZf$MqG%1`=4Ai1BgZw(q5-{d;hfJ3bKRlKMQ5E}sv; z=Z&npfl3=M0uB7;?w<}}mINn8gNib-LROKsJAXEo10erz+PD=hSSr%SItkmeW<54O z-XBZVdDHQKDj-*8$`&VSWb9`T_lBekkW9 zvR-fFPAUR65n=$rMHlsmi_xIVOVTytN)vox1pmuV@XHf)tBYofW3uzCqB~7TbhYdE z_lua(T;ABfWplJ+*6Tp3zSz0E7SHbaT!UbZ;@UNE`)BP`MbP$r-2E&OkeDGPO zi2%I>ivZ#1Iv_X7@Nxae>i6+#xKTlk&^TjQ%5(#H9Z6_DeWvqfH%mKv5lIW^lJ7K4 z+6<|*m@^jy(^3kOk`|J!hD5REN$#CvK$(w-tdtSJZ{AKmIy!V<7y!3ZnzchdKVCx= zsY%ktXBHM9<0Rsg$R$a9?y0#5^tilEF;;naoNni>np#^$D-^fi?AGf22bQY*6{U&i4_-9maJ9mzMR5M3M^UWc!A2 zyBlU_9ZPr={@|lVf;FUD2%_wpxC*n(BvZfb?u@HouL>pRXqJR0R)J9Ci)_k)Yo4Fn zo3RttqzhM(%flLA3J=nD+nxHAnYbD$Bo<4Yu*opo_}}vLefxyHQmdZf6$Vl-@?Ew@ z^P(Qzyc)ZRE*+N+OK)j~4orY}qse6LPrYBcu zvN#bF8qM#aO$zZowVjQ8kv`8ja#Ar_(vfERj#8Dx8c(~P!BJ$+3zdFm;WqnA5P^bi z>m8z{GCvuq%;GH2M4*)oQiNbU0BFHmsaME5Yw)TWgKc03$NkRvCDYeiF2Xd(n~+=H z?AOvl`0_Lxc4C8#Pn}A04&?esQ#8lw5g<&~SX#-NCVEB@&>AB>E&fv|^oZ&P&(FSksM)zYSG z4|LR3`@Zu?ITlSN)RJc5lSl^ zb}xJ~I!-axi^B&c_=fCeFd^$v^iI+2Qr;1= zxiaU@A;yR*>M~}J33pY74XgL!z)&jn%RUhs{BKvUKW?(5*LCqFPG%t22AQyaJo+IV z~-ouL35%%Cj+LZ0Zo z-HPj)yZpyWMD8CdT9eEEBZN1W1MHv!HWJHvc;edCFl$>;5K@fOST3Q%s zh#O83K0=r>Xq#zzqbwl<~WzUNKr7e(O~inF%AleTrn z&N@uP1@cya9*lasc0HjzfMGy%>?i9xzlHyYqzv{& zC&ruT2%6Q3cs^yO0$I7L=M*tg)M%jTRWk1?dBS`I49oAKgc(RHkn0vI3DX%+qGk^7 z6w0ge?b7^EtnMu@I$XharrY|GE}U0=`fAE|zpN&*raHiNDce3?#NSmrOy_l%{P4f( zw~t=?8=2x(jp`_#emA%>YXJiFeazoH->cskVG};6mv`Q3yS=;KC$^s_Hh&BWW^jOm zAO&<|>pzhE=?dqQ0C+utq<_*|f>8^+;b8qa34Z?tS@~#nJrS|%VQ}oo0~8ZdP=Bz);i7>HW{-KqoUn^aBB&4Wo`5M&fafdB2t zJ*e0SlT1^rT#%BL>x(qf8pTbC`~3LpxbyBs!0n82bkPi)Fb+WaFs$L7Ed833|J~TJ%jV|U5$a!S*cR^Z|5+a9@6c!;0tcybLMWU6 zQ!Q3pM59(A*a(dK;vmfK*GZzWZ8*Lcc@8s$(h&_Eta}--z{rs9d+s7U?E0ULG~dV?iT zT@&ZnE$BvZ%hKa-aqQE9No-aBK09;N`p}umY#N~-Zm?lq-rU`&k7ytRSN&0+eY}U% z?)me!{qs$)?IrIfX!;R~=AIv}eLO*XCfVQR+NBzDix4^fOX7uVJ;32wEtp*L5#p0k z%ZKP`OL!PChO9Y5EjtkW{yg;H>du{*l^o3f_EcQa4jY1rm&5Ic2dpE7X_JJC)yY{| z(a9y^2NOv}SzJdI5eRuOWJ=Ng>EWuFV(8tbW9~?_<)D&^ zxUIoat3FEjFAO_V1fBY^+hBc-?)G71U64#evoQ7`3^OhGFo(l~fQsGt+uST@RdzrPLCtyJwg=fS? z9DJ$;)7LRq)$BhV&|;UudXRJ~Vdw*xeLVR#Pyua^AmIbPp2vuuN$Q+nh-i z=1YDxsDnSL&9`CcO@NLcU0v*L6X6m7)wHt{v$5&PI^3UN`2JovW?XRv`eBNZgqwZ1 zV*<&+jKy73!8!)sa94~}gr@<%)mW`RijV3?;D7^~;X`wTsnOm%Q8Q{mtvIKS!fQ8f z!`75s82eUe*M8FsL`!ogE z^oU*zdC%wYCb%3;i+)S#-@7rK2KX^wEl06hgp&V+J}%VIc^Wkmkn7I3vnu78DLoMy z6R=iYedWJDZt7B!*Gynp$B($i<-aCB?C*F>3t@Jrpb0Ezxa{xG%zeJOxM0?xG31vi zsC&DB&XfzsKO4Qlpxpm1=pF!l>zvcJLxfEbQ%WM^r&x6pL|sZ`z(lLEJ)R+?v>R5e z2)D$?{pSEKXH>ah>jSOLd}8JXYUPFcME}Q&xlnWR`x?JAT#+i+k;rYM@?6BlUJ10*aPA;?I;RkL{8@8LGv+N&ikRw3tShg7oLTW3Q zD{iJb`b)0s5BLQt-cw?pt3wCV^+M+MT6;NB?#uXc%=dY>&mpr`+zQdSbbw9&(^LxH z_cOzb;?^DxZnx9A7BRlEj)YZ|5M?oDv9i#0HbYRIjh(%?umZQEP;`doX4`ZUHcH;#@3HkE`p<}{D|gr6dpqPrlyuY z_haU)Y#qlFW&YK*RmbfDOq zj$d{Aq^Dezoob#BET=kXht`nk3?;C zY+kZT9$mvQMZcB{sHV-f|*&7wb zzWTS&(6O8l31Q9od4uHe9ePJp^obl$G0}hrYXy?Ic6=%i`7a(;ZCk8vt1dP0B5_2ncHy-OX6Z`#P=lz0fM&a zUjuwLyuUY;+GIjEDkL4X<%x5<@NL+c4rGw^RWU-BGz(B`_z0(ZlUCpK z-7tf8T?V~`qRp9ikTiNFaV|!U%kJL@bT$Cn6kLfje#e6e=9Wc7mv*pdG$x4?exsNm z^L6w!ALV}#deX8Y))CU=yRZE;tgYUyZaE#-J@BI%PLzlgZElaf}=+)f3OtNnCxF@wLe@r>P`p@RfJOEAI*2*JnDOy`JBAh zus42cA{U5Y`F;F+q=O{nE;>8Hv_+NoDORnUSWK~t2>ntg0QqTyVPx_nv^P4TX}PsY z;GC<+hwdGG@->&X?N-!c`iqD6UZ8n*OZ$%n3NEPOhB+qVf$7|8bsB_z_t+1cuQx%S zL|zY^QoEC-C1tokFrk&5nm{@Nko5PKJdUZsOby7-O?Sm0R4rj>#}_MHq5wtW=dPXp z^WH7ze8{1M@)lmnR|WZ zR23|A%^Bj27=G1dW?7uMWd?IU8@@C!tdy9;^0X92Gvz4$e$GEa-gVRgE6xMx1Lm)A z-;hG@P-Ia7wO(CJzWm9qO;}@5$4p@6_q<2ryLQLk^cIa1l(!3#WEz5#q;2_~dR;12 zXXc4U;jXMm{BD5jOQXF1Rg74CufN|L2T#jw4ipDzi0eHcm;d3{51%;+?+}l1plH~% z3GeZAb2clR)VxO6f@8VoF5XLd^=0s{qSzlVZ%WP1L!Y9|PeScN-s9N-#8#t{yZA59 zT;d_(*0c>Zi|Nd>F3v?^#(W!E?3=J45f)~u<34omt8Ds=Nye}NIjxtJ1FZy!d$Z49h1T42hXvxKshpB)sm zDnmQ{n5cAbeiRz=)F5QzZ+X++wttLN7uq=a)+goRZ=esU6-MOyKEbTdmCvjSz9rlD z*8v+9S969^Ise{ZP?ehUrjHLM_v2TUo~?EHZmg^I6ev;oYmb1%Jx)zJ7%8>Bm!A`K zHY_UH?z=Jn=RGIM~$J6sr;&_^j$Dj^R-6a)^pGuLneal~w~gfVdT zgCpop5A}EjT`dvv*upVt`kjEs7lN0bx88ljV);4_wltdq{`U+O@wbYKw-amhkJsP$ z66|!Ixb7F=q?ZnNR|Q)sm;7QROd!c18VRyuc+rA z&?RL&n?dGi#}L4ZmA#zhIh%2Zb>d^`Q{Bt~;1#Rd)eaTA@i&4o9CnJ=N4+j~YH2L3 zj>-=l;I!e>j@95ctd9DqM~}h56&#Mb(cu({vIZs5G)jgYfH89Asw*@!))1*$qx1-6 z^ju!jtPITOLVX8eq!(lKCBSo;m&3jR0mgR;82Csf@7dLjH@Z#G=2VLwE4EC`I z1$kRm4keJ0mfM#-5&Ts1W&aL~wJ8B$q1dV?jsbLGPBS2V4s$MTp*_F#L^z0CKJUc# zFf9@^rS0?>REe;&m^dlYFJdJVkcZnoe&$ z5?y52cY5pMtlNZ&lXBLtaAl1gIb8wITVJRYR!-$+s7}?sp2w0b1Ul1IFMmF%+UK1b z_~$UJX)ywt*bO96=mmgpGH;)w4Q^VUXk-dNo@(7#{;nJMmuimL2tLyd3FLb=^Z>w> zMD0pMIS9F>6V}wi^Lo|=jzC=;a8;u_o~ZL5lpBrH`GHZL%wv<;h|ge9CGm=`{;M#o z`z_s5K~ezQxZS@fQ@x1m&W&KnrBB#zhiD{2a-PyJCtweib2F3g-(f^oi8T0ML-u)$>T$A#Hzxrbmxy#W&Zc?z8ODh4lQJKb$ry_Tknu#^PZ~D+5 zI|nccc7ecuz{`Mm5p>0t_71s_%iVW_td*FFjMQuQP_LAWv_yAo>0fd&0f$p2Pk*17^myKUGAo^bPG@R` z@H0=j8mh50&sfZsTl0OEWBEQGVW=)9Pq~(ELMG_JWll!8#$g{iLn`Yh2`QoJ#!qUb zKoKVBN0)juksf$)M?d`*PVE4dB58ixo|8`U8jUI}*IVXO17>V+t2k`@rBTwxq%-5y zAIge7exNhzq>^Vcu=43LjssxGS+)>-uh-L-;J1XvVln?-XC`HHax$J=mj}k5(~ds! zd%JmuWTCfCW{sF1Z{s%~eR%%gv;e`p29o~tOA2gr(If8B5jYOOqQlArUy^$lYr(nH zgnz4*3@0PU`P(wwC=kHZb(wnEFS;{&>Ecjl^aBjZ4D?Bi#vk}1YSpww%XQ2z&of7+ zi_xNFNyWSP6k~+3ib#Hkft>psT=^t>uTw|;b&dj53?|kKhd#tJ+EM|s33{7VMDk;j zQTLX_uH&Ic)M`XV!g*BOj1&S6=i}|{hu8D9_3-Am>pN3H&L{68(d&3 z_O(vbZ{^T=_7dIV3;6^vw@-!C*;Be!gJI!rDkoKGzIKR?H9;FuTFo}4a-oa$; z-_3Qh$2pB2hn%9c@g0J)+fVB4(X`@P22QTH4bHU4YHEx~hngwiqV~C<1B)&Sa|=aC zQFZ4;+^%#gVKH>^xA+bF!w^di|Ye8~4cj`YuQkK7r5BX5U3e9Zv;HmnVZ9+v%PG=P^w< z-u8!V*2KOjU*(C2%+MaWrRS~!FM*+eD24&y!B0J4^1YzbpVb9=CXu4U%J5STiGr@< zX<$OXpehK$#`CY+FttsQ{xs3Y}4a=G?u)Heq7{!#@A8IhOW6qD;XwSD1Rt#L_?p@F$W)MNK zTS1}gdtIaE9ec6e+8iD=(R)T9>IBZ$($YCPli(eJ;-H58OjJ;jRT17t-J$slgj8?;OV24{hex15Ro>cknt^TyE%=u*eJQQy{LY`;rF=#&q3 z6hp$MXb(15OU5Y=Co#Dqb65wlW&&E1uPcb=Bl@9Txw=xC(;hu^%cYXxN{8vb8IP4i z4z)^`VjHDpebR(+jcUQfw}^J-Acg_VI(lWJ6%1$n1{V9#Rv%`D>97WJ{rgS>s1;fJ z)Cy%MgEa8XA2jwn^GFH$Pzp5!oQrNE+Gk;Z4uuc5r22dxPYe-5+7sMK)vkhVL+~v! zlmjB#wS&6qcR&8Ul#zTS!3wpi4$X2oJ{W`>-bL z;w;zH%VDD=*&_GdH=?uO3ZX6`Q<%-8_%UR~i}3ZBny);+De>AOcW&Hsz}E*)^BgDf zEXW&lY?fhPhAZ1JE!gE<#opuU>5m^Rb7YQ-@F@>3PT3Z%|aidZ+B z3}E;62R(}?=&wa8`MoX&Offd8ZI`$~-XD7KFn*Z(?`^+AnJcX)SS6sDG>XLRkyAx% zs$bbE?rmoNDf(!YW$NS4)oPl~p)PLLqJz=>%J!kLDx4-Wh?LOhY5dK)CK?%FT)=}L+Lm))l0&yPGbEf-3?z;cH%Mu1Q)8d;5~ zV7r6y$0w%NvF9{fgNqzIHbEHLGnCY5*9{tt?#uV{@x-Emvfd%*-r|g%KQ{Up4zj_% zJSVoy@ zPHOIw{#`9XX4AQZ{0FrPM+IWk$G1FKxVCa+BZ8LmA+|rAg04q>3@d+vyPK1RE_DyH z%`y*gfW6V*RpPX6Ih!}vGb!!00YQF+3Bu{gGW+sc&YWV#X=$)_^k9)s-Y*psFJ$bO z@am)M72=SZ`}~ig$R0k-a}3SfCG7g`^ub6`8P_I4S5!~5fo9STS?pGap3E1(G;`1k zmwt}I<(e#3(&c3-XX4wSF}Yv9U{8XOSvCezHH2E+cWNy6ev=f@#y0SHWw2x{CP2?G zxc#^{WeS{T#GkLMOsSQ6qf?Fp*`z^(m*Sh6*z{}r&(E;9rX0w(!#phKoX$W*?5SS5 zaun&CRW&wJC;c{U{_P#ddt*!&5_=l$&hNDTjXfhRr_4@S#>7#Of4~M^(!|h8UOu^a z$~6tr>uzy%)yTnausJUy@sgJT_modc7rn*0?pn7reX-vzEOt=7k{^eu?hCJ36>9Jr zUlt7Jp66pQYd&=v2P|jM09Q~x$dpRBfNs<9~RP)|@>Dr0`#Y-YJ zl44<^)DY0Gnpx&~ml)*um2wy{LNTM!P}vy9M?^2+hp%2usMGK3jd!{wYZlfFeS^$_$mjUIOWNn?v!A=a1{>ojOkG?Z$ zm-U7RR4+k0`cG%ip2eEfO`Oy#wfzlX)?MTE@b_Sa+#0jBHU@U)fU8CW)6EFF>;vXl z4^p+gke0~^4fo{Q=B-EH0E~4Z!Td!+MZ*t?29jfp7z85xpl^gU_q@cQk5jisH-v<3 zC)4_)v|U`@Drgw_ZOjj_#NmD`kooe_nO6HRgT+(( z)tENtHk9%m;qo0aLzYb1v35E{Lf+?NxC+Q6x^{B>`rOzbC3iDvM6Dvc zupK#Q{3GIM;&PA&WRKzo4rmI#*S|sxa?4R zuJ{YgTpeVoO(zfaXY1ba+aEqZMt0A>@8ew=^Q`jLj2zspl63;KB6oG27d|kqBHtB_ zyJ($r;IZ@GqCdow=@waU7zD<>x#g**#Mx(~L$oVTib7CWE;Nc9%j$|*Vp9m~IN{DF zX#`h4qi#9?R{7seg=GtkR*Qc`{zL+nNVh6EY)kFFlDwY|*83)>E7(7u2!Zqa=I{6Z z&Gs>HPxOX>#g`^mrRnM1As0)#+Yc%KxY--L2 z*D_U7&do}5I_aJlR+HSiSmBXOE%3Pkeda#j&Z8Fe9NZD>D9WTBdC&e)o;n1d|3m1__Q78|J~H z&4qvSb-$wf+0a%OVO9d5$%HavZA^s%)8{s|u(E;9Saat&z`2)GdFL|}K03ts9Jy<2 zh(2J?_w(~0qj_Hbv-BNS`Oq26z5+5RD}wE5%a zWPq*wX`GXn#qZQqCfjU67{>u-6M5q;6o2cpn)F(0(?00I*75aL7At4&K&edWxg3Mf zUBgjl>#g6;^IZP6aow)3D8pgMqLxF1!XM*GKKS9;Y>7TxXa6DlC-J4W_6fNS{_!+I zI4mR1aHk-rJHR7bsju6m`RtJA5 zk=vQ_?3`-v1)dw7?d^mc&5aXmL!42R*_2m3w}0)XfJJnEb}oFHT%kBt5;4-ml>@r3 zYoa3I=wtXG>Xd~(!@1o$`d>Gql@%JGD_$x5HlaN1`rL`u4*!Zztl=Li=s<9Lt7T3I zc}i9fcP%>DuKM&BZ>{I0)WEe)DkedVh@iRJ@@9ojx9`<*LuC3971g#J!?Pox2fw8-&V{gBb3?f+ z9FAFNlPq;^cb0=|^e7m4fLIFmX13N={kf**CscqQ6%ir9RywUo3*&<~HWRAA z{+v_Sp0;t&gNSW93l>;c{w9i#s1d=)mnoW@Ku6;CDUwBsfxSZ%JsCqsP-n^-SJK8~ zwAxfV=>(<*sS@>&u$)={2}tx{^4jW~H!7D=7l%`h)tSdgEsA{=GklZKujZ^?e2xp#MKw~j|!G{M+E3J`8_;>_~JcCMCfi*3OiF3 z*&*Zz5b3_3#w2S5AbDOE_Pu6EAYaR#@agModpQaqnOgU|Wn}exAzLcEtibh{?S{4H zWIfvGx{LDa_!q>fE|&SXU;jtbRYkScL~Ee9YoNs)iWMm?#ogVD6!#RjA}Q`(thl?o zI|O&v;9A^n{(IMbOV&CM$?SDzW`DM!SpK(R9}|JI>`waT^?8`{&O=a3cz3=Vxx=N$ zb|X%#z4q3r22Z{lic-?URLxL`<4U{=ZxyMya>5v7T(-BaPd4Q75~OCQNo!Ij7nM-Z zhSKQe*iuBKrUx!(7=l=O6GZ^sxM9ng~53b5t$lBOkuu;0VvHEED%U3}#hF z8E?lsf&u?m#>)v3$Voduj3x>@IfuT+fGj;~i?)}(epgVdU+&k1t-{b_wnDCRDH=lO z6>Hr0T{*Umw0_Tx!oCjg>!z$If5aASlFq@kew=A7--w zSpv&-@+6;J$ER)Njm+ORAmrJ34g2Pv-`lgiFrP~uxXD_wy;%LcXR&==hW_?`7P0R^ z*d!X|Rem1|MOc5FzZL?_HJytY8EIV#u%h7~tM*Ku0m}KR1&Nk-8n)QV>~(IaG}j2i zNcD-%>qtKSyUOyfk6I{{zv=yw)mbGB^=kk&7jUpw_4Q~xEHgi?0LW1bImuVCI${CX zYiuhc(ri?H5v=JXP&zmE#PC;C_Yv0ol265_4Rq+elua<46b5%R(^_jz7 zlyi?~7u-BI3QPK0Qq?aT+7^FyzL89X(O<=wFw{4&z@%z{)c?fhmF8k$8wUM)0$3&~ z@;%D8ym!-sF`I;Z@n8OU6oAln2?dC4Ur135)+fY5^JOhU3(e4srQLa#q+kXTgn=2- z`b&7B73zY3f3D6d6#R>P#1H(l7~;FsHup3}SFCmhM=*cSQiu?4cR(uPL4QUQ0|^yg z@s$YuHm>$*)ZT6%%0Tu7bz})2joPIK{Nb5jd1SYAF!hd*bPv!MPqJ1iQ^Q08%00`t*P0a%J2Qj;cW!$hD4>Wa5qn{_5yf zO5+}DPS(MhHGACZ7U==Os2c2|o&O0X4BZI;7=4cu?lUcN$V zRS5oFV`oMNvx)mL%-);l>gsFF!_$_lOZwOAmame#Xz82&gM{ab=~E{KLJ@p$h%h!T z*H-o?+$GiigzFQ&vwtV*8w-pl283=(JfqplNu#9C&nXiZb-y?aBaHI;f1T(V6Tt$g zsF8Y;5?BUOl|vyK!!Za#uyf07AkRWf?^p~{*RBlQ+Ke@&e>$?i!s^lek0$n?wTY)1 z?0zBwAinpP3#^11A;0^C7AaVu;)5AAZJOXBkMZt+X9QfPP;gL@h`dx!J!|Sbu7^v& zygQfaXx-iemhg5kl1A_?==*;5>(v7~qkV!fMS=4TOl?(W>Tf3MbaF=9DdudL&yh)vT z?O?icv0C}h;B@aMyV*8BTL!McqNQ;g*gKDxk$jPFu{WOX$|awvfKTgfwEx`4lbh;86s)_5lRbo37L9Xnn1&BF&3jy33+d;qFQWS z&0N{kTkp3>t}Xs19+|7EhHW%N`#Q!i7vL$Xo%Hv_?G)uNSj0XfVFuK7Wxns)hS0vg zm)Fh>a_@9O^2FXRJs@$~&)sMlTnJUlwdid1;=Zxw z9yvanK?S8;r`5R4o@T@wP4T3sF>9+~x`vrf_@CJe+k#~E(~efu`EidaJ}wRw&5 z4^{dfsg|_{%;=xvFJC+wtIzYQ0Ke2VBvONMRmHVvB>eCJTQe3~ml3O^OhT)Ziu=Nk_(Aqt= zwzhx}hm3`OKn=@*7{PsxZY8YeZ{HbcJvgylTb8i@L>R(sYI%ZRd%yb z!t(oc#h$p<1P>vV&j+HEIc&G)LeOK;4O zps`N3F=WB-=x<7zHzyu11k{p=gke|oS)$!OVz4(TlHICrqbWbN|4J)^i;D1G3rSfb!9Q{0Bz8pfgB@eB zabTOnihtzl>&FcVZ{+;t1iQcIE;_MePJ|p|7vqrr=f( zE8^_IYEB%l@_P1X7VskX3jY7woEQ(T;F=;wh|9)1)S-bF|B zf65*@QC{|Mm)*d`No9Wv zbbQ#`n-Kqfq_<=NmWPQ_{BlpqLyjgMS$2?B?upvD!+tv6U!%Mga^Gjd~AEU z%Ias5PLDc#-u^?g;NaDH6H3sL$wQ`C^i5Xw|7z0EFw;zMy{C@MqZR6|xK0FYM(NT1 zWB_uioMtkxPPisCF=OPe%Ou<6O_5=})EVmU=L|8BfvaZcVb3U{E4$o0HW5o1%y|AR z5qt`j{NYVu0xSkwvPa>MXkcZeYn|mxNuFVJX@1U&S*R*mrP>a+1Ap9an-k$}H($fH z3{Jr{JN~0+E{ZWHNp7g%-@9KpGXb0}+G}k~Ic9Yw_ge*fdD_|EN#<>pmo$={JE%FvImlkOFT_thT z4LX=gheLFz2kS$FcXO~=Poj5ozG5}*T$5`{fyui_(xbi$`Lgb?r#q7yERC!vl26q3 z2X26g@7+-^akBD`BAYW>R9m0CXLBZzgrDOWGThBR$7KGRUj(}f-`t~ZmzyaK0tHf= zSrZz5`@>^t*YM5wEGfiPL8X}pWa^8aB*0;i2FaX8GH+nLNwCubv3|XhNkoSbPV0%F zKFf;|a^GS9vb3UiB15y1PFm5nPAwgR)NfOeSV67o@0)$KJ#)~eBUD@UYibw&wd6y> z$zktTm{TE93U}5UXQoY6@?rg=>E1Pz8hdZTwcVpf$SlNSc15cLBK|h6Ah-JaLjOtz z_Uk6_caQ7{ds8x=%&gjE#AJC^M21O^D@BUlWu10bcOYNS>&?wOY4^Bo=9frXfA!Zi z!|^UfnsW~}_NK1t-@36nFIu0k5oa&RC%&SVd(r(2Sqd)8DCTGCBW=11Jx*H$m7EFN z9jZ~VtcTTJm=6aKXS-Q{OKhdwJRbzRa$pxYFn8o(jA=$W0T{lNMfjBUw5WhGPx8yd z1L4en%1`FzLOWm?soy+>Vyaxs25Xe96Ov-Ni*1)Ze`uuGHH4!5qO)dM^sWg~mYK0q zj_7%6{m;#)xukb_FYGDXsz{*65=7^mZSzhw*@rim;KsYxRb=MG@HF^F^7o-jXs-#; zX`m9Zq1HsM?QWBg&lKH#MRC63Hjh7RC9pCYX#ctC2Zz#OCJzii@g$O$T-;(0kIvY# z+1d1E?Np&(eGLHhlm24H{=A1ADIqQ6NLZcYROqxT72a54lEG}SJy)+Bb_(y+2Sb5Y zNr&4+J50<0!x$=$1T*VDZjfI`-<9PfcnY1Riuk`CbmzZO%eoFwCHB$XTV$V6b)@*) z2Y$WhyNU@9ug0W>w>?K&tF)bK3$)+&d8ki!@@jMQYMS$w?{SeCCK`kn{!A9?Xd!O8 zvFyLRP8rOr@*1r93+(6hFwo78qQA#&6qpm%eGm}%`tMOWz0b!{-%s#o#&n^-wdyoh z@e)aUbn9Khy)p;!cbQuXzP^yRh>@FACS%NdbQiD8Dw_ZHvJ~Yav6&q-iMnAsR_2Z% zUF7=$83r6y!?C&8l$6YCBz&?G%N5GY)^`Chk$gkfFi;t)l0aZn>7pl%Glhb(NMq% z#jupeA@EwhsY!~gB&9lwZi-GB{c8LR6+1#g@5f$(Ja1E?eX(ios{p!BxQd}lTsi*x zkd zil6VgryJnshvKd?^I3GgRlXy1=+3u#w=+*)yx7AdGOvOf0@wYNDc637KOZMZu^fT$ z7*>a6P(nmEbzv{>R$6^5Yk~A=k9hE0m&+z*40Pj>yBa1zV!dPNEN|(;JCH+g@~3}` zpT_DEo{MzWRLYoQguXz|H-lPxQLbX0X$HcRM2zixwcjXJCW&;1bN|Kz$R%mCD`=|L z4X&poC4$4JIKYw;tn~5NrIy%ndg8cM*}KGq!k3iUv>&JI%ESgyK;R zOZ1CYDNv%#AlQO?w-!p4Rk=8AxC0a|?+b&EWKQ{U6hac6foLN4nzeroHWp@kox4Nw z9=uIlUkt5v%1}hlQo>|%3D%iEYf9t0f`U6l!zrn8rB8Vl8NM@CNN%s)P1P{MT$3MS z-DCU<#pgC)#`49wJyVVWkt846SlCqw_~5q8{+?cmk+Ymx!6aXb__$c4wu*Tsc|JdP z;r})QySFJ8<=XPt)MPf|dzRQ}sih8_-FHDt?yx}buY>6>Rn7|0i{r)7(f+)UH-3*% z#=~J;)O3d8E28-&s)gEo1p`w*@|p6zvZ4F>0(1xifu?JRs2n{wt*Xm_?W#b5tdcg%@l z0kl7@iY8uV zz>uYh@Ln$O`;soW@If^|>>GPHl#I(IrawzQ{9?^)xdFGThuPBeP8A}Dua77vWU`P~ z%$rUEx*>3tq=)@lNvKsmB?DRnjOFQAc>k&EGEdAeE#S$w_cmL__=nT_fz$S^E(PC( z^RN{HrZ(S1wihw5^+e~HGG(Y7c}-A|ZVUJw7|&OwGn~rJD2_TJ)~6@> zZNp?Jc>$BwV_CuUZBN8~=2d=6a-D*i6F;yO<9mx64R%pM0Z zd>*Hj(BvSfTC>guVDClc8*|G5+vnl1T5#w;o;fzkPG-kn@~vlY>#h38p2MQxh8t^; zxc%W$kpNuwV;FoHi^Hen6#-E5?ZZRMeD) zhJuD-n6ZN=kvcMbDfJV}n00I4g?SCdNd)owhP1rsg0Qq@oO-62O>kh60eYsx1KXto z9W`XR9B#han%)DRk=Qemu}xNCXX_F|W)rGoclEqh8^ApLc|0y{dCqM>=ggt!rUyev zM%PeHss)XSVDbQ;x2e#WgJB(M42IpV$paO%610s_p5b%4Ig}*IV2{K`FfJARK%`Sh!FzeWbFu67=-f z9lp?KLV0nUK^Zj3USMEv;r9ds4?= zgJX!(PuRPEh)e;oua~2rUx-J_A)9#6Hsp3UvuZcXQ3J)e$&(pJ4(uhkeM8J=uj+3g z-;SUzJbPik$WKnswR!3+{O>m~W6Y5q-L+;Ewa7PS$h{et%>;^9&!mC5$$n#rxuicc zW+W3;b?7Uj6!itL+`;2MW8@hGMvGmk*BUQn3N0V^e>T_m<95DN6=AW*B`TsD6#pSz zf&qm`uT3Ot0B8=mXq`i0s!qySnZR@5&F&>5sNVGEBbCO>%Sk_jLgi{7@98Wa|Dc;K zLcj+IhxJ)DNz130HEA}VudX{ddaI2=s6^iVv%@j^)h@dvdi|rF;kq6b(xS4SZ3tz; z3*X<+kNH18jfU^XAPSIbSQ-u0`6~~$byoY7NgiD|BV)y3peQ?N3gCw4% zLw9fXJ+l+c8^euBpVjMKUN}J~zv18hyy>zvPcUq{yg)}IKEj+oW3~E|IPE(M#!Sgi@uI_o!puPzEl&oc(3UjyFnO+L55qFiIwH<0!UU$d_uj+Ue@sHR%xhg;MJh28^2b2f*6+>57q&%w%Uub}fbP zl8oLn+dCi1JyA&|gDqcx`2fb;#eeYyM3VM5y48CzY-)92ApjT8{`5he{e4v8)!J*( z_B5gTz;H5rFK@)7$5&rv!qCqSm)}y3C8KA8xIaD$HuzU#)t+(4yyXmXGhAg;!`Hes zZ-Em6m$m}>m5jRFPH8XdpuOSmdTtNJgk`~I6VV-m1WAcXE(ci{Lf6WT|2XVyDMOlC zE6i$O5D=#zZ9&=*A925yyn5ZjAbG#y_T|L9gCK7w)^3>iV2@?)8Yla8bNhsU@x+iF zXFZRgXg5uqe9T%}Z}M$-eY0gio;OB1M@1dMQw5drB7d;lMUKPWztABK;T##9w2&pMMUg+~)6yV%%Ye-LYtF@*Fs4bg@I#`0Kr_^S7 zx)eL>VcGF1;RKTd>sgMJ+W{iMdDEw!R)VN_v>e&j>6z_mq=|Gly|PyUFgKqXcw`AV zg2d0D`IbYS&<)1o^G2uR>QzJbXahpo8euoT#E0#>E;L= zqF&^-?&9-f9bf@>j8Enn-k4FKME6ez?Qeg!K@eg3Kk)(SJp8Z^moLk7P-n}B?huwf zsLD1DV*DfS15^SJ4%`x2Z!GKw5~B&e;g3;rUkVr?k$!1kZ1k)kCqE|QtiNsyCfOb-5o;> zdOrQDWsioS6tr}fc2rxX@BUPrq!I6m(EF07-~wa%kF8yFwszs`5!FLg4nJrdOix$> zltRNE$7L@?kU?kXkAo_rt<(pqIB!EjTciR`^ZS9Oe;PmMoUpwpg#*2n5Z<^K8K&Hn z0*fFGW`&d<6Xk0<2=~oX&MdQj-iE^_Ha`wAy$nU5w02sTx3>eS88n5i+gARt^2T+u zgot!Ql6=Y9{`R)bii!^!BPcVWoYEKARXP7%RM_yv*hx3~5m@&2E&ZKbq(PMD+r#rO zV$LO61rx$XvXD81{H_U5$ECrJT`Z|lYxkh8LGoX!w|*sSNHUjpUGyO z2lRRGrOWz17}hpT?&_fq0@=X*^Nd#f`Fk`P_lO3lE_YJVt6aTPhjeqI#Lr;?vlk*i0RW5HJc3;feK+x4zZO zgVgckyg^>KxMRLax+c!BpfQxzfI$*o6i#jMna3l_GJ*Uf}n(g~P4w}UH^YNJ* z$m4Mkt@S8Ild`N!oyA3Hez#953#zxq5})>v@efX4+m|3G{X9!=JL*Ip;q z`_Wx8Q~YT|kszB{P0hxM56xr03XK8Zudk8qIB_TO$c=f#jLF64)V^R()OJmAeaUPf z?q0!*`&n7nCy$<|Qr|n`C55-svi7*vhtgs&AmF}HDHJD*O{iBiD$LCv(uOD+KQp7V(AyL*skDw89Yz98vUkdg)KZ1ptau^bcFzJB z=PQOkt3|40%FFCnD+FtzU(;K9n<)nO*SLN8T%Cx#VlN6`H@{5u)^E$>V!-W ztOfn>e@}nR$c{nrnn{_}3L)d}kSTUn!zdE>EvCSP@qbHjT4{fO84L;v5B!9Bd^x)r z-5m}JBG*`(Kz}>A{p#@(ffPndK+F-XpcTAJCd6(35ea50WpJu(ELh)9=pS0&gP1Nn zq3}YF>q2PpextskG5OG2Z~w*0e26!a#PuN+X{zB$TcavN9|j9PQiBea=L8Q@A`aqy z=wBS%`9u;YqSlSQ*8b+Hg8CQ@bigcG1c=tby>Tc~Y~;?x#ABssZ2!gL4_cqH z8s6e1*jSrrqJnY)n-ig9-@oeddI5ss?D?&8`{T7_I-UK)#51Az?4IYQ2NSdlF3B>f z8*Vyj+Ljqb91$-r{NNn1a6215kEgT@*ifi``#1Y)*ggwF6nd*XHrueCW%B6c z0Tde<#ob+%MU~a;+a4`$8$Peh1Yhv@14)<;ij0-t9y5_@OnbH_scSwlrwQ|_4Puvx z>pMB+s08I;>Kl{B9q5VpY%_!(K2#k$pHIFJ7q9j1%<_a^&NMl~!Q}dp+G(16r;LDx z6B&4Kh6XvNUcThP9-hFyw(#aA_hXp+Fh*9DSJO~l^G>^``Vb971&QJ8bQv*@+A2h> zlf^gi7OMr`sT5TZ#cA86{|@(5;~0~c#g3Cj`ts@cqbfUhey(HVP^CxV6X-^NH(zMH zgi?-i6_&Mu04a&8k;kc@;YWoRO@yZnV}b!@|K=Bo3Z|Yg*}-y{ENDR(`*w!P@4bai(Az5$BMlWHk+WW7Bm@nduv+X}`x zS;P#pII57xTgGVRe|c^@ub(u2b7gO`_4R4BU4PuLc{ydXGLO)5=ArcqsbAn^sHuKP z?`Yzjj!_Ql!-utlV!3k-zQ~S|+tOxuT}YVc-~U#{^l?+8FY4}obDo-eS0{yNNEE5K z!~jh7e!UER8)p17rdUdp5;dz8ISi&h2xF;bl(ZrMGWR#PIY!ZXgGU#fD-Sy1*T7Ya zpO?=!eT;2?$9pl$P+2`7x*?)KmP0om!8DVEG!7<|Yep8|hBbQQSTxJ&Ub7OpBaST9 zIJYM9_9jQ@!%X6?7rO71!#TnyU^{#Qv*SNP7EqG`k%^%VYQ!S#>NQFWTIuU7=tesJ zOq&xFz3$@c4sYK=xDhGUmfwn~c+b@rWB734>=D{M*KH`Y*pu8>B0}V`n+;%A58Xrq z3?cU0nFqo{mt;*x`>GrJpQ0D9lz{Wj0&5~Kf1`kZcY>d-{tTZvSbVWR$glS_eq}JM zj*+mrY_70#dPaB6uwQyw3FQ*)OfTun5^=$TSE&!M_u6qcTB_Y` z$NhJ|PmIWTdOM`BKOIX|ekc2++?it00NH}j^{+ZZOJO}%VYmlKAS(ai&spc>o)oRC zbV_nKC*LJXnQ5bRX*c6w0FzWIAu%j9LCrJ&;+{O$X0s|OPN@yq62(WNUE-yW|IGc0 z!Z&S1QKTC+*t0aM>7sth8dj$IC6`44abV_F1~igN z!t|d@1XeBx{nz(b$XgEOO@j^DsoGMJQ|)4Fs~WyFLWUlFz0&l=4#p3tQb78$v2{X0 zUhA2Ev{?Zy!Oa>0nv8@_r9^B}Qv}pH5n(|%Ou_Q586U2Pkm96TWt>A&`Z>A~X)Oa( z3RKJjR4jvJU9Z@EtO_zqmNfL*e#H>n)Yrw#Z;%_6b);R;g$|yXZ0Y25p5UX*GF`t< zjSXz;b8>=jp0QSI>N>G&Y!RH86*u3{f#{w0=uJ?`(_0;nM^Qt&TcrC+YgmzIk*+0h zk>#=K18`QD^WR*LUXovhcNeP=6DbV$dt_V81ey2d->zK+($33F>6x`tePd$wVh^kM zCN`3N16Ijbnq9p+4*r)wjJ}J-oSdv4X?w3`L8&=*1dq4v{8>S6id080D%DgYe4>XXCHaI0_ERS;N;f(l7jBIsz}C%jn3OyyVV|G@X(VEIessC^#~C2>M*tg-$x)0?HBn zPKS9)sN`>o`ZZ?O-=ZB+a}`D=_%4%6PJ1&Iuo`_G@7+(pW8qeEgF%4$qq*jL9Czh( zoAA`eg)3$4#0Vlsgp+Bobqy7FO7VS;jHvGM_fR73=OOYkrd%(eyjCzXKGi3+O#AP(}PJ1ryf0U zI6pZ3oEqpBCs894X1jb>Q=O`~<3>NA*Yo+H)s;IHpXJ+U1j`O?KW2x`F*X?0y*~aV zkZWn{69XYQkB&E{xb1>J<_}j5TgZ-}-Au-bU|5xS3g9fxaSg(;Stjq`1w*rT1EZpe zPs)Y-S7g$VnNwDkvdQVNEvN5*&1I;ai?`!pb?8Cz^#gq~Il8c`H=jrsergt-(}(V! z!6fT!NmQF^hlvjB?Cf?Yt_fE%_PM`p^snyXu<9X43B@q{2F+u=x#xmGSf;P6*QFB1 zrdgOf398)@7tsG$dC>DZ!yf_yW;c5W=!Ect#Nq~({ng?x=&-l%Pp-B4HNs2-mJiJ7 zM`-%v0lD~0hzWy#khkx{CZ8Ht#l!cD69%o!fv0l@9=I~6A0j|WG=ly&C8rx4i6<{$ zI#hb%X`$>`bUlRr<1d93D&dw{G(Awj|LJ z9hVSrW1l&z9WJB^-`#_5=<$yKQ9`pRCE%piC62&`8MhSVfeBNsRVt57-NP@bZ|~Oh z#Ytf*)J*ilt5$?F%dflZ#{}rD&BKq@pUk7OM#+rb-TojqiJbiO)4!&R-<>%hO^gmDbZ<4*~}z!kjjF2|F!Za7A1~xt%eC2RJ(D}aj(Tw zstrWD);ESkt6TGK4^+J!D`(7B8q^f{9ynMy)w92n&2B$iYD~%y-mY7waY6l=c27mB z)?(h~<`_$%cT{lH^sxknA`P`rgv7F)$Z9+8Z z;`+=kC~I<5G`#VR#^pq>{=DH0Mr-t)+@Ph~(jKT8q^g~20$YYZHjbqQteV0f` zk9vy|6#Q6D0y%fP<&#QiW`lIuyM*?)j9w@WtPh&oJ*dA|~=>oHG|!g4zC@YayoFU5C-ip{zNu<$W$H*UHs{>E`EK5BTerk^N^&r!xKQng05iomD49c$`AtcU2T#Upa?ob;Ar_`ARlAqoNab__!@RHbXr^u^PV|C z?&7zxs{PAG+KXAv--^9-wi5Dwv2ikl0TMVEVMn-ygBqH6G{d|69%4Fi*m$78c@_}9Sdsgdvh~#4R-i5k z7Xjs>=h+{M&+=y9NOX9buo`Q>EC?+}qyh0n4ngogjhmEI7d>Sa3{3KAOc735VhY>3 zT?X8=43#Z42x1L?fafoB!HTwX+rMZ<h) z6_1E#okU$F@Lu)<$=KX9bkuVP&#vIP1)|97#uj<|Nc&9(`NwVHq3_c((}814kj#O{ z$7mr?bJGpn#l4nN2Ux(~^bsCB8S|)JNbm{|6OG%fyIa zOLIf8MgR|<3tthac5t9MeSr6gMeun~636pV4GFXVl&9w0fnBV5%r=n*0CB;V8EwrE zKU)s{Cl@hqTAX72Edp!CUXe^7zB7viW@7F<(lW>Z3@m{6Xjy|m$M)^D))7P`fsx3= zW50L#y5qQAaBK%OnDFZ289QYL6lA z!w!0B(QWue0%0Evl#n{&<31luAG`d0ayZu54h&8$HvkPox+I3BYuf{tEqQ zS8HpzMU&LM52qLospO{4KvMMB*1di%R(rWRwaa~6VO`&P5oG+UJo{Mf=_|%{Fp6kg z6Z-y%tmR#J!`iWZM1xT`^J3V zje)tGZRVf}V#J6&=R(X*;vM6~LaU%3c+|~KYrnFD=*AhNDC2*ctyn=TDW>|{@`mVx z32PK1RsIO=UsM!ZnwBB8SZYKG8;g$ASGvYbQ;-v5pkt+kDRl2B*_1m=S^j6qXZB;y zX_-k^-eeDhgSsM>`DG8rs?hBOEkgb++M`5wtF2%o1m;8nAWZ{6a~(%DnFO7(u4UOG zE}diarSJNhm!bE0CwONftx0+4;hv`~0|3ne(YtMt9#2(XIZU6sGg_Dj-G)@zIZz$% z&wfDBIs3k->gWe(z(M|L*~)WJZU!W}h0>!EwauTSp=YszUJv~D;^&b`#dlRr+*J|`u?hK<->x3RXcO&vI zPVUMyC$gdRmWvx6%k>xpT8QVf#aXMjQ$D4k zLDyD#^uCseU`5d4^2|yUh?7ah-{JBvs7f5`BvNMO#n2a_`My%#dZ<`HB_PX6e+3f7 zf@tT-`s>5c{OtjN*88s0I21*my7_pqN8d8Ir&kP#V!`y6w%MW*DkvA@I>`|ehJ^*u zgTMn^-dKJ4T&G{TP9`Rg_I|VA8DK3}u075zyY3c&{;bHFUvKt@u~f$YQ}~=;S>Y=a zLe5P;PhIGZxG3 z_%FjXuXxVXf5GbJLthihRy;>(R`yTtI6j&wkpTAvQW7I=Yn0Sd^0e*Gw)^rZMYT_? zMqDfJNSxghU}=44s2Z*(qVLg6G7B?1W5dfPkZ&G{8W-Fk6&Twqhjc^Z@M_W3d_xL^#Odm8weN{ycp~QPL z1*PA3w$NXk8?<_7vb^!V-PJAB zPYR^*gNupWIfIVGIi?s_1|Q>4_P2QrSfth(7;&a|t1MNVl(0g_;|o+6@YSvf=GE*? z2!L%d$KxBtak4~OGbP#f8KAifeP-qw8K%NmE8LnhTw+ctZg)e}WvOhL$IiK3MoZXP zJJiGjDzPE@>m{^XLv~Q6`~68FUxbaUWLPsibe}p?5X}`gAP_j)k+&r3 zZ);c)*A47yr$mg3Q>)+)aEE}N+uefw-6Pyqj@xpES_gcsY_u)Om83SU7~$v%3W+^l za)e17W-J5;$zCIOaS1epwS_f2h-u8>tve{OEVgDbCpKiBp$gq_9kCpP{;sk>7a z@SW6cMMe!X4EAAVZxXSgb+-Q+FGBM2(dy*SWfd(?N}<| z2MRjELTdiRsVeA^1~$nG+*3pM7*c2<;v>teHG_Z5Bgn~{@v`(eZYKkR?CcY$`4NXn z$P-xny0SdHSpWd(^n%wypHL?O=wlK!pGNNXs1Rw%ote}Y8MTc^8aMY%{nO;lkg@Lw zU;OcjH_;9z2TN!fn+V@KI4lit$<^5Jva;p>1WLJ>KpC0WozC z@fx@)m&6lJ)Ghn%JdDFP+~)%6)h6YF~GaMEVX;t$3b8-&`crE$Pk9Bu_fB{L?zS z9W5vmqnWwc!Y}1RvssCAylZNzrxu4lztiIPY|`!KsH65T+|0si%B4O!rnA^ks^j&F77bC3=}KLUn7)@}caTD#5F|`6kf@?@9!Ki| zCfWH42QG5UB)dukG6*@?G4DPlg@?xxHw-j9Nc?;DnaQ8l`Dk23#^!SlxXYN2CQ{KP z(WH@5Kq(!R(j;Dt@8@Q_%IkL*Cw}H40E(iQ*_$*^mb|Zw4*d&f_%sP=j45ww*hLmq z7`I#m?Cw&(R6guleuVz4j4Or>2ce&5nI5M{VZ|igq>+?a+?&m}#=Q+@MZD0=_}xHX zm)8|x@T(h?u!;VIZOJ@FPp>6fqQs^SP1tO}Z&OC!K;rjhDjm%$E)8|5 z4B-%DAjgwdR76G_l$dg!{uNP#2T`CHsscd|Oo1Rv9>gn?thIcne= z;Uv%8i#R;8{Svf>v>6xYiA0q8k~)8O1qn*dZ_IO4rM zoV@Cjf6Ej@Ivbo{PK~8=cjQQnU$bGCKKE5CjyfbR>9P89jd`kVbV`46uB~iUo^z3f zzdB<*k|b$Xsf{iA6CP}X!ZHYrJG@D4th@>k`+-J0HUiEAmAe1*RytDss+I1j(7Y14 z^yY_SL$2CXXBRb zzI5Ht1LD1Kd?&bYUxyGWr1lv*0S9T$wSQOO#ftyG7JwSG#{L=R`}bp&alE3Pa?b7P zq@(+{lt!V5+q-|0nXYsXm9tcFeQ60GMsTnZ@GKh4)tW;Xr*^ z(gQGwUlcQ{yTwVox775w0+`{)G+jH;R^Om<_KaFagSa4XMW-DfGP{2w001f@W|Xkq zp^J~ixfZ#uh@Q2{^$AbTj2BC2d?;W!`b+1{uD*wz>Q2tI7M+oddlN@|-CYGid3np8 zY=HMH$9BXi81ZVkKTX1ONYHbV6iPwFjo0wWMOkA( z=U#3|aCIOnI)6K{;j|IkA~b#WmJF;Rw;5U=@75YTply^y?uoqidwb(-^Z1YJ@i^|0 zhi*JqSns-lc~Rqk?FGH`9)@nz%h;}!1lBkbpzNhFsSoLkNLtb4`lLX`e9F0}f$xHDi;SnEzo|+CT|Af%$kg)}il-dX1o% z1gfXiHA-JyHH|Tq{J{nqRjS$n!Ow^%9$K7L8;}nFMOfp)LX%e8=63}QR?C4}B z;+QbnlTsr|ic_kVBrY~48^t(<>|mN5UTiIIGCz*fl!%8FC=sbKhcASC$kfemn_arn zFUg@b$e%W^(2pJ)YMUlR4Hq*?Evd#g(+gee_tC;XPTuubUo_NcNTPDw#&^yBIK0Q9 zp=TMdd{9=I{OB8xC1wY^(wZVpC?CTkt7bqHQWW*RvYq*lsPZe#j*g%`VsrXOC{Y*m zd{B$Lp$;P3RD=&)yPr^%Ue$HfyElI%j6@J$q&xV$_C9(g}M=gr#w54}~#$tuEJn#r8~l zTe+|RsDqspWu2;nts;PtzuKE$86%$x!o&op>_7N3u|8(|libTT0e^uUR64^Tiq7NT zj7wN*6CaV(XeRbUmNHDc|3Q!}DW+Q`0rs3M^HSK{ao|~x2m?8(VQ-x;KDbQZXQ1AD zgAdAi)#Kiv;!2`rygu}5wkvx7-5@x4pwQDi?$3rM9&t&)xzNydNs7oTui!-oO+@ca ze;9M=-rP!RTPV_z45muE9JO1sdU0Eo+!H5NbOhOePxvpF1a{^z1%`!#HM62LIKTw-%R%)wsI;{^Y0yMU(c?Q#MTl4J_l^KWOD*@Fn8qNNeb9M%S zJ~k`4Q!z_ymYv_bE0@-wHg-tfAJjJC2*liooUcI_KjevoT%4qa>s?5ClT_BxSueAN zBaS+|eJ;!No$OXE05;bCeuzK$Ot-qu&)>lXH+iR^NFMDK_DC5Uxn8Rs?+<+keu!=K>7Bt!EDV~ZC9dDH~6bk7?T4tn4 z;nxfOIbZZ(v(SWdU8=%&A8woh*8%dPt-?izZ7)nQS(WK|Gc%^lHkLB2aR-KNu+F*T z%*pqN*)${^EW1$|>kLB42Eil{;-0OMeQmagX%qON>vl@lzkWdm?fLhq(`p3-xk*DB ziKsArt1<7}sU(?;2X`Tg#ncLRzpynof?I^2 z-22gz5a`1%H-Zwh0bE4K-Sr5Gx-KiDv!?%fSZ5*iW>5igzpdJVig*G32?r&s`KHWJ#G zo@&wS`g~2DVE-#2O^D4P8;PyM1mZe1rO;r-=Fc@@K#g1#DipV*i}~R` z7$p4pPrLnEmMwEh{wtyTlONReMiniMwWb0!i=LED5JzG+b0I68%tdq3n=_e#yL`+0 zMQeFB;w|bHKD?QBA+o2cGIhcylA*5}SrL~w zsx?YK`4sb%>qS)6CsJ^e^}6u&%VmQ46$;l34X3V%2?`(6w2k=_oxEvf!w2u#+s)z_ z`uX+>ZM6c2o4}jnUMG^G2?A@eFBBw7NIpXB<7~x}?RtipGhtgT1xB+1Y}i+19QY0( zHYWCrwl;)gf#P4R0de>jL!=&igU}5r#OqTW4Ah~iC8%2KYa{6aAWf)?1~K6&9jd2T zZ3ug32!}|a5Q6T*lrJKq{`Py50md~Ycjug?#SCFUacmTzxNMM=Sto|kxE+QCzYSjN z%l%86aA~d#R_@38dGQ%ix2||f89$3(|7;y_OL$wpo%LXR$|&$?$#O}6H}vw<<+b4l z*ARPSXvGh`I&hS*<@7<@D3Ic-f6d{-W3NZ>NP@t-$jeynqW?@QbqR+Wb0!GmX%c&Q2OPK5v(e&WoGuVG#;*|ah6#tVOg?m zdA}pnR-~KlZlaUkGbUWkyo4ybShPrd4}RxoVqGYZAL=~*4QnzA0l`3Hp-nENx+#*G zW)DYR1*`1B$|OwQN+lx*H-EmfNbYVhAjv{FWd7vX8Twp~o=JY|WL8S2Qlxi`>{&4i za8Wh4sLzC`R^>ec+b-7%J!K2mG*NE6)I4mE8Z~;jm|OHIr=k=d+CN0bgY@Kzab$@RN&G#p`YTJZmYuWdJs|yv=e}!ZC-7X$EBx^#Xjyf0K-0! zW0)*tRBM5uY+}6gQ)b;NUucD72w;L#cByiv5iNlSj_-@I|qg@%e#}-Y!whsSx?r@o8~2pgsaBiLr8C- zpl8_mMwo(08*1y_xaB8{;<=7jhfdF!bZf-NBQ(8vs%vXIhnMg34-xm$ydtvA5%=CF zxvbLnU2V#L17Qx0)JZzmKsTQ(^a(IT91lPM%a@qP8BA+F)zn_xu=d8OqMEgiS|qT>n}{sEZC%HkVC~7eHD7Hzb$vLSSF<&8^t; z%>?iCfG+e=Y58CAG3bx-o3^1r_t@Yj-PlPhZWRrzfq%2CjTd;}fNH2YZc*dTh4{z| z^A#LI#1`_a)9Lrk2mRI+l-nR&Z=#bU-MJO)>d96xB?h-PfeM%;tO4NPN19)rd+4kt zoA#97W{wqDhE5os_UvFvx-(P9R8$B=X%WnkJg^XP_Zr0*qnlj0{_ByC4p`7G#{(pH z7T@@(L&v#Uldl8EwCxB2V&=L?=+ez8!I?8A4>?;^QVqcaGv+s2YL0|CX^#@q z=Niv=S(M2w2Y53xKCtK@D`Ax-SRVQ-csC1S zZE&*EKhn*HF-khne&JGtgx`?-HUzZ`0$|)ZV&4D*=0Aa-qQUp zv4(GaGFe+*lj-7ZE6?`Yq6w?A0YetUrGeQ&)Hz&)h8c@@yTj1u&8`!srpr#6y4+@4 z$bwuI{}!V7SDjYC*3>}?=l?GI4g+w_ry{zYzP;NJMKtN64%M>`ZuDKcE@E_|2sZi_ z5@>n4@Vf9@IA#EqbY8WLMd9V4({z^O)BcEWOjq@I+vkg@NSbS-z0C_M{;_Ma4pU*L zPcuu9xWd#ZZnxV`J|zqSzc0Rm+pPglK)}Ng51*yD?LbN2X6URXo>R(GZz}>_pX*7? zCSXlYg#^d}|0PhrR|U~1>DKY!O+9+{Ay#7@EbL7Pz2i$n7$>9|fj05~$Y=LjVamQ_ zawIyH!@zovs~7F5&Dg$y?GHBEf4v7*T^q!`n|u3*v~;gLiEG)BV80Mk=jj+53;~_S zo=<9u=UKq5AnuY|UbRLeh^>*Gx>R8Sp+lp3khm8*ekjSxmk5l<{D+l#Fnc?hLk;&5 z$J1sT#q~v*#M20iT($3aIJ?e;Uv_>ipdb!sJM>Eu6_8EKmU3jVe`i%-^c6gN)cWrv^a}dm`7d- zB49LGb6fwI=+=Nz4+}9694u}}V3a_>pE0D2Rhbdv0E*CcBV1gfCuWIZo+gWPr0k;o zM{`aQHzrLAvYBB?mtp8;G7lB=&A;^qi>0xB3w?#x?!%c%;A!2mZIiUywMMUPN-VI# z(|8B!^zau%Rf6J%jXtH4A9nOYmNtu7Q1`?kA4lS&?4MTyJKP<=k+|Zprrx%|p>X4~ zHqio7pNe`^3J3X> zC8^|h+URefu#qo^*K7({@X#0zJPoL@uZUlM#!`2IH{>7}NqAePIr<*%6RiBRhLu9H)SkxVeNU451ck-Qk6J9I>(goug>&xcK#eA>@`QPJx*BgaC*-NDc%qkuI3)xzB-bv# z%b3{rYZ5DpgEz#JOywHJ+6inz>f3<}6k{%-?#^}AW4U{DcZJ26mnF2)Aeh@eMAToV9A9)+qH5D%E1 z4jp~(kSR~p7CCY|zaee(W1QH@{IT+t9Dy1r(N$J!0&|^s7yMn=5t}4$`hXyO&i>P8LrXkGiF9GX2imxNFYucSVjqBcP4P zOTxMZ$U@vuQr%${gBIo3v+{+w{3>84m|%DwH$W3If4+s>08xG?*f5It$!p==XZcYk zubUfyh!O-qh;+oS5Q*3zCXWy!%Ti(_;D&+zqiT(9Yyx}U>f*E9qSoRiISVddOCr5z z2j;L=V%Gma#`bDYtNKu?>Z3>h^T(7PVx*eD&@Y4|EX8c!cAPG+Na3v}06Lh(PgRH7 zYv%ST)mKl0TmBxwOB$WBa-1GRbjYN|zwB&8EVb=gtE@ z3__S$zN-Y<8mgsO<|rtXs=#uyr6EBAo`7caQMS(3m&7$Y7qwc}C~LHLBcG{exP}sH z3z=x0*rtAsFM1&xRKnUj4*;PCIsLJP=I{W25)tfsotR)d=Z$9`> z`y7sz#&*dNgU9nJ$yr|v>f9wP@G=BiUJNojyx}`f`BG{6jk3}D9-8bvnYS^AhU&iH z!f%sDTg*TK>FYoI4dq12KSKy+t=4OwHTA(AJJU-pPjmzvEfp=3|AA~04u#|>84N?q z);y`KrtWfi?WGO2@jAY4oJ%=8{Lf`WERXm-LX9nDQmRY&`s#pu-fsPFHEB**|FL`d zbjwb86BG>psC-^9&iks%Ck4S5N$lKf&Ol(@=+mU1QuCbkL6Z}(o10N`#QnyB5@RN_ z0PMI3yQBYK=yu$JAo~Gyrs6XhjSQb;g7gs ziep+XDN>?)mh|BOq6K zuOhi0?TJ3|-Pz9v8M6;wpIN-3MS>%mOH4a(?8qxM4)6sotbbj~>P@zTHOlJSZSupl zPLLLSSTV}LklgwUcL`p8yuNgj*9DAaCT*0$^TuzTDt5xipq8YoIom1Gk3G&``B8)5_;gtI0~kT1{4`_|Pf zVlYGeBqkCgEr`UfC375gft?Q|ZD&bPnwxJ5%Le%tBa9i3hmzOIH(T)vI;B-s$LH*HT ziW+N+7Oz~}(fQofxKwURfo8IptBQt4nU5o1FddrXbqP@)oe^x8qOE?1U1O0z`?ol; zAkjm-yv_D|ZVG9J^%X}oA7q3O^kgji^g|hj`cAiMMj1p50!p-*>P@7n23(hC1#YMk zB}|dcfw6j2%qVp_q<@oI>;vYwza`>lrGpEq6OPYwC6EV~ z=KmpFOQ%0eoMZ`p-dl+}uTXLbNwm$F_LuzkUw={y+64H?08?F$E$R+27xfQs~Vle>i^woV>60-jx* z#)RF*bRafawwm~xioluc%QyDGB5a?|1NQHQOn2gTReuM!Ax;X(SKH&7k(o#e{1Nj< z;PC*Fe*EJg|1WLC5GdGQoB}#TW@XMYz(W*i%7-ir@Ij%MnOzYF>@31-54ML65=#kO4rk-zOW15T>f8}@qlHs0c)yNVJY&f!-sk-fMr1waLB-|z%d^cC>o@za9$ z&b7ddw(BU*4v>#?J3?x5+qn19i)WE=&fR$gI<^< zrwqt&TI`y0nR74EF!YI|qOh}q*9UMfI5P-HTy>se+Q~2~biI^saYqcSI_Aa>|DvwM ze6&Voxa(*UmJ0jdY>4>A|Av!ygK4eZry9_DV@fBCxG0VS&w_A-og)#Em*~j9cJ~1> zrz=>{V*cRxUXRUagi{l9^40~hVJ~he-4ex;r4|}&Fgo_f=zzWk;ehF5C?~}O>cCos zR4O=E#mNA&rasEKHINk?_5;vs%DQI@t<$wLSwxk55i2Ut<(aL5+dAM{6@`zyJ5f4} z7)R^Fm$rXkZc^u&K1V~JUZ4CP6v?3qUVKnq>uwE=s3MXl8m#*QhrqK+H)@jAmtVkx zvW5YGZmb@s8P;LrY{VYG;jLUBGu!LhXhITxT0c)X)*SPlUs}I>Ms)P6tO$Zl#V#F;g=wA@6Mu_g$^>1Oc}IimQen8cX~ZSMqy$Ne#ivBx0%n= z`JU2r)r;Ed@X!v9!|Z4WTWZ<)!>r0Ey9J0VGC^DQ^i3<p|L*=xP%{ zRDpBDHd+^S&^Qc`BcmhsY`eF#X6xn))R4Gn$-Aa?Ci1P1U51!D`DEa^WZH797JzWk z@KCRw(*N-)gaDPfGoxZFV*Ea%K}IM%;geI8@9|MRX>6Q@*)#cwuw#4XCny+-@?UQ$ z9<#dca@3@0=@>RfwhY;i6x=3{0n1vOiTZK%6rs}Ll(Kd^3~BKxJE4WhKg9)B*ezHS z9K5$2GqWaW8(MYeYbLLO2{BGo=mZN8aaoT}jEt4&aOb1Rf<^1`%k;OvB*76YJ8TPU zDJ@xzi-;tI)(bVHN`v`5OT@tFE!@zqw-w7IoS|x;Qw47av8sJ8o3)&l?ND9OylI=D zU~&H-ej(j;9K2>`1{(Yq+u5-M^~@pp2x0hFYm<1ZmDS<~_gkP<#>5vlt8Py?d-ClM^3d^l8 zk$G>?(Z28!etA2Jdu4%`wnrX!e%9Sh*2~(5~T(I_HltVoQ>2wS}U!eukdW zdS$o~!B@@01H+TN&A718R`febTJ_76XH9V> z8Y*`6RnzfRepyhn;G#@9rE%unUy7jr^8#3|{AOI|bBTI;OHah8aW5D(3wWro(19j=b{0?vbOA4PtjG*l@COYMkbz;*uL zVgD2bgoaPWq8(Zj?8OR5;2Mp#E9e%o63d(e)GZJuB9ZpzM+Vm8sutTtIqKS9J=#_(OqQ)vk&Ucw_82>D;ft_e4NTd_ed z>}AV0g}K;lIzVe(?d^ACK%@-6FMGY&2r`ZajHG}Ny!fNVC7t$H-DD6>c01Lv^dfm> zV?XM>e-jwMAb2jOwsetyZ7)RK!U0)Nnd`>1=fpzstzp}l3}6eghZi`RiYnRnu@5~p z^qi#WG+99623m#`RY^5_9hisM*;~H-Mr%IMF>eSa+ULS~)yL>;D3zMMk$JG;%IE#@ zx*%G)aqVC4q!@E6J872SoubaE)H)%Pby=G4QFN(1#7o68Z;h0H@jD-&J2*l|9to>< z4@L%5k)Z>-|+Lq>}4~uR&hqioGRDLsU%(>lxFTc$qtKP+1tL?|342SPsYpl~MR3prm z-)4B%%RmWXQ$+1YosVT_E=iIpivM6O@Ma>A1lribJ`3{Z+|0o{%{z$~t{Pv*$W z+!U>Aq+0j_n4L;E>BZFY*9rSs)5aJuoul8|Rn!@qqE(H0`=pr~!%Ec0eT@uMbsQ8& zjMRPad2O-Jj4T}QMZvIQ1zPp^mso@^hQgm!+~K{KYiPZ@rA!B;LsqZg6e z{0$vXZx&uxF^Ql34^NoToYt6q0TSqfzG8zOAtn{yciPfCd_%uL#VTb7*v35HFj>)N zXg&h+s>?kl@HRRX?{Vg?>aD6sjVmbNnxyoH_%ROyQV$V^SN>|Nf2R#9kp$>Y&u*kn zw@>n~Kh!}9yUmA9!I6LSX+NBMp>**gM}Md=W)Jmd20on+b=>#rMJc> zJNNiIbwV%$2euL=Q_}I{X*dE~!Wk-Wqf(e2wm;S?iK@hHp3Rg7nR;XpMAJy)>N#0` zJ+9-!TJPl&Cbs#(?n<=Cx2cu=#>n9M*aY*8$eq==`-IG;c?U%mrpHw=%ak8j6I@hC zOCBFHUF?XF3A4D9_T^RUz2qpl6`utajiJ-5-#br0Ak2t8_lpsOv(BGi`@E>V2SNS9 z?HnWiV~zw_>XR*}kh4L)M03 z-40#pcwKb_+>vT-j8jDZGIc0yOH+6kH&v9X8X=AjGOmp=`YvvCtpa>s#_k8viyM8& z0J<|mRFKQ-eRDRu&p^76UaJvq>f-s*pZ2Zziz98tP{Y_oEYNsTVhbvrMz4l8db>CBV+fGxPXCJWBXSVw$ zV+|P-lg!DtJzv%1U-c$7RTn$BBYK7^;e%s!H^tm zS;-SMdJFnP<~Rx$ya2Rso#jlY_=jj#yoeE=j=<#IS^$sAA#T2D2 zRII>Eq#}j=VHA2J9l!u0i{Ot%^LcS(W&}nk2s|Cm{)nUZ0Zt@+0h+a7YDg2Guire7 zCN}uI|4@gqcyotMs&u>i?V4L<_4i7-t6+1mfIZp%3nw?&2Q615{>D6805)`J;|3f> zypRkpF`bDe!mOt44@uVeHs<%L#6NF>5MJ}N(OreDBauk*zK zuom{T9L^dMV}@xljnRAQpuE1V8q~Z{x8;FhKIT8qyEG(wDnq z(e=Q^{^Mj}kgE*16VY3s#drya3QP>BXY|5d5^iz@lQatCicCe>E#o3m!I9}+$=A+* zL(ck+Q{f)Ta!yH>C%45OdgW4#=ppix)>^a@%b-ty(`Tw-g~)NTG*zdzX9jnLfA-?u zozAS8bf*w{t2CXEgOoRPX*&rHvlW4aTjaft@`r5?~0|HBsb^ z>*P%d%#Rc}xHBG?vTCYWOX7O(^I^)Q&7!uqn%Kl%KJ4v=>o%SLAw47ZPjloPb zq{RwGQ_l+}yX(90Sfkdc7owUhQ3v zW%NK{PI<$j&y~2HFW*^2cOcH(o8Y1+-aQ)M16s-!N=9DcfhK!P_%E&2GL9)SP|~Vw zDeB``6hamZq^1WLunN`Q`82y5-TOS1K@a-^)Lc|H7 zYWkyZo!A$q5P>Y-c%{PDAAZr6Cj~s}WOK;fL!NdQm?-dRTSossd{K3_ko1z0W-J)8 z^d?roaA7bFAk%Y_rPHk36aouH)I%{7gY+Z`Mr1S`uoTE)Tju>if0X_^ouMJlFVa1s zuZ)Sf_9qJ;jd1Y-#Xd{-SNcnPs%^v>Ip;kE;cToS?u#hS4FHZQvCM`fEEBC}GEreC zkJ;+f-~@;f<6G&#YnV2nmFSh;^rjD>l_3f5WAGi=6Qv{%PEU6at2QUpGZh}L`xW zKOB@Jis)*q;U02mDHs{$!7e-~gJMjPyn(W)uJ+SQu~KcQeR%cqvAh?Yg=^Z?Rfs|R z=g;fh9|s^1bhrQQx+Y%8DR~R)^HYIz z5yo|dK_S`>?;7pmYWo~5C9j}rMYAs{Zj~AsqV+FROX>*&+zml4e2BL}%hhzX&;P~3 zIem92P>eGpsTJp!pttH;jXdw7pXAx%AP5u>7F&=8hHdzE-5rrq zIj$T8fmkMpe$pc$0H8`@Ph3@UL%WN3AQ>*zRj~aX!lSz?)aGZejlr`XOHmdJnsauF zj`m#v7J>rb`q&F%AO!r7_uo2!%}Yrdvy)-k2fy#V7sN0zEU?!}fiGk2 zZSmWSJw^UpROA{E)$TWktB3hvF>07H79VL!Ig)dNvcU5h9>ZE4tS(9i*>6tTsG z@(e)Q#5lxZH2OFr0tL(-kMOk?lBK=nxJ{i&K3O9~nfRZ;_TS9a3q9Vv!p;>^sZVds zklm&g(&D{LN{k=01+Uo!td>6;dEr%oGXa1_OCN1RXfC9^SqeOm4Vov*OvP`Hx|+ko zDfTS8D#bLUkaAuJmNP5XjFEdzl7|kCQb_`Cp-9lg&?eAanltWlhSH+&H(k7&kVG(*GuoulR%d=uDr&-%{+>_sJfbAEb5a#Mu!E}bq@RMm^)f~b z49w&+2AUs@k&Wl*FU*F2=>hsbk5cM(DoKKkhuBKJWXn5gunXcV`&0pWx!S?WWlOJ4 zVZ}qyP2J~a)_;6>Ba;^Nm#XocPV)Q@z=y@SGILV5g~q!1#B_&5P!jT=Z^t0)bIhyn zf1_XN&-Hk8L!FlM+xe}JXj{}RzvNJCuiN3HO{hWN@~bd%Z4nV*4JEXas0KR&;9-V- zC8Dl?d2`=0D5&vY(vkD*bC9+bjhD~|tr}p z(xg8nfam48rdlId#WH;R4>xAzfEN?vs+qS>(Ry$GZzGSKt?5YNcAcn()0gUFS*V?F z(6s4O{o7}nV6yuUmUOJ?`N z!~CGoZGpdnL;fI+W^Tc0;8Hc51i8)!ai$Pe4shKXGswLum+RmTJP2>{qGO5Sd2Uu| zV}!VHMM6qNr3&%#4F}852%VCg1U^^NHrkSalaj$~g+uV-l;RyacLC^NN4D{K#)RmI z5{~zq+Qv@77(@YljyG*qOV(KXy&ivQ!{Pd(j#qG;sjlXl*m7bYHyHq_S}1VsjAvA) zj3z=1&J^h$eq^lrL0XXsJ4pQ=oMx&y9)K)+t#(6Q>GO>i44SRv>Ab_~2y=zBvu2W9 zD1kF5S1STb&SYaaJ$y7i3g?%aU#@S&SreKqlKu-#_y|xv0ReH9it3Yi18XlOexFrM zP>6>K5PU*9HJn?Q(g`c;on{XXF*4f|CKv?r z`Iebmws>c}WqZQCRtq zyMNld2khwMZcl7rXHENv+F(pE+5!-Xl6K@PgJfEu%nO5*OIHrl;>fcjzI86Yrz??t zLvReAGI^M@A5BT|(mmAC&Kx!V%#<=2X>MPjC86sG=aQmC&$=1um_olsquL$Qb5sxV)?&`7D z@+GhJJ4U0)ny1LaPBhgVAe|qgo5qM;f?2qd0gAS zcyH$Zr;JgNp&Kt8n<$V29zMhX>iD&^N~)pftgzL7H_RA{An0e?5X=8A_#XgC^n+mm zK8M{#bbxEA)C(YOH3q%9)(Zwz>QhJ6S2q_I8wkj;Fms%k*GB|i(eyvIV?ZEQzRX%I%LZ{X{>Hk7Qiu6 zi&7DQ3#5=c{tr$uv-G+M5pDg9?1PVfr+3~EVx4)MD-!Hr3)@0}IN=3>Orc>alKc^l zl8j+ZjeBnNNG}?zn{}qTZ&I4<3wy%K-f?Qa_e=#(-Q~CAJaHC?DP<7v0bQj{V?jqt zQ1&LCgd}fU@pwxtRM`??j);+qNMjkc#x+Jawg$}c+=%&#s13XzX4`o8ECve zrL5Nw=*|n6t6?H+P_gN_{W@TEKlOE8NF624F-4k{2&zpSaCQBByhxCv_44ds&0v8~ z4bYP7zsymsEQf!;OCYySoS6^MEy5QhKo(NPFQ2sKp zsNE+#`y#REQCy-~Qm}-A4A!I)M&;P^)ZK2s-8`n)%`#im^$d4(^ z?`2H|H-#O)>3^n*;WNVDZPiDu&_2r^dR{Rabmh9sp;w|Z1bMF^!B4awt`DX9aQ`$1AV)XW+51+{J#=Z0*y*M8>XmJWBy1YlWzVP4Mlg6 zqqQp9B?sBO+zyWuUR5!1fF`Uv_(26|*qy@rZ*oCX-RAI4Amx-9^(2v+a=}X4B8V0X zey5hB*?H8DL-`+6Cd!jaA__EESM*r0l9a3XQh14fF?&3@Y4e4lsYGVo_UrTRgr@Bx3LB=x~JXTfcunj~L4TZu6eo@r$Sk z8M#eTyl&LN8+GMZhbSDWCqHI;oZa5`@DwK3m2*dq6Qax_4|Fc(_4Dfu)bmfkQ}**G zC1&)x{JUK_oZhYKtMyd6>(c`dA~;v0T>O6lKem6jn|R`-TQDUAm=)qt8x2kxioeH? zoo#17@#z$e4{&eT^=@1B9bPP# z;CC&^9uTt7k9Cw}?hPdHp*|3)^wo#-5llc^3YLk#N_D+70UYxH+BxeD}1K+f(Xtq$83+-geEv!2A~QO$Yp(j6$0}+2}bJ^>Fel<-!;w>m}_kRfgQVNX59V zk{#%6Y2*3lUta4^=R+&8@|7m=poxdw9t%Bff#7Xj!z{R4DvkA$8+oZLi$uM8>-hAo z7OalGLdz9VJc0ttFNw4-KOw;O$Y0)+{B%Q+&qIwqw8K;UDtcmQ2>l_J>+|rp(jNo~ zOFD4sP*?`GZ@FhTwYbRr?iZk1OMBsBU*so<(I^J)zx?7te_Hp{3}>-%*nOg-N@k*N zb`0z}!!vk0zR%yj%nOo=j;!Ohr1UUfzDXsh>Jof=j+IOY8gj2=Hq~MmdEg<{M6lX0 z(TnTO6@=0mQQ$h;60bx_D)vYwj%`X;diN=IpAY}~f#0`S1a2+WKouui+L>b8peXNT zih_fUo4{8FyR1^JgN46u$L1@?N--V7$52$Nu_FoJ6S7y&i8cB)>=@ z=>4pneSCW9WNOv|yWyC75#lfG+eBGWOWh}z0eh`w*Z&w+9EGf!Y0%}2QUKtusZJS4G|I zMi&bnO4yj;cwB^F-})Wb{)r+OG=96i?eN?1sgX@vQ_B9W9s}{v(;oO8VuPWb&yP^^ zRQFD!O73RgdRMZDU4KK|l--W6vdW*{|J7y{6JL4H=$|}BPwm(p?Xwci#sjD{wr&O( zdz>r$eVG20!}qP>>&w9JtdMK`63l_2cFY1UGi4w=C+4+>9joIqj@a@;yl{|3I`pXS zh;DrlMulJDKdWpwz)PTPVx)I4ctT~c9fz;jFW!HXO}tv_8) z!psVjD6xhW>>TJM&gHO6C9~vKPWArwt^zwwb*Jd4zLdn%;pedQT>Oo#*}UUD>nQUn zkHo|l!$a+}CT1a-f%;Ue7pB5bBc?Oad*ffVkacDIVy~^d10Qk7+54XxpjL@pMnpu%=)4-Y+#-$&o2?yC>oyXjKSUl^0MQ_2s=;3d-Z7~h3w-~H{ z<`NK$xqI9Hn}lXfBtG)rQXE*!5frZD;Ko|^ZsITV{WnruvI;qNzfPwlWOABVL{g3= z2&}zAHFy{O;n5Izu!!|csc|8W7OOx5r>sCol6|xz-%Xmmelfsd_lf#III72){DX;m ze2rhf98zAneA6Ko(ra>^t}HJKHCyi5>DaB&fclt;`6V)PEaZdeB9Z8v`(JUE&z%cY z>j}iTlm^es52NmY|J*{s82$YO#>RZLwddd4EB2mkEmkx5u`f@=$KtHNC0_R`HV}(G z##b(RvoFuxHC9=`|DE4VYKjjt^ri*w-VfC6?`u+>3_ZTszU!+kk9h~&pPBQWo{~MN z!s%5Ww0llrk)rUdfmCdMc0#+cM%kwO0b4CfW%hLn@GXkn4O~>V4J8gINf-qR@W`hk zr<)M-HqNFG&MZj3z5CBAZR}&8D(|>I5DPe1Z{CJAEmVhYEQfE3#U#O&>~LFHz<@Pa zhj(CspSP;;-Ur=%Q_WYiN_IW0YlgP(?aTLxNcphOKv>{toUq?~ss~%+rq;4sDR^$i zUyE*0%NAe8DC|(K4g7(P1lMuU$5Qeb> zVFeBPY_z75>&8YEs7PNbEt^+m3Ili4!lBP7v4=N1&kc2XRshG0(=i=i?`t^Ax}F2)&2$ z|9JskWxP?%_qbtaw*GWq^JJSb;Oq0G=U08Jh$l#X;>7s8YHGU5K>4EC)={E6viJF3 z2ZK_`xR=Z{-%HsvqlHngQ(#76(i$pu3(V)(imNq?OkzvAp4RfZ8a4Rgxla@E135GS zUP$lQM3T~fTx#?4)mPvSCy~8X0eJ5y(bjtNBvekEf_o6&K<_X@Ao?Na?0>JEU5Rro zw&n_wL;*3ulG0R(A|LpFh98|QuN0_O)=*air zBY&Vz3({#&rZq;ANc%gpl;{7Y|7XFj5OEy>^fA3a^GvC~9)rK|+2xZP^7FK?E|^;& zcnybk`%H9NnftQh3;*NlB~osaAqvK_R&@4ucWk7}AO=!@Dm_MaHz%GaMyl$Zsj2-P z46Xn%VBsGavnq8tKVA z&*pgK*yWH&F)sARIum)0F*u+y&NU@QBr}1B9L+!P`4Ei;FhySoIR}6%=)wL|FhNe+ z3s2i7?ObgU90o|+&GlV*lv9X?#1KOx)9r@Qi*uvKCcF)UdD7ts$+=sTMlJDu4U}ih zv`I76>By4#5SNk^I7_os$@db0@qKRyEUkQ4-|9$Z20bb8yzt}2ZFFX9KBWuwPU40= zq9y1x`F1GRh$Fsqmg|%khziOXHE}E(?eFT;2d&M{*M3i3ko8Ez>GJh~Zg=GOkH5cd zk<{uP5yY&~3Ln6yfVILn4+K2mvH|Pw`H3+Mf_JNXx)Czs%qlR`n`JqIh(9_4|XtxivmqXORn^qc5Th?j?q zqz~63tpHo&3>V=gT?cE%8;k$^`ypw;jj*^dH$}qeXiZ zmMkL%wj$;?>g3dwg*@ruTMthRq1}-)Vf_U30|E>*CDZuwEjPZXMr9WA#y0hsFB`X+ z$aYR%Mqc5Wk5_xhk2G5^)rgx0Uh|&e)aj8f-}(|#13cJWvZE~j2a;q`m1p$!&80(4 zwIK|(r8EgzjIcaud*hH6)jkmW_7PYbeO%B!>rBasJ$l1$Eq=4A-_Yv(!%G(6#JCo} zU5IAZlOdPYk8;PsjC@$b%e)=A-us;1mYYJ^`GDQP%{=S7em_wn8~x(IzouQukXuEW z5PrBg0yP5P0$jQZoTO<5^lke>5-Qeo`D`+2t{1(i%|$ItFm|5I*}q<=V34{jkUn2V z_pM)N0w zErLrrJ}M(n;r~YOcTiD|rAZh5a=PW|Eo3fqOiY7nxyZm>eD7;yD(41vh{xeD- zMd`Qo6~(({8w(5&;T-zJuNgT6`o$GXgnM$6HiGka2)Cd|d6LJJ9M|2sx$B%?eH7zT zq_E=_Ax-Z9g-Y42XSmkhl}H=nJN!;DEPM5-M)tOK z@^~ChuxC$rX<_Bb67^7swvIUlKcN?`pTfX znxyKySqCi1lJJU-Q6v?1Sd!c?hxEv0>Rx5?yh$~?^m~qpQ)lUd+1rcq&q<3 zJom+`G4G3H_jh?g>yn}E{`+_-bHg~GeqwNo91xzE#UTOz8h^}-U(lkK*rLE#x^|y} zPx<8MGPoiBsRAj@W?Ba?G}-*{1VNdIpZh{<_parQ3vO`l7+X=)RH2tqlg>(`_0G`m zFaT>jd37&oH0dS|l9bg`$`Q5T`-u|{|c zPZ%;zSR%gP3x$?v?)S27GWA?+FbsrKKUnIG6+We$()5hn-=|pIX!315QVR%?D%xaf zyI6@P3xP!mlz;Pclcj%KMzsi*j=_wZ;7PrDhopjz{MNvIB8HW@;5?&(HRC6as;~Aw z_(jP1(k+r(%IEljhovyb*{yJ@9mhPCeFv&5XxiL@U-_pl-a zgeNkzY^Rl!x`UMN0u!c=qs#Ad2M7O>1!Zv()hGC0`fGwL^pzr%ei(Li`Mh4mUF_-w z!UiQIT^$IikAC1OuRd`wWkmB8>C#lSr!v+h<9`#Pu;N4%NYV9Z*B19Af3j#! zpve7N)YfA~>uWfHnR@^7cg5IBa!xtTA1L(iD0Iw*1Ib~X6LW>xH2fJm0ey>UBCTf0 z(`yoB*Yv4ghdNOD1vjY#0tPC(P@E|=^fO3@D0b%dp+scovCQQgca>OlP$5q-vUmw_ zvYqD}qA(Azuq)83^p=Q~=D<|Y_ejv%Ms;ToHjZVY08BR*cZq}Sb( z7^Q|3$slNaSED#pSmPQDAovv+!zF_|aVN?5FE*G$0BEynO{($mSf9$`6`RD=BZ_ON zW){6`Pnv`toB{n|h^j8^PQdenw2bjs{m(T@JLm%;#<-JrtYn-RMwZ#79}RV&};CzvW-WyaPg2jF^hw-j}# zj0h%^rmAj2G6&Z_DXVGI{B0E=sOLRRj<_JNPk@GW)=!d0>T46x-X7qxx zTG{EVUM%6-!c)B?Bn3-er!v2Yg_isOjo%H_#3c4pO;z7EcVhrotF^LNLb$X6)7 zpa;&vKjRXkrq@t~uh#S3ShD$rFcn@c(S4SlfHHlCP>EYDy(*sdRN=2APpVy1T_Faz zPF^l9y(m)**TSeXVptC2`iLe}=UllNr!Kyd$K{b-%D*s`Z^t7YeoZr;+t_~ZQX_RY zb#hs7)|08f@Bw?wtMp!%ZY7Z8FFYf0zaQzr)Dm8k`)Uqn&c>@f;BF;3f{HFw?$|l}-{AN}m+}Q51+sCJQI$*#Ce5uyA`xvx zyehx>tl3+vYL<*1_EqB^#fYX}DTqdagKnt~2O)#5>ymlkx-8uF{aFOz!8ziCP3yy1+y}vU?N5PDB~Urrz2pc$lqy!{vDH z(ys|_;R9~=deRcEk-bTc-QKK8HA(YXX2nUNFFDMP$Mo~}G@s9TT=+A?7GAxIksV7o zdQwpbg3aOh6g?B%P3cqpiojpZLi$YFAX;*J+wn+Rv3dK-O%P#(LY2y79h4BhVv!Q3 z_P%e*WHtx)ySEU(MSg0XJ(|WgX!*Y72_IqX#_Ddt+wdr!S~=9|0mtV>PPJJCe;3D!zcUoV_MQLxjV0<`ay%}6dYjE$vCPSO_YfCuqZtSX{Q&&OgKW~Ys7;=q)|#H8(KP*r3w@P)>_ zff+Op1#f=m4^^wdFaPqe!fQ9~16kSbB(=_oaHI2B&HQPeMQA*)=-zMX;#NGPo&oJL zT9TAOZd5LQN%%FYhpJMq4(;KAsh*=A7CQg%r9Io2dJKYyO5H zTWHukAFsXp^6|1`IS_X*R$ z88crn@W+07=Cd1rE_|vbR6+YQ)K1TkgoXj8j9`TFS8=!-^or8xBaGbqSAB$N-CXR3 zh=)XiOOP$5zI*41eA!2a(%TpuYAv<*BEgEzkktH?j3nY)4xvb(FgM5An5S*FXd7-N zBJxV8EaQqq!#kFLUvM$1gr5T!cKq`o_V0<%9upQv?W=Hrj+5BN$4vl!>800`+#q{k z<-oWY@t;?*X8b-aTHTK9#3#@72Mub-QJ1S;cb z92FuMm`(8tO|M0RDwOW247hX!-Cu2qvX(sCPXn6R%|p3};)#!;h8yX}>PqU_T6U;o zgzwlZJLXs`xITGyY836Fx^m9Jg_45j;)&a#Q9Hz$dUC(%h=y}+Ff1V96NU%;>RRCv#A$5R#{?hAX z@onjTeRJFGg4)0#z^gJgl@t2I3*zI!pDC~N#PD_E5Aw%t&EKZw0_y2SQjZ<64Wjoc zgW==?r#zMVENt#o(hbd99x^4|2AGn!u14vLy2=~E^ewxPmxW7N>2@l6%E3;HM#l6{9bX{2k#SA8pNxxYSPD^^R?vwx<}VG)97pQDjFG3qWi z>>Q2XP=(bN+m=1DL?V6|)hGmSXHgW~E2&<(Yz?eN$FtiuLOoItuzE76f7+L6BJc6B zedLkIq(W)1)BUTQNUnZzm z%~b1ceXje{3dz6rPGMKiwk=!VJ%jlf_HUzzZsQWPN|IW#1={e!xXF#7LpkjewY9$) zP=ih^3Th~37QIaB6#uCGlxls80y@YydmG>q_x&xo)HmdQEEcv~Z}YA0zpzcc8cvs6 zS7-FEb$`j%lD4G;dZ`;6oTimRc|sDUty-?$52kqHXF=@VZcCW=Y3%)dBfIszp?M4V ztKz?+j{&Y6=BuRkV?P2=bDK%Ug#JKvKOZ>`wezQH9Hbyqg*Qo8sRwPRvyLWD_>3|W zG1d+>tYlW>?5wyCFsV^`kY=Hg;9lO(;ssq) zq_mIfWSu`y0pmvaerUO6LksQ48mP03RD0ia;%q&EbpNW=BC5GNoVj2HfxvtWN!g%ZGjccxhPkv~~_H8JA8`-j94+)O#V6ln~Be&e0WB$DM}qL?{>+ zfsCQVtN~*e_?a=}42{3;<0p5Kf>ho5R};NKg{cbzFqTuLQW{+sNTY)BO#Oo4F&ux`L+Rb zMe5ly`s^~QfW&mLXM3MB@cF!ne#IQ1%7O^v*>;OOX&-Mhks@43yB%-3FCz1YhlvdP zUq^ndO&0=Scc+{0n1GRN;2y5cD6;3(=`dHJ>|moAl4XZkmJ z3l}<};rAv6=V?4c`d>7yUh+OW2;s>!_!W(R1)nS_wq_6FzIO z0qtmu8#i+0XyJzZk}_Tn2|TiSG@>q394X*8K1$KM{Tk50 zelD4}Fk0W9E-zb1=tZffv!mAB@|nQN;ZSW1$8voO!}6Nkcy$IE@~XmkGC6*VxHcyi zCVKr6TFjFpt`GqAu(Mta`#+eAm@JZ@OeuR5VU{_$yPk*?Qq=YNX2irRVl+lV#Mzno8 zw3I5ee+}b0aF34F_kLQv?~6A+UCVj9t>QChNru>q3rAd1=gk5a(?so^hd5Cr(%%wi ziThJ@tnE7jUy87?RwIgJ6N?R)Z-HM}_%&$Y}D5{X_U$DJyE|knz$wvEM3#(K+$cCx>ah04{R0YO$ zFtO)kc)PcH`gEbDcz)O33(z%oathypQ_LLbaBgv^=>}c>aU@O#*OWkF-1hX40>vGTb+Li+(7H!6*hX$Fnc}G<;j_E@m`~%{WFn{zhSZ$ z63t_dVbfOMztuDT?YLVkof@-OEDv2|K+O34qV;0ONBDZ!QvG%bt(VwTgC!8w@?%KE z?&-5EC=$!+!5r~F#hu}On-R}Mq_VGv1Lpt`a4z6&D&KRk6d^K(>JsU~lbIfqiD|S5 z1iYkVZvl9F?ulg5SsLX2z1MJ)bRdj^U=7P}OR8C9dSqL>Cr{?9busedYHBMwCBW-k zVZ52b_m2t0($IsVjcRyZ4uyrU4_pq)ks|La>h7{ACUSQ|E2SgC(VTRuY4~$`4g-po zT(|@KJyNh<)b{UHsK{zT?10L?Cv)38Uw6mJo_ghN8gJ58SuhJmGyyK{k_?XBdVnon z8WF#T^Q|%Ott_aSBSyU_PV`w2%D)QUu_Ms(AP0C~M9#v!o!=DT=4d}|oo+A!yRpvF zhV(_$>tpZWpl$h}L-Qj4(M~ou0YJ6~6~6*Okd>asmpFC8v@^Gr%$*UJE?QRAHYLtV zjh0d9AHsQE)a%rMXbVrfreb9llg880^B=jQ2pZ?kaVcG3p$E;La8%Ozv0TSvt_9cE z#B7eY;g5)CWI(>1_NQ9trVIu<>mGfoO0;$}-4}p6Fn?FI)amK>lYo`NNt}-PN)91k zz@Y*h*Z9>e1QN}rJl|gf>1rHun0ovSA^{y}|K-|A#0xwFs}FcoxW4C>1e)6L(?2UC z+Xk^dOAq6KH1Te83X{*J6GCJmJWa9OZgZB#$=-HzoG{AB&vrAIxTlCmlR%<=I87!xNFEyI3LnJlU*7G|EZx z66%P;^hi?-H2UC-hnaGtu}iB9d1^u)QCw;)0+r%&EUIOnn8g4W$g9l1_RxtU&-!kR zH9PY`uwCha;{R+&Qy_`o=wHrkAeEdbLhmN9v8_F-wVy6~uOfST@>~0TQhE)jA{&^5 zot!wysX1>Q5NZ#s8fk&@OHE`=Iz^q{V{f^I>?NgQis%#h75x-NIZ!a_?W07(^9SZs zKO;V)_ot6wEE2L`8WwvdsIe#)s7j2VfG>GG`M3cF357n%g5HAfzH}b;%zlZ1gy7N* zp>c=Fkn(dJ*9l>=S6p)7)h9hM%*eQi)hXZO|)AdW4Jlk<+oVcIx=XV=Q45pm@2R??nT{`h5AvyiIJ_=H zfSJrgDPwk`cB2Pp((EYnAD+STGq(}xpY9c_2qGI_izlTXGE{dylQ*1w1GqBX68JfH zDA7M#i-806Szc7k6PJL1vO~S{$!U5wDWU9g2wUje-5Y-BJ*n_R5OQ~bty^`;(PI|0 zIF8bcrDe!415<9r9Yzy|OB(9LmV(#*UC)lTawHyKKVf$^&7}?O+8jgZa#7I+7&|5` zYY6i;?Di_AEVp%b*yIj|&7cYiWeRHsmxiF+R20n>oZBUqLerYpGwBkd-Ba+UIu2!-b#dy0)%(AYqAsd393VR_5WJ?EUiR-KaO$kY zaRB()CK*oy4Dp&&DDs4ZVWT%*_#|cBTxB3*tTyAr>1rQ9sx*_fnNn@3vc6@?D&9mUHh#t3^#+3l(Y_U&Ld@9)w(FQWulg2(9 zo0fyrkq`xzDHq6}xHDLv^`Pc_x=CWY(hHgl1(dk~SE(5gIwtxCpS&_F_@C>y^84=) zE6P2y<>I=gS)9N^7l8+I!*0c`qYr;AK~W3to@#!)IC@tY*2!YZ!#bHEK{ z1Se_slPEV?s)G=cOx)>O#|o;Fn3VrCSKQ(9n$KS`m8QF&oJUc&kzZP`HfHB7Su|wH z{8@q>o=GlTFzUL2yBe62{*4E%^CFzpWV# zUhD_zzKPOA_(`*XvyZ2Es~I9XdSkf-vW2i&`HpE9{hJ3H?bBDCkhIV)jM+UTs>nzt zZ$A?a)15iiiRH4s$Ukp8-kxx<@4uKKp?gS|4kW1}t??|Vr2Xf3>9Rc&v1bDB7h9a_ z)e~NDuWA{C%`b4ay5G63ti{_H^R#3WOXUog?h@QYm~RG~2i1rAIeNv4tL`dq6Xn8U zyt8OJL{p+m?d{yQ|MhHDnX;nY(D)d+kgU4}e)1lLAu|fh0J#nHHAaU{vQC$mU;uF@ zbu+DDOy$#u{TzfJ_NHEqi9%STJafyktke%{D~Ek~D0D4>uikVU&!h73G@luDLVPpO zYXd*W+2te3|9>w);M0ZUwt+9({KY% zC2-|euz!e>E>O$WUTho=#ZMgq1KB-jTQA~QbLd&Fd&~N2!wMlx1WKgSlBA4vDC1ht zaJNQ8c^q!Xor_h1|0#L-ouxs#wJ^;r}Ny$$k;ckS7*3h?LO>3Py9(I-ts>+ zt;a(v+y75}&kwxl4M1*ZMDE~U$kJycJ))%D<*M2@X;ZG@I>KC808-yc_kgwP@sJ9K zkx}F^l&!t?rBkw&IarlWybPQXc_V!;+TXTA zo%BElpKBBLnvNO=-m4|+uhK(7_R3^K2~0{O5EyZX>M+|=&6D2Nq(3TRce&h4^4A!I zb})Dt*|O1)GTn1Zl;Ncm6d{DwgFHu|^0JTxebJw{S~?i$T9@hVhTOWU5xmsa8F=Ip zf}gq8rodIZlWgt_Me8CGDq3so1@8^<(ZetN{V}+OQB5vW#%w`*x(>#Z%d8F%dEf81wC?k0t@4d@ z63=%v$+>&WtVtpdp!-h(hZ*4~zI<}KmqmE?fy&h`XlBM9#!hMg42`eLb)KV z3;f@?r@ToHfQ6M2;ldN(-7iZhRFOo%@xOJUs)1BD6zL_@0qB`ssZc(*UKXz!&VeyS zH>3+tX>MDgyAMD0wSRgvUFJw(%mN!XWK4VNB)8#xKs(du_ zI=GrS!sz2d==|Fn+V+QCn%^7vg{8Puv?dOCuBN-TdTgrTrLik7fGZ4R zyJ8CN%mNS!HUE3i)5ZbAlJ+}7!?O%^&1)}e!8sM0q=L1 ziYj1Tpk%T}Qxk(zGA-^TLa943?k6v&OY?tGdwG=e$Ml?LE(SK^Ks}&;ng)eJv;Dwo zp`4^0^=c?n;)SRAsaVSFwLl=CJd0QxI0Df%&@n0V=Ea_rQBgZIQKNv6e z;cE@Y9y4L0G{=#4iI4l5K)??Emo zQ;7yDYXYwOjO|-nV0(Q2hxJj^9RNLl2fJkRw$|M;fPUk;^1ntCvURe%JQ)oBkM49W z^QZ1ZRzur1Hf92J#-DN6RBuwVi{Cr05T-3>CmPd3tK{;&Ktn&t{>(`6NjH&5%aARh zi~iq>9gWw;9~LYjV7Gpap|LL>@bIK;x-tM;JYnq*j2{_WN@iiZa_l zEK}eWy*Fq?0MK%gr`;rr*+e1eB* z&j|dP36wUtj}r|}QrHXSv!Aq@B^#58_&&6yWse)X`XS7k)=qd+VsH-4rA1F@lw=a7 za?IHV(cjHIJ;*M8QKjW?^1H|foa~=2TQymG-i#o9R2hRQ2p+$ipNduvrD-Xa^Ss;k zf>Nl=`b+>yVB!7IUF*xR`3hO(tw>JikPxb6B_DISDPVJny$2L$m zCR`T869REkCG>)iz))7A6dZbiXY!C3>paKQFZQ~H3kZZ>d*YTEP%6`{1tj{f^BCiSY{D=i;0$efC%sUoYsWbbeK;lUfBj;4!Y&lZ2_j_O&UdfP>m zp+ngE_kQTQ&P{QVz($5}=Y;)6{d?Ysn@mGX>=tHr5i@h)#!9pxqAPtXcM}HyQ;6dw zBX@HCZN>us0X+ z8>a3Vpf z)RTAeAly1tSD(${WF3|MLuNZmEdHO7X>}iJjYGB?5PB~g8G36;zk^^!8Pa>P3V{*B zN72l|LVYgl>nMz$psHmRju~Q(0ClGIZ;5zdH!;wF{UAZoapcG>!0CycHziOCfqG_6 zH<_6-DIJ2}Ne%YTk=yqnP5gJo?TQwz2O8~U33bBc)YhT%2Qt0NyFy`{8W1}7rKb868%@c@Vi$?Da@G9iR?M_Na$AQv zIY)q^lT);mf9#V*OSG?Ugc>E6F~2`u*pN& z(-kJ7g(0SpXtqEmqb|X?w9PWbF|QCeBcO}SrAFjAggKZ^au_ou7*GuqA^3WOg7K`h z`qW3EIeYvxa5(Dd!zD+_xY+~?KGM1qncjUNhK=b_S9t#|Tv>_b=DychAfDPQPJBhI zjx;D<;BCD!?b)Hhct4kWn@K|grW;^>G}WN1&AUF9<%1(44d^u+?F!>qp0k7C9rBi& z_kLV>)0>4z1FXs)qiM1lAH{bwyh3y34K zgeMk{c*yfdVST?lxzs7QDYC8}%-6%5DWq53d(+WkKV4oijq2CM+;6l+nS#)6_LnTo zKOuw9iC@HxQds8wSE}tRi6hY~~+X!&Tq9ZTdcO?^K zujpb5mD@G^0k?4t<@DfBD2&Xyeq0V)++8DS!+g z?|t#)onfO~x~?TkQS{f*1oxh10X0D#zUm9*odV-^X{0JskKb3X)V5C-3IL`O8L)Ca zA@78fPx@-73K$p><#g#9*4-+#hx+QNbLDT~sNmy=GX7qb+A5?(BV5@n@60#k{hYQ~ zw;|0Z(Uh3R+PIBRhNsIN=PFIumoK!4Nd=-2Q&8P}q+aU6U z#%h9U1;L`=P;3m!f{akN<{kp z#1Z2TwnlBPZVm0T4kFA7r@G{$iTM|!W7!IOolDTg@C&4i?Me>9km;%I4@K4OS3o_( zN^|nk*^I4lcdzS^omlug-RwVxI zj-gFPH1d4=$lVPGUnsI!!s@W$#)^jP;R= zS}`(Nw_cQp*m*ynQBD+_zd!oo^zT|*K7VVHn#13SdeaK}t#&?r;f9WXd6{Jf$_?jy zK;I!JUyeR48%P+dh3tH*#{>QNmWLF%`Zc;5-E6qqXj{PEHHDM<^Ko9uGmv=*!3G+Yep{*AKH1 z3=TejU$x+V&XJ53x7uqqVA_*)nPJBj1`kZ~7X{VN!WODT17ays_hH}Ug>3;R`bZO0 z#ew$>Nt8ji`Vg!O?wZx8*J5KS%Ky z{R!GK0q{h%2L8tK-DHt&N|JI6v#5b11y!rUuo7!;|5zn4Ie4r+8xPIgODnv)T@n$N z|0lRNSVqi0&$^!RF$Trvm4*VcJinWjwifvv))lcA?;nf5Y@;{4|9Q`wdO*|>ux|iB z1hCVY`;Zi^^?tK7SsCg5E8t0F#8~wE+`f2YFwi(ER70Ze+Pv)~)$x!Hefxog^hozX#SD_tAbA{H$|ku-nuA-H9HyNTm+ zd7nTG9f^kQ*T&vZ+a_J!7H5WuPDuD%2Y*8g#2_;wEs{!vHM4|T>fM5a>rVf=r>r2D zNWcwFHq5dfhOsJ0NkcZO`{_%|RqR8I3EHYhQ&N8$fAJVvjc2j;b}yB_VQcMd3 z(1Og*?L|o;y5D7-@CxcbTS&s|(3J&+Qc$&-^{HW4#%b(~n+EK@kstvk$jIE@g52IJ ze5wIC5U#kfoD&Umu+`7<8z)u+&7QSieTkb45yufIcx+6UDP;GioL@5y)to#~{ANn< z{aKr?BZ{$Ln9W3z?}S?JIA>IFs7VCKV%&oyynp>ibA!D}QD>3YF)|B(-XJV(mX>N9 znn(Q#4yBPbJKl1!<+qCQ1FWV6HCF{d5CBw0{6odz&{i1Yl}m~d>}ArPA$Ounqc_bM z8Xdrrfn(KO9<+ab8Ccl0vrW2NxGD3D+UjZue3)dz>^yf!2t74M)06u}Z|`3j|4a2G zM^f+H<-}9xA4xkUHV5UXe(f01p}wDJgzq@K%2RcjcVaxJI8XhjKlm)SeP4A9X6BQ0-lkp$&W7=_3b8vSBiKcQAi4n*L22tC`ew779IaB>1K!4e14nFh$7`aWQfw9o) zkob*@p}`$^>r6M5uVpqeWujS(e2%~e9%T+@8Vhge173jd~mg+BUwlFuI{1tN)+x9#U=HF#V&eY zT5xnO-}=H{o|5Aoazsm@{$v6pj9q3?S96xSg*v6N0Z4ex&llq~o}R_rd)Fg4PGrcB zYf-UcezM;B63aUO5B+uPLa|^!cyV*`{S)o%y>xd_!ClBLrAmpzs^ln(v@fDRi-hf; z+h?g#z*a;UoM(w-fG-ZLjBo_&-Gvn-CI>{9&o*Q57zb zoB3e-9~;cgvbSG(E3&e_?VqcEYvE8Rqyv*C>)1;h*2p?iuo!Ji>a zgG3`^aC`};Og$B1qLb3!@g^qLzx6{??wZU^w)w|rF-USuOr zZWOilnZLMT9IS`#dDpT53_F<%PRVz|@IjMY>wqay=1we~GF=Jj&~~)7(E$>@@pj8` zEaU^1<)*-;D`TZ~peJwWtyS}E^2fW>D9W=>h%YM4MTaqjQj~>Z*Gneg_5+b=7fMM^ zw_wN2&rFlo3b=stQmhj#72Vp;lr@`~M)ex!>!|I=Q{ChT^Qar&O6miu8x61c>rH=a zRo#DcJLqY0c1g@oDX)0&X40ikd|}b)i1A@34V-Vw$VC%}E}V$G`yv|t^wmVrnk5kp zr=hoT+1z1moYQ2b10#^h1TkIEznA_qKvp6!E3)X*V;|K62bF(H!T=iAg`!}O@_68b zzdCxLlU|4WGaKLB39C~(ikgO|PUL0a_nW;GXTCoEyr4vhdLRlg$pDF$+uz|cbui7} z?FkRA*ga*s-q(OWghw_4VBsV&z+@3Jbwmf3OILW%mlK!UmVfBBs`%=u3LK5Lhlu1# z2$mfJC|c#%aVM)BmFz=lEfZ@_4l!^ozmIZy7!EU_QNR-v7I!5;2%D(%RzXCxFggb@DX zbSc-?NhZ23O%KYI$N)AC_@Y4+*d7oUcoOb~25hg@hRH47dIN7;zxr^o!AW@2kKncQ z*miTg-_q06P>zvMF6lj*wEazLpUO8524Gb|ZMngwkZLJWn)Ct_*WG{OZB3!B;t@s3 z`>d+iE^~`!!~cTdpt1ZeWeNT@!Bf^dcreba|LTc{wwZWmf`5K*foO;`VE<)BzX*K- zBpq@vntgew+cj_b(bQ;dItNXHllmt?ux`OoZb{>YNVo9!Kja4lw(w>Krx#XHD$B5I z`LUO-Y2Za4swgIK{P9EXPbsQ3%W8(1+ghb$Bd}(|0xn=60r1C`)7XF3TP>gq zuLI!#T)dsglQUZL9XkM?0lPoayND4+aiRS>%6~8pN-$o$yPql^)L2H(zvPqIaV(TN zKWhyOfk69?qV_jC@qaQ%4=E-?hFU`=JvKu@4LN&DVs2|w?}$v?C($%8E`AoZ(NE{1 zq^+|;NHYa#HnH_XB)#-KA4-iRz=AeNXsoEQTZqeYMC@34%s9uz2XH%`&q7lfT*DO?s0=G4VSL^comvat#FeHR+sWE(8H>8mVT##gC?lqz|?`OD- zd_G?ulvr;+cGoBN%^NFveHesbE7C$0M2pz&!i{tsv#Nf!*1%8nhTFlC1Zc!B<9{(W zpNfRBRRT90Axo^Z3ic%U27XIZD4Cs0VLf)1>Ba+`zap2$H({I@dg9?eZ^Cg+Bh3)T49#Fs{Kr8Dg!x+XaR18 z@W8?mTO-&MJhH#ax2atn3R%hKJPosPsdIi{ zC7)ppUQv@FL7X_*1^%}iE0GfE8&RIySVUzaflOZ6uDp0UqmM+yOq~7pJcK81{m^9M z_ksNPlh{et$kGp0bd4^#tk{49`(Q9T$1&?>;t$DD9=DV*j`cvwq?y#Efmpqb?>$_K z_DjANoJlh^@z)bU?I<147mgZbr)sR#mh_3$90OFj?){^U)6c(nX-K_AdF%_QXBOO; z2?~Sb=)TIt=G`#-(WiWuUvLb$4&8)?&=%E(KF}nZsCoy<#hp-`Q0siDCwnn84x2EK zyxti(!?$^ArOKn37UHb|J;`-9AhkogJd8p;&e-M%JECSh}?OXEyK264D#Hl`Ll z{P7f?q9YQx9rPNh_`U1=+=ygD1@C}DHgsOG?@T#%$DBr83~@Oqm)rUv!M9=i*?d+q z1TaNCUNH?`eNl#(V+4{dB~O=(?yI=}OS$~ifA^!c`Yd^-9}=c7$8CRu#(Tb^Que7V zBmkpu=ZW8ZJjKDFb)?{K@A5{}$WAv-Hh~tRM12TC3n%g*w(&wELTfzPq|uvoH8LzY z+9kn5a>kAtYx0)&zsl599*OwUwnTdF=(Zi`x-=H8foJRaOlw0y*1r42L1(PExEf~6 zA8b+%Hf`cM%n1~$Cb5Y;aqL3gk9_HIGYILJMmkF&GW|FcGI`&261y_Zv>VB+=?!t_)k75+6#AYDNP905B_hD*8PoiR~}~^P=`^ z;r62-_T|J)ACZfc(_ogv!unY^?yD|hqFRgvz2A4}KuJVYC3T+3*l>y$gGX&KhxfmM zvpDwp=O4c%bU+c_aZ}*XXj!S*dKf?(@Z@V(=lF+g8|5Ed71^ttF5PI;wpP+3rJvjC zWaHI2k1udL#NUMlPCFDC6z|T1-=rJ9E)hQ1l&W13cX|}}LF*ID5Bk68#&n3paWf0< zZ^`RX$^NGkJYs$?ZeS!}GL6+|%v#4nlg#)Kz_#WI40}N}7zb|pCv7j&qfg=h$I^`T zH1##TCvB(huLn;TJCN&{azu*ItxwJHx!FjU39~>1k%9Iq$0RAafWZYMN}HEpMS&Kv!(%#B-$cLdi8qC`WIGWXo->9P72GMnJ#`Ac}f$rAN(`M`*& zM>w88g`O;p(o9D9Zu6d3Ph+K9g-0ev+oC>NgaD!x5890YPDkuXZ;l}1MUjt}&7yeS z1$t&z3j6%^qlq?ZDhtWh7ZLb>+xelN2;`)5iH^N8)yg(>mEwtQ)Vk>r$ z;|q*nMbXCKIp?9s$bzQ6`*Si&AO^i7tS&l`g@`a~{&6TKQiPy0qeji`!(6k|3aQ$i z#dWFD`%gy{hk2S4g1=muN^VS$QKlzktD}eTd&8hR=MvanBj3s}X6p4WL5VXIJ@0^Q z$z1d5)LmJ8Ka-_1vSt9nqhC?}n^a;AI@}`!hCaB>b#Pw`qx9PaepR$;thC00|6wRf zSpjTuP2{$BE%dG-Y{teKtw&z8`~O}5#oQrTJUd>2cwmUZ5dIt|Xma@9%op@VkGQut zfyKcUKRWIeVO>lW!EEcHipj53X2K+#hIv5FCE~6Jd28|uvTMELfzQu2g#WW*N^r~4 z3%~Cb;HB5}w=3XId^V8FIACQ5t4cZ_@b9q(!n8F-Le9-zY>uR*WH$Ig!>OH-)P+_P z036o~79$D=COe7pRs*qeB-% z!3HI<_$*Aa)9D#Lbsu4Z-!IkS`WZ>n`4<Vp5q{9XZfEpz<3u|NPQ(mbHni3pkb!YB{YT~mIdHDI5 zr!$U8EF|nxWW%BqVlgTGL&0K5i+1A|m%tq3+{NR%2OL%-)P2_xn)LW!SJp|=0cC%f zYsAOLX{Wav@uGLxo7-o$rPe6Q*)6DK@*WxTXegRw%)tZIbaJHxdzo|#mRea4+U9;o z+N&kHnCn4}WUlCM!gO>uBxErj3uvNZ?&_)e2CM#V_>uEZK%KNb%ODTSd+e`L2@;re@a>iHNV7ZKIf+db%> zgYa0W?oOz$(no&R!|feb<{+xi`}ASSvOb7(T$TiDQVw&b#;Dn~oi=idAZg=!JbWJN z%+l7Dc3DrE7}?MB&Sf4w;m;H9g$%UWzSc)P`!mJYX6(vb z8XT7Gs4-T>oMVY(e%5TtN)_i)wnT#^;zL3%JL;SW*s4eKKL^tWPJ_Trz4vEgUeQ4U zziCr8l5$5k#VGKMA$DcjJ(i%wI*V~N;>7#+I2oFyL!uF<{*K zPsrW=MjQTZyBbng0!;(oH3eqBnHOW)Cs!ZDUbJtRIOR&k*#7WxdSzWfS${A}&O(wu!iE3{ft)O`uBo(OMmllJ6<6B5SwzxoHrV*mw_6XI70U7L3Z(N zmRz;S%BW4ItjYeItmfB$pEb$BrF28#AI85JaWx6M%W2F>Fl(B=J0p`MH}^`Lo5dyZ zbi}~X9+TzM1~o5rF2g#1PU6&mh$6$KW}MBm zS(m(ly>l5HCn>)!dHHIcMcNbR&T8Ir&4e%6<|rQwFeWJ&bADvUsSwBUI=0PDoQHZk z{rjMD+<25a^>5mm01wLf%^Nutjl$uDszmE-8u?BzpF_L5!pNQ8N=-(De_O|(| zk&!s-v_9q9jl1Mo)hT*9{0jI2{EEtF_O8_61@232N1jB;s&pZqU#LRG zv{V24DC+Kk)I}Zj%4Prl3NaVO{d*5M7XQxIfrZSQ?J!H6*=UtFBK=Y_8g(C?wB0bt zCY-fXj~*^VOJa>M-x`V*0vHiS`Aa)8;p4M$sgNjLQsu9tj~`$0|mXU|a{% zEo$O-*Z)V;RR+b?G+h#sV8Jywi@QVc;4T4z1Pku&?(XhRaDuzL%i`|t?y%o|-l}iv z{@c1+wKF>{=bY|-pWL3g!(@p{j}^&zZf7YbUaZvH-3VS(h+b6T{EK(Kl=IWw(J8wa z3kwTQf}4!3A?pse{_aSt7q7ugvpvRbX{1;1ST+3?Vo4_C@j!HEvviO{OMN8bTQI{p zF#x$7q_KT=>|Q{y2RVtLje< z2;omZ_Ea+SgyQwB5gSZHExSF0;~ZA4W~4rv=`xQi|6AbFv0igllcA57q~QKW5g+2v zKz^4|F*ab3qa>SJARlV&CRK*zQ^pD5k=ud6nO+N_A3tUEN-tcsgw;Ytwy$<(5^9$@ zE;^{g7CbWA5MqqvjaVc=o$%LzfH*3Bb7)Ic;<2(KaWA~cBhDOon&ae5kRpMB_69tE z#r+)qhVja@$mv^$EuvXyp2lUdJbTzW`uq`sc4?I@*e>&=gBR1vjja)r$tQXc^a@zHfWc+`7D6IB#9}AtFd28P# zbX;J~8eNuRn-@H9khhX)%6PRjLRkjg_GC4&$XfVE($ObUF{I|5>0K`N#V`@iewRPT z9?k1K9~FDTGA+XR2J`i&V9$gGPA+`kz0p_GZ}dc^r~iHnjrJp*L(blKTaQ5(>)H~B z=l-i5FC6=MFpG_^@E0`Ar_R~kjfc8@NJL^@-=d0`drh_5Dx|D33I6*ad(#L?*^#oIrzb5>+VK~^6vZ4h!+&)QcQaCcqX2l+xyH4pt zQtJKH8k8|ilLMrJR^pBMe7f#mMC}QlEvYRv6svbk1UM(ZV&-v<95;zvis;=$*Pp8C zd0Yc+#n_WqD9_sNjgUN}m~^}gqdPvjoU;n9d+@Y^`u1B)kWfDq5({KFN>b_Pxz72X zqEG2(bROo|h0E>Dqj|7iOV4yWLH3 zw7SPpjhVXYMeeTc-dHu{wn{x@oA=Oucs?AT|ddWWGDskE*E zP95*BmZJoL-oc+(e#P0SkrT(unDXluLj+ysezgT_Gd;lX1@@1{4Zp07xI0YfRR1#% z7c?5lGpxaAkzH0igx%3)!D7rVL%PgY|HnnKFj*^>f4|(f9HS{|9Jtb_x}#TAZa2_E z1k-gtMCu$E%}CSpbB4>nj{zIa>xLv_zwEGZ%=bkn|K5L#$8)fezu$f11q$qLZ=>EA zAzbo}qq0ad|K9F7(p!@$nZ1X7LYHuuK~g+2iweOYQTv2gV+>8jo3v|04zCD8(Y|0< zlUPG4h&zDN$w>rfcLYGn9aFt4jEuYM#$O(pBo#U@Y+`iUxjH=4Nsp*W7vp0aOj1NC zu=Do#U8sgi8d;1rR4kdHZL!%`bk+@Bre68_dkl1*VW*&32)1)|;y~k25B%0-#Eo~RK!6j+ z#+C}SDpRs7P-^~#ow}e@x^;m@U5catnYoI755kD`kQA49ku@LPBDR#oV%-`+5v8bO zTcY;j9m*rtv>tioFC`K*!K-w3%LdgH%;vBjJw9E8c&zFT))SA(L%6e5(jy0*N?#8k zGvk2|nI8Af&s;Bs;W{g2cKgStyo`g}fm)vS+P4Bb_6q9%l+?5MvJOI(2^3sc(lfV} zPwS6@D0nI?LBIn9b-!1P7HD(qKYK@qbcz?SFW*-<<9gW4g|dulm(-`E^IoMABZ;Rh zKV;N3g!TdgW}cdIMFo_o@ck@3dN0}EYHC0$q|v+b+AnoDsf^xsKC02tZ<-m0f&5wk z?)q4190y$^WuN9IzFm{LsuO?ZN)*Z>dC;pgA=!C$lAVW-kZFJ0pl7a*?n%pfehE|dz=W}l2R`bIs5Q|$2kOr& zU5PT2l9R#3PN*xplRwRSxbGNeH3`7oZ$`_h!20no8>)vm4@gZ5wU%2%1?j4e{$$Wy_ zqgS*NvE{-iafF6m0g z>)OuYoqvfG1ojRX-|?tMnbm4W#zulO{CIRHM06g?xQmVc7N1_A?!+D-$~w_LulDE# z6>}FTHcaGH3dHG<%sGDF2-Ha9Df~ zeu<^Dhfqe@9Am@lHAS({!8G5Gtl&(WiBx(owjCQ2_TJ5SizO$MQhg3tf7ZRhnGPfA zILsQytxpz)(Ym|m$JUA+pvW+OoiST^&~u9sj10)Zn4-buC_9Oin;x1 zsX-x}Rj&6@PP7ZoAwr*T1qp_WQ|{u{AdJkjXILaYl>8$BGO_@B7o(!f-{@dgNTE%8 zSI~uDyoM9r;JY=U>VC{a3gCV>KCWcQyX{g(&Fd%q<~9r~^{0UvT%V9bz?Qf?(Z+9% zt#6w&4hk!lcU!|Zo1~l0FP@4(Qh^ix$2pqsP8BNY@}IY$quc)oAO$<$EQD^j_E#&3IPR z)#+D{Xr-a*aQO-aJ{gRmncDNm3B)`sGvr-iKc&RWn_1b;Ykp3BfqOqkH<>%p`-`N$ zVUowiB*F&sJ=UC*?r2pFy}IG>#R+LS8y?@q0?M}eTdL%Ae0X(LiVEP1?U0VIFN4+- zNVjA2#rk4|W?HmZL)8gzt|2X?{`c~sdCkJp>X6ePV)M;M5;4BG*k!%CZf!_@(Z%`< zN_X|^b)xn@DwY27-p!0>d%m{e`%s;af`p%~?1!xJ3=;Pw&o;v_&bB9X>~BtB5L_pX zjdes(5FgVUt(AbG#T*wFWEylDW|chDhlrE6MlxK3>rRICCP;mOEjQTs7!JWDtEEcK zb1jsqR>y5fz(YeuK>chS%co4BShAX@)JzUaA#xw>e?o|Q?85vLx(_E27qw!EB>irx ztIPaQLbnj?@mnpT?}O{3J7$!a!v{)tl;{Rt`tvTJC zSZAI6I12@%eM)Hz<@J=W*>R)#Sxtr!h?{cmTS&|DCn1~Wp0C5%la=;m$5kWMoVD&# ze>hOXk)$Hf;tUg2M1RByxwOYFIGwa1MTroRZ4CVoiSM6PY$m_%Vq5A{y@69#DXE^Y zLuV<%k^)xd^@XD~e7wH{M{Cw%dL7uL--Xrl%+2Qk_y=VHb;vKil-mB|KwQ>{o7fKsrz+t=0=99pd^uUP+8&QBXoJe|2!2FrLeu#(1$fQIFR(pNunMRGP-Ok^tlUfl&MpV4g#bx)V76838PH z$Qab!#;Cq;`Ly{O)9*1w2lc_9=yxZ{pHIWWLYWQ^1fr>U&C;x^VoYC}WGL-q6Eh1a3iDsFNBwuDnNmw(7>v4uo&H*IZ!apt4io z4g@hMX%jEX;gsoaVH#Y|e6jSJ^Geje7<+S5`zq!%ukAdLKS_^}e6$m|=Gpc-nv2X= zLfGSVVj=)JS$X1BBFJIb>X<&`_=({w)F_z_>O0eE5X*Pjs5@sa3P_RY$Q|1>^OyLU z%XJ!=nDX5qRHP)9Y^}zqx(ZlOEXM9EgdEb(1+TOE51L0zOKx%pUL$1g28r?ZHm$~S zt*aDT`albS&*`H*e$zbLU&Z7;>)9~DufhK6;``J3(XSmzU+Hrbt`E!o(!_M#L-bYW zvvr78tRb%kyPSjdAl150MJ>#rIJ*m3&x|v;zE)NuCrf zbGVLQmw} z6(@F@%>Si}l0fj59nmU)QBQ*zwG2xzlx+3dV(M}O%e2`d-!(B*9Yajv6E5ezZU#Jh zlu=6kFiq5CNeX2}x_NkNk!d2LU^Pj>(D`X6Jz6Vs z=$x;vp3_V9miCTVY$)@D%m{)=_?ljg zf?(tNAV?GrgwE5;XJbq$IHXRh=Zf2XKr(+)PUE(bL$m;FT+}K5M@yaRy|sUc_rbsi z0Mu&G{FfgxF?NGZE%9150Pw90``e>CsB@5?{!1)bCZD^5*JJN0$w6`8f2&`g$6vFV z`EK&<4E#>%M8uBD|Kt)=mV9Q)*r`6fb290q_hM9rk=Hcqv(f-}Q5gf;PI742`}Ww% zTD##iM8nBi%xKus77E(m#cWF;D$RkQ%ZY5r5^rmqTZd*HYOr}7oqg;YXdV(OM6QtN zQ93W!GlD5g#%Xge!O7LoU0bhr;B3^FaD@$%i*LmjY>vzcaCsI*9!D0C&3S@9xi8>2w*njq8fPqQ$|O)Y>{&<>s`Bo#bgt^j|F z9MU8&yG_EyDFOzVFOw5^;)Cjirs3U%#VRLR!)fy-A5>e zR<@Y4g}C`_2P^-!3NOa{x?A~BQ;hel$>H{~;qloBT2-#q1}oqy+pb1iWoP@zP5p1x z`T(-du<=S9%0%RsaRN}bx0TQ6LB`hz;(^I8G#6mgvlPCU?^?jYrHuk@G9&=A8MMD- z-)UmH?;VYU{TAlH%8y^MUUzk6w2q&$IrO|cjMm@d)6W5 zR&{dGSlw+X^GHIm5=wT9QNmrk-7Ik3e(y;M#L2j6Aj==Aqd1_r-l>xTJ*v0@C1niB zch{%uR}*nQceYor6OaGQDGuWdN!ms7ueAKhxT95wrtD$ww7OSE$bRTU*1007rMJD0 zm*`lE36g>4ZWa=Fwbp1?5SN**tge<#SI88)>>0kr>saa zr(Tj-NXP8bFT~-{92`;=28y(z9^Qi=jPSNwMAvGae!M&x^I4t7@Ph3#rac};qL_#UGt$ttnzxh!ggq1|>?oHS{DYNIDHCH`G`+XJ!FYDr4 z<-fz8eZ5+W>Hd-Fzj=@HW?Cogj`aD8GqOWd=9UPVyk;a$(f5;G4T`swP!+R^-WoZ2ZKA)e03woaP! zDh_pWj&pFMsVcdP?M^MR4;Z-*!;yO2!s!}UXw%Xf3;j5vF z-^78VTuO25`GuC_kgYRISPgZ_flQ*+r1v{IY7$R!dI}i!w!!4-`5Wc$I)0v(AY?P% z*IB3oI}4B7Opn#M4+)sM#}NK@gLEKM?g|i#Xbg~TGuBd8hEZrk0!X67Io~FMXK~|9 z3`uU!u%Z5Nq$E1FW-vv~LF1Pu+j-_PqFHp&8-YjfXP1Yu)y9-zqpQ^oQbmlk&TZF- zKG@qD7XL5iIRcgqkm?CV@sJEZrtol?b1INI8Q;4n2v(G$n{9>1IhLzzWu$~SsWZn; zI>hglNi@)iw-jH(HBv+9=`mC^1sgLpBMix-v#Qlv+oeNQf*VsYM6ArRt_p{9IM4NG zmSi@+`v!jf5U&!w$z+|V6x}r6nq^4n{?TG@fnMpo==FU)EvOMQ7D*JJ-OP>b8A$() z$+kUe?k4JnGLNnm6S=ZHDG0r$o)l@if46A{yYzCZsr?P={3WtrF!mz7)OZg+Ucb_u z$*61ngyMtkRU3_-yLYPP5u7B=oyYjSsja~F%_wGnUiR>XP~_CA`)QeRvDLxHc!BfM ze?i>q&9Tj8-n?AfY_pSoyVaT5$do9LQL)k9jBuG+gN#}~3o&1!@9OD8&&Bwegh==) zh^*`onaAe!<#xRbt1CTm=%W&#mSp|%^*76<>cq-IxEh} zIvr;iq1ifwtZlU$AWJoDv&GiX_lEHeM1;#Jgx^qU37HG^u3y`KlFrri_LTz7GfnG83<( zg|yRMXF;%(e`)2{%gT*mdHb>=>>HK)5SAsXw86`Vkc32>gbLREOcz2@rz{S(<(<4I z`^himWO?WYXW=C4Jimd66|`KMJagy3@4KPpN8LE{G~EYH)o@UF@s@Iy=b9&R-mC+I z14?KF@XXf{dWzt@kgHC$f_D!TVEB0fiuG(03xyQ`Yl;K*12i*MCpu#AQ_Bc{EmRC%wcTX{^4`8^+8a&7$hiWqicO)GEv=gQRVBqJfgs*tY^@#l>$ zhU%1>cGONEOvoDlDbWH6l@^X7Dn0hcHiCCh?ls?Hx&Ty{nkF+@w+TzN$+a%#ImQ(M zEU7jYiYIQKe1v!@eAu_t1JpqA3ITY(3q}qX zLY*wVF{wY-&YfnJzhHa-$YI#DaCougJt~r=iv}sr3ux1#0~!YKlQbRj%k6mfRTt>5 zCr-Fl`S&-|D;>AJC%I1E`r_N|4!9H3YdLjI@+PZA1N{Cmy%WZcz-LMg*VugvM^oS1 z=faCFzsQv|rQDeB#uYq>lFjdmm1i3KQOr)MT-fRE(3{H4z9%a-i+!Wv$w&@q z+Nms4Tkzt_BF5<20O=vz?{uO*Rjg?T9|$56A(P&V^xsrvCXP1P?1-_hX`Q*0YM4GL zh#&q$5oie_!30sgU9ljVqGQ0qHi+G?di&P@=6qL)RcMZIDMOm{#C_KQr=NY2-!4pS zCjH$Mk{s-oW!@@#za;G6ler-H{aERAsraY++;A{5?v50piEgavYh!s%)fz9XQ<)4W|AXVQVV&D-!L!~P z5e9j3rw;sAPyEM>+`%HcAG9BzzjEO*5(BGwHRLa>NPcLq7q9Mjk;#q?tf%(Yeo*VYW3~9z?meQbK!LzQ6 z1%n<_le0XgmrK<4xOCLaB?&@FiPG>bo=#5mOid867@hK_UIcn*{Nuwt@2t*o=Y@4y z@POQL6Ha8~kya1OGc?s-B|CrD~zojF)C7+uNI!=v=G1S>kb6oh7F z;tmRUV2Bq}yr+M2B3;CQ_wN+fn8^N+W96MCyw&*;(Twps^UW$ObZp3#oopdd(|$yP zEyS8=>#frTTKISLVFk>OWP^YSm9bY4KGEFQr7x_5;k6x_m-J>Mkx_oM?;QsNLIJ|=Mx2INn#~{mcnf^CRe^Rd? z7AHI#LzOLS36eBfrd*|eslf5pA`wFbBvxHNE4$mGFa#o? z>k9#l-P;i+@~(PSyAn4uAANzLUW&2+b4?d1Hna4g26+xiO8hmBpDN5|L5=MFj1LOh z_}j1KlqdEwW}VG8i@dC&9V-O_EuCm5s$@sD5PP4`R`F@cJWWa;f4v|W8)(ernq`kv zqc4Hq1s+6vF5X?tmcy2Oiq!J0VAJ{_b?_P*(#ykMsQ~&Ba)cd$Yq!$#@)p?%~5*&4_5FKayzI z|2X8u6OUrdbnFY1M~^#R=$@aNBy|6!w|NHHXqLbqN43`Bjr zjc}?jI(jW@bnRP(GyDzY5gm#Hw)({`{}|(K>lXgdmHap@7uI3eY5K(~1h>=s-Zl(f zPa?Ow4|1E4{$U2-yRuEPA@EJ1&mql8#TK8)ru2JGjxODLmV*9JY04KFcRjy4xxZ0Or#eaD(9z#_rQ(LM_QHY8Ag= zyd~Ucp?h)kaeZwrdA`P+EYsYy0nAFzpn9fiY8id21Z;R1JWT(Ua*qp3^;!0j+Zd$* z7fZ@dR^-Y9(wY%GxVwfvyYOZ)!$7M&is~UZ3Yyyq4x_S5er^7r1e*t}RDQ`)ZepI} ztXk{bl10qWdx+>0e0u;#Lg}Qm4f`u68WiSE!!~C4l!5ZFS?r4EnLT!b3<(j}X`I^LFxiR=o*&%fj*OczpVBi26A4??cqx zin_t*$yrM)#li6AM%X2NI; zMw$qh#_UeEM=3Kf3o9WXKNchJ;^1fzyw4UiE7puZT^UsvlXc|=DfokbmpCequryO6 zkl7E(QINJxI)dG6PUC;c%{DEP9eJ>Idp7-0iN(fwoe|jk>tXLjvB*%Ck@NX1u^(8gwMGt2vN1EExia7iQb3(EQ za)b6)VWjf1^*k_Rd^R2|y+ z4g7a^nRI!Ki4NR~<(!F&gyFo%qcjZxUj)Ga49N)J?1(B5o&0o={$$wM>`fvJlrBeX zQiF?iOoXqv)kuzd>FnkuxnKCP|7`dS6TQ28E&oiNk^OHw15@dFADRI@8+c5oQ%Mrg zt=(Yn4{&j;ks+~2D3YZfZcO^!do)a~qzw8wLZfR>)T-n+xVoJq(~jOf`e>iJ0}#%9 zLwAFj0#x%*3)5rm+lnEMVz1K53hZigHy2& zI9n_3|7<6$GOYTkP6hSX$lecq#(Kng|A4@L3$jF;_WPv|X-Xo_^4R%s*VLi#XQSi< z&?YzBYHw1U8=867M4e4vStI4Bz*a`3i`OnO{Y3CrA+H8b3FaPW4;Pnjs@Rvy)y7mx#y>vmHwWS=gXg?WgNz!Bg4T&zW1UuB#1F+}Qt- zX_+nRWJZ8>2NZo-GK*~nWswUm$9G4^P!Ja1muGUTcsbEOzU7Lrk4B~r&V@q>vIr3~ zJDQE7uv`@>Z=&COdfWRKEO>|Nqcg_GnkTOzhAZ<8SsT`as|-H4&+HGBaHpU z&VCttq#17LF>gqIQ|AjjtO?VP_`=H-=Fx^lkG|C{EGQSbnVf}GBI5W{MZFZ3N*kuk zAW<`?W1#;T`^BW$jPf#mENmh)l%G=i6o>a3&5dgRX0UznSLzw#n%Y2Qhw-u@*I|Dp#)Y@7vA3k)@L#IO9;ifH(Y$ zqQ~6n;^7{Xosp>_NQQ;AW0<;9;F%?YCl7P9JW-%O!-72|BH}^u?Meol{hNF7M=0^) zFV&R{e@*^XK7EQLAb|S1c(Qn){J496^0@Ab(LEog(hgnmOq_Yo?cj-B`r2U*I<0dtQD~7nNwwi=;3IksGa=v?LQN=kzAZ zW+JJgKLQj9S2SnWW6_9M1MTj;!K-VK5uTpDw zA-OZY6N!zez1=Z6%PkGmM*?;(bBP?<%2b!}YnE|bou+DjrsE{i*Qd3@kVl?=5(qTP8(r)#tVCP|6tQ0-*Fp*{%mEv4 zL6iIiuOAyj=LPBra3`H8cC2fn`DVUPJzJKqRn!8k)e2|Z7%#KTd*!E&S5>~(9p`J- znu()AyIMK(FfVHcMHRHXdfDA(O6ZKv6wjY<%(%Fu2ixe;pPSdHrxvX5)=Dlh%pcuF z8tB1XUJQ2m+FArDoT0F9VMB9CV|9V(+Rl?hmQvSs;QjiPl|IlIrf47bnXvxCp2v3T zF_fb=OeEX`YStX?JI{@|fSLhih2^}fMQrMdu@q>2BF6yGZxJ0bp|$m^?y9GBzm-J| zF9JwK?jA=aOEopfkL6LJV)W_ID_%5gWUkSEDhoNzI_T&Oxmub@y?w09+x?zE1WcnTXpIl&i(e7X~FG&Px{7Gj;;Gouvn^EIb;wjV^EEF67C!7o}60^9jp&ZE|-IR^{m<#XfaMnYeGsgRV3YbC{0%1UMP1koU|x` zg7S7V?VkjX@HHFiKHBS|M%lBwIGN675t472u#uSNUAT@sozE1%%?<6HKKJouygwx- z%+wvX+IHBvo4k?1izOJ9|P~hR| z!?~;C-kdeoX1af#X5OR)ovF@$SwqoK<{BKk{-AZo%jf813)z1Ly3BYXhe)uA<7Y!7n>+=;G^7*pVO1-;f32Nv#5?N)+THzA8Uu7C-~Zc3 zY+-m3H)G>ZH%(}zQrvxnIMVDBn2U!G+>5U+C_3#DQzu;{M~AgJtkMHYc|TX!-Z?He zq8q`r++#C;~SOZH6Wpf>oEJh>S6{c|!j2RB@-d^+E)?g>Vp`gGOz#=jA2(k1*_ zHrj$J>OUoAJ}MIZB+d3;*q)MIkPcEhi}L;4HD#7N z`)i{}k0{sTN#!Q>f{pik{HjN%mzw9jRm()$E8#0CSuOOX#dMJDMy=EV4}xk9M2_(S zM~<7HVAogU>lJ+i@LRM4s3pYWOdhtEa{A9Q6stJ`Io%?54SV8{kWCl!GDm-_|9we7 zFIq8}vx*E~ATZ(Q$t$pLRr(P=VLUOtpyzKs)?^u8B!YK^S-JO9IvG*J!Qx_t`YzzR zy`2?5ezs`{e!RssFAS)|i4V}<-j?5O$<*-!rrm)Jj!xZNaX0E!9gD#}S}Z#gUUE>& zpyn4m;+0qy!!u>`MClt1;&`q7<$~U|MBKzR2p!-(O+r_x)6m5ox?> z5W+z&JPO9A8QH~oAk5(ggqv48A;g5*yJCk?um_ZCK{>^zC2c~|<}d_)Lc^uw7E2z0 zgeOpgSKR*QZ!WFH6$w@B*b#Xv$IRNa+z*Az#t@Ud=uI%AzJNUzlrC`%VXj7ZOc-hc zA#N$srpF#Wl&ppDp%O|$2-8MgPb5T`Q!g5MvK?3UZ3Sgk;v1mimZe459u`#Ex zJigkn3Wr_zsENR>u8@O%jtaZ6m$$;H#|(ILRvDVfn`)0K^r9#0aMG~-m}NXqG7F$s zWBkMUQx6pVpcc*>$NA%_M}153=mJ5)8CdNC-RLbxvl9gLt1kDJ*cl7OpC2{jRW}DQ zSK7<}729g(&cJLAW!ggW;)s>aYZ3BgyJH%e7sW*IcKHbZk0xCBmM3aAx7-B zu~J!ZVa>mi3J=CtggXF>Wa?`4$**ou=t=CsO7TG5BXMpW@-lx|B|7{1Nw$!b?T55I zOu7(I57Fj(;Drc@+=AJQpV-K8+L0C6P&i3=+b$u269Qn3cPCWAqwZSu{DORD!V-pC zL@gDCFQ7cv=Ah0)gj;PdTGQtoVk?O!*f4&J)=%VYWY?=P4kFo^d}Yf2mT!I{z#o=; z>&W=88lq|+uYHw^{Wh^u`J-#;hK!^KS0+x{K4ban zfjB)@+GDhQpa|w?uB3T-${ez5=tq@QRy144Dy#3IGM?vKLo9X!4yGs|zugQ24dhD~ z2`N03&#M7P=U+DQ2r;hYHoaXM1T?dnx7>>W{;KXziS;c9P`WoKpLl-MV`-Y4G6P4xtG+9vhiK2sGo6&B8+_||cUdZD=ev|y_PkaxlKw(~uFtycw?uC2PTO1v~!nP`Qhgp~K%s1n~I z|C@}#B7Od%c%D$07{2}U)DHw2qFI<|s*?WD6Xu(Jwc48R_s2r`Ev z{m-n5>Oi(9>q^0iM|vijTb}oi>D%}7ywhec!leRm6S&}2B1R*=c+>&V;Ur1tx)eOo zSNabM@OAA)-=ZJ@))Jhj>hdx~~Obzx}Gn%QgC9(Z2YW8YKGpF(rcSjS4hnZ!!V!??`Fl z(a}^iZIVxlEE6bqbS`hO=>g!yx{PkYC!xmFSpKOVJqlCRY4gz)OlJBmx0;WRd6!uw zzALE>5vEs5|B*KS*ni>j>^ebFW{upLtG7$6_bM~Wq5HvQ&}?o5CGq|(Y^lBkjVSHd zVsu?G4Ie*>v!IT#bAIpp0HkEh50!f1uU*RB4+z%M?JH%qpW+xsGeXNVk^hft;mK zwTQuVbF1?1dOw>HYSUL(@DxvY_TBIUhorHycgj5_n}>isYFdtC7ohmzkK`y8Q87*H zvO^|>w>z%LKrM<+N_EdHu)i&9*Sx5naqp3nt{kdHx9?ml=gyg4rm%TebRriIC7&%{ zEwz6aa+*%u@pnigNH<3a zKDQ1Y11r^`lBMarR)S~WDIGxn#-0tO9hP=CXh$6%5_y_#BXnbUOVyGzVmXh=^Ae zeR2*%v{8f0^CoA|hd?}%Sc%3wK^Q`}a_@*J!YnB5sRR|8q-C1n=c6F?zx4y6!?n;B zi$&MZ$>(}njy`zWJS2Z!NNFzQb4XX+z7GX*k|MMHR}zbU=)-ryW`?JPOgAKttZ?(T zM z8s61^ghuIOekFZ~WM=>*q4lz?3!L(SP@QtqrnlS!bH;yrV?ykOmje#pO!`s*W7*cO zOFN;;A2nvJLJaRnrw#elasokv(pnG9-*+guRQSBbEb{a#7k>VnOZx06^w)%%rthLw zuvcZoPH(KJ?PPmwa3;DKNg)rB_;@5-1tqGMc0m5VT)`?!WMf&9-DM<_nShg`ok;!> z;>iGT_dE2YxO+YkVi9^-_^fmD@XZMxcQm6w6&2)1Du~4v40`roxEuNCcrr%2Bg5EY zr@d~&xC$3W517Pm?dYZ!%n)jIbXiVgd%pa6$R%zN^IfJemO}Lwcl7yO@i91yaPy(l zX5mkJQfghpgaE9#r7o3XTfE+5Y3(x7(jdLct6m3jjmi{-@e^7aSuQ3 zLK_WMLbasS|G7WUCGen5e-!c~e(nKaj6{}z+JiaFtfYHSmY++tsl)SSGSk$@NJ{RO zZZC_9lEzP8%bg2D;I5d1iZKD!779?#FX>>1KHp2=w%%ua22}SyfJv6Hkv9Ch|6-d} z<3E^GFW8>%Iwgrhh#2*pMPiVxzpYW0-wRU?S__07o)P|J<1Dxmbr}$`_gVfz*-&;C z(rFl@L-5CtHNjKgW5o)HKGhx6)2|(IrVk~3l|uLbQxpTU=GeAvs>`o^Ck4SffxzuWp*!f-poJ}eRXcT^y!dz`R~-M4$Ejrog?a(U%mds+jT%l{2N||X z?hJxKGmx6!(<}L$zivr^60T*hmlIudX|ntFj9%;!aE1Bfi!{cxX=p)%O*Ep}z$isw zE>PL5D*^EAc=6~n*h;AESVtJpA{P{AZ=C$u%ariQG(J1DTqyl{&ZjEHonGq!u_WAC z=ZRPTH@@yJ8@@D2Ua7yl{4g9c3TVx~G#Y%5Z_ZAaX}=$)5!EVL$iea12`AiJ;D7$u(q=sL zDviF6+3R?^Oi`&$o!7Sp5v`MjHq+I zjm?|UKRh4kz)D00#>&1JEU`|;Ui;{v!!x{v7Ifydk5RbT1yE(4%0qJFY-?7U5PnEp}N|eXOb}e|z(PpnaUTg3SJyMw)x2cJz=Sktt^jWfk`aXBBd;&KUM zw;hQE61kgMx&$D%CtOi$z9p4z*U{sux#TLdNWJUT%|43@3>!& z+g@j-NZPpMZc0$_x?&3(o9S1}nw;e0YQQ{o;o7i3+}9XG9MShxGz}SxSI5fX!(B}r z_6fWWXrNu|_~#LKrbFCveg(TYtU?8pRu9mfjH30Ql~fr^ii{1@0=o1=g&!j0v{@l3jCw{KvuZ=hDZNp@0=kL) z@73tcQJH_OPa2NwE*w4Ft#8)b8XaF6+C5k5+GW#MDXcOJ9nmSP(bJQ#)$1%QlO)d2 zx<6xx`h_?7b&dV`azUg9YoqgjG@S)kTU{5e+ZQYDZpDiicW7~U*W&K(EmGWzOK>ah zp5hHICAhl=2p;6-yLa3_ka5O1XJ@Z9=d;%Q5=(ms6%CUAkH>aO=uaLGG=KB))h{>+ z!Dv}T0d}JZ+Fz?qdO&J#W0!5tNBp+vlK%80PQ5)UvAZ|W>d+GGBAstL6MJ$UL~r(P zmfYVA?VeJO_wJnT5oU@_zD#mFyjJZv{FWl|Cj@E|Q9%wO&i)%&k!hF`*~mf(5@<^s z+e!NHEuS!D6X_VamD9G+pYfvE$-=_Jw^6#8`_#j3M!Hhw;v?m(=X$H`@G9expwNT# zUhljBc)cp|Y}Yxd2b_U_FsR3EUl)(@^d7JUMim)$i3|pOa65nLAD_67vS;OOU?yU- zcYC<+;xcX9J;&J_Clf<8C?f`u1!8~FHfh;*CVm)AaSv!vUMvV{qx`*w<}0e(mVsYZ{u@^pkG$&mn%E0ttdiB+JHB_JUf-+a+tREt;cMLK{sTHu#1Q; zs()y-Zc=&%&D|;4sP~bVZCcH&sB$-lG4~;IT3{w-lkB+Q)asJBWj--pt?~#@g;O#g z(LQ<0gS6sdseT|M_hLc?H9lwzt6AKH`s(3g?p>V7fWm667i)_eLaj%)(Y6oTNuws% z4ln=@BC}kk?55LY%jw4X-mch}b<l@1n7ot}%V`u=JY^!1HqJYB3tyr`;6I&AafCs|TwfuSf?WEs70EX6=k%Y2F- zJnky(LWUA22uX7EF0ET`8Ub_OS&;8^&}{7k zd2I`+^ZI`iV}GI70U~b%FNvWKJmh99DkcQkpqs-ge?`$TCT5LmX4ZE6k-n5ACsR6A za;$E`0#P!dBu?#|9k897V0=fWKRnW8MRdfeLBES@ND64(#9xZ3RQ#goly2@{o9~E< zn~)UTByjwaJ!Xd|p6R4K+2Lx~nx)Ja1EwvZ#J*Sg6G`LKbCuYu$KsTBk|18t=@J@i z%M-6y5;vVuRyL$t225A1{zPUm6(^U6{j;5>cne*P zm*&8Mj>?^CFl=Owj@-_#Ui{VYw&^9hn)O|aw`>SZin}^m`e#(xkJm7lfs|N zEnjzSUXJ<@24xs?l*Oag(UuL&uPKrDna<0xAIopC6gi+tmwM*(>e$dp21~l6GSL9 zAQT!VdGVI0^=Jod@3u$zK7M1>^qglrdNZEXdOihSUl0o>#3bpLwI^Ov7jA&HF)u_- zerq6Cm3$x#^9MOm<^Z5HBM;=UdasL%H zDIGS?-m@T>BsTeeW4#P|P%Wgd$Lv+W%lTJD`NI1r-jQ6u=kjhs`Xs_dhxDia5Q4(4 zD+SlozhRIl!Qr2aWWHzd{vFZ$r^@pv$Mi8yv%e#ks6oU|UgvWi>+C7{l#GI?_OY##Lt1CeMaJk+~E-JMSVJ3Kq~_m};1XbPl*&2dkT9Yfg$I}+-(QIluTm%p|>sP|&Jc53JqktH2QW^{vTRWk4-`K`~5Y=TP-KJsJ`#Gpn>cK|i zHlR~Fq9=Pttn8DHT$w}#9A{eE)3xhE0XkxL5<2{>y5B}2taf19;BfWj6|^La31j5R zB?4q|(*)4!GFIWON3rne#J9WX(!MmSg6$|R^C_A}T!j%pzZv8d0%M!ttSX7Zoz#I?<8n{`$nmpA3&z?jI(ba6QflZ@n`lJN*f_)QL>li@7x^+nX|d;f@g zwe|>G=Y8>dD0|_0-z(nF+8r9v_11$qX_*jrAmhSt0Td@3>Y4MA8TOE`b4}+M7F+Zc z+db@U!nmVAYjQD(e#!-#bIL06J21!1bQ)18*1Z-cRlh6ylZFE9Ca>jTF&<`jfyX2q( zEK3IJj}`t64H{G`$-8-=n|ke1s>r)}qT3PR@$gCt-lg~xa)vaHzXquMfNHpGFuhXIPFeCMtTy5^p=HT5@&6rf(mg$*@@KT75T-{tgXU z-5hz?O~9Oj1-WH^;s-Uwqmgf;krPFI-3Q2sPWV!M*nt-ki33m{gMZY{);IUXNysQp zTArCMZfbqmLCu}8FQqQOy9V~;R(-BT4BiDnqo?z~9s^)h z>fLDC#z+p&qDZN){4tl=a^dccqIa<6^^$26@A^gs@Djb_vmJ&%nhjaqKIp!j>uuRN z+}JkpXM#&4b+DzX=vYu&gMGBnrcQEK;M?`j<%J4H-%QXAn%dq2BE(EUdEnOPjeB(0 zd1Lc5xTo{WT_@r7>R=7IoJe?I^qz=rDAZ>&TJx$S3!aP8d2~-tNOc?&Bp3_XOztfj z52kGzU)F0x3F#$yH`qwuwO(DiSE$*Ht>GSyuW0(r=bV{KDPsD*a5Cp(d1iiL&p=`y zGi`Y$(A75OM726<{d%AQbEX+t4ZcO-dftb35OcP=x)b-SsmP44C=5IIC%aUO&dy5p z&I)(PS{1oI$wkkE1osOuPKbJzW~QpF#H*04n0+5} z!G;RW;`Ti zBFmacyqVr<>)9#_Zs~Sto5wNv=3&Nsf$bXBF*2lt%Zo=v0Z#VUe(%Qp0g5W=GT+!% z(ib(lAA&|TGu59PJbe%uv(`l7^?C{_k9xm?8D+NAWU}#tKjP5QZ5FOM9-285A5^U|m|<&64q-Q^v>I7Mmm08!G3D#P2A$3et+vU8RLAs%q~W1 zcI6i_(&9%e=?1lk6O9w%mthwe;>vb*@dC1z!sMqF-d~?M;R9H&wNE4c!6PDpjys{S zNECYNV_EV1S!sZZ2B(*XJNxyjRyarf*XvdqATXU}n`Y26qAeum>+OQ769o8!!&Uma z^<4wUUMU}qLS@@vf*naOapz^=&S>KHO6ktSGjV6|3En%txJBsJGeApAeS%m|Kr_Vu zTZMezMFddfiXWZ#UN@qGOY`1eb&ka>{+~Nc4yWB!lLumc$KH{%7i!uPOm|8NnfW)X z+`JeSFdyrfG!*+i)^^qW^)yj&jB~}^IpLw)4Eve6Z7Vm$WBnAT00a#Y;Nm*Aq%GK* z`wa76MfzEj!W6Z12YM$1Kv%zCS)%i$3eYc73Nr<4K{tDo41C#~{N(qaMF!2D z&FovQC$>#h^_FcSAf4?>6KK=W*CD*fjK3>2N@IsC>h|^Nmp-Ug22vSPeis_ldTIZ@ zg}hoaZJIY!3rhD5Zb_CUz%N^37UwHz02lB&%eM2_M4WrdPW-1s5+C!U?L@dYOKShR zij5K8Ous&BR3){Q=+k+FvPJ^ zz}ugB`&mfA!lUA{LD`#!Gf&1=`^e`2GQ6mTfIwi!mvv(yJ_3t$9u)v`;UiIMr;wXyS*%HzN38xm9{_@eHO7N_s zt$gC-sODVRDZVSirp33;s403x^jt?1m?}+SbYvS7*x7lkFzXqd!z61rL=^G7d5K`BL&GH4RuT}MA?%VZ`6wHfLyNA<$|JOXn{YR(J z<7wo~(YH9OeWeb1_sC0ug#g?PTdmEat&RcV{1W7Yw?r!9Uz0ZRh(RcW1Y>e)%AWxV z3h@FUvfTZdXb^=hdN^E+u9zyL=_U-?Jz`o!<70NHFB;%ynGNFq7JIyr zI=4I|WjnP#w^wQ9LqL)=?No^usv2D9)@R<_(+&2JGB(ogQTZ>_t6LWo#kaTT6E-Sz zBU771Xu=_R?LG8XUndksfPZ@Y`*-Uu?e;Ta!&2Cu<47?~gGxy8$?@&;on=TdDNKYg z*t$J$6fbLZBP^h2_HTbL>#5L2XMXSR(@yUyLg(h(mtJ6L`R+&T+vlt0>Or-6st^x+RQkXjtB?GmmA%-sivEtO+lRVj;Nj{iDMUYs(owqNKQs zL72JbDSF^mpg3ipij`G-aXb<@Ei2?YNG+Bm$C`s3NyKg|g1q7L<3cG>5cot*ig*zA z>9bu2ow^)}#0YoxT@pPtI+j5kJQhx?;fam~2-W6H&vY)C!l8n9J`$DcI)RXli1fu( zp`b5C)dw5SgMRR%ub9`&xg(mA)p3{zD2gV=Dk91n$(FXP;-oAXq;9U$sOsaB z6%_RqbbzxDSxp;>)7SPtYX>boa!%h~re&tG(`i!H3YaXjIT}|tG-~sFnpm)v$z>Yw zllIJd)Yu(tGywlJ27OC3V&qAeQ$jGVYDjQY&j0(2kKd`q7gc7+t0vRS52C5lSy|fE z{e(ek8Tfe{-&Y0xA~kC&qy>Si#X{fzwsiund9LkA28`C4w?4eaGnQUN|EV2ElJDbq z$9o?VQIWw=K*#$5n*op|H-G!l;h4$JuQxW5hN(B^j@76sIq3ZA4S+$lFDXG2{6BRw zg!VaLLFM;lp_4zFqZYlQs0J?zeEriw25x~Bm+5sY?PJdFn^9f$nKxLgLvnQW^QDwq zt=^T>dUT_UkgNvPz^+tgrX{Q6(W*^zY`ein@2ASyHXPI3sf}l%F^Lv@7oV+KvoM)! znjEp3ke+I0{T~ za9ZvL?=psunhNMsv4;!F$X>0HbK%pxb#0pXgz27ZXpZ89TO$(j5=9v>blenSNR=rO z2lvsLz!io7uFHBcw*bb1YdmM;ygGgCL5yU_Z+S|$lAB|-TMs^(xituWjSuTuOk2q_ z6Dix|yg{$lZn&joV3?_n<34B_>Ed{=h->y4_!5E*DaaGkSmIKO#KexMyw=nby^Aaevsh` z!j|i^cIKC2WU_(2#jbrZ>;I;`-amdfq7f097_I~!JJ~gZ*3AWBfTa#^KR|pE^TYpV z0VH+ug+_BHDC)GAM(FXFWPOrs*+Q;KC5Tn;C#|cqR$X$r)1D-Va*zJ#FpBARFRmFPYmLiKy21TpRKbF<;(!H*N)9 zXprXgb{2JDj(=m5AS-O1``NC7bBXGr$E1c)J*o%=#V}mN#QZZ79^CWMmu)dt81iq) zTjNU3InV_l;gf>zgh!=Ul zZh2Wa5=`C!GvO(B8)EhqR?suJv+fhqap<3>mbK&mUmRaJD<=PQh?4OUcXsxK)$B8f z6S+g(zQoG&p96z%A7zL>jR-3R@px`dR1%e1ix4-dgsMS_M{=ot^H2%aF@vR;Q+-m8}JyJbNB?$xOD;w_9tWVLzcni0d9j5$6rt{ry3p^&$R3z@pj2| z5}EZF*;uC7gDQH$V*l!(RZBY)q5=J%wMLCKn3n?6UaV})U=+lS1nFvNsCEi`KAP(u z`LhGOMo8_R!KJb37;H(yp){=*R%W3lCjQ$JGkzwQ}3`jOLna`bDDdsDP*k{-iMha{c}56 zO^I*A4yntuTs)v-3A=ecMxYS%&AY~iSZ?Mu&!E?HzUoPj5YCwehs*>Z0H>P8X$Jn_L8ZB?7wGY?ga44yOVc}*+`w5{S#E)uV zJ1R!jo3XiflYC(X_&ymK$RD)zJ3TXbENw+F0+3_2Lbn5J?HsqN#L!1g?$Q9*m++;f zZPN=@0Uk@Wmxi%Zq;NW*dwe^J&@`@&Q8Av48bj}gFe_AC83|<_&6Pg>cb#Oq2juMN zR7JxvBYWUb5#jkED$TRESu=6%x31pO(uJCFnQn(*>|^H_aHZN2^z}_m0L>Z` zLa`-W{N<^O`OFMIjBv53LX7_0QOjhUMSe7HyLxQ?y8& z+?6a%_kFeq_wuKN4Wv`F|0-N`{j#_I=acfNu8;7wxGLgc+(me%2#Urm;alioCYt{n z%0{U(h8z~WCMh0B*h?=s9Li>D0KRH^2z9DT+iqTYFHb!)FsxO5D1QDyIKD8QdbPNz zykfg3ci>)J{E<0eb7*MqqH(TP-6Uhg*r0^Y{Z9tpk-+zQ5t6+X^5Z2dOy^kSdl{F= z3|z)O=d$-xDsz*I-=F@Hv7=D4_*>7nT$u^4qQL z7x|!&PX&+ioSTo(={w`L*O);DS zW#w`NuA(5pl;>p=G0{+uXCfQM5;`LD*ZqosM~Thpz2$W=(YKAW)BDM$k>Se7cW!DD zpO-#48W%+PU*VU%=g`%!O3a{CIurW!iHnFPs4MOut=}o&v$X}csm+tWNBgR6CLfUq z#>vH8?|`C#rGl*>v%-zvF~I4`g{wLm+W$cuCU_mAVr(3MIVaNac1iqB6jnwxHofxr zee{D#NOlDRu-}*Z0k?QZHE6Rx;ufx0YA{PsA2;YDivCeun1sF1F7e&Jcd~Z15Tuar z+eY$Vd|?@#c9M&Ts!MV#L9@Rse{nArYHv*M#s1zmhDx)P8JKY$yN9hcii%fbSgN(# z9e=P9+ZW8-rspbI)(i1dJC4{`g+u1ZD}5zPiErq|v;_8}vI1@6)^@Dx@{}skBC}RS z3@oF!=V$n~%s{t$pfn@nJgNy8mr$!4QGm^H!kxrR4WH&TTQ1;XYPz{`jLdT%=dqpL zSUAJ59@?17zAsN&Us~<>Q6ZttSbl zqqYi--hUqUOzR%mMnF@UoNLh7!x5@@&yy2`#zkFoi+aHG<9|m^ZFjmEDA=bA?jU@5 zbCLE;%IrVs0@b?N=LJjr5=)H%Ia${mZLgyyTF-MC26Hcebc9!FS5hUT`5zqEdgx5B?gI`wVPZD zDr}Cq>CM!7dW+Y?2`-B|v1vsY{BjXBo0G~!1T<_7!u~k~zFzM2XQ!+1>}M`KVAi8+=9pOf*_ zx`gnv5;hKTa95|+K1a3{Ro=mmQKAI=MRxnhxy-1jd8L6qN=*N`{XSNm9`JnFDljk0 z$Dd8LuNAHZcH1L=2%;6|pU}lSH@NVYfXY!}UO#a%3S64E8}(;UmajAIyw-DVUJ#-x zEFTDB{0a$a=)?*?2-$3x212GHxU~`vrlkC2`xdDahq}D6xP2MhYSqEW>x?O3h(Kt{ z!A|NenM&>bh41_j{fOP@au>mb3K!&Zz&Lm%@w_U}x9{3pVt;hLL)V;KCwsuWFrbFb zmsP)c5OKs!Et$m?>g>Y6pzyW5yfUw!L~US}e!B-`7H+yHeR70vaZk|B!~oA4>TFI; zTrtg|07hxtGm5E6D58?~c)yTQhn7V@!|HdO&sG=rwV92pc6$l^*%@;nOSNc~me* z8Exp^c&nbwY10EFo!w9~3aL+zWqaC@40Fg2Y#M!o#aJcT2{^!4PjHp0>}Z}5Us2EUh^g){iK~#e-W89_Yz!p0ucd}ZU9TrZ8RD{|J$cr_Zl5x>|hH#P#4lFo5 z%75=V_0bhD_#ja;=O1!HXC_?y(jpJ;c#stayjpSU)iW&aE@X1MJ1+>rB`<6Ic#>&s zQl}-V9IhRIt>&%EAKAB`zwy$e9c^&@U~|-Om^iYE-R;+@yq=1(zpCV~pvbu`&IUbz zrg@I8jCN4PEG2aK!0#odFHX2h{#Lw)e{%~|tg1poFjS%P3-5kEQ3^NKe||Mr^o4E^ zCW+n<>+4bIK23P+>8#^uW%SxUzLN**n*4+6E%79}mGgIa0*Ot#Wb>#nGrW4HnGN#S zMx?HCY2^O`XejuU2;sn_msw5XSNQaQ)qtN>B)0dm_{k%QnX#5G$*q2=bK0q6uMOq> z+><2U*Wr21>WWfKW1h4uYRz8?C6g&xLNM zjzoic)%gEDpm%NP5ck7NjkY}hAMF?ab_~2eZ2wNw9;@^y3nP;E3u;l9Ml-O{smH?DVxGE(1^oW~5&=FT`RZ2&j>7`WY~%3Z_Zt+^-69 zYjcfB_wJU}X-&WBG$+#g(BpftArs*06{biqsn<<-A{cXb4%0wOKPSE|xpNv`Nr;yJXgK_zFMimm4NYCgrFZoMSA zKYSmkP8SvnL0v>(`JY=3#Zcsr`a6X-I+{~%lXAmDQf?P=?>yBD2$ScKO}eqeSCW$vVLW5dB7_ z!h7#lS@t{4$y}~@o@q&ojAT~Ura@fZY2FFyD!|ogR7z{uD-l!tC{4u=iHm(oyZZBF zNsWCucbZ+Y()IwO+~fPuBcWj1XjF8_F&R^ZGbu-_!3;Zs|pw$Wj*pQxh|{r4dmHTnT!Ro6ebTR+Q*yDyMq`fZ_Lk)WAE?i^ zi>kH0y|Y&j8KJr|2eyjsRG4~YTx+Gg{E|{LHz+g@y+Sg+|NRTV?`olJ!!!=$jq0NI zO6b`pajVtt%(E;CCLkV;dTR+^e1)$4qN4r-_n>XylT-b!%74k=ff{>;Wgh<4Sqr&3 zs&D>Sp09EOCU0U)``#3sNkPDHfCQhwg*VpaIiSV!7RA2jp?TKiWBib^0twlmPT?HS zB6o4cr82|p+uG1jY0|T3__JvKvnay%#SO(0t2Eh=f__KWGWe^Pe5JJ6T$84>e(33yC z3y+~}vs&F?;XKo}VZCOE_w!4$G+4jOu;Qxx+wiB+rH8?Jozt$ygi;1Y6iG52xS=;mr74f`PDi^ny&JzU`F09R3{f+P|&92ghHM z=yv?z{8?L%jnrerK(<6ukBv8L#Kj!u0USXoGYfobze)!P%(smUWP;fhL0p!Sjv&Sa z^h_IY0%$v`B<7LDR<~O=Jp0Q(t8%R-4Fn}=99M^oj~Mz{mx3977xad;S;Y^%<6gjH z0E>;JgwroRj?KtNr~I0t_XQD_-LcwZjQkB6qQYjnys)LB_sYhsLn zSRU+pQ7RZ+^5D4@kUHWvlRr)yqq;CR0&1^cZk>7Hz`o9IZ@U`r$RPJ0+_ctBTrgGv9 z(>-=wooz-5uKqdCB!_D}rC8K3{sQacJ{1B1;F#h*o6Na@|FeJy&f-bsEqi~MM2K?k z_8;0YtvQ$fac%87I8!Jf;+XRJeGGcD58tuW_9$3AetY>LcIExtn~!1}Z&ghIWbW3f zLBUFjPblNDAdeBT@xsr$UI6O7O^%Z_`4dN4+| z4wSD535>3@=?}BWFP<~a>GQoW_~JS_he|-^K28+f;;v->k;>f^f*-Mo$F@@BNrx2X zHo??gWpFu>V*1a^M!9%0XmaaDMFb93lpENX;5EBm`Ji5xfG(AlFLdA_#xEy~?Uf>p zCT8i7g0GMEB5;bTn#^&Cqm02Kdxs^Oeu!maVfXOs8DuuO!vt>pDzEutU;WeSJ(Bep z=(qK~zuYPNXE>zdi&txamyHVMWfynX>p4aT9~mFFJ1no#JSf^@f0gr7pAB-f|6YtF z49SNCx_&;*&`;HPCnS}`8Mk?)tM5pHkO6{M4eE!V8~kcMO%r?*6YE+iB?A7eJc@8) zP30sBHOVBlxQen9B5l-5Snl7$No_S zCC3jsL0N@dQboddGBuELb7iv?tk0)$n+p?e9K;lyeirgfcI+HG2`A&ztC7kuV{>eQ zAzshFUjZL^^$?M!nXu~goR|F8nkaWH2E%;{#jB0SKrerWnHa~w ztY8|>>9>!$Tfv+3FB8=G&+D7;Rqt+>!@vXm1L~&DS0d`3Ko$?S?UC}#gw>Fdp*_>D zp0<{(r=&Y#D3S`Xzd}9+;Ic-FDu@$99rC>0vkW1tR zbNq?;O(azvi*66+txS*W6R^AUCQ2yiRZZCMnDZbRHv4h?(8(!PD(GRbsuyH>p<79A z9V&XQ&uN5( z^pcLmoUHxEswBleIr2J4gKDE9rW;#|Iz7+C5T%n8C3ptlAsN8_tmU+T^3@y*NiZt3~>9=YAj-<7Z(Da$iGEU>a&Hk@Csn6w7!$? z`#bMB9cyvN?s6chN*Tw!G+~uVHcB0smI4D?#U3EIue_Q2{^Ljxr4Z3|k9sfE& z&TSWTYVxk-+{FpgT3=g0)&@JU9lYBc43RU*%EC}=!vs|{_Gnv#^hrlmKso`JBpu-D ze{AED*O8ZPDrcfIYh(j-I~I>{%VLB7$AxaPDA;c(u!yMqiUyO8Oru!UhZf6V_eTYM zM9$ncv1WG7DRScTG61uw45O7*_A#D}b8?ro7l!Uwl(R@q_RY;ijr`@QN|94=;u-9$Wfu{ZXm`N)7 zIQ*xk*#-Vj_8fv<_g}gvrl%PL?tcavX(PJhDK^fGyKL+&-|89~f`E zPBz;9rw}OGwFYT-vqwh#)QDJUtGZ$G!@Owl+f}u?CU<+PT)1(dNWv5^dhDiTNaIwL z1Zgg15nQ#L6(-&@jdx1@PwgWu3zO{qGS(xixm0if>PqI247&h()K%|P=4y{%>hhYNk6ZQP~I=#6eow@aj54Y8RKKC zw{z8MDg%o45MGMxGY}M;%>L*cr)I5oF2@b)?%r(EfNV=Ql6`|J&_|F;ryw{qnkdP8 zh`t(5<%G`*qaIF4mrO2>uay3C{Cpkj&GIvw4(^rc{*3qIeHuN8dRWbDVyBa%;wN54?en#VNT+uW~Vc3U8^HLL#G-}ige*p|Fm&C>+csoO}he%xX!Zcb8J@( zewj(|5yNRTb3fO-0;79Ks%nEq%@-(%cYo05X25(Gu^UuLj|Hp#cms2+22(%fbo-}!;KD+QtQ!OOFkY#d}imn2w{)DcGEW+ zy&>$_t-VrND*yH${2fO}{bziMPE##}>%k3U3fv%<_eP1{ZXCYiFeei)_)qOizl+wdjDWJsizAq*R&>zk(bpv*Z6Diq z6A8Qq#4RDkrY%&16gC8?i7 zDV2S)IPY^J9ShOIKms()Gi~i3+oxqw&mm}5B@zB4HB32qT+cRh3Eqsk|FFMz@dn4L zRPDsfy(2D(xp$c8%kxqmCrBfKyQ>JPAsd*m#O_IDYG1>kuoe565mO+80^Ce}{65yV zPiF6oi(5KuDU(UVm2tL=AlB1MgW&GD#n<*^N7QCUA}>xEHyV3aNqI_&(5fw`E&oYP zVJ*an_F>JqhA9lOz$~eN$m#_PGq^souFUf<91I@QLZ4Lb*Y$RpviGwqLsNntj>B>jJpQ!J3j}43@2emd7T6XiazS zGL8;K z$Z#vI@@3}{o#|DSm1S*;iP*K^W8b`fH8te2mB91kW;b`j-#yp5R(#6kMqhL19)~4A zBfVFmWX9QKO6zdz)AgR`kN%9MZd*&C&5KeAB$aN_E4CF*Y55yZhTruYn)s0nWfS{P zpprU?$DCn%1QlE$pszpiWrMJPwfP&v_;|U2H-RdofoJ3DIGOSFWeWcok|J(s5!QKl zhl?2AUIwfe`u+h(wH(?zR;z?u2m9wo-%M=S63*Yk~uEVOenNF z=TEH)1s%VRWeP~2frGp z@j3Sp>FpZ{Tf95eu;1PR8>+iA_`SwGcB5@Z)=<^-a)o%!i`$s@;*RH3to}_uH<^(A zI;YREnql(EV`w4*ObUWg;`LB?7g<0`lrLI8`t23X66_Bc)vu8$=Cm^4d6^ys4IgD` z?KUtoR~O^PCN8Ac zuBtuOq?_yQ+rHD3{n2n>FPVwpzt)7^*;}Wgw;<}bSN1(Y86(^tK-V>cv0eE@2V%6}HbYv})d!5rO&!V-M(M8L{;>xAd zXZR0E4)=#5@4AX5RO;W}n&dUoj8Ersh)Tus{GV%1LZ0ciTHa(TfKC(V zd|cUR#*R9ot4+8Cv*=R;B|~o)u7ehW10RxpR(^jH{wioz0kzuP`rQ|R0zxSg<2MAO zQr)n$gsvt%IT-ec^Nq8~_x1gFD{_shB>nmgpjWvQ?06!*_!P&F1}{FKLo?%T8KS!t zk8-n2Q`CAwkHF@Ke-Izf^B3Nmv(L*O(X5=dZkO`kjbf!=)Oh4G`6Sc)Xttb*6;ck- ztrIfP$p7E)84;5-Fi-@kj2dG7I`H{WwPIETRP2+qIRN)^bhNBYcnJNvrBm(1SMj1p zIDV?kit-IbT-yLXBf;mS2zKKO)WiYNNd|S2eDG<(3mL2q!e5RVq>Cs5#lP{5@Wc;~ zFTZ`%;Ej_1BeiWTcA<58j^mYw7eR@<;({=49MhwAJJb3l3}7hFc~&krNxv&E2K{~R z_3R;j0`J_ndetwdr;D$$n`kt;2J5GLXrcpb;`5Xb-X`XezVJ@KU( zQ=Td8`MyN#*C88CcLnlQV*Zy`Np1;n;%)lpH~VwSx?YEm3cYNrynvRU9Kwgba}+Hz z!IBLyPvlp8b~acz?4folE>Ac+(M!?1zl}ooHGpUG4e)WVk@k_T^yS!@s1M(2iite} z8@cmt*XiJ5d@q(Sx=rufacj|Ak>t@S`d>_+CfCk^Nl$zIH8k?LTR&|f>EcOzc01&_ z9A3S_?5y|%5DDF=kxj9kIN|O+(*?GLeKUrC-sYpB0CirR9jTfVwz{C%VL+nwA4N#u z5AC=EoS1KF@I14RIjbJP^anV~1eMMy-tk&AM<2jf*vUk?xq*@bL)#UldcTm5gojqv&kq(#+q>;)k&U~qVQUStIEk6Cz?jes^VFW*s_{TymE zg3`v?0Y13AdkU7v?2RT*|FCTi4B>Z~o$Epz%8v=oU}Q{-Y*%TR1}ja@VbBA_FFaz` zSe%#npRkQ${`1=oMVrkL!`{|N?m=#|H1Bc#?{U}v&51U$2m_2Z^GlHF{Q_R@l~$V|V1gyl3;;EPUe><4!9Z3KgdF5*;} zjo6A=#Nz<>%}x0a0c1-QQv}huo*4Ooe~vM0GAJG7xI=1T_58(d{dzd z35c&!*Ae;C*8q>_CB*~xJw;-^x8*T37~X%IzehRt-S(A9&YSs5sZm#&1}i

{|Sb^Ovidfik=hxSPTDA~tEs_Al<3RPu78ucF{7pg*WLi(}iI0j27^T0!B(QeRe{MOc4l z2F!q||4j3Y3YRI;Ycext!1JjswRUkIj_aIRoS!V&rn;o1{P(h8?9K$Yh@Xse`_C8Y zR>gcvqo`3Fa5_WP(xJSigxB9*$fNmGg?rfH)~sw@xZ9`P7bII1fM=S0Lc5N#JTJ=8 z==ORHU(VqySyDf)l9SO#0gvE3d&#tgRFJ!L0!fg@SyVm^C zhs_Bc5VNAOZ1NOH?mWTFsLT$gqu0ri@%+g)wxmp1w)>pmu(Pwzj&sOpo%byBlNn_awc=cMW`QDzKL}yOj$L}P`J)r|N z;O@@z51wz%;V`gKXTycK__~qm3T(M1IhgHH0O1sjBjLMVbP=0S=7WHEW=ga(F`&%7 zsamm{)h~eF{RrF49xXPBZ0TDW>?G!S3|eL1bIMOQVTqyw3*wyZaQ<#nhk-15m^=mD z+}K@v=O$J+CnaIoBe$pg)fuPH&&FiG>l6t7lG*>4(L-H+r%iTJPuOrU=d4O)5`W#7 z@JEdtwEDaF6>ng*W^V#wuF)O|MwxGHc`)dy&n#c0U91+uLf{J!6C;|X_$=dzpB7ST zL3QL>&%ME2uj=k`LIl`Kq5QfbBH%{BoXEKA#jY0eL0wRdN!?D_f9R3FU2+$ZZbSkm z&8f$s3PIeG9NRH^w-L}EmYnuSkhU2%pQl{Q5>fSN zPm!Y+R5)wB-|iG1@I;T>u~kzL**`o#Qp&#)7vRdax4T%Q|0*i`W>whbw6B!ptwl=c z08f#}DA7-nt2y;R9w?y`C0Ze8z=#Sv62P@1pI8vvc5TveS4)vK8w8L0`So_?#?ya!90F zU#KNErmTvryOuC-m>NyF-izJAOZ^=dZK1$H7dQ-_mdNHv0ngCYFdsZTRk9K_na;1; zyPA6^@nkNW%J5J5B<+|jXY>IA+#J42Ll`EF+myWYPw#Tcdc!1d&;R-_!=Fu}%+sbH zzQx&S;2COqKyVsVvmkko&SGZt>1wQ=ZHdS8VPTrP^QIUev9vg8wAtSL?Ko&4uBPRM z`-{6H`;ER|TWR(oumJQ^VtQ)=VC3hXFp+QObJ@JkYS3Miy}KQh_>$efR%;*he`q?( zhbX(Qi>q`uNJ}?JcXtTV4bmXp4L4mP-93PSbUSo+NXH-zL&MO`dp#fCKVjya>zuuR zYn`>n7W?>FxE}J@-Uq#6p?Wu5Eem(294CzNq&LH)z6n0As0Llg(LY__V3yJ7`XN6b z@r}3q#y99=ttS<6HT};%p6|7`zcau$FfsT|oiJSv+4wP{vzWDAM&+=EgrHAlYZsQJl{(B z*QNc7eha=Re)2sH6NcG(7*9!QUCVZ{M0tHp?aCTXcuoxtHXhn>-tLV=OGL!TGAw86 z&IRcJ493*xSbMDYrz2DHr3$^>#v%C^S zimFtwT7jd&6vN#-941<8_9F|@+iJG3i2K+^1ele1{*|7edH^1XWH7tR3S-Jy<^-9B zT|~Y5qOBb+>)6t$`^OHzfERW)0{73lKqkMxaD~CuH&LN9zJc%Hn4TM{)v&0FmF*Qm zo0Z9?OwB#|d*4K07{F?UNvX08k&Z=ER!NfUHf@PSl_%m<_nJ9*NbXunME1{yRzh7F zbBy=3XooL#AvY#y2mk$dc@RtM(eq)C|8(tb&0O_OoyOe~1MMRI3C`%a9(P%%XF9kW zquGP=VewO!p}vTo@gzgR(N^om%FpVmY#Z_Qey|sdv0Wl5JRCBg;-6UUI>`qDVHqOE zp))Ka7Hwo{-+1yR=Cn&@;Tm4%J^qt`8++sDesAceL3Joay`W3AHq%DY4l~iGO;zL z3Rj5ncYn{%^N#NwuI!1jv$pZS^MteS9&qt#@ttDOi@J>8hG=bPmz~{DFKpCt6ixcC zcf6dOSvjerBnYDF-<{E&vAo-)aR@PT~Uu_Dj0Pw_jZG1H8j{1+r0e}QziOp z*EYEgb-pgGau&g9Rj{Y>sBezmvPNz^eEr?8-9Kfgz_KzPT9oS~-p9=R->LuTR|+Al)b4cPpg%^4)HT?AeJ1{(K6xio|`lKN9@mXwMTBYY$J|?V$WrV|IJZsTCOwZ$17)lm!Huw&@-@|$@^YKEzJe~LV z-sc-M9`&?V@6Shbd#G6`?biQA8BvkgYz3;l~)Pq_>{K)wR&w*I*) z4P=z(Og0sd0@Xd~s1xtG6CW9Z(78B$6@0yVHxynz<;Y(fM%oi^N=crACmIyQka;;a`JKo@e@s>R1r7`}CSJ6`VwkZf$>4IXkhqn*&F$ z752FU*1cZRVY}mhV=rW7d)sueVldywS^|lA{OK=*6oW|Q9$OL`O{w7pQ*6xZKY`bWO3T~aDmd~W)smEveUn?l?vjP6NGYJC}| zEnCR+K^x~}xv1f{I&0wxPLzSHf$N0F%(1~1Z`vsS5pc0$k^&` zStJ^Si0YY+LwK@DtJiEB8UkG5*_i8FxF+_n%I?VGd&j|OExt_o87rRag2$Vjy0*Qs zQ0zFTfIC3d=x=h)qCoHMn6dcM5p-xJ4xOHww3*PyKb|IzAy4VNNkQTjD?lii4sBG} zyKa8KQMXSXE0TumxHWJ(bIkBIfvCW9HE#16JwAW0_4fh z)k)W`t1{8OQ}EzY$w2Ml;Mh=VoGvYTN&cRji^voUR*>#vyM|r5VIkWkF0)7+vJB47 zw|cqut2)uE*l{HC2}+7!ho;n`yVQtg&=DQ``srgeXPok+>rx*H0pTKT&wNT^tuZwr z$g^K4n<<2|D|3Gl_#&$j5f%*b&Ge_shdwva^Y!kX5^^R5SB~+oPwZXS2F{x_@0{XC zcOcJ*q3QKP*v)Z{teBk_h8|z;I8N2zmsJRz3qDsHsO+7C+v$w@emJ}dGlk2@RMy_xQ)Z2^0hd>(kaW#3Bu5s?a1+}+h@`FnaTDov{ zrsvx(w<(|Ycgs%|?+sLC8K)njLCr$44?>jemGpI@GAlRM`5Rv7hY|!t>o>E(dqm4T zc?yWnM_*K|xwBb_wute&7Hr&!?LVx z2Uv5moQmq{+PH7UF9*RP2&os);XH``186k6J*%5_X%&vbcRf zK1H5rPLH(nd?EXdg{SD63+7o|!R}$ZSKKBWfwun{%Ad0OE6KV-fb$Cg2{Mx$jruh9 z=!_qNCAQJ2`(1qJ=l}o_pu2H*55u@{Zc&hApxec z6^d`8&V0r~de8mEBDwp@AEp=wX3m!W4fT(`=L!ABcYTFq!+5!Fc}ZKVA^1_vp@NZG zmX-fyTvM^N&$8=Zv6t)wirQ7tvNAOj4wNIXZ+gYlvT;8Ixz!8mQfbNLY5Y&*AMWO3 zHt#&)3geR%c?C}CQ< zGV>ru%}$?xP}^%~3J~p0lFw{oXF>YiDHTn=!IpKZ?9PV)D?p^@w;0;_$|4PuST3oS zK@B|23)$_UjG;A=CV~Ljn-o;T?TV4SU3?eDM>{BQv1M>(y7uLG)Fix&r9Qq@*=2v; zr9I4}(!klLTI7;6D9B5IVa7)FOqjpMG`8diMKm`daL_W45SfTiSO$GIl)VBkPl;SR zV88r|;FhMIa<;ypuu+9#{) zKUzh(8S))kFO4qfj;f&YP2Y%_E(4_h#Gc{EZ06FAr~XdXUORDQpk>koCjJ%EQ(`EM zMS}zrf$5X*`2#J1ePI^^LhHxb1?Cd->bN!AdFkUKm)FKTMqLqpCuRYCVQ$B+mzb9B zmXMu;;i}z#2Y}?fv0Lz35^fYFH$5sY*UQ>|;t`^yy*oibsUo zjQ28*XD=0GFx;b9Q#ijou{W^iwnpxpla$4c_xCwwy)_HG*lGWpI8nTT+yH?Tq>^S$ zb1v&Mbu*ka;`ekPi$B&;a^tQ@_E?Aq-Vi-%dyzlP$0%xq;yx|PaG$fq$MZspr-Sq(y5?&!O&ypX-bJ9Djw z3~>$mi%wg8uV|2}Ml1|%h}ON5kPog9XxBir*@xddUMz^@7RX*VRqK~fxhS;5U zZicoqAAyk-Ds@<#B}M@x(!F@Bq8a%;c64x!xZibu{|tv4{3NgZYj15x+B0nk%-N7Wt!*jDXSZvzseB(vUs0LNJH>I~ zZ=S5buSq@dFa=!1xk6UlDFLegIRcN4N`&0SUe}@0U7`M12oDGL`fGcruD^yt8fEtK z@^nyxkh~&kL_BH|&JbCeoApngWw2|P#*W3w(5;avRzqKeF~aYvfnSL6&4Ih58u93reobw1?Xo-@*H z%+p!}KPt6R%a_!8hoS1NoO}OcC_`ENo8vukwn1O{FXOmT5vwNnqHKFtB_6*=#}nj) z{A&|=pOPj>tPsYem8=i-f!oI|!fC&{;MX?|;@~ zj)v&ZiqOTw=+3()^r>IE&;uWTc*8!Ne7{dU_8X=$mEK-57$1|M38J{5E;A>&toTR} z^6$NiP&HeA9_rOP=aoO|{A@-lTzy7A!VSvFM8B&UGE5CxZO#q;C7`{6iA~Ddr(1Si zxQdIv4LhVmT3`A&eqf_pAK5CJ z{&x<-_I2HhR)^gWf>8OQ?)H+Ns^Cr|MfRwN` z(B$pLfaOPP!%Sjk%lN7PWXh=Z@+qkf8qp!vB~KzcZhrxcbH{4m$VF}^mWJN={qQwY zZYC0$jYtZAPgJ`0{IV|3Ng0)JdguD*Cu+4;+b%Ani0EAgneEZ&{hmyaFTEl|Hk?eq zc2kqrh1RRHo1HU}-$qdQ8!B@GO#nqeYwahdPJ!{0HMj0BF&-((2)@@{Gl<~h(Z>Ts z`L|QF>(q^3je9~mfyIYFn%4P>dyka++~$)92+R(_MUk|C958Jp&}L%=Q9^VzXsH{9 zUP2gwNadnuqi}g>Q7vi>j^z9x$)9MJ@Ii~xJ0JjzKneK}2=una{7XRO#uobxT!oX^ zuP34tn(!Mxh;^Vjc*=U5FFuD({qeYJ?GE-%lJ%asujv*gV2Lh4Xr!XD&l!b@@gr+@4j(nLF)$y(u02MQ<|be^&9wwyjH<7U z{90DKy8Pyl$im<#z)$=T3_5X4aQQT>_CS)iq`WxyZ15kJeS_X@@_$5bc8?L^UHn*2 z$E{$G896ik|GIp#E={XSI*Kzu3qtFdK$X;gE4MSkU>N}t5v9*})~a`25PaDhVG&N> zm;cky@bSwveRAZ{<#z-2NL&bdbMC@kvx3rFc(pC>lH9F)YWN=u0F=^)IixkqT#m)e zhm1aDl>nprgm&)e^?4{0kbFMz$BK;w^2%JPJjHO}%lxll)DXMy`0GX$zRzs48E_gc z{F632VX#vg_rDJ`e)$O*?Rk^)tzIgAZ!w!|#oLaARmi$HAKj+fI_Rx*{6+Qz&NX1` zBpsCLK3Piv3^@5tz}E2>Yst-lve$dpD#6_HJk=bxURKRz{`TACuZ7=Gke@#p9|#K9 zhZA0{{FBT^+bGdQHSg5^h6<&>$_K^{(4x<*fn^6FRLGs?G;IzjeZWjcMW2F*Qel@cC z8H0h$<5eIo%H-Ni(5#pZ=>rAJ_*3CqTbeAi3Vn_Amvc6*3<=1WtLxq~5Z^RkCzy(U zQ7pAu{ZcXB5zCJ30d~z`MvmfKP&iRDZ3tW2Jkd8);u1;G)9L~tQ+P!zf0HW&LOV#4 z2QO1C3(!Q627Ff7?TuU@E`$~MYzxrTLJ<=Hilhu@V^2V5d38oeJf*9w_=v(`JO+3# z2GIRax;p)Er#M~2b@e48GXC*0-IYJAl>Kqe6|XyicfdDPp@RBks}R`&YFsI>8_$1$ zcjXk@wuV%d|l%Ubs*Ejhd=2kSw89^tKBuBs!ZKji&}7bAAB7sp~w6(6X22WKPdkX z#Xq+7!RM%GM&`=$tVxxW2{(wZuAczp7&~OyAAU7Jq^MuUt!Ur4`QH(UNztbpZ-z|b zQbctcpAL>(sn8WENRgO6TbM-)WOF-HurHG9T^73|(YHV3uZ%r9It;=v=r~!gbh8-b zqLr0(Py6d}iX(I9yO>tHZTpS8lnq*6!vum*?*2PHwtF>8oxMpLVZodWsE8Z-!U4k1 zv)X$~*w&TLfBp>Mk&ol@)eO`qGac9JNTSlze=%q|JRTab<0nKLP0-OSr6HI3R3L z`J1aDcK)HA1Tcw@bgk9UD$p!54i;W`GfWP|1cvw&Ycy%tK;Jlf5{}9AGUQ=ujk-1! zEHY}(MoQbY<3?0%$t0a_y2wSn_8Sv|SQpfiIk?0?vtksxS#vQ7|I|!NdS1znAmqIPsSi+w4^c5yGMAKXKAz~xvj3e7Rl=K)* z4yft!6IU8`jlJ|x6}x3};648)Iw!@$Q1H`nk0*FOr0Ys;rtOWRq(C-F4E*tQn~iLX z*@OFN%`yaU9V&78i)c7S_DZ2Ee2_nrTR)>3+56-v(>6b@`jx8sKJl9GKrJ_iFi z3lWG4ybU8%8B9 zaZcif0aX=Vet==$b&%~YZRC-Au^|q9V$kO)n5Omv8xKPm^onKoOKcOFe%Mof-?^+~ z833&vbhI#i=FGx+eq|9$=ZM>e=?VJHJFT*RNi2#HH#^f$R|yvv;pri*wVGbBulh*+ zNGcGgJ!MReZ$mo>@G+O;5aepZVv(z2Y=&5!`j?p?oxH`b!Q44xZSM?L+ziA~FM{5< zVjIJJ&X|V1{&)`TkeY*G;sexEbb|@(wW={6)mm_Df4&XPR%_s&S^tMWW8|J@ChBEj zbZ5yrYeyZ4)gCh{HGJNv@>`5Y_G-pX7v8F2s2K&ZLEkDqgy(7P6xG!}1pX#INiE^dChZg2gn~6?%zV!7j~iD?QP=QP%9dKr0BaGQ$`43O z-+s%O?OV8RlU}P_?}0F>%&b{TnyDBG@>lwtnS@`2zn8)UdRyHa#xNYB!R%A9RcE9HjJWM5a9~-a7n<3`!=)B)azl^(ujzKanD7LUxg_6Ea z4Qc4%ERa#beP?9Y`>}t1tp&zldJN5|odU)L64SUI1Po>}Ufd3)+pu%Qe9DQD!K+%J z&TS)nddk5$pr>!dvRIgi!8=R|%>FUe;u91F++pkn=_;vMJ1jW++q`Gq5dvxW;7nF8 zUw?#z?vpYxcI)Z@zMS_ta&`*!>KN%#(mE8Z``*16aUlVN2zlc|DfjT#(lm=7~vS1-umh03Y z=gU~%N$q?X!Syd&C-V08^z8LCD>&PYtXRz9Ez^lY3RiPl+@uY8U_QQR4JThdB}% z=Ic*RQf`1;1H;Q5ku(aJa&uV8aHm(HS08;m?=>bp6k_w2fr9~qlU%~xiUHooxWz)0 zPvqgi;gfNg9d;To&}0mdrhO*#D2PBB=OyV}B*vM#;BtX~qGlW<|gLUrz zxC{;1Txg0<=As+boT}dl{7K;{8SIl%Q z<_LjJ3-I5Ql%u)7;bJ@~k27_xhrRvf(qY2_O}`gZO^K)3Mgx@pHB~N19DL- zfH_y3&lRqF_oM}LpB2NOFcBFIlD@dleZ!6|88|y0BIolv3ge`Nd4&K@=A+*4;q8v| z_LnVjGF&q=kDZ!U!uIA3e_^Vi1ZR49@*JU74CmU-Y)E=$?njPwC&`~I;pt7&i2BO3 z@RRUa?9Mew)VZV}U!i0?zZNvC|22aN*xF(yGi00jo67ToL0o62A^L3D40xl{!`oN& z-r@cWf1D6zawo&R!O^?;h39Lbe}Y6E_2UsDp}xc|SWbobBI9k)Ez5f|+HtkzZSfv| zO07>MKkL2v*|RZo`){+up3t)KMom;y2yr_p;pv+T*rA`845WCFa6y6+O%n1N5~7)5 zF80Og+Ly@%`B&VZ6*8K`B`~p*cxhWPptyM;DeEMv!0C?g+^$ zI#0AP;bC|zb=L}}e@793hj*LqNN~CCkgxbj*yAaudJ~ofJHvHW z#0EB#cYd$QkaX-xC`fj^5ecqCH-!Yym`TR0;?Lx@T_At07-7d`=XZ_1m0{X&#zyN+ zKRa5Vm|kx+S}2dVx9LdNDMAKqsyfi?H)eW;+xckLMDa&SmQ3PM_Sl>ZV{P+Q)B-24 zL|2%-SZ73B$rUSil_?FR)pmNK*MTA)5CfUA6AGYWP-uqulxlr730h?p4#{>*zFm?( zRqX!gEe8!f5;>av4yIqE-hV%6u@mGfJ$Dt3v!pm`rH_$ zQb+387*N5#4M~fU{W0gLZYI_e!pa9092T8H=})>?n9}1FVX~$l>+MI6Sem;r*w&OHtJzMR<{CzF zPaV}NiV|jL`agM)^u*|F|_G#pzjk^dwe(uX5HWKCs{$jL0r$vQgCu^ zRfyi74w#+ZW2u+acN+i$0*hmF9hhrkxLc@)G`QVXZpsssE9{)Jln*`pjJV%@ms;?Z z@0a%lwi8RJ9AKyV`$dIIp;<(4T5KN`wtB1|a}MxFS>>AnaX_??z2aP^w->oCk3}F% z%@7=*p5(v)?}NQM2^#oRc+`dg{>GreF|)k$$>3d|V=sh8?^;`Y)r_=Etm|j~`8AcH zR*4~;M_$wRN;An;3_==c&L=K0y#+&4bueF4E*0wp?HO7xfnL}N~iHK!(hTOvry8qDX(Ua z*q44AmeC~VZ>_juZBxF$t2&pwp4iRD!ojl#W_&Rx=(NGl zcHr2qW}|6q&5DXUW}Nux=5Cl7EhxdCHT*-KCn}RJ4!E&)+6EP3)9+dT9sN+~!ieJt zeXI(5Ns`!J`MC?h&S%WSAx(;B?!$ZPaP15~hmf>lV%=%odBt+dxRY;nHQIP=09h@% zN1o3QKi_2#=>w{sT0m(+r92rtzNCEA=8=`KL3Q3!%kQ;6B3DT>8MWx*Nc}B?5SIH} zhR6G*goX+eysfo}Eb$H4-(S%PIKKHm0D*3pp%EA48x#azAQ+MpN>wO5F*K;c{N0?( z_kT(@3_5zh5zS2bIBn_CGE6hU(dNkHIUCSw9ioT(_dLMfNo68ICZbB6UsV}o1*h)B z(fs$6P(i6G-YdPb%6D2R7`aQ=CkMkMKKR6FqAe0Y?rfme;<)%}*0LA4v~?`MnZ45M zpub`J1_>9}?=Lbo^rsDbrEY}{@Mg9SW!xvV!@FAXpDKyoEuY&e=cKxGWrDyliu;*W z3$aTUys}q{pJ%+h+UcZrMtes!`gN?R)sKslP-X&Z;?7eDr&8?f2pzC=UHf3?-T_i9 z{o3yICD z&ORdi>0-gv{W*E}XV;{8xJ|(8&N^li5S7rs9Vc5DCnRbmHL)GHxmL1mOgNN{zhHqb zLLXN0gY|bpMiFrSJ9g$tbQBriwT4BWAy)|6od1`$2?>I5M7au~mPq?sTR9S$q?9X1AU``M)XcWW11{Hdg;N3rKZB zA{&jqTvNvB9How#iT$xGtJEtloa?JE=HnAj|8hZ2xn4IA$tKD(e4bV^5UP_bI<@iS zOW8M`G-3p~Wp4bxUq|N7L#?2lj4z^4pV760Zj)LJT!NQv&BaVvEvG-y>x z-Q6vmBCnv%Z<&hF!EUd8EkXI<*okK7j6teJlx`xx5Ezwz-|6yvVv~C3IJ~G4#?Dc8 zOCy|<@hrOia=dE{8AWXVV9X9zD0J-9(EY>~^jJyLu~dh5QwRq=?}|Gu_V&4JCabEw zcS)a|8i)kKxy>pMiHG?#&mGIh>))`RT{xSUPNI2~&GHNvQkRmRVV-( zqCiWd$@N)~$JCXu!pH;S(>~PO;wmOhPk)s+ynSl!`J5#HZGm;_Ho6l2CaZCEnNqp+ z9d^jzH4*r@`BZCt<<(*AMOeY~Hf$Y7A`1_?({`*zj%EoR^SS>m0NZ?k+ah3@b~k93>p)ls)%60pB+m4yTQFpc|#xQNU*Q{`LE)y zk#OBYF8Qr5tvHe*tavMWM zr`Q(-``W>udG4S8ds{e}FfNH16_L$o#5t4XTmtLwbyhiq3wMqfU6(1tUOmt2mfFZ9 z|CGsnHlnllC^;0V@{X`o6qA)$M~S>!diFXS0pM?`Bm`h4D%&P@m9S8pLlcX3U9 z9M%7wtVy!PZxj^d!5(M&>f)7qXIY-!jKK6La^;Xn*`3aN3v3g5wB%tUs?}9<$9?b> zAL=Dd6BF)~RNCr(Z_xGMJNjY^+6R>(>#S z z5iV-Ap0SM@rMI(d&;G#b5Vnl1cHmanu*h`=*0RVPD&Kd%`+0v3c+qPP-J)Of^eVFMP`y#Q)*dsTd{`sM4K z6gG^1oJ5zwC%)1ue!3O|7H_)m*2*$)h+bXDoW@H6eR#=7CPoVZZ~?3+L$~xz#0hd~ zcB=X=_pbba1+leSh%)Df-$7^nGzd52nk;X)rv5fPT<=H@ulBvm(VPwT(i9EJwho8* zv)HXJx!zg2i__0j4igkj|H-MBaiG^9*j4?z*BjD*W@7;txys_z#2{r`Gok{BcFH?p zme9yvIt_k`CEE&DTA8b{X-u_M9?c)L*%^ZwexeW4k*MuUw5JM zfB6X9-eckV#LA-;&U!Y9MZ z|2o;ScQ-d0fIZ1#>8SC)+bbn6-gV}=*Rrxh2?+_rT#AJRTN2V+!Uh$8R+{5~5`ZaD zO>w1h$3;Pz6$vN3yFa^yYHywO>KB<;g3bTO=dXTL;7*zatu)f6tYMmZLhg4vEucy& zzy3MykakZXi~vR{OD&$@vxt>qZWY2g2OcANVS}ld;AG`&G^jyTb5$_!CK}k zkQ4{GpPvh=Nt3OJ#`@`1rAENVJ{=nE*iR}d9-j!)xyp+m<-)c2-=H2knt{c`#)wS4Tn zc=)4D}B=RjK54?$i7^c3t8>HXN1Vtv-rD5wq5VwJEpdPX63MyVw8U&Aix$!Qts);Q zN)8d+&CdNig+a=h>q>dM?!!%@w-<7e_6FNPj+g#@R$Zo=SzCRgeYvmHu~U;z=~S;K z!(jbEh+r$%KOlsF08oZXeu(Su=f6m1JEPaEV^a_qFaFJ+tAFc>WH*c^lu1gRx0&-P zNM*R6nrat*;XYX_cl$2rK{f>fw$xVbwdTW z%gj-H!BoT%amyIXk#A%?!k8hSq_zRaD|^O$Wq+`1b11ujVOOs_+`DH`iv+QXkwbL| zoaIlv=|telk@(+#P=w9=@xqv`4x$}QD7kn2pYOtEpP!Kl&cfLem`Nlr5XZeS^ z&GR-(iRtnfX9P4bR$Fr1hUhEa}k5Eniy22s-)D<}nn zSSOpK7gKOZUIS2O-|z-O$h3ofGzBb(ro`Ye*x*GBz+pMWc zI>MUQ&uGVEjHfWiBhspXv&IlXXwosOmM`>VLPc+aFjtnDp?1Z0fB-pfCM!v+t~+TX_M(zF#m>Z@UO7*Z5aWG=u^5h=uhKT1%sF^j zQN;P0>+E*G6#5{AKgnVh?Lo_X^Ibv90g+RXCdlF2hMP1xqtTjhoyz-JEH*bN<;GgW{ zfj&)*l}QX(dp{SfzJIyY*~f10lew@HWD2rNpR+4*-5eE^#Ix-)^agtXN;|;Mqda6MbIx- z6>j#eHT=o4f=++!>>La6x>c;xKZ`6z=drxkTOkYwC*@_l$K5XdFws}g@A$jp-^(di zYy&seCAr_3b?;nW#PPrRAM?F?I_=WKKkc>$To4_`^$km2;T6F>u{RiIz@>4Otap8X zFY7*OMc1INOwc@Be$pPmcT#(^vj*A*+jI7D`*bwKtNSI7%~~NPb9n-eGU{y7T|lfh zLF+X(3!q>*20UBtkUv(9iJj{5H+nHf1-_DwVJtFt0wj_EJ%kyh4HoEvXKlaWEKKLM zPJ&0SJho?wYp}uK83eo#$7o^ssR4Ry6OoU4buq_Wla8`3hBzoQ&+m0d@c*7CdN#;) zQ|sM4yh9M?Z7^cCx~o{G8`6%NMEG6Fvx?tK6g)k=I4K03g8cDV8IuTz82O7b=5dqB z^g|6xE?h7%noI5W%p^Kga6rbrKi#TE9-<3qq)w##TzcL34)cP>I|?y1_F!g4gPN;8 z}=vL*gI@YD!{5iH~)K&5jTc=p+nld8LoqawP z$d{t8dcc&Z6nQmE#%DDtH7GQSVhGlW$Fz|JwA`ZyKU$|wzQRwLr-7{em@4u@J3hQZ5o4toI^HFZZJUxnUo)Ro?*s7%3uoleikvXkM$q8+O47##ibEwq@PE0bE7^CzUN*Mf6{p5@*P1BTC&-2sVZhG zE=W3TXc1Z0Mx;vajR1f|G%F=go|hkgc<tmt_%$Lh z;UAOP)@X#6A=&7&ju~n2fMR=qHsPi?^RU~!aqN{S)aY4~Z{~ylP=qL6N|tp8=s{0G z$r306u}53YVX}XXFvD#w9$cL?d^sSoE@`IEbonT07)kmDrKXg?%GMMJ|g0??PW=0LeK);ksV+hK)KnE3EOY zA#+g8cGoeZPOs7K*>hrg?aiCZ(7^xCi=@Ed4jIs{Q!xec=%PH4x58TD@MqQ}eA<2m zJfBvPfuAGjv*7^wi_1n2aM%9muI7@tIthECs+y@Z(_x3GLz~m*i>oo{-qN(lk+v)Ye&ppOza#;ONO^=pt zMiDzd^RCTo()??aftrU)M_#CvtXY+5;_}g5{XT#7TEKWHyA8WtQOu}HG1x6qHq0hA z@HmX8rqx0;-Jq+LJ6*X4thm=l%AN6L6|7#`$SC#1=`Y1&TCYZj-%vM6SY#&1)0H&& zOFq=&=O%`j=6a`G=-2)}s{{0lNDQ;F0t{I9n>FVVa?%J;SphPI+Xq!yoRJ1ONlD9I zlmlsm%kJmXpx4uk6{cHw`m90hLgt;0v7P;))mmkRaPxjFoluACaJD8dlyK@v z)b6XJQxb#+oGIfv7?|ioZu_^L9}qqjAXYPE4Z@&7Jvup%*NA7aebGWap)H{J(No8N z?YA|%e3tY?z7_NFI@AP)gRDP`O7_I}G+N_T=PAq21}!#vLn0N;|6HWI=zcfH=JBGA zl?NuIrBgX?L#C1~9A}9kw4_=yK5!FTw5X1Oc^;&_=&7xJ^vbQkG+-HUFuOY;zaY;P$O6?L#kAhLYVx8A6XosLKw7uw`O>;X(0`3>4r0_G_aDsl#7EK!Ms zWepsQ>-=!J+gigFHYvtvo05fj?YkbEYUSo=8?d9~=4f@~S=;nmo^eym7-g`fWV3!Z za+d#dgTv6#kyme1;Ti~UC&cWpi=3R{IL5WMAYG85NFh%U1jBPuc&q)#XO}x&kQ(U-0(3#ZH#uWB& z{9DSPt0rwhXNSw@cZnl!pO*sLxqCyX1WEaZAtT^?^o0wa0_NO7=BVI2QI&ALN4NK{ z3h*z7?}|E%oOD+Y9&2$+69ks6v9N7Vsn*yJuJlGFtyY33Y5Zym3aPh2zWfr@g5|x# zgr070 zEgQT@ZDpW!*U-1{m87)*U3<`;PL!1S-w1>Ujn8U7^amoT&<_B$nAqdDOE|Ad?a1n1 z6#vm(hFyaZKdiY=I7Z@}FnaoHWOX8w2_{VAAG*$Lw&>?;^6fptdPQ9vQHf_0K zE(y8SMj3RUq7Lv#W;FF>7QM~<=OWqV>lRcVXH`_J$=e)c|MW|Xxqn(K8hFYaj3wWq z2nHWfq21PgarQi7)vf5v?>f^zN1f5Y!z0K5GV*C?(T%eyi+HLMW&EHp&& zic9hR#oidY0TpDw+GYdo9=8zKwql-W%f>KFsC|%ctaN)`t|V}DSzLr zx`L(V=PlO}ZEL=*p$(@qI&*A3eI`J^Q4|9hca1{TRD#Pu#}aX|pCKz3+2#cVv+H>n zE?2}xx#P96|I5-`SoHJEIW4UB#|clBzP)97vNBUR}b^HPjaB))?KJHj)R9#y}a z1-BbNLM(C#hL+pDAQMXej`v*fq%{~HQl=#9U-cv5brtQueFLQB_aOo+3Ga}`C51{9(;F@@<-5VI6sb4?_KGW~DQ~xl5jElb;E{DZBB*DBQA?hlutyF7=86pX{ zthO~|4!r#gzr2El`uz2UZgtD*Qkd;skl?Uwvc_hiq0f&*D{HNK(3jQu@>5*h=wJG? z_wlrgwHdr#R>xKTCVPg#i9zoKND{zOWchSU0>nUL6gbY7%Z~)2pOa|#oTmCG8-vVc zkX}lcNXFJVWxsmF8Fd#etm7HEHLbT~&)t}83SRCXcfr}9mVBlf{7u>?;C27Qtdn@~ zp6LV}1{FJ7!{2&mf~O6qvfGBdg($+g*XE#ip;4HLH_bFLFMz8BFnp{kdxb`c4ZfzI zU(MjFV#-_+(J;Me>U05?@|e+O0cEZ4Ib0C2j1iJ!|6*beZxICxXLBy&d5XqHW}`Hp zbI<1wP(A`F7jF}~cSkSNxMEGz^^?L21^u_yqL2H`*YVoR-wk{vz+-T1p2e~I@6ube zU>74ZdofEhp$i9YnRg9U2X6E=Qv;UPADO+%@FqQ1Bu{yT{T@c((!JxZ_o^SM3Gw@M&EhwK_2`j%9hEIy0$_Qzp zOJHI!?V-o>)OOuH6e4_gIvHosKsttpF(t}#bHom(axaK zIy{D`i+p#uEGVR`ZO{&{mJuZ|`_1Cphr5Z3OGi!kg@$wmYN4fz+t~1>>S>#;(y$N& z(vbWB4)h6HkY z-3=ljF${=w3`2K=z|c8#Nq2WiH{AK|UHAX2HEW&ozGv?z_Os&vLWwm=|2UxR&nKmb ziK3`Vfy_}mSEACEprtsu4IOGb9+-o-Fmj`Wd)5=g6pyVEpqY$DaWiGylw^0&T^gx91f|kJAG* zn=32&`5JzKTl2sFlz`H&Niw{Or!uQ^VV=%GD!(=>=R15UT1(Jfp8XXBo1v?NXOxC0 zpWPBIN?|cD*bHT98R0(i=I7JmNoqoB;Y17EE`+aJgsdta#KGi4|BO?n5bh zQ%0CGs_eYe_`R)=KC4}w&F7Cs8|c+ks=G_=c{2UFlq73Qv##L|PPZT=d-t$^N^yig z+(Hx_y7#z;7BjJGj_P_8O-^MO$hN&a%bId6h_+;H)4M$~tK9>#{h-~>iXkEF4?b7T znl0!(pL#>YQ=`0*@9nE;H|E~^WtD7h7erNyZXA?oRU1)0c zn$JB>K+Cf@QNI7q()-Hx%K3>*y*Fu5<#Z8<3(J)}xW8=I_^^vEzRv>JnarG171fJ; znpW(N$%ZLZP4m#UR(9xUCVN*7g`s)5$yD@Jg>uTrxGO1SD=X)$lK)&lAX0MGA4enxG!s6HVQ$S`4 zgX5>$qp|Muf3HhWjQjiyJ~CGKU*5~&P%i=I+)iC%C>>=MwV%|&?q(= z8b(AKcme(ka_$6TrqQ>L=jD!ai#ofGs+*9Md4K=_4o1x{4JIcQ%n> ze|ovzuNL+5SFR?b`XE>&ba8`(;KFL6LtzGJjXX<6rcp7#$)dxrPp z5>`Av8VttA?P>R_HC&Ph!CsS#gtt-D@0ye2`s-}5ooA`Z5oRjJhx)}N>O4|#YlH5% z$HX8Ya8`ErfI*r5)c#c(OWGI^PgGyTq`#hZfcVXR!7bMdd&|b=CAmsXic-w{$F%OP zB!tIKp|ep;>J^V3Ipq|&bC~sT6Wr1hL0%R|Un=&r^k>-6 zvgGYPtjn9#bm!#DrM~p}@2YI$z1i~Ja0e6UrT#Ik@M*=^6# zww?5WQ}D~MB{Llz4c&5^_Oj}aO)%>Ln&x^R96U8z-6}m50#Pn*Zjy=mNGSBl1hC&VPJbw0w;=E(? z;&Fa_y+y5XraTwqT8U27Ek4GEjyqmB{&KjLpZ_L9$=a1}GJaDSA`dinNLdO$DW|Z1{BF0Z!9HMkID^>uNe?WD%an#)u?~?g;R} z7b0yT)m8HR-QWE)kkTS?Xd?w1#byRyLdh`TcQJ>})E|rb;^(6-;*T!QayBJ+%+va- z<@crW4}q5K?P{sVKZ;e}52MM(kM#$a+!++Pvm~i(%#XQbjJ@%*a~Fa$k};vk7Sw-G zBrKbg`6=|wx5;e{Q*wL!s3R|E9`tJ`QMmE?jGGw#Z6RH}FG1Js7!q4$D25mqM`9w229y<<@!jIwLj)FExZUtkJk`uvTgjEM$0~=E;#zYSg^O|jA1dDk5(dKTB~9e zml(x`u5}pdE6pdyF$`wLf5M6!{q5}P3MuHYhLrl5H=c9k1Z*pvIFJr_RI2fGRT8Sx zk?sk~WIg>+pOWz!l}k#E_*yORb28 z!>nG!Ofqh;xyPQOWWMTWaDz`UlkX%ModvaPKvyTmc)7(!UvT?+GR@vN^Dn@cl;&kjDJy9-sh&Iu+@qO}Qeb zHM~MAAuaS?8awea-x_m)yTJxus#pf|dU%fyJJ>YO19-{@9g@%eaX7pdB9RVnHj#Py-LAwnM|{ z!|ct+pZM4w4yO%gf%mJw7Z)PuyivY)7(?#A!ttYfeS4MNjLh@?swwrz#Ib0$hIIev zQcK#XAQd*5P-|&CM4zQiF;cn=UM1OD@QAA&$jJ%@3te>%9}f5ea|P`zTQw#cg-~;k zA5KYka=q{;!-o8c^0(=}>FnOds<>Z(g4!b*jK|1DxwYRM;v<1WhKzWKyu+8+NmcxZ z1VkSEL)%@WB7}xNy2X7x;%J^5bp;5_F1pCE|AMJ`*YFLh8k2}NJC}70xb;#1H>Gt< zM%j9BDPGp z3bCE(rl5sPf}9*U4yfaJk0bu_4M!Z;QT7|L^~>zfufp_ZchZJtHcP!`W>hF{eTmU6 z&=dzV2HJ?u9;q{UkZAw4u`bi@gceWeJjGq6DV?u0;XC`kAD&BOZu8Qaq2Bvm!NpPU z2T)ikW{cir2S`MApg?THfYOBXS+;eSqPB@cC{iW;GQdqZ=80b-bKFRq@x-3c@#wxt za&np>dXs+pD6p}E?6S6ZKmNo86hT3r z+nA3y1LU(qEoS-lYIpt#gGMN`F@AG-w)O~4`8tRtXJ@xHf#r|DZL?VuyWG)Z2vt&9 zJ%_How9`4iAvLM(U|KdU@M|GaXh}+k3|u8d{A`KlT5lXv^NhPW$Lz@QhN#j&F)q!RfAh}il*QnhdT}wcLVt;OyBEql zL2|kb?Ykn`F%zhZL?e^E&yf*3`)J?9-!Nrk$8{J9X)_C>84+O-KNxLOR}mYKmOvr;-ZSLmXc|!N-fnnBuGrIPeI^8 z=9zL(63JZVQl5$k=Pg>e5uzZOyvBJo{Hgxd!->nB%1C;QXk=UV=e)h1|9xumag>bL z>!{s(^0C(+rFV2q?3h@@i)u@R;2X;*$EV(m%XVwVczvxbD!pb{Usa>CH63-t1c$L+ zC)xAuKlOl##~Bas^eM*opQgIWgE%6z@NF3EUO6`9z@*G-+@d=XLtz`A!J~;;3BKaV za$+XPldzqBVx(A%$nK~l^+z``e3AWv>s~67TJz&K=~r4oTvN<7FNY!SEyrCCPo9}Z z_TS$=y|jhewKKa)&%m5ll&xY?lG0tCmLA2#u)~1hoC%@6RY75D>k`QmcjO!YqZgg| zwWi7TRNT?ex5Ix6qqx~J8+e-N3E69_c6yaVj5uHNl6|^0`j-?Zp;-Cwc-%7vjTUWXuVSr^Zaz6Ey6J&e*DfDz+l#ROp$qgj zvottq66kGT9sT0)t2OAr`nESzk*X^HANp$nfvv6tCoxuKd$P2D_ebUmudV>}0<2z9 zxsQk9#ob#yxrG@a_cFNIirfYySL<}@L5oi)0rA0slWR7 zw;{t=f$n!-hZn7e69b16<4*}jQ2Cfin%nq0>Q~XblZdCAJz^X=7)mA>7w|VTD`n;$ zgL_6v!1N@WXsdcX4llWAH>i#!&}hl@{utEUONeLfrYeeFo#4+!8<$(u02XbYl6HRQ z3mK)~xuaf{A8!*E7;H$Em!Q`-=R+uCGcxMh!3{NSHy5-~7Gh?AXaCAqm2vTA>Gs3v z8&Lkud~uds1->GM>+%xIkj|@j7E{odK*|D^^`}+N%P*7#N9%44pEplg3m#TK<@{55 zyNq1oUP1R@CQJy9DhpirZF%-b)@JQ~f31qwr!63*r2?7B#v~c-Q>6oJLz(U`h2Ncf z;f>|BMX7z>b&$|7pzql-71Zw2c6yd>6#{c^-S@-SO7+TEwcW6O-#?uwM4 zgnyzGO*euf3pjMG6jJjc%_qq4W%Lu(1FjWr-FrMgnIvAo9UiLch43olX8W^?WC!=q z)5q^~oM-hh-~5iPMc9o7y;+^ZGY2cVxAPyKDgMs&nw)M7dw%UmU{^Csp|H&=kGoZdZ;#>o>HE)XY>zA(X7bnUm_1Ci=fC}AKEs;Dt z-$_N&+|iqZ!Q1mqyn0!d19qRH_6@Tzd)zr&wVH*z`!=%}6R+9}!boU3{(>1&vEtgs zDxv08796yPTPl5L)R3__exqr_FL)624X)A z*QZY7=QGty)*{=|&K9Jax~w=;+(ZM7B$VN>h|ZXvm*Y-#Xl0;*Zz+1NX-8_Y{ic8hU9Yg(8$!PW=hXc);FXcZ0-8e7vKAJwLmu4 zSQq!{z5dnxVM72LFrH1L)LJ-{kf4cbLzm|ZiHJy>&gPMgaYc)fw9`^=LAJmdE8Q8? z+sD3kwAX=1@q}k@*lpb`{0_vLCOlbF2=|=NG9VOm;~J5Ny^7uTkF^@u$;vs?4+*#0 zCgQI-(R8iRku?RW^rFYdI1m}sF}yqsf6F5Z@dGKP>9BWsFsfhJB-&^3Sw`98*q?61 zHxSGY2t!*WY;x0^Jxy{s-BBBoz1%7W;-gmFocjT_9!Av`>TnQmD!9JvQvU-lbwSg} zQAARhXFw)XZ7SqMdTTfcT}D6^0JTw&Rt1bq4y+hg9E0Gt6Av}STNNY_yYf_%&@>VV z0XZvyV=`8}PT@UYypj(R9$`{~B_UnaF!UDamHI5I~2=^4WDB1SGSzU0E>tR8cPm^t1Hs4^MxJpw~ zjr7f>;fmgu`mK{*I;sYY>ZPtU__KoskFU+ydi9iz*(c%XMOJ31y2m4Kc5CS8V@fQ< z1WWBEHkQ_2%e4evR1O|XRk$s&QQgsN;HJXslRo>J1)B-~cnd8?(u5>~3ms{krQ%wu zYq2q{_TWGMqO51=I<{Ow`u&(dsoin zA;T79-LAG5fqpyss6B^&|L&*(L6wSzLhDv~gs{I`1x`+w4nfhke+9m%DG<6p*~fvH zcSW^WxCNgB@vd}5SQgBw>(MV)iTa*m!Z(9>|44dchlQE&y#f@f(w|h$OLj@V54sr9 z%_J!hlRfJTb6+}1>8Ac3Pup6aoz+7#CaYE%dBniSeXp86A|1r!E_$Zwo^Due$l_NI z-J?vd{x%L&%!`)Fmuh5U5h7V;iN`W*Y_v&~C{oRX3A!j7v63Rkt6Yw{;oA*1@3W}6 z1&4$vi`7hB#L+u~c7g|smt&9k=8jVie2GX<3Bltm;xG0|;0&bH2Bu)90FArNc(df3 z3Bj=TN`mR%sE?fDh4gs)T>6Gdv3f8ZFF82V{p;Xmq0@5)StIcfftFJ7s0Yw+L~;io zH^2S=B=rHkL0v5)-hc)0=R*Ult;22yjE|KfH; zA{4r!!a>yCJ7)SM^DawS7;?$)$%*vc7Z~nbIYFahxIl_F*A=~J3+4PFzuqwXCetf6Hz8?ZG}4Lo@`8%;Bt?ks7e!JPG>tu95X$=lxlEo*#hTNn#z)0xoc_CWs55(9Fw53ZH!NB%W*?p-P|bu9LINC8 zRB7!VR_BPhFq~6o;O=ZAfn3il<&v#F=}Jun@wf(S)GqA?w+dy)EDfPtM?X<~1`ewR zUEg0XWgWZXoaG5n9=xyCamstr!WcP{`R3TMv`1erC4osRKFO*gRIzQ1_AQ}<2r}-0 zC&4$~R{#F2QDqWB{oCeO8ejYx1qSC{bb=s@{a=e{Ykz~*4Q2A(U$}Ephb&161|LSx ztMzhhZ6zXiJR=We;!alIxm`U`Z|rM67jS^<4f%-E)+f%HfVu1pcyn3YhGuv=K+oh9 zLD_Q`d_TpnH$tFh9yiJUTi3%(L#l-EVQ&DyU~Kt zAq4us?@|HOgol~l|K?+J_;aQOy_3|z zQ}iu0W!EnStvhx-=6d`^Z}FW$R=sWE@6yp^9lv)=A{_$IV;^XSMWEtO5|PAg_abb3 z?vgJn#0$i1zdPt4q<-d??Hbai@hWA?Sk;T+E;&|(W zKKy>ww`Iet^C~7vn1r|;3go=bi9JgEb`MUbIo3qtl_QIr<}tnqK#Obxvt$ZAF!9J-LDR?O)Zy-7rRKjn#2{)9 z{pY)@K?ynDjNSTYtfV;ge;1e#T);%KNO%$0(_$V`Bi{J7XVn088#C*jBxbuKLQ)^n zGM%uqmao_ueNSV##oTOr!Fk`?@Fhl6*Sir1OLL;CtJI~P?>nQPb9;fAkMxflg#;sh z4hSkXYPdfA6f-^pH_Sco5p|kA(CybKgicr`3iAY9eXbJXsMv8;9nQKMF+R<#_80+w z2BYZ4<8g@1e-!CVzfeMa<*zFEIiR z0CtWgU*UYx#fa@QKis*Z$t9-h$(kak>uAO_sSOg?m=)duVX>Yg0s+bYp{N)8#bGG zfEz>1TF2PYC*H z)bIhuPnRwei0U zV`MR|M{tGlB{duTxisf|VF7_*Hh#B=$|Nk6$FdXz*&xX;eQkP1tJI|1nU>XYrmGOK z*;RCthgfY>#dJOubh^1D!Vm#yqN-8g(|9Y1bSNtW_6tGy$9ZUKtcu^FVt*q$^mGfr z7H&&#jm$|8W5_C;%#SMLWT{^|j@Z3n{36rlb1(JMI&f3(tIQ`-FsYH%Wmu${_w0s) zs7N9g+YFR^d+u#dLcziwOpe^eFH2Ir4s_Xekx!1zOCh)_Xa^3-egZ99@7?(>uB@m? zRF+NEVZF{2V=v=aaZEsqGpyNA>;Ab7@3Bl`nI?-;em8wl1P{A8JHVNi+}&v;6cTGE z9pj^M;-20i1Bqad(Zg3Yf|Bh}2F`y@vf$zIZp2Sei$AfI{hmUSZ{-qG7}<|;r&n>V ze^fq!A;Z%y#b>Lq;^!LqStAk1alB%QL9`#+NUDH2`t{AoDN!(*gURPbeGJZ`Z1F#- zQXo{@3YJ1w3w|VtNU1;X_=OT(>h*})y~_op^3d!jzZz?1a=9bgbYzcLDL$KFA>Ec$ zZ!i2Kc3?d>#b~wrju-xfZy@j9xc$NtGpd2?)cR016X6#(3BzT-hGcBQMr@=EGns`# z@U=IO9t>-;LNA*8B6L5f@<18RQYdEy4(D}q-RNXHRTl}NY-x*I_#=JhB8aGq@q3*g zr4;Zl^?23vDXuvfRz^OI)RC$ygJaQ12R>L z#HlhDA1q}Xj}S9o>E&`6FuG=jy^6ZVti|{~`YHAr&yU8q>a6^^&u*#;A90KbxC2M& zu8f^F+^&*Ek@@z^_+&s+lU5^@z}t-+VOn#*01D6*Q}pg;Akg$`5T#pwomq{PHlfAZ z+tNZSA-c7qLWo^bKSS}9DBC1K@46H(r%&`KkWaF4NfJi^(YHr4q%aD5!rS@i4AmPDRuY@4?quJ#4^D zEseT&TKg=kfZPTa6{p;Eq#-3qQR?(I!h$;__MaQQOGZ(<+jezE5mYFs8r%+SE88}E zVB@AA8lw-!MF!GpG+N9gvwZh)B-V7U9yxg!H`s1N{w|)e^eL*-VHrcTVyRb_4PS*E z_fm;Qf`1T<1PijC`|}>Afa%HDwI-IV>3|pe@5znSy6*H+x9--~o@dlYFWjToy2*I> zccNq89sSkRgd%zEW7eNgZ0n(N@ZaJ25>)O+#eTqWD~Hx&h(>(Ft)_Q-xWgR@PO#0q zX#H4L>ghJUne#**oR;gjF#5%3z5;PVZbi<@B}QA47vE7}DU|8(bV)=i|4~mfk@sg4 z_Uvu#%sZ3_xpHdKw+z0vPpDaBy(TBy$)T&NV;QAEGS z6PxLNQ|l-&kCfjR0+HHC&xjScoCUB4dk8^|FS8iFD11&;Ci>AmG5Wbu&%D636;Y>_ znWLuyt%Pd;OtDWx9GOKRwn|W-wq>}zr6q(Nc|wFT)VH?`%d8%1 zV6KiAs-q!&XhRjad?}3}2!4j}BYT^Wqki>bUq%eQ1Oo#d*I73{^_^Ac| z=C2%e4WeEDneYDD#}|6X0oNv&XBU)7YP6(0yp}7qLh-eZZ_?cl*nPe4A6g%C=7-YA zQQDu?5@LfYa>Z+Y&q)!=UCmbe0~@|BK3 zeN2-&@tl*qvTT1~_9r4tH)pK&Et!qE}oR zO?u|jTihX_aXmb4)_y{y%1_#z62t7Hrs=GgNcdc0Gh`mQem}IyDe(L#$QRGS=4$D1 zu540`(q<&+>hH5uJm|$;P_H+la|uF=iW>gt^4v2=*of1{(SO&@xL(~yye<`yyyqf~yC2-Y@fC#auQtdLqPcZj&@q(!Lv^M&fP)`DO z(4_CY^5bu5ef=dD$k^*Z#Ny4Rob1l{brut}kVLlur*?rJRTDOft9wbYOjQKUx0#rO z3E1!#3qSdVrITn7@2Z@{8hNo7Y_?LN_~_t}U7*3Yrwe?eEp(-eAJ9@j=z`MiNUe)Z z@?1xZO`^9!Vt9bN0pqA}j(%w4|9r7%%=CL`G3V~f{Ksq663&<_YkTpk0Q0ddYz*k# z1|KD;IPf&rOm`*hVBau=Y{K7v=ioljXyi;}J7R~s%YEr6##s!7SN|0{>`BUmA}yYn zlfOO}eY7bhDXt0Oz65LoI~No^t{5~7c&Z?rC|Yq{9n$UdX5fd)#T*|``yoA*yA&pK z+F5c<;7N>uy&s)IH#D)Di&b*aY$qe&fdAS4kD!Z%y zHj~Bk(-0MK6RayUwv}GFtLDKqJVyRMJl#C8Mfl{y@|Ho=~dK#F_{f%YL@_r7I-c zUJ}z9{Q$dx!i_a82*x+qD>9Qa;OV*BJs>jeF)VFBc0N=YNZVD65vGs9xH@c8*h-TT z+nFNinJ(vZdqe!KEk3}SSNAuzd+kE(IQN&b6~YTCC2KiM*Qc5ythjf1uw{RX@A(S`*iOTZNPpXgbZd z;xMi`TUT&Fvzkl-+`N||pkc_rCoN#IMyQH=oBp$d&+-Yk-!U`^-K?QDb@U$|%#mq* zui>_jwOmZbWRk?V#D*V3%r3Bi6Gg?Gwn`7AM6Sybcm1C8{rZ<~RG=NtPl}#1NB(rJ zuZl*bfz_3*xO6!%fdI41)l1VaPpGe4puwm0f5`AEFRo4AyW};e-y|ijRgiY5&D5|g z^@TeD%m$f@Sx)IwM7)~V<%^_1E@9wdK03&b8)KSq%*|bAl4ZLY+uLRTs2z@lc}VQj zpl*RrTkM$v6u3oH?7*XW)Hb;`HQys>3wR3|dvmVDMf%{M$EPs#zU>0>Wq6CiXqL4n zYZ#|OFrJxXe#*EoY8^FQ>K+zBoTsVwp#~$AgsJpYP@;%NoIbQ#S)ys`vwt~GH6s-~ zmhf-`JyrmYW#zUa%#>6aiewTq`CKg_!hpxlF8Pg9z<>IayC`Ste7UXO+o=y8&J4)* zeLlV?4R-je+|9T29Z}7g_1ZnosKCH#!>mnJ#eE!wB^T-3lSF(bC`N5yYVU(GMO)iI zmOKHRFu^)a0k}E*jvaAG{!`5FrRlpz1yy71VGc0h4JZH2i%uwk6PVn|f;;_g*Ry3{ zOspTG-L59*m3f+A(IEYNSKfor8M`nsACGi-7XFSVB5(*ovg^-LMZ1b=Tn1C8%?N*min152($+i+zj4U5Sx46^qMM-X?v_GcFfu0WA(=#Rg3=nDb) za=RGHgDFj!uF%4OcJnb==XZ+x4&+(#tT{D&qx7-loi@_2QtybFOby=vGd}GK)8h?n zHhyotherhz6&a2MaS&>YflnP9Zh0)H+kK}EM%jVLyIGJ*3fn}H?m$t#ze^Tp9ye4 zWq-(SSY(KY-D4hbAcd^^Urh3u?Zw?QV|3!w!XxT87Ud>XHKFA*guXo=n{LU>{d>S| zbUQX2A6~~B3rxX1b9P;uVi6k&92rPmg(muFblL9BRM}6p9VCP@i9ZX}nG@edF5c~{ zzrGnWPpL^xbL{gtS>u@OnOxo>_?YGyzu!WAHV_Vc$6pwrd8Uu7`bo&xONX?jx+l!} z@5pW?A*u^g!SNE|P#Q~&^XU2UH`M4d zSXqdc6Rm#qY1L9p!+^9mnPpCpA}XiaC3gT0ro+O@obnKuy%JE%X4eB;+MAlFiiw}d z8|f0ck}2{nT80qFPqe6^m|`=L^c^@lzH0oC*-AvedZocg+UU$l=DGde4x#-vn#{aw zQabSwhj%FOdp-5irY#`V*(EaB4ySj!fhqaW z{vb)c4n)-CMAn*4#)k*-k!Qtq|ye>9Z)znMlkH`Zjy4=iCK@(1;N#O~m4k#bLFyb<9hJ7?_$&4M z!Yl22%bAN-bY&xV4lM#l>u>&1`m4IF!%4JM$-OWF)9wkTyC;Dc&35i2!e8ddE+$WX znJq*Ero}=JBRy#aL2Xa>wq`8wc5s3r^O&yk<>s%;tc@2NKRt8C81T9A__K-J z{O)`nXh+zxJJL1vqe1*GZAY)0hQh7T?_ruu422SW;Qo=P@^+^gQy$=kr4(GSp&LcW znyBwsLVY9lA^WZ+y=IqYkA68}S|$<+l_<6DTA}BM2GfIx5f8ft&k`@n8zoy$Z|JFi;z7_Vvm8%m|XH==sAQy4D zQSf`PwG0_(q?|g9Ql}1cq6PO_81XhM#%KLiHj+)qHoB8RA5;zxwetjTSfKs+PHEnc zc-WY}`{LL(foy8kgL!wJ!J

)Nxo{v*B&%+`N=<7T!vTmKn_#TqwrG8I@M&kCH5 zuobjmOOU4=S_=$w?dLePozON&{%kzP94oXn<{rc7QAsGi3;+Q7eCW$7e$u3=W()|7 zILRP#lx3vv-qL3P_)iOTQ_>_R8M3iPB=qW_3|fT%lyIA=;DSa&7(OWFU1 zPzY+Il(FkZo7TOD8um?4hM`n+(uEHErwkEZ>e?@xlWQ))NSleo1N9=9%R}f+)KP@s zerBNFH)`D1#@8>Sw;2mXm8i|{8M^MDp3L1Y3qh@A!sZo&z! zB=;c`XV%3%qB-VJP2OwW?JT}@hiu`SM5331rX+Vyph=f z6r@RkQACf{0K72b6o>p6)G#s=VAMgqJ`7!;^Qvn4DYLY$E&)_)wrwq|eHr39bFlQ$F z5*Lx~bf`zx*Ah79AdZ!EjlbT&=|x;~@`RfQVgWPigY|C&ZTWA7*vrgp*+xyrtlG9* zUR^(-o)Z7#eDDEXfG{A*phQ7Pt(V!VC;MV4YpkRKJYZ9lOTI3UNHc37(E3VNb(J#&=q4Jx1&nF1l1}Xoe0AK^Co1&*nlZX17{^S}p@xawtR%)#J$~|gF4yCt zRveEp0R4H99cOZtL#~LvdicB0Z!lYt4&1kA4IJ%j0J9b$9V`%JB|31n<21^?K4cFS z^jqSlk-XAs->jud+cn65g89aXH1S4)o`&$S$tEIwvuVa|Y#tWc)TG@$O7TEhChtzQHD@6X3*%VJs5h2s$^Hk|3RzW8q?#lbED3#!|mAvg<$#IXqkCbS<> zt}=#%1z6n6>LjX?uGiIb?p%$im{d-iAviOE@|zp00EB1b{7}*3K+3U+RD@AtLGHPd z{Nm#vii>teo$d22ViGNF>BC!v3kd`g=7)p-JV%AgHrQo=BHazs7DjH|bNzH^w2np* zN9HI2%O6AJZ=NC{`I!igd#Sks&kKMZ`)r^ZmVU-d9%oaA+OMZZT_s;=j@aUi1!SDP zo&J^Jo<*NjjS;w@zoWBoD3dEpThwfY)Iio<2h3BB3{>cKjo;CvSgHxmw3snu3x00K z!Q^~wlRJxZjvJeT=W}El3>1EcN$vMA&0Q#Ta+zSQ{bQ?qCxY+GA5#GUhSyySd@OjH7BsCiwju?lU z;{_(tGL{BwU}$}V3$yg!VHBv5`{V-sKOlw1hot+m=(+Mp=R7{4ZS&LylDAYDPT)J3 z*gM&s|Mcj*xus;<&sd<&uL!Yc#AB?+?vP!tfnMdInf1fzpN1&1m;pnT#d^~n$95(N z{Et1_taFNrM81&_*fdmt1xi1~ra|JL^4FX3>FYxf>^|LF%$N7d&$L0Mi2DUlQ7wJp z&SD}z>fa>A%u|91F40SAfG$Y)nS{BB7P)NYQc0%8oXNfWJD|6+c(kV0k9;x#b1r}D zbmuvoeX?KaRI75BNvtHX<{-McQ@u)-rws6J$R<`saHHdzI6#iyv~B7!6Y2F>@)KDs zfs;!YiM|;KtPDsyU%WfQP`I_E>Gp6WH~^?;lF5h_O?VHCjK3F7wZjBO(b6fFmg##0 zdlgd~mGnQ!uRlM(O$*LsOA|h0o$L$Xy^uJX@X^q^w6;$Kb3zV`=dBlB&m$dk5$5r{8b`8%E z%FA14qgc0-LQYI8Bq!)Om%BG1c{{O>qkW|hZgsWb#C4sw+E7EN12590z>RyjzUh#_ z$=;naR==l{YTs9}#nEGbigpA2P#moTOaQFl@}~4RI65LZ60uM(fT)zOmskxb%L7HO zpk)p?gE>lz%@bZAIV%W3d`FnhsHCT&$MV|S3uShD!sAcpP(AneOqOGJ=_%EN;34|Q z;hwmts;mBHpYbvaNAJZDGNOyEWoicn)E-P2s^FeQGp>krkQ9B^126BwR-v@ijcrCm7`JTzp2+* zhpOvmEg8P-RVIbcx#=eHZ_+&uX8W?)+AH9^Q8Ka%Lb?Me%V5XMrKM&)~K(Ve>|8~oYbZ&>5-hYM& zZ7A1V|7g~=l|R*E)m}JE8a9^GvXr-!9AV&Xfj-NRc)X-BOeCi}w|;~QXG8w3dJ}s( zVS9c03*ue_qhU4`;iJAhO+XA#brLi5m^= zdH+PV;__qsPaUH-Ikimck0N>+Ya!sUM_}mdMANfwZ?;yr5h0b(${q6e9l~b35I34M zQUzM`D)C)EbLUspE}#Aa)v$hf7}AS=PnS{*M_bYULCj-Q{0AHR0#y+cA^FR`ESOYn z1^YEx5Z3vIpnZ#0OYaZxJI!j}9(A!WkZd*onJ!{X+M5`jzG=E3bZnmf%D0KxyjJB1 z3WWK2L^JO$BeeZiRT*4fz!|E0MXO;(HTE@pPu1Y`L?fQrA#(M!#VKXfnz2yIzotwT zURS0HvXl3MhTjA0SE}}4bgnnEJYs=<_djk7h1(pwu1DVzIsG0AsPPNyv;l~Icza4# z@Dt+U&&LdU=sm@9X2Dqn?Q>-!G3s)vG9UW)U!|&5_QzSWqIBA<7f*bBo&v4aHZCxM zVgC0`AnXJ0n-6k!eV)*8Utp9~h+c3;E)F9}I$v5sA|2V5lo`7nsi9v+6e(FA*=Q)9<|hnoV3VxquyoCir!H5`G%hx zGMIE3y9G>LE^)#^(@r|hMr^g+aA9SaPcWNcDu z;f@Q~nibM&vf{Ea0KmZ-hdSIXL)BB1d9XZT?rB*{N)uoH_($HnL)z)=ZvUrEaYwl1 zAa6tJ=&BkE$ju6U>=YvLRjYdV2=m{-`>~AEt&(mR?xP=Bn)-a{2(VRX0YHPG)!Q07 z-U+Po4X33*JGW}G`QrX`k8!#`k@IN>f>xdhUSal$Z$!AqT!a9f_b;Na91v_y{109E z;aIAo6vZcz)k0@Hj^Br3b%lvH>?acA`0b>$Ce*mbs^R*{)naBJ&)U3csz+yb%!U^q z(WICp8wS0CJRwD9>o>p0zS)F!LP(3*k|@l)+_|o^ zmRgvjH*|f08vEqeX6us%57G|1VJCPSnJ(;02l2?nL1>|I_E`umh(}Rq`H;o2#c(+B z;$%una}H^D)JLyYk=}m*tDUf*L_lTpozqW5{Ak(Dx$H_y#Q#}lyft5tj@q443XU?& z0RC6})Q@-2M6)%?F}HB%3gn}T{|cGn=2zXc}JIadQQ*PKl%1N{5`nlufP=+1sf`@&~zxS zadl6gd1NX+{1`gv66HP0Iv)}as|dON`M zkLNzBKjq+*Bx+s380Yl4Tq3O@sj8?XC0IP-Bjvf;6)bW*ck((nTZ;_33?&Fb8hCjS ze3S#YU_8=Vt5kQ5ejY=>(Vh)Sax%Did(K3XR8}U_ygGxX2a#&S$9?Y-Bp zt7^$~kODy+I@|rlaY7Zh4)CLYnY<+@Y7I=;7{5<=LWn`fGM>d8k*UxHif?k$7r(Nj5NY6lpSp65Yu{ zdiJumXr5k-6rfZ#QU#Rr#W$Z#^rbq}*1OAZu*)Cg@|Dbeedqy=zyTxm`CWd4Q>Wc2 z2f4kD^q+0#c=|se<7bEY!FOI9;-~4ex^CfupEidTjT3n&t~Qs1(ym!E^><7!IJ)xg z7{wP|ss2%=Y~Xp=P2@P-{cVx@3t&|X{PvPK-mU$-cXScrq9GPHiG+GYDrF<(X0+Yr ziJz-zdpV5xwG9O8hFGO&tlDU@v&c$io#!eXI{YsmCcb#2NT?~7Psp|I;E+w*JQQZX zTpP_x%!^IF-1Ory6YF5yBLv5;tc*qlwGF@3-ZN^`cgPoyd>x&`3PH;VbcpBY4Yz~I=A@}DI-m+>i~elfMpg(9A3lS@=^ zMDv*;P@(hL#e^VrHHQoRX3T_W4p34XomB34Hnvb6YjkIb?%9zq*%T=nt-8R0@0)x57(!Z6(8XH|P&aSZgc>R1yCRVbmNmb)=6kLsZqB+cb+{uAFJHuzfy}l4wFB_B2Hm{Nmb`+bOxiE4aUG?G+ zkzBjI?NwEHpox53H)EmiW%94U5sr$6z`l5ZJ2Gg%Lc1_7VpiobFWaD@5Kez z$Oau#JjcDYQM9aLd|o9{z+6k7Kay+^yUF@X6pcuom%t{S{+AMU z!UF4c+BU~&sq=EXY|x(kT(zRn`mv`RObaC!UF7r~yTz zzQF!=fl3{7YaA0eKE<{#k_`sOIPU{hI`u8nJJ#D2jdKNdT=R{wLRq+ubAYfbe*&zb z>_ZH;17OPQ5Y&NDpAm!YeDhmDKK#r>9Jty&oXS|ga&-&l1VsFBj?ah}6QWsg<->?w z2^YLeAK5qE{~WQq4kBIpbkh3;BRO(nl-K4T7;Z#!#9YAr^KKv7-=fh%~)ZL|hdK2PH(=!1`Jl zuH&)1wlSMZMH`i;4vGA8Ylq1|C~=I|Vo~==5#eiY9{hHgE7@;Jda-5sNL!FRqB%h6Itz6Y5AVBn8gzCg<5R9k zT)rZW=?u3?e=j>`#i8)oAsg(FV>AaPnuF3UbKSlfhZT*|viK;`91_>4`Rp`@%&3&v z+E(^9ZO8eeFNFE@wM5^?^0{z@K@5U;&Lm#$K~POzJyuM4rO6|=$7nk5X87x6oPQ&Z zDKAA(hY{2$eL;z>-b4(GDf_4r2T(;w%goZ-%QqSC^Y11gZ6%r z#tBA^9j%ShlKdOlQ7!55s@XHVr<(1(LeYrYv5f_IT=R_>4Hkyu+>~!eY;2$FW&mI= z@gw$+@BX|k=I7cZ9HM~(I_OY;!o%$`KZ|2B=Zk(Y{xWy!U@<2JLDMmm4Y=#BOnNy} zHW3>WUt~+sIMn8%{+tI>jw3cY(?uL^P0Ve6aGyhLoLO;sqO4Uk+UmUg@t<7hPwPv$ z@^az<%OxAc$LI*IRy4Zmyxjj}gbyyer{uVtDuE3;^;gEfCi-Lpwb9K6MPtoH7ysf9 z2l)1HFK3r*@YW2ErrVC)`xK3L=5XYGuD3szY?lqba9o=+&P=(9vMEwDOjSrlrL2(+ zuKTQ%OMD_6c`CwtFPDsZJ+Miq{_^O3@G9C(*Z<ihjfUK2g}`>5`Y${Lw&~QLb7l@W zI2=$kE;PEit_r}+_OA{o8Vz}TKG-T78AAL_F2163!@Rhd_Q7uYihW#ny*2JOtR+4!t^Q}UR8~VT2;sTQHW!08kDtkf zki7T<7`vCz{=SJR7bgV6r+{;LYM_Hd0U>m&2&x6ZLw6oQZCyNJ$N6*!Y|x2RSSfeV z!%sxGeBRAKa)dd2N#g2|z_2PNob6*g%mg;-oIjE1a9ug?rdW=lC)Xj#2GUc*n4iwv zgHU==(6I<7_whzhqGE~3$1#b=zBkBA|8^06*~ojL(2Vva9Tv?&iDzn~a~7S_9F$Vd z^VL3!@GX>W*R6_dmkm~zTTUkW3^H4;&sfq4?oK+t2UT%gXSt0e8wlkVmMYS6ZtOY^ z0G_1d+-9ux-}_{Q=JSbl)hsrsZyveUeR0yA;rI*%rId(%>WurQ?sA8PkDXtBucA2) z^EA?HDirE9`(QF#e72nCz)iOm>K9q%ws`ZkOabP*Um4={zZDRJE{a<DL#2JRf7nl;N~iKGI<0j&>tut$phWSqwB^v<4-j zY5nw>=wI26@O&5Uyq;sG%S=$n+3Ax#F1Fj;F6?O&Q^kxT^$z)GUJK`;E)l)<2@aJt z(wd{#=TunTyqiuzC8Ua&em{abHBrhI^|J}Ji9ERcHm>yaa7{YLuoxt8k4~sf%qf}! zv~+F3=!mdOSx)<XYbA9+qmyL?>FWLfTu)>A_a;R58b3B5~3tamI#sZ z1zYi%#EBC(RvhO^vrpo-+4j}eN&4)j-KS5}ZM*G0&vu`-Y13|-CTW_>v17-QZP^k{ z-3O_Il1LCBcn7dEuNN?uWW!X|hd*&G zJY&IhW)#i7Y~CZ8y#0dw-XNcN(NFI4qx}5OLseI{7|Ucwp29DW&wVt^ouEsZ;b9Yx zIQiN@&^2kV*nb4)VBTwP` zmy&K7&!j&V8L?t;f1(TX)mZ^LWP#gdp7&_4g+P&AWt)ABbF;jBeW6llSGf?Ub-2?Q znCJd;<1(gxa=G-~p+qay=ULQTC5q7W8sO?=rzYE67RzPY3qPhof zuRwLKr{(+rF54z5v<|M^u%g+skmR9B5`1}9fNR%7^T>a(l%ap9WLOrrjT11Wxj`h6 zqV!&*`DVMys;t0_;`MH1?^99nEU^^Eb44t~b9B_rLf;1S#ocZfZ=WE|uHu&k&wpi* zYiAe!mBfK@zqeRf(Bd3GRM*nfB-k_h5-oGkAg?__MBS}42VLqvg{Zzc<*|mY2|=!| za?(=gVc#oxG+&(f(qB1N!sz(2B##VXKX9F@4@1@4qOk_YzL0Fsv^@{i`E-p}tvgB; zyzK&qJybET7CLb}Zl(G1^in<^Xm(pTCw=DUOwK#k?3pxQ@naeu!?9JN{*Xe;`-udz zl9A-m@J>~}d~D8hn+*&W3#$|-zVUs3CLEg-ns<*8oP#QXRJ%GUCrzh+7M0QNyaI0g z#837MduR+aQI+u|>n}I3HaUSVkB3D27)nnPrZWoC#t}?$jH7X^S7xk6_x1}OEFYy_ z7F_;iNM;WYoA}&eA2l(m2#-EUn(y3kx66FrNOK);|NQ698_W&5)D8}tZh5>go&28e z`O{UDN53v1O0G|u=J;poR-di#a|~gAU-PYR5AdUZ4aEd)PSD6p(-uWecRc8l1&xce zinP$Kl93glOBQjfGJo!{?~a?|S*}QU`vj6K@OBIKeR_oEs}^2+W{6|?66Pv1uYOG7 z=k83*-9c)9X~9|{;ppjOUH>4G7@=Pl5UxJFeFDwCii&|20{H<3^xWx3 zM!9x!Vj24{x8Kq7s?I`$YyN)k8Z12`bI~KYn=Ec!m`7)t-_3X)&no&Y_Sj^n>(V@4 zCk__F35w}>t$gUNqj&t{@0)og$cy0naxqJDSOnr+XD+00lakBCRT3Sgs>P464+jBE$8|=i}B*+ne zh<(=)ysZLn^Y}CdyIEgxE?jZ$Z5L>{B{U9Z6I^S{v=brUTCT;C+evfPxeRmF zLgFXrG9x+t_bkt+ zljb^_y%s-bDLeIG*M%X6riy-frPDNbX*Hn`@MNQk;j~V8e)7P;>c4-9EG%k z0AN}W0{fBisDP!;Vm!b$n9A)c!678N)hg?(D#vHTY~o-H45E4V`B83MoA~T}@a}{} z%uCa#^e*n|>bWA*7GPund>7sgdbW5xV_D$Nv(umb>M-3ViI&u0_;*(G)zCDKfc{U!O$>+>x0}JucS{4cGDlVzLM<2+b6=(9Kh?Irg8f= zg@Nn67tAOJ~3K~#Y15j63T=DIMSi-xMVB9_P6 zkZ4A~uBy=g5zC{AkW8OR zngaxt0;JK2YW4aEx#evVtR5?2aE%|+@F*+C?A#pvS?G0z%dobrB`_|{lN2YOzz#?N zNtGE4et=6kgczBao_|#;%{NEM87pCM{B_cRj5H)8b%p+)Pia0Kj;+e1%kqTl)^QA$ zW32#qy9Am&4RcjU$T>DEcq}HAFK)$rB0hr6z+ka57ZvBzp+4qBG`PZ|+_7E3y(R;# zbT^}aRD!8bV(jt#^q*+u7(j4?N`O%1JAa{y#%} z|M!*y69-=nJ&JmU0|k{UE}b`6#Uy6Bz@X+Br- z-QfN~k7J3H=D?(@UKYaGKc7TqneSX6--UOA9+MJpVIEoCekWvh!s+t~(-tQQmkG@d znmw5n4@+$R%XSJZ7T&GS;SaJJ`TofyHsmGJusIvy8ki!@0am@5kMB%BYwaonvY^oE zrz_$(YVYqC(ehCj-cE5_Y3|sjOvyaI6^1lly69s0UM25bS9EWlqpIz0S;Vc{JX)B~ z#h4qb>h+oCvzW8Zb!IEg0rFO8NcjQ!WI>)?4UfH_{p1K|-kj)Hk#1MGgPXJhUsOq6ufnSbumG({Lx{%Ukev zuB1Gpg@Tbm>T9jIvp4ck{YBE&FXI<)D=dGrpO)+thB_r4zEDluj~b~^+i&}0NOeAf zaJlin@(h9EJ&5YiSg6^H31qL~p!NZEJHJHY5B@(!f9>m-FHe={!?M7!UO_xCMqkvy zXzg_ic`Gz*xf+i?>EnZ6O>UIs?H6Hz?(G*bja7*}Xr0ga7Dt}KhZhnIX>PD2aBQ5K zW3D6YD#1JaoJUG?OO!;n+Et@DlR+3=n9nqpE;czFOLS@O$Ws9Za|R5#!#R#4VI6Mn7Z0fiM~ zB}lz8qOk^TbqOoRU#I1i#CUD)4N-mTlMkwM!=(Q;dnOQS7OGRu6e)}y$l{=So^?-@Aga3%mzy!QcXKSKl(auM zi0|7k6R-uSthe%-&qa=X3`RkD{~C|&Z3GQeXF8SFtl|AX@Ar$s^HrVe!nZ9)-UA@v zyT3qkzm8^Kj-y1u)YL(RIE_}korJf(3qaz({t4=XADebvDjTf0r^)|Z@AOmYvGTz? zNvz!z;M3n8nEv(SKjbf0TPU{2{zTs8h)X^{d)OEA`9(6Fw0PL*kLxlR7|a!w^)pL2 zt=fX+9zNS@)TP-9efbTLZv6XVAg zj(p{=vuf`I#~gegmo#d$-3$pj@A&8RgJ9_IzE3NNYC+ns1e&xGtnlLQQ4+EOSY8Sp zkK}zLhk#wha>PsD=HR4h=h{^&uUXkQe(aJH^&X4rmfJ30n=zIeL@`%UDEp%JAAO&_ z+kJO)41NOkq%_pt_urgqywtF+`j(#M$ zAIF0VZH*P|FRQ2WycN-VBb>LM+VC=-WipaB9?vo?Gb+iXkCosbUOd(3(;-~b=bd}I z1j^wJi0WP>c?97aM0FP69fg5+`cR!K5w6ksSY!i(`v%8)g^|1fBjabMM`VF;4I*4_ zOv73zQfW^GUhgnFF1~?#jh*J2ZcM|&2v;X{uQwre_F}FIRjPmgToUcJQXbgW#PIM= zoW556^*8phUm3z&xSF;XN~lQgV9=UG|LGq5ua;r`K@E){(!$N2AGxBzK~1F2P(~Nv2&5FF!!O(@+026&#Lr3f1Qmu-R2U zy=4@OEyxgc@~DRnGn|mj?D_?X$s1xlc@V^69Z$}lo!dI z?KJcDzoa0UU@R-ZP+cEoTU7#u8m>1ICr!U(m4>%d&^#_|1|!~M&7OlK52D%gkmUY* z*b)Z!6LT4bGFKJddNa^iR6oaJEQw{6cDyRhV|cRY?On(aQ(|Ra9(`#_WqC`J2;Z;AwWz`smgbsPf;4`6)HI9~lv&%fmqFpe-C9b} zbQX_l!`ACySh#TY9U^dWH9d{LBu_lYfOdY;{Cv{wqhuB{qI$Aa7p^`eIds;w!ZLuj zYjF)|1_q0byey5YB7^euL0mg?5UwE}{K{q;6%9!aow(Arr(*r_NxU6`;OZ=bYsQdd zA1QW~y_p(~QWn9i7BHih%610;R(ER7Bzt$_e{Rwls}8xS5BF8d)KZg`#l`5Vpr@P8@%!TMuVHVx2nq%|bX?c2aF z5zMeLkhBxgHZi_OO7qCP^U?eO!?Ivl7HGXDE)1Co^hg8-OtTWhjy#35fgiY$EzK7z-tl9Kc;}froc^#hhr5$&TkI;CeL;4;G)n4vZ~_gX7e z$1S*5FXszoe#Y8|=%|Ft`__=&HAEK~JhHVP_q&NSU9m7Yp4&gEzg2dCep&Fb2S=%E zHd7RlZ(g3!jXOIZQQgEUBZt>umfWk*TxAR3i)c7}FM?N>_;XPKA5E;pbM%Ra#nuQk z*4gQ0PCreHK-@;tIQ|)og*1=MP>-ZDYCBCQ&4I8q&zwcm(#0UnVV=bK-AZ%E9tCg9 z_!+J33f_*%Z9g3Ui(`qrU(Yz-AJG6+l4P`C36g0- zcn=B}DPtuhX`o0lrr{BW$7O%uU^bQ`AK}=oQ0)sKjVvBft~xhNsV2Wy^aC-~X`|)z zD5^6Z;fil;fq}vOgtto&%*vkAzJR%^8ReB- z92~fbR}NCKs*dJsU6Z7_j$U;h*(5abwzpqUXd7eKYs38TKP>}ppEIsE_0%PaE>dF6 zLa6w5yUc7((D3$$D$p~t0(3@fi`BLO!x2AH3=9@KV|un~j|gX`>oQ%J=8laD?pi~Z zE=4|j*f;6wAAPKk9P{<@&!{e+KyUi_{9zw&|1|OTFIWWVjX)vx6_(E)_Jyk~bzy(6 zSn_6hRs zD#b|}-aawuN^)Jcbgc?9DvL?^=H5<$B!?pL3~6ol;+d1_OOqEIXa=EkL~x$?WFl)VqV1g-QsR3MIt1Uqop~3 zdu1t7*Yu)Uk~?seD0uH;$8+pb@U~67F0v6QfMcIRx~DXJU$k_Ol;%2n_cl@A-ZklD z0Kl%1Wi+Z!)7n%63YY?S*JN`(m}_Yc6AfX6E3_Q~8&VOjkvX4_fq?>Eag{&KJ zg~wTMhoC%NruD7Rj~&gvl3-Q=rr|*j4qc$}`4{NDl8CmWjn<#_6U@qDsH&fYZP|?Z zyD2;A;_YB52S+aP(a8i>|4|ng&-Ng)ddaf|=pN2Tl6x6>`p-!G_djRnW4}XNeI z!?9lB^10hrxxJ7-%16ISV(Vu|u{FZEo7P!1>C_JtL)C||mD-Lxg>yHpIPw(o(lnMA z1SZ7<#1n772rrL*xxKzEhKEfY9Ir}WjF;jY7(_BtgHc_k>yOXWgw$a1qvw@Jo-B>V z5att9jF11<##y%d%SRLQ1JGO zDbifO|5jLR0Rqz$I?aVNU+MHSdXM6K?F>;c^FiFix$4}8aCP3(G<0b`OA_f>ClC_w@sjCIT1slD#rGxxRlX`L%1wew_ScU=OHS#-z0B^M&%_d z`5PYQ@)hr-=d=%XV%9FAWtAWX8hCWaN*dZnQ45`juG>e@EOiWNZeVctX!Z?A^27s)Yc(&gvK;?)@FiPHd=pnani|2)tODp=@C?C7Q!`zB#-iRnV0$x`Vc#}QoHRC z=IZYe+_{a4?pFGL*TWu{M8(!r>Rbb?&koSl*-7&AMQoC`v%U8!%M${4yk{_d>@m|;XQo3Iym;6* zsafZ(h_%3u{IRZAyl+kj3H14r=QH7Pnc0%CG(?HP!Xo9cZ%Sj%STdaukCf?#Fkf0k zp8$;%<&HeXh+w%5dL&C{R3+tN{Vs^CFo*aEBFA`+dL;Kc-z|2PqC|~HD*SkcC5B{) zH$F<5^qgRpVEs)$$2R2g6Z`2mJ?vvuoe6KBm?X{j{&oQ;e{pwLpL;t6g%Qy&Fp-;Xur!JFRUNZI&oiG3 z;t`v&f00Iy#G81;*TjRFe&^2S_wRJlJd)YS_nEj?X$~_-!ORD76X*9T&F_Y2F|JE< zM~Oo7m9E>q-t8+z8VyZDm*&$k9FeL1gyN)LxKN9oh>p6CA5!rLxrXb)uy->=gAwNDIjyk{AKjcMV7vq+5S76XIX z6DiFd+ZC#gj)bMTX5WOUt|yq4jwE-Z*|#Cdp>bQdLO)0x_FUYSove8ANnBfU@z*6# z?7xJ!eTajdUb3HU<ykNS`Edrh=l6 zXQ1@fQ<|aCeA&m1;v&+sPcXbTpTt8Z%$e8u*kko%HILAI(L>umcdqbETy43l7?xO9pX+%0ML0HPp%J-E+r}^1H!!$Y;wjB% z;#RUe!N@sZROr!C`j{O(Zbyz|3vryCZ?;B_?Tt%7*c^xu*O3+G@gTbC=v<-4v|PGj zq1|O>=aYWi7bnJ2&2DC6mZ0V|ta`kQUt|`r{DBUVWi#FXeU#0Q`)GP65lQZ+JZS*( zLs{n06@de?z_DK8#H?sx2(D zt>zQfOg{JYdDLSn*RH%u&e;nbS^0HHScbW&j-m%wA+B7b`ARGPFa0)_WTEzu(n_#Tc^*7}`dNOOawjQ+!=_;Vw)9$gw)&PyGATz;@j z!R<1K$7rKR!=16z#`XhFKPMuZn8r(}=#}kVvY2yGq*t4lJgacC+QJ6A%45X}l~oh# zso7!k$CJq^w{YE&#DDrh3zY*F+J6{Yj;41K$sL#E-aZkQ=FJhuO5w+QCku7q>So2O zTS#o|;Nm|e&)It23eBEJc}AxZ?P74pY_hBL$b#lMJeJ<)^pl(#T(r?3@mlWb;#1~w zEL^OOKySrdUiCO#L(uSi?qg{V3s{`1&i#;TnN%Tp$J2PkiExMHbfgs5E6=448L3MS zKjzLToi@H@Pnkl?G|fVF_LV6#M?CJ>p|I6^h#SEan%f)MwC1z)3|#?0j83f_HxHa; z|I;Z93LBS?*Wv%v=V%mbu$((iV!+0jX?W2{bLFrdQ5_YTW49s6Q?uG9bzq+cN%rF? zQfPUvfBb(Vrp3TuF39`642HhrMtP|eQPV!@G0mQhaJ7%$UWOzqIEoZpJ6CgXw1E%b zazXYd*>vvjXz=*)b_j&a%WIz>LX&oK?Z+QreqF-bA&}%g9)Ed+3yELmLH`Nro=Zae z-SaeG=wYm9InO+8r8@uP>`xq|`BFa>FR$cRm-Dz-<|F&`FdZw-a3%Zq`NNmLNA0ye z^gh3mW>-7j5y9Alhe-U(KLfy>SxVKry_7w?hPEFcMJ@X@32*$ba7385UEn|X1}6Q`den6U=`-Y;UQ`v7mh z2n+Pt9>nR-i)W0A+hqj^m5#C3 z8erMZFlE@<-oA02B=;NA{60e$-uKE} zOe30RmpP{LIaU?n@vbyC8iB@-d#O~zjYX!gxm-+vQQ&6GVV@LX9O!dxd>ngi2Ha|q?ssm^r>SKp-jBk%Ke z36#SHi0Z!SCShP;a0^uDDum0&{)0i9JQLM({U3!+LW!Do)ZI=*>%>^8OLG88RseA4 z6k@Jw#@i-v>{dwQDj(IT?0;}29_wZ_i=E2hA>8Tv2@YlAc*aljej7RM z_1G?T()k}A#oxA^iu`lDG5TAqQEPGiUhfviZhSE=#-Ey2oYa(}#UrT>x<#3yJ8s1B1K6Iv$e} zFKG@CkOdaI%Kl}Vk$1j8DYmOT`nba7Y71_cdB%$J$no7^Disk;pSRjoKAeZj>{wA` zS2-Vph?LtAt7sOTNKsUL*hfdTg-*Ab)=>#hwFRZj!q{*klB|(aW@26I7_NOulqL3a zv(v{X_b9wonMh)ub(q@!|9PxGxgMUrF0=J&bJbbQgQ+LcfMHo+ z`BDbGCr0mSeY}0*zOQ^Vn4VY&?|WgDEr2ghS1-j%n$KlS&FzR~v(BZ`2y`yFm*drV zNpr`#g%c06V8!{}FkQ63q{kzqxn?g8SDuRo7oxUirk71=1{x{N0laMj*=9$KxG*VB zRPzP|F0>UT;kcJbX|CA|kmLyw>}?TfS_zUQBgx(2b#brRf^fCna-9}C(b7EnKL4wB z625a|%5#ita|46hBV0aI=L!lmKc2MZNV0$Glgued{W98yl5jLsG?LtdW?x3xV{57U z)d1c$!2>UT4tZ2!Wm+0twOiPn(v4kx6SsLcZSS2zTUCPOlX2`+7)q#P>`|4o8CF)l zUr+a!{+^8={wv~(=_J?woZ?jh>Vge)x2IG7+1(5ky^fl+nFmJR;+>rT#>SE{x_d_` z&uJm+&tBmD?`W9oP9t1hIJPP@6hDsnLM>8<%rWs0={q06-*%eDhBOYW?ZutG6ZOE; zJna8>Hk>@l)uG*p`WgbS{5c1&{J+$_Q;TLVraZeDZ`*QK7G+Sk;n&%^w~LO3Zmw5b zC_9i&b6po&c1WPRSC=C7$YB9KTN&=iQ%D?z-g*cagg_a9_r&FTmd9m3*Fw6z@^?Kmf1(S`HxmqmzgV9 zEO>iDjSDOx-s^rDFKNCnM#mlT63u!u(^$@LsWbw;-?)`DPqPK^$1zq6mO7QS5(Jb&Bi`(Hh9%jv0E&hYJr^4Xgz`@cmx2^H&w`>4)CgLbnP`)l}{BN`6 zYr{B76_kT7A*u&C`Mm}-dm)Zp3Ll*_v9|v>Wm{HaUU`BWojU=rUi~qST?(eMbhMQv zR9>*s)%GOr|B-_EyqO^IYn>0HmD!G|Xf4lA!&N%+oB(6*J}|HR8!&V9tdcmEX22S>3q z9^pgZ8Y(i+lK7*)qVl4Z_tU7QbEL zBl+SvN>epJY7TpXneqBS&Di@M2U_LYbO_tmz*jPFOK*Gi?=%9UyhD|&-K zC^jJ0yniGCN1no!Y6}m=VSabYHoH3Ci?ATLR&C+KBMDS2!1rh|;MjQQ#~JrZbfeN! z^APi35EA8)*lsZnJM!ZHIa#bkjzy8x3`Z+ zHd@&nv5$DFExh>b)CkPn(?hKIN-6_46}0j9zIgm^{wpKlJoAG0d&#h?lxOr~InoNi zcm8(S%nLV9wN8%hOY3uLFqyahIVq;ozuW!t3*Q);a-SnVcAv$Qb9~(K)ZzH0Vi& z*^4n(ou2Xe2Z!tNb_z6mE|MIQPFisZQisg8u@bsRswSq_Hu-FbmRb^S2pWmEO|Wjq zHoCPnNFy@ee5x8W@MzftmnUEvUiekintdz6)wH}9+Go7&0y@wN+u zCnSmeWv^g4dlXagL59w}fwxU?`Ft&E_VXmP|2?FCl4S><=E}RLDOk3iEXOg5%t8Dq zb?o1w;yGjH@!uTc^>3xosAkh{Zo&J`7@Kq6V|%+yU~4~vE;FfsZKa0%-6Z@&muMKN z;GqLIsr$#{0Ep_ka1RU3UQGGwX7aK%JOzoE{3GFbDF3S;!|b|>cSu6{qJv=PdaPG| zMxN8pnV%%#C{Y-)m$9O;jm!h31aAI2yDc~Q&dry2HSN2ceP$#5ueX!lCF2>{Ov_cz zthV=To670c4)Ll4*XQSPnc22LVnOssgicu)@huTVR-9Kj{Y$z6{Z^MU-)Xj{5tDNN zp;wld*vDvy*iRa6vCkNlX17O=j%tj`f7iF&QrLz?!-g( z?>qmEc3Ubfl`tX;8XC=L_GPs6`&qM2qc|Zzz4sYJZ!O){9W>W;p&YW1?pOJpCx-d% zFP^}g)<|YbG3_@m(%2CCp{dymDYv!Ka>@gQ#_^jkew+;#&(f&o6Bx>btYjp)3zNSK zQ~NNaW@7#EX_VjJhvjGuUHMNT-1T^6!4RwH?{(4kukSG|3qWA9fF;_Y9K)IE1SC?ci#XAb)&Rj|i`EeRTVX&TGMBV*=E zqDLOU8q$0+x}<7!nb~Sr$(+acDVE&oQf4EM(qJZZVXlvz4KoN{gF8bP=8r2dy?2C@U}UZqigsEA8{JGsJEk81Ju z3B0|bO!B;J4Ud$DxvFt4SAW*1PCLRSNBm!maCOYfvKScLE3t@YneKQjmg9b`kMW|# z{9Lcg{hFKZC|EeT(p)F7!4}HVEm82wg8j|}K1eM>xVpkkLbc^3NdD;s zinmpuC6pj(lOGqYF4PT98n%`3kW|UK-r7*r=RD!quFUGJyth^0@*P6?<43Xn%Mmn6 z2%2q3f!PTpZ>K;xyaQ1^agso@XCcW$lb#ceJ9|yIid2$)csm7>Jc4kI;3!gX=d3a+ z&J7Ii07s!h^VIWk>lkW_*+CKK>vVOFZx z_dpS+-~Wh`{12!+{s5}280)|<310pgre_L~-jaE^Vw8>*LDoI4u&r^F>&qm%bDkuz z9tLlIi1PGHu&kZWe|ZZR|G1HzsT!-3gSU4;_Zn1=GqD@Yf55%n_VxlOd3bfax4 z!TI&gH2(83G|LXiOhL2fGVopp`#xTTCt(X^Y6D$Qj&c2}h0_oI7UmNlQL(C)<0D0w zhK2|x*uo7%XW~vP$sKtLZyisJc|%WKg6M)|p;Vv)WZD9Z44XLU^y3-d1`BEV;zeYW z!f27Tlp2Z7RRxgV6x3kpP;6HxRgxFmRUR8}@Oi6ob+HTH`9N>_c`dTiaESbfKb$CrELTBved zJgOp}vC^{Kh9vtKl?9`vV`R9xZrLbKv)dSZyp)E*by$wo-^1G88VF4KIi3s?FfSdoI% zGj|n?cY?P=pgMPjn~`evjY#tJkt%_Mxf~3fruqB;*!(b@h7_Fraz{#YV3IVS30<0N z_SH!8Fsd^L;TjArdzV0xM{yJ>c)J9SB89qVHekLuwehHd!Trp>7m8@U8XD8QT>>@D zi6`5Hx$Xw)GABEd|D9m&7Z_-%#@u<9pv8tXGO=$HYYs`IdurLWwwdaUzd>Q!X$DSQ z;o_wgj6Jdj#n;M__mYrgAD{o1t^C`2-(=J9Khh)(u-jILc-BP!cb3!K)rD5JkKw=n z8RF^{Uij)}D!U|F-uB?%bQqHoL{elVc?7Ay8ApYJdu$^uXI#AadxNaJ(!tTL?FhFE zG2o&+zlny9=lRC3)#4u7jpt?_=KhP^thZ8XZ$tdsM|7X_;FSdgQYb4;!fQ@OOD;ro z&wK(_mpi%$e<(r*Pe){Yiz82Ac|mL%h(@y|LBrcGc*yBzWJsEI+)OMO8J~CLcIuSH zB$0l6~y^-i*u0q!hC0s><)3$P;jlF7uSJBri={GTZoo(?2O9CD!Yuk8iOOE7MK?R_hcksUH4{Z`wGC z@1IJ7R5R9Hi6~_%+aDdFuoWsBtTeCKM&=6|4_uHL&I{m^1;Z}$Eu}etW-q|{)AN|m zcyVl-dR4K3!QF5#`*5`2zL#ljva77h3dFQYX(V?VVK-Z%MSQHsNPRqtm7tGxHTX>8 zf2qa6IM#)#%kQ^m`H%~bk8M%&W zc=V2>`MshGbm1CAb><;l{o%*FT_XI~kmd#kQz@{v;z~M%=nGx(Vre_Vf$U*C-J3aB z_yO95Rrd+V5&~UnkhGsLu?ZUBM!Buz&bNUU2&Rt-ju%B~R zQ;~XGx$)Sa($bsAn)GZo?x`h^{Wu-f9?I7>al*5jfB20K-gs*aX;?-ne;(0zZR$oJ zN3R~glYDV+e<+3^*45|wy!7RpPicND)~W%P6)av+JXb_lq3iN%u~nf*{-BBeffM-y zZXs0k7}9)hh?eFhb`@JzAS}vXer1Grew8?@X)UE6rt`t`hkcWpeNM+>-^O}|d68Wu zsU^PaqmNs$kSJwNKNs&XW@d`uNeYsZ8l+biQZLJCzMMpm6`rV=dbQH0+W7Sv_WB;!d*V&BudX*qQ>whMk2j0N^%?zjLD zt`P9H3Ti+3KN);n0Vx^b@}QYZW*yZs9nsM(v&A$thG|%x@o~+*!iaA%FaWfzC6wnj z@nP$3_C33v*0VKK6x4Ea_wTTwJkR7pF;AIpRq4S4eiZdeXO7RnA-X=!Z4Jz7f3)lhz=mQjM`WEYJWytvn{q4k89{!1XQuh8nHRVDC~s^f&;-7HZ*ux?{{(Y?C3#sI$7@QF zmbH<4K;!U+)BHuA70Zz}R(|PO{HI`a+X`r~ASp5ht6RBT<0Uw{hTr;TDsNwWfZ*0< zf>ko3Ups*Ll$V@`x3j+f1gYEB;an&5w47fr4?6lC+HC_ zdNruN4LW5Jj$6=gFVv=@kuu4VuW<23e6ogPNjxq)Ud-qxd?G8#ZCL?oBC7N*U7Q*d zVh|gyE%BZbks0P)GhEp+7wD2^rs~F6NTJzEbA3#ju0pllWu|xhK3!<^%L4b>RfuW@ z%^n~lIgu3&8lE2~1CWy%G<{`ITW!}hEq8%Jad(H}?pEBrxVu9kxVAV1cbDMq?(Xhx z#hp+f=$B`{dH*GuIWtM-I{WOsWUoRMWS6_CSto`OxRCM8#8k=D{r;s1oRVC}RD4;I z!H;rSFh0w+l4!Gm1?%+A7L=))E%{zk(DDYdb2 z?9x3Jaqt*H$25QwHIaqGR}LnJ_UWpAkQl=f9XT{xmrB7#P!4zkQ|&DFjWi5_3XTnq_0sRw&L>PKEqVX5q{+P zc4%MJ{S0^cm$F=MZeD&CgU4)rd-RycV!!$YKfRbtWc*#cvZMJn8a#7*8K6M@u{*%& ze2T1vf6vhRiphXj+|XSaKrLZP zAq&bSj7*UZ4MWxS<2ZTrF}V&wt9NM&Gjn>Kxg36u$VZ`wCAp}vRKK8_c(eE@Sb%6K z(~nffsfkWv2x4+H;3YlA@!g9dNBH6(IzS2WBik|EumW#?+#S>D-3`&p9UH2w6?3!I zjzM_n=9d|Xme`aQf7HwNcTt!avmub!Na!2OMc!S_`{iqG@g%pqvA0^R;?cjF+j_Z!;a`s{kqEVCFcnnQ@qS4 zKE^4H22Av{(f%r#Zdr>aYzK$0^FMs|m8jYX!wkOG1a05{{2+`d=SMd+^(wlRA&^a& ztE5KgiN5O+>D~G%H)}dz(25B@MRL}OyZvz7?Ld=rDs; zFxLOkjVJ`MI-3EF`O9y=T)NMsoYhJN|E9b<9S%}|HGS2c2^p+QF%-+Yg%N8Teh*@> z;S)m7{@Gm>(Z0uGLN5rcKm01S?H`89^@mymHWlAV6plK_u+WX#Qxmb;S7pZW_IoPa z4EY$n|H8yi`XHG*vVZW8wRQgR&C=!sIVa?MV&pUs49bd+465rE7_DU3&yjf|&#xr$&l#JGNV<5e6%u@dNH69n?W$hya@7*!ha8E> zixet+&~-!Gq4euQ8$4v37HV6OvAEVE?MpO_YR<<4HvwA$t|{ne`7N9`Ho-DPUWlZI zGU0lM|1$-?D%!Q)y+WB0Br%Y*qqrZwh}){iPI$g`afPkxU%IT;xLWId{dNmytz?-o zC6P1E8q8*xK7lA=xnIw7SEl&)h|g3|7Vo9h_JpAZ1@I8Xr7!uu&J$W1HLB>?I@Qcd zKW;Xl*)h)jqRksQ#G&X9QKMuZ(7#SZkF8wmzvadA^9L}^jA!}Byt}&i&MBN@(@i)@ z`Qj>hK{r<{C|uMtWcl-OI!ON!n}E#P5j;?V^)qt86>6*ZRT{2uZMni)-%X1k?IN60 zhRzce{sR;3ihUZoG81Jgjm0jWq@Z@M6gwwlG{P%4{j`awdp-0DL2%Ku+5|pN+PK0T zo0og?JKiM+P$|nt;J=J61lgujFXMYN=7v*n zo?T&pK0}CD_F?Px9;!!V*nYTuv$DWVAbJ*E_=}jgwxW`=Bo1z>uH{_Gt;sFL6laz& zKtA)Q-3Csud1&Ngr?5VRV>&m%?Kpklc8W)6Z&x7qbl<9R+lkc0GzSE*_~u$F|43-M z`8d?ew7v}n$!7=_JQ;1rK-Azr>HQ9cE}21Yv>ZtlOCD<5uak}~8;#{ud%G|=;{5)^)htLPKkv23DIg#CmKw%l@yn*k|_9w7e< zQl-6bc3*q13RuV|$s?{-D`w}<(m9cxDt?qQQ_%piJY4A1Y7|)M;LDVy z&QcF3rradN4W62*JQU)O<~%>IT|k@;TX(#P05^=|AGdsJG0{IdkjC_bELjQ<_uYO{ z|17$4z>KPLr+BuTRg;TbJe5>y2#btthg zuEm-yf((9$=VSUoEl*@jNOLYgKfx`awS#y;aIZ1W@>wnvbGCkgI0w_-^Dl(@o?J>N zm@k*{I5PmhDzGnaqo&o|oe*b-qo+OPN3T(L@|En5D6})e1a*6j%Mj>$m7{ zvcsGb(UI;OFpT8*yr}i@MRRB8_5!!1e$qQDJDO%2d{u0rK|BD9QKjK9+YnhN-9oO< zv^Vt7{Pq3sFRl-}s^rir<-{jo08Ac53*6&TmuESm^F`x6Uk|E-Ico71F5ZM!V7$?r z;*&()K(+B5a)V=SVtcF~9N1Ib9Pq~Ff6OtE<+~#eR>2i7GRk|ihYi^fiP3ZX8o&bu zLhmYJ7$zP5=Zbh+Pr)d>T0^?;K%bslI=(Fzi`CaO014b-B}kDkS#P)Hg;!5P4Zj2i zmh@TvQlV5*p^Axx(CMaV-#KKR+69AR?vyrPK@xh@)=cf8OmU;x~f5FnlOlZ~h-A2PZqreIc6C)!E-8nX($x)(<~X z0^pc?a50WCqkn+$suADZ7mE1MQVyV+eUl$4cnM!JM>uA2G0wC6pK(^% z@h6FahXS_MfDyMpLR+q8ZHgd^8~tg996t-tF_+f)ZGgW+9AynH{=9E|?e`&wYaK-$ zS-b5l15#jmv+UzJ)HsU`jVYAno&TG%a77#|bP80Kn6RI{7?QaQj*HoxE{-?R-KnH~ zT4lv9W8!?M?5*2Zyjy8WXb~%bxUj?sAu2iuD-_>$cKH6X*Q|Y3KP5!4h=H<{d)8s6 zY0*#|YAHSJ*T1k2C#}r52FeRiyCz0$ktu;D+KOH2XzAf_$p=FU$F-tYPIK9R z&Q-{6HJAW-Y%!#WyAw7|*CWg%^F~E#PNPdP*RY(_)T+5f&d3xZeo-1JeHqGp=PJlJ z9vXj{=h=E#{)Qg5t`ag?^w@pJrUaN^p%QX$3(18E!G4?y|yVg1#Gyw9@X@&NHoE5 zi-n7BZxDf(p{?vxLgo}Lbsn#h+-cSksI3=xAt+;25_SBObShm(u&p^Wi)9JWd4!qf zq=`{$VM;)fFOH+n^1(EjIt>y83(8p1V@&U@dm_xaTG2{CVbF=;L-1w!Y(d40fO#L1 zbEMi_rg{#k)3>8b+`aLmASIEp17vz+9F#rFtOImr$_1iQkFmgYTcljUi-P9$`tKEU zl$5%|`j$|yKuq*F)6j#$(#agOGP`kk?@_F}*L1S?4*^qZ@t`N!&X;({hv#Qs`Az@> zU$=JfpqhERpBJ6Fxz+&fV>?B#v!HNL3_=+(@NCQq^`(D~u_e>rHEO^<^>D4LKp&tp zx|v5VJ)Xz>r$sOBZ9u_y=VIVPPsjf05N%3}i_?eZQ|9j3PKdu1UnCa2T~(zIMfM+$ z^^!^PhGVj^AVKgNx}*NrF0CSbf|6}Ta~Yh{X3toTpn*9|iWY7dI30zAwL{$JclJLWr0s z1HI^3!a(|QJoH?P(OuWg%$vp2(9<4raq_saH5UiIX8Q}@U-rGsISv~tl^j;#d=^0b zE?`^?Sw|c1HX1nCmYeyFc!WhI36=Gz+!>19&s0ZjJFN8OC_u_hHrMP}wVFQX2k|*U z!PGbC*x2gChRpDv<{B#`^maTjEUAUo)PUmqj6**Ik^~TG$;LFdD=lR`hHge4Vf7}{ zUR!{SS9to1y=BIk7`$0ZSm%FMytOyY2oKjfvOy(TDI};cG02G9+q1Ep@(mH~6`DT* z$f7zojwR`hR@LmwtwH{$Oj4io%V+;)$L2M+IajK;rZwk=@hTsV!~X2)PL1R$(Gg({ zY|$W#j?PU>l2$=EHsibNS@Qwka9_Ple}q6jlhLU@embL|R$Y|DFPPw$1~HBt@VcAw zsAABTrB!YeI_zK4Y?K&`Y&o=SY&qs^T{ibLZf#w~J7jTR6-SuSy6Y}96Unl=k>*{& zQhX)Zzv=#g#(}r{2#@las!zU?YWm#k9)W1`Hv7|&K+t1n&$aS}v_X>{Urd0n05s)w z()o(PH?$qBVNZuVf8usC6ePNynNhper)4sC)@V<$$5BRXZjnDgg{(2B`v1dgDABsU& z?(5ENp8h0I>{0xnK+V-pjadd-90;ygDrq0i@y$k?2m=IJxfDEFQMH{$kp7y=NORwB z+niDLKUKQ`kW7jSv+12@FNTKrwXM9VbVe}p3yQ7(`$KM)MiIa zJu;jLj~6=u-o=ZOeOGULARUX;ymvyp_t!aJJDa$MYpa6Fx!V?`c8+_#MCuIM|G>@o z?j$-nH$Xthq9CzO1V6COtel3Ap(84Y?6m733Mk zHa+&4EvwksXHrpL)VBj~46`#Fa68afhNYjfnbY((!z)f-%$Z#&br0C&FHph%rv>2D za}{3whhN|Q2)_5aaFpN`j;#a;Hexyk<~bP@Z$y`tlC^?G5&-WTn4Pq+Y=>|Gyp6bAuXjymsC0sFnja?+>!DHYd0G z36ew4)lZd@o(ycb?Iuga6wI)rQg<~)RF8r=;L{DZLu7>OD(Ie|RC-<`Fk1RSpbj}z z6|uVEK!%skD5`HRDq+rms#d64-a?u1aLubNU%<--;MR*c?G8r{gnRq*-a*~@d~s?` z>QH*+w>BK4t{#3u=w06?jW+$&Ej!1NNoPo=f7I6XKtm z0_SzvL}b3!d+zq_sYgVvJ7&ab3s-1zGI-|ZH^IJnWZt*kGIu38P9P}sM&Sn1CCc5( z6&Y{(vWRwQW}m2*2Oh`#l=G7LV6q=LqaJB5n|B~RALrnEN6PIRmu>j?le0cOA*VMn zV?1&ONqi|gFkL?0{u_OovQ*Mi!K5eY02CL*)$-4<@MA{(idu9)M3#{nR;U==;nNth zLjqSg{O5)03)g*TLHHHoYxL)rqK!0F9@P@yjehc|=%2S3T%T3sE~C8me?;>#MX8 z>?ewRq_XEfj5H&=@`nbeAMxaF`myrJ2&CuF6xS2he!x3|fc zwrhU<`3_)5)Hh zd4#Nrp1$ihZ(OT)1u>^}Df6ou^wtOT25<&~UEqzCxQuRiznCaEk}Sr^dh>l;_k#9i zKSNAeB_!F8hwS?3}#1JhZ~Y!9 zX&&&!St4U5;huYQ^fhxg)PuS^)hr@44T;mKA3sDwQP7cEd{${bBieYf!4lAgSSWz6^IOhDde4bZ2cz9{5@@aEEU22!PfKGV>7$)96VF+T09r zdSMS{`EA&axOZv(*pdP`I~E#n1VH4$Yl0O)0sLFXyzp_2z2O@|IKeeGqmL~T6l2Z* z?H_B!9zHjwnX~gvkp|zoSH}jwhe*@*uL-BO9larC_CJvhfJ+)ijf{)2t(w!kHHUx( zkH`6LS$YbL1QZPzz#qan z?srE&b;GEe;X!ezkkff&yzwM34E&?`SvMn>&+CZM07vJx&9v?)HO@@3+5lXuqdK zs~)D&9+6(U97G=qwxq@Inw!lsg5%@HLWD86$KiOSTenJ<(5_={HdQrGJ#85u=L>#( z2m@$ZCqChHP;lC*-CdWt$|(&tOP{lb!2{A^JD*&B_k2vO!Bi$AAGK5HE9vAKW&puW zj`wO`eUwoFJ+*<<9~|Lxv!Yxm!90F``Kc?3|595Pit*2Mi7X!B?DcdCO8BP2`jb*A zJO34I3Lqf?|MOWyD^af@Oj+>N1ywHJ{^VOL4*m7ns&YqqAt!9v*^!Oy`-a(&z?<9W zg`?u`P9tAnCyuP$fDsET5q+yAr5o*Cu$l4$Dh}sCjeP4@0ye;wjJI!&Au_;>QO{41 zb&(6fNFZVP*z<-b0=)xIfe%-9Lh!%2{(aQ}z(T}L2GMi@X-4?|UQUwJDIPBGTr2_#r1eE0xQp1!A50-eDPq{k6Zni|CJ=qHAKYzh+T4^Sd*fBmLqpIx~^i5;EFUNu~x!a*gDqR-8yt{#nI zFt=js!nf&$7=KI67RC~{$aP9aCgAMr@o&n+q|JWvbx+dZf1loK;YsjfET$c*7p>b| zsd>EKA=U8UE3`^`?2%H?Mek1HR#c>5h=xq4(>2Msboy*p;zcv_v^er_K;YlUZEJlISh&n+%ysN{vw-X+T^VKad z?haXE#w{3UhKFVOmS;$5@im0zPv?ikV*(Az(UOYZLKNRjG*%?=_<$+{7Qx8p=uHg? ztve>_8aBn+@pja#+L^M+4$l^)A6H2!wNWZ~CsmabJ^|E5=Oi(oajXC9?y_e4sNivd z3XL>18}+X1_?qUG?{lI5=1;mXwS9C zo9tGva}Uh^ZGf_RF&&gI#3`Q55 zji&Y88am5N--EYMlU9&~enXuWC)JS43B%o5mWx6d<`gZgJZDQ9ih_jTghVBPib?_; z5pJ0dJxX8IhVI5NPP%g2EoTUHw8@s>#dk66i5*?!fW#t5a$miKFly!F#(K+gr z+i!%L4;sF3{pnGht@vu$MuGQ!Hv6<;W?byH(p8BZm5v^S-*VQwl z9#$5J=Gg^vYxwEI^7N}xK+l)oGBTlD0JLZx74B30D~w;)RNfEh5>MW~x!$VFXPu9t z+z&V`LK(eThs7ltySm9k(ODxW{smFGMjUhDNL1nLfVO6^mt&8AW`mWO;Fy4Z<-~#U zvY(RvWdF{0Z90}C!##HjJD$GEwKTo0q{;5FOO|((hlLWe5h|nOeg|5`jNJ%T%ali2 z=4+C27$M1xy&-@xck2qT zKU4J8JKAmN`3>HrP8xA@6lsIEQKH@xXAW+G4aoel)&>*c=Tz^&P1*ZajuV;6t-{)o z_?k?U9CL}q#AdVl!X@m!*FzRyLTU7|rQZ4SrqjqNgT;7N967Z5xoeYQbDRNw8c+{F zRc`DQH}K+uFeg5@OjF0omSjC7#q+qfY9bM112ZFq_VKwNn5N?tbaQM}(l!Ae4P) zniV+l+fxDY8Alx9#4=){+puE?dVRqAV4iX-v&OFsjWP0P^zJZw`g??Dd8v+XkK^CE zyh(x;LKvBbN#%J125(l7q9F7j4^OL>ddd_ll+!>TF;3;b*|e)~RpOOjw}$~k5pDjk zt}`I>Z3|(3o4gs}NY;7qY_vZ1$dop^C|zmY^RhlaHL|*4SRrzh8{StaxWEc89-!bw zKHOkeXCzls-u*blw`dq0ahOnSRtiS%-ezkW={MzPPqKEb_MmJU96TT2f8!lzM$V$m z5f!eqW@Zt$7JuY=_x>Z~i=v(rRu}?P+UPK#`c49)Q;lF58+|6PL~(14ds;+N9&2&n z1RN2W;x6mD`m387d@w)=gIBJ!wAqBm(r6}PA?}H+(1svuXQ4bMOW*Q}s7UJcL&%+A zr@81!z{;#+V<4k?1{@vj^lS2sH!PTR29mZ4{klV({`8Sv>@Q3IsdHGl>2AZ^Z}t0JaVj z1!V4ew{hSbfb3_>)-2|;tjsP^5_65Te;4B8%^U$r+h|UCmC1aoWU3Lkjf@n_u<2Bp z;@yBWf;GOKtcMyhy2n3x2Kx8&^8-k^a#m`_qO4@&=rfcX8-$Vrw@mz>JsL=?iL*1v zYB*&cv4n$j=vI%I+$Bre(Qy)k?pkAx_1hcz^>?KjHH;^Yrnd z{Zo{7-hL9ja~jCsXN9Yt(5~2T<$2|X`Q}C$Q=j=g(^c^8E=tjht$$HS{rDpdD( zK_x%fKdHJ8qHE#n*M@L?qJM#dgGvbP!Q<#dp)D$*s`{Tgxgk|d0i)zg{t-}5C|GUB zs~YRvvpRaREZLicVZ%)j_n-#JO|bjkO+pT-*6TXqIC8d7R$`y$voh&fQRgMA!M670 z7rz5d&|HZ57C(+%3z4WNHO#W0P%QS6qNn3Sm7Y!w=CdaA)JH{lMbF0g!bdm33>U5C zYILm@>#<#KLD8ch=mC4xsD(VxZ^X9De)hzz_8c04>v_Ojs5kX`qW%#g(hv|iCG;`4 z^DfIA+DRU5Dj3i&;*qyOs zxuDmRrg#A|nuMwPKDYDGS<^`8QMh5&9dV2799Jh@ZLEnp_y%=sAeVv66l=iZT21Ja zb<)fFj!8AviD&u9cC5Lsu-h{Z*P#8bLQnJi73sGZ$ z6gUWk6H>*Yh6tTCOH;O3;CaER4JCP!9AWWq3C*5VH(3DF^(~tP2|WcO0wqqK2Ga?? zf278C)p9;8s?B_)$8_yC3l?FM4N(x>k-kC2EM?W&G zQK+)3A_zIdx1vN9ekz9_)!Dcsc4y&kzjvtK z8GBPzM!%glJ40zTPUZU&j*!K7X6S;3@`GAc?$xw;nj+)Z^*VBkt}+lrriCpB#24r6 z1rVQPD5+f5S->YI%Yg50`Tg-rD2#C}?;j~aT0v+6v@^YW32wH|=0+G`~MNWe*~p_hy?oT*2p{_Edkt5SjgZVz~uK#-N5HLf!|Ra>e4 z5yLCOTeFBGOz5q~J`hJSa7=>Qt}kak@Mp>3C$mvdVbO7@JbLuoi<_;j>4088-;2%F z_V2D1mW`DpAi}bL-0MbKfm;17+`IpPGkt1JZ;}>;@05)0ulvjBj>>}+>PT12>P*kg}E?=?O0en z`4(h7MKqQ`kWJ;wlvYeAJFmihzUc=Q;%4l>m*l5q z8S$UIguF_dVg0QOn8u7W^FZuO-8cl2EgQNNSpISg?jE)IUXrW0d+{30} zp^HF`;L23Qk}Aq7<&)lj<8ayQb{HBD7OU;zi<_aP7k{f%@!^x<#64h2Z~cV;~|e4p(=fyZoO*PGprxS?h#5~sP`pfU?9tz@|jIHMoiE0)U zy%{%)rb!toUn{V*2cOZ7;aW(@r+FlQx|WYyI1iee7=ux&B_<~;4MN=$N$0Z z^r(cJA3K+;N16+61z$KuqSv-%Vrf>{HvT@3albx(`FL0n+11n#08yWRvHMi%c^bC=n7R$vHDvId424BD^jJ!ik0Z|0u<8;kFMxVa(}A#d^^O8tscn zDx`q^#Rrc_g8u7<*wW<@>s2yB`=kMJoJ2y$T+E3WE@d9_4AhpYzQNK9cft}ecY=d! z*^G$%>HNXDDdHDF%}jFo8opa2H?*hYitpV!Qg&V!Evox1>axm0`A!eDiVbtEg8ebm z-=TRzOf3D`6-qeAk_o0>`ya`+;Y#QE1w)hy<+VaN6px&z?6NIAKrfJyZSh zS;A|NL=)D;&e+Ud`b`zK=H`h@3OS2!Buk(nx8Yv*yF|#97{k?aep5cbX+aomLZ3pS z%*bHVbm;4zF@8BW-2O<${_lMsCA9t19x&qNp&=XZ%$-1FuYaj2Jcnd_FSnjgy-ZnU3Lge?aAEM3Nc~$xYO#|^zg&KesfHk%3d@m?b{*y{xeJe zLAq_RJ>!b>J*jD>hHC3CrR3O3+pi7T33<2k>X)?$Kv zx_W?qV65;nRM>QhMp$PP+FNgT$NPBq;s6jQuW@*tS{}eQ=~z4f;|o7={T~wCODL8l z7cXqQ9u!BgWg2nB5jIm2)h#PHs($Bocbq;3@S#CCEF)48m#ypUkr7%O5tBVtf5W6= zZnQRC?DwE?wk{m85*#WzHoDle4dGB+#T3rw+Ze#A`bKG^TCOP(=bj8k|{nTML4HBeCK=k-uRm#v1 zz||`W#C3Jm|L#SfcjMU;x}VjHM7IUvr}}2@>nnx$Pglky>-#{R2-(YB=cTp5V0>Q(fVB+$1j?HJh7Jt>^?)~i?il_l?MT*_n&*@oZ8}1Dl z(f-2UAtRfvvs7ohoKmcd`iF2Ka`Lx89WHrmBOIqSPS*^iE5@l6=~i9{S^a!){f@KU z$58T;`QKcp*JAc*p9(Iyujv0kJJnS;>;dS;5-am~C3&~x-*|$KRM4iTYTd=2JCIvmTy8_6CPOJg(3kRP6Nqissuchq0cW4ln}kbg zBP3w~n@Lm3yOG*JXTwdUn0GN>_jV*_`<@s13JtDz3Z0FW;SJcH%vc)Yyo@CC6%D=? zR&HF}7wU`~(BSg*Jm>4Ckl&oJDO|9!TAK*TdVe>#s`mRMbYAVUM~iI#&O_Mx_@*l; zI5M#o5C*-CI<~!_kj8~jdyaf6?*8`=>Sk*g^_1HdCOlRG<5s-nKBAMGT`{+EYyUz{ zUi%zR5HUkE0u+?^gbJg!k?^Zj&zweMRaW9FRaRy!f!v>Icxagnp!H9S9zhMYe)Zu_ zn-CN=^)81oH(?`4X{X2{9#qVJ;z^Vdyx*WAv_S!v{SBEXvv4vmQ6zNY*#j4eIu_~E zhUq<0XayVhKJ@OZoZX?eD@T8d=!m#@L*}1LMqhWH)h9nyjRt2lq(fx4ljLB~ zwYP3xLH}>?|Fi%SyxXBu5dK50W6Y^c;1uEH>T$IvU++k27#~ClC0kfvx)b3a-43?8 zVNBt_t(qbNd`3n_8j%cYXQO5Qm^Vcl8g*9X=*kQPC<+^Yp|wx259XJ0vrk^)e|PWG zizOOv%%vY&N*HT4jJ{*BP8w% zS5es5`h^wNF+E~yHJGg!Ga@Kjzi#RX#+4iE=x-b(JihEJFubG;FFwSK6hG^U z%(d+H?wPCZni00BzOZ!us8sp>`*hmux<=ai^~!sYO+Y9Y!sydOaM-mhLiVEUOQe?_ zTTl_zGbjF(;{UZsdjud=d)@mP1aauRZE5gyHVl7mAojhS5pd38JP>d?x+{3erO3cN zH`5egKDZfv9!xmlLYa2xed>SzG;)!8E4VsU@ZB;^mlwb}VX;3_b4azqvH2|Me_Wg1 zrI;}oKR>rpns&PBISS0Tq=Q1sk$DVurZ3u$sSS`Y9xL)5tPbUK7QL@de(O6i z^?KUcf{0Plw|fzcSve7XR};e>s3CLzv<~{pzH#x81TXrvzQH^;Y)FCmM!IAk$4#MJ zrXO#x!DDzi+K&GZnX-WItpF_*gF(NtvP|`VD*|GS&%U!{X3k*|DybdawUc;tE)TpTe~9^M_!V%i{*4QHjXwd;;+;k zlnT%=9iv_u30_(D@$Z0+chRrw9A-Y zXX^S-6%&l!SHS=9kyh$j*p-j(vs+4(&-$UN$4mz3xv* zhZ6WPtcwp*N)pyTo?eI(%lL6vlHl6#KPof0p!H+8L5R>iXviy`6L(K$xknjUl?2yL z?WJRGusv!qzRi$3p?~U^Uq!v{F?>&&@zs|HVCLw32 zU%@Nz~fRF`mL6QYHy<-x^IoHr>?g=Z+rph zqu(dRcLCw>`yAN(p$x&dk)7|e@*+Vu+dtN-QPF0gE%z`S_Q+Pf$%;k8mjsX(J?V;WC5N2o&Ufy6)M~(o{mE~(^||7Q~}~?p#i)~uKoi3 zD;}M9!VoIp^@meA!Ais3sQoMU1aE78=$#q=Q4ACB_%t|^Fes_U1$^X`T`b9bBw@@I ztj~CMQS{)8H)!wObv=S&HOEnTAv`v31+)og98Lm;W8skdYCstfZ5|ubRfN=^Nxs>b zxDD3x|K$>kUX1@b=TFBNNI<(q75<&(c$gcDLTxkxU}K=u=CTWf&a!QLZi4p|&q0WK z$D=H?B3gk1|)5_!tIs^x~U@k zX}AV_%Vnond(!W8=)OF+@>4!mklXq`uvy(Kn|toEV@Nf0b=e{~jawz!==tpL$M+c2 z>TiidRn0kz%RzR)913FBVrR0qoce-l{iA+vhi~R+BWyAV&HO)Ovb0O zA*+!jE$ZtHjPG`?83JFbgkNCTr04m=kESwa=Z2sSJY^#B47o*937&C6wlwj*OLz&Pa=+MCmq-6HC{}lWP2a_BRU0v~KKh^p+f0X~-L`lk` zN2%0>@RO`rOf_gk^1kEtVY-yG{x=6mJ*7OZ0$J76l)0;J$<+N~A0EG7; zF?HBWS^Z&XCF7Pxk;NdkfKijP@o{Nuv1jgotj9u*A2kivQjm1>H<}CvAJ@hXqrS$G zeRcb{FW0L2uE|~en{S9r(~nZyyP~rqbahP|cyTk_^4vEDZuJFC@iQ}5y-P*v08sV~ zDO~HT2p|y*Ie$q(Isi2n;me-O`k<}Oc_vSb!G}%a2zUGGZOi%ww-dfE5 zVgax>A7?PSItn{3sMKvEa8UiqCE}H+XjHyG|FZVoF}vMG#BLGIsi|_rF>~nptZ@QzNhe6+d)J3NF9V4uJWGmM9C3MQLbJLUmd}ImaU;A#0FheGOHKNBE(9JpO^Hx6}W+oV%cl|{ttv>G|B{+ZG*|&5-mE5Eh%!;7$m~ZUyU2ZFaY_5|i zFLksXf^gl-D=&L){$4?NDzv6xXcOmH0~_F@z&R6K=mr&FG2U+WQ%pN@ah`_!pbd(c z#v_fA2oOZ4jA#G%&kXw*9`K3_jT6Ri2B#5#=B$)4r=)}GrIZ0RdQsmtI)|!n3D2Ew zW$MT;j#9clL$TiD`ovw*cND&W`;xK8WC#8n`BR?q>Ft7(H4$UG)hP=fqw2bPy%7LS z4g;gp56>4<9fg)mt#1EZ^^b}eOf4wx)8XB}~&sDcZ;;;fLH z;^X0T7n1%Bw16(C1M3lmE3fbB$J`>Q*hD?77T_qxCV*DF25R-nnUk2ed$qh7Kk5tVG;{cN<{G?po`gVqdq!K}{;j|o72)O$|C6gt91qQH z2dBC$krS|NfSeF-+3IE%x*8$Q?Amg!RL3GmjV~{>bx$5Va!Lo~ zfF-Gs2ndQtNv+>6C9`3L|t`v%v^NpgG*;8Xv`@?*q3t9CgqqO&Bj;arePyJ@0>w$${5fDH3TF5O%e+*_UdTF=f)`Fd;lw59 zL)qUi+xbK1#u4_jf8C6$0S)#KUkDs){1nEt9neJ_PGV{&#cw&_Y zu1e7E5&P6>Wr>wLzz9^TuIyF6kvn~Ox?VNIqxVTuc3PR1_InnfyN&2g=Gtg~etycw zI`zDYy3)-p3PsS_*|C|zSu-wU=w~|zjE^c@OFvYQ3(Gdu8GxwH|#(=f{&d+J-PcqiI%2ec(X6ccCo{A~PIdXgQLQl^^-?FjY7ZOETjR@TV zPNBe4sDwc>VY_Q**zjC*tytY=Cv*`Xv#@Y^@^f0(0xUZ2s;Q0#Xkui!HZ!y}E&18o z(3N|y+9gSdA5x+4+Voj{KF*s9`fh6b(1vdeDm*V#%zD{W;W1^YA-L}fx8rX9{U@K< zRMCp3#s3&4=FyIIQ4(QiHUyQ4kp?pWXk6>*tlmsrg5+d$=upNWY0W%;TOx=R8RL>x zSFcm@V4GVZpz6C~`5!w|LVSpAxG{yg!THOdV!>*4J=_Vp$CgO*q^NqWl6vO1uq-3s zKRTG=PUv0Tr+*-2yAsz31C{->bBJC!=;dG?DXvL!vdCQ)rTOgOgumtDMKapJ6?bNE zHMCHAd<5$8WdFUQD}ED00_Ltsth|P}+GIjj-Pe#>NM9|TO7p`DB7S+z z?iX-mTPoJda<5W_Eg(MVe2a;Tj(XeFW}k*Ny?DYPT zSrd_K-lC0P?91WOAeCN6#z>Ztl8A0eWr?oR)35g6O4*<@zOA-P1BH4c{u_Fct`ZbJ z=7rsa5;|VQMf(HPGkX-U9Oo8EjD0F}f#b^Hj&c2&qd5QZ2eElKt2nO5=1YxXNw9yv zPUZ2P)DQAx>Y%)d6W$vv>pe>0fjd@5~D<9kS6useh@LZfe?(T$36)fku#lwZ- z);YF*2hJZ~Nlr^R%FUH-MD5f+HJ&FMJh9fGt5M>EkFv>jMF`~0%^2gNY|-&t&3q0j zn{c|12peje{F*@Wova$GM$c&kx%=nw%qz;mx}J!{kuf3c#6 zH=eTb*MD;uN7+RH%!O|Dl`iDWpZ^kbwHr}Y!QRqMoVd6O$JN36+7dNHlO~PW6+Twi z_INnYGm&tlkJia}q%_EnAHkuclgUhTk50Ag+lp+NdJe0hG)MUs+2E@6nPg<9^$~;7 z-(?P?cU?|oWXxz8jkELfuXgkQ{vRgP zg{47St!ul5#gwsI4ROXAdG*MUhzy-*7DZgNqzLByBD?h213Vud7`3R2tg|81Lb4 z6xaemdY}JY{KtO4eZGP*2M!k1;BT1NrZP1 zXrug88yd*C&z+pZej?u=Hc8;e*FcX=I ze-5|Z^|HaH?7rft6WPwxVtPXzll{;3Qgg>Xz}cB;8KpqyAKxBYz&<#y2j31GN0;>S zw@)v^_Dh54bx_u)JJS=Ra|fe94RJ3;qzlgQ2Q?NJQ^i78gkZpyR&;bC``JBHPzZD) zndri%ZZ(89hV}c~hW`BKhu!p!gF`%M3-DC$QSR9*$O^lu>nECT)>WE>k4Urvefd!$ zA`j8)%dobG8>=#o1=k&8RV-C%fb>BY! z9IS}FHVfSVWWV*F0oWd{L)@Db_LN6`9}PsAH(Jh`8nfq!kEE#ZZfq zuRYhD2yYvXvRWKv1FOkfSWFd;vJXZypDC}I&~}(|>~dnL8{&Uwb~6Dim194)X1gLt zS}g9xb93+~=X%PIuQ_UHK*18vSts4`X{-1D5ym!^txJlrHS`rv&EESQrkpuP+?b=H zY|<$SHBzFt!KJN)K30sfStq<9kMj5XGS`i@Dvq){D8+iLzasYJzp>WNhMhI^yy@q$ zf42j&;A2HU8geb2b@))J^?2*j*qR>~k?Z>a>P@;y0 zoHrFEU&p*@qiKQ)>{nx>SwzaZOs^yDZ~G|DpZ++f>G$AKVN3k@Zjp`T>-lYc180?dJz2~Wrmmpn zRI@35Y*PE)8(znteeqNl{e)OFOKS1Y$#8JL6?Z<5ra#=LhQ^$0`{K)e@pU8FX8+=! zLv8b;chc``66+sonNRH*`hEgH(wrQhvyg+Yw*z3xbMW+wc}tj!2BW&an}5yJTzf1m zraKdLU$#4bFVi~6{ryDtv!^HV-hF+)d#;H%mJd>hc{sMKAu1+l{q6P&Hiq4UzISBJ z0+hnRkCn0~efoS|<-P2flYFomV!hJb1a zT;RtacQE)H1@fwYj@EfLInVmAn+oT9gRWB$JF%{JG!d%VM(1J|QZV+^Dv;w5WeQL>3Zowgtt$~ z6288;hlD%bP?urrj%0LLSXfLXhH68M@gc6HwU1jnOj$zG(o?$&D13vtD`t;q?O$3A=H8+)u=3XYH%qw4HRKtkb!BE(=rMf~3XV z^!BiuNXokX4Fb{NqoJn>;p^My6+J8IthzJk{wOZ+>nZ7-niOn^IkK7sRc83h}3 zD(3z^y-SZFys>qC@s%zviESt=Dv-Ku)SZqA>iLBxG(pj!R{rZdTRHH|0#3DjnhVE* zRL`1^q_tw~RLS3*L*2=1h?_SNRX+66Pb0iHhCJR%zRm}yvPR_GPR&2xEE~f**Zm!X zXZ3yM(4m#y_@Lkj^cm!P0SU8KPek>pX61en0Ezw={^9Qubs#^pYYztP}kxp zyU)Re?d<)+Y$C2%8RxgKmo(4aKYf8e`>W>3y{XWv$K+zcYudH-FCQ53=!Gi!HZAHu$jN zIk3TB|KVKz%cjfJ-R!38weKKmD-hnhu?^+GslU6yp;wmzu=Ls0IA41Mqhw(JnRdM5 zj=)s6;HC`D*2KI@zRq>8Bk4ZhJPIeQlCSeOe>rIMRzl4Pkm6C`GZ)>C~*g9~e2WcH_Ad zTX(9{JS)W^8fh5Wt@3Ey?-m1jGUYSa((kkUAa&$KzU5vWjL(z?Cv5c4gYrUYEaEU# zG>4Hnq{qts`1k3S*TJn(xY`pg#`3Z(ZjWKa)F(@Wqh4;kY>a4`qIlcRlx3k5=%aF2 zE_6lkR5@9;KFqxg+w$CYa`figU*R-fS2tR%!yC?xULe6|IW@zajzSTWAB^J*fd9L ztY()vM0&-efaN%!;Yb0En_CL8-z`V#(8!CpXpl5kh231$nlTqXh0<`3!ot7Be_tSp z>jT!YW$zbgsd@`#yN>^U-xD*@7(01BDtF@UJ&IU1?D*5!W1Sfx&M=g|7`$ zp2KQ0Nco2m4&(=h%}chhm@0(t{>Ww=r(A1Oo{gl9O)NBoiioCL=^d^JL7$zjEhgI} z@Yf1VO|Y-c&7E7V7=yR~BrQn9HH!o8Kw7SOD&eQsQTK~B*jk6A_1$b3>MU%5PR!6D zY>sYhdVufScd#RO3!h!|L(cxuJu36(A!#~>x*OrEW9293(^7qq-nuHx7nY#6``JF* zq_$`)U;fN-PCCCz?}b=#)`)8X(UpSV-{8Y%Q+BE4ms$_T-a&uh8!)a4i}|BCx5=l#an$hrN2@dOp56nR`HpvDj zrs;z)MGa9F&lGRgM6%DB$l{tCWP?lb5elQ};|3G3N3wjXJ8?9E%c6MxaDO*^CQ`G^ zM>@hHk#U?D`QvJ2P>16tHAJ(|j=x1vpmcK64^?kD*}u?C`@Q3DN?$fHy3bHIAbc&X zkPRwR>JB(_qXXRLg=&blX?88Nuy~j$k_}olF{smgBAKi_^Thu3-{wTz!%l|VJi+Dn z$9CP`8g_HHvSrY|Jn+Q8KnAnwLZE88F*l001BWNkl|vX98;@6*#*3j1pcLs;evr970*t;u=zcXs%?uKao>W6gQ9Si^YUE1)B9)21r$h0|=}L(jN?tpf zwdr-NUMLOH+#u))*akc-oQ&d{E&T-Mp-6Rz4ywl3?{Z{xlx>Qn266#pivMC%t6vjeA~m2yO6A%9YpTfnXiWE_1Rgh zhUiK8Yzv=>(tb9`=f2d#rBktfc##^yo*Sh*KA%fA2x!6*%`Gg(nf?WWA2l-V-$YzT zCQCH`)^Bui`oh?R^M(-={#;%242@rIMZ?S9SWB)B4ISh3hjD)ZAljeTQtr(;d@4?=qd{C(2sEZBpSP*v8X0Kpg*iDDMA|{@n+eyie z^T{}c=|bq`$FQIDrwMQt7L$SE*6~zK!ucQ@Fa<)UvQ{VjwO&rYGB<7dDwKd33vpgKORw~89JY5ju%`whaI$$7;!Xv-|K%pm{MT5fr&;9Y_x{g^{OQ3(C|h+R zb6k|4Z0pySMMzp-vEhSiXv~g5C0}Rx|Igl=N5^s9cfOyl+uc~XFAZ)0H*jYcL4qra zq&Al&OO|Duw&TP^G|J1&B-V2>c`tdgl1V0S-t+jpIp5G%2ERaf`>qZd>+x*Oft2vGGohlh>ss$2Kos=8J6t>69r zo(S`US4!C~8#x7NrBa`kgm8)NSj+od{RlsdCtk~^&gu0ys)pu`eTdD2#jS=?5(hgx z5u%!ekd3@N$#bDp>q!fje5sNRn&cU#y>D`oQX&aLuUrUw*|K#OC{_Y#GWb4xvp8O2>0j~+ifSb&Q3X>*%}f#`&LO z4|Pi{KDXa|tsJFVXY|!#e1TZ9(1h3Vf;_$2CC$Vvi`CPVow)iN#);-ijgGl!AFhU2 zlHs%8H+i)8F76Lw$&rsecA4Wf7m#!fX+-1rq6-}S>LW?fTv@Mk<_mA2U5!Ol`7XJW zqPZz=j4iWUN7A}ccIz1GQItx3%G2zB@JeaYM?4o+A9RTM;ueZ^JDJ3qe0!8)u*$dfKrPjr;FTRWt{3istD)>JU5UGl}Mj{a1(&@qA>ZCz9e% zZvAW($`|!UljF|EUFe+*J7gnk?uoh3mzl<^nLPHl%0`M{UWku5#6)bXXzpuv=PgVh znS{sgVKtN@nrG{qYD+&RM03dArs@gC*YxdV6U`H2+uKDB&h!dybq-PfqQQvlV9D<< zO^W6*64$A*$niG6i>+z>^33lKBtL8Mwx5r;$rjCRY^KI$OU{GYVzxzdVAe(R*|=x( z-Es59FApbkYUGPmG*>o^)pKF|*&!JJyp!WhIYo1;r#Zm8 z@3>M#@6d*?0iFIryCI82 zJuHhtucQ$PdvPEy34NR{W(U^PunkZ^K9})>f3n^zh zwrevvtV#3I6X@Bb;!Gq5j`vY|^!ZGX5S8*3=4aBs`9bo88sgUtMLe#C=+vYXVcceB z*dZHv<)?TMC~64bJbU43jWVB&b1#0ciaxv4@U6?9=Qr19z>-1Z1Er>+BeGvxAN>y zXV{z6;Swkt^^_!^HM+{h`181OM8{{zGjVL>tDJY8P73Aevx5?vpf#GkrcUSLJLAXu zmyT@Z`)^fo$MWp2m!HHv_#Gg7MEoa4zRIsk{wA;X&QRL>B(Uj|DV>6$~CYqZY^N&8ak`T>{ zPb`a-zcV!|-FM5)vAR)~sv%a!Me|Sm)-cz8RZN7KkT%*-gi|(k%;UD#rqzAZG#yuAzbh%4J7r^1 zqPbLHT};1=!^0EDnv}-dJfB7LCoKCd{qwKmef@evQBpKdM3E;*|J!DAtnfrqMDw}Q zuZhU=&(@D5Mf2I3RZ%y^@o*}lIWT3>9CD8hH~kYwq+99k81KcKtNcDqqOx}U*!P3~ zUW#u+l$#AjM8CI~Z=H(O>&t_%fk}wwRe9WtT6MTmU5(ki+)f?mqf$rm zv*WF2SUh?X&ka(4tF(HGyRDIPRzobMQln=6F&-Wvfopnqox2MC#L!1~f#l9e{ATN_4>z#QoH< zR*7P|lD3QCpExwPc9iz_1ZO>*Crs39ni643;bCqguy@GjrP zoRVx1wJaN*L_HEoL|sph61kaqzZmm$e&B%wnYKXEs5;yLoZco{u6A4Rf|3WG4KMfJtBq0KD;CIS+R_o{WPi({WW;gdv z?85caI~*_S;`ZJu7I)m^!(WVvS_78$*8RIGT7DVJ1JzWu2}$cC*ee)%NTXJ5Y#s!K zod1Q8NHqK)l8&Ztb0)7Z)w1!x607c2LtHzP`?_8lI)UN50>IJ3O9 z_u1O4NlP7JZ&GUnaKsakKB=o&labCfY~lPNM%k^?v}z}k)|L9bS0`A&0HM_B1X~18 zjGpAJuFEL9bb_6+^{=lkA zy3p60L<}@yy1YmcjbNL=+4UaIq4)UB&yMhR$qKl)94Vv`5guHluhUdggY)_sl$w~R zpNYs45025Hao-0!1(Mch`8;vtxfMgLLInCT<$l~h9p;fw7jyoJH8@Y(2}5l@ejHza zl^bnc6EBzp5x9$Xc1&!$f5pkkf4Y#@|HD|M=RJ2X!)M$m8+3f-4i;$={{5dO+R%hj zt+Q=Mm^K&GZ8Ny;T)@EgQHI%yr1cW)7Kp%Da!}=fPN4ZIjvu&6`_&J|iRJ*u_g7bN8e39IttuibX3CC0=$rK46>k27v{C06iC2y>BgV zZh9Vb-(K2(aR~r(rx)p7elHlhG%;ndI3Z#mRYN(&*o0`?r3sWuoeyrflj~#>!gC4P z`E0LH9%j)TGCv^9$Cm|}+L11r?^Q$G&GXm@2b@WfJRzD-gjFohCX}ZO>iH14=}Zyt z=R026z$=Hj9dNRx$V~3LPK#(;xyVe}r?xmgy&P9VGzXmA(*(_v6j5i2#Q5_dETrnD zC|qxq4K7)Pi9$st>$dYDy@20-cTq_%Vbj{6u zP2l>R&aOLQHuReWy9Gh9n2t~>-9-k%KZ5hU*ganGp5W-Reny2(g&d|QLmOIt+0O#m zK-b2ewQOu`rk9zzHjGU1{^m(N#4SEbw(Bn_AaN%`^-A^G6o&g{l_TrE<4%O+bUuE(}$DL#urs+j0pkA|$ zEu23j7^)W$NIlSELhyJIE2s$!RYe3+1tK%-WpP+0l=jvqaiVOFR1gq>q-YKx4QT{} zH7s3tf}!xwfS6$KZheX#5#Y$)CA3{hjjWVLG+J5&tFC{6TaSJjSMYV}>U3IK1Y#f_ z$r(v)i|O!kx@#R#eFaB1_R`wi#nGL;1Um&Ue?Gve`?a)QNo}jS!Hd)vE9dBz-kdKB z47COk=*aqeCiHqQ?jPO&Km?pr{%<>Zy=wuFbbUndo*Tz_o!-Xgp(a@1TkCvjd_Tkz z*`Tx{LU~05_dbK+i!NHKBIsw_coioDSFfULf}8zcqq}kh$HsPc>|V~+fgZX_Vd%9% z!Y@68AUCZN9LsmdaW9wJ>X=CC&K8E zBX7|>6C#J;Eo6hbg=TW5Nv`E56L}8#i}w!#uWX>Dwaep)aHLL8MvZ%A18^`j0SHq*xnPlVwi2Rmeg3unfXHqWKLKB|WJAYQj^#pbNkZL4hHz`^j4V^YF( zqKs}$j1#c)SwCBpd9HO6VtFQOmVC*leO8gD(3b$gK0%KrsFDr(RPtbmGvk&`yk!bxn?@mNjOg#79MTE43WA*i?Wq+| zzL*W>Ep9#WJdr>J!bn}e&DqGK>;4D5O*K?hwkM~IBrxR-$q0pGyIW}L*o&*Bf!5|O z%*9?>gIySE4QF5NA-rEj1jcM%zVfg4u%I+VqBLCLLaxV|vTL7=rgb~7Ov8b^1I(st`Iro0468^sVR$G2UjY0VOZKXvxV z<+qCv#KsN@4KWa4-)DZ8&5j=v7=4PH4HqyMc#(9C$`vMi*ZdEvwglKb6y*p1y);=) zS%J1Inb;PO3@t>APQN+ae^jSEDEM6cNZv_7g8^qO`B(-4KD{pK+bb)N&b!Fz2aWaR zMWTP_qiAlmZW*0|=&V%hR4z*u#nXvuB5A8){cf^2)ew<6_QFS1Lj>Y=@^~U_+8jpH z1YX&oF@Ah_Wdlz|1WgkR4LMS*RubRA+!JdbR(8k+_cW3Ge>mR%_bkWeT-XoRaXi;} zK2vmC`o>Bj+b<;IJHZy&V5=N1*vI^^8p0ocxsYqS&%Q9s^^4;Zd1kXbN{}rIb29tm z*ojdV-gZ!aFwDJxllz+B$wxw5?h+i=`?>aK>p12dL~Au^I^{yys?)wW%BZ}W<3+uU zl&zrkBZF^z^**n^H`Y&snn;S}MF+xcTUpAz`h$c|x1@;Xrd*kP?#zWPn%mes7~1l9 zSy>T@Fz6URMo&g8hpEk^nd-J4)HOFTUgj&BmxsORl18QF#V5opT51+~x!!+|Jz*~$ zQp~X-A(|hq(^Y=)$}Sz>M{Z1c2N6#Nu7)?pEpxa|=WJR+faPH?+xB0;cX9lK zs;a9rxEoLo>zp}VOEEBPIav<=@m}8jw;znJi&w|j=tkM6<9pxDa$Tj%-GH)B=Tvho zqN@>Ojf$(S0duvN@aJS6fA?=;6i(f$MU0GXL)oqK`u@-12sjWQHp2plP=U0#nM0rT za>mz>>(>pK+r5aZ*%OPJ@&<&zX{_9xI&ZGoiL2pe&VB_j)Cj`AFzJPE$_oe|4O8^j zws>wccW|g7q7NVmN}(*14Z5?4gUTkIp862?ept-C_%f^15J9Rbu5D-0&qwI-yHKii zn&b#=uNL#AZ}idj+Nb$oeFMYaE=iVUsH>5*VenTX$T2oVy$DC__YzNp!Hzu$Mpb1lC;>ok)$~~%vIQ@Y3N1|@iUEYJ3 z&i`>B*Z!I>eXdmLgtkU`FVACM*{tKc<)-MwD4|!2r@VbpKZ0pF|Hu7q$&c_bVfDwh zCYYQHp4lH4tVurSBH6}}>Ap@(wjL9)RW`VuNTM3AbG~(-Y?Sy^qRaE;pc>-cwDEE> z`=nYnawhjXR4;J8JA&_etlXtXBP?>4aziZOXjKpIoG-?dm*D<(YhK$^cIq$+zCda{ zH>x3SHx#i_Ht3wg=Yx%nP5wNohj`6h__NHX>PPrRj(f7{BGWkfpn0->gx4l$yK+d! zcg{WT?@HMq7#}|m)#;pj$Bh~GBI5enle)@lmIR*D$qqHd6-!@6!(JQ~-LFUu5t^W{ z4OARDIA^GiGld;-{xKtAvm$Bt5P_ILyeaIZSJF@p=mgtho<-ZkUb-yPC59!9V28l0 z@*?$XEYMZ-cm#SP5k47{D3W#;b9-G%WO_R39(=)j0ukuRvUChXU4{sZAOa4Kt{EiQEimO+ zr0OFB!vwqRs0o`n#2ky7%*IH3oG{d_h(LGBZ(?61p0@_LcFoQ46Px(jrhohX;>q&dK028K-2nawtsRD zqWLuzE{<|9ExDfWgQ97(FWD{|Y?s56jy_LtR1Hx&iOBFod4;SuU#(jnM7=ZZuS7IZ zmnKl=L0?ubHt95_yd!K9QR9d8$hZjd$q=1DsEKL)eot~t4CP|E4lM&4`S+YzN z!JUqE-F&C*TcgZ#tvglE-qP~ulp--V$G4v-Ls_r$$iEuG|5_2s1|6d+!k{KtKN8~2 z^$R%e9^v5e5a;g}(SJ6~f=#`IcU97NHG-?5Gg+=FFGbQuFx0gyEbqohuj4&Ius7AV z1)w)RPTCRWHa2sIL?Y11GTBJ;TrcyclgV1o%p|wsZLdm;Ah(imV|Y?mDUX(M`OaPp z5lC6SH6F<=Nm?@E+?s52oovwCQ^T>^7An`61lt7iW82Z1x>ytTGEksBO5!;-VYBRz zG!})u>^|B;x9%X+7;9INY+z=yQzU>S0x6#6iMl8LpNrTL=O1Itm0m<=s)!tkdQt?U zbV_xV;R)UjIm2GU&PEo6z4SZBi`0i-*v8pcuA$WG_%66HM`QI`k{-{W_;E)gp}SqPG>JLdDgQT2E!Kj_(6E=1wo-a%wqBjn1jAT0~2JWUXIape4viG1)!yhk1*{?$nT-p?6Fw2|rHEM{qh9cIgAzB-X zFy-|eciq5uAy%ISTXr&V<1))mJVN)YZ?WoyZQOn38YiC{#*BdL6Jh?#|GY43+qTO_ z-gYS&`(~CS1M}gt^&|XamWT>#6zqIvu0?y#wff8#lxiK{&D7&DJp$dSh6v9>)RL-( zXqaQsQ8xK8*CWfVB*u#QI%Zg-%qK&k5#!4|5xO-g@8zGaAK~Y-5KUPKn`DDPhBj|j zL)`F}^YWoyaKJZzR1SclmU3*Vj_>M1gue$vE#=XhefXN(80tojR9xmgOB3WV(7VG%>a+fpFESTwFHnuTYHp&LK{jO=5 zxwKX`Xw9>XM1=Zeu|~E-EN9s9BNw>P&F>Bjg9StZoddhc4 zJ`ro1xZH?RqhoASW9?Rt;k)QASTt95rk3x!;^vJ*HI)8g7f<}?62d=(XZ--q_e)W> z=~+s#v9SS&Ec5`dQZ{lfXBEu>Q_=#1001BWNklOf`n)e@R$E#A@1A1;MIS& zm=A~FpyRLVSo}M~{8`NicYpFM(P0M%*FVC=Pw4mpZU!5QFw_c6xiqEBu&%P9%Ym^` zr8O>Sd6pI@MRQ}L%D|1w0Ce0aMcJd%e0K+jAK6aRB_~^s={ZGnrBY83&9_g`51B~6 z*;T4^woRg(Y-LQQtZbq=JUliLR>A4B^$*sXOR3UX-uLjls8y=-zjlf|k58e7GJc;f znr9-DXkJJi^Ffvk8XAgHELCjgHap_SUb<+W*oSjzUna)!qiQHQcFneEp6yzqR88DZ z&sxUV$%^Jj;$y%Kzbmh8LL&L+#E;F@mbOhsG`FrlQQZz^8Ot_j>)-V{0l$l#8P=-^ zI*>Gjzc{=e-_^0PP|{qS{eBqXkIlYyH4Nixa>qa4P7%$4W5sj@-%KQ$!|X(x&sEVJV7VuPQl(EQn(xV?yIE=VyT&cIPBt)I77gw|?0V99 zs&*2!jS)!`%>jhei0_=6D$B7X{1Uz!v14HH-PG+R>Y1nyFfT-Nu&r7?R+u}yNcU2s z$%AbIiMTC_2+-QzMajqugk2Yt%Os{yC`WYey!{LVuCWB7s;(xjT7sPdLp_cNG^6Z} zMRy0=y6BFtZ?5ptb9psGML*-1e3h0Kffxy(cy$8uV~9X=vfPMgDUPAo&9SjTC0bH} z7ziL~_mW9NTQBuu>{Jo=0+`#qNL?DrUY$VkQ;5C*H#~nv)KiMkV)c9H9i5RE{td2+ zuTxoJa_cLPL+1*l<}Rdx!l#4;?+FZb3nI{sp&E#QK=|(gu;z(HG>Zk?{lO?N@9*VX zn~O2!r3n9M!P~L1nJ*}{I!!$_Na4cICr4-qD17>ED8ur~4xQjV%e3uYfl{q=b8VE` z7LA*4ewv@0X-Dk3M&wbQCGQ3a-f}xESC-Tt~a?I_!`cl?-RT$5WQp5 z--hpuC0F_SNsYJP+lCa?5ZXH^3GFdBZlMR-~lhIo1 zG#{*83bAL&H~D8Y-eyTQ5TDeEL9k0; z$_^eo(}(Yto6w74oaZH8KHQD6Lr;q7ro0?U8)n5f?=$@CB20NXro0jnh*@2VKddHt zZoI{1Z@`J8CQN^U$K6!MRT~?d+)Q=6nyXCJB5O8i3pm;M8J#;52AeX>`m@#0x2@~T~k*LlBv;aS#F1}a?fJxG7*j(7AoCY#`dZ` z+iBD8q_hWO8svP#7S11XlwCT(PJ!apY5k}xDQxFrWYY>n|M-(A*dqA-KlI}}AG>+l z6ZZ0sMMQs6S82NQ1|?xHx4XJH{Ck^O)wzoH{+O674Qm*ZhH^yb#@n?F)RZG>y);$S z;5>7lh-X<+EKmGzF7x6D58~{IZD(Z3U*d2KA^PI=bCn?tXh>c0lkl#9;xhCDCn!Gm ze`6LMLG(8!+wHpedThB4ffO)tUOzKVG*@bLf*rX}W>YRg(#)jya%9u?6d&f+k8~t$ z1ZBIga)h6G;o_EZ4?nJ`-#gd5PwU7hdUnwkvo3r$-9$8jvwnn#-<4c{SQAvPF=^Fe$&F3fgQN{5%T_k( zRBkd^yLCCgy4H=O%tN^M-q`OoI?cTsIJTsPU8P|*EQ|2Y6?axIyL6^1dME2q74uSu zn24J2LC+-Y=EHJNgnf1TxH@GkFA>c+*G1Z?VihQW6rnmH7(IwS=+aVOekAJju;2$HfJU=3slF+t|z&GkHxosD@_6XFTE6KG#Ka zrAlYZXLR29b_qw+5G@n*%_V0e$Lp?g>QXK1Yg&`fkzo-?dYtd8)43b}Y|Yt~Kr&OG z&ues*4+~7rscg`>r9Gb#b-r3Q7|7AzZQ31No(PfnwS8xu&b^koy??S{dz^m^Fy$(Q zzj>UO_=M}l{l(LX=qghDL{kpyl%0BpUuHS+lzlpe@1OH-$t%3{yMui5|0|zdBQjuY zR&m{mZP#4wMYQLh=5gSUpXL0&{Rsds{ZE7ZpFcao@l_Y_U36ov^QKs}m{ndP?h0Ht zCmv7?)q|^HyjZC0(D_w;EhR5CQvS+1w1oq>|5H)MWo>Nc6Uq@C-vkf9S=X)6@m+LN zsfGv^=;3RqHMklsj{CkuR~d6tu5c&h`uXK-d>)%e< zAUuiVT3M&#Yk4?qiymg?lXrOn>sa$3u#Rtqc;{yFE}x9|ZbJAj#6vdIvbnZB6%XBm zYKR_9O0HjM8#l{FGQnIvDC>3F7dg-&qaW_UKM3*ezb|6wdnJ^8ITrlmyXwZ2UBF^M zLiop?VN7`i0K$I{WuuON$jLzbc&m^NI{dC=ZkTiy$p-!N?0mAZv9XyB@)^6I)Ky+{ zH?Y4>CkkAcgfF>Ks`BX0pW%CN{JM2@I`72GTpjk(o@SS_Lk)2ykNa)qu#WGn8)Z|> z@)SVXtmC^?czt))>0F+I|N2a0N1T5QkhK2z|D7q{D+ly((Gj__O+e4PN?R2oE?{9 zNkUi3v|YUuTmQbs;pZ!9y%g`Oel4Z^T>NQ`hVM$6x9|>~H`i|G@i!X@b_)j9twlIN z_?nS4fhh|l&3@ZW z>nfs-p_FBh99}}xwK0EBGaSq49qbV-J28q;YY_3f5SB>Q$|WW(H=3y2Xr_#rdcA`1 z2UE(AmV1y!HAWx*Bb-fVQ8wx{UMND@sAD!sNQc8zu8eT|Vtx;d*63xJnW*ifYKW>$ zW?p4yi%3zbbgs2IQL1!4xSsu{XQJQdBFjAy_AWQLc-@_hR$T6hux@iWYxH8SXvpCq zN5-h{=i-(&^PMW$$a_{rp_nrmu_V+`ij7OANcHr{_Qc;xwa%R@lRK`1_vdHi&BM-4 z*ZC72z1!Y(;&`!`NB{Od!S0xS z3&dvIInQXx8F$KNonVjP*s?yF#bQi(HEkFA(JeCu2jk@zmq#h8h%g%edx>l?s)>v? zd+8_}^b}hH8yg#&Y%I0RSc182J(C#spLubJ8|O3MJKl;v+qSm|+AYuB>H1x!aZ*_y z`%V}Eg6#sc#G9NEUZbmYhyX2?G6ynPu-waVznw`t47LiCjXJ*D77MgIZ5GXCUUu(o zNk*X0^+GJT9ZN9a z^SjZXJsC?rx=>A7$9XkoxuDeQ5VPaMP!FN+KFQf{1u@ro$0ZfDV#$3!&GlKAhM=0vQfC9q(8R zGm@q&(ObSO_e3(zpvflz=b34mNwUSV5A#hP`phK8lE3>#;WKDIm0>&iCMQjhNC^6F z0sFcB<(QSqX4&B4FN<<|>V{7basJcs1hQWm2Ef&DH&)jjsdat3dkJ9TYPgxTJQL`( zZ10ngkFp}q>sunxsEv)y{3280;zGx|Lg`7&c>tZn*4~CMof$4bA8?^0|` zc9#+4u6~3ceY<2@%FWj6# z5ZxAAm8mk*;?9%xBfMsL8Jl2}Y;dnba9@-7&v+9YBj`7%h812F_H1;OY zaF0(QkU#{Q5n(UU99eWH!lSDUWysiTY*!Io@$W-rNP4O@OjCuNw3iWjBcb2==Quyi z9DNQTb!tdjSLWZs8s<_j(nxF@QQ^VW`>PZ?m(Yt}zw86ko7xL2c_t2i)Pv3uOMcJ-%sSVt#9dtX&kTg3=&Bmq>%a%eJ zUF@N)t(o9m!P4q$3|BN=Ra8_B*G2*9Mml8Z?k=Sp=?3ZUZl#AIq`OPHyF^N2=2 zZurmpt@U%o1#2!?XU^XHNnA>6tRUf_Dt9dO~{W^Bv0(cz7(HKTiYM~@tlQ*lPcF={bddk6;;%liBs@8YTw)2+Qa|X z@Nkj%XZ$tbB+sJ^>2nEV9NlkuX@rMyQD%91&pIk5ee6sx<5WgMJDUnT7PZwqyZF=( z0&yQdiwp%0B-z&rdTHC~?=hqmC+Sw|sdkNbQ%@EbZJJplc>7-aK~mejd@$8CkX(u)yV*hDR-#pFzDtzn3RQPUaw>;T_$3wE)re85AunzEh8YQZkLT|uvhw$lZo1-F)|2O zzW_PB-V&Joc`c;8F$J(^W;r6R8=ffm9=!;OJC@AyTVLmAYtJhk^I-g<&z!*ukk{8Y z<`y!TJtq9zex+vu?DpwhE9z?7bvsl3w7(n`c0%g3!s~Fas8VTNsdnID_t(aJt z>`|JD==@cXWCnGbnKg*7=pg(BL5a!%)RcX(4YK(mqj4SPta^yI_vD|htOZ{ zx`*F61kG$yAzNoZB@qTM|XatNabsZKtx+FK#ok=b$t{&??eZ zu63w2vGDp47qFuH)^+AtB+)YmH6_k|Q1}yOUSju8({FuknkxBvEC<}YylpQ-1qn;t zf3&;MU$HR*j>gI&WWstt3+{q903giMB2Om1&V2jlNW>}T*)oPhVmaACr0O*CNkczt zJX;SvHxD7C<)IR#CFePgT{=puS{%*C(giFvndnvBF)n3Z6labYRNcoH?M@>ffb60# z%5dM2ehV$n2*>=Y(=WpA9P9tYzDTOt zBM%mI3p5cD!h9s+hz8U)-qW)_r4XwHh#(Wr5GFr*>5%xl!lrKnyVwV73Es;&J6r!K zm#sS!1ahh3gK3VZ%2is8e-bZs4}A0?{cc)*=6vMBJc*4l$S49@VEOrI@`9sNM?5(b z(K;sIup-{j7tF==z^hwK6AyN4n8gAOW_dZfIlU-*x(XFezHZCn+nbtlV!gBEum%&x zN^o+0xhv-Is}|VokX=8eD=I&$b8=0^Qp_cpXbm_c#A9yn-?-^Km~TrM`ikv%5uE;8 ze_N6$0&2l;=>Bf7jOPrHZB+%3>=!`@xEb;(Kf9fZQB~5W5x8%!vGp%2&apzUTecLy zB=u4dT5K6SIg_lRDkH>DDO3gxfi4UtwWev%&b|#O2P_jSR4or-(<*aY12?x%AdXza z)kYGTczreDW3HRBa50M{8|ST6ad~Li=DF}J{yQONNw%PnomJN(tXQMQ6Cbd9IJxWU zKPoGctk>^y+#;fPqcwwxCd!mObBm+0H&^RemjA$^9Fi^|yz4itkQ*wYKh)?Bsze+3i$+A9$K(cnMD!}kP-V|T}bY-|IE zn;!1}2*$g@$9_O^eikP}X-QM1n89p%;%Jf)mn45R=ikpa#5<(n2S*$Od z+5cfTyZ6K7?C;K5?-zDc*r?hT;xp^Uj}_vr)?~ya5Pm zYoRJx>%^4DO%<8`#|*_nb7X3U!QF>*KK`t*oAUOsW-VH;fcc#WA)KZ1K$X@h4g;Fe z{PuVQB|OEk{t#Y$Bi1S*BAuLzs8cQ}yA}3}cF^65gOyzO0Sc0%k4<2UI}(tqqAHsW zE!_h{h(&mpUQRI1)ova%%dQKJ_(l~jq5E4{!J!gg$HUEpr+WmgRj68*{0o2kZ`;zz z`3x+p9IziJx@Edjl?nQHFJo!fhifo(+kwZjp@^rYH3mF@c?zfq3jW8|9K)Ibt^Wr2 z50H<*lZoB!+@-lL<9GmG_S(jDZjR$u7GSpYJdP8WF=ut7Zz`=!#xL=Shm83~LYtO& z=-0nG{0&`ktXXT*y=^qu7NUF!Aru%VZYy9UQU>5VR;?;5oXf45z6&9aG?AUzu82qT z1Elk}=l%J!NztV@p4|H5B zFo(2!KyJm+vvNf-tbBon3#1z2)5%;u9RK0{z92P$Vw~*)_sq;vv%Iw7RS=Nx*X~su z5R#+AWL{_g_LFF9g=$HUnRuEenf6}&1+hDIgXrhjJMP45uAE;vf!nRdW8AGR3E2|v z!7&#NJ?-9IT)$rX=y(G)gwCEq>v~L-Lul+_|E!~b?yHB9B_?RD`0ui!7H-`QmO&KG zS)?OgQ6dh{nVBur7|E_liInN*JH}%?Hlw6ZCoh}kzf;8UNNq|MTw)&c?qy+7eII0f;?lnRh8Ww(t`nR zj??8efP!2_yF9YC5FB9U%KEviYk)*6gOG8)Ghh6Qr0%{bs^#!FOue+g8jzm3fHKA(`w{~E^nvSI5{60x^zW~vK{vgDBSmNZH{4w&z_ zb8d>18rc@9(!@6T$*n7Np=06#6es}BGRTf{AY1L+4I?YMqD?zFejloYl+Kf=u+6l^ zUX4#OEoc}gzm>bpPb6Y*j_?am$JRu-jnhh7^Y z4|Y8|w3ef}zv*SlH5lfAb|70h5n8)m!&QtXcd?%@d2w4k=2XcuH_+r>)`^$L4LTb<`iTksfjjA^7}hlk zG}*hvLTQ?u91{M>8xiizyy!}~M5uLnuFB{r3Bep1p3&nzy3)G7iV%*PFNVHuC*j|Z z_Y~j;-iby(DK6%$%kDpY>W2LIS3+aRJ;OXS?s&2=THxvM>6s!VFv7F?8v7LiAzT?% zt+^U?A7IOt2P}$Zl#}288;HA^@wbO@)L<1w>0?=gMUy;84|(*3eZD+~JZxJA{=M}7 zP;^77-`$OGo}+Yr_oi1DrDnp2HLm*j!V;kIwhxnP+q`A#W;(3*4l{ataN4oUV4&^} zKKAX)tJpqwH^epoKPM~y-V+M4pz4cPKoX=C-x^r7(coB@yskpcm&+m&16&^!@3C{V zR&uhzeh*6<+T@>JkBw5OjcOKnShm?YC0qnJItbF3cu)Uc5mE!ay2ZetXytCT6tm05 z0DhUYq^b4eS^7yp39yMAyE-`1GhYXE_(CJ-=MGQj3fs~o;_Y_Hl-k$KaI`DHqO{xQ z*&@P$W%-lPh9)KTwI5!B{?N0I6BHm7^8Ljwp6)&D`~LA zrm6ofpi7hC!F(}AAK>B05X?~3cn9W#-hM-%zsG8F86YTR`9>?qUW|>_<-9v; zX8?cGC=IFH@4Glb!`pZIX#0c@SKYZgfo~&7gRthEN>EyHR1w0xbCGtlsqDQ*X?K>) zY+~M@X@EfdjM-x}@HknhIJa2Yebjtk_28C9O;Ze4USf2-AuFQJaGY^+Qoo0SSYrRd z`GKuYp68yf%ZN-(+;7KovQ$>6ILvFC!kgV#@%kb6-tGnQO*@xbMnHOIqTwNhw?km< zmeQyKa9*?NK$42GW!3_=I74TX;gRd5fz0lcH}#0XJ6;skuIiuBh2PP?UUEe}lSmn{ zl-v{7{*X-JKJU+Oog>|ee|=;VJCxc*~`+j%Kv zc+(8<9eRHHr#cpYiW%_@4T{)Vd>p4WsuVH7=wC^1T{y)*oyZv!xdz>6jSTRyuMC5@ z`xs0f*o(!s(&N0&#@bfikpgh=@E2i8w%D*vzROIo2x-LD)MX&ItzLcFG+-$x?tlj} z0Pi{xSB6?*UWsY3$c0l!n_zm{-?J0^wbc<{4F%%nK()KjUBkl7nFFuM#7-vj6s4N! z_|mm0BcwQm>c9`1-Eq#V!@D$H9X?ai467Q9$7IPoUGQO4MF5pl!s1JBwz~buAF6a*L ztzxmD`|xSb^=w#ruoLJ+7Z$~E_lW#xAMD9mW=Xc^X!RL@y53O2gZKaQjSVcIh2)1J z76a)@iS~70QfQE?q*;Pqg3jJ^RE=u{y_DK7y!>Iy!Z%O{XsCdMXnbACVaaIi{pBL#K|y@|=vhv|7QSSJ~+FHB~^Rxv(;|6L%Q4}mOH z+!9p{awO7ZuEyu1aku7QXsL5zLa2eMT%dla&cbtbl)+pVr|?{=zB`{Y!T`F)b$Znr`5>JB z&5X`h?A&jWgw?i`mZS7?>HU})A=~Q`9J_q7p(53rGUf?Rrmthi1iO`vMHW&1Q{%#` zQ}!JFYl_1k#|*wOki;08@h`F%`A)9NtM8&Ah}Y3c>x^G{j;=MN5Uqp0Rp(ZKg08QL zh66nX3q&2so9*kXu=gMKf}VN?2KIV5SLa!e7kEliKO(w=W4FrDhr5r;4ZwwuAa{{7)WbJN$C@O)p`3lQtU6Ta`W{)f-?)rgZ$$>bcxj*4a;UQ zU*6FsK@_`gM={AY_^kMa_beSg^12vz8aGDnC48K$3>tPrywGeKmQs~z3dpW@Gj!XG zLo3ThX6M@YW>hPygE-bLN+YMBC0MfEW2RS&w2Cg08UiDV|Cc%)R(4Z>{GFh{(6)fy z;@o)_5bvB#zFgnWviL29q?mp~0c)gEJ9HN?($n_2*qV8}hHYCmEt_>#QAzCi_3y#C z+t5j}vAVtZA>KleMpm%NjVev;x^C#yuT#rpOg;uJ|Y}{d=J667H7dv%d8hqq9{hZ4f&eE6abd`Bzd)FuzBCf#OqsR~=*Q4o1N0H*DcA)+6*qvadIna(3xD{@7%|JQk2L zd3Wfi0*EC9I*6=hsBAWbM-_-L$jG{JrOb8{kP>rF$%{2^LRHDSUl-N}tJVAQ`jOTt z@M%8Ph58RUNwYrCC2I75th8<(@}eJXyBFnF{%>uq{>zVZ5W zj=N?>oWUQJNA_pd$zkeP9t#7D{z;xqJjv9)%>M#r(^3CV;=Gez z3(`8Y)>+I86xAdG9^np1&)AyvuHPcmM?)hx!f7E2$a3|SOF~C?62+5xAMhe)ec22+ zt?nnA<&m45YFR{ep74)n%uGW9uA$>)xJ%tM5a>%=P}(4 zrQ2iHP>5UWaCUhzH^BHNYoxkX1<1LtoZsz@qP(_N=q1_++mc%N4xjl^8Fyc5uZVMI z><;@~(v1(WbN4M1E|sVs)vs0A*YzMPQyu1ISIGaEK0coLDz_F{S~rT5rdu8<#mRg^>z_m@;H&ToOCM|W!}SUsrp=+e zUy7wMxC1W`-n#HhlQxHU>Ss~6;|Xr9SZK1zcgSq6$cmRF^j-gSqpHMkrv1)UhNS?h zW1Crx_-twCUp-bim_xfj@$<}@FHGtk+pfKg?p`TtV#+7$7ZMC3%CGgr`)PXH$Bk+w zhvK~Go#dObF9CM*bTOvwlVtuu#W=PXuTNK8m4=a~P9c3Gjkz?K0BKVZU@9r9kt*I~cuy&xJ8I(+a19*fuIeqcE9U+9TH zLycJE9)#n5Uj-kZbx=-F;HjiWOr=&(OE<~fO2D~4zJ(@QQd3Ng6(PFW!kJe2G_E_> zc?70TUee7IMb@!cMvrBVVBPhK$CzaSJ@)@{`~HzcoXIcHL%HM{v)wi2^2rucF{UFe zGX`fc&39D<-U4seggTi3dTQ?*ld+(aF65v}3mxD~w*OMcq=#ZP6nTyL#11E`%ba_4=m%h!Us z{2Be3-(bJ@KrCq;+>qS%5o2Hv(l+iCS_%xWL38z?t{HWd=U>%?BCeAR`;L(&wW|Mt z4vLTtE;W;Q+&RVgeEEB9K}#motZ%N3-U#{Kob>6vsb87h!sFNW*vD5gK{=Rmh^{>j zSnLy7&xYO05GUb2RN3vRb_cgoyi_peQJ%w_jndee$p*fX#VyI73+0rDzHBzvuE%#u zy!IBaUA9qf5}0COFvXFyNRZdwXo!7Xt+(i>kU!QrrrXJ~nXx#Ky}8}+V37LYBB$Q| zrO*OnpSD+J#_tp9!)|ZHN`K;2PF~8}SaKs!&f0h*J~|AzPkYd4gye9}UTDRkllM=z zpDP~5TZ%E>XhaDj(jM&Xg{#AkKoTLNi8s<*8d)+5)_T3M1Lq4XReayaV^6_Z3A2Q? zpL}DN}@wH;!Ni)em~>=PMB?vztU!$Yv=+x1Pni?@${lt_8+f8Lz*)vR4* z*uwQWN#Av|sHq>C_n=$d_XOqnchL@Lj06l*Uu$U$CII=aA#=r6EWE!=v+FxSJ!EnB zproF0rk)$9O7g1H#A+pHyYBW0A+Lins{g{5=tAc}wGf>FY)n17&6R<@mk~EGhjKT1l9&_Q1?oj{|B{MfUY(f%8YyW3eZIHB z%t$W9KZi)4Lyp(L$r?~Adyl^~4d4+@QelmQCkvVU%7LFt2SSuXTQEJ`7V&f32GJ<8G#t11zf&OGVsuvHde?7~ex9+-zN7rAg{~oKOb1~6~ zD2w^sf$~NF#;`_q+-M2B-LpD~xaNjMn(u=Hi+t+R?M<(`J{uOeE+k7J@a1<9_}DB0KXfS| zk-=xDSG@^DALjRXvQ193*)Cckhm3iN{Bhmf)9_d?uzUM)>>&JO{J^f>49l0PhzA42 zu+A?hJa_x=m7}=hlN<8c?CFc2y4L8dSC}Oq9Pk7q1bZBczB&N0iUOLVH>DDf7Xge_ zlFblOxsYbLRF`f8u+t3oD#p%9c~X3G6x%pLtKsgj9l|N$++zBa6);spt;1qXICwc^HaGtolrjD?#JoyF6<-oi;L>4m@%Src+Iyj) zBF2Z`=z}2se^XaA0`eoCa>S8)s}aT|7lD03vPN%*<7y%?ws!mlz2|4D$?p3aPh(np zz|!{c9H3uKC6wOZ1S95|zgky_jSA*lm#1Q7t2BP!7_0ga`-bxUm09Iat#~1W$y(`)45s0&2d+aqSKx|3v_8T%3BM}$4j{~Dm;g#gjxEj3F-OxjT55m_wwQV zRp>6bgiz8#syco8koFIezoyK!55;w{3AHkO=W42K*f61UHrkgdtMp3O{u*6ycpp*% z7_U9cZa0!J00l$P3WG0UU!u)?+->6>b$o*+JLO1qcwga7WLgKOFnB);*SKrEChHI# zOdq$aM&Vp)J)~M;Ww;Hl_0w=$Vb_VIh7jsF#JnBOhuZBXbJ$up?&`X>V-Iu75mib` zJn9vU2u@pM?%E9YLXFp0ev4Ta6>f?ij}hc8{E{H3IpB)f#k2DD8xlhEE;q zR2|C)7hX&^N&MT@=(RBSOc=I$@%|80e~2w6)MQJBFCe9Ze?xOB)5a7xwWlqjHZ>7> zpxikO$t@D;KFUvd`h(#j>x3CiSK}U0ObR*Ro9{g~L?3yKW*G8{neM_nHs{e-UkN7;IvTv&4tPiz+TCr}FnriJ$IfX5S}O?d zTmV}81!*jyYloxfXT)P)K%Z;n!IVwNS5}zG@LLzhXSzmi0sL6?jg~_yA7z}ac7qew zti8yl_<6>#g{J}!o0KO+KhOZw8#%@(vwQc&#FSG*C4&*`WfCc6I?<=^vyF+7chT@S z`zV<(Vl?kyxqZg@uQ^LmUTusIFLfdajjrxW6?!APoalW8B{~;rzDTRHpP%a6?%&5&OY0X=KP9^soP73> zPCZuv4Hf3tGNRP?vJZOOI>0g(os91?x-Y?w6@D`m)EXz^wkO4h08>@3&-?rSE&4^) z92iIG{40naP)5QqkH*L*ohgp1$_(o{$JZnR)*bz9 z76j)TWx8JDx~N`xwRC~pG&+OS!TB2cR?HyWS}7*!`l-MQeIdUU*u4r9?1fn8JI8G3 zhtu2WlJJ|T00zJ#uB-_Q^h=`M7&UTif$`sfRg$@GJK;{X+2dze zQ?nEE?geiHZFK(ny&zn#!KzMA`ar@(FL1Be8Tvt3+ ze*e~;s=^h{-mO>;G>55P7&u+!y#Ax9e$|1YnCW#TC)g6cBjJ$>9GD#-L}Uj4{h^TG zn)azd6KobO@;0wko?5SOIZrF)?HKgy%FLi%A`XAVGKXL@#Zf)x>V_p$H6PKDdd>$A z`+|93x-&+Q!PV49WgSfsfCXa4~{a-IbxKQZ9dGX?7$dEWKHk1~7 zZiKo+nfr_f^!JDJ>&{_n&_fo@PrX{H1ik)C1wgf-Z8@X?Tz*Q~5k$&SamLb8<+&yW z2cs850s+PQhkrF3@=Wy#3RUXql5hIYCGgmy;|IpVH4LA=Y=ye==Of5tZCoinTbt0p zg#J0|QUp)r4*oOnP-C>V^U_vSy2xpz8~7^Iw@gB_J{y`Ww7JBPgp>qz6{gs z=rN(5%ei58I7c@)ep@H6aljVhY-`q#1~UU-BotMS4yq5Et3oDtvmA_6{sFY!`Lw8BKKhad_(lEm)j>UiQheaJP;6hIHv5F^CTb58A2ZP_A9}k zbS?{DOM@&=0NgEF==WM02qq)aDMM0UaCc6 zQfaMXipGIPWLbPLiL8t|T1&Ydi8YYu!iJGAH(rqhML%rpSYqGN;ynI#XQauDKN&6$ zN2iGogw7*e;c~ssfP$AP*+O>~|dFkr452({x&lw*A-9w?T1`i|JOVW~l;IBt9rz zke2<2b)L{Ki59b&e%ztT_YdwP>`97jysc{F4wWVk>au5PNNQ}XJUy-n*qi#cCMV36 zA>QnhTSXlTr}Yvk_@FlJl2s!*HdR42{<(-7J?hsAxhu}`!SsII#p(~4a0u8~`@Ko% zy39=s#aVKH=>(gmzU-@HJ^nz%7wHPhSU;6Sl*DAE3i>GKsQGo0WY1*XBxHgv_HRLl z|F`E+Ud}JSJ}TE((~Sj&0|09%a< zedj^Q!(41tHP~rq=R-?f)};=dCl;zTk$Y{^8AALez;I3l{>p@#tdB7zKF1ZjH|}o{ z!Ml{QjYz9x(K&#EZiNw(Kkt(eD z1%*F>*Oo0~oqx-!FxMDiQJ zKr5*1SEW)s%|@1os0TtGk&94cmJVIn&TXNT@fPd!%IN@4gi{1;jDooJ=W)K+?&y_V z7r;$Uzcqr!uz~|+$PGM(<-K2~!<$8!~lSd97$AV z*5k}|Zu^&Z&PD^nye(0l0FTc;g$8Y`{uHUN`*W{v|2Qc#`8OH((*x_^9{i!kRf!ky z;MouTk8fZQRQ`*DI?^q8sQbYra<9LGiXP8)=RP>B|L@Iz|GFPL=V@@4Zcj;qSvT(#zN<*h#1BjATy4&B43eS%(D&O zn*yvvZjWBFP`9HO8=lb%_ssG*)v-mJFPiX``%|%Bpt5Uf81Y4-Z8E{v$s!v8rNh2` z0dQr-XVfTc?*TBSCKz*S;$2U*YLNtA!WS+C0R08mq2K_)wRUz6@VgD?=@A>>wswz$ zk_5t8jAQ|qbmF;{>fz|dyaA$57|$UER_D@4yl*fnd?rcfR#&*TGG+E$m({q9EuFk=NNSdZ9CbHlEBEjxBaYt)>WD9P$Z35qI? zkyft}WfLAZ;oAY-g15Nyq+r7J;%@=5WlkEXpZLUNCp$Qf%q7$?)u{q@*@vT3^>dZcrG?eIz4`{OA& ztAehey`2O8<%gu-duS0qvcdRc3Eu*B`|bpiiZGyCk$k;;gMavsryqvh(GOy`F?}$_ zcz+VBzYqTaJOg%qd{LH&ECd*lKkV;7AA%Z~jg&ju(QgvQCmQO5s^0FNqF(1*^*LNyLl)5Q!7lM$l`$B~gVByEqJOG#cGqW)_38MiHVGMH*{Pmg(OLT_Ptj z!h(V+;)J2bL27PcJrb!V-nCmDi_Ptch@=Vs*!GgR#0Ge(fLq8bfSx&?goE~9!({*# z^jrg^&%>lW1%Fj~d-*LEdoz`SEkjoHsxrrp3boNEFa^c-kMdt5KAu57TYs9eWlkfa zt-c=B$lS~S*8)sgB${E1M@Dn-zTv4R&t`vG9TCd$vC{%|7}q8ZX%&w5zl@_#dvK|Y zY5W((>Pr<3y>br{2KnxzPc|`yUDZSq5SY(b$4+@0m}=h8^=71ex?K(V8NnlIF~0!( z;0E(otusun6dK0Xc37fVeo!-_NjG^Iqe*H;Hzz;mCHUj39OF|08KFEm2pSuQDkExEEdsz zeCt|uE($Y|;*I5yh{u*;=y)t2s;I(Bi)L`vw#{{km(;2yA|s<)Ji^S#}grpTv>;PXF9lelzmv|-On0-m|IEKJb8HnZxwl_ z6>jo8P{e_9WlA(OE9g9tSZidlE{V2UWwNLivRSqMYsbAAVf~Qd)>^nvs8v#Ey|hnp zxJyzLxZSC`+7s{3@`_a)IyU!CGnDpZh`KNKd7T38#Fk86v?=GI~171f^i%1k;y zq;h>#x71YRnS6bwIP=GfM!Tn>y%W|{nm@QB7+q}6@m+%O#{s^3;JBT)^@dE>_Q(}! zL;1xVj@yxwSFd4?a|^F86!SE4(|^|kQjbyf9~ ziPfq_d82r2KO)19X=anH#y)j@qEsT!-WTab*f*q{yW(&SyyKHcci2Bxe)`vWEM-`< zC33OF*QsE1yt~SXRLR6MAH1NVuYOnji?@1r)T8w74B@xuiemXw3H`{4&2RwphE(=+ z+3B6iK@2~4_I)2@aluS_EpN-0@#a&aXW0;}nx_xN`=|6ZLeCl{ZmGbhEA`juK;;LP zy|h@&qh7+By(ppiJ^Bb^(HmkOr`?5e)AjYDjU$JlR)fXzEn9b-D<+AQtz3tJ8{IQ^ zV8kF(K69rLjz?3oP8PvOysl*)GuffL3M<0+eI?sH%>ea&o@sek`nZ-gne650MW{G+iDOgc{Li1wsJMxQf}PxGajgzi(s z*guJ9c1Ds+Muz7w_PU_bUO`j0)~$Ep9b)~S4|69*U%;3n6QXHdo^)7S)QFHE3XXn` z>nj^s`LrJ@HaQ}N68A+aTCucJbc6DQ8SH15eFx}B6)9Xw8Gp~*0QcN}L~iUon2`C>EBCs5Cb}>B@}hHV;Pf5VDd^lUKNG6RKpXW~ zX|2j{S$cd%lhlhdBTTNzTbilND7{v(CAeAa?Iy~q-W5^hi`B2$zyLr0H`Sq-^$yfz z8TeYI`cY~n^w{p!pha=$e$9nadkuR?P{ZlB!nPp$QY2l|mf%*gT!PwM<>=MvRORQj zLJ*l?Xb1fbb5grM@$V21=Bih`kV(uGrMp~KBHMY1eE#p%v(YTxSYq?ejc)tY=_AML zCS(A0v`?16CPK6xFxv|BD^gunUq&ky&%lh>Vx3DSU;@(7b?Ew*e>MBg_*<`L^b*sEEW_jDtD#lOi>Q2lDmzF;Tv5^OAuIDuv*gvviY>orTXdIz z{i3p(ESIuZO6=)4C!TXRrda{h@}(+X@=9U;yU9R;g31vNc%w)vDPwZeu~B`4kN^VD z*t9ax(6-;pV49^NSz%izY#%l5`QjPn3^JNr$=KH252guUoq4dd@IdubK zV>Et$89mQG9i<0(27dU?D)P$Swj3}P&pp3*v*iv;uQQ^eXlEHc2-7rWXy{p&w%eML2@H-6dOFsGpDmiQoMdHN5fL72GYR^ z2{3U@9bt(xuN#iTFTXqsuH@F8;%xlNdUXw#yDLZZur^srscD`+v*Whe;0~<=S(EKs z1SuyV&M1vS9j(*H3_-*`3IwK>qRf8G5QHEFp%n8ayscQ}XI!ziffx4X&^IAvXOc;2H zPF^_`0obubxa?57z@$Rcx%X9iy$s_fEYdudnh6uzxek$zPGjw?l^T7uM zN1i8U7?8WW9z3(T$5wutU=MlsN~?+@mIDU`Px$1> zMrk(mmKq0L8St#`Yqh~kxw@v}uSo~|3$6Py)iQ#!-I$DgrUByb96mRjlhfs>>zHxw z6Z!z{E=u%dwD0y{z=|!-ZT$Ub#s^0`k9!V2Zf3CcPlPkh-aY>j!keLZCo?d;RT5wG5NGS_>Et>8d%63X|tz)pwwf z5M01c;5n%{IEc;5l21E;DjQ6|buSrUt*<#PdDS|Adxpll4cuCWJWnz54r@=%aw5+q zMT((kXh^aU%qvF`B;;KIZu(CdYUiTbW_2>~6JLa)or0B-ok}#a1G;z5ccOIX=vC_|SJ}Z5w@_ z3uv~!-luz-A;bn;8lG4E1^8Z8=Zp=a@0UF%<$5M zFqHx{&?QZhe71i@M5FUfNdamVS^kzbEAbfGR=Tj`o64^Dx)!FcmY+ffq(39& zSq<-hYmVqpGCvgOJoFmBuWZAn;7Y7j@J^5$T+H6FG?>B^1Gxkbr{53_cB@IA`egxu zSgr^RNVgDuB!Nj~L1z(e!M=KT+h)R#vH;}n@3iLKAtHJ?-`_el zNu!m0OEF><`hNzxu4ITTq9u zgUbJ4BI?CfTw8A%8KR4ysm~cG(|_Kn+6zp*b*-~iYQc!ik?bX|_kWPxR*ykgE&X{i zZPR@jx5ws4U~=$rn_#pd_R74nkeb=RXV}T1I*tonM`Hi>JLj&~D8g}z{VTLN>R*lN zO5>mnYckSwBz!J2bg7I$5Eo}Uxv2VYKvp*$&luZb~7N4!9F%OQ8Z;j)yQ2@36`wZpR2|78pSv2F|j$%=yRW3{Cl;`1=5r z?5)}ffoPgOms@Sj_XHo=0^_8yMv^AVMJq20IBC=m&n$SvJbE-eKfoitCOZ^;%8_ob zC&*)JCBJ+NLE$4-U>*6@vd3y4sbRwXZ<+H;X4?%nT>ZKclE};{_Nc@ zSL5oZM_U)oK0lq}h2?-}F>j*Rs6e?>$ah%c>-6%vd(wvTIk>g{mv2wLdi>*`L^QTN6W z;T~pW)hO29D_q7Z4D2Fp;#*FX;ox6=dKX@ZHSS`VGO~8?@|`@G$+Z51S4iLw|C+IQXAt+F+~SZ7_cqo(**BleIpB_}if>T7EZz zqO;n|k1tZMMe(VYJe*?wqp)pITeS~@%&x0ZH)xFfXV!%eu_B{Ow!vKqOdqHE>}$W)SK zJu*^(`74C941_EcV|AH2Tzi{0Jl71#8SIoMj-Pj2@UiEizy!|IbMd7 zAGA;pp6Kq$>Z&r0Q>BZG@gd(Epu)xq3uZQ8dUwc-;Nl!dZ)Y%nl+;Nu!?8T4n)HLh zy~M9+0&jr*K;DE`hacTO9%LwwfAzRhj%S>AJ1NBKL~2t3BTr%XEF2QiXF>;~FOfSEiiQ=c!Opz;I3Q8|JFi z_OPt`KbpQdtnUB)zpb@wd)aOo%eI$REiT(F+qSW6+jZh{oxF^bjo<72`CZ@t&VT2e z>#6&G+z(`@_mb>27|M#1_pGSK>$#E>CO%p=Gwoqb5>iD=n!G2=0XjdylB)4LqD70x zQ&=Z&WNm|-eKG1;Jp+|i{h97j4XB_QR$UZcWnlvmiL%(T%^?k?v*iFuHBM8BtBRm4 zp*!AU-;}pT2`8X*b4(aZF{KaRcg!9)0Uj<7ZF4gwir7nUpO7nVi4kYKL;N4aehEwWvjHtTQ0L%%rh0f-itH@99TjPmZi3$8Jo}H3wS{ao*!_W*?!~6XFKkk`enA2_g|c*Tg2GWl>8p- zI$d8^tTnN256cUIbB!3>At8#{?mVHm3B`Nuhwenzo%Y#$cjKEvA`kjhjWoUeHg^CY zgEaRYz0`IJseDOmmS0KYCbg6Wm{Sn|eZvp87)$M68hn1qt$)HifbkoqTJ&1V;+H2_ zs2MKWu=Vh3o=kl?p+QRIP}7Jk9Q%6hNPv!qB{=Cj(D(~~lGVpv-zhDJGhW?R8J+t$ z%d0p*F66;z)ep;fTscZGrUM){GQpN4> zz{PPl=Dpv}?yn(CVfgkpq?n(Q`rVE_nF5q+h2q2~MmX+oIaDtdjy7T3rBdlK zUGp`R_rwjI^HkgF;MgPl^DoAc!^cJO4h|hF)ACfyH5mJyJTGv4+iHC;W?{{!_lLIH z@AXOSrac_fLacR?p>8-9mL}DkxxP7AKNRNTjC`c!H#awkhGCG3Ub`j3XEOg}3z7px zMh#Bu%YMNim_J=}t=hy7lMj&_9=!31$JbV~;dph4Y$# zKyus{=JN902^}nx+OQKf`)}d~>9wyDl5V}>ow5oW9irvIvS$H!42?oBT6sr8*-Ks! ziB5vwtn(w!s@BSb8&Kb+#eXR~u43zYh-)M)az3(u`MJoeu(o4;sz0Y#EBABz(3flT zS}{T+5^cIVdn(!kkLg=%L-4g_gwV8?oVasKd0r{;%@YBODCAkJSBq4~AMX(8RR8)o z!UvdyS)?R-sw1&-oc3XQL}XUCpcCa6SujIX;a$VjC4hl$*_T;8wa(KDtJ1D2f_u3d zs!qLkcW4Jg?ii!!A2rhdoUX$dvnHecPWPVfhSXo2{B&0BOgOM*a3|-2Z+>)rU*_||+de)~akf_t{nvp~A^b*_QF}%Hp z-kn%YQPz~^NJG~Xl(HO@cJ)4yT!s5Zc~~7g$}_Zho(=6jVveEl}4DRC7VjL zo^A41H?U`Ab|pd{U!C2{7?Pfo;Q%+WE0&_~wc1_XbLkNyr=9~&ug*{E5TdhDSb&1^ zQtP0n5RhiBK+YGxZ1t3)d!~oLD|s)#C3_LjP;?UO;uZWQud|5ZUHraLJ^+9SNk;nBW*QWlGhGEa^##)zhlio^bW z$+zII{GBB?yg*}kgk2Ec>)${gR0Gjet1y;~aI_4b$FlU@Jx$}tecrC8vkA6Tn{Kl-iTyuBDz>J%7~8VFW1cdE zG-;Vw4XBf0S4{~iSdAdMl$vDDMcLT`5GTdB7n89K*%^`nEu>Zb*dsxxVq`VPdpt*l znB^GefL>;IePD?60BE8R(I;B)!=*UF@5Zh^i%*df8IEM)F9KnBCnOV^Jr-#GzoVp{{6_VdvNyD)4&dWOc60!UP;PuO9HO+&Yw$+ zY+pMZPcA8&IRiKF%)vGhlPq*8ZWu~CQ}8#twM)y2D73k?3*m~cm0eHeq^nbMTZu9{H6HpqU~$;uRl z{e1|@J2QueVC%1jT}YB%(I?}}e%i$6j;SVu(;ArPm2h=2{CVHq--QGOnDPU7tQ0x+ zhYUyD0>9eMy&BEgIe{YG3gRd{)K0qz=PyeY6VLsuZ}hMW8G#5gV$(^t9U{d88S0H9 z#H22^%iY!O|MCRSTIAIrxF|{7OD#toHj+)a5euE zqvYkP{X~(-ZOg2Qzt)|$Pm#+~g6l~ZE<8s^DRM2SL}j+l#MazF4XVqNQxx~his+f+ zxlkqoI&3d%{3(<0=e$8cj0|MPEF{3OV!W=8-J0a2d+2N}D8@enwuqVhfsTeIG?5fc z*w)PUFBK7=qfee<~*pvW6Yd}|!HHa`FeZs#z?BZyJ z@UJb6F!_*sm5=6luYl|dl}9(6aMO)&(}hnrJzGK`mPdD`?u6JI(mHF7l^gYKiO}Kw zMS_HcFSvwq99^^vO8mZ3ipVBdwzV&1@Jf}*&%+eoF|*fy5;=>=K2L}WuLoNnnJ_b8 zCTX}ng{DSp<#tx*FoBG(QlV?>SoN4{!fiOZVvhhylvd4i>hDFi8%2rW)<&)O20zw_ z+t_4Cs=m9Hm38O8-Zm+Th>?VFk;$IytF+(=Ynk1N%1bpQA1yHO0=&Q0m|q_**~;q) zM@s)dSlGkRR6t*sceRMXZX1lf5ie2;9+3RoPTCU}R-eZBVU=Dv-N#7bOS)xdaG31D zYjx5U7bKko70C^w4nF2YZ|p-U`#s?;!1AUGXv41179#%S$nebgEFrA>baUR6a(x>L zylY0Mo__V5FkXQW-v2)a|7OczEtii`F8X z1)r{Y40qFV9+f8BNWNZUPwrvUmtQI#l-I304Yx;I?j{|^sp za1!1s6>d)+d#S{ILmgVqx?{bE?!w5kfPT9ZMZ?XUDPqxgVaC%Ip}9A9ah^w`wDF3q>R~DMyIDsF;)5LAd2ImJ`&@p9u{}P zn6%K6si{<&6JY6I`tpp|;6kyN z*rAUD(^_OT>X$I8b_6N(=*KL43A51D0GB`No1gI#ZH=KLhf{ox_ZCwSkjd}KSp9r5yHT4%e7oB>^3Ax2rhK_oTr9!Hx6CY!20f3(WN!yr<&mql ze0v01Kud<`i_4!RJ+_pgk)Wv@)YkUmO4YA&VqGWj%#lb8IwQH>^K{W0G$vmaKzGlh zb8=`xLc4C&wtr_7t+u*jI^CM=iOJ`(>wWE~+vf^Bx?O5uAsBSC^40|wvU_gM4O|OA zcyu(eUqg@hs2v#x+|y&wuF*I?Z3Jt$Ir;osFKBL~J5~VL_3_+g4~lK^+<%C4@Mtnz z_4TX84^iQfa=_!zvBY~#xtb*})lACvx6NDOp74ldPq^-A&xnZa*^0~kZP5w@{8IN$ zlxLIRvmbytnZx2e%u|gY*PfS0AOMY!_Fe|!S8h1PaAay-Z{7R#dv&-}SFM6x-|pS7 zH~SA0GE0SBv;9bH^R5_tTK-^jaqUT{nQdFOd3037W46!?-yPG^R1jMeL{RwNQbWA` zs0Uc0*X>6cG&U++S$}xM8B~i~w16A6hpuUQe4&-Hr-Xeh3}$cHVZN(*r!kI`S;@mp zyk%74qH?)$wdi7T=p2SS2vQblSA&np+mgMK;c9e(r^r{EfkRVUOiq`fTL&nF&aagO z`6pW5n7?vM3hhBO$#)CJudB4U{5zIi1s^BiScDBVQtHP=@`1>^iKo=n7~@5y7SnjG zvIph^t&q0UseM){gS2=R&KAe_5lJ}p$}MABf%6;?eF#eur=&lRJ%`k$)wrY{6J$?A z>%S=of3}ZO^wpDGvW|pJBL24dGL7qn)4<~wlG~lp+LxUX$+o-1afi)JpaLCZzcS4! zn$0!UTPnwHMsh}nR>VG3cBohZ7detkHF|abZ&5z)OLT$5nEJ__(X)&Cdh_Wy&mK{| z?V__s0q_)hXSX$m>NA%|X#^yU&?h|gkb)e0Iv46&%@uhJCS+CCG#ViHdclpU~}kIDLU^dyYqQPrGGQKPfsc8Bn5V} zEn)cgW-vG}CX&yvMEua=&$nu=l{e*}ja!HAN7x3rio(lUA)TE^b#z3KMD?9Kr9e`k zLWDwy$|a2n;h zMk4Gc-My1{!mns$At}J4iheJ{^p>3E6Gyv%;JAQc(mpE_Z>5**R|d-Hl^nb(OPiIy zMEk8O)9JFGm?+UC^TshvL68ZP1w#6FM{lmFz&|299F)J;qg8#1_v2}3`?=O zvKSEZhdeq1Jtj3>Yv5GXrPCK7p2|^0E1G0wABD47gHOh8>BVrHO|f_PH0Zk{ZFBVN zVtP8f&HB%VO-PIz1Wt8RYstH@wK3E8MK{WK__-Xi>D7auzdY{zC`iR#sSO4Y6~yUN z?U8G{JrePZ4D~0&M}5U#b2X9zZ9kZq9JUmAo`uzw1$ul)^ z>d?*;KV;e=`yR)cBBK&83~fbylJXVk3r*38|6$XA^K&{(Gj4fUT981Q!}1jq$x~(}Q_jkfRj5Yo7086|Km^Iqsc9 zBiXZuM=!zXSH?TR0=gkLmU2pKaZK7v;Z*NIEG@dsZz2%pJ0Ul|@o$xq=&B2%SE9KV z6=hc;>J_ExA127w>QPHpjY&3!WCD~C>k{^sC(}bc4WnMP-@lH}ON}R|4=1>ng3*hT z>9j#+#sEik-)E?rI+>d$t$enOUawZ(R0r+$@2{}Uq3--~SdY;0_$6Vvd9*0 zKO#uz#?IC+7nwe=c;=rif+>N$l5@4|Hoo!?>rr6sAT)w+&+lf+Z46P&005mty}S&* z)E=@0VBm4b24l%A=s_yv(9NMvVUmLPia$AZ6@b{3ljP@t9D$D|YNneE!TPXU1tl^> zO7gKUcZyy~H!8C$TQ-Oy@yE6!jYO_F=6IDWAFGFPn+>kXkFfP(01DbM-B5D-dnu%` z^2IXis$-lwVUt<*l1XXg*u=LYwr?y$L8W{>we8JYDXRP9NThKgNP!T$B75AK5Hl+W zZ#M2Xvqs+{*}rX-jTZy#cFxel92Ws#1~CRjv}E$Nvbv|A&ZH!O*NZt@CqZ(^97pwb zj+r0-KU?L-1I_4@D_87I6>bn!v};dfv;sXuhqLlPNO+L@GfX=Ye=1 zL3WsB#H!V11=#i%kBYg-!aa7)SAVAk*qMYxofaqgb?7MnXnvO0mbf00e6Q3brz_y? zwI9PMO(T!dE*Geql5IHpSbN)7KGntWMjZJ&PAvF@1!k?;=%glnozI8VK^CvMUS%r-V z1UJD!0mqH9e}T!~W3?S1;X%DJuJK1s>5kJ%f)H)q&Ra}v77jn~+5JM@x&ByVdtHBB zLm#(vG{NharG_2;N?xOtzTyy_c)(p(#ES$lRPH%L0h7|%YuMLj3tK?aAf;?&iCh}O5;!XjFR7k zdY3o=;kML!?Qq&L0Xxy!h&{{$z#u+5xEl|OePo-qF2}vCry?40^R3s?-1Pc!oW?pS44jU4wg4DlNhG7sJTZE8^PURL(N~&&;Z(o!e#*-7 z{be8$-(<4viY9ZQQ!mflmG>1?%3dt~CzZg|fF3zvn5u^XSj4hq&Vt?rfpNn(bEk)Y zb&3Wx83X>w*y_HfpQN*8%#9VC4K9;HN9Ev8WFXhjjY1r_zYU)+;6kC9t8tgPPNMk# zM}knOTT=WL)X*tPRnIrI##>EHm<;CxORP@nEg)ec8~a&ln&U%lmCPQo7R=qlr!j@LP9*};KWb}`@in)o@%8e9Xwa0iXO_1!X#y1lrw)6I1MO95m5vbQ)e{p zq@7QCY3li%GVr0Qejej=;sukS<{eyZeNJlb7fl?!K%kP(DD|nQZp-?XIQDwgD!gBtTVS3{<3E9c%alF36)hPF? zkD7e<&RJT;X<%8M^iqV)7hEfQ;1?!+cz}ccNc486-B?({xnVHKEE>y7uV*%t4&51J1m^r;?fFO!dUQ}+ z4Mek{TV~HWLsBbZnHi#fNetNQ%O#Fql2@4xj+Y+`Ggv7QW?IUdccfiD-&JJ(X=@D1 zj4|RIVFiS`=2;Br@KO9mHO-NFSR;ORvQ0pr zY9hk6za1aMLlt0oW%d<=3e2TKseHYe; zLy1|?s#Z(qMWC5VX1%Q!p#sJa?-oHW$!ydBkCqNqG&+pWLr{BEEjp9E8s{V_(-qG4X(D3CNF$N%j9c`j-a=NL% z?E`wEY6&(^QF1NEEQY=1jZyplapPDFG7D?DYPCpuU9R!koD5N|Z|aP*-0T>>kDMUsC;ji3>3Ho`DQ3pg*1PL#@#ll>5C1WZ zWRod2q4mpm5L0U|kR6!sU65y*sALDI{7IDfJ3@9|j-zF{z{QwZ#6XmIAl@PDx73t| z$7^DM&s9hkZ*wmhrqSQzrk`R{ErsMvBMc%`4_GI6kqzoTPKL|xlQ~EJ@1%y;8R(A7 zlw7t7f?SGaHD(6ch%Ged+JW zE(FQaQ|9T`hfbYv@nF&aD7A$li`gQDgpOEtLHMWAOpxz5$gHIQDf)-|1v}PwXIBEv zvhr|;pvWJQrH_D}0dP;M%4be&jeJMUsyAR_?0unsliZU3MBm@V|6Kp02H-gCA-iCA z2rUnrMQmD?s>~H0T0etJLEdIwf7Rq|D@ELr2MP2kR^*+XBmMd_e7!UEs&G%vX5I{54 zC2Rl1tBu(7xW-t5H}evUKBKfIak{&a`8p0`TeVllA|spQKi<(HN;u=qpmrU-tef;d zMCEMIr)5#Mufd^K!AlFn*=g4$lZ4uDlyNX$- zo~T4JJRlE^wBvmw-9N}Q^GSd8yp0G~MVw*qEm&RFBeYChOCrG{x5hth<6j$qb z1NY+S<-2;h$bkbObkTtcRr0bAG#mS@>r50klT{`U-};}ykP2z^NzAoV#Ydu3#d&kq ztqIzUU*q2gzbUOe0hVsV)Pxn(k2+=@7~AH;lPvXm2KgAR9{5neASv?0z7&& zKi=~X{BRfYD{Q(sI|HbOF`6(bOTDZ_f-qS$$dkynP07*%6rKzLChOC zY1W{)pQbA67}h>q{JUx+r zZbJWA-R>DV3n$GUc&SVzx_lolFH037OS&qt$}P92n*Kxom@vK8ZmPn<9c2pihA9T_ z87OkXqa7Ob%mNCADc$jI74yuCM?&v3r{HIx56w0EHOKEv)RC@59IS1;)>pB+8THvq zyufSG5poN4cI^`48M^Gn_uIE6G=iohJfyt!?$zD^$ULk|_x|@e*==*|%;or(({-;8 zdiz12KB9>pzmr$#OsQ0HE@R(SQC88~guEtar(WsR{w2ac>^6!CC!=fxtHlOwhSV|R zZW=C2HO*^dgj)$N_S@Lo7uI)DR*DEnT>3{sN@Q4+kWgZ0!hYZ`2+x< zEe;GBVp0>dAYyM+ag<)^EJZQ1XeB+e?G}sBEkzn1wZ|=w6dDo?dCY_}AHk7*m}LRR zG3cTn`(_^xRguc~om}@>YuqdWOQ(INh|8;RD!BakpkmPHsp@8ph z{jZBTJ}~h?p(=z9T#)6#?fcc@W(~2%4Nv}YZ)^1o+=R5wt>mxd%l=$Owny1q&5?A*sY^KSI(DZvx?g9p4bI5=TXC33Vfr{ z9R^`?8`m9>A3ec1IZ<`lx%R|X_#>xpmMpucg|f?kK+R`DrqUA$4I*&gl|+W^=1KJt z>pFdk?xL6MQgwJA#(6&i++^iD9~$eq!4WPE+}jMnlMZt_fE=e?~^!^Ir5RZa(2%#J3|Z0 zRp{mYw9CU8tmzARWCEA(kXso>EcRz7Nz1~33MkcraMso@GF(|?OFJ;xVmMx>PHc0> zT-hD6c&`;Vyl9T@*~dD6wkKw}VbD03C!`O`xczk0)sT!f+5NgOg=pQ^@`yaRO`jynM~G8 zDEuj5ME?E{M0Ep+_eH+AydeWq6rSz^lnw4_+=J+c^VpOYMBVj7$>{3D{zMudpkYKkNPxr=@kk1c>ZzSeL~N5 zln1sZgGH{&ezA;XZ1*);--#gzB+k{UX?MX^^H~yu9s&!$&k`U&c;})#vuhJGr;rjU zNQ~9tdj)zp`3o^JgdJ+XH|XWJjJP8v#-h3Lm$$hI1WT{i)R&RQOFS_NC^}Hjgro}^ z#cloU1ULD{h5x$^I>Yk+WiZN;+VA5^g))t_11=;m+h7bHuYrQ!f5VFD`@u-ubMvSJ zww<*NYCyJh{Pu%eZ;BObqCblhzcAv zX`+uJDpN9)+-TzX{?!=QU$;AmM#8NZ?Ql(_WU`J7b0BqAT}lIKgL?wi-lnaciUbQj)FZF=x2~|Wzh`MjOe9e3F3?BWdc++D3tDqH)T+eO#i6oys(b# zBfiv2Po&R*@pMDJ$Uwfc{O+0`9%-bAM6XDo)k&UAe;eksGMmi6>JomRN{O5nH)U&h!AKDdS^i5A zp|&+8c{0D++%)_M+bBn@R}7zt5?KXeT?^TV#s+ZDXbR&14Zq;Xil=eE0dXS85H|Dzz&$ zSwuCq6ShdOOta2%rdQA&C|gFakdp}{sdm!-&DA2vw6Lt*?rti!pK$9elFlTCn0+5M z#xuz@(nvaKwNhA3|MUA&-ux4HU``NMQRc(7DoP6bXBW?pDhwba&{Z1kuI*@aM~aV~ zO>v0bY4p~*)8*@$=Q9RL29=MW>8eKk{Q3h?Hl)i=h>RC84&?T{q z7(a#vtE$*yrEtrvW=;Oaa=F_6uXtxSXuHUjo*Wh9`-5+2P)Pk6+<&W1CTE%Nmd6qB zCQ&Vu*vO2Fc1}Y(>#fYR;}S`0B2Ega!eK&8J}5F;fv)o`b<1q-9rr}1#1Li7E-Lh* z^(ZSFd>0{oC@qDY3%?(LJFyTXn0<%0bL-l$+F~7BJmiJDS_lWB+B*vU*yzZNP z>GOrF!g8u19yZKfj_I?)y}OU@zrCW4uG9HFU z9-w~6^vk6@n;!7&htG^kk!7y{P4U;-GnJx2Y6{f(R=UJXCHr!&>} zwNktKvtVocH{&|z;2#v*2Tgf2Cv>~8;wwbLS*r=C83?SuM!u}uEc7yHm%isf4&xn< z?&hT5(tqtJ6%v&e<;q!tJ`Pst2s!W=1_hG5yp})QYtkL2`*)TORgC& z^UJVPkOTp@bVy$}xeVufvE7uhSr`YC^rACvUXZr>6PX z>vIyK2hqfIO3nqx&*I@rER8De!+#?&4Eq@1vTg$`1TTR9DviqHhPprQhdsXf__JWh zxF-RgaVJZK6V3)Jf3yKU9HCNa7z^;4c9%8P4;lC?HLkloAAEv~q8!8&e*j#`udkn+ zvV!b|{U>D78U)9FW$~L)<07MC#Fdc}!#<&t%;eHKVhFW1Kr7k2GM^{g_GVHybhOf5nwtEtb)+*c?y}2?Q>StBfSM@|-?}srAX^h!J#bO}_Vu7sdG8!~25R z+{4nGLmzo!QLf~_NI{j{_!+xD?s0|d`YEoVBUg9A@7NxIB#qqnyxXsM;%+x*d zha91J$j1*6+b|2p>{x0IvB|Ga+6tXo9af@Ou)=LQ{y2qFc^rz42{s&se%%J#eEV`Z zIaBK^IWG|wwXE8ZMjj<6G}y2W`3x z+`>|Q@goWz_v)1)NOHQYix1)ql7g3|rwduE9`176kvZw7_{7{bF|bM;L<6sGFw_gP zW?eB!KYC6}EoOV|DX}br-r9N*2(6d_Y>?{owx|?yRy?G@KJvB{4O;u+wO_|ti)B}5 z#8?N4)Ulbdk_N+Z2Sg%d6ahv@L! zfsxhR3{Z8<6`ogb!L-gGZ=nTT)@46O`~xTGsc3Rn#`o{-UvQmiq`>By$R!dsuA%b5 zH&_V>tPRvY#k7*PK$*HPu6IhQ-LC@QhXUWAE`78+waVN#yURVWAe?uRSFzpAF2h-< zh^N;@-yg1*(}U2F4{yXj-+d`M%3jY<=_g!->cxWva`quVm7J|8Z+?9*7&XT^%MqM*Va|rh zKo{&z)S9?gI(km~n(#t{BJ(vh;6Bw-*s7U`M%c4q-aA*ZN7(N9)%8MF)Y+riSv%%6 z*N=)#nJlx+-h{C>2L3UI*=}jgTkvoU6v+P^l_hVZa|$0h*W|iVaX)}I$+52J;@Od% z5XKDK6qyBUQA#L^JhZ5_tMXX48P$^c>0n9CBlfMG;6Aq|Kq{T9M~(5-yQUaHltE%( z-v$aQ*T488pAs5vmCo3+ z=rKEwP`LF~4Jqa6i=?6C$XgQ>6h`*a(A%GX3Q*rH^%+pERI+M4A{j`~$DdkL7Vh6P z%190@oS^%RQW}&A-%n@DNCo}Aqx3U;sea^&lYV(6)p{Yof^^!tGAZO<>k|)gG-Oc0 znqqwwC6w5bcc8Y^#=Xsq-%77#I39sn^So6bl!ZFz(ubE34~E9#-t_w*w!vH({lvC? z-lqq$+dWG5i`gxuuI(ttKIl)~ig`kJx!*eA=f6ljhzU3m{s8%x3GV_F9YmUDY$`xjHm(HEUMMBJZ{KASlBo&>VJw1}M$_vjwXC434| zq8N6y*usuNjqkKh{Ms2XCIByev`UQSwNqdkto3DL7_D_1#vR5T&fG|VYWzV)EBp}w zs>2-yH>IvdN*o_xo~6}6HgD+}nRPzUp94c~g*Z zs@;Ewv3=d>{K5S0g(#cTjihD%iEZGcl+w%5F7_Z4(v!P;JM*+wF9X{7NJ7FG8&K-k z)q)T7fTYixxQJgO_XQ*ef0TKJ!&16GFI=s1GQS%LgdH4$*D$k@TWSpL#fu>JeO%~y%<4MzGt?lXLwC3A>}2c z{?|`)Pnl~F8Q0DZCJ4{ID$E&l5um;tWQ2Y-N~7<7%y73@OEnXQ0tihj zG`~TEie_|}xPtc5pSB%7=EswJ^M+=UQ+%-afZ=bJNx7J(B^=_#G*WNWqB{C1!?hcX z-$(TtQm$kdd1=*Tykbzmd?d7HU8mHRu!nq9CZ15K)vu#H?i|McBz7M3DVHo%d}_s( z^w-X`x5+XGkeoW-yL?df>{BxGEl>lt36#e zGD-&pTrBzxDy{OP!k7H#*6SB$&bGqkN9-@^-w_}X6wy5p`t9I1+rg!ibv@*7L+Y=t z6E3lVL6WuMTC9aFg+;1j5Dk`bcNi79HLN;hN@w#vE~{>hFjr3hpyf&}pfcl0dFFdM zOf|oJ@9h3~kAvTH@2m`NqI}{M=quId*fPfWE{?zUmFZ|hOyhNnkzfHuMRLqgAm+_Q zU{nt-bzM-IX^C^*3rRdWav?+k5lX124@Mi#h9oS!A||Q!d_uVs-SIf z7`BED{mo@QmQGPrY(AE-U76XVlx@4cX^ZPaR$>M-HtJHLo8&C!!!qJRW_I-WTQdjL z?>m%;1LBfqsNNi`Io*hOAve^I>ju_QPx((C?hr6*Pe;#hT2hDm->ZNa?yFc_$OeOVb|P$qo+!kzV8 z_{jA|vkiyR9oj{GkjV~LQ~dP;iZ+^fFz%p38~=8pADYmuEZ_-xnIc#H?j zCRwSDHXs9);SpW|C^UYGL;Bu_dZNy!2~OW4j~SCSlK4#<(G|aTl>8L(nUmm`D=q;S z`XIxX9i;9z!$r}(Oy$QH0wfe`QH_gdyzl=W(2i*vER9(4q9n8ryFoH1?2M{WkRZ>9 z5q{dYX>R%nQxZtt!=bq6ZcPiv$MW3Gc?99n#;WcvP7$8z5Ni6J_UhQzk>NgdSnU^*)^9 zKJ^9XNEnV8LO~g4pc2rCpu3q|48k2Y=fYaiZ=F2}^#^`BsJ0G0@#RJlDEK0f<0*^A z%N=6QKxg~fgsbG|fwQ!3fVEO$#)^li+^sP5fP7ytH(I5Jg?y5tS4n~AfW#kw?vvU5 zkPF#e^`a`fu*~DAZe-*;os&xS;yY3m2{=;dz#_1G5irv(!;+S7&SB6mK;l_;PP3UM zD~L)PaI`6i;{^%yQDW#e6IXm!F~)=O%5DTJ-Bs+plo$>=o;V z@(|i#%7h>H2}&96RCMhEK*)tI19?Sq+PW&Eu5Pk(Oh<67WUBeEfn-!G512%ZzVEpq zZH(5#0F376R*s}P8clD|mn1$zJ8p4l)hc}Qv5PHqrW=_@&lB~ZJ=J)wezfp=)58GU zB`6WDy8}ZBsXG>gn{Xd~oO^F_Ec#+5Vv#4qQFmI2Ybq`@l;Qv&6(0s69Xa_0g=b-j zi`XQTK$V}>%}?;|7m&w)7+jlLU?m4uHO&*g^*CPQFLhwYBh3YQz&NE``$j#X>7GH; z&{#RG%!o@w9r+M6+*GMMFsm&~Imkff0--RcfFz6U=)p-Dz}M~J27iYTZpKr7#c|-oYcBI`5jmJVnwU#zn!;g=){efw5J+=1bKGqRd`LYfZ5BrvENawPvB{QKF^25ZeowWsGRJ4V zR5{%aGiwHAUpnQCYxyUZ>3g zoUr>o6AkE-AHE21ZN8Ppj2uphr3!+JoKH~<>Y!-8g}$rwBDElcM3&QXTU}tY-~8Y(AYpX^}K2n_b`U_U=T4DM8hVi^cO-uO2jVJFOdKaI?#+a zVIM%^c{GdL!mi|9MS?_=a7viK={bf;;+lfb>HY5y&1Sf96_Lh));;%gy`a+hNghwv zZ)A{}K_4-Q_X21&E1Jt^#;5#kL)y*}R3wLDvg6)<3f1H!YRHwqA!GSxBHmZ<9glqf zG8SS6i|ycoeuf0arGh@tyeE)>8bLDgT}dLSQ{N)&$)Vv}23aJJIU}$099vxagsVmA zD5UszdrZLA)ehpZ1?5jOTtyg~=zt*LS~?i$-BTfIbNiUTZ!YpA%5!%T&BNV=4X*u^ z{4gnf>!KojE~tixLBI+^zf)D$sDMMA5RT{XycLK!>j;A&KcN$QU?_AO$;(nG4~}3i zHqCW3p+Mu7^aX>{9<*U-94s~qer!45*SX26Rge5&O~K8NAr}xqJG?bkGr^+5?p+79 zO`@Tf(@mXlLAQy&Gf^=Wm#^%b^HIpr=e0zzKecx$TXD*t%=(k&GO;m1S5{tIh8?0G zLS5*YQ<|W6&cq*_6-4=ed^@M#gi<63t&KF!GyiyO!lX>t()+xxl!(jqlwq2yA6Z!% z&aP)EncRUCnTGYg#_Pv)3!%r};(n1e|AZSzB0x8OxbXZlY)_KXqwYekW@78blEqfH z`PF6(vW2CQqevPR2Ec2y<8Yy10CkN_raC-<`WBl5whAqtuqTO)o<721fwJFjTw=Qt zT-rPfo`S1hv;JA1tx`KPktz>jH{&+t&(SfLS{Yf9UsauEXq~rdSkNhfA4md(5R$|D~#0q0_bE0L@u;m-5c!-klW zxDy}elq$tWfgU6Uw{P&w2PXA3Uer3DV_n7EtXTjd7Bd65T9gv%aGPZ;ZDA3)Sd_Yap=&m%A4x&qe)Y)gbjSZfD zGh!p!=Hi9ZxAs1ZNXohp6&&^xaM7}dq@P*5zL7%4<# z7;)tm5a|6}QE=bsxI0qR3&hygTD8}#!}jH7H-JJ1_xE<(8Wte(dfBIFKDy%$$jLf` zzlzr26vk`ScB_Iw^0?0f1M*`U_S~!j12jY=w2ZikFnDT6Y;R61 zt!$n&0oTtY{-q}*Etfjg7T%Y{ih{|>VL%79ER2~k~Sd1f;NAnIY(gMXj%%5dS;8C`Ac1=i@KNagdZPM_}b4s zV$ULGmS^`#`yZI$%GSKTIdTsWRsQ{dG+kv-9Bs2*U~zYMcXxs>5`w$CyK8WFLU4x= z+=E-N5Fl89;O_2jciyk+{-d^v-Pvbny8E0yr#m9vLhM#*gV88kIP$K*KA)Z42Ql9p zyDTqR;Tj;yyg66k9;ZBz^dUxe8a$-D1OWF>9W(~>uIQOkImoX zHm4@m5xCSC+b|j7f*f-?i4)BvBQ8 z#?x1eego1=g*+OW>gtBgO2kbUSS!q-`|w}}|VPBsxSGgv5X z9aE;99a>M_z%38>@GweF|J5{r{RiD$NNO%5{^!t(vp;0#+UPsfDGst0Us#_{+v9PN z{ErLa^D|D^E9-KbM-c>yTFpEFB>zEVC!0UV4%dqXh{=zy?;3vToE<^!+Z;f>xw@VU znWT0e99xjZ6xbdr(0buJTLz!^K&q8$3of=C7LO4NYQzHQYy~rF47FE2*i4CaT34x$ zaHw^eVxlIkjQ1KMUkg|V*j0R|a?ZWQTmNUO6y(}>4JMt8MY(uwg5S;YAnvhu-= zoR0kZ6UGZrJEU*L2)heRG>6>m-1lqaT4IcaZ8*G6Hc_evoz;2CT--bF@cCOX)<2cC z0!%yAq@=6d*Gma)#B5(!?Hh}tMV|uw*HQ0_*sK$7ZM0~vj$60+XP$W7UmF2WvHA^u znZ%wJ>hs&h@tiT-!vzLQ_T=8&tYbQ2^KK|7MtfsJ08B!R;qLz9ZrRGPZJ>>qe-gh@ z*1{=OUL?*qrM=ZJ9@{}AO~`+HT70FNyzx?v3=s*H>gg1C?6wC5BN_F1;5lkNY9()! z#?PDoSIWX}ubCt5jTj5ucGa;bwbelWES$; zW*OsQEO-2*=E+{xanBc z>(5x3w&G13`*HJvo?>yZMC0%yx5l7i6eCT84EgNv z3q_IsLDfP+#U)w1E0&5;NCLWHMQPYAhge=;L#T{&?-JG zW;Bbxmidcpu8dZ{?4#S?ZXaSPCzr{QOxJOCpm>Q*y#P!2eA!5;`?L8#t_hO+0cX2` z%X2YZ+z6}7bmh3%n4-;L&)C#V%_(U3ovhufGu^CtaD@Ly6E2Ma^zNfq;YvbC{`1t) zz1hW1GGSi%RrAKTk=&zcA6T}S;3kLdp_fT+(*mIL4ng6J;zC7^_Hdx6#$&;cd+8ft z@8t?}FY6{~xbd}!xzis&U%ernoH84@U};@y+!;vR4Q412+mY!lHR$}H-g6@U?>L=4 zl2yUIB74U$U*0e>=u!N49>?3xU!!M%ba~z5fNVj!JvB5C_xfNSmEisO;j?s4wQl51 z;3C8aVi42U#8jzOnaSo_TJ5~jXlRxOqHiy}+TEamEuZ38@I*E$fb;wX%Y-?l1Vuv- z2~@W~QX9ZIX?N_irW;4nYNWY5X13bIa?!LXmO#PF)}IOnnmrXwG3YMCPlzu?)}*&o zor(%fD6h80@DYC3oXJbV3l9>+PIrl>UBfU%A;p0wL9zwR({#S@xSVzst7N@I%dg)8DxGAg`I*9oV9AI>)h3 zQ1FUlXJu$0prObQw})gl1IVmG= zD0WHlHaqraah8Xp{O5NXnNLTcLl1ng7E`E!oI%jwDvT%O$^)n9!&>^;^|lT*dDs>% zC-OWZW3;TA-BOB1B2*XNow8I5zYwGK~^6K*YRu2?!metIqLvyL6>@`a^ge ztQz~AdL={6RR(1NCDnFv&|wuui@FFWPCe^Pj(c~MmAZ26EXmW+&7x#3fIQMA50vP+ zyfOksYO@&5j+qY?_s*SNZ9G-S-HhP1E^ z{+t}uI$LJGFL+Kf76An#d`vICpB={LQSb-0XjgmAn@H_{y+39%YEIIN&KfA$spopT zH(SbUu3>L-mUkhC7_mR$Ex<`qN9cd0bSR^cFz+1BpzrgcnC`hMZ|}NKcp&ILw0E4MOHEj<0E1*St_K4^ZgZsoi0GRfrj#XCLbT*cZ%$>*8OV1}1ZHWC>4- zuOs!goTBhsTC83uuOn4Z-7p#T*-2D%Vo7sPI$cj|O+J%p4ygfi-_=nMcTWxrDQMo_ z`l+VZ;b5LR@<-SZp0Sn*1lQm|HVwMfDC`*1J?3Ww8)p((d+skry6lny9LAIKpM`Pz zzr&hf?xRG?v#%zc{RHozvQx{v!{su+eLJERkg5ebH5UwdVF@3tDo6Sd7l;L2Hke^ddTZ`1D+Yw3 zO{h@qUP08vj|W+ABp>(Q;09iEiYjm0G&{-KT8PN5$jns5j>uL)Bh9p>y@erWH1c-Q z^ji9~qsdZE*Y#MQ0Q@S~0YDaGI*mX$C#!O(f&T{&>MS)De@-{Dd3;SbBIMJjFUhro)jUFrM z<`}NC@RdaQ>fq@W#V>{<64pl3!)c1WG;^&~|3RR%*HD zKtLbt&4J@+ITf(FvAF9QwMS6?=3RSviR2WJ`?Mr^P-xR2{TooIp)5R2{S|(Hy(=g8 z7s4?hAsIrT-vkr}?^KvLbtRksuLZaPaU7iiiZxl?>i+mpeii@=yIh$l} zwVvU3@p_m9fw}^4`o8d|{=>gh1B>2C>QaVMO9^znq9hhL51c)V_u4&`h@^}`9h>k6$nb~5-lFxfoywvG-X$qFgtzif5Hv@|e+?ll+? zdzHAa!uL|+M$Dx;i!3`P3Ac*%?wyMCR!G{8csFO&=s^O!=M1miLCgXEco?(1Mo_KN z!_qBpD~l$#)ZR~GxQ`CormDX#0pX%2rSXl!@dt)c`4LHOOW`^i+Dnh8Y83*}L#^|x zfRs9}1Ot@z9gF(7_jXZ~df80;QFT$nt6lSaM_(WVd8ni8a|@6WK?wOfJ_cv-L)T5} zR|9?0H6m28SNV!tJlAbueI6^3vyq?0N@- z>+q@r;DA7m-zm&6u^2EJ;TJ1zbLpO)GKK~+5JhDTOUgFd`Dee9rz*x~mDO~9i58o5 zwKJBlyi^{|Z7Vafyhu6Pmc11)67CK+5Lz64;j;x#`zG9gT;(x+uN*MrMeB#!k3Y6xF>$r6XUPBYktcm3LE{sk%5+Gjo-B^q~#mOZkWL z9Xs^ok0-v#Um}^za77GbrX!eoNwb}?MGVQa3&vlrtyS+5&|PijJ}^u+Z_kn!G_wFL z{Rw5;1b|mb-^mAEWp8kMCHLQ&KJi1vL7Idw6AH413SM1oCrg#1x!7Po5VVN+0GK~g z&Jn-rnliifpm)wJMyjd8K1_L_e622k=HUdxGPgeAvr@q>vD6CP#*YkYFa(@39}80-S|Qs?3a67 z`TB?Y;PX8jNPM?SBD8h;7)JsG6$X^+!U6D*dQfqbrq1LZ5ifZ;^DD*uK5yBp2H1Ct z)#Lcp@jM#dck#AKO21$b9!8A!-B=3p$%-);AKGfJ-vk7({^9V5Xy@IbIZ0jN-JaGQ z0dH7KGL|T=SQ;7RB)MfFC^y(V%O~1DJVo26t^+st!Qf7SY!3)5|7xcA9W8Y262oGKxN>b{vyJ?&xHyB21P zRI_RtHJYkHpMIrz(H$Lp$<}mW%I%`AS=G%c- z#v*FuDjpr_gu&!{`;EM+OkIy7iau`D+(+Zz39H9x;jebmR2Y>9#fY>`4aA()+Ily9 z1VM2B{F-XU>OC9u+7_?_h+=fPiz%K8;sR6;&e1> zZ1yBXZr{YWl%wQl@`atjg7U1#LQc|Sv7mv5IP~qs3b$$NqAJDiD`6fnOh8)2cUvW@ z>Owl7|Go$@R)fL~c_?GbaUmkX1G|*N=eVw7ayA?#J#3LwWKf8=yUm~eivr-z4+=un zSGLLc4Z+ow+L!Hzll^mEsPvP^&`(BoM-mkaSU@ATR*{hzqF(SZ3N7arNfz7ly98Fh zb?u9H?)@8B+(5XhLJhOUF>LuB%blp1v@P_4BBWyk-O0-KLVX=_&2 zF&g#Oq&x`iXIBOeJY%2vXd-1cvk|5=D$pl@}m4?c`i`;|IQ740$e->H1rsgN=%-;gjRTj;l1u5kcFBSgE8NY7vQg zrLUN}8^4Az#%<|g5%rvWh#8-ji*+B{xc~~gy4aU3e_v_qnNKycj4Co(y1tuxiy(q5 zpXOod48ch)w8x!Hgl@Dgr|;4(0mK7Fgrg=l;70lpiK~)dC%ZnXNs&R1-GlF?@}l^e z&_I~VYNu^VTD1g?QbYzz`dVX9T98`#N+Wz2k;iC6KHk}2aGq-R|2(IS?x;F=wxl z*p8@f0b8d3jeGTFHoNgHz?l^NM-Mhhlo#o=v&W_+6Q9KroGE~3;=azmH75|XaUg>z ziZK7k4Fc<|+60VL8BNFkkWQU-+BQ?C*^t$hkZ+o9G1Tts^8h&!CI7_xMd`XG%${!R zffNW(JFzKoTUGCmqHH}Gi}5r;@DTS4!EiMj)tp-ryv+n6rKkadS>CdVNvC0Sv0M)W zYwOu0Q$zO3seo(It(n{C8a>m!1^xJlm(hE5%rF{&L50(rHV_a`mG+>horGdQ0_Fqs z3x=6ukf{wss?vHv$XJ>4Yn{Vn0{IJZNNIkcJXp)fG7$^$GwVA;S|*nY~OsmimPAV>KWNn=YH1z?NcG z)u21Ox15`rvlR1lPp0SCtl!4adPh?0TRqjWP?k;phX|j8Q4{op48-4_!qay13KiMbit6(8q`v9W7n+98k;VZ8=E~Nt25Uz1kr(Y4zfIny)-)y6wMME@J z3Rm?yzwh-_wy0Ye4ANm8%{;p^o0OTu>8OGb4or4|?}r!lB_qi`6VZ4eg9@XSL&N>> zb*Vp8hrUQc_h|BHKU%r`wHbW}bSc#8@zN7wPj6dIe)pa#>Mw9xm`9N|Y&=tsgh^e{ zau%YOO^yNRYeWhU?|^;;1%-5v<~m4<=e@s@-j(&KmNA>S7A4DsMx-Y0$#r@r0frQ3 zxpMX^bZ4qf5APN0%5^~QP5T7_YsSbMG(JRs`r(XNcLB35`M03y*PnE8)8uzZ);Zk)<%#_7~#3`e$CT zgAs$81#F)^W?dWZx{X-J0?#KDxs{%FA9Lj5c=416ll`~=It<6z*Mk~!d8K7xWzjta z-o)<;K+ez#Sx&7fXvbcL5YDqacdPf?5A!XgH__dHN^`GRDKq`Ycjvf+8_!bTT`e!1 zMoqObw{hs_J$+Zo<}56Cp{I4s^uI1-EOBf%-ikCHKk7SCo@2}9>P5~6NvZUasM3p>yN}cEN^pMSiW4G z{k93WDFHo18%oh+<3=AJ!U`w=q_M`hi>Y@qlKQVF5JAB^g7Ba=VcbcVIybDZs8n4a z)@8F^NQ%#hG49mDzvsiMx;c{ri3;EZ|0?lr87~v8Bi%W;eJ7)K3a(ufd{44NmrY}szAA@t-uxTZzFQs z$t+|o!OSatYSkF|W!|N-K0cuVf^l9@9b7gsR7?x*ItcdzpsmD!PhCw>0d5VQC5 zrOoM6_atsrQoF?WUA>aI8bF;T35etXm5FFKA&o$j&0_2VG!~J(9-GJ~70;8Z%%k>b zR85#@IdJwQe9d>Vm1rk@TU)7iWhsah&n`;)ov}^7_#}ZDF~5}KCeZu*S&8f7UGS&; z+)KdL;WC0nXHtx2$6>c0=-9R=k3DW3{X8f>gO_TFwl|NQj<<(X6YI0?5s12np+#)J z1Bo~3l35+OI#K+f^{XJ}WA&=`g*pv9u+lx{k&nU#gcrGnqSNo22oa_nSAVjwjXuFI z{j}}*b}rKJr|DUg=(eo8x;}MFU|-gMU+Zhv8{O=`+2dNGSmm6XFHj)y4Rdx8Zbqv4 zvA@nzbYBmq}S7aSFXx+X{X=Ym(;VWH~Lhg(4UPoG%7Pmx9UgBvI^$K zf`?CxRE^H)b|NJ22coeYf4u%WX6b!b!)VJ5Fs%~lMLi-zt1a?Jv;P@y<`J$)yF0h_;;LS$@(h?uy8M{A>VI7+uAQar5&z5)3gYXcQ@8 z?8z@X=EAv5d9bdzoScOd`^ty8dH(u=>6XxSR21_zfM6+o2l3?C7f`B1#lSv!T{+jm zfY98nL3JYQ8$2qHPd9jL?Rr+hel2`^-$CXCN|Y;l!I@?haRZ2KQV zV8Kq3d1d$z07stZLIz$EW>C`W!S;#Wb|WTYgYG^fE4K_xj=rA7YaT@Z12s4Yqj@XE zToW!k;)DSJYjiqER#>wb{yQzsZv-U|c-s;VO?hxeBc11UxW~>0EO)H2ZLrEHH`$>b zR2>_KAG=;O9vvwp@D4Ma^?YG7LdhI%Yyn|J*ScmXb#eT?dUVcXqp5t9X?>kOR%um{9WM-N?rJPF zF*;$`QorzcwYY=@vX*%krXAx3oQ%DB8{v(KWoaz1sTCk&?~__7f9#5AX;rFxCNjXX zhI4+DCj2X9WvDHuGbk9ALTAtA^D!OiIJE_E1O<5XBi9VVuN9r7(sv0EJ>r2jQp(9g z3h@El>UUcf9%)m{VD`5|`V7kTa4d!Fzw!eT{NYGs^&HQvDEd~sZoaF1{kq173t|s8 zWjOHND4vYd)ENOw@i;R~wY0wd8luQXX5|6aeS&HjecQp)x!Q%%Pgk}whxSiyzwE0) z%lzxA2f*-yJsj6OR^xxmcGAg7a=DD@%aCh>l2QI8D;|=@8~Y;BU3H#y)5q=%Ngn>< zF=LjWf4~%Es%zioQ|b<`0%G@`Z`T(9D@4K;ztuWH-LHk7*(P(mVx{#rYsX=QTGc(T zKH*e^L85NO3TbzL-AEgw=hG|TV!Y0H*U7zy$6}F>siQ?1!%`WFm9@n&$zec%YH0&l zXBESJs&`&SoYK|=Mzo?4 z-V%ME+R=yZ#Mc?$>F)b`*8V;pI@rb?{;0J#DI_q|uvC_lq}w6TTX&L9WLzGjJemVh z!uKQiFz>u<>;o#k70I!>VW5jn+o~is#D~Sbw1;_ClYExnK z(uAK|%s18G%-kSjqVhpkUtn1)}+%k5V08YY}1b; zvk8m18g;<{(JYO72shIA^pqI8_GE zuouJSFM)uqhwc%e7)AL{A2JGuYyNt9dD&x`i;{%BBJWzmf9Mi)6BD>bwng*6Ltcye zCu{xocvl&Jx?5fd<%ZqRKg(sp$42K94}5a7O+G5Es@N=!S?5Ms`B@Mi|NU7c|AW+Z zA-}Y{{olw~zywVyit_0fcUS5f23QPYv)@F~UGx2SG*IR6eYMoO3OMW*%$=r##Z{l1PVu zO0k*W@L_{|Z1Z-IBXu{zl1ZZ6G%M9l4?AwJg!Jglks{++B1m^I@7&nS;8%7ugNP(X zRs7Zz6JZe_s$MrS4LCWuiM)ffh_e&EU6LBo8%FNW$3l}`cWwKym9ghSc_2}@c3wG` zMgPo$s;T^iqDNKPXF?tuK^Y?+HZ{Xl5>pHYt0Rpj z8%Bo@(Aff_Zi>D?*hl|)ZkW#G!RD{v9A8=qp2;-A`A>hFo2(FN7nlR z#H5BGsReBOp9HKqkffQWNup)7!{rg8`18HHbbeR~ea{6uvAhKt&L$x$^`G{w{yaSd zo91>ThWuQ-24sXd=!XdFi`B>!riMj{TT7bkK({c-Q-(u$yT4G%LeeKT6EhkeSWxmu zR*?uD8ld}Ou_vu*&777UAlDHLkq6hVF*_tNNT6(I(iL*!`Snh5Hu?hOggDPM?Y=|A zQvt@v4c?yF-ZMQ1VF$rg{1h>sQ|HgjnP~@>dJ=#X>MlYf>0jzJ_n%-;&WKDm#_HGst zvRbO-XTJQ4No(IYBMYbMkdP$WGqUeXNs&OwC+a&{&)DLA7l>IqZHlg00%aJ4EN*-T zyaX9*?4H%sb0@74DvxinI(i4;#A4p3QHrD?`-ediL%up~mvud!L986{|HuBqYv!i6PR9-}w zdWUAL$4*mW=I^#d*6Ut9hlXbiy$&vR?hP@V=tPeT=my-blh#EMW*2SO8ux4Th-PH4 zGz9P6OT7l6Aqq@rwOX5lSWv8;R2v6HB<~Z#AJf7&3+Q|C|GiS;yj%sZ(F7 zH7b9~t0VubiB1X$KU?~@jHpBeM~}MST(Bq}IuD#^aCkqk*T81_4Dg!F#874<7(#7-qhVazQ24s4bwx~}Z z9do)+vat~WbcsWaHbC@UG@+*jl3wPPLY;N;B#*j-wLoeix_*^rfCjRab5lQ&u7J4)H{VaW)B*y_X zYyW;nCEFwHb_*h1cqJZ)9*8Xy_E~;@vE9T4A`9?Cl>NR6XoiuCCp!ar4b`-1=M^zI3S4M&<@w9bM<25Z}bkBivDW9yuuCa!$ zq$fnID9p5ud0TUQay!gM|9{R0Qp`R6_e z&7hg6%g46~_S!k(fWxwGAYCfR_`?s4V2|K$#4`0ubzq6klp{bBL(pTnL=Chdk+o3si-G)s59b_PK$Zq%x`&|r|68@o% z#Vu!0X2mA%4eW;n+R?Tt%}`k%*w66Gs#kf^MLG)-m~BT9^{K@{_jm!ffzBdDO~gJy zt6qbn9|7ajk&f)j-VW8*$=Hh*f!Ak@wEHk{oc(tP&X$-ylK>&0f`{%N;uSugL2F$> zHQ^wm1H_h0>&fnd0NN1%hAez0#R2{T1*5tTgDB*IB7h=W{j(rk*yV-V-i%rxKiQ3V zc?qD}vX7TN`*-)>K+%qn0xMisH;K{%`}L*aKCj4 zT0o}g>E=6hWNEs|0kcDc9%SEWD@gk%c6w%y%UdLfg=L3j=)m>Dvi0l8! zEY;L(re9L1I=p>V{*xETM3x`FP;9r$(jWxJiYMV$uA~3mHdq7XOv?#UJ~uM7Y%Cb6 zN+rV^o{fGix6&rLA}&eT~okWmLzZ*G~cWfjWe7Sf}o)F&4MinAuE90jsm9vGryJ? z(K7u4so4Kc>hmi$=qI2pTfqonD#cH=UV#Bl369!b>k>&s6xAGUzuC>G?}Ta}ugnr~ zZi(9j8W4jUj|ar{V<=?&m==uv^r@wU+BvMKM$^tG=%R zaXX8RaoR4FlV(?L(SMDP;x`IBIG3J!G8g)o+lX#(c60m!eWGVgIo)>gNpJ^-$j7uu`1 zL+7j!p)=H+**ihC(T*1$wEmIoyxGn$0*r!!%~WK;WmUqb)Cv4c|E~pbn>7qfM*h zx+i?1k1#JQCv}nnKfj{@M`ZCg0nTR%aviY5xPvSejOd+4@gSqC8oejJdBWC6Njgm; zZZ|D5e)tVQr6760EcCVa^I>TT;55pg5H~32(XnnK?kJSaf;n6){-O62ND~43TP=1k z3TX04wyQu=rLVQoh3HWXkicVn9hKy9?Ig$*4%!{JuOk@a*SvhZhrRbZmoK#YT!UBX ze{K5r+Y>RLS(d-MadE;`W&R?6{!|H+dI1ZKvpc?a0jPD~H21Dg-OIJi+QL^spd#Le zQ>I>|5N0Evj>yX+{O=ON`jkBC20kSyAqs0W$NbE9<(IqyDQ=7SJp%SU>_1RrQ*F>F zN^RI4u$N0nFrh#@lIR+N+JVG?#*YAY>&{z?B2_>>e=NQ!lAqr@^ z-P|SPyR~OA1}0fEa=&QocG?NPu1mNc zh2t{=uEAE8rkGfP0E);Uk!$m>_M(5>EMotLp=#*f@g8O{t3SvaZwr@LB+#+)BV||tHFNO{<7hL(?y_m7?%8sFMX`G zDoreyafDXL)q(ln10M1v)3JqB%_99IU8m{~U#q+k5xsLIuADy%St8uTV#Go**s^59 ziF7H;Ei_*gRlhQ%pvHJZ(@3aEUn5;W7gnkyyp~MbYT#EAeXh{w?^zd{GhF>VQK7C` z*0FXy_l&D4(;2(-c+?x1mK`wd{G3L6iIUE9AdnVol2E?Oq8T0Gj08b|EK;DD-^S74nNYia4&FG55*cLyK;^;}1T002B zlGO_1h{83%cK1}EdCXN~ivBLeq30$^6{H*agVy|C59F^XcK2k`_r0fb`gt<=^Wt)O z`9F-7sj08Le3kLB!4hED3Ps43J4$+PbjX)cxKRSU!POv zDSo%GNc?0bzm`1M;zFpXN-wazqDCmwl(YXUaMg-EJb|B2`fFWuB}Q&bI>c?6@>}ED zzFJPKt|DO<*_kAb>+B*b1Gb?7ET!kab1MwsN+TB=L*X?qjM<|#?%kKcoQgVkH|H>* z^mxyme}oWs+bAU0ogClZEZYY*2@L6)%~G8Ka!q5ZMAN2foL3z)WXl?K7NO;+wCKIy zTUVV*o1Qh7Twvd<0siTnwYtJI@2vH+FO4gV;Swsz<1zuy zBWKr}us0NF{XCB1i$F+&VI2Ld48A@T1${P*_?0A%SY9t$%AjibY5{Adqmwz_cwBQ- z%HR>9Iznh>zFf_2f;vrh20G$CcoRA=FYWcvuULI(yE@)EzAL#&uYKf1=TG3i6ufBI zY`oaGKK~yFy}b%Ih$AIJ=tXRe#Px_d&2yt@9rWfk}{vei=r8DBi08>Bzzf zb=jAQ?4(7t@D+A$&Ij|Tq*S(?>uBV?GL+jzNY=AycVl+5b94Ew5xLpvGv&Re_3Kzh z8bWIxSpt7t=6pAHI?HLb@e%-VmWLA+M4>El5s+e4CLVF@naS;$G1~>L?9h`?eofMC@JzO8l8O55lmzyS1?n@#I-&qfF3t;HRW{5t6jPt$8CP|D3 zs79JTt9Uc4GaJ~cV-gD_5f(?%X+^TtLW6Af2c~umqtD(sjh-5l+R+@qS1_B3z)R|H zqFG4)IF&HKrgV$;ACz#hW?@yCGn@L6)3sd1F?E|Uq_Yl=g((7ZaU1y)JvYJ=jD3qH zks4^QhZXlsorXgj&{kNBPbQRbqtIu_B|<4G!&nZ<0Q|#VJ z8_xHWKT{h+`LQ{NU;FNVBdxJ*=3b6vtRU5$Y6tEPMLisAmnr3IvI$$j%3?L-2DM{v zLpsYhyT(3i#0(|RgQwGJZ2}K+WmE?&E)rHkn2LdysuQDu)MK7IxX71 z&v}t?d!>5eFRXEyfipC0X;enn(XJ(PqsZ){;9&XUM-46Jz}P+ePy5YzHfQ0e$Vp86 zG8s7#_p(!?#QM*dzfJh~Mq=do>LAw?`Wpg_**SHbyVBLpX2a>~#lERwTEO?9W)5}V zs(#ryWbkkm{l@#aYu^Y0sRV8x=GxT8jVJS!Px1edNcA?$^I@XT?!9S;7o0X&Dm05Y z%${!a4TPMsr^#)p z=HVjScw^E;;YD67MVddBX0>iG`=R$ZQPso(xhj-Sbx&DgNH1VhGx3mg=}DVdJ0f9o zA<lJ)@neJ9X6U19)UaF= zyC0)tWAWjdK)6Pb5=SqU68P`Q1BuJUgvbngV}JV#eGrG@4adD010}Us z2Y*-=FzLrm2R4`bD3RKiK9j30wq;R~gB=_4q@ACz6GO4Cx6 zsw-k2KaYDQmB0y`Hj0SbmB9EtAH77wxnf7kLCMf*>OIJ6j5o|J*w>ZqBdK-aM73AR z8mDRDn=E~GI4Yx?wPS9?sFsT4S`aF2jFZG;;limIrTl3)ZK)e=`jwvkRV&q+^2=}0 z@#3xr60^FV$WH;3{fEM!;M3k_LV8glXj+OpmWX8Ow16?h&`d9uFSskUp`0Ch7)RC< zZ|Um^6wzkB4mZ9l>;vp8vB;8j)Vl)XbIj0qR$By!A6Sl_6@CdN*B1r?FaG+Lumv~&+UI}T%E`=PRBoA*{FcdB z|AgFL`a=@(o*evE6m!bedmmGCIzhto;WP~-)*UYEsoA9 zUX{M*K<2N^`$(>Pk6qP5t}s~nw}9(EgJKfL+@3hBI)kz+{95w9@=(`sc`NM-n)ml)&b9Q zgT`Mc_KhvC(zP{`{PS(=XX~$qd#Tmz?T3|7Ea~%m0&}VRgE8NgH<1 zYvpEqFqQ$7GDCB+!$qRczGH6qT^tVWM)>p8i}*uC|Fq%z^_lH@jcNSp&S6f~J=h@_ zV9q?s&0LCrEsiF0-CyCCbS*0b;Z9ETZbgF#&&Pj?X-BB)YEvzdfgou@IhMW@g8cQI zJ0y)A`E=V8PSsGaXpcqb`^U3GzE0!^`vN71i1WIglvumzK;y?*mx&(*eFsX0e3b67&oyCe_+#}i!x@iLUIR@@5lyEdfT45U z_;Iv*rGq-CY~P4pS+=3pADk@$FWf^ALU%5Cb1UU@r!dfVAujpj{2U52?msV)dJh8O z#Sy(--dCr7w%SsF0>vdFPw{(*%k8fB9&BY7FV&1FVOb5BalRZ`AcjxkUKK1jIZ${J3Zg-$Lxiw>3)rz`x_LQ#^*z3E5km=)dLu$WYTE9C<9*z?x8Oc-HJ)?+=tu$b5wHA_cZ9_BjK@g?GWUBazY8Z~ zwt7ohY5eEjzRYzG_mdm7hbx<(ngWIrvcT16)RaL=Ibw|!5#6W`?=^Te%mXv*$P99r zWZV_!QmUzCx^@0PSiI6$V&ngwRdM=dQ^NwoXAg^)$mP5ANB4w6*=n!4ltL*G%2JjT z-q)#kXS(G$lZOQ*W(kCaH4RLS_U9MeC~{i@-m6L`x9O(~o~AyAQmj~{R+|*IvbCZx ztxV1x5Hk02#IJ47VMeS{*|kmUN6A7^KfmiFJ)#n_*v>aNWF;O$ZaUY==H`NzRwFO( zQ2NVc%HA61epe+2S6&El$e68cKh&%Y(L&!Z47t%)&gsJf!izc-M93genE zm8!~xdBR=vBm`>A9OkhQ%Fayp%l5V|QaEqcF)(7SgQF04^v3e8i*H;sFQz_Y*GmuY5mtp&bjIJcK5z($cz1$q#S2wi4702mbl zCqjW4_CxY^PV6&)C{&9 z-jjo#`bag-KZ>M8V`hWJYvAVFNen^FP{)jJ4An^aCu!c9UUD{t3kqiAlaez8gSu`` zU|ynn2xKtAl1D}5OY2U=zgNK5#Px>0^*$OI399`MxVj)&mQ19xtD~bo-9a|E1cTL3gwb&OZ&ac4dV8C5uWU(iCB2 z?s-i2<|Iy1|1>E46U@h!?Y~+ZbbAE@`W>^kf;D8@>+CeJ6=8!0+IOh-%dM_jl6L?3 zDuSku!pEByyBF+!$6~uy`E}OHhWL0|$po*LfbXvH(PG`yiCQ-&Kk|S2+Jgy&;xi*t- zSCbkLpfA!Cv(WzK@)e8)>R{QD&iO{KGgD}ypx%GQ^vRvLo;`ZA^>NLUnJd>~ zyeNb!2V_?)6((F>@E^dgRkpG6sq>gi*|PRb$A5S%$s3IU)qFtD^@HR z_QNYaC>c%eHN}WD0q;0L&kk|r#qCoEic(O#qwUbNm@fk59J=Bf9Hl35(HS2QB&3bw zOD;#~T^$bvs9w)Y&SaBJl=m3Ed{9Ms|9387r_PCteUB0g>6MjcO&<9Gq&S3PtlyOp z6eu2El>z|^Pv~cV8_*2yN02Pt%VK5Mo>0~ps9g_!HK66z+upY*;l_=!WKbZ4{envm@_%v3QrKPDH-vMrdd(I(W!CC!R^UKs&mw7I~~=yW0tUrs^0jGKn+C`2CFw~^J<|eQOjJ~fW!$nC(BbLz9 zHU-4Smn>V1U6IK&*G48LHPNKefGWSL+-=h#@Jg+$WOteM$fJ`zPnu5zb1TxuDZsA` z3mHdLM%%80tG91ylu?cVK;o-|cYMUPj(=rv(cc6kmAie&omU@7XB#H_4^5@fXf9^q zSe1D)mQJ1(?Oe}%=H_Q+Du4@?_+AwKZal}94HK*)=6=`u;sk*Hgy+p4>xvig3Ff2( z7pDHL-jzCTuBq&v*wU?52?Tzk=`HafO!ofd9uf zo^X#dVdAx^`g`ZxgpzJw+M3Xcm8Y@k>DGDaufNZ~&-hyv_ZxClcb6?;=lzadhRuXu z7WPXU(-Kk?;D@KhXudX+pDa)@XL9ckgI2*g_d?dyb zEL@uhePZ$_yhL~AehGPrbdM*twvHQ(km=Qdex3&i=LlR(;gB6VHGQ0|&-4{0=kpg9 zPL6I`SO?(W^>4Q`b`VV{28D5{GBKIz(^ABC1wi$|OroH#7cc-)Fyo+wvYIC(O zD%;*-7E~VXk~ja9a8a`!W&!OHUb^_)xW#uMGMdnm@hCQlaT+Cekqk-xt0TQ1=48+B zTbOh3fH-GCf2w(Y(~^{#<%rb%S1@GHT^T|DVBo^9V;hC`uKPM`?1qsquEB-qXswR9 z@-d2)RUsE6)7y{bgf-sUB|m}Gs;`TPLy2I`)90@pKDI$nOHib_rIXcjt6JX+zHX>u z;xcw&hOR$zg|(7M*jNR^L}p^st%I4_kh6E;+oD3-Llfu8%a6nb<)Gl5qL^#ZtXN4q zb@!3vfkU43`d9L&x_7kf7aWfUm?C8-Nx8g;9!h^_w^P9S=ak_auRzMv_X)T)G~g;N zu$CDAO93ELydHjT&JN0%;7)(zN$jyW%#pYRaWO9ey#~us_&?-JRg>?(Xgmd-;C5wN(`L{&*C3=FXhy)7|F`*EC!g zuix7O8^}_hNW=j>^uRmv`i(?lT@AJM1Wr9wgkWt4>*^r*J$#N@?_llmb?XW;zTq-ab9uXUWBqLd7KX|9 zVD1U+Q64oStJ=3SU$v6!wRI_B0;``4Z;|VQo==F5k@)^kyL2E>Ky;MHE@uWUE%qq9O|8mRbS>zG|~S6bkI%!(6Cxyy+%Xj;2!v*LY26(ZR@8T+P@gH zb5Ta2g?eUO{+U7u*hYbt4nsofe~H}Ynxp^DQpTCIqRHpog;EShloFi$Tm7cB#&aj9@~}>c6d|#jhWM=ac91=w`))NL!2qe+lcL6-F!IH+d;<* zL@fpQbk#Vi37v4wT_SeV3I(glQ>BT9yiF?Q2m!(e*00csVhbRCzAqLG8FmUF2T+Mg zo3G^_TyFzTO18!A{4*3B)`#;kbY_ow;clH*+x+OVRH>i2{23&~=CCc)*58Q79d6Zy z{$OG!Xp0-(tIKs4DMD&h`$3eJ)2ej>pIITC$4W8k(r?4i>+C(2gcDSb@2uhzG=CTt zn4vJ={3VL-dy!b6rixOlat+0vJh|TbhM*P!ftVAt2?lnH$YK4ZPyv$|HuM^KEh_^$ zajwMmc#=JYUjRLkpyf(~i{BgZf74y;!y`R?3<}5?BB} zBLQSQ@M0nPe}~Kz6D?vpDMH#~*X#-~{|SdD%sVsG8U6$rEcC#WC zy$*vu#z-4-%m-d>_RwqySEtP;*QHBV!Pca>7oc~EGnT87x>GxH9VzR2m@2zmL0V3d zZ!qe2xMjOiXJJ2XEF|n%I_`xe1^zJucStzal#;77oU-dDeq^O#9wl0iZ{LAER2P3@ z%#z~#+FaraPAURS zliGWojIadFb{Lay<=|IUA7{^xeR*)^q&Ud7tD` zUCo&bAr&p_SGKEXLvfVt+tfO4~EN?CZT(9^**+oE)QS4Nve>04WlxjziiQeMi}EG zL8*SpASo8hFFqd3Ft=m`=6aKEv!A1cO2ChxRcL8*?XgNW0p3fy)U>@$VU)^ZTNMVc zfxSX96t>{N&W|A7u-#uS*z3o1B`!&7i$8-Or$GpPlJb&Hd`5`SywP7>T;oR5wV|Bv z!ziQosw9^y+t+AdEvl~#3zwb)y{3ko%HN*0O9!8N!=2L&oHAKwwIXYmgr1wLxVa7s z&~n&i%U3MTy_XMMw!*dpEJ~a&Rj3EjUJmD^L1af1#;Md0m@NkyM=FW|9*%jc+t}+_;mVD zIgFYdHiv=*NZAzagsARgp^E9I&IjLjdDdQ#9A2!U8K7jI{$Ns;#JH-IRyN4Y*iJcq ze%O@!46+bHEbwH*cVl`4kQrxaa>3;82hU#Y%9Rmj(kyy`1`pPvj+Ue>QK#j=7MT+? zY*ha&C)a(YMH$u3L1oicD=?!8K?pLF>pb!S6eyL zlm{NC%rH7Y?Z*S+0n`554$KjrU~VZ0<1_VOjhq;jk`St2nQ8f8^nPME;xpAEW(Lp> zp6dE#h&n3i#?$k4hujEQ9(CnivXCEPW*X@V0E|R1kHu(^n=rFjaAL@RyK+a`!l>72 zsMwN29*-2XrM@&_%1x{^w9c8LF>7A9w$%S%s6~~12l&fgMUnc+)Xu%grZ2V=01dufb|%5a(=1KxbLk47NKZP+zTs3 z99uR#3BjEF$O)5*f^y@UOh{KO%)_5BPLs$?|DP9N_*1H6NanJlL2RiEQQ7A)g`eLz zkq%H_#tQW5I5Av*H!0*iVks;?y0>!;1dOK3K7P7?&Jazw{;LMOKcf3Cjvne%l@gOC z6gpvt6gPhewa(Tlp+?OaXLY9i?eZo~RzL_D+UME(Z{T%kA7OAch^#_{j0XwEroxAd z4iOa6&H=gG+ceO_IMJ&#(R&Gq9?ssh6%k@v{+8H?z)1;QER;3&BWy4AMbWv5+dYdQ z{oJ>n`I*C>I#xpkZtCf3%t~uy?cLOUcf|q#x_*B`9Q+7|^eqa)N`ey&2-5FbzC-dW zvhRg7{}KKpNkdsa2B)|9dg&+U#BW$qsz`0y{vA5afBNgwZ zhXr@`ee);^I;Depw9)YI!=bP?v>|Cpd*{i=_8Lq&qffWj)TnCu{a<BV=RDfd( z`9m&XRaJGb%EJ_e7haEl@9OTFXG4cZ)f&ZtzyE50yy{p*c&{#oD2Rza+BV*pOfh#F zav|`WNV~$wvoA@~@~MY9=K5Y+G$~8(^$AJpMzY#q1U}n?^qBbi3U}I0`_!2_x+c_z zrQQ?iGpt*dd+b3C>%Vy9jPb}{^3l^Q`kM3=B$p-(rO3=TixIDMo|j+&Gfsu8oXF2( zZU_1Z#NG>mJBt(-=a?YSTkp{G$#Q(d`+$zOzS>!&5Q2P5D%$jE2#J^WOVAgBl;Rhh z7>;814=6{lB3zio{;c7}3WyD%dg1gu!B@q)o%umzI|tPqR3z?{IC65NA$;4 z)TvE7&r_>a^(4XFHvoxLtw_Ts9zVmB%|G+M$2e*1oT1G3&=+Y5zvF@tD!hvwD{8)) zlGv=ec6$U&1FU&=FrmuwHq$q`wA#o7`}lWyylpvg5Q?GyUcK38!!#t$iT82 zD)?pLAK0dRZJ#iJl-_OkKp(#Au%+ofQpX)!kXr=|MAaf{`%?Ccm37qa3GrF*=;!s? zf5^}c0EnC4pB35ZmR4Refw{bZu6P}1yd;G!u=%B&HE;XAr~m(1)qnfs)S0Jvok-!8 z;TPQ%=?cf~yEt?&!;ekp^{U!sjj<-Vaxz#?kk9(u2}3&#xq?4 zmokp~%{|rP%2^0i^!2}URFB`kP>+D`UG_tefLT~8+B(pCe}_Z`Ho@BTYX-l^jWa^O z)>RRypP-0x<+J?2)V&8kmw(IQ#c%MZjsv{T^=FUL1-M4&m_}xd^I$+tZRoB6<{cAe${1R0-mF?oo&k<0zSjLs)EnddI(K(=dKZA$ZpCro_4N4qaB3TNuj zGnA>V)8}Nrh1gJPq%nr#DVBg*`31XeAW=edJ=1r(zIUG71?2TCBZIXu5Gk}X+L_K- zpsDq)*4Y=01?PobPYTQmG|F)kcBpjJ(MRSLE5M+J*J_WOx&k6(j*#LCI(RFEnoAKv zaQ7ni(|J3hXKKP_U8u?r-$#+5f+d8|vgCWEx}SU;Keh+>LD=uBB24RI{{b_GGJm1;a!!A(c$2Pc~|MZ4E9AAoRUkG?rpDfN8okwMQMj^5%w$R>93?mDttO3NT9 zMt>7?2`(jA)!@!4oyps4)rGN`A-^G9#z&e0H%5YZf3fx)wJt$3z1l|pRiWlZcB5UT zSrLAXEHfYE(+t2lMw*Q{nEgwvcvg1r)$t?R9gQ>Q5+R!Lv=?gZ>vF|OSCvmz|7j-w zvoCoJD5-w)f=mADsT-3&=zx21&8LIBJ0)2jK=xG(|iSTaXDh^|BI zgVf3BH|)-Dq94np%jzRJ&1dg}Jx5AejnER1B`)fg(}+zIT?c0NdWepcGK**&jtD+l z`M5BSVr1vCNQSqfs#~Tw;A=Gp9S1mK?dY!pethg;uG5lw=$rr7|sCmuNd`}c>I~bZ@{#iVV zV`UWjN7FdVDywQilvZL>>3BOSyCG7ccxl;BB|?FMrq0&1uiwF6OWz-p2a|M>;$e&Q z($g@z?B)Dta`am_S)6(5zzxQ!fju7DeZC^Z*7gN-0nW>YKn(&gp(?D_(3*KVH44KeCV4_n?nFEcEMKh0X#I#pk|Yeqk6O}R)Bvz(N&=~v zET`zfy^|fO5R@V0hYUkq<5%`%0HJH}?ZoT$M=UvJ4`&K}Uy>%l{xGTkB8=K-S6P<0 z=xV@nrAO*1Cnq)r`FFBOlfSQ4c;tAv_IqHvkC#$1m3KdmmWRkj;C$Dl@vpT=Nib)3 zWCEreuI9vPC_lGxz*BjDAvP~So7I`C zc9;*XN2Nj9dWP|iapiDXUSUU(=!<2hnN}Ew#V~c;`>mFa-7I%XHkw2c@Qwsjbt^nL z&KLh&8+-DH-_xY%@c!4~xo_zBs9dkLXV+Ckanb3xa2sMztV!RoGtt;jJR*$Q4~M7c zH9#OC+q?GGKvpJsCtRgD6T^iYNNY?^t-)f%jpMEqkxFDMAe zkNo+eq%T`-K?s{O=cYJQ3H*pDUnryG^u>dr&bNIjIoS~3ySc*_%M8Vu%gVTFAdClT zN6dz?SFcb`ap|M_jGnLNg~J)9FcN~$Vt4p;>%{5zw=Byv%4?UU25hrmTBZGD>Bv9* zQiyGR{VBexN%8&#yCf>5ei)7ujdz2EUIuOt2TzY@Uvps69?V@bu?R4OxosE4ia6l_ zB&Wa;ma~TuDeb!vex4F#zzjQV5#vD5zW#leJF@&?>v~=7xc}6}?4VPfVRUdB#%r^t zvc2Eqsv=~~;;}C(8EAzl< z*#hcCTgw%rw1+N0f|MNIK&3=7F6RsYlNq7@1$cgv`h@8xji+_R7m@N=rv`#SqMKHWZ5ZL4!Wi}PKqhM0nsVAW_sH4noZKwB6 z7@pr)ZkREL!_h~X7n|`N?W*6KfvmR1vZ^|ys-}aXVjpF%VBr_9@bzr|Y4RCBZR9nn z!AunwMIVc887z+npb81*B3palic5t!iJ)kS&F*Tm zE^FeSqDf*6a$tl7~4 znWaXY3%>JIWl4CHwG;3&wghG<#h^7>wf#U}N$o|%5*}5m0(@}ENpUYVsE!Pu2$|jF zr7$u1#a2bg@c7xZ)<`O9wR<(9-@v;dSYy;yeA*hcVer5Q*G?L924#uk9@K`9v#U7<96UrBiX1@?@ z?L&U!=1;pgysty-#+@sXo*#sE^6#?1P#rnt82iVEgBbK168-X77@hs*)1Ywi!_0XktM^R9X)m`$asVp6&-BKQ5A>YaW_7R;JPGq; zw)WPuAV4^e!6#Q#CFi?59S`x0roR)ouxWBlY0JjSZN67|j{;DBWmB2P2&h464{myD z+8?I$|CsJ{zmMq#51hVZ{P5G~1gV1JcTt3B02dB>>>rF+^=cwPPcU9P+Ng(9gL9Wx z1wHgzn!F$oC|2l>k=B+Im(co#(-|12M?Q z_Q`l{fBn5B#gr9xGYO4>59C;7B(J6^bWU~ItYvz&0GGr2be89|baph}A@mWik@UjO zNMMOV*qB*J>4ajz{y?%V#SxgtntNMzAV)hz698^Md9}`Foq;gansDTa)8upeALHgr zn0v6cQED6IP_B?oY6Prwp<5d$d#7ZC<4B#YqZ810MrVqghGZnyLRtMdQTi+fG7pD$ zuKH2b-qVJ`O4hHM6fTTit;jMmY^C(L+nYC$;=BEeE@RmB3YZ#zG9MUoRAWOPE@neX zbfxJo-$#?w|J^Da!BhH;n}3I3m!AlD2d%_7wL5+Q-tei3-6uYgeWjKYEbS{JhV`?} z+RFnKsR3!E*&&HZ3Ra^40<<>y zi)BqnqtlN|@@NVhqgxV93ChK;A)CuXIBqYV%Ym!y&v45g`f>2P*8A(pCaJKye)aKa zpQ(b#3Md#8-*?B6h)3%kLiN1uJ2m66$zR(qOBUC4tVR+&2WQ@+L$H`04_lpRmgzL= zWie|68txn)V>gec)xr}8VBla2#4A2l)r)_e|3{tPF9*bm;!K~mXt2__wZ=X#5Y3T{b7h9hNv?3i$o^YBc`#f#g z^2C+tL$6VlY$s1)vjwN7RVmJ35cR{Qn6@U`jX`XbQl|QCbya@lJk1a)w#Ux#Y-BHq zUZYkuR!SKDSDGYlLI(D)?Vh%P_VlZ&4`%%>uEzYa?)?^QtfLwUhFH8~8Q6fEpMdzW z6L{oyl0@Jab~$-*XuLc%!R-fzgzw;8?QSS<&qWkYdxR|Sw?3L2_koS34{*K*3tviU z2b5-6CZXdnt0%Gt5)3gRq-S$B(yGPx@+BzsLhfmXUZQUhAV{ z?yNLwKBZZ1e^o>GQXbM z%akVyMw&0L-jVNaJ83+up#&l3KFc+bxZC(%owg7Sn}>3|se;JNFqlZ@+((+`gVrWb zbjDlSkv0|+6T+TT?q+}MT!E`l6`2;>)0>H)a?B$Oogip`XBq5|HGLl=q*ZSDc4)OL zd&Z(kvH!LU*pIYIO6bt5ZfRVe7k2#E8|apH;wnd>t{3+O%6}t)a7&~7Pg-4u-vZ(H z0$)ZXHzl+1`=&6r0YuG*nFcU<LHO;kY|z=3a9T z0dGYno|xEpPW=6f`D2WJ!Uqaj8uV{cTkrqyN1k}A0N*G1(XWeR;`JWyl*DU+^_gni9}`fhF%t#AIXV(VD9u z{P0g%r-v3mDC@|~K18B$(M85K^F_&+q#Q>OrYV3ykyf?4nrvJKJm}d<%h+_1*McFHK4ob|_Lp zY&Es!X+LQVDuLsiTp7y*YFqCsYqZrAc=t5Y*p@xNdS~jr%`dC2YEnmMIL!$JxF^~$ zSmgp6Cf>4T6=O7w>uU#=8ZI}>9gB?K9bn;jB6VX(MH~HVj2`V0y>rrQe_N^mFb#}g zpww140m|n`UoomUPdSZAt{S#u?=c!RAjpz=Q{F#069uVBF=h2XRjUGf<3GSJq>GX# zE8KBwBm0Wk%5lxB{~=#-f5=z!6%X;HWypa4_T~yfVC(CTHm5}=E6S&H*knTUuaYno zqe7?Cys9nzTB#W(R6>Y?%&uOy>xgeGm)nx&@{_z2x-qB0kCzA{_|5w;Cor!K@aIT% z8dRLIg|tzGIF+#GysD(;jTsn~aWwNY#|QYR1kA+;_^AgP+ZGjOn9M8U@Qrs=p#lK0 z@rDq(0jy%7Q-a#E%*(RyS3S)_&T|(HU`uLdzej<%X?BDh+CKvm9&mn6;5ax9?%rXj!q_bjLSr%LRIVRfQn(W1r$x<-4uqiXz0IH;7y;536wU)+Y zcS$R{qUsjFSaaK2|4BOteb_++WhzxKyZzNxYU9-UJW)jHczh%b>>)C!N@7IMYi`Ha zht8DXMa<6`$3fe(mUbe*NryZu(MX8a@11^G;7XkO4-a)5&d)YPzvrTC1Zj1&rw0Y~ zFKib|1o-)aY2CC^p=9PBm9#Poiv@Rc&Iwl6$XVKIh-SGJ6C`{2@JS`tnw)7 z(me!uPau$1@uvugNZ!_DtKt61bfo5(W=pkwjcXo%h+GXC-uNXYuB+n`!a8Z0OzDpy z*9j%VE9>C9f!TxcZZ6{FoDw`Y@PSfFXyo{Y()^ZwNr*Li~yy91-0WW5tb9bTO$j>G%woPE8@q ztCf;J)IV$T?Te!}#hfMHJ2ct)uHeXxCGm%luo|GNondHFc>8}$1uOin%>A?q;8W8j zs$MzIn@m&VrKXQWl!;XF=h=lfz0oDIz&mE7>Rf@7NsU6e=3%!=j@X#o0bM-OeKzUv z<_K%R(};qYT>ROhkv)hjb|-u}m4qi%EQyH?25Q07@wJ_MdiS{U_)_yrP)s{S|GDDy zyLUIRsbPsW0=&Mw_FtYgz2~ld|%h;qMi`Pukd3Z<*ns=CeAuUO=Uh2v#SQiZLi45MfAnmIc6ogew`4)ZgG zM&g@S^5d)~b^x(9YAe*c4m|i*lHPrs0o&DlAh}uX>JK6qw29tbWO)_pjvBEU+vTm7 zLFy=C4=OEX4IrNes>}l3^WUBy8lpV|xc~v*HexixT-S40koxEVcv5f>@SKEokJy{S z$g?tKfU(ea{6ZZdaE~=%a=x`iFx_$%&wiG^BM0YE5ZY-=*k|96)k(EdE{;sdcTN+& z7I3BjN+MQD(&^eTMm1F1_&H(9GGlDjP2ZOGgS2SY2dwWPVH;o^O3Kk`v;2pJM_IaB zzq-;!**=jlxk0bJj=uup=*EB!;8tay=&cv;nB*`L%LyCkJc&O@S;V#+Za^LV&*%eK z?Z0gLUVz?4>&`b3tIY^uy9jx>aGYivT2cGTtUuEURXtfOVmCJ#E(0ARt|-xKLk2JM zO#FkY3?`W5Y{$VaM~6)Z{)lLcpsp>k*)ni(1$qY19*Jd!3!IL5=`gB>uq`H`QYF!; z)Yuu;nQ?vp{coBE$(nqjv;KJH%c*lWOOQsDZT5;qXS#c`!?}IO7(ZRx{pj1f_ib)U z`TSxp6a(L*e8V1P4U^*|4#yO{LI z`J%-D$*%wml0rBHaS&dP;$-j4UyTqJv3YrvD4(zn&v&dBu1I`zv3@4iXRL`0(bCM% zFXoe*d~}A-7?eZHZ9*56L;9$-Nlb1pd{wt&dD=QQ1N@FP+@2LwpC-FiMvkq>NNk9SgQ|mN6^{5G;8Rm{&-(+rUmrC=0o) zk)v9h%kHk;17`}g6lD z5l{1NkhFGw4dq@v(O{bNWOi*n&$l(nYEpweCqGTVqfVFoZc^ua+x#yP16ivi; za!X${UvhTH13X%RS2X#~x9DP5hmI|G)!PfhA-`g+&W)y>o0S^eraFs$C8ovo0A&@t zueo+Y_efg@_`D-!)4eYqpI5AfF;&1ptFk0B6 zQr(>bpRst4w+UelIPwKER0B82CMA-ldATcN_(b@kkdm#}iq;np-(2oW2>a9um8%fD zj@QO!4@ramra14qet%VxpIew!#dPfY_14_B-*o)v49n{5SmAvY^|v2@x@)=3Y<-C@ zB_?fIu+&Cj(m<3qwmTnFV7*f!x@ zZOqE|A}&Tcv_q%Do3=X?Aa{1U&8B-L`Qdb0I84I8vF#FTX4&^JfMeK~7CU(2hx`ja zWwN7hY_-7dZtXpARiCch(;j00v}uc#>qJKwaXcZ?4mkq$hY~iBj0nW61wF%I*fl!Q z-wsQdeq*x@G4wOq!9bktwAAKTe4*Y1{hZZrbcCC^-9%8Or1HeNMz97LKAK7xmURJ? z=3z$qi=w&WB=3&aGiD#-SGTW2H0&;__*l!^hAryCh%SiFhr|k9wiVBv2sUX|kwERv z8$V%#W2*Ft>R$h&Pw(X>2H-Z$uJx(SmMIcgB36A=fo1rT@P%m1h6wBM>r#R` zv%V$!HvF(U{ScpofbJdy<~|oZN+N>!U#ka z!WgVXr8U@}b)G+K**Bv_g+J?A`efA^FE{!HuX0DtaBKAEej7CCYue+x0Fsj~*Nfyr z+cVLRSR-Wp_tkM}B%HmxbYrF_rYei#tD(+x*h|Qkpmcgo$N8Tt8rq~^TyHS z8s#8tS}H3nL~NDS)oR_$pnoLOngIpGR}I?XugIybFaqbK9m~KexXH;N=Z|+W@b8b{ z&xgoVPQW?xEE4dVq4Ig1$gb_kMdhB0fiT| z0MV)BS$h2U?mOOo&cPPdDrcNg#y7C{XPXxs_m;ZI$~{aR9xB8 zPU>6Oy^$85@Pc|`thZRkW!*5Y)n)D<;u~eqPd1o%q5<0bL({!d;*$rxBKN7pQ?JGa zr5m_p#VN$YuOWHX|K+O-v{a3A8o?G&IVr1_I%#Y{vRn~)pMQ*=Bs*OxuXo-qw0qHM}kmiAl$-Y5Z}Kfy>luOad%P|WgV1JJ$we+C`wP6rn9 z)&Upk)A=W4=qnhtBIXva>+}`a=TarT{qtI0a*m6}XhY`fD?66fqakEz#B8=6&$D|1ESk-lu# ztP(#kT>sG~HD|+)IbHxNa3_VR8*Z?RqXBk?w1pLE%>W0q|C? zB}rY#=FG=-^3CjKl#cgbaK%Xd3v~^B)J4Wpo%4T{7xdkE@Ekj0o>aH?$y&B1cTtRL410?4CE6X0=;<25L!~sHDF-Xo)w%tZT zsIjbaqZ8^TBsKYFmAtnD4Ak@c+)y}2iUpiIhwNhR?HfCa_Sa)yJYymb4Zp)~iIX&t z&&2`=q>FR8V)G;0RonBW!ThF4^BV`ph3%aVpD2uo$-8l<72GEQO3gVFnMpI^7zcNB zhn)v+W;oTr08=_4ecIpGyKZx91B)jJu}z-Vb!OPd{Z{#Q$K-gTib;Nx{marURXjj% z6=5U@$Q%FocfqEnRjLJ+yGD`;&Rs3*AorAc+@U*_EB(v;(3#Sl@ya$E<}s=!uj~ex zaA8CUFjq>z{Q}GYnMY1J48$gr%uoBDK!lBvsjCeTFi?P$?AldP)O-Jx18AY` zRzmxmKt2oy2eOjRa2w`?zsVdA5*T*~LI)h^=W!O@ue6ch=lZ#iCh+UhKA#W9dnXblJH%n;y2;)PqY_W_ew*l3 z1M>3p3#NH5I~Jy<$?Ei3mO<{wP`*_m9jy#mnh$ZHPSkX5>wyhaihumCpCl95(mRA9 zSk7EHqCg8P2W^j#=Zdkb7I8=vSip>3o=2ogPQ@oMs6R`-O6+r( z{`gYyc^hVsoZtq_-lFu-$95^@IKEa~_=;_j_+v=3!XHC=z)aY`cwMmYY6t{U*Pl!t z&v?+kbPE(zY_TD3 zw8^YMnICr6l&!11kIwOGs-x|8M|U$IeXa09q_}cp^%81|_xuUJCIECWUJybhPHMUY*D2}PSckQKm=2L9;><>rA~!dBcJt1uQSW~-efo-q*kfCyrOLUS%#o-Gla?Oz0k0sA);*AM#lc2)00U zG8pJ?H~#_0HD^}(uw|{> zyROhB8UnX^+jR?jiu1PV$s>3}DEJ|+@p!NrmZu2u2p-hRJFtK5rPBO$28%;NT|Ci{ z2D)7>9`v9&!kY0wOI`2l{iLOTKttA4B!U4x|Wmu9GP^T9E>g!%xr^DA5YK$Ke+w1DKsI zOa>s!F&8Y>6`*(HdG6=FSrY1bym#QswuFx;a&7;f%zj zjW$6Z8POm--1g+F0=ZfJH8&me)k?LOT=%LFf=dD0xC+b(j_Tl2H!+Y$xFD06_qyCGqv7 zm~J16B^AkHfG#OG2YI)(YnR#c0Hq&6^-Nr(bTum#Mh^t--YocF%_J8#hF1Eo*4f^l zGRQz5tTa2KE8yCpT;PoZ<{u^;G@#=Y-8ke9&ITY&X>X$J?hRZKxF$Muz6kI=MFFF0 z(p?)~+OJ2Kbns>9M@pl%9_)g;HWEA|+uIdj*8zM5nuRVBl{z-n=$oDzW{<{H80|ZW zl-5;ln_qoAvNZss%Bgl5d5#8(8z-2j5e$gW^Ll&biC*g+cu^r{5)VRJNX{&DT~3>n zYtcB@AEE>|M=@dFtrv!vbk4HYOLgs+a zL9GC#t&Ib*w8*h+^E-?)5%Yfip8*=`mR2a9hr?doouA-YhU6TitgA zgaV>?kHn1H=;W}B6C4dST^-&Z$?N1^qKP(i^t4QnrDZ>AAc47P!&9rW?QH$2*p#F! z=Zv>!UDrwdd)!Ew-um{je@~nw7|MaMk9=l@z>OnJR24gqd65TAz5!*``%~%)ENFt0 zgP^STY`naAFqMxC9jtgKRp38z2Nl|fxABfUz3>B`CDkjgM^2NncReWy(fABiw^;Fpg~cv12x{ zKzo1_r_;VSD2od)v$xQNg(}mP$T)jk!z~=s&gfzEJi1>$xh$|dk5L??_82>mG^xby z%2tQU)|?Jaf^YljSTT1KkD#se^$Aou2{O@&(BH>#TW)Oxh#EAh(eJb2>YZT#{-4tU zdqxWc1MUtYQdyJd2>6589wRXeMObd`Cdh&22UTr$7^2apc}6260eYkXyAQ4hSsOLA zf$hx86yOyC#!n6u;$V9db)kQsm*5es#R zaF*X~iq3qKPqaWu#g-W2wl-%h2OpvO*^qoWLLU$znkm&?28Kw0QkC?zOrxAcOf6dG zl5)|6<;%jt&3Hw~{|XV&tU`JjLzoV}cB#V_T~F*7f$#vwDbx8q&_ZJnP4j28pqLVU z&40sV1_A9L`K74x63l74^1nFB3BvL%xEj<-^rkH{!Xl0c?!4QaTV|%!PqV$%87+## zLQ>4MlI^rXV#OxrBbuhl7uHj+9y&Hmr+gOt+;)mklhj7feR3Ad`^S9&@7JH@#SEE- zmW;#UQnMCG2E*s5={WFC$n>BMzBPhSnpaB`q&OVW*hoR@LFdeIVO5l=bMnJ`v8SVw zeYh_Txi!d^=&ItF=OooNl5utn8HTJ*W4@I$X|i?$JmV0Y9r)sOBF%^47E!%^nLTe6;wF zb}GN*68PP|1>HJbZR-V^WRn)UWdiyYhLnykgqnwX7nzhRPFs57eWw3lvUs6V5WWFR zLI`fNcyS}kozx5AT)Fks@k1n&K#e9ba7KgqgIcb^_3*EBTDto8?AuJ3Z8kQ(&tWeZ z{}-4=p|iY=Au94_Ekk$yD%m(Yo()Fy5lLTiQg)MO^c=^77()-8zW!=u-4Io_z6cqI z7S*9wF?myHOf0c?Wo@1alV@Jl4Uuu7!$p|$qH8F#eGXr}97qG4kK^2M3;I9jNDu0T z(N4@47s>^m1{BQ!{~?q7=^QtCiVhe#Zk2+cfA^fuXY8{$CZRd$oBNK=i~UyS(0}5T z4DT#hYk<9yNnjTUT}Li0xZXD0V~mXN9nD|ICB>Ppr8B%q$}#Ee+g`5ut4o#9#j!1A zul57YS*YMM!NoAA>fot_9SGbnWlJV1y1VZOv)dmVpIpeeA!wO=nsd$hCvL&JYhLj; z5Y}NqVviQJX3WXI`KsGi6`8Ua*{z?rk_Oj5pDG+StMx0FC#EK>SUbx*Xee-q&MBOh8dL4|?@GTjVPsQcN-7H%Du0$XmqkX(j_uPL zzvMvBVJC&r#;{`RAM=I6>!PuElioIBkl!Afs7tMK?4Dqv{My{Gq;)8nu3o8p;3}Sd zDv*VLCHi-WInbAr+viSH#otNhtG9y)O=bmw|3LRUlV;)V6%;2x+9$~6_o{81O$hSg z4dCQJ1_HOm2U=jEU~2H?f!E9Yuxj?R(s=Y8KNb`aqUFuYYiW4T=n{ z3C`$=+=#DV;wQu!?VzLV3yh=Fm0Ky49_L3W^ zmM-|-IJc;vC;&7*7f1MX1(+m*H)#VWFeFW4#?C`={Pbz=mx%;H5Cl;Q(47=P5QKqT zqIojIAtN@c&YArO;t<;ud@)&r-tmV>G+ z@PSE5TsX0&Bt`RPf#E6537sjL1EuLKe?sd^Hqjh_Wuke57XPkk`>mKna{!A(bE{La z=;$d~1nt-yebJiQFSRyZe})X>!cNf~0M-v={{kkH)=`Ew|0u*q74U&kbhBYFsSXFv zTmS&{zB7QNunqvw_0kMn0z<=*I6P;6hPx-WNHiCl6@*W#;&-NK?h{x#ZK0WH4j?U> zC)?WrEOeL`+HKDEO9fpYK@bE%WI~Q}f*^=xk`z+lLT)_w?k>#y`CFXvRbXz77vA@Z zL-;9oGM!&kz>^>dLZy`5dV^&D*qNn~!Lo@-KXxKly$&>Yw)m0J>gX1po;4d9nM$ z|9}gP0L?Q9Ui88pb%75gAhs!}dinMu(Ohg+(qC2rNQ>qG5WM1r*sOqQ^CsV_LM+5% zHsHfLt?iX-=D;nu7WGkj%3|o_3uxr%emcA^A(jLmoh{RtBZK*54F00eyPYlmoImg>WC{fDsr5^ zRu?$aQxUY6xhPsH@E^?|@4HRvN1MBksK-Vxd|0!Lv{5f;1w^kH#?+M%pBB%JB6_bD z?|Kb!uhiY($fhhHK1kc1^}SoI{J zQ7y3axggKvFYLAm3}YGRkWnztL|<;qaL$Q!3L;bG7yHJwe#W%@srR$ceSKV#F%tIR zP){sf;BzGG!Gy`!7I!F)U1#bAhRG<0TPCrf9It(~0>hNW@pZeva5rNcP99%i{w1_n zpI`RR*xd|jVe?tJ$ukS7s1S?6k-y{Li_*#1ffYpK~zx=bDI+2 zLJZq?*W&O0Qbp^&FQ;>F#Bja^uPzqM#U=&!_9hU&&vhy?q4r6Sm$4;Y*WBaf_Z&eG z1VI!(W#nBdJNv!+txL_h%h?At#+Uj&QdO^TXcaS?BEv+rR3bS5@WGY{Wl*-IMEzb zo>*8SXnKjRRoykN3*}O#M^vQ!-%a4_`tRFZ~3^IBJfs-$G!te0Kn$Z z*8rPOv(lYV_igXH!+EzwPf0ar7?+h9zk^r3*cG0CVJJ2#@M-ROGnN`JsrV;B5Cq{Q z6^C+pC~{@+Kl<94`OvF^D5SW8|+Bh`(L~&siDnsOmD0jHr$qZmbWiN&?4n_rDx4 zI;ZYg>>?waL3hdN4!&KIjN9atE(lILA*~``$9QCn%lSLycfpCvgxIL0U6lFKBCtiy z@_by>#$`&uW!@w(j7K?iN-~DSp7c~_*d#uT+kAZ}*0I$g$+#8vm^#dzAa3#{g%$hF zYL|H?P967c2B-UjV2puJR|D>SK1}_<;BH}<3VRTXa){hfmlGdR@cBy$xU*VnyWI)~ zH@CnYok*`k+^rxoYKSvhd~+Gvn}~AQBFXSHCJ_&N7R15G1czjSUVMmxg5j^P7i3)o zK@bG-Ah>Ea_~-7w7(o!k^61>J;Hz_9>`AmQaGw_|`}Qk1f6j|Nii8W^K+a{8LL<1) zV)6ULOVjwnq2Ivw=6P_TdwA;iepG$76N)E*GhglnRsmeR`1b`tEETa{S>Tx4Ca|*4 zgHAYu*s36Sxj0;+M(PB%DEIS9p-Eu4dY`_Fb&8{I`Mr{iZ;GfMM!mo=7~;_($qVwA z+l?T}2nBq$oximLv(#O_U0{pyn2S4fVsJq4?r-|do&XxNj^VQ$rS^!(*!*B_^@{cRS1g(bEs zxcNy8YknnTB((+Z=q!NwIGGf94AxYE>%Rv8Ncp{R&8TTz#xg|jM8>#I@0000 - - - - - - - - - -
-
-
- input topic 1 -
-
-
-
- input topic... -
-
- - - - -
-
-
- input topic 2 -
-
-
-
- input topic... -
-
- - - - -
-
-
- input topic 3 -
-
-
-
- input topic... -
-
- - - - - - - -
-
-
- concatenated topic -
-
-
-
- concatenate... -
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
-
-
- timer -
- start -
-
-
-
- timer... -
-
- - - - -
-
-
- this data is abandoned -
-
-
-
- this data i... -
-
- - - - - - - - - -
-
-
- t0 -
-
-
-
- t0 -
-
- - - - -
-
-
- t1 -
-
-
-
- t1 -
-
- - - - -
-
-
- t2 -
-
-
-
- t2 -
-
- - - - -
-
-
- t3 -
-
-
-
- t3 -
-
- - - - - - - - - - - - - - -
-
-
- timer -
- start -
-
-
-
- timer... -
-
- - - - - -
-
-
- timeout -
-
-
-
- timeout -
-
- - - - - - -
-
-
- t4 -
-
-
-
- t4 -
-
-
- - - - Viewer does not support full SVG 1.1 - - -
diff --git a/sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_edge_case.drawio.svg b/sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_edge_case.drawio.svg new file mode 100644 index 0000000000000..33835b6396e51 --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_edge_case.drawio.svg @@ -0,0 +1,2361 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 0 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 50 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 100 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 150 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 0 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 50 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 100 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 150 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 0 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 50 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 100 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 150 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 0 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 50 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 100 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 150 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+
+ receive all pc +
+ concatenate +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+
+ collector + 1: + timeout +
+ concatenate +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + Normal + +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ + One pointcloud + +
+ + drop + +
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ + Several pointclouds + +
+ + delay + +
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ + Several pointclouds + +
+ + delay, and one drop + +
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ + Several pointclouds + +
+ + delay, and drop + +
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ + One pointcloud + +
+ + delay + +
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 0 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 50 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 100 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 150 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ collector + 1 created. +
+
timer start
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+
collector 2 created.
+
timer start
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+
+ collector + 2 +
+
concatenate
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+
+ collector + 1 created. +
+
timer start
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+
+ collector + 1 +
+
concatenate
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 0 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 50 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 100 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 150 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ collector + 1 created. +
+
timer start
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + +
+
+
+
+ collector + 1 +
+
concatenate
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 0 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 50 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 100 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 150 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ collector + 1 created. +
+
timer start
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + +
+
+
+
+ collector + 1 +
+
concatenate
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+
Can decide to
+
publish or not
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + +
+
+
120 ms
+
+
+
+ +
+
+
+
+
+ + + + + + + + + + + + + + + + + +
+
+
120 ms
+
+
+
+ +
+
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
120 ms
+
+
+
+ +
+
+
+
+
+
+
+
+
diff --git a/sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_left.png b/sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_left.png new file mode 100644 index 0000000000000000000000000000000000000000..87e78ab91fed6c832596708fd3b1f03eeba72d5f GIT binary patch literal 44393 zcmeEt`9IYC7q(Iqq9V##sVF;R-?~*)wq)P8Y}t){FbPS*E!hSm3E8(SW0@gE*0GO$ ztTXn(*v4R8Plv&OLf~|0xyK z=^iSoQt$!>26lA!CQzf4fHw*KeA7KIJ8N$zceks0POf%TdOmhn#YC^(x3j$}E-DVXDk>=_ zAuA^#e)Wmw)yKMeS!2&esi>|}J-Yvoo`3r4q_fN9UNCkOEgKoBz;b)@)|(2uwx~7S ztm!-ZC}sg?-J+I%g?a0h7v~_L52n#Hi?6EtPP#vM za@Fw#|H^E2bGlHa?RTRa;}s7dfAYWZXwz%=1v2R7))SxA*HPPnXK7DTC=}948*ycx#mU=-W0msHA{;ox7d`2YL*-#q{~@LwGKmk&P^;lDWeFAn~T zga7j2KOFcE2mZr>|8U?x9QY3h{=cq*#xZBxETVgS?G(^OP$5?^Jhnq1dW>0^*25=vP%D8T^uh>d}NWN4{syN?c{ z%7bQT>N}K!!)h6U|3F}AoB;e-83m4NCUp<2rB%d^_bvW-`07=pxSaUA&GK>=H@9cj z)?$^FmBuC(J^fpWM;6zqs3v@W3NKp_R9$+XqH4tiG)Pf4fSJvk9?~}HhcB`9!^Nv{ z_v|k^GIA@VR63w>>-Fm$V032tDA++lX*ijd$KUeStybc8=FtQAF%dOFu%ia-&JpwS zFQ~^xQ&Cw_f|mx(klr>$c#?J|tP`^5 zY}!}^E-iFfG^9jrZf;i{csYd#t4FINDk|Q!Fx!&);(F{!9gmSmc@!`TdWnjvR_N!A z-+eb9EG=jmP05o;MO}U<~RX8t6di*kxbcd^gXtUix*m5TdyZ{ZL=2QvYG-3} zot~bagvC-qXyn6EQ!~0V{3ha&NTfFn?SR{!ot@pyWD!fP%D%3HR@J2BwO1UvaFFkd%Xwr#53<%*;EbkN4wV@e$4@N2vjsQ2D z%9Moc5b-dx%j^f=t_+kir!LD|MA+yJW15#%+8Yg8?TdRB7$_I5-Wh;{U^|cj<=&4LrUjnkR^=a&O8d=b2(OzCA^R$DW$-O(YU(RIJm~#>BbozpWjP`~b#%0- zq~sYGEU>b&vXq-b1Jnt{c7m!&v;QG-M+1r;C{1@>uuO+_)dJU!OA}>mG}RF#i**PsY!?_CB@&1tf;Gise{3Y zpnz+Ig@vOdBN{d1n%R91D@VJWiyQhJ8#X(3u^fgNFHfAxShv9~M(s}$y*>6dY27g~ zf|kbJ{fPp=jbBmr7A-6kK!BucusrlYK8nN0jQ}FJ!TCb`AYC2g*u9XldGi$rc5Waq zkai5hV|h?Myi;kj*c5trgd(RNjzf1A4i9OS|8+lXmnJq+h({n;_XHFhoSKsIFi+xN zz{UX5;m=P<-r3o~+#~r4Vj1Ti^#cZiD-lP5Yj~}^gucE$L6I)}Y_xJm*0FEw+Zfz* zsMdi=F$3c{hsHD)Dbs-YnMiR3Z>vmYF2J=uDL~G7a2#Z((v#-7E4!4*`%gpi+60Lx z&*#FH1hM{wsZ{y^>p1eUAbG*^;6C@!k4P}ayse_5E{Q}Uy^V{p3$js&QI#+(5p?kN zl`=IQw=BiJo{Mo_C#uR|ktO4r2AJXghhC&Dm3MB#!zH0OcZ)Et1t1MU+V4s;FL&}P z`X)hFg^HKY6~@&}<;pku=<2F%`Dq=lHIVV^=pR2GA^{}JnOyIbCm{G}Uok!l2#^(N z+fUive?0qrb_bo<*w93tE3}3o1 zjM|b~ld>ew&eSX@xer-6T;(}vB3B~I;qvPZ5|ouxhpo^(lyY#fLEVx)02~0CW8T`1 z3M7>l7uy|t_3nWyCNC{56_pgbT9Th%g}N@1cF!bZrfQC0mwC{utKUKWKl%?3eeb&8 zQUg$Xwo}9*@YpMsTedS{tlLTYMiJ8sw>hsP7U{7`9Nv~p%xSlCiEOjcAOeI~1sBK@;a z+WxG9Ld*HsF?l_xm)9LsMO%x4va)QV8YG=EF|UXA6cSNJKx&V);t-3@_2IibN&yaN zpGiR`#r?an+={RkW@e|os>+7)_?CnOgqPh-Fp+3%WF%Pswe%dWu+SMuUu(#z&YkkZ zswW}l0;TZ{u>twj)zx0di9}g2P6Mz{q8FQKFFo2&@oqCdej;Gc9I?_P@7CHzO+{4$ zngOEBU}rT(M3%gEtcb=^zAwP>QvpH2m^oPY$axpNB(siS6f{3e;N5r8E0^@T=_9YpnQzHoA zj@9@};}5GaJB*A>c>_!HBN=Vt%F3C=#ocDIfE+~&cJVcH!p;H3t+_pK? zR#QSEHRj$!R4 zj_T!Ocg$<*4@a48ue5hbwsDW!)*PB{((@?8o6DojEKJd>-w_PHa>m9c9UWuOVclz` zy+mTNgrZ`lnkd%JFCgy8RP8$2?bWMS384PxRqt*vNAmT%RCz5K3X5Tq`Py7vb4 z8Jn9?pm#;Z#S05WJb3*(8#uuF+9QkLyN=*wD~r{@&wl*w^FvpbF){z}T;XaT+9|xU z$N*Hl_IO@3V3>ImsMx{5!B;pryPEF-lvED3ha?}@5N%HY2>9kFeTjz53be@Xf1Sd( ztOd)dLEeG`*5^H75^TPTenoAK>!UY6yJt)Vn6I=a`*CvkZ!O2#W+c>8$jY(D$Hxi> zBW>cSFX^M|$^DxB%gzp~y&kN1e7_^80)a?%s|yGw@2`{;&(+6RFJ0*@g=#s*^$E4K zw4`QcY8N6JR~i6A=jY==b&m@BG%PJG$AXK$z`8jvb9T){Ns~Vt0F%@UJtwH#m>Ovk zQOhVe=M)%263}L}+urYS%(#)cxCxKAQ5Z*HSg%*q^Ip7M~9cxV`VWZnuI!A8WZkR z4Fi75g2dkeOwg?+4fwOzO&Xv`PBr7C#cYUT0YHBjAN&l=(_PAqdnGG;NQLyg z9#o*0Ok3c$O$Tj8e1ak_6>95sC(<_nOHmX{lJB4NJlqoA+n=6Oe`GQ08AKYalFyaa zB24_#7;qSCj@g+@Nx6(hfJN*BJjG(%`rY>M)4flIF~b&d3*+%Y^}Ym#Ma-1DnkYrg zHb7ERGBMGxt+E04V^EJZnRP(3q8u6T3xxvgfm2aD^%@i1X{r~}n!n6c*mU<@??F!G z9g{}Rl?M1HbIq0ppt%XAgbPE`zOvO`HiCxQ<_O$~A7D47(vM*MZo)5^fYl$`D@a|3 zXTaf;iM!W}zX)_D364*zNAJIkxw<&b*fV3reD%b|SOolA*R#y|vnLYn4G%EM1YEsl zcF|1?cUObmNVHsR#7L;DnEuS9@6EL%af!xC3B`dS^C5F{pX1L+eXPBK1$?y#DFU}! z-Yc}!#|$3CjiQ5gj;g$dH+B%T)N@8zuZ$bOR^5us@YPmO8lylVrq*kTu9h1{+wT81 z*EN*3AnyRN_qr)aPdy14ReDE|;Bc8H*NH}n5B~6c%ze-FTg3*^_LWf|3r3Q@hf@2w zfz_^spI13^?c3F}JrO@&xKZtO0q)KIl(5aJAFo>ZCrYV_T<#Sp-mzIWsRfuWEWZYIQS6 zd!}{-+dKAHaJpc;T;?4b*aa5!T{>0HIn_R=A7r)9dHM2XZh=4ZSjAmS$76k3T!J6{ zkWbi9;xzVwLj2YE*8`5A&qL2cgz7$)xf2v3nYa#~bF2Qc>otb+?`1Lbg$zvZZ*CSF z$Q?J2s~Lv+J!{pAqIOiDGyQ62!FjyuKu6Q2dTN=_osqH6z*Uu#dZBWs>7ju6L|>!t z#|D#IEOZy59ykREdseX-)x*`hi@aQ2W2&m0CrNirlMK01;+Wdi#2Bb2MNfi-Fm{AP zivoS-yro_jDUWnkt;+Tmg8z770RL|vT2$VUVf%S?wJ{0@Ss?c-mCX)qw$Lj$+FN>w z6bmKI=UpUafyjGgM9dpbb*uCwzIa zM3MN>d(I^Go*=tzh;ZjB+?bIEN#7#s2x529F9c=WDo#?r&dqx*Eu8L`&E>Wi)9HV{ zny|MiOh9MyUq1ZtdU+#6m$_%CZCiqpuaPwNT2!HPk#1LB?bKm$zehbQpP#!`P)2a5 zXVJe@!>x+z=fs>PcRvk;vpAZZ>uK1&=+Fb7IT-V?>Ekc=e{0l5(JiiqB0O63aV=~v zZ14QO+34UZ!CemcTFNmdi_aTZX>3z|`Be#XjH;~1v=(~|%}(9WQM!O($;G%fxA|+o zvLf7HGhy27r}t;2h$HIRVQV2GP~Rlm2UR=qJRrZY*`Dq1Z^b}OQ&H;1wtpw+VsY(=j_@WSIwc<-)(MO zluPXH(4_C84S-Yl*kdlnsE$@TFhw$QFTR>DHxfBjBPig}qIaizaGRx|zy@}UBatrg zaRjX;<$xpbm+OJ7NqY1rYdGXcQSJY1W%E1++h~YRZSJ*x2@1%y+87pFGg&uhpPaoJ zB@Z&}%oB@dI)xj28Co@c8uz6iYa=v);ZmcgvES63^vtocVhz(@Dm5rv==b3KdS~@f z&g<}&aNdw6p13w0{Y#nyhxpg35PdxJX=d-vQYS~a^FXMcLUdUJwx6oE+F zg8xFM@Y>1$9Vl>HzMqrgkZ^Bujs&9EYfv$6bcDy;rAR5888dD?ZT|3d_!TZAh~3#* z?>r?ZE7j!GbDeJPce{?fJ@6IKuJC}ql5nnr&@0hN=n5u9U99MOX z+_dL#N4{k~n5vhLRj z9INhIUq|o=oq__dqcO>n(vs-_?t+gW3hwZKaAGfaWY8SCdjd^Vov`+@nzA&8KfV>! z_VIF^R?gF`pfz@Z!a}3!7}s(6K#Kv8Z14d{q+#PETA6Y(^LRVc14!xFO&L>DQ~tFk zltF10->l_i=Y?N(&q}Ji1pmy@*XD~eV~bLE!j!5sh84?|0`_WN`4T!T(wAfPuN$jn@aY5GFl%wrz3!rq z5r=Txray!JjzISbmLaBrb1j!0G2#;~4Yp-<3W*vvwq5b-s4l zA3_2Zr%QY>5Xj(2A$eJSdS6Y`Lt8l7q9D74@GYp&|L!U)qe+Vf>#&@z8TvTn_%Q;c zr~g2Q#oOG$&Mv}}1NwEbso`n9w?Jo&ZsAa!HAz=n={p#$h#nhb2ZCl!hH=wqg3z)a zIwv!@EGZ==?Ig!Y-d%I3G`Yz_mldJ%Y2Y@4dBN}M96l0z3jfP1_4=n{QBd;6;fxu0 zmSkztPue{@6Ijf`4Oxeqxz0CKK8s1`@!{i>mIpbA+W-s%az$TF1Dj4!b-fipP zY+;SV@UlO5c#HM*c>dy~=z;?OTF}8)w}?LUkjnw;?S{g`n+cq9{x9^z+gll_!9dV} zae}1{hje*b8M6^=7FMona++;STUnDQX-=bwKc0yLS>jS3I^bQl%xYL-W+x{b187;Y zUg0f~Ow5dG4|CM^^8SF-Hh=r*>gU$Czm8(VCPQlW;Xaz*{b$iV$#B0%V^<&AQ~zcq zDCFC#4+OyyVuTn+1ndEmA`e57vt8uz zWP%#nlAAQD<;EoX!11$JFn)@>?sqZz{_FeKznBQaa{FDRQn590j$bC%?`KUGJZKhu zsknfz1b?#;6YTu>G=G&}5QVIMHR)JpJo?SY+zicSw4k=beH^y|A3uK6wxpYPR_!Z@ znW!euY*A+0|P@q6UrWSnf=0PhWSoZU}1UhOGwsoWDLpl$(fY0my%GI zN?Vx9R+IH#yt?VniSg+J#RN`%G$_peOb6Lry(S@VwjlBwmKWoH7et$6ND&Ke-d&Rs zt^BVx5wX=VLPQyh?#G;M?Am!6eq?)cYru9a5hVHw_wh6}WTqqwp|fUUg0Q+&mrxI} z`p!i?N2K0U{FzK0Zc;#T`C=mU^%|=EZLX7EO?B^=>9{`os>d>)NJ7R>9|?Ba0CnSW zj`-G8M%m#~9tFl`85CbtB?*-6*a5aAfs8V<&1|pIgds9Gqh=ky6mqp>C2&u|41O$d zSgHHSHZTXp7`OkLyi5{(o1#6h6<4bs;Mm%J?$j!E@Ibb@<=MCQavDR+jStbhnSObI zW;j>tRx=a@q!wJQa&$W_xhCS?wW;miv|hb)A587s;y#NLN`--5FK=`k@~+0D*v*s` z^`?Oex7c%UrKck!$O`X0R#P$_v?W5kq`?I_5j zPfzoGos(kX^>G z?3~OOvzk)v0QvK@PY%oK!H;#uvI6h|8OubimLv=RsihEZ{(F0ezCv~ItEn0vsa94v zF2B+eWSv9Ws-2B|$x-#2*Ioqw5`R+sm1cIog>j$te?~f z@o-4gS+dBU8sp<6mG&9-CinSI;4Q?+*=Ik!#zI$KF^i%e00k`NBnQlp*lI(9W9%zY zezKDVo;d@4IRjof%c{|O zcSgA=NBbWO>XB<``VI^YNBn1(5=xhUlD=b4LGg6&Nrj3e&b~3CnFb9X0kxLf)d- zp`@JBX&Fs3%uUvq{@Z6Qjg6Z=iTwGj$FtV@eSQ^Otc_<@Glvbx}m1+4t=F~}| zl(M`b^Nnb7y9XtB zZ{`Hyu#Pk8{$Xx|#IIiDny>tyw$3+{8EWNmIGI3BpibYn3&Z~Gq)^H!PxO!F0kR-H za~LW{^i_&6E@J9#qf0JlQ;paWp;e9VZ{1L2qjjJ$jh>JYUDr>Ie5@T4(9c2aNUdCa z6}oaDIR(^NJ7Y7X*LQ;cl-I~a(Z*MLbY(+BSB`pe9Y-+Z-gU#nZskik149jsJ<6E& zo<_H;>!-cIr6T7EuW)NIck5H@X-n{=OY0@HboZ|}T0RGA&V{J^BjPnOzN?qjVmW7g z_9oTj6kF1!_FH#FXn%Xm-}O)PVv{VhNiWyNGm2b39N%(+r=Jg^4gzK3#?@T5N3-5v zpODP0I4svlg0z`&G_%VR=52U!x#g^ZD9=%Y_fzdXPuhj;*&r{ zS8X7X0zKPY%3)O-@OU&hTdJl22*`q=JN$H;{^{M1PY)DrO%Tz%NSd;yz-PQvDOU4w&zngI^KF=f^MFXg+)$1Ux@ zzthcC91OnI$)tUzHIx5At+e#91w}3s$D{e#jA!!w>94>6J!{34^a4G5CVEhpag9T10vChEPp}e$7ac%ZJZ* zfOc#kPYb-TbqUse3y$yih7B(JJg+jTdBb^HxyvBYif7CB^3>#&_gV|2s}a6Bvca;l z%{h%$7CLg7r%P6BhBZn`OLa#lJ{T0v)CmJ^)BWogN{Y?f+&}@F+X4;#%Pe?dvkyUQ zWB-qnUXMH0fW=@_%`~Sr<0%ea&dG7Ofy2XakHgKgjXjw{m+!Zkt<1j?NZM(LFm8ZY zxiLFmy8zG(i`=KjaiOx1OP0$@KCLyvWSGjm?LhtZ=+y*K1S$H zB3+DXLUFN>;JAHuMJOII;!8bVUGAFZ2lf{pnjB)8LV~d#Q#Q?4Ab(8{N^M3Y)VQHz?s@b(A>Ofr*jD|T~ zjQb8T_REuNn5_7|@@Xo=BOSRba8isq)&a!x$Fo7uY9y@V^|> zniuM{cXo~jPQTj4K+DM8;6!-zTO=9}{maz5qO>^_4#Jk!Fh@nr8wMHwP~3sm19mbNYmNXt_awwNTJKzlo0ED|jvl zd6+gWNd`e!=8k-fjt$y1oXaun`EZBMU~#Z!#5S;NUI8Jaoo1T@|ZR2 zsdH7E9^!oMY0O{Z!G^-H5UbIqdgkHR#PBLyEt+I7YOEt79rj0#jPVZoG7FBcV}BC_3* z)5(ix(qWf%XXQEbmiNjz=WF}CPM^1>0m){Ap?JdEuLxh-x9m*Id?(m?TGxOa%WOo? z!%f_lwg-dh2P&SZu*Vy{&CkCLG$vXDGg*<`vp*))M00Zw*b~WF0etd?i}W4i903Qa zH7;kDPp@o8%zL+$pibOgLoe+<*t@s=FYEP-Q6F}yo*7$Owp9q)l&4T6-QFHp{f2pq zg#R7lDbq9AW5qdXsz&xNCKD5JbUMY%z)XzO}Ds*2+etjv#dcLxO-7v|}1E$Hs@-Cl+sd4F=y@LZV zWVC)BNT;t~xAr6`v9_f*yx|~LHPL^j=zPf90y;+C>%6{ptYJqq~u#Jrw+WE zr#V{nKDl3FU=(p<=vJen!M%3=s4g-$|8mV-C5H`Ak*__@IYfpEgt=O*euqxggj|7a zw$-@SZQD(pr<%Fwl0F86S0(_~C*GV6I}G;~vNZ0O zRmjBz_&jR6($}-l`})p~QS(=eGu5a1h>}GS&E2;}PO0|gm{=*)TJxtbk>8@NL=K;j z_l->u^FQz*RZ@leUuVw4SF#G&VY%g1RSy*4SJS#beqMXCu7&ohsnKzW#2*Oh)eX%| zmNlXX0gyGT?ULSesHJ)&IAaBI+^AUN#~9&p%Js@m`lM^ALEu{7QR!o{(UQeV-#8V^ z-L*m)zee8%ZpXFR$oaIiH2ya#GAyc?o!#O~8&H(Sh^;``Yzn~MAda~0*DD35!+yLbJoln}dsq4%la%Y(t%H-BuR(f#6>O>IPUnzk*_ade3Yo_jS<6?Vcc z$SSA`@(HgTXMA{!1hbK2@v2Hh!|Vz~`_`8Dx$#@vaTj7#f$72EiVu*xQTI<)nIk6i zFA^5@VdQ3CX;Jq`T;u8leUYDHsi}UfnkD^Ziou(oLS8|^MaIaKjLDW&msjLit~oel z-OkO8@qtcCcbD&Y4Hbx8D#>mx;9ref2*T8qYT<7WH5mL=NTcO8-!?}nOUoQH`LV)z z6wuX|7N{%*FEgVFJi5jq1uV_fxorkHOqOgtdHIPBk+`+*#ZCKEri0PVbmYZ;iBL~* zVrR;C=3snS+8a4UJy|u6JbdI=6af{-rCM^;_ci&Le~lN7Q4Is&*$i_UZEI^A2FN>P zef)FCoYp~$7c>{sF+u%)$^`x0=jicP55^*H+u|hlY=@-g&;C^_?@^wE|739KTvp`N zxA^)vkNF>yi?4b#5peN+4=r3 z1EKZ(alhe;g+3ll;tsFW5+}k}rRkVV0uk7C8;^5dHe-3fS|X`N^y|Gr3C{Px`R^jC zL1#2U;LU=^C1ZJp5{xUbIwWE!ygqoObQ-i>F=Vq=oNW&A*8YieRzF30qCi4*(G!xV41 z?!N4{TKrV@MDQoJ_kMfqu9dE7Mxf=$wKtCyE)aadOWSvAI9RDn_`4L<4xnd$gWxyk zxW6%4JE&IS5@f%H%jCkQX@d_fT`YZ$CvBw;R{bgA7I==FGn+cikmkFl4bF~%f%$KY z2Ty`6lwuk$o7Gf(d1=f*Q?0eW5L$nZhA83__b%1XnpOGi3pnMJ{U++<`8(#{k2eYI z>vbM5^r{tmW%$Zrz_yY;*|-|T+` zS$R35JQjPiEb3WLvsZVw?wnIl0M?aiDM)fJh?Mv8S4Hz*dzbm@*Pz8WbWr-4EU9vQ zPn6bwn&4{bVgma>WuCpzpMqxtSYyaO(HKkDHs?h2o63Trd{}WSYXL zohw3hK5vtnM%s6VP3iYO;+04I*4G*%X0EtZKa_b}urFk|ob-KgkY&LuRl))7g~%=jMkB4H*fPii$b3kFJ%S7 z>6ytUPEkz?q2TH04L}7bp!5H5=UDkP%b}-TWxs2gn}%jW_cONxdFEgFX;bs>U#ZMr zMiNQafQ{U8Qj)h1L&pL;nxqXWeY~=0*0O>`F4IAd2CLuwY4}YLD7gzH7EPuGhh4&X z!s*^t^%JT60xBRZza(5gEW&by>lG9_PYjVRhM1 z{=(6kv7EO#ZBvC1fL(7so{w&e;=9=R;0?Cqdj%kTy!q&XnYkx@l<_-o%T52N0p;qS zkbIr(*fHZF5*ZL}+|o74?K;X98?B>|~n&>Q!WUSxlO` zOVEw6TOMI`^8o%drQ6Frp_iTnYBv*UfF8-atbW%66e{i(la%#(%hH#Mb=y4UtV$Ey zN1G#rxuIHeNqtIYnk`xb#s?31m6SIfAWS4SmLW}wD|GTd03%Br?uq`*GLi%SiO$te z5f5{oaw;ynZ^=q3#*CGS5?uI~OZ88>8eP4dgzokkD`d!9t}D^a*GqYX21?8|%@u>M zWJ7)zSJ#u=+}wSRZySkV=^58Q?j-+pXEZ1DLq|Kae4!jguX$P#(SFpUY$%!{9MJ}c zDrDkH#Psp&DNl~R2eH$X1T+D3>Ln?WgC z=$(xEy8>*qSM};1Rk?5e-30(`8C%9I<=^gs%eNgKDnO4TL^dYCXq_4^_Ly6`y1F;= z5~yn7Z5yJ?%e z|5pf}|0Y2b$E{6}QGm_^O z-g_u`x)f5)LjN}J%&x4TSL24FUI9}&5jrvS7^A9$FDyq?eV_E>!ucufK+;hj@%Ama z?*k&b`TJ;V4NV`6L7{$9@==UV<)|QxRYji#q{(~nEO@c^8n^%S32(*FvC+HUS4Ekg z_WFcrNs9qv<6?t`4d<9BivuohyC=z8%XBfUfFy1&9LD1UnQpFfwtH@WE^p~y z4K3#AHh}7EwMr{}o0u?@9^t-}l9oGqtedU-sD$6cqw=et!d^|#^eAc}9_%2yT1_=V zs6JC)yngFr24pW14=99P8hPgGXIex@q)}`wy-u=13h0}%ikcu+TlA_R#NKy``{ADk zJ>qYJK4@#njkU?KEM~#AjBm?PA~cfR)5}s9v&4uz=w|`w*DG3V3@SOpy+K7~|KuDF zH%%b=7qWbIXAP`Y=W(>HjZZ8DGQJCPugm+@y4w}FhwKNqB^gx48oOJWN=5mnd*3@(BN)Q+&j%71(cYk>9djwQy()lEIe%3|XE$QFYrL6&dnMbw?<89SdT689T`j z#-S61hL5P_M8`QNF-Qupl(clz_m5x9l7E6Yzl>J&(2#yosj#kavd)WFlU5XD@C}>t z_&t_i$NIlvD>VB}He*gVp=B-0`M9`elV|K0h84Q3Q0J&+MqId=0R?3hcht4&-6LIFL1IkIP#OOU2!qWuM(lmc*gklmB zEvxX)fRxUT1XTM*Kso zMY*~xG8$8}#P=fmx%Wr!s>Yec&l?JKANVIX%xGr;8{}7aC0ggi3hXaw>Nr)IDPWwH zOFD;>u)=MgCJi&^-2e3z`t3x?2O$T)X7jZX3eWRol_U}3L5nbGvi)4@nrZc6+{@-Y zcVJCv^k&B1&!a}#;xf^B`Eh54s$PaB6f$+!%kqiFUSjyD4*2cxXx;2H3j;J;9c{~s z9rZgF1eoqYTb%TZs&!dDzaof>2zxNG+2h!L%Pf+J@6oAoF}o@+O&h$XV^YitNUZ+w z$Vo?0Ma4;_0s2m|q-0Dd>{Sl`;EC^|XS_oQ<0n9LwVj>b)tef1@+)}wYrZoPU!UP{ zhlCSo_odn9ohnISnA&1%kLI53o2i!nbwHJglE0$H_fHmG6`MUAD}FtU$rNuT%@CC# z5)T^#clr~bpu566_@kmGl4!T)A9^6(8RKi_W1)10ldVx-2Mr*CmFN#TzV-TwOUL5Bb6NQh46 zVEJn7aE5RMsnvD3!A}G2^&*ex^wD+<@vKd+Fwe`B*S;z%)nMJ3dT#OQmCF4oWNPzB zEvlf-Fos*eEU(gf(O~Mk#bNdCVWkXHP}>iOhAU>6Y^R~}m0KmW`QGdg)^5%K*#`KG zU32vnAp9|#e2{^)+6_UqdB>}^Q=da)sJov_mOc7hva-1LW-A1kHq@7z+tw|KX1LVE zE(vsqB$onX13J2VZ`ecrFA12dza~K6O8(b4FF&)(h;c`hCkgRE!5L7gEEwmsEugST z0RyLZ+S;o=$I~e!RQt0>akat*Z>AZ-mjjhzjX4?6+O(wt;htWRj_$vVm}!ludV?sXL5tsD0Z33GE zvinJW{M2hLam-h1jj=To9KQTY<0Jn4HIs(tiB7h7l=tZ4yz=c+`Fd~i^Ou?`VMBLv zon`~Lqx@fH?@dMH5%S2I-wdWc@o&rgSuMedn>@$i9J9ITms>MQ#WGEuDyS@X?J{i& zOQTlubxuy^UNtqn4EKeB!8a}Fg?TAzTSa$UR$A$fAe(8J#Z{!SsD~FVxd*9nUH+m0qdYQKmrO_KiYO3Jz<-=j9 z?Tvn?2JgE1M~)4OSZs-1x`aayuyFR~j)%`A1|Xy9dYoTf}^%u?7fDF`NAt^nfcj?8~g zi%brJJtlRB-d3bsx8Dr?iGJ21yDEo>{y8K1MjqRHIS%>nDW8JZ9(2vt*WuGA?yW&w z`Z`9}ByV=j(zb9spJ` zzi|xd{?!#<|D}*ko4op3O5%vB$0*EN=T?-fNjX(*&KW|+lMH0VCt{Kqo~JWUR`iw; zs^SyS_x>F7>s(t;pmuI*KQ~oVvzccs>L|Qh0N**hG95ixp0J|m{(0LBdst77McL1T zv4T~B8J)=xA!}SE(GjM4gT1-;9D{k@&~spe)n&Z2PC9qnq8y=SmC*CXZqut+D`O2X z+#PfBUoSqxbZu?zN_T9?F5g8BZS92iF475To_RFB+{EI$C+Eg=Q#1AF<=1fWKcJ`j zcRX@htHI@kk1ZxhO{sAWmI>Ieki~c4&dM+)F>{Cn`oEo*p^ZR)lw#Lqvw?VbrHu7u z=7l@v?3Zax>%x=YomvWZCg0nkyf!v-L{s#!u&GUKqC+O62YZSoE*w5R1tHi`j*p&I z8dr?UUW__bGX9llCM6{`rjO@_&sxKpEe#gyw0LFDy`8$@t*?*p-R8$NhfVqlmHQ5n zI9IgjWcLW+7%Y^|28JxsN^*h5V3ZgYI?Ya39rs66#0@K@_AemmT z2k6Mp@3CWCZFE0lPZvv~ysg@JNZ!{Li^dKr;^(;?(V5MHA+8Xq%Uu+6{!-vU!@~kd zXT{;2HQ#7vG;tgbG~B@Kp#(3cs2KAS`{{x7cC(uhNdH`d#rJ@=j-$P7uA#GgYEf;Wd`gm8ZaKD@_5@M}g z{>E70A}|E*Ieh@5mO+e$3Y0RuMNI%=sBm8g*K&O|>f}*5l5~nH@Yu6!mNy%jk(N8; z1uT%-v0Md&!`So6ANkE8i?b zQpdK$aU|lRL(ln$EMKAaB>7F_MqiFpe+4Z;Zd*6umcjSfi>IC(7v+cMC7XLXUa?jvrf%V(#$edp$G(2qxKjP z1WWxs_5(a${VI1mDCIFpGZgXgn8AKCtI5oJiAgM)XC+pVk#WMQm;eV7?$`=wV|ET+ z_>CbKNt$;SGEZGiC8>AKYR81&(!NpmWXP*2umZIkz?VAs;;zh|LR^P^#ACa#ol)bi zC8u}oH*#f)JV#b|LDw zI`>?F^D@!V5Hibf0;j{4&SFpw_b3Q5suqto;UV%ba?qyc8`u4Q)(Oca`AyhMMY%_ zb{+^b_+=RN;P{%!hnh!@dF?T5jD8rO_;WTb-q% z5(&3tGww@!f4vrCB-pVvRCphdPiM~S1_KWn{DM-?`v2+JfxyZqFoCh~Ij%~O_o3Q& zdi$%i2GFNSgNPw)vuXsAC>~s3WmGl#55y%f_rJf+d~VtTjOpU+XGNd&_!UY z8kij{<>DqKrMh3m6cm^>dPOKoNZ1lEqc^^2c_j4e9E?{{eWE!?FD)uzG`BToeU+7< zaSL$Zjf-d38*G&;B_x1_8ez-2Z^OgDZh3b8owoHxhrH6?Q1jaS-e1oxf77LzXgYoi zsWetn%!-q3LN5$(c50S94w(xFtEpcqipb9*Jz3iBH7ojHEn-g%e%$)$=`lGJvDlwi z#yT}FJy2LMC3sl|@dVg*PzF>Z<~1^~DTWBu>{fSH66fq>qJX+Dl{CB&iL>uZW1Uw`$12MeA zDdX|)6aM?RB-DXnOX}ltcY@OOng7GocYw3mesOoas@1A4RTOPeo3>W%mfAII)UMil z&mdiBQEJyrjo71NHD+6{8N?=5s1h?l5D`hf2k-y;zUzuc+w01c``l;z&N;tx-wz_J z_sh-2KBuKI|Eb!NL!E%K|L1nvwGXR)byIz|J0N7NlWXe|RR1eM=llfXdWA)Q;U|pn zrM|Tw`s!QkUhUAUK1f=Xs^7r3Z!MR}=5LNMX)2Xrzr09VtE}8(YyI~d87lHxqy_9q zu`eAL0=$6Klc$D;K#{tk-0alt&Kz^gHvA2HGvTXEpE5p390xq&<2;EASu+I|(RNeo zsA}3N_b+N(A9?;1m1uCWa3^cbi?OlLX8<%Kpk)t~=Vfp|7S7E^{KtNf{~!ASt_qgy z>u%2q$EfZ(5ZfODQ&{pA4;~vt#mG?s(knsx{Fn>eYvs_BJJ@%H#eVDO&uM=9Ey_>x zq8*yDaNOA^ef6H+;7X7-Qb7lLh$D^3j|NO%>`zQXcK|KHy)D|Ro0NyFG-sE0m8p$G z-WHZYi-L7-r-85fVA62WvQhHT$S>Noyd%rSE@`(LteWL7^Z;%V4QrVVU6X{V7ulI` zUGsXq^$(C~0!rt+D}6!k*GSUa+#=v_kJ6-kEikj30l2^7Ct`hn2Kg{rVOl=yT=m3SB^IdrxUIK)oV#OSnz=bMEo)|Y9qFgX2$aOTdhK)% zg0t#Pg@wi!OWeQT`~-BDd1i5@K;%{ja|9*wKVrQzV9P6SxG zCB10@eB)9J7--wNqzQTeGijE{LOmu`594C*AV=W_-*YbWy03%{g6};T!-L-@uDQuN z3qA8Z^YnoFQ;?E}o#6Z;Y%dH*)}oG+wTTk^FMpv^#bbZ7UbA&R1^nYKON8~6=yu&3 zGz{`+Ft)i!{Ho@D+fieC4<0rGDj$7=Q!u_yH6DD4<&=r1W!}u5%&aFYNqT z|C;XWl739rpI&C}{i8aC=fE`{L|<>o$iR%Oq`ow<08C0u%f`8fAwy=vw5&n7*{ID8 z4q%kM-rna;=+ShJ?*!wlxFHmmZ==6ZsN48yV4iFurEh0PjF(QU^KJ#tcQ;`2^8znG z==oO6k2`3H4A{H&9~z0AeEks;@lwZN9}*^LAH#oX z$%O9xDS9({0Vv$u{C@T8FrK5+^6&urIE{G2e#`8@$b7?$w1O>w1XK9SGiT((Xuf)I zfa5iY!y8DF9AI_q#3so^yD5OUn#;SPr6}60r6`BY8+FzbPOWl{Zm`Sa2h#o6R%>aw z8ug><;wt#bHw(>>fA8m5T1937mE`xd3~$d=9SsdZq^|0mx)QBi?CN@jF5FX&fiwQq z{j7$q)O#m!SV-+ZZ$8!4hV2i|g6uQD$C+hb>8k5HMcZkRrC{_Rkn|N8U$|7DQTs4} z{62?S4jiRHoI1Azkb4i8-X?>u-;#pY2gD_&>AbqBFda}gTaR@)h*g-XUot0E_xrxz zYt__7EdGINie+d44IB12o9E17uQrIu7_(9SY|K1d$Q)^B4;1_c?&mbfPgk_#f8v2A zs&S?NR4o_nK_+N+&W;`E&XpShlNOF69^*s4rXLiof6t!>n&)}e*Dr^oCMW+c4}w~w z>i>r>{uiUB)K(WvB;@O=EinL303YinL1zJQSR8*7TP=s+F3(5d={hg?0Fp;y+Lh#O z&>5ew@Su=aSkrIDaNOk2bU^c)Q-Gl?>Kl{8m!y5k?>8;SDTipNKBaB%u(i`PFh8`? zK_!esatfH3L%p<8)w`jX^To<NRy2b50{0;NEUPASK~mA;P}AI7Fj!0t+3 zaEn|dGx<-}{tF~?Cg*Ehm|cg@=oTBOalZgq*pF6PrwWFFAqJZ%34n9Z*C&)7dzN>) zDgbA^Wq+cPKm7jZ3mZ`_XD^VIGmI-)^zeefis-o2I2@s=|%Wf!$#PLCEQi}e0s zpf8h&G&zhv(nFvKK=AJjrd*%7GHr!+VYn`ED6Wn5B>i~XJW;A0iQgbzoQPIHWs@HE z{;7;1Te{yY9Q|`hyf~w!xbP_uw9seS<%W{jZBX`ei4Ja_b;CT`4lB9oI{xUs9nSsQ zWQFwjThvvcs%TONj8N0^rdASJKh$wj)WlS(QFmBAAC;<}-7Z}8;FT6l%nsB!Nkje5 z{ui~}MT;Rl-rLk!lS=&2AVB*C);DKD9w#pDUO&i*Ox>x%>@>YI$z)BByP4f4*uo8r z(Frd6y?m*RbZIl>RmJrP!cMjplB(1DCtx=V1jFqI<61PSr>plbp8B9crFWU99l)Q{ z#&%8M7VV|MTlbiR&7X}LD4L$P=~>PeEj8?iC?H?xD6}skQcWyPfFaGxH@^hX*Sb86 zdD3`uZSH9aVJ0$BEoO$xce?qsB7g5 z8qo(FgwtMTMD`c5Zne-XH(K}|e$m{bB`Rm_+3%~s9HYHo^va6m#dN*Xgj&yAi2zpG z@Nt-yA&O&^LPC~0iLLuel(Pzb9G0Py&{CWV&qM`x7xmj`jqsO(tMxAG+)qy~0y z!tL{b^I`7i=-xuU=L|sm;VqL+AP6<%f9lDqLDo-6RQO(9f(J%YTjlTWpL^VxkFRhm z=~vwqr9GcaIp<;>>?ofWbjii~`)?2%PwJ)KXQ`Gz<`Q@W43(jWW}yTkBmW|_1xbo_ zM|;arP1f7%YvU@1dP2YB`gQ!`GR-SOE76^lm*1%e=R~H-TvC0i>0j2z@I!YE zL|9-p3u`9Hb*jV50%*bO2;Nj07L%3DOwlY|ycYXxvbkTN%&N8j;J|OMKaPSvq3c{} z{9o&|zBux8mT?xkv5$!6z4iCLK^FS-ZQGrt^kB}Kl|Jn|5LsA3lEi`>s(1e){ zfyWHZHh=N6&k+cL5Tbz9{o9ulHSSCKuk(toFau;;&|dE&1qjr%9BAzS2;4f;ZHr@~ z%PZ*@*zgz1D#4={fC@Lqp98;Epj>0geJdd~1>I+rNpb%@^#Ox|Qz6YVaUSaxI5IWG zx8|j4U5BWp7;Bo4%mq!wvtD<;B%R^b<(x|yIu(9KNRw}eiDBoa#?-}T-!lCa^AzEv z0^t9P`NY1^sA;S}8B>3B9roPbN_N(c)TKHUze8$ccagz3!ul@-$#KN3sG&D*HZ`Ozh%lw^RdVN~^UMA7}}*2@eWaFW@npWU%@ zw@;m#GaiX@YfdMogSm+hMOLt*7&D+@ol4Pe{x@&+km>yem7DGj*@1_oxui^YHA{kcJ_s+H)6YRVh(AzI@Poj)Ufn>V8&ZmdXE^{6C0InO=&Ctndqn^|>Kh3_~zaP%5x0;}~el>^_%RMTj7Q#?xQ$@g)t-d?JZyYA3`w$rQZwXXR#$~K^dKVMO z&lnv$`PwabIVaM9FV#Ts=E&e+&KK(1C4EhiG-SJ&KQ&)o3&HMKAsk2F!If;$fk{R;{94RswWBBd z^)*=Zc!X-s(Afm)v=Pky?qrFmKO#|8iRGz+$TTuo2=vMe3?n7-@A?UbQcAYL2MJJd zT)g;By{1E`>X<_%o@@f4yZ+*ZwCCKL-w}6*pYy^-&b6NxGRmWUf7c`hT37eg-roMk z=SahK6Wy&Qnq({81POIhZbNB-lClcNu-zvA4LA41*CtOte=ax3(dEd*&AK@f+?5h) zJaA4eIOp_&$v<9w{r&vb9d=U}>Haz6t-;O6rYb5r48sR40KsMz)R@-@eAFcZ}(k9AK>f=^e!p)Sp2vu>8>{KK5;O@)g4r~{D zaV;{rD=SM>x%H{~UwFB*bVVdxn}WN2xj=T3fCpgBAV;FL09VD$k)c^aJplvmw4=`&7jwTv1r!~>)~Ry2 zYXzh<^AbkN;uorY5uZOX$CjWWjs|nN0F(Bus`cdN^|z8jeKXt`?v-?hSu;G*suY58 zmdD-pB1>g!0AroJHIIs%v;^uNmh6d6GCE#V(<^qfdp`JCZ*d`L@oZgiL!+Os_w!GN z7o0w)v~8PKT?7j|J$$0DhY8HAv-X%FICABB^5zqXL0Vcme5nZa9)#WZG2qN?!+yF%54Za0zxM#w#T?eN8_`CkctGvONS9mcV(U{ahf)%O8QW%7 zR#}Z?RaiueFd!s_?;*@ZC@PF+1=C+(u42HvYkvYT8IX3 zQ&psV$#!~z3L>v$$KbE8R8;w=ZebDLFAQoCVi^ejvFnL5?xj2<3qk&7W*NdiC|ia- ztvf@&sXD58ddh9qb`JKw`(0OoH-j!F1O8+`U)SfqzU0ueN;n!C*Z+?Hp7~nuG|i36 zk&NfhiMe6?C_%{N9!Boo{p(~#V9QVO+&J0tcBP?C%YYC=Ojc)A0m7kwoq>NOV8XBe zmV1SwLxjz*xF%wXm(s$U!TP3rVWd2DP46nbd( zVVte}7v{1?Hx?=sI$7A1Rjx*+0=acja>Yt)ugUsQRiU1I4f33&enE$$_ zNCTuybhJ#?HR;aw|11HjhU1sNNU9h_BIuTErJFmME~qQ^4UFiyuV*lD7fe{x-c*JT-2uw_f& zghhlQ>^jZcC^`Z%6y2Gx!vP1|7(m;-4rMP!QR&y!`qVrQzL3X**TgD<_{xJrSc_0#lEAb}u~($v?^b z;-RU5yn(J5hlxBw_^%;_tKN zbmLv8#{P~Z0oCi;@2^S?EY}^fv$972{rjOT6AIMswX~m?d=V+q<<(#;)~_fs;4cQi zV0#oJf70#UGE=BNyo|B??{!M^u~u9=(TXm&w)nAVuF%j2IZX9GxC{~|51K^SKGWML zvjyN%u{&CUF_oUoWN29qb?U($vB9HblVHnm=+#Hy=virewIYW#3R`nR_;h2L_(8Z? zD4c5GAL6h}TobO8s=dGC<`Zh6^SS)xkzyEYNNYx06Ft;|S7=oE%~&^+4ywwaGuOgDC?y$sHh% z@pg|!J*L(Tm2w5@L-nDEK2WW7n|w2wjhf5U`d7t7N;5I>dU|%czC6Sjsvmz<;>M?E zHMpN)TH4yq{{BW|P29!z+8)?q@ce%-0)xiPhfl??;iuvj~nvroC?V{V%WITj}~vsRB4EqnCnCCNeqM zwLU2M8>wG`3yrxh#0!q##*C+w^g!Etwv)xdiwB{=8p=oSa%bWP;#(_zNN-L*G$>W%Rj__xygkxJp?^%*mslUd(2_b zX&2x$|EB!O!#gsNRB;a{XIPPjG9r16QGMR?C1?*j`tSaa+nsv6w!F743D;X(2v>~i z$mM^m%or7W@2b+&Yz{5)3Pz!eMLtUs*eZ8D!G*8oU3$X^KS$O@_+-Moh65en!T&1zBbxKYhln00(c!AKO1dy<#?!$e`^W$-r({a#x|7DkiJ`4 ziEgdB{{v}c2EP>-QhGp)aPm$S=*q8x_*e&T2O$e(I9 z&;uj|pFS`OJ-cx$H8;HI-tbjM522C;&&Y;7U%stZidB)Xhu-VY0U2838M;|UgSpu+ zbRwO~)l40akAJjK!=TlX=TQ+B) z`(iBVe%S>npIAkkyBp1RmEIul^hqgh(%YtO21YR-YNq|=UZ?f09|eU4siYLmgfpjW z+b3^aP`z>KA79_~qRY2si%=*jKwoIioMr~HAF*Wfc=Ix023GwirUxASsRI1Tn$a7k zbTr|L5k{4kd7Jv-A?;o_9$j*qg(=&cncpor!m*xof2^whla98cacJ4@A|zpl1#yRXIU+v*Q*UhUYO0BbE!sJ}68I0ruiEcfTnaeQAdI{V|wVy9(F)|K$- zGLI`!D^iSfG(ZxTjIc8_Fygwc2fTQ14gGpgTT5=)n5^=NjE!MWwgaH;4cl80uiYND zFL<>txY03p1`mrEMjO{0%H0t%jt>AboI7^_B{u9~q~TIlj3`4fZ^-znT?{hAk8P3B z%tub?(cL3!3rtxBD;2h&b0gtg7S(;O@Fi~f)DP+8i#;A2ep#Xs9KLKo$k(#z#+KUB zhqhQ-gj)I71ZI>~S{YYkc3~}~IB~o}saYlCsIzx@iBSVjBf4n4J~n*S!)UKi+z^uy zTGHR@CQtcpp5UEuSxuUE<2-KQx1|{#k5A8rj2(t)iZb-^dUAbRw=to)Oly$N?}8NB z5kscrj3O4LAfd1s2pK7Z)L?vN?ZNcD>Y(> zB~)KM-qE1INjPFn#j(n{=^n89QLZITh`^DvIrnbW5vLn4&d+z{%T>B!bH25KoVL{! zQz&U~T`#xUf_S*KI}8Zql(xi)X}y*SJ%h6etFA0EX6PkV1lc|=(}sw5Y$mP!KtU44 zcU*+m+F%hCt}Fq26}?p zB9;2saE^`%t`P*|c)*g}Bv`3An0;YytQBe3`FmTHi!G_S;!fzr}O_c)au@iHg*w{d-zkqP-QKK z`?46NwqY2pv;`)!MN7-Zo~m<$CG1;}*Q>&H21~L+Qh=<650gZ zQ9>3cwcao98GUXfFx1BYwQCNo3YLQ}a`(*Yl}jUAyX79Ia@qXLBa2i|AMy4hdcPD_ zf02Mq@=f(c|4a6cO)->xndArI#>~Ss7EagJ*Sh%be6)AK+&KSFjrS^DS%PDlRX2_ZSd|38|Y3>v@NzOB9I52E2=*XtV1*qKw ziI_2~Yb>mXI*Z^|33DnnskxLTn5WT-(`C7I6a&UrIxorJaaraliEMreo2|W-%{rx8 zvNj7z*bO3BVg_6Nh@oROuLtv2OAvmA`K;VC+$(q037Qub`b&S5=JpJJndE2VXJis+ z)fyg|taTZkn#$W<8yC14&37%9_uCu57aJCy_^5BfMk(+u)ux|Fus&FR>Oa zMX;odwU@>z&{J}^&I?m#>I|&2SG9`e1}h9pjrigLGPFT)HgZZDgtr&EaZy@KLb&a` z%R&cz!%C-uADIk@6b#c7SxZ1%GN;^^3jZ!htI7zx&nE~cmW8a!&@h$nv5<^~T4;NNO*D0u1uRabZ> zRKF^JWOZ~^3+g)=K_AsI3AmU$hWTn-O*=ffy1erRMF0le{~1QDvIg?GlGK~0Ew19yO%RJ^b){;cWxzJrRx^cN{j#aF8*Ty zppKv0YyA6IW+XxyJ32ZozzTp!eipwuDlwkwp;xUbK~nE^8f}=eFXKisbsBHl1S+Do zCPRc?hH|u5M>=EpRZM^#LToOmxmj?Jjoe zLz+cBvnl!K3_nve9gWhXg@WEdbG8jOx__7wJ%+_mWpCBN&!(|#GOd`5 zOev>otfO>>;ZHAHlaz$+e3(x)g51?M|2--;uPG}PNIVdlhD(dyb`Qmjp)Hm0{5gHI z)Vh}$K&@tUcsP$SOCV`=W3gZN!PrBoP{3cBL>j19SaeSNn>%)Pm#kI+8b!=!qlqB1c z@jkek8f>D(QOPPAQI7yJ0(ZfnSzuo`+r=fv`&1P|U-YFxQhG+CK=_`TGNe&y_h&1k z_r5m%&&D`J`qLnqh+rL`QFxWyy@kn-9s)Njzc&qr2p0lrFc3x35&gXNUtT=8VQ_>< zZziVjcY;8{NoHL_G)q9p`UQ2~)=<{e>SKC=pU}r`11^MbbgINKbzWeZOK6SB12*C6fYDT6sv2ymhPbod;19Zm1^p z6!A*nZjTor0>{95CX`cE#qL%_M@NTmo0g=Da}VjyOJLjQ44wf;UK!yIfo>4u<7s*RIAodPDB;D9H%9$o>79k#@h5k z+Pnf}&r5pA-3D z*R)z1DqcJq^^Eh;^#TdE*_w&!re-DJ;tj+oa1+7IWRuhTv2u$%ILc(EF%&pWex`6G ztxP2@*2y{8w66JE{1mu?3U}MTKs5)J{Ifge*zOV8;M*?Q!>_|^qKWzT7M*!h_htRp zU05DQ01bxSs3j=9)DILGx=t`I?axE+C#}CF2!R>cnp9BWvWVGkYI4F62Eijre>D=J zHDwG!wT|kAP;7cih?Vu zUgj9<&th2JT-NLB?_29y)-!=;o=NaupD5;-^-SF3c)VFd={;KKr{gVtV`sIB9fb?= z_cWT;_`rcIEm?lUw4<&fQSN)4ldQz!lJ)(mjE=+^g(SJ}P^alz?$~a3S#OuN^r>WA z>ACr;U*H!Mf`SP?RIQq)SX}c8 zlf1qRq~hrEwDlMx)#n@NdYy#@8@h969xZqst&&y3eI#AnrPjaC6!6JLgN_C>Gc$DO zfV8~C?PV~iq1J!HIm_$d=I)NKi)+YpnE?4B5Dxq#C2Kr0c{p1RBrcjbdU%-WFTbxz z-i%F(y6eY7- z+U_DkeQsH&GB%d}1_M+dlJtgOHurU6)3_!D)|W$bub zhNR0(RB{ipzxxt%Ns>l-W~MGs-vfNqW7n?pG~9+sS!sj6a(-?8j|2gF zGdSM08d#rh!h&8!0@xoY19qiD#^ng^W0x!Kw3+>YN9#O%3+gVLm%FWv9+HEj>GhpRtzv+Clq! z8NZFVu%ZmGSEF}$6J2=IHMfW5YgnU4?8bK?#{E4`$k|YqjISfvp|oOB;(6~QV;y&v zzuqq_sQF^1`&(?cddht`&b`S*ft5X{;dsx2PxcJI{7R8c2w)UOa<<@GZ$EeZ3?MI` z{f}ii)fSkT`ADD!S&Zm)9^XYZ?>_Yt#M78ihXyL_mh4S{ggwneM}U-;uK5%Mz>2zb z%jI$VzpiCY7?>RATIeWw(1ID|AXE`IOTzS6>dFZO2dMb}Sb8^D_$!u{W9U7DT-j); zu>gzP3!uSX(M+oGA-HeI2dc>g;08s29~;u%+TaXGO#Wf9tG^MD)J9kzLCy8YEX+iB z1=~S(m?xRRZ+SDma5oFEw>K};@1RD_oSH8kspNemn?ecOOmmBirGi*Fb$cbUCFrn- z9WT|!zHHz+Aos04VwS6#+NiaF+LB3L57TR#DA(|}GHs>eDiVqDzT}2AmE`Bf8NIfx z4@>?gkK)D(fq&mRkQ?)eVO`q1Va-D&8p(X%LsBEGxKCY{eHV6;4F5$9xW{T3m2w19BSi@umFH%)b+lMh0-&}8 z3+Tk=AE|D$7qH37M5$DxbrQ3kl_)>ibHyY)29_GbA2c=0k&OnS$qm3AHr(pT8p>>J zY=Fb;>F<}{K%N7>Wtib$$x*gf(eHXS1`X@m$wCjJi}O7Ysd6yde!r}T5gxv5aqf*d zPC&_4iC8~UukwjLOiw$2tejQF`UpnJZwZgChK7Bvs%{|!i9zCPTN-$%B?p+tm1P&k zz+d$x;1e+Jy~UWnv!9ln02Ygwq@=3j5kinvKh|AOzi-Oz`?0@1jMbhWmn8OPkQvoq zu=}8oIT3v)q2ck>Pr ztis!_MK>f>hhW#l=L0Ja9_}SRx3B|k3-FnQM!VR&Z~ZbTevikHW9+ED`IvY$6L|mm z0wyyjgD%NJyaX5KwrrS&@qy-K$J3VUJc65s!?kRHn5a*Ia=5V|t%3}Pzlx4s0oFKw zSP$&AF@brQ)4Ra=_f}P!O~(?FkX2T}pcUJtEfgl%nwC;q)gpIfHg6I+j(R_* zWKEQm(L^~QLPHzQY~0V8kK}^ai+-Y~sG+tp%rP*TJ#hwiSNHL2zy(Ts9;1<%!IhZx z(b1~Eh!-$KD466T`nCjzMP+P1Bjy0S`Gp8yNypGa_=wLoCM>#0&y>mXfHi+S+p@ z?UKM2ZQPKph*=E5KB>8;V4Rp8lZhyCdENM^r=S$SG*g*CPFPKIgC>n>8DOTOoN5=- zOVLL_J2UgRI5F^B8kvTpzdthbn$Y7`fH8M{kb5{LfefAGOB!P>n9!cqGWlEJ{cuk2l;7TM zEQ7XhEHS|2{^QV`YEf*X4aHP$U=7C#R}TkXDL#eBV>-TDDIeTLooyW#V<9z`a;NUC zbtrN6+2nD0_q(4jM<$nzkN>l1h3JA8g=uZ$Uckl-#=pu81J1Pko({!FW3RN-I>=Wd zZ{5YYWPng;=T_8Di++61=3R==@uN?2>z3E=>tGA12Ng~pgKJHHhAY~Ss=YP8Y_J># zt7~59z<=$?v_mj?GpkST6l>G5x`@>s4~M_z(*xOyjm#*dhvWSA;emL>;FVqnm;OU< zm4@8;@czX0%|B^XYoh7kAQk@~Iw38;T<*;`JzJP85ho=2(GhY%e*ORd^lz$@Zzb$+)5oA<*P> zY;Mf5PGv+URBClgHRp^I>sLkaNn95Eiy+o_+kr~DVQ!{ljP&y%ZE+@H9%O>!gBRm} zl$mU8X-kmmSPdt6H3V?O+^IQRm17XMaK#yZuc7>}lrj5d#LkKj`;3IJ%d%gEk3H4F zmR{UAMl<1lMr3BRaLVq}RDa$KmVR<#O-wcLD35}*gCxxaJnZ1g?4g}0N>NJ$?@^e% zQ5hDu(WMq=INnK-$8&AiaF@-Jm;p~ zD2KT&&-6hq&Hlf+5H9DK1eD{9fL@sJ(-*p ziw^>BX-Zm1NVB^?mQ2&XJAV7{*mqVPo4TiY?$lnLxy_}iY#$;;+e9fA(}V*5q;8gh zAiK*<($ip-hLI7}sOel_UQ=_v7Dl96%W+4aZUqemOQEAcx@ua+;WVC)8PoAdWELR@)&N zD?yT$FmN70IzY|0%1jU+0A?+-+%BW>7>N%nsG2fS*1en1KrLPN;K7ggT}s9i!72JH zLA$5J)S1Q&)9UM?H`4R$fcsPb*RuGzpc|&|Lf0l-??2Y%vFq4*j}JwGUWT}2Q zL8u(i2FV4dMV{5tUQX+{i&{qxT6W=N*QOI@sKTJRakDaSoU*XGKe(_gCpjBm^$WnH z&A$M0O4t+WKAVN`YAmQ_{I*J`dk=4GKeY0PX7p}|jT%L*pg3GpEIXd9l0%^BPM(3A zu6v)t0neiO)p{AjyvYQk}YlIunP>zGigHRQ(XAF{=jQrvTHO519 zQ@bwqfBKGYEj+c^d(1NWxsbp{t;2=5dKSVKAiJ3&h-T?SAYJf9!fgpO6$|!MTHDZK zsXK9G9~EtoPh-koV||$A=)iD@>oekTy1-zyz-sAFn>f3qP$lxqo%I;l{OVV)SI>ap zJL!Co(s}bydhHrvQNnK7?Fc4iemEB7=3_bU+b;I94h@l^{5{;vZL=F1nJt)}6;KOl zT0r&y(rA#XnNVF2)I9hwSFs|88pJ0gGX(hlw+AKo39y}Qrlpl0yU(MZbE}ZStD1a2 zbgvg6ZN)G%*VvDAjRDDgg+Jjw%^VpEZV1J4DvGh*|-$E)xx!-Rd zrA3dOPR!Zs6TsJVSr#!ZgBt_PO$&_C`oud&G-)Si`N9NbQRdL?%G5)>aRK$J+r#%7N!b3 z>=e(r<9M0<2A(3&G+F+f{(jAOzlH0Q0!Ku`olH^x9|jSc`jxiSV0=5Ig9f{Xf4fvG zT^iH{Z;}dBm`EOqh}blT7TB@SkK(dEI^4+owtBn>=KmJqb08e7Px?In>81etUgjry zAdWOl`t{#dYs3+?RfwPatOJ)RS5Zt2|ExM+9!Vs<(6SkfkAeMKINvDpr7Zk_4j*_A z>cjGG+uK-UaDA&b?#MnjcaF=mKNsvT;auSNQDk`(JC8hbK9rex3F0CaaI{UD zqd{gGb*o564xMiO(0#Ux_9IieTJB3ju-*vgZClg%*P*(z@z0B&oW%7H_f8Dneh;jO zQYvq=z;LGq^>a5;mBt2CL;M3k{m<&jT|WK$5D16^4h!l!R5u-~l&n|1P`RZ_+3EKCNQusIb;v#1G}U8sst{0aE_bYd4g|Ng)?mNU_i1%|U)Fr;2>Vy{-$ zip-SX{R0tZ6NoQE7QS_fJy^!b2b46y$!sT+L0xzvmZ_IBzpeAaDVara`{m<25=%*U zpORC!c}aIG2XX{w(dDS@^(^O}n;9UkH`m`Dmn3vP4ihE;3xr@dvw*Z~)WKgL&|Gte z*Y72}SPsBg@R5tFDUAF?}FQ!KvzXhfl{kwJKj}7Rj+! z5h&^I>rs7Ao!GxLC+qK`f&$#uufEQqhE^$3%7PdzCMT2=#@XjkFZs`(DtHXLPcawA zss`VfZg-ffu?A)Uccj089seo7g&9J1ip%Tw#sZ*>fK67`CT&z`*sskG$myVL(WOx* zq?Ao~r`&Xl)L-oseVD-R-2m5nd0mP=p7LS#KH?xVV~wCx=j~Z@JcZVxWb8P= zG@tmz5C5K{YNNm&7W8c7IuL7;-4;3fMb3NzCKE-KN1erOX4WhG_4M}q z%e|dQU5+#@+jQ^LUlkxhns>`*eK3u*m?Z_MoyFf-nQ4>xSynmptgJlzHyK{vuqz(t z;H$2*&lcrS)4_cO!VtF{ME?}TH~L3G9{BK6fg1k_$j4l`+tt>RauXe76WHS;EGEkX znyU}-Cj>)e7T8v0D)$0$wb(ZGMyVgMjE|fJBxpDNhvdGumJ2`;tY@~`Ecj~0W9$}~ z)9B>}Y%U)=qs{04`{vWAhCkDy`IgsM_T)JMma9hS1ssNf`ja$m0puq>VE>&A>{H+E zj-+*()H>d+m~};;J1tk-u~2q|y>0u9z$8OsjVrUopsYl~^EKbpW3xDw&3v4@2ma1P zJ6m|MlR{L+-UOV#&3edV2gc5{O|9U=B2ZK>)LHP~Fs$(-nEWzjdLob6q;fN`uzFf) z_s}Q(th>Wvd(;n_jV!FHPD2d$MZT1A1wU38V)O;s$I6D3=;_+yP4Gyv&*dkYmsu8Txwc8 zS)Y)-Fc^wWUR=tlS?^zxtI|~&>scBA-OY}lxsnOskAy|`pOF?F_6bf|GglHiJ4AyY zXnP!`!gJ3~a7d!QbfI5kic#~xXATb4ee7LSXamN4y&*<}bq0<6u4I| zFNPV_Bfi4F3^@riE)ckerTd_(hhH?+ERVPGl=k@(Y4B;6`FXNWu5iR;;M`kmeS#{e zrs(FqpR{BS`3x@#(YO~9e4NYc?x1$LaclWr5g5JZ_|kkvh)`QM-+vR7e_jHPDbP=m-IT0B(q zP~gvo1mUN=l^2J?+*S9upcrJZK^}VjA-lKJ!qLvmr70hS5FYN}-L2jE%YCGJmkVx$ zY{`g#0}l5>#P?9SAYdl4jE_hIrG50&w(7q#;UvPAVz0m-5-Q`=m5$z>FtVYfUJC& zQKIa92Tizx%BUKEFZ)sBjlxkhjux7I_rK3`?LPQC#yHf$Mq$KsBbrH|&T}4m#W;O5 zIp@7RMm2QSC5|9p_-A&>PH-hGt(XznmF7mVc+NGPp!q~teJ!dFIf3&!ash7~{(}xl z6K>3WBf%EDIF8II4>(XKZ$2AXh!aDTiRitGmpT+Ljj_@hqy&c=Vs^bn(q!{8zFdNU z&t+T@F*hwQ+d1Fw@w{O7YTTH}(HGUebfPUzIb~p8Vf8ARM?Dq0mp|H|d(^Jt$Q_&c zIAV8daO8Bt4gSDZo3QABWp^2@PmVePuhCu8vhqlNGX3amDNn zPq}SFy_nMtArkGs{miqNuVh?2*_tZ95(ezH{M5ueTS=-9mh@WQnn2#bVuFC<5Ehu5 z<1aovt}6VuR52cK$gd#ECFCy3aMxpgR}Tn7Y1Rl)#4dDV{cD@hg_E{9B@}6$cyXsF&jE1Zj@> zd2bTWoVXMzRx^=q1!QZM=AOmu#!C$(!Gn3>-zJRBe2hcm&GsgwV9j_HgPA?hpH15xVc#1C{M|J0$H=^o=OhE*jx3hPdof6143Iqu4# z=cDq=ad!?aa9G+wK7eTIuPn}z`a}xstp2i< zVGzbELG0zmOCgg*nTx|I+>2Mgpt02eX93vb6XQ$NgzsJ>U4oSCs#BYx61bnzQt3l- z>^{kXDy4FYn^tPh`18N7v%e*swcxXmnxFAMDkA^^W7)ima%Tvn6{llkO*#qZF{XAkm!oYK zgvNY>beKu1No0D+#b;Ja=zCDaR(4~a091(mG|`5g+{@j)eSR7j=deQ;oOPU3u$^dq z-p%ZHqM4(V`FgJuBu%cB7Gf2Dxzr)#jHmkKnrJ|=>RPguKh(ECb-Dph zPG+wN?1{}> ziR1aU<(sn#E7xr?4f>`Sz4$QRv@!cQe<9jG%%ShXmX74hcLEN1vUK5oXb*?6#%-Cs z-I#R*c?$AXl+xVGDSwv$lp>eI${oX=DICY3q?5j7qK-1mY={2p*Rw z?{hQ%9@+vu z>N|VQxxH#LuT=tfVD9$^H?9hTAl+%r>~oKm{5-w(S*!l8`Cq2LbVvP;doP9Ogip#W z72ErL{r8#HeY^cZIem@;IE7oJPOXm8>DW3W{~}*n`t*A1>2mW6{&e_zPs^T^xp$Q- ze>qSsgF2)kAn; zr2GfV>+Q#ke=U8V2ew`roEraR75`bz9Qpred(@VYpVP%cpN9t(g425uB)x0vn!S>* zIX*dartYD)_A?}E51p?s4);p``NavGG(SPQX`AO=R=V*ou)9oG{MVLjpl!jWU{iu1 zrmWe1A<6DmlHDDpi2aL?+5jEUFqs=tD1B|x{WZlN*mjedzv|=PNqS#q&Y$w73{r3f zL(1d=8M!YzRlWq+EUuit*S;@3q~=vTC(w)omsKXbd9`-Vi|HUA`IW`)Ty64DcpfOT z{kZCQ6x2d4kcn!2wz??%Wv{LtCn(_*WGw)fqd+D@gH#A;R1FLQn!(*05W7JN9F1V% zE8unrn7IJr7%@6^J1!T4c#CG5XhbdS%3!G)a%u%C3!9eE#dGJ5~cpoUj8Q6YC zzn67MWMNPS6#xtj2}eK)gMpz3)HMgjw%~IR#b5wU7H*Ivai9ZKN-;1T> iU^|<_hWl_VNjNn(U%U79xu`R!AL8li=d#Wzp$Py=;J#V_ literal 0 HcmV?d00001 diff --git a/sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_right.png b/sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_right.png new file mode 100644 index 0000000000000000000000000000000000000000..cd6d64eabd49a1c63e43d6092533a98e0522af2f GIT binary patch literal 44147 zcmeFY^;cBy7dAYUl!OQl0s|-rh%`udD@aI63@u1^HxiO62q+CA3R2QBbVzr@4Barm z&_lcj_4B;XPtRZQoyA(`jGlGQx$nLAwXc2cJ@3?16o?3@2tXhZ(KAKammm;MKL~_9 zfp-h|mkIc42XMf4k$$F$2Yh_-%p-vB_g&?5T{RqDyLy;7TYxO>9qcUFUCf*^B$5I9r&wzHzXp*L-7V0n&7{py%eIm$fjX=i%bvqvv`m%qt|!#YeC9 zg8sRNCR9*81q7l8J(HEv^i18J^Ld}<;WfE$Sz6A&{lTrj`}q9f)UD{|j}|F`cD7I# z{71x&oA;zKF@!hxxYC~G#Y5u-G`i^+mEl3(AOy-X&-I461{o9Xtx96CpM*4@5_C|` z@JxPmc%n3IR(~M(Yw1cVCS%O!)m+o74b)lOiF5x@030bQ+W4b_xmWBCumliDQdU-U zY2ymx&zHTbcaFq=&i;4&-#*+p!vFl>e}3>kKloo9{0|5IhXen^f&bya|8U@cIPgCl z_#Y1Z4+s7qI6(8uxpi^m@-7H8Uvj4(0~9Dzwf3jPc09#f1A&?z6s-EFr<-olfC3pp zZVGOidt)%zxX%g-oFkee_A?Gzx>t7k3`o&cbT#Vo2ouya@b3B$cnxC3rwEvKuI>bFf0REOBWuhf>1>u)m>3)r z(N(u9g2VzfU6I{v0v5lwe`gUYRz@;>;&%4BK={!?`&@x;SjMKfZ~1w*@|qtAG--76 za*p#?-aTVw*-Ize4cJqvK30kmLH_7bJ3^mi01q`C3$Y zEKEY0W&kgJxstVugbY+6b>bo-e(cTwiyvbGulQogVINx^WQ) z2fHPJBz~OF@+^ow?4FnjAqF{?-@V!C5dMordik}d;oF;u zpII_yXtH`<>^OPX=lIM$7oGGkI6vSC4~I7Rl5-Z9;6gz2R?IgJ6aH_NINHQcj#VXnCXlE^yL-Lrj6EFSlyHJxR*0>GKnfxYG$4>5V=MLaL{W6WY=cN{ zeTm;MpTn?YH@5a~#}r&>v%?ff0rX+^ZpQoFGW@DpRKA2i~ z@s!7>w@1gdSnqNA1Oy(Aq+vtf1|Gow=KbJ_VBm%Z{YW#bAwT)b|~|c zJ&m3C&9Mm|ZvV_n(9nMW?z-588XCC6?dumOfD6X@{xPYf{D2Mda{J@HJN47UPV{SE zLeNC*Z+3isN1^H_ekzL(i(+Ja(kZ9oI{!L^^guobd}rmaoAabwryuX?P4Luyx1hT0 zSbcM75zrbZ%+z0;5<8?no#TGJ!0SV~3eLX_IIC+fDK|uXq)}I?eG!Cv2%ke#`MOdH` z9{d}4!FY0u-R9M<&6H(BE_mft--CKVn8i-FCi+ANVZdZdH{x$|dL zw=N?h7K2xEPEVN%^Z-BlYt_LH5>*8+XTREdPwgJ5%sf6LI#{XSFVR@L27{|b(`fkg z6?`268QHAzP(W^)&4~;%JdEsP0>b$34N8odz@vHP;R3|j$%UPJ3stwcyAnFk&yJ5n6avog>nj6`qxo@T zVB^L^2Pt2}f0O-=uP<_w5-}$_ zH&@}Ddr=3`SceKi|BIVD~3j7-WUH>Zd|Y9c@$r@-W+1 zs`Wuu)sd;|GqENefun5Es;jiIF<5ea1?_4<@v-TFK6|*AyRFg>aRhB;fvTGVa>(ai z_PKH~>hpm>(*JMCCiNn{pSX)x*XdCQ1a$Ea>2>r@kcF8FS-RPe+iB29)|CJfGTUT+ljfOs*U#q6-0=d5FMcA{H-pvE(s8 zx-~aDOdlpdWa@0+>c3CdCo42V`fI>?@=ZhG1m$P}9bfp)V()pIhnp5>K5|s2Q`2Zu z?iF7r>fq^4T}R!wZZoZ$n=S^&dN5>rPNh?7?QB5-%l*CY!-pN*kQ|Mqu=&j*=n_HV zX8&hOu{zqAp0%ggN9-_4!%;`Y^@=_zzk`7_`#Np#& z>QEqKgnJ!jeWpwd>9_pPE9f6S3`0=2oeqV$JrS5#ay)8yio9x@{0r<*)`g~#zgvZ z2Ke9SDC>kF2R4%VS?IB zTByTSx7~)D(L!bnx;@zB&!~4yAfUicN3V}+z7hVbXhmyhzfRCaHKEuxgNhC@DDDisbmEKzvy}lX z<1bJL=Jc*7=LUJzdk8au+0t$mSDs|g4w9zQ{WQwI_uABTQ#_-_1xWL@$+C_0CU)J^ z5vFs)p5hH=Zkht49uYc584T}og za`R#`q6<03fIh9e&&YTYR`O8$cvg1Q>Sfo{nWL75%%oB$PTZUea$|Wqp;B^wZV1e*-#+bdLGfsbHXiE&yN7if1S~)SiI4`OvkSrT19g@RXI@qhSOVC_N?-_Yk!jv$WZ69 zoRKl?B9{K=${q$cBF7ueA90q;bSHPiCfZ?-vZ9pNLLQM)X!6XjRBR*oEDNZvbloUAX0JsTQE>aXE7 zESx`!jUK1Z(UhSBbR~TG9-8{1ToW2c>pOCN%}#_94<>4nad1m5LQvC(*JB59fKn3P zvq8<@c0QsKgX*85DZBLl`KpYm(teJLdb~JJ-+qQnzsfFVsyYAWMRlv}`HLD>Ypc(v zxBOo>S_0XswUdgt-vF$>J#}|UA%LtbeB#1f7#7f{VNxrRudoStZ;@YxzuoCZ#Um&K{V4sLjd=AWE# zGD8Al53u1rFSd_80)c)SXxOMG`z&r;0S#hDMiB>8&HlJRqY%FXoE-M~v+gWR#C>O$ zf}5h$Y^}cA`;p_Kk! z8x>tPYdP07ehnx);DSl6dyZP;4!3{+*k=6aJAHpgrR~|8C*x_Zra#j++V?xfc+dA` z+wR^OkU*a~T}(gSKj?|9cI(;UKHpwj91@%JsUkTQKyZUso<*tK1z5kV3)nJL`e4*&DKrd!M`0_eBkE|3ZLH$RZ(*rU zpQ&Nyo@$X@4fMJ;uVJb3_{V|gYrukgIuxL$JHKOZ=#(Bs`1uEtPLTkl zhZ*Wy%svbmAkpBnbh5aGIF;X?DicsiPl;;Yw*6@opx0ZJ5(5$OXxnX{?1_{dLEwag8(TvkZxbH#$Q%!%cpAAnY;Hahh|Yy$_~C zJM3>ZqVhc*ojiPBA5NXFY9V6h>O4C4JL%|B`0bA=E0u+_VAfS(9$pm!(@*XtU1a9j5`^&0E z3&q|v@8|Vbkqai59-1VFrp~+K%|1?~@go_v{Qkzm-7nCxtNv~4Eq<7%kfW}B&!7H3 z1S`aa5ZB0~3T6Ny?;evVBqZ_CoO(%LzLag-3jtUO+*i^{hlZ15JAJoUT=Z_cSNO>_ zFn-ZA@+Z58xWZRmmM*Wa5bbmUdsu*Xew%bglPpbdIYfw5*~d&xO-+`V_=&Df4a9cR z2C(fSN*Q)*(M8FK1~GSbwzi_sP|xKd1v3*9GM^Lidm0)V+(*%tZKI>SrpKohrS?11 zla9k(PMgp2+Vai5EhTFeES19II$<+aoe&QMb=`^h9UI&-rwt_z@t@b%kAG_ z(-rGced>&R(YcPJD#m-!Lf>)1Zs_)MZYb(msp{KCYto#k`$BAFr6ywpaXHfdLjEtn181arweB9J{#w_%dbn{AyKlK^j?EXmK*xe}G zyv)h3%dag^sC*QZFn~I;Ox~!=J5%sJ^i4-7xJgo7Kq8T2>fSEOG7!+qeI0$=crNH2 zy8M)Y+|0unnRJrCGj)nw1hv1&9pGc=MVWf{=0r?MztXnD;j*K62@B~%Qfd38BZNfk zt%LuTzV546&8sg`9LEy-CVzR|oi5~my|(JKJIiJ}BM*a1*6oBYe`N78sR3R49NI9( zcWf@w%<56-=b?UY37PZ0an)n*?dLSjs*lv0X+E}_aqKHf1D}93F=U9OmlwGq$464h zh8MB1ExJan-sC07%@kdsoZJ1ihoQ^Uh*gu>(W;ayTrYB_?2{+{@(LRjAq(aE-KXz9 zwGizS?U|e?P;p(W$H2Pkb>tSl#89t{FQ9sBNP!g%QG_-N-7Ia0_p5oCCyLrA?&NZT zZocVCe{ZZ95!adSNfyjvdQxOaNk^w3oYr#CP0*j7(heN-3h!Y{1+qkv%9Vnnu>$F_ zljMfbn^2X!kwHG9F)eB(US@7qX6{@Y%C2u8-ZPq$Q?P^ABgpJ)_iufFew=-o-X1R; zjWrZFW&OLP3b(oXct>>GC%9+zE-M>16>UnV7WwhfP6i!as^jBjT$zpGEnJy{me^+W ztIn|P&vY@3@QYwF5v1vbG)0GMyFfoi>IrDD1tmBpEh{T~Sd1Uy@(}oBTh2e?^u@SB z6<_e|)-Ih1dY$vp`fWQ!$3`1Z6s1v8Q_H~AJG(TPxm{M-^2hXwU%`ob>Viq6L!_@^3t*@;lXq_dag$rJ9p5 zd>-GHrt^dO50z&<7d3uCOQia?g{i$Li9dI8209API7M9e3KBO{MLzs zn7)pj5^sdzFBLU6)j8VvzBjC{z(I+G^f~W5ItzL)ao|s!mZ#p|`0B<^mjx{n@SBr6 zcJvt;EjG|gjq2ksbH7)dJ?DK$9)4CfMpxSXW__hupp`1*atnnbbfgg=OT_Ivuv(%4 zZ5}bLuHADyKfJxVw#F?W5htG$B%gy1F1p@?yC}bSkp(Tz8M4aMtNidu)*k%Vvm{7soS8$mH0`*O=xBZdLgZ zXOud{aRK^x5IJJf$m*T8-$D?*CMV;(v*SfxM18xy!e}7pFtK^ud;fY&{XFzk?4YHv zReve;a_vn5AvHo7u%N8Yy<2NHM_C#3;m5PyJ$+Uc`jh2ey#9OZIn^txDS%5=JC-&y z#J0D$|EB4YH}T3DYPy&eRY?<$IXm+jrH1CSonq8TcobC`KsZwC7t?I@NH75Xv64Ila8hF0eE+3bjTQQnnGwqx(&at}Wq zLQbgHK0c=johu9?axo7Y?(-|QIC;_N`yzBdxH;ya<rS}&jweW!o+jouddYvHkXoL{wERSyo4yZikmZf`+NfEk7F6FmXucw%A+^oOL%^W=V`dGnrT-*OA_oL2ZI#37n=!+O^7n(l(Kh8XGW3J$lSRR_lXGUa1A@-ee_F=Z5hcC;Xls zrSCrrrJm(IVAhzdJlZ6@CdJPDinH+RDJ@Y}VeD-)p3xH881Y#>)fRs!;%krF(EOC% zj!nKqHnDwZC;LE~a+$6waoF;>GTCuJ26a6zm+SSc@Ey8JtiYp?g(?img(fdz(no*= zvY*`g2h-vwTb#>p00D4hLjBXz?t}A&$C2oW4$vF(R5~)As zhI9n2vqicI<1h8EyRAxm54?AcrYL$xQWN!!cXLwJT0B(o(N}?a10L%ws-q z(QqoGsdVjv6S}p;tWz$6qTWrlsai3)=2x6RcV_i?C$!cAI_sI(p88JbS?sk(E_+@dcB-K zSYUpRYxSo_ZpM3WyrTm=($i2WQ-4DJd?N5K%lV+1XmK%_=FwE7Sz29x8yuLRC{3qT z`np(>6x&r8QtdcY5O*RwvR{2aG0Vj3S}05Ao4%%2sNKwa*O>)%I_eIWp}2RZ~8LiG~jf8)0fne%w^iHW}SH zhh|w_Ne=5JMsorazu2k7!4d@|v}E3mJfz*=<4QH}H@#UIGU5YQ6B~vBTYGym-nL6= zsA|cK8^|pZz1{!r=ES#Z)|FwpkZD|>{kJp0yRXrMp0m&Pb=LP$gB~3-0?V!av&? zqxX$}wUy_TF^3k&%&Z%Yn>1!~QX&bPowN{Jmu|GVKIeLCWqv_!)_Y!&bmKuA%_k0N zRAla*G&}^L@g-^+((}n%Zmyv55T57>k_?vze~Z$vyqoSssuWTZ>E*%1X3GRE`B zlj9W1=YSJ^9@HecliXS#TBFA6%`nrYO&nM&-5n@%eX)YlE%@1tGiYD&A;E%?5r0G@ zUX7zgDhp&>#LC43rMK<>&gFh9{?V!s#qrf(b7m(wrM}FzDe1t*Na#OEkO%0E=y_DsujAbOeX%$ ziVsz9oL}emKMK;IT@X`qCYPEfL@3C?2>xv`Z1r?AkT9ZXeFe@Pr)F(9^1^ zC0C&rQ?J65BKKS+YYxcj8<}I)QlxTxn{Kvq-bd|T3;0cw_uh6)pB$8UgfbZz+|TWU z3fj@WG%=tf7|+l&Zsd23Sg&#;XUbV9chW()pX1}?rbtVjF>KD4KgZ;<->~smyM^%H z5AnWWI=}mjk`rPZo!L9dl|;8d3f$U+(|Q5NBi`u^*+# z6->QNRWz3F$yypHuLc=#K1I$2OtLAhx5yFpqPI53tSdZ9mjoxB$F#m{=3n^`Oz#6b z4_+DTV_+@MJ76({OmljyKnY=|evm=w6N&uH@&S@zI&G7*MD<$nQJ(8O-{rHyrJ>`h zv*gH@BfmmaL(M&uKTfEP-iNJnj}?xO~HD}!z z`?LTZ-07jUUq<(>vjXJ8FNfEWqm3`17m>6=x}z7b4~<_o5&n+JpiI>$O^?j5;D+9j zfc+YJkU6fw(@VCddlQaVPtE=!<+6UVk>tYOi}iLJ*7?j_-2(`SXR<1}0Agc9fg! zt*^}|h8H%FTmgU&mE#s;1}@gQB}AXrBraa(wqB(Wt?J5$A#U7TR_E4#{(W>LJg(iN zsQ7G|=RO|kydbgmgf=%XZ-@r7YIbd9m~}2si5W+m)}R2NC<{`h>22frkH|=sx)@j1 zn2jHzOdZT6W}PbE^CMrEy{mYRQ|L~Z78_#A6tgWS%t#I*?JkOn+bluehTN|Gnpyq? zFO^U~g~hxcmz*8q&Rre_O*Emw3qD?KTxWscJ?+lWRG%Ccm~hT64!ybqIUbOcvE8XU z;M$G-{PG=sdEp38bW+A(W|OnTsp^w_w`TGR7`{=LN_kRiyE(l zSzh6coQV!^@M+3Pv3_b9FVxAIvNiRC!F|%oEC(LMzY~I>gji`u)oYnXg^iL-mM`BW z0$FTHYX0Y3Qg|sZU-(A?|MGk0nGXA3-y;bN(5<_VGY=OBZ8APG%xoGiNH(0z&ftdZ zEnW|s)C>C;wX;1goxqY@=vc_|-e7pbG7D>#|I6);|BGC`oqK>rWzw527Oqtn{W>Ss zmMJ6}F_|cf4{)HVpTP&#XW2Nbmj)B)=eaKxb6*10dgrm7zRv?MVaVJ0BX6;Tw_m=Q znY&_Vvt;WPws0h=b0j&Thy+9n1{Ui(0*8q?n>fU?TdN<9(nx%5ZQvNiBv~1rwmkTd z=G+5>wb&?+M3L;OVJ|KPrBATD=f1;X(7oETK+GjcBOB4xKo!&zf@l%5>6Nre1gRn@ z*C^H@R$n1Zpg+oC%!~x`m+RsF%LGPwOPN#l439CFzT6V}Ec^19Y*3jAOP&0|GkBmo z>n8%eHR{M)t4@6f_G&l9c;UgjeJ86LnlCZ8RMLe*Yifjg`}!76_m>2{HpvsU6P*qx zxqJKj7M6c#l=N5tPH4ap{@jA7@Ach+0t-GWqG}b~vmZaAj$ctU7UXc%Na4vXqVnu6X~BsjYK0xDzMhLf+P2q)rx}0#k{Sq}odL1o_F>8t=Z%EOWsh1c2lNBC=&QK6Wg*C-T#%3oP zHcn16*RKxX70fpzD<+8D(3MrEr#uDOa~TRIzsBll;Di(6@!_Rnt}N@Rx6PE+4_>NG zRK7N+A33R|0~kv74U81Oh8H(g^PXSFo#8y?p}70H-u(A<(&y6xLXS%00Phei>A$q9 zHkW4n{T$CMNweGJyFps$*g|xy>b8P6~372=r7K5Px^E>gw=jG)E*rKk!e#kuT zRmBli!uEUeQ_N%_&wl}X+mK*O34_Rw-+ozA;(3k^E}5xj=G!?igmlC9OR%KDbe?UZ73?sQv{?nTbgK@XIQQJ_4Ftly8kN=$Q}m(g~Y?1^AT|0o(wX78TM_9y5ZPG-B&H#N$L9?aSZZba7*L#muj^g4gkRjzjWqg z|II`Bj6TE(c8pN&!l97t9o)mmwzAXDbhaj!VQ) zSTe+Texmp&_(I+OYPePcoO;CcFSgMBx7wa3Pt-Iix@0l4=_Sb?;RO#8cH>-2;7N*S zAX98GK0dpD_T%x*YByX7TwGj|Q!)^aRrPv>i-$in1f7@hh{fFSZV*WiDqS!Zyd(%R zzzYVcM_k=$nDH&1*!nK8`F$*(6dOZ`J$z_Leb#%Xa9t3>5*ZA9*`95HbhVZ2d|2zx z$Dv-G_VY?0_LN8o*COY~Z7%bY4l3<($P3^hQN|s}y7Z$3IBX$`*KcgEAs}x(!*u8> zL-cv^24Vivw;rv`!;WUj8DU}HHPP5J6N=*`emFPXz1lxCa3$t%-KHMROhPNonilqL zg^OpiBJ$C*VAvvVk$*%%K5PCMy&#gmcVy#`*E-q5QkR%cIJ)M{i;dmO#H(&3Y)R13 za3X5sat92a!+Hiwb8F6s`J9{z>``Zh&$02$u^oUhjx@L*8BP3Pv3hopU>0LvUz+&4 zcfpq^R(}}<6H69GVv5om3gfVc`5N_@qT{KQOFdAZCKBGw`kds)PN|VKaIE1)i4N}3 zX2(Yp4b9hC7YiRG)SzefGkuGld+nu?YfRg>48y@EB zW%{q$&Ka_nR$&_2aDA`r`N{0rN3~b_A&hd@l!ib^DJ#MmqY`Cc(9Z2yn(h_nZ5NN$ z0|nYM@pSLa$87BESyQ&zbHt%5(gJMY`tP%H#YkG(cl!sfoTNGl^z&{sjaeMet@t)6 z@2kVGqz%C%XODj$yr(+CDaq&AuB)Gag?>q!s}Bn>FVQxaycKFxM+|o#^vW zwVwJ1Iprf6?q~I}EwSqj)lT$ybA18oL7Iq^bt9DzAaua(u!Zsc2SM(=22p2KtlO$> z0zFa4VRi45J)y)!5x0b^2p9H0oRjJw=j2XIOdN8j0jh4$9)G_fxKO)?n)Bq*U3{9! z0MJJk49Q{(T7e!i`=sKZKQqS;_`5{Xh-m`qW^F#87pmz!^;hT06fQGblQ0ga*TwvY zp#@_A=wz-q>lzx$F~v)jO|`7{rDU>#ujjiLC)|u})+5!v7mB5ZmyQv_qHx_NISGQ- zgK4b;Ebj;{mz5OW7a|`OzDrbJ7)fK7buwq~uMW9AfyVJ^AAvo_UC2dBuQZsJeFmzs*4C8KQQrngTJ9kHKO5VJ5`VK<=fc^ zo4ajKJ#{jjuq)n^o+lq(*KF0U7k)dzoyV(PfktqIeOV7V*@lyV3?|yo&xNfksPuOD zsbZMMx3&N}_g>?1^!HYhih9!3R)Xy{G;W~3ez+kXrgH(s+u`w#w;9$12JP;La&sDR z_`gyxQ6=TG2}lZeG92XL^fwH@oSqko$`}t)**kA1*%L`wYLsXLfHJ@DaB>+zq4ITe@|{l7A}jv%#GqiXyN3fA z_8~DnMJu8R8;N$^IV!_0xj>mRM2BYVcP7ZH&ycHG5(D*Yt(e_ko0Y4dbc|Ak;| zh;{*vI@yDFWZf$~R7c)OfA^Yb*@r^CKg0`QRMfW!zdzv*0OEl>+M0o2m~$X2i#=w1-hixT6b!3|WQn zp3nBTpVm2GvGNbOz-?wz+Q)z>V#-gGR1N0%{5K2m`Lco%RmUoQO&qugcAJ!-C~xQs zC#Mv6+p|&sw0vwBPGHy6&_otb^T8e!FZ}tdt!g zD=iI!D)4-g=6PUd?Mya-oWTV*#UcE_zowGoxibm|$7`N4wd z+$y3&a5LJrx7l95e(jCxM{NIr5WbKRJZSjz1i3ah-q$||rQelzb`cxuRv22DpDlpv!Ti9nGO#aPs;S$`6z z#oK>vU9X=-T53SK_d^pTCCL=uY+Vy=T@lQj?n_1@alr)$au}clJL*8Nl?Rsn#C`+e zdKhB;#jm%mE{$yP&H!Rr8JFT{c;Q!%lU&1Gjt00}6>eY6@7JV;0i_s?|2Y?c zRg8~=+H)U?p6)St?q!AVjb^nbe-;Y)@Zk#kyoPs;oN~!Or~cmanARN!2v_BK*%P6r z$t8giiGrLG_R)upoXNfzAgiH?%?$M+|0g6%MaKQ@Y(FG>8}XA*p0L0keZx85NsV*vgQ~CG=R(h`Ul+4y4Kf z^kz#KXdr$sEY8s`IMQ1toe!PLCY^h5(z*xl%3S9kK;!Qzt>CRJN5G%rt>R>%^#Yd! zzmMnZLSIRFjmZ~khb##ur=*0i_2?St$>&V9XoSZt{*VcGTpWGO#>N3HALtYP(NaC+ zkPu*`uyKzwlb_^C3G!Il5rzAlGkW|=kYs6mP}>tImT6w6Aaslyh46->GKSQ>E%-nJ zyAivwDc7QuA5)C9%}B5+h>6Er`{KR>nn2(g2E{7ksBxiT&G#YxmiqV~4Y&yV9~Sp7 zoxY3LH7d>lDC(50iJcwMkvx|BR2Z;UzAr#o1^fZYBRM03#4d#}i^xTmNe6UWIqBqE z|DE2F!(H+(W*eN}>OPo&Ilm$+;R>U7SRxlC@}lG5%X%O)L*naWEtrgG)Ls++Q!w`S^4M`;btT`Z= zt1Xi=C0jNIa8qg4M`rDnfOZWiQ$Sh-if8LFR-O&z_ii3D3s>e*GcRCu3xd)p_6B$_ z;p}g?7qW8wM;45k@SDLbeCf$20@g8tkNEeqGk#BO5&bMIeDLYHiK*>vV8*VFG2=dn zyfLq}x}C720)0?&f_{NwAb2j|^`N?f?PPj=8ux(9es9h2^@^e(^ddjDPyqyx9AVG~`iKfwopn%U71{7x2AV0Q*f z{kcIci395)>K-!1OHFR!*7f_r;w=_iVoawcIjKoI_HM2sqKal27xrnoRR$urof8xb zj0rEdub3okcAWcuZbl4#5id8=NAXU;q(RS_Jr)QxFuLCHx13D;$9}}HfS&L7@hws^ zvSn8)1_lP8_yXo%j**BsU~WJLavz`QlTVhHfC!kBp!+gJRBS(R!Dc zcG@Z#)tKFS)!pI37CPf8$#Nq!uf+a0|KjTIP7ElpnAppFL}-%j&bBt}j*bp49$`#% za&H%wbo-_qL$V7HBoORg=l8}dV5UCc15Q>~;$T3a2k7zJ`D19(oSS-~cQfknkV&HH zB;5l@3ZVBubJb^UeC?tpHSR28ny{mf!P+6J{*(eTxovd)9dqe501x8t!!Pe~`f~Wc zjN@zU!=)g12Z|`Shg8w}%;?~QxGfe~Dd&YfMn~Gv{LGgRCiRY7w>f9|D4oIA@v$wC z!k{gmUx0c@)UvOhc?kW-P5b||jtn3%A9-V$nVG$}xF1XpC{fu%R+1BLjAZYAixLJl zc#4#((h6vByybk$QP-?frOttuC8Mx_%oDLk@`EKiZ(0~;Zgv!DD!3|nJ2=~<^DXUD zWtQ_Tq51jMuh&!Kl9KvITTJFP)m;``kfC1Pp(c=wWf6n2mN~ZRXrpaB zRt0Q7+4vl=%yy06%qb16ME|o_S&7~c`p?QuZUzzA*v~$e0L^%1rYK)=5~)M#xw$@P zX2I`eJ#O{*pP(Z3;L321flKtU0us}EK|neVDcDR}*1=bS8_;KTi^?IC9fu z)%vRO__s5ej*;Jn-rD%D=oTm^+xXQ(5_G$N&V>micjj^^-}; zWEb+lcUjC&HEe(Uv<3{o!o%~Se|>~QHn!r)@0w3YWibl139}h*%DORY=|qd~n-Kv6 zYM|Y)hB|*rxCq{8V-;y{jt>Io+A`}z7u<}I3H+*qYAtrFbL+z!Fejstpl)@0-Wo&It_L1?(y$$1#=WyLh zDS?`xE&KpEVpk$Em*y%Eu@N#j=Yy5aDD_-XS6BCK>caGF#=}X@&pry|5 z(9Hm7@j|GFkFUyz(QZ(s8S5UFxn+UA0;v!hv%u0Rhxmc8mIJigR98ea}h>a@vM-Cwz_W@YTha*cS2PH}+Z|xsJUaIPYr+ zN3Wep1OVB1RZTaY$e+z0s<087Wh`9&ju4Eo|5S-Xwx?fiDx$BcvSm|kzklP=bYd8Q zEA7kx=?uDMa7eN%E68?Ig#WGA5G3trG!eAq`Ql*r#F#-$alTHfhVdED^&fPD)QX2~ z9RtNEn#A~|Xb#ZNz~oxZ$wg+u5;*FlS#PKq)i=fBwlE2m2;p_4vIcHrTEC$!<2CLM zw8uRcT%rqpya22edVX@W(T@E&`!;29RYr=`uCJTLmLzy@(b6>`QVP#bjG{0Zn4wYk zRx(l)iwy$$jmst%Db4q4++2S*|9F#mD6+rcv0+9Xz6jWqe0Tmq){Q8U#PA>McnRnR zUGaIqEY^^Hg}0DHu3jh$o)v$}WP_iGta|X^%mb2OB>nA^Q0asD+AB0Z>{~UkzV2u1 zwXwjY_~I9v6XS_pdKP5b(@h(IeC54_PI5&2Hs^&sP1?QXo%0G8r1*}pXbQIV(brxq z1?B)K)FlDa5{!o;!rLMjl76^q-syD0K!@__RZv!3ehGroIurLy;wLW;fxe8?IkW3z zkB|8A{J>;QqC$KLg4dJs`x!UR_)znGFlex7ptUlL4){g!^b4;9@!$V| zGwdI5x|C=aK1h4c@Tf;IZ{)oOl%WQgo_W**s9?WiV$Z|v+-H{ej(_7|#4d%d#4a_3 z&WJ3R&F}%gq6kE=fw2`oMwkOLAp1_+b5&pggfF4{?ktX6m-l_o6XPK@(_OpIJ{z6@ zZxc?Ff0w_;)XoBaQgrWVHXKsjMWAV%;e;vNx9NX{S`1S?Tf6#P8`Ade?|wBsQ)u-P^z*td41O>plt&1697+|fPSFU z_Nh}f2ba)O{KpSMrJa}s2k+W*F1s6^#<(0Z8P;mBb-e{AB2mn`?mN>sa_S|}f}<8^ zPEo+ypvJ_RdPmZ8&R!INUXjfL;-Dvh8{uGkCiN7oz?*7?c_J^Cmmi_GBaJ3}f+{MQ zS|>LJy5qw5o0+9a@WNLR8pZ}l#I+PfsG-#QPnba5a6vG=A^H*!Me+KoQa=VYOgU|x z&SOWN$>DUUw$YJMbzXeOM33zEIWIM81!-=-XkNND2-tLsoV(%*^BM;)0IkAwZ`wn4UhZi$0!63x?xRlnXss z)x(x*>W9p5jw#@RN>*W{wWlP)(KGe$r+qbdUR3GkStRTpNIUGn&frp+t2wOESXpW! zL_iC1u*T7@9A;SkpxPGlA!w-K#7Pt%?Kd_(2sds%JWqxHePCf_`ZWokWzl#4WR zV1To&ULUD4W=#b6OqV&?uhh2jg5q1)7)6bByMn~`?tw8pU3h`%0vYL#rs>E<7Jnrq z&JtdR+-6lzl+lp-B;+l8L2_33Eu2;hDv9#ruE7zQ9AGSm|^_;fQyJ0bZtjoHgN{@XP zVSSYgmodc*z1h8Z6u^1OM+Y3uFnrMz1y3+)~oEVF#R1+(Wt(Zh8D;@G2} z=)FSMKU`?x|70FuPJ90J-QDE$^p1($Mmkl|ee7{+JH8b5=;&yAfiGAf!J?>|npZz3 zCO&kTX97v&Suj0zcxYsHgeGgujWbUa&8d;&FhpX?bsc}1zclgkD4S(4w(cgZs)!9S z@08kxMis-YB+2FQf+Ljq3ANNi*1&SVpWQFirUngex|RSxw1`449C6dB8{6(nuLtk` ze@uM`Jk{U-zZRvUL88zgE29uux2WvBcZ$sHJ?>4CB%3Sq+FUZSxwzpYdyi}Hy)LeO zhyPK1e~*6;b#;w<&-=X2>-Bs+pU-pN{+*3>D|~zI=(k%4mzzSK5bJlfZdbAo!@kyQ zrjQ@~tj%$?c$aZ-mGSp@&$E%ZzzOt$E#n^QEyMJ+*VTLs5p*#5fGu^+o4moXn)K)7 zj$LF{35zZ?N#$F2lSkfrM3Ee4?f>Eo;s4=`i@Da;L#0j>qz!&VV~cuLkJXdS{^|R` zUVDmcrCA1B8!dOPxVV_?13?sv^mL%^x!wFRk+v zTyVuXoJabcd^z(QCQTCqY{1C0qnCSt*nzO>&{fK|7}F@*UHug<*&)cSvy+2A#zddd zY%Unoe}w^!vY;n3z$L_eOj+?A?v>H29tjCR)or)6}#{nmDVe*=^}IRYm2PmL`+YcN6jb*TGPjIxjCg zeZRw7W%+$lyfP=dAvRz}K4nUR5K1gCs;ispxIG>e%RS@Q2mb~)eRk5#v$mQo(_#Qp-75B=2$+@1`87srmZSw>; znaMFOce6}wM$2d;oR>)>ub)2t_MZ0pq_$VEBkuL4(^i{^oZFG_5uip2HlaLFNgy(? ze=<4)q-tNB&g8{i>Dt7=7iqGWWfZtL< zYN_VA-?chULBwiZ6cQSAaC*xa|CnCjbM?mg>Oqg+=<3GhJ3Y%b2S#)^Vu0Fp<>l3o z**7K*r})j^spM()Y&fg%6o7uQ&c*OsaIndnYIMGj18x4+==}b2;c+nCtN2h3_VJm3 zroiq*DRf*ZyEL1&B=_c@&W`3&S0lQ|L1(JRS3f>i%vlR@;|G<>>9_KS&G0`F~^7%DwO?RXVRIjnbq3SXjSdQ<3# z8;2e+5##NDY#gQfo$B;z{b22;r=U0TB?=lty0_T3kCcfOi*_BZ2Fk8(P-*PWp z=8dCOE1q%6Gm?h~IMU8GIRHLo=s@@}vj4ZT>!}}B*Y8fEF-% zvH65FA-u>=WTtEgLV%rX9^Ji9(D|S_FL_I%J+~+NF|&NHOl)m`ue2KxLR}q<2tjB+ zGP(})*}}LCA($pO%c&CCbSPdk!e^-;{(%zm|6{&h7F7!eY+Ie9It%o-VVfKFHP0A$ zKqPism8le9KvNs0)Myvr#_yoNT_&wX_9gy_M={3eQ@@@Q1?>Uu{?HB#^&`7X5pspST~` z@l1CQivWboY~>TMpx%zn<}+eAJGubL{bjmSns>j4?1Vj8L*KqsotGx{(N>UTm0Tb@ znRS2@k%Rr*qLJSU7WsDE?k9PI2cb0oYNjDeu;=B)cZ*;E)93F29Mn*_lnbn1mAHQ5U=j@es=ju7dkafW3%22XG{}iG(*vm_Q4?$ zg4yO^{B4+GPZ*{A7BBVOb5j2aIx~4^WbxrWBNIV9=okRK@VaM)Tnnm4 z9d}Q;U*ns&4Vmw)sj;6D3wAW0jsIhA?EPoTcMca03DWXm4Bq9uP1o(r`0*yobpC3p zT3+(7O-j$s>AoHE>+J7AH1=30Hi2O|2MyAb<;k%+%4Daqs}Np!=u{f~&ToAAt!(6G z$6?Cb($CWPr;%;#C#lVHP{(E2k%lc5D6^&KgU z`=*;|hhdbnN!=TV^z^@dEy8TM&rdG7CYIWIFbx;|EprN#3i)5bw zK!>j;tV`9NgXFVX)%>n#$Z5UQeq3JNmj|jveHyE<^m()38f7!eSAhgX57Bw!>Y*l_{5h$&PX$o7GYdVxaep8 zDV1CHyB|ilAlJ%f)j&u0xu=;~LnT}oh&Z_G*Dao`T$y^~DMEcplJ}R}H1MB>xMp3Z zQmDlb z7)ffbT3|(@=y^R-?N(@LD}Fbv5LT#b3srbIeYh3L)mXmDUTtx3JLr&Yg@5Fc&@pJH zaknVePP$9yt$!P)s+vQXM9Edpf}U?^=;k%Y$Gs1Xb2U_qjVaEaT3r=P@8jst(fmbQ zT_9oh$XRA-M_`4khrBp<)!wDXO~#_UkTJ=ceqre6+c1_3pplGkc@~uldkOrIJzEH= zh-)|dN-MG|g$W-<3GlD=PhhF@cuq<$LLj_rnVtA)A4PYvVOMd<>3j`0Zj_S}^|4S7 zpD4Cgey+}as{rsKS1-5XsgDI91@$DA_PZ&NFUJAkGE%N7H9x&JR~n6fD){s#671C0Ny@J&_CFCV8EX(;U?8q3~;?MAMZ zm$+l3OpVX>YXFkQt{W;aSMWUIb#uTZI_#`S60r%BVzw zpAUT=1#et>6N}J%U2SFm6ZK?L|2%iiPjoapkWQuTsA7ko`k zj=gp63QT6Hn*EJK7n4T$dtft3Ck`Ic*iTf#`2(m-nh3WaXla2aiCs=0!Nss#2oup_ z`qO81fbMAP(m0X12yOqM~17hP;iNyMc+{w7MWCw^MfT=QvEUgo2$bFC=7 zm$p-N=Q|HnCxGbXv%X$CR(%i;%2u#t3{290>-T}7~i)7bZKd6 zSEhnX*mHW(gCF7SDPNNvCIsDxyH^m$-akS@-uR3@X&?8-6-%%Pq^#j##vZ1eUDD}REyvgMbTjZ5b@&}kNoBAD|lV1U>sQ69Y4@qetnehtqKwkuG&8++) zqN+kqeV9S4gvZj6o$2Eo{K@i7`_*wzJt5&^FO2?DeW}pgto~v_YeU?vYhl!uh5Jli zhD;fu322x6^|my7{GrsJZI_-K|663I!RCO5fY4_r+E{qh{6wovP0z2H-g{JxBHxPM zpLi{e3hpP$UG}LhW10R2ld*8me~HwZ&Q!bEF+bJ%*eYiv9t(XE@aYN7Il!O8BUPj| zuwg2gwj;v|AazTl20mXraksIg%j2{IXC^^51hQM+;ensCA{>Me;$C$o;`iP}qKt2Wnu2a{-m7%6)iOb&adj%EUOW!lE7jeQ;5u6zqHH>&!E zI+EP@{$qlmLCCMzec@eb2UYXkIy%U6TAd1mU0RaZBT{}d{syy|gTk`w4>E9*;8e^n zUy}aEn8wHes=w!L6A)z2K7Ym&BL!e;1r>0b16PCwr$xEm&<+vX@Dxg@&ck`Q2ji-8 zBvmx~wY9>YI-V^Z*40o>`sBEFQ|%Y9w&u@*Zp9Gx>Oo}7okZEUK=!$Re*zxJMdq~F zIo-mB_%D{9|NHlw(om~w!|fhr(n-0WK!dIG(xkk6{0&sy*CCfVHQ@B076tmG|1sE? zu%JEA93{U+^g}HSstGg?PDDvBW73>B7R)t=VEjWgcLO8NvNPOXn()+%3Q)ok zK(=Dx%Ut~~E)c-${9vYk+OL z!^=+MRw`mvZNsU{<`I1fd&Jv%xxw0{dY zdFI2wtCRB^$!<$GI_h4(KHJvz1e0$#N`gA@Zo5E+i3#Jyss#N z2uF@Zi(eG>3LpgFA?h;&9P>7ztSRWIZ32A};!$*MHy&zkgoq-BL?0(zH_wW~FTUla z?0}A`iFC|?(}I3k-9I^JmnF;DsdDcMVS5u&}(# zr6s+W_pUZxzwllM{XFHh3f!zT*MI;G{`QTXfqtxo6e&Y7^4xx5RW?KUy|Tt4n`CRv z4@L{~+60Xa%;==KU6CoeU9fIEYVD$d{Bt*dQ%Do7nlvlEzH_#{DUy?*2*wE~-4Q`^ z%{_HVA|`O)G2&I75HsW^BepeqP5NO50==E?KJz1LO-Ley0bUq|_LI_?Zk*j#g65>YKB22j)p;x_|r0m z_t=V9O4N|-H-b2?1zTEJ$bg8vIA8SUor07U{8B@f3VV7_&!gB(B!77l$=$Z$`gQmk zKb@boTi2m({*__ksDiRYqD0exFG;7+`jo}qDtyg&?Lt-LIQ3|oIKIK&4dEFx!I~cQ z7@erGkv0KC42SB-8IRrinst=l;xj*F2#)I`(=j}I^6={dpYg*M%hEZ1ZxDrPZ_^$d z7%q0alkd=y4^Whsmb%+GyG3iHC{k3x;+#=+gKb#JFY(P!YgvorQb&8Jv!|YUk_Vh& zx9ZK$?{UGIAAOTqq%!;?>Zc1i2foT(WF5#6yiBcIq~O$u@lJg_DZ^P~>0mXMsEKlV zhv|3ULuIbX8(g2sKZh7TE=(^Kx0`Z?v_t!%h!@ANFC2p8$GiG;&qAdVy{mKWXeP=L zw!&zi)x|9K=ubjClc)l*$EEpT=3ok!FM_cI{!NDoWTl>lp<>(3j$M_OaqEmJoij1F z*C)}+(h>JLW7;CppWWfx++~2G9}FZ37w8QBLgFT>Zpg|B=yO2_U!~pc6VT-0Z7zBU zRuui`yV4Ppi`wio5wj%_WAM;rZjqf;?jx8kJ?iTOjj_JE^!D!XVtK>bTE~K8jK`in zyw}`iMR(gvvWR!%)5I{0-z>{86lTHcrpdO{2_26hu54VutqHa7p#>^JeFoKzJSLvI zA6>)F2GV6l;SVU)XTv+o7s?<@qKTFFIPh_)Yvtl0wIJJ*{h<7K@-TJQ;~-pG@X^z| zh%PqtWI;-b>rk}@MvX&T!$?OZcer>ad-@TGx69b}ebGbMjUMkvy~tPEo`5 z>pHJ&3$(_qA`v=GslJ$%p;0mF6}S}fPQyoh4U9q<`gi?YPgl#cg4!y5{s|(iq?o1O z;kIDBBKU(;%gZ)EwwfPkaC-12MzOF)`p8Sx)Z^^&m#bFvQkmo>8MS>{=K7<+8F}~U z)mRw9yD+5opB5-))@v86%T!eETv2IrFl~IpAWOx51dZ6n8(x%DeoxUg9RF~bt_&-? zr>~{`JpoJxD?M<1^HPJv@E$%LOXbintRg_AvNc)%1{ z2yj|ATTu)ud2M^w>O{>7JL)NxCcs~5eHX#%U$crMx^Rcwf2xGapWmFGuY$WPcU8{r zNOXi-#&O;V+Qt(p14doAcVDUdK2xcCEi(XqSWmO=nFVsDOVlKdEB zR(k0Wk2VQK%|Cfhjzm)q`8x#Py>&=-efzgd4d7B*C@1nJIo+0?chvQdr3W(GUE5KEEENOiBS zd0#w{&BYL$qnDRsRA6muYqa}HDk4R36?1&nEz_8!!gd}@S!alDoO5#vF-Kc+xGA#D zb$Z`Jj@>dhz>uSEe0YbpMQ)~SaBLEMlY7mbmA|t=#WQw>$D4`}f@bL6`**12mKVYJ z%qQYBrqL7%iOS%;Mf-HLiZ8@s9%#Co&g;>EDI(1M3&89i8!PODPn*1C+Rvq#nGU69 zL!_1_kG4hvLc7wyDBo$zTO5H#<(oZgt*vHpc32sUDj7`6Z_HE6TcYoBKPh1)bf0)$ z5mM}5?0PCr+v|kPg4~|dW5Y|sNH3dz5U2dYH6UY*x62v&A!8Q8X9htt@|lw!A;(rl zr`}+Lk+(?69b|>PFj2jy2L|;>XO>#q6s=mkq9o zES0iyT-oHhM%A{6;|^F1ekIC6eU<=Kv-!cU^X{5x1DNEZ``j-mRmtu>x%8`tkU>YIb=xiZ7+J3)}~Oe zV0VHWVwM*gVp=rZ4CTxBZqdForw#lBR#{+$sSLo4DJpoK8ZFEiA>p)d@@?r6&m+rR zw=@>y0O>ydzWg3*{^p3FZ_?zzg(@6{WRdYo&fChCDB=vjOI{I0ysKhL)jR`2CP|0* z^flx4Bo<|YoLr@wmqIE+b5-<#>>-{)Ik9cFe?X{nNhqJ2v&bj32wSe<*>IVY*mBv= z_+;{$XzNaJhW$rDeeU&Plys!-es0T4Xt)<;V8L`fx{;?Ewnnf z5}RVzWrukk&aFM?ASQHbxI?vN_6nSpL$iPz0y>HwgqY-~kfaWY6Qvx($~v6hlU_w) zTkTPl`)&x-x)&_fWAY`ZIG$Xy(<6)EWfy+vrtL1ld@^X}zk|N^EmV1_Y}8Jj@218* zCd{xoA|rh6%S_;>!5_N0E~{!FEmEG78bQMlGg}8>vNJo)=~ngNnVojs);p|*$mM0% zNAf763{e)e2jMYsDICM){%uoC@W})I8<8eADak*6rKZjW`N!1sh3~Ux8NDClI^ci` zYQ1RIc&~@n7<<8Cv3DcJr8IVq`dl=G@6IohoBXnic%6F}u?;eEJVtoSRG=NP7UQOz zY7P}eN=}I0+4m04aB_1-c**eg!>SjV4q=w4d(=i*&BrL)DJPIw?Fs*a*q3)IW)h3h zHBUmyu%v1gBkhH=E!bK5z9IQUbK$e>S1vV&fo$0;=u+D+Kd~*O$(*~?T&cJ&k|*wx z6c4McMRKvqUc3k`)q~%g{xY*g;#gUpLF#=U9&%aho|fW__AGEIDJ)EO7XzEAGC%_d z{vEE=)oeAB?FDU5PHEgLY0QriA4iIr4LSIln`p}kZgIpoTWM@lc%5E#2L%Hb+gelR zX$2R~f_1CqQA;!m5blj?x_w7O>BBx9PQ$X;m{w zN;NMgcdMDebh6#}H=V#@`SQN1_)fPJsC)yf02ETUF`sX?ETuVrmSz*LSs=vH(48Vh zK^s!iH>Q=0tkTtTky0(iwOS?iM5*=Wn?F73TxFd9&AaMZAX%sJ({!mhoKzLl#B_0~ zhS_Iz=Du`9+T~SDn*fSVBVWHFnmA^*rfF@FFUSJeaI$(vI7Y6t*M>ALM z!Hf@fH@yP(*1^Tk{J1T`N7ejD)W^y^M+{e&?uZ`0@Vj_YFxo3(tW!x$PtdX&=E>P8qT9eL15Yy$_uliAPwo9&kH zWlMlQjq9F0%e3Su(eb;sS)SG7BY~F7h)C`ELh1jp{%7*aTeE>KuH4q)_Zu412tz>U7Kv4n^GnQ|Eq z8~FMyo@m+$Xt1|utL1?bYn5UEpTrtRdqqvsX>4SycZ=d;O);s;_>BBz?8Kza*j;=u zyf+@Ts<%exq8#EiSSr>Fd$?r{dRpbgYu2LFN2$!O8KkRMfF8By-nM`VxRKQ_9eP~-l@U9giGO? z8Z1i%#7vO}Jh^JQTsJ9m43HKbaixy8rBm#6kQ#CWdWJY$qo)3qxSB>aPiwXvB|CdX zQ`CxvC;mVD4d~vb@B4%0rX(>AFMVa$p)srGfyOb5#}SyP7yNdLoIV>LEFBu~g)FQ} zip$(W2APY;9T^en0d^b2WDvu`^nYC@nb?N<9FTeMeVZpi$taZUa}h*AqwiS1?=DT@OiQ|0G~7sBJ)%=VaDA#>xFNl;Z- zGLLL*Ze)=$1`=F5SH$dXENW|zCB#gR8RNd2==EL|ExLPP^#+X8-uoYH=&3zJVHTHZ zRT_8iXBZ((%}HLdR8jDpGPPWq+Q5&T(utmW4zmscb7!~NjXmc>HJw`5Ev_-DX7qkd zv!hI{fT09CpK*}~jtP4`Bu%e0r&m(8laUxdi*Ju^~>}yqy*?HEv_ncA5E=w)vZr z5~ED@FDI=hjc^}-QRa_Ro$D|B+<80Vs$hB{4Pzj?x0TL-j;3Z>>dzik#oLKdrN1Md zSUi2`79@6zW-UFllTpz076%tM3~fjW`v^q?z9!Q=v$U}A&eM>u8L1oSW9U8)uK zaV%kRc_&YQp5Hr1i<7cEjx$c~;_Zch*z;u%OFj>vVji>sgj8wfyW)(% z7TH6>srSQ0FRcedIKf&}Eoci%dCkY(U~ZAAHc;Fps%`bOsC_81=H<9S!^mNPsEOO2 z7ko`#G{x1ftCHB76u6DA>M|!iMvh@SoD<7=vD7W&*h<3033wlQOK%~PF(!R7)c-^^ z%6TS!q|u3G8oO`MCoTT}IaTJqfj(8+ExUZ=)^?n8S;^aRsuo9qTRhFoyIfb!XB!pd z>RRS7<+ss0YFyTyKhXagdfBo_ta1j=Vq7BCLbvX2fLI2@d=_JHBz5Q`amdoq(P`!F zZQx)314MmX9{fhDnWBP%l}XCO7S%QfjRNg?VeaU*idg)Kn^i;L_1nXA3MFT7 zF_`qIk-Hl>)|zJ`M?caWl_Dim!WO<3Q?lL930TcJvZmA)eQukfrCB`C>l1+OE3wlH zN!Sp|l@sYDRm~wL^30DXE^|T4bh!kK#iC_eCk7$1NfPCd zOI?$+YZv=jIq+Rfw_e61IY}2{bq?I}d)t27TB5r$1Yg#AB(iWg5?#(1pOC^$bbnTG zVXJ4Z4g+t2EN{4T*@(%ZJh&#k%`?|idqd18?%#ixJ;cdLa~Z^FYl(uUdCvNW5eESw zA+|mNm!!_VW&?an$nB?^=1=*`t>9%(%B*r>xkjG5c~wg}*rn9m+BEf~8u^Hl`5p0* zBC`T0ZWqyWjt(jf$gL12@zmI5OU+!(ry*(2_>uu#SA*YQUg}AUi;q`F>O{=3gAfGe zS1Ydtp!2zGP`3sgS){B47#Jwen#t$^XX!ljU2RyDPc2uwEBE;h?0V7_WyHvZisEAv zS@HLe4jaZXi~GCE-$%7Q`b)=dscjgFt1lvoqLlV2R)$0MISE}aCLLs3LCdsJJYH~p zm}D3`tDWumUJp_w%7R}f)`^45r1V2m&xsm*k_=LU=R4V8gmD6A%t++?{d~xHYQ&(- zS6OLm>3MWl!KQ&uak10aS7|u|H~iK-Rf1L2gAYI7n7PQn$f#*)EZgxjQzQCeL$Bwg zr|v0vPWhZ{qPgzLg=*E_u{?l{r)-nHeyd6WWUboI^yM^{ry+1Q45Mt_YZcV~T2DBV z1N0|{#8ZdfweusifDW-|`JtDVuUC_z!hYuuWTBx77_bo-5V+*uaJTVI=0XswCTBF_ zU?Q`;KSPub4QZs+!h7*3I73Q!c{%XdMF05Z#XW`Z=8;7O?3`Xwi*ak(c(&jCuvm=^ zUVK&?Zr|S&os+$$T@~Z`!05Z$h7^A*;W-SVaO92UjA`DhhPrsERd#u~rGrLm>OYg2 z6Us*CoMGR*xaLEVA?_@d|9Jrn!E+-l%L=kt79RIJB?Jmaet-6cB5vHcK|^_NUO42< zBlX&k$|1AONKwu;F7}Zxtq;HJX&Yzp6U>(`9n%+a!kuN-3oKiN=G8aDlTVjZ%%MfI z>;0VKlD_v$Z#i@*bXh>5O48<;nt2$SOXRfY&kFd=eX&KYyE2M9YDgfA>r`}rGytyT zBmM_{kIgRYQl34{8GXa_=I2WYW$=})=|;U9X^g+vK7ZEAn>A3|Zw?hr3z6INPrR_c z7A&6PR*E;-Gd_~qn($8^=GAQ_8p7NYYm*_Hoz>#QlXiWCrq%P8+FZ()oe!pBrp-f^&29n8zYU=SdxDz6!Ucg+ zk#R{$TBT~h1E*H0rj?-=O(a-2MhV%=d0${HNyAQYr4w_4?MGtl18K5dX zyK^T?JT?FIo#gw{q0Lwv*9k!p*z9ookO*aclS#D!Nq%vUr(tQl`*1E@$W?NQa3;|+ zx;-Fr-3yhzxL!25cA-@&g1Eh*B64gGGn7BlWlCJ2-ZN&C-HXTP8nSSB)o|c*PMvbk zJy!AF5t>I=`uNPIKEj?9ps7!H{^(L#&kvx*q7P%L8n$Uq<5<0Byi60!*kk2dE##)( z>Fh3lK3$sZ-6x?Klj)M~`~oZ{LL_wku#Sm)&8T~a*q1Y=ueqBNN4ejgTL?3X49F7T z7cU;u=aGGU3A9Q6AMYMslDZyweFQf30h|^!zmGS&`T4Z(2ZcTjv8#5UX#r%I7^mLy~t_h1e^E?_vcQwkb}F_^fKh_IxMg3c74i#d+;nkD&W6va^R}cDMe9U-CUSj&G7Yg|9p&LWpX_eHpv-;$!*wQHG%W|7^B+MM)xmHc$3-l zk*C%2wNIt$?%!2}h}>@o``YLs*rs^6hwmSo?4RpT_r566u^!tujruK!S5d`Le2t5b z)y~sW2dqTyKtvi`vMvmK5G2q5FD9eh#`5qRXyt$=HVsa0p#E@NInRDA7%*)>8){|N z;iNLYJ?UCP7z%@DHDmI1xf;UsLhfhHH;2(|Q)t9-Szzn@IJLPr;ni6`5q#Q=a-^S0 z$*5tc_gHbPkJuQI&&w}k46*x=MEIC7HtFdcEX0b}MrAb@WAuxRMW+^R+(EbZ-=GF& zws~(A#k6?b7_8dgU2hD4wBINJfYOg%)k~_=U=|#@Qn-Ynoiwc_Fw3_;w zjjfNO-+g_|Ef2O5Jie^nVI_}Z9?eaz*W=@)qzce*NpM}PFv;$*_*XlsRkTdXlC_FC z0LS03*|Lbs)yw1IJ-S4GBdc-#p;FeZh}q^PhGGX6?%IG$moHzoWQkRgSNnz4ZnIq8 zthWiyax|%CEf8@B(0sR z8UbXN53>P*C%VMz=(Dyyr?1yvjM$U+e9?PKcD`}8ulI$OWS*z`ZkmfC)AuOVUF5dK z%jjcdo5!z$k&Vy&0wpSX-J#ejc@)!V-d3QjqJnGfi2z;WwP)q&srUKP;hE=$-q3R& zp948;`k)Z3fIEf4^2GuM8zpD9mA*_oHJADN;vU1TTLUAd)-?Qzd4|PWpq53X>;25G ze4`q`mgPKsj<04V3042nj++@%#ezk~z z)u#T;W(clYcxNuC|6LP+hiM$g%}cFVyMXzhIvSZ~Ek*5(tO$TtgU&3-N6yI$KK$(U zZ8W?-B@DQ3OQ1xN#3IW`wYP79dZQ}9FtD?uI<8vDqvcytt&ou4)eC z7{n`J5{y~X-F}`2*DiQ+KSQzvi~o%qT>wMQZ95;H;?^#bS@|?S8SWgA9>6kwKl(T~ z=SWGq^OLcvxlV_t*Y>D@;`^}*Rb>BnrKj^WKv)Agj{Y&odiR@p-p~dqe@+K21gLMi znUX1mr`yKo-*>*TtsSZ_x}A)_G`WrFX}o}QLAo#$eJ**|!JrFgJ)TMTEY<6InuW-B ztjY9?RHr=qQDnED`)C8^0~55fhG|!DVaj27?3Iqo1i$e**M)+JqJpKQ2Qf{?k=n|Y znBJ~-ESniRbI46>Yb|PRas|R8yG(aEKd-Vy@Gb=J@6csU>7`2p)O!1Se~Fx2c6;k= zahF<2+90ng1OA8y>A!>|A43otVlfdOc53)N<}g6&)q`HwQ+;)?K-+3uy7EiBN6yeM&KAfLCZ)r?eE&-FCs zN314QDIo?gq!t^ON7Xc~7~nCo!=qJaY`pZ{*ptw0Z>_55w|-y6c11!R#&H!y)P%g` zb$#_#V%mQHVH>Y<&ZdRvO=|DO8(r46BCj&Q>L%0rhqgyTtQtAt^UK>w0X}WbHkoP38UBUq-ESKG6>c}c zRfojoWdd(Q!r&W=S_6IChf2}BgT*)1SgvUSo_9z`ZdDDrCx9{m@@t0Ls(^sN!?vOl z6QT%fse%P0bdR$WHP<)gKa<~%iK=zp?Dv?vPS*_eQe805-xNFE=87nqTo&&D zZki7R(tk`fKZ-V+Zk!o91#V>6H(#D*s^m(sV2j#c#{jmCido`E?659<@Mpl`fo1k? zaS@Jh_Nz-?3I3cDol_#LIiZ&Tc84aoTJU6{Fa{BJKL=SE0&z_A$-alF>ugyC=Je>7* z8}(e(sUn3-s_jjBN^a^LTMreiP+^LVi=y!Hpw}cy0{L}Po^zi>vIf2yjfxJG7Au~b ziO3hhi6Ir;8+BWqksnoG8?dJ6uQ6B?2lq$@BVPRZ;H0torF_rcO~$vtzyGG*B?Gqf zU+?ewGe4sEJm*J4cZ25ASpkVhNYjUzAIw@9icEFkz`nuI7;#BTE;!h7G2ig(?>9la zlk2^XAb!8OA}W81+1j#S3uI?v)?&F9-nEI;D&Qy+?x^iIHbQEc#y!gT{aZl5ba|@I zZv^&Q?y+}Vf{k)?fYe>$l(dkg=LqWaT*U=fNIP~-m&w!B@Cd$2NW427Ll;dfSIP*| zzAS(A1B`d;BFAvSLr%PAE`H=9g+iGAL_jffiN?^=l#^1u)x5VyVQBUBg55sUw|)NM zg>!%@QT@x5%-$ims0V8(`qtd_H%GX?u1zwc`THjlmP=y1k1o+ifNXUMk#e9S`fwjl+{XJ*1~llQp?)9?IHOy) z@p11IRtGaoV>5p@HSJDGQRhrpnd-JEJWE$a6hna!dL>hMV762nR&rG%3=n@ z_x_#sZ=BIZww1eRWg`n7j^o$+%^pY9RX3#9W4cCpu}Cq8D&}|SH>C~EG40GJxf#vL z>Z5e*T*hpMIv z1NU2hz5AESRCWMjIS`oDr9&*bQluzFdUtk8IHPku&pNyxbN@Q{!!XxEAX6(B*+2As zFyAoE{a(Ie{1Z@tt(L>&r6qbq2(jloqV5+ARc6YfJzkz{4@u-n<*s*L4+p-f1U(3%d!wGD1Ki4o1ky+Qo ze9ELtzc$&uSiX3K`mfk{iMphi`DYX~(+%rRTBtkLi69-47B%vHg5-oq85708H4?zZ zduqI}{)Na%N~ZYJlx?af8z4C)#D0u!RIB?Be;f=@SRX}ctE)$D(|>N)QHX!?z89{p zJn;GQtx|`ES0@D+h||E^ynX1sjUQDEmXDmjC6teeHMcn_H4m~LfSa;WFXek}Xd=}H zye*%j+_0)Ce7SENjP@a$$t2w98Sp=(eD^MXGfBjb(h24Scj}g>g z_2S|F_ike;gpP8n$=a+}uQ%X`wF}AdiFU<^k|hW_ zdsjQ%6k_Y46eh1`f^aiza~b8PrE)_A*%_1*h`dX@yY)de#@E5ru#x|pnpBnV1I{K| zt50lIfKm#zd(^tyzD0OA5S^@S!tP}6SSAK;uhDTM-G;oH@ug1K*kwpX4}OGjyrT@>{vI*2m(E?GME+=WKmJTs zYsY)$e%jFpPrASDe(+V}c*hVQ`jcFd_0r-yp?0`L)wiB4sMmzp%K zpU?nDsG#CNoMP#1X>igsu`p4;>)4x7li?0@Kp;l0|=(CWEUaV0MXEw&TK{5TGl(M=2mot@q zK4I;I`68PNti<{Tl(=?$d15nk2hl@6pq1Ox&0S8|SI;aav@|bN(YcPq#8iF6wIkS~QLe9I*Ylr=P8^HuMQ7AbiNO&2 zj>`C8)~+c7Zfuu(AERH)CtC(Z%e{67OO0Nq^ycyL>BHqT4q{K~%NiJ}34cN&RJ{4a zI2~~8jUl|sz#WAE$N}zJ+Tg~18-db76}1e#zB)gOXc?BBrA|X2SwaS$dlb|!K8UKw zG4~`Cr4~(M&vq<3SsUK1Ag+QdImmCAgiyIR4jE2t>tuiHrW_8IB`01MduJ5tqdMH> zu8;<^eH9Cu(>}EK>^GyD_nY@rWs4?_H1_;H{h@iTo!o630Dzw;*ReG4_r5HU*MLh5 zWD;axr&O|J zbYYFEW6?tC?T}psy8smPJJKBvyiiq)?K_A$2LLo?$$NJ2qY&8$;^3*Kf<1{OkC$qD zqSbUhwRR|%cGl!$m(i)J6Kl_H=06<@8I+TCqT8?_0>+*`#=L)aim7j6c@ZNXGH?`P z23Zvk%uhLmSgZtEXA0y)3=7_HBBhF@#=+ky!g;En5w|A??Z*3>&$XGw(8j?h{%W58)xl{J`>@06Z1!N7N zt6y7Ee{kj0a@sJF58afOMc`+;Td8ec$%4N;(Koe>1HXWf=Vz^1>zTGMP{rb7gKuSA z(0(t!!p|jkqFm(${ZRvc^}RY;+X%$2nR5@LC&W7vl`v+;6Oifm=#*ofy~r~wdgN<6 z?bU)Dcn0k9)@bO@^E>iQ=YJccK}t{=2AS4g@^5i;A8DTGW_BLcc2N#Chq56F8>AL{ zydtr0epuN<`J;Kh66gM1Y_cd3H_^9*9k*TnOl^ z_HMz~+N!dOaMT{3=8R|`l1Ne!8V8{lx@MP4+z=ilcwOW?MC^C}p|^Wu-w_(i$ae}X z(hr(1|6Ui%MhUbijWVK-***)g`t#1t^@$W`=m@G@3>LG$wbsN<>*^k`&Mf>Yrm}cO zcUfwb+fdQ)#P;d%7qCxRHq-*rcU=6G`;TLhu5PbiMqTZive;QWB~IdLEYgXU9QJ#Q z1FK>fkv|6SUkvGSAqBqugauz7{rKJ; zTs2!WuH1`a?ogCMyT}yMJ6TXWR}Nk{gf_Fa>z3m3#ik|6KWpLnzd7&9P4n(fcPCAp zYQpYQHJ_j$JYnjCmx^JK^O|w<_ov{yg`fUG>||o=W{^q9VIulI3!a;p;<~VszLtv* zH9wi761Qg(*^34dy~}mc4_Pf6k+|G)*4mtFMS(&C)K2aFX{@u*5$Gq5?alFb{52~^s+|ig(OcT1$=qKd{ULe8!?+Z*d-n1XX`UvAs z$?u7hE5oyR>2HTXtarBdkte_T;O}oH<5k2q1Qt^SjO{VQ$&>J?bw9RV)@3fCUMDb5 zn;L(wHkr|BKjmRNT++ki9!9^iU^%d+TcC?mfjc0{$btUQh;Z=7g%xt^e(jTaP(neV z0l{3blDCuH$!z-q0=(oeWyph*%?o6|8ot)K`)ne2UUKmsd1FfbvQD1f?0@!WX33OQ zNFh_doR%+I6%~NDJc?x)^E-)|Eb>2%2-%cuvyaKESd7G075tWMLJ#d|wg>omch0we zY9m?Fx4|j(W9V%AFQ-onC-36l72h=dM1iO}T&UCJ0nfUxq~(B~4r~%bnaD#Ig zSjDK~(a;!88w?DiIfY@gD4=Fh@UPywOb1lN8l1Ra^g0Jj3$!NM1rN>8qFA^8DlhKjAjhVTfl>|B=N~II>gU(BTN(II!{+Wmvv4F FO#p3?f_4A^ literal 0 HcmV?d00001 diff --git a/sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_top.png b/sensing/autoware_pointcloud_preprocessor/docs/image/concatenate_top.png new file mode 100644 index 0000000000000000000000000000000000000000..c317642bd979979a9bbb47220edaebb9764b9fb9 GIT binary patch literal 286968 zcmXt9by!pH+ebh`rG|vS0BLCi=@1wxA<{iSLMdr!=>}Yh1(etup77}EJ*xE2Z6?`hfEci@PSX}a%AoEL2W_4XX9mhU2 z4h}Pp8bn_2eeQ0XZ{45Xyv?h=o1HWN%A-63tt6y#Ev-|>nJ4DtX^+W=57x)HxcvH4 z-6neS`a1M|-fmR_1eD%c^|P^oLRSVW?-pE~ets;ouzQ1v&&hXj?TpvbWZG_v$@a0Z zpkHQs^;%tB?Z?OzXy`g{>_=*POV-d!E*7@Hbs8j+KlnhPNDlHr?z%^=SDui+6Xp6d zCK$UJth`)R%XWT~u)J5KelSquT7W;h3cB`RuCAp5U9ZAXtL=NFWBG3s7SWyavnOY5 zCZWijU~p{$=o8^V&W(+@b|?~r1y>J+oIV%EAUTL&X0t({Yn6nF+qq@XbMF9@r~)ecyw81aOa!YO;9(S4)`kD)S_Xz`tj zYO6(I^Bq@^-xrqQ0in0~%+Y@GIy>h5?CSI8_B~B;Xkq29#rg!q)q3-e1lg~O2wKCb zot3BW#O4GWCXF<=VvNw8e(qK62Ncy~T}5&?1Lv8+=TUeu8)zg+1;U4HEbho=+zpbg8hE=hro#2uGft1`X@;gYXkcRh)*4pv?{nkk1#~{y`NT{V${c;D$m<1_$-5PvR3VjocL$5j z^HG3ZT-1VgjkJGQN=eOYumyh(L5$br_2NqA$-~5K>7h#Xs$ch8-g;GY{i%j90i!fib_MrY`A~EOr3-5 zHpPywUl)z0NJ(xnP|U>E@AU9nK%<-zZ=1`C*I_z;D=*DjP^acy3rXFDiH>x>vQN^g z-8IWK*g5X|=mrib!P>vZZ0vqs9e^d_r-m%IF11!I{rq+ZOS1pneIa9&@nc{5QXE@H z$d4BuJ%od<8dzsH<7=ha>$m_HobtFRf36z=sWn0()YS4#^(bg}QTDXv#bv>r zllNJ1r3}$8uGrp~7wzA5>WfZ&hA)q^wu`3iB-P&6U5oExdOH>N(dbWS6Z^tzj)hiJ zQua@#NLr>lf^py%RirqdPc2Uq&UFV0Ez|_ZnHoM+_~7eM4Yl{0Z!WcJTf^WEQ@+!< zC!dRt44svJ`)MN`edS^s?o~G=jR#u5^@IjrM(W2W5({}%CBwfwP=dvo-vn|j-`@ywt_%9J)EiCDV3fJ#3&(bs^=3xp=0*mPwOQ!*w3L68cDH{E>XT@R|r=x#cKc@H5*r z_ZU1>*6vN}9$#0m$+)8$bw3{khjBGIzPyI0mnMgL40Tl0P9o5P17`1luKDQv*U95@ zr+zxSRo!*pnm&Ew8Gh^rG24H*L7&e_Gp4@yDf4~1MkwDBvCZLuZ~(egG+xmm@+0$3 zq|shyOXKaQqU&FCUqIJUJxMaDmmi-cQr_7Zm^V@BNRoOZ<_llM1zJ2rQs2Kxd*_Bi z$Fg`7q$C)BV2tk+{NwKsA&hqM*qK&rv(!F_twr9fcqWCyj-=5kC6C4NaW>vBZ4pbB zu7bC{u^UdhXMVe!*>Qxi&a7*^ZS&0XQ+L_3YgtpTT8-eEYmcZ#=N>QZH*YRL?Fz1m zu_O&fAf)}kbVmRK#N)4Fg@u|(Wk%gEBA{Fq$U;Rqyf6ez4{dGMD{39B-cVAF4j;IY z!q7=O2(8$f9i7vCm*U3FL-DKnR0pkxA*3*g&qd}R$D)-^8Br;aV;$)+f0nUP?Rxm- zz+0xzeS4&334We6+*X@v2d0-kN6@q-4y$=jlZ z8H|#8ld93|qVe=8oa1XOHgoNubEq`FZD{fRHAqxSI0#?oiIe4=T7&wDg3eD!9+xC{ zCfYQ*1kR3|U(6&!u_+HXTeKY2P)u>)cNsTe#5C{N)sBw}Roha-84h3?`cDz^|GF2j zbtPfG9pRBX`_@WL=F#b=`HxwnS%ffed;GoZ1f-4vjbi!j z&37KhJRP!B0#kw0OHqNtO`O|oEgu~$1ZM9jwj?op!pgY0H;rRVZOI&V-70L@Ji$gH zJcj`h@cG>U;vkRHP0g}*P#NhgJXWb!p}~#*q>CtL+RS8o8F<{0xc&F==1qpOfs`u^ z&&VLq&$Y#A(RhEB--Up{4rewV4sxDLL&RQX%Ac6&zw+f|A6BIt zox=vz6nX5<&wrY#U&N>QR{YfkUp`(7?4%K^U?0+S56&>rsmgqv_~Jip2f&o2sMj^+x8SZD7cT}Ic>QZ!VUfgpIOgkj)oJ( z{=Ggu5wggg^8cbEmUTUF?3hEFc3Y=oirjC>$e{)McFeqsx?Sm`oU5OBbK znqRZ4x3d*!;hnWavi`X0#|nM7%_7RisB%ZGt4VWwP_erB(s51DnNx`QU~sh{U7_38 zM9()x5FIo?|MQ|}^?pfHk2b{H_B7p`rgwS{rEa#}dGqSL`$@%kQHABa>~&CY>P4O_ zw$1OJn=R{@_bVhN1a#AT#Eht2y{{>lOnU29coJ?}2#Ob}%pq)2?>1?4r@XLQEZHOx zl_%fkx+BB=mD2BJAO36eUTY!U>*EN}*6?}x&zH9RDCv@|>zbY7;@&Jt<@bh9KnD6u zw!~+D_$;(NRliH>EvN~x+7pt^Y$$g7n(0YMEiAa{(e4Lq!Y`mSr`V?YuF^k(u`N?yeDAxSD<%nzhv&PwG7nQQAvqnWsS-P1N~w$GT>(0ix-{jGcFh@%~; znXgt$Ga7-~UD>hD>y($zD^(rAknS3|8?MbO z_~RCTGu0OlhAinTMtxGkYW_jxzrWpPvq0Bh{Ja!IS-TohI(FU-_#Fc6yl8sSc)Z~l z5mPZ9x7~uVE|clryR{%O+XER+BA9HnZ4hD`aS+(bPh9c;I}H47_$-+%n-Zu-A#USu zt;>;a_HC8Mz3*A;U9N*2sXq_u!YDIewMKU*rmZ0PTwhwN zs2&)eG`**owhsE4fT$#_HKvGTSPAJ(L8y>RbG2;T+;EwNMq&{$7lquj3i_Kmg?P`}N|BPu1z@wGVAtANWBO}B5&Eg`+87X&B8&~e*=K_u*b$hJ9=`%$za4uhP|=e ztE%2q@xRN{pd5;%OnsLD%Zuu71L|<@eM}f6=u?4H;i>i@eBJsR9;yotQ3u~(!vA)H z*xGjplu|GQe?=c`m{#Te?QAL7iDQn&789MQ#dLp*_7A0X^$cj|%5kg2i~Y_K$zHMd zU^2h=2Wi=Wa%+@oyf{rx>rkt2{JwGfQ}Z@4OdjegY>hE{8h3(XbWUm8YlzzCmS41g zCa-B|K{nQb6v_nkQusoH=+}W*`bOEB$`&(WLOq0Mku3~fw<%=(S zDe=1VtZMl4H*QAI=&3xzOq*7+!*T&4c=v2B2qt0r+(t~EoKYQ8!F{jA$z*@Lw1r3} z-aike1%?$2JF(hMtLP*bt@F~_+b*J>)4-+4#+_hhYx7zr{?>#MbvoV&ap^0v~z9s4{@BE_?@KkgeW zc3Ve+@~%YpQZ2d1If9L5&KC@mWS=~?_|=|t%sRlDf7HI<=TUN;pT}y2-ZO`Wc}s3! zm*Og#k~nlHRn^f%IQ`$k?r)2@ec{|Kw(jq8xLQRf<=);QY4vQ{w(@^b)wcb;i2EN+ zV`8ojAn#QtM6A!D;yUIQFl&rZwUNisgEotIJ;8-LrNzf?G95iH36rZwyiE-P>z3(x z1wcaL>n;Va>fe?3)bi@^x~V-+;45qvjn8H9Oo48y9<-irIjogbKrJ|2hWjzMR}by% zYHrQ|QY7XIFB~HZRc#1+mqikWa>mp1d6ChQS@4U=y9z%zp(6R;To>F%@LBh(X-vqz ziKYY_3A{At8mhVa?8g~B2qQI++CT@9Hu|h{p7#!tmT^YXH_GDT>>l6P2d=@s5QdbO z-#(D&Xcd}r>s89OkI17{J)ntJ9W@o95%U+$LDO$j3`a`j8H*5pV3nIgwnuRlK)VeT zm||lk$v{-2eNQZqn{uBl&s~$$&6VuaxrB|db$_y2Rw@oF2%VVbD2=t^38ZGVze;@t z=)Jlu6WXs0WHSAwoU*rxMT>U4+W%GRH$=qK@i_FF^IXPLTcv!I#eOd|-ak!BNU|kv z;{)d>PM{I^L5|B}N*vsL8`SU3$KmvV2NHsMPZPmm zawA7HEgb_Lx*Fiv1#n%^x-TIepMz{0Y%`QSXDgPb(2Uwi}`-@JtfjlzThzHBwtY2Hq;r;XUEs6gc%dAPFpCbus4HtsmrEz@b}*>0*I zEU*~6jAyQh6*W@)o1sbbIw@WR@(+oH*$-CVQB+zd|8DMz3(I`>H>eJoiPS?-=Td<;FOjCrgdsDB9>thA5V z7Nvv~aWv(dviq+*1A$p=kw*2mBFuqw%TWea>VS4Z?E6t`iVRbKMG`jgE(rA+H@$S9 zxMxM9c2MapwQF1p!nnTqkjLC*$pM@V>a^;Khqwlvh7qTexc{hCRd#MBXpL@qzHzKrS3S7N?8T?((RHHW8dPTBLE(!VtShL@Qtj~i6fZuO^f4hVjHo1uT@Y<0z%Hu zhEz%+v||!SN+a|Z`oR&4ON_N^r}*pDB{LA|=Cgv`cu$CUF*3o>(AtzcG4{1js}ZVm9syoia-9`SB)KJ!QtXz7k|H7xBACbQ zBFa;m4u+);5sgLAybV*4T-LVmA1JnS^TACX?$2>5V56d_;N!zRQmseK+g$Qn1XAkW z(nEc8oHIm|Psv{}7>z%$u=5grV#ly2BSvh!7|rivd-Y-kkL_N|8w5}9pA@z=qye;z?nq;P=k7?+(+%Dm?8$F;Y%@9 z4n!ojnEgcOpD z?;YfC73I}PhaG2Z-yagn6KGMYl$vs6cr;r9AX4U3UH}M6;tZK zb6F-)F`(h;QY|%cLaSFw9(geDQu5KIgy~B0i4aN7d(%HiGS!R+C5d4bkg&`191C;< z3$6HCzyzBCL;$VrOzW@R6SzRo;TrU7D121)U=N$HeF)k>dsLxM3Zq?ppw7E(T-Al_ zBXT*4sLkWfjwKu^^|gUp>K}v8qm-oAJ544T9K3L(%tC`J?_lKS1+g`^nx+0>BORN*6{K3;5mhAfH)w*^5hw-iBLHatU>sxaC)KXRXg;>=;FH9^chQUVKq{|yF zOK9k^hOmXWeL?yPlCj()))Z`%(|UK|c13hK$oZai4xZ!QA8*iq;`r~oq;B8v>h2sT z%?pkVYd2Dhn?fW zeAWr&m;Z+CR4|b>ZK$Z3OpN@EW2*S?kkgkkm6iB+G#Wk|sqEx4{MVUIyzy$95m|R zl%ogF9ewX*72rp=7I9ER-yjWbtA^lue7MMTK5!i;ymGpnWIMi9*FK{*L(2ec@iWjr z1nV3~-xDj$_0z_M5S|#N^pcWg@;O+_!y0BV8;+wA2hkbS+#VHRy*sleY zptp%2p;7ZT|HT%QFpYb8e^!FlhFkIk8g9qbgDqn=Y^QQuGHCRPW>a~yXXY+@785{= znIU5^E*%+Q39xpB*eO$frNJam_eQDe{IC$io>w=8e8u8j z_>|G#*(tw8S%q>X)m_u2HRUn4%&>XP0G6t5sG0Tq-uN(t|1o##K$eIQO)>UUDfY$< zQ08Njs~V}BJJP4hNDCE{94nId-RVH2QHHI@%u9HNi~e_7C?d2dMr2au3NyL5>d<%e*8j z(OzfIk^0Mn2;tF*+tin2X>Q94-R>(DjJufO=SG)TQiw0{5U(bh_cz?17XJB3TNbH6 zy(;(3FPDi3LUZp9u$9Q#onEc=zD0L=9v3jBmyFxP^&V$uuIlUqC~wX=#fmU~rs<`K zlYAvWuwTO&R8>i{|2WGMUBj&jQZ3QHma|5Kr2;_2LE6<}t8oi$A>-mm%E60NAR_I^*ku=$|WYLWVKDLIV+ry0S*Pye13F#!M&_$4z)W>LN#k?GR`^ajAh&Mq5N6|Ca^mZ@VnZ)v@*jUyqpHdRa^>F^hC9 zmP&aa?~8R(tI~>HU`Sl!F^W&*|3rv~aIg}y#FT_vo9l>%+uomB=MtewpQs&E(^C2J zATG~s#9rUtLBHoi02_l*8t1%!u3Ym{*HNxabDYNWixY1`*A7uK%O%kA?ePMbmu^kG zw}-ThYIQ$`k95QvfWg1X#m=oK*tf4_{S4Or@`W)8oAPz-m$&!C>XV*hHVRMUE|n=_ zs7TAAJPt}Nw@-+!VhYUvcKSUJ{vs$aBKM~7^!TzN83rXB(o5#6aIU!vx*k(gA+=h}D{A=42?k@rCZ~ zauH+m-Z7yv!_&bmU6u*^nO>S)fBxCpg_cOzVC3sX4*<2Ge8x)p+vX$P>Sa&6&wvJy zm}L~_L^B{&W%1U#fip0PIeHL6=;k*G*AbujqM@Jmr3_hy3Tz|Y;$i@78wOyQ_^w*K z?YWVkA$=aRvG$^muTlqqp`51CLAefNq8!1Q&RpJe)KYvww}>B_(F5RvD|#?IH;<=F z)K*};3IHw;`1N%>c3TI|u(e;=CTfcW+@9R&Q%^gU^xCqqwx_|j0-({j5WWoZOpT3{ z_RkI#m&$+p@mINS{9g_K0>iRJH= zCvw5fMz)qXOHRJ<&%gTiHbjzC|2sD-uVabUbRpv@MTOwl{G z#zE&HcP_nUcBGrpeov*>o5QdZE}cKuXS70rZMPra50HCva*{B+1Ouz#6cg^H-n4w~ zOma}3Q000!o^rSBv(I~r2cRXUh;mJV@rFAXXJ^MV$jpY?gyUk90hx|UOr8?xWVW33 zx|!ho>_VRg@A<6FPgMZ%N!{du+1jQ#0xtnP6L$61$7MIzb)}LzR^5Ouv#!o*B&ps% zC9otW(k)sv2~l4?N>88ulI}WKPx`Lk-PsjPG`d&tb{XJ$w!dQ4We!?0FZZ_h2xh;4 zoL0w@gAMaCi$9j*qkqEsQs?`taQ!ARv7kTc2jHdPI&7M`rf2J^wQyZQP$hhylemNJ zmp$ts3nZqItt>MMjq8`bR&%tR4=JHOExo*Xihl*W>5eOrG7m?&QHgr}K&nOkTe-0t zy=eUxi?4$Jq4byIl>6Al$U{y)qHo3&GZIz&`^(VkLbiid2c1pU^i3zib3k2m2rW-v zS%|E2c+`pXHv^_?;pwoujCEfYu$u`g?J;!p{raanJigtstX;SLG(m{~N-G}!v>61C zbn6oVzT0(FSY|7?)I%$YyzqjqTgpBKQQ^LB(lkL#HeL|nK_k!}N}oih0%%W!GSi?H zb@((4!cGzxu_Pq2E&59uPpWS>XV}I56F&=!!5Ub%xh`3gqh{M!TJUiI-1x7 z*!hE*`o##3>b{U?rh%MLdbX+;t|#IPTsEvjr7KHdQSYQ`!8?;Eoid*f5`ZTiqge|w zZ4~L0<>~4Gzuy8lUM|`P@S!_8cP3 z%KpAI`SMY>&E(Fvf)y>B02+@*U`}i5{(3?3;sxxss4s=)gL)5|Hs=Ig zvKBjg<*f+S4rY!Y2?RIw^nYo$kg9u!cB!{=I`U>|U+ZjX@~i%N?}*%MsnMDCifs8& zuOuPDT(jyM=z819mK+5(@*(x9K#Zs_3V#TUy<&2r4Nm8Kyv3%RVsAD3YhSHDa6YoS zZZYnDEn5?<3j>r>{eY&V^^u*5YSoQ5>=gMOa9qtyd32p7pTUc&7(TT&)brAR5#z>H zP)e%}YooH>{g5ZC)6msf7Y5fE5SQoJB-#hcp?(03w_iHks_@l$M&7DlxQlY^` zscvV?XbUkSiyN~Y#`8%fu_?8fiC0UMtZe-tn;7rt|MgE1WC<7?3VSAzXX1uHqYHs} zU`)-)TpC!GC}Z<1e%e1Y6;jENq)?97)zvQ7L$K2LPJApFs=_IeL5}Q zbeqGhB0s#!Sr0#Mj>x_QQNmS)O6jQdi_4hRJZYtG%PO!)d|~M(l$i z0I)pP53hgJ!v87e;8^3D8vGAsEp2vEpYLhQ)LjfJ0-}IsiyBNKnNSCA<{P47IgnNC zP$Atsy0nu=qpXr9Xl@(&i_K)8#AiQ^Mv3#mG@!7x%t(Rfdzv^%$|?2z;|%29z!6ZSEGy5Gy`+si7gvRAM`fy_*0l-fT0Fs(nY&2I~tbW9&18ra(kPO?B7*YZ-6jbGccHNy>Ry z{Btt8ca=3(X2M{{y@}(cl#J5UOmB%MM`zlF?~fBbpn-Y)o7^#`)?69lRr!x@e)j(T z{FsO(co9%crM?f&f5TZ!5RG3rrSvQfXG!Lag0bZOAfX6vk4^>Dqse1qxmiF)+t^y4 z-7${wXPvjx?)5bQJQzzrQHV7>^`aQne_i)}HfPVh!)$jXui2g+5jOhKfgi0|@FwnG zkjwcyal=T`j`2>LsB2QvdveQ@GbXChJAlL9u)L6T)#$x>n}>{xIl}H_CwJZg}Zul?mgy&zIFN3oI zuC`%0;#(m1RHAGLJxK+3MphQhIBQ?2ZbRU>JrY8=^h{Jr4V&MLw2dmAM5 z{%^xcoDaR6M}#fgKCEL-HQ)@yY0p$z2$T3|>uH_8tDTwID)-ao+>{Qag4=+RoIr#0M$Al4-%mmO!-T z>b%WB8@-zN~(Vb|+EBr_-%;`u%X2LaYN5 zg;VXL!T`H&E|}U^PvArZC_X#*VjG7nt_DD-K&akDIceR&M$yi(J)qv8Xp~aDEFI;Y zv4S_9*AOXv5yRv^K3ALt$T?N2(HRwK#M}=0>K2={WD_X)U0TQWm@O7GdS~VKTIW1) zjuE*Qf3RPzn2LHmTcf0OT)f}nuisFNmA{^kJMtEwchmoKojZBkWD+cQ_be+sT?Fsn zBMu<=>a; zU?IWXElvBVi(0iVNH_w~y4(asFQX6l85+iu9kjN>-wx==dHS@8DL)y1cWUATyYU7E ztZ=56D0zII-C9MoPG7cg>HtwnuPJ|vv{f35a34`XzJ&bUejNQ&NG`u!AsoC0tk1hK z4N9IsO_9dvV=Ly$(JqQ2iK=!)coQPT%l0-d{GxKf;U>?u_3#6pqkbO+Ig0%}Z+r7P zO3I1hQU~O9sZ&RGA+B5-=g44Wc#%ArOmt|)(*GM;kh~JSejl$Oa|L;F>pJ-Isg61H z`^nF-8%Ttk?C=jHlaPYhCeg8Eq4e-ztC>LWD?-HYwoOIbaP8wQN?|Q+>+Uhkz`I2b zqR?Vtecu{g{Ihf28C6G&8GXO=Ntre|B&aGZkk1C^#+uwcM%xyZS#Luf+KKdt&c zN{ID|K?cpEKGLN}z5?Q30ZC+9BM~yj&Cl)V-RRwd&GLWkYE3{A-Mo59>^Ggr?f0)=aMzf{ z{AJ5VDdhsn)T7nDL9H5xAZsHLL!O)|Fa097oIM_YY-KkuQdNCVH%8HqL`rY`rV@>k-6^_OBAd*g_GSyXU*>FN!rbeTJv}g1Juw-?q($ zx4Ja3bvQA}@YlF)nTayD2fWPzaSXAd=X7`Ks?9GTY+1QA_y?y%XbUi3^hmE*Gr!;lz3gQ2( zy)kAMp)u(@O3zM>f@Xrg?eu<8`ds=>iXZXB_{aL;hRmFC_}vk~G`F+eU>2!$&fwSzGpf#6V6zCvOjqK}*v2n*&n8sgJ(h zsqAI83ALQn>yF-J_;@qQnbt=ObKRyJOqn0;ZkA{{_w?JGFva%P$6^oAf9diaF)M9v zAmvLAVSE5~<9Er~{YI}Y;v0VJ9*WXZ+jfbqO1?8ON2F7?Rdyg4k-0M94%ZYCQB!Jcn~mhr_-+=bzdIN5S_&M zw#~H6fj=>6AMb6eAKxng1yXG97)d41B>(cH$|{#FYOw#o`fnA}f0Z|=AnAQHqb#P8 z`dQOgTaIsy1Kb)5e$n5Uy%ZsH*`KoP#&WQy7=t_1d3RiBU2OHHxvI_D5JDw&Z_^yK zyk@>dw@m1W5SD1tnuwym2Mjc;)yocs)u6Oyik+?9Cmt(UmM@NmwFdg57H~yp6z^{$ zn&%kvL#@zmvYW=@D=TmUfE#QhX~;+{2m8I26GEE=ev&zkLdi1scdHb;jZH*ajrQdP z+f(Gzmi07PsgtD0wY`((ns|@MeH`8A79D$NylwYtTlbwS!uNp4mjW(&1D_|y;i1F? z4|!BjB}7MjOv{!$l%?aa?<8mP-!C!X_jRt;*^KxyUWNEFy@;LYueK<2#l1$pW6SZr z;Imees`1zR!Mnxh;{05n%-0uQ|S^r)#uG0*kWp)y7U+ohOQQVPMBTov_ zCSHTz6z?hB-%x`@oD>(A7fXUV_BGB@W=G ztsBc!95m9KAWW%jC+qoRVI?+v3%4@+gKURVdxurXe>pj&i(1xZbY0bhKuAvBK0{Ps%llO%@i+iH+S#P4_fcVF=%E~ASQ?{;xr1uvEz-3g>I}nzD5QuFa z9ISCYrgR1fWS6C*XFtAoct`ho&vH8bmwhyX)OV0zkLbTZ;c2`iE{+diL@@>qXGV&T z0a=GX-f#vNKt7r-GD z=YYoc5|~yC*E#FK89F;*zA3hv*$#{eKgBRR%DuIN{ z5C&x0XHt3L_l+UPUyDoG;$ngjY+tCD35OH^sx2akt;t~xLh$HQ2h&nKFDk(1rcx7h z6H89iQgEBLeR703ZXg9pZdl)Y%6FN?X9-BCv1Mjn!9wK9U4Z%h<7w`nRdaGUYrIp#3DQOMd+c^8t2{Njf{Imd_#lM{$L#qfF?rF8*MmIv`M8$n-6b|fFCmMj zO~5$HS+wt#R34)Ad!D?p9wR;-aysj<`D`ZoSo(b4o6}gNqmd^Y?>TDPo&R8W1mD$} zs;%vXC?Luz!#FRTOi|g7EghK|*dJlq6qJs8)|ET}ZhSS|Wxwl1J{t1rPZS-i);M*! zAaDvP<4;pq3P<(;`wf0KkIH#!5HheK1c4lly9r?Ek9^aVH1}@5!3yivOSY7d)`Nlg zRHDxKjwuh}{%_M&s^S52vU+lRQ228S6)v&G1=E=_7y>xVDSA748S*h4w`@C6u?jT9 zZ60p|Z0Y(FR@>(;y?h?%%mh$n^`B)zuZFeoD`5qe67pNha(7HrDi0m9P#I7F(QUY# z#$5~0n@6m1OE-I!$H8cQk}%Rr$C8&HwM!iMsecEq6;H{F%si$j8tW}5U<8Q5y@z9? zNn}1f-t!tq^2Vh%f1|~&Ud)Km{CU*!l*LRX{5rn_Q!V=IB**dkwTAtRI&Y1LUAmh0 z95hNWk`WA@;MtBvTA{+`kSdFIgWydd#aDKs^3bht)m{5F$;-mSy?_Zwp%=?MI@DX) zw@WKI&k*|>Z}&B^x96qAD>cZ4E=kiuD;XT^m;^Dqev1~ql?%E0^{FaGaEG0p8am4c!DSFXq7;ITg@sJvg10v?67cZ-b z`l}zh#x=0spqke|12DQ(r6Jwzl39N(sk>Dqa z@V{yqJUXGnc(V$`*VHR~GW0T1nxVnY&nq#e3`UzIvPP|jvx4ojRK$JTTCkVWygEQM zf#;sJJMJqQsxCDU%GEG1GA>e_T_fV_jt|W< zX5;p~&7@WLp-b~iWB<-k7X2|5R}Q_|)*4r^{(>+2PsRG+yIrd2X>@PwEV=&SuXWlY zn=H23uA0q_vg5|IcFzA$U}Q#E$yd=e2p~y2G#@`*GW84^Pn%!XCGY(lZ-e^^#u%-n zWe-aIRWKHQ7_N+;sh01}J|)0GUnB5%M`6D9k>LFCMlE%!G0 z_Ea6u@$L+;sGXciu71?j2NIiUky&NpYa~waRKX89Gu&1mBp!~GVyGO5oTJhWYEDId z>@JO#Or5H}@;Y}5;Y({SLqw-=NJq)~00*QZRb@k>oM`R8V_1*J0kX*}o5G_-YpjDcAjeJrPN1O+`H2i$((as$Z_gsIc;AUu zj0Cy4XiR^7dI2Te3$Ok*jz5n(7eh@fJFCq3b+$bvyhD$m& zn&v~McUz`3ss2v zLm)02vdL?C{7bz||GpHYdr^3f?s1&M80ld9Vq`gO&>Jl(AlXzdwph?HNil>8O z23us!xmh%)$;65G-3hM0;~gD-n7%#H*DEuAtJPhDC}#3_G^H=X$>ecEYXE@yhAz?+ z!3K@64#bCQ+ZLbzGnAx&M;ZM|LsU$$O|X60nOoA!ttX7xxEVAB5O5{tX>fZ@E4-*Nty z*bVf><=p%>e>UE~7(D?gDX>q!F*$v+r|)D!+_HU5?xSWK%!ibDLzkpxdp|VWx2E)F zYD;gd{L#e|7AH0kD`Xi14mM5hUIfqmvBj(b&fxj0{m&z$>3|%2uiVmS+}6{;X~MY1 z3L3|Dek_E0`^7%%EfTq1UK+&^pc{mjhcvCH}^ySeFL*dTeV~q}zZePsgl*=#pCm5ve#rd`wgjtrh(z?$BHrGkz7;+tK zTO_!ZuaQxn;OQ9SvT8n-?HB!~vBvu%G+L9itXwm?6#VJdw6!wxLe=&n9{)CnpjV0X zK&rE)SzF=xi_kcN5$#5}AE)p2%K;o5^pfcL%qHF~Ugs^TcADi@+(F}ojafgtq0+)P zqG4?UzMUC#p_d}!X=>P!kYO?QVIZyjef9&nJ03I5iRbqJC8$oDX^L6jM#N{Ic+4ya z9(}K`{a+RUo%=neldiBZ;>AOdbxeyD8o@6OcbYb!(|@^XL#lO6BcF%jh^a|Z`#TEA z;c^NFe3H={&%LkGrIkEz05jpaYwzYNsN8Y{^)rcb^bStP-3et5crKXEf?($I^x^E> zG=G9k4#QQX^GNw<7wCO+=>1Th>I?%n9RC$7aQzI<6@DA|%9k@PY*7AU2 zbqqxaCo|2e@z{FfU8QuY$em*B_yEye+f^zKK@zjEo>XJ=rcFxVB%klVDcO%P*ZcBC zuiTak3p_x4(QEZvsgou0DJPV*@9en2SU^+}x7lse)4ugm^kKc?G=EY{LdBPj_n~>gY_&t^0eA8niYa4Set=x>n2V{U z1#0-lZKOKkWiLSN7``={$r4=3Shvu0oqK=)6 zqDfcKJ-~K|hpVQ(0^4q}&oA%VkqkU1msIW(B9-RH}vS7rK%HqJdHT; z^RBeHI4lm6!PH;Si>@Ca8<`sXYVqs9Akp2k4KwH$ov5b*;1^iqRl?i?hT)RDB$XGj zWpqX)g>&VYXiFmwFXptoD#Z>G<~O>t$7cEe*UKIxbM)mA7J2tk(ioUkzxwRl9mCA| zZ+ooSF<<^Kt})hPQ28&Et{T5im-%W_J`jb8dk4zjn@Gr5;}w1-B2nu^XaKre3>{2v zA^AyoOfC|~>l-lB*&9*E(6u_iEnL}qc2&fHmp&|iosNAEUkLuM;q%DV7ukRkwYLKA z>NRmm9R&{pYV%9S>x)A{ZD*jlWo(mmr+N#AJk~`jeD+1&Md`T+*PQ&}vluIyO8GM< z&f`z*U%~mC&lgIFz`|QUdef6>-sJ-0@gC^6T>`Gz!-ah8{~@Fqpr}C>s!@z(5Ek!rK=Og@w{lloGd=Py0;H;d~l_% z3S!?GP;_uHU)E7C@N{ml$d#P;A?5^ne{ttmusqte*wClal}R`ndthTrt;Rg=dECvP zD>519F5hnmWd1T*4C<`Cdm^?tN6&V*sf+8DlHfywD6)H(+DP&zZAg<;#3D7)oyv6F z@Re*Eow{4{pg@9&Qk`$|gt#nGSaoXB3$hn|<=eRrBS!NFR}+~1t}NL~&DgHc<#q>Q zJYZ&Ol=AKHwFvipRLstXI`+mdkDPQaAW6V%8E&LhkVSj{467 zxd==7p7G>0l;5^N<1!3G@aZT21hCOAmGJ0zy0q!;1^^apU(*m8ali^LnZ6Pv@l61X z)u*$r{%6>;z3b2%zb5$2`&T#qQA209&R#CFiqcMUeftF0`ExW)+MZ{4Ry@Wnd= z>Z-@`NSCDWw&**sXCDdM)=UW_RY((;?EI6gOm%%O&&iuHsb4F32T_A5h%`QaD z_*3s%@iO$MVy;cJ0Cr*c|DT_*zZ1eHB8d;a0vGi5oY;5YO}V5d#)OPnKcb%|K>q;q zxq_7y^0CmQttvAO*(I{5`YTE_$zH9lb39PeB=<6OVgTHW09gD~E)VSxT+8BNOFtPu zR~fk2;okYF?LWje*|#lm!CX(y>iYM&Tf;;N*d|D?CqUvW&fm;h+vAmudv0JD6glz^ zE>&d=JlQ)Xi$uGS`^hxhYLckSyA=kKD{fz~`zsmF_Ex_W1FI!z>G~*RO1QB?R*J1m zU}@Z6RUsSf8x^nn?I3_EV42u<7LkhvksqSrB3gg4v0tmm7pu@$gdK5`7WaqhtgCXd z!E?2XeBQc^xvIV`53{>?sg7gl>86|qjPa;h%pm`bmQU`tTpJH zoB863-|S#@qpLMH27|a4{)HHA1#?AuEa&&jcvC@MfU>s7l#6V~AfBP>Sw_C$@)CGV zZ*_*KDHk`fyqSB#pf(=_s;j#w=)D!y)R0*)TU}Y63zwg7{9Y%-hfYkMQH9rbay^Fs zSE=LD(!a<^54rjarl;(%ki0aE0(swMJR!srylAB&w3PlY?mpj(7a4Np@-Qcrs(mvha*3#2pMBZzIW^i&Y-O`00;fASWDD)3n&{%V=xU@nlDuZe6bSKbY zqtZZ`j~*oP#D|$lDySIVYN%HO+x`w?F62;2KVSn^+<(3iYJPis-lbcARf*~1WpaXV zJ*~-dBO0R2$n)*fw4_Ni!j*y#!u&$V1me-CDd+gL9Pxu=+7)5G`1a>Ek>TepHL8oO zW+K{OKR81elRtA9b(WX5b4P13x*38C2&1gxaw-hdY?t=#ow5@SO(j08P5_w-VQEEm z`3|2Rs%8@-snr{97W$$WEyEwRJA@RqPoMHW*gc*p^$)b%|5(SA8c)QFS`__>GadTM z$?KJqtM6U+7)Y&at$yqQ}chCFMS`|NPN;3ZWFgg7i5)N2b?ZZ{oyka|rQxQan^qTDuy2BV46gX&x-DnD+o>2YUXyVMC`)R-_C3j6 zuq77LsRH&a`3wQs>axY=P-23}e1p7|nT6TXR#?%n-=*tM%pltqUy2fmx^$x6^5oumKL0u`m}wDy1Sd+zbob!@f$q8`6{B3?I z-If1u1lNx2UUlkTs=^1b@vFp_tv(^xsN%c9*JZ3aULk?|mIJ|!%W4wKzCo%v;JnZx zw=b#t*HsnJtM7j1bMVKkOqxE+lJp`k)2~`W{5aF5SRaiMobG^11f02mmk`-e$&+eJ zM@c198Xq4sdb|+mc@wAz2+eWuzqo)3(UWLO3slw{0jV{sGIw$JEipT9n%v)$AE&MV z;5pQ$is7TAgiO4a?7B150aj!_8n@_rquRFmZp`TMv+3@MN|6trrPSp~WaJ|q+1RH4 z@D#v{9c=vo-vfD07Ne?J+rh{>?H=FS=vk0Y57_0Yrbox&=*mrIdvmW$&FyfX^4zq* z2VVvJr>=9p5UnDgPHj0iy+msu4JQ2(!q{8j=$S6ifWaJR^bp$8#2$ zpV*q|3Up=4M(JXbX?ub1Fk3GyQ-JJ^SxhGQdk=|6o#Lh<@yW*FHD^)P*pAs@R^})m z{z&+Vi3yvB7_YTLSPDcfU`SV}X48jWNrx9VEz#y(%w=`;Z)!=rlxfqm!k8Npwavxr z(n~H`J91Y#Y{^9=F+M96{{1}-)tMcA`Y-m0(wdKY5%KJwescBqY=TZ|PfO72OcnO) z8>~vYQi>*))d1P)%2XbA&~Vn(s(+~=&zANr3&)0QGO>+VndyOLXDFaBBMb_o$d|u2 zwPtKT!JgIFzx@>H)%m->62o5Y3JDxEv+~Q102l3^2=vz?>!$X-EpF$?F@p3u3T{|^ zcoXmW;M@0+YPn9yeNXE@O7lC_1~41ePZN=cA5}M7EQuQj;VOckzoh+EBn4!cK(BR* zN%3XaeH4BIuHOQgmvby@Eg*7l8aLzYOJ%J~WkT61-7W>OA;7j)?kHi9c_PLveLS$Rg);l(TA z4dZ{!1LGrJ=f6ZYfr5Li;)2MVhnKj46Snxguj@(od|eu-aJxD=4O-Q{Ox=CY4{Gln zF#A4VTdT`*^${HenA&Q2#@U}cC9fG_OLhTMT0n_3mc&NpL8(iXN|aZUM06H2pr_*koXwtVn*YO^{E*!Q^9v~S_grpY zOgesy*@YYKLcXxOUo2QKO+`CAZ-4f+lrn{;Gnc%ai80zW`V0Lo4$4(VB!n>{`qV0S z5n|WplWZ$fTH-Yk=uR>gY!yqS{baL=utDHF>`0KF#}f#Yv$Z<`I}tU0wf4jMy-bGUJ0Y){ zzkkyGicuUq9==7;&AUGGDl-7+B-E{S`uvGx>?z`SlDcXG(dz585H*x*>*xvpA72Jh?vH-b+1qa3A9_$$WQa%bFvG0fDjec54&tV2NBmr3%yS|%o7yhJI zdCg->5T5ftT4;nT)TI-Eznn`|NPjb>wZe#)<6xj!ME`*8kR>$76Iv6E}|h|m`$746j4*oMYW{kBlDmYJ`@uZu*T`#M+(4U0HwEdjtk-pGMdG8Q)1VED zB^jUjiq$)3A?@7lA*j)haOFMsHE@TeUjM%Wz+|v?j)5i^e zk2@wU({Zcv!s}{I0@U}a$^jO&GkdEW0MhdAQ*c*mF4HGRul^Gg!#W2L*OLHO7c6p& zw|3CDnL_U!PuG6qV7!cpASf*LQb;DMu*dYw>Zv;5?Xzyw;*pk7@bPFJ2{Z zCO(18_5ypqhkoM(NOFa%CbkDXS)C2cZ=|XSv>5pCTc+{%eeb9;gH{v~Hrsc4puSFm z${7q_ekI1;g(tYkDfc&iLiX9EP@g^Lf5`qB{ojRQlDlZEK0pl*669s}1_2apa@2fY zzt>_O;1)Q23RT9u4F^(A2#CVXY~~pR_zmrNZWDj?_5`w#oK_{MzRaeEwRPW_z#UH3?X@x4U zN$H-}!?S%;da!FMIfF@h&5f9%|J-&a0C(7S8s+Beg2P(GhJ!D-Oei6RdzXS-ZRu)C zH=nVsH~%+Vk#S;`H)@R91maup%^hoj`9&)4o2ukB!adLxh6Oc=YXJu0@GpPtKf~GW zU|NIiewS6Rm`u>(%O-FLD5WYFj*IUZjJZOfl!$$e3|+ihuwM^WklOG5uu|2W;W_Vp zKY#sasgRTZZSFz0uX;g3J~?pq$bgj&<5)eol4ZFymn0otQ1>|gS^m^(fN&(u5bwtR z0_k|Br`u4eB;NU)}-l4{{ni8Hw_O& zHPvk*m1~PVds;ZmVI-wFrSB7fi~-ANj7?T)hx({fIqcwfELRSll7tScc?`GYEDs6x z$wn;i2n87mpRoVO1;$#Y)RA%B<+h_PmIqalxE5g`!hd=`am!MnfkYZ`P9vi_`SuAAmx@iqncYsA@Tu|bi{O_r02?Cl zulUW2ZV-DBAq2l`z#SH8_zJKAlMTX(H>%RhT&b zm$UnYZ4V0&=^mVDu@O0W?68ECZzt#g9>0Y4gV3N5e1j>e-qT{ISWhZFmb?2VlwIUgtXKo3|Uon z)uXq2!EnxRl6EWt&zZCJm6m*B{|o@$rX3c$M}cEZQZqyt$%~QNjOaf<)RP@mXZBt( zXIML1O0VW-GABdoWPzz8ufS&u9TnyZfAAI=dFL`5W31gDxMxapJm;F+VuuZUyMVI4Nt(PMNKc>#l&nB>kg3==Pe8b6OiV3QgaQE<E=v&1iUxf{cb^cio$xNug-?ZQ z24-US;~nX=lcQ9D;0%|y8sP@}AoF~xYI@hYRqU=6G)Y*)PxMLA5UKG4mX>&04#_62 z+2XN$T&nO3Z_-)$PN?-U{E~4zNH8;symS3o3`ZMI{{;&tka1WN*a(&k#QeRL4CWfSkgl5{-uji>z z6``4GsY+SIg9pt6CU2Vab4F#}eSc+~YCX`R6u1lVSBPnBi#@Z(Vw=q>8vlrxLt@>~ zrls(!a8jiP18#blfZlUj@+S2V(9C3yyz)ONYBv_z?k(p+hI-P@Ca0Trzh@YoA&fet z(2}f8zofsy^fIq|9S5h9I$PbuF{cK8cTRe zXNUzjTF%E|uI9s)mL5Axg`c5moj*Rd6?r>IiZ^k#pbl?e;6BXpS9tmJ))a=v`T?PK z2cKL1!6ljQk5k~%*&j415j>X!Dk99ZyvNy#wcsPY^7CjmoTrOsJxh+7YOyI&@T2)9 z4UxF2?RXojO>G{DX|Dxq_8ZjFm`I!v!jDiJ%clV2e?Y^#-9GQaVs6!}%Z@f(#e8Tm z(|9b=82T5`_EGaQxYWyS`zj<8x1NZ6QR|hQmmbsjY~jT**?h1GU{fdv@aZlbv6&yW z6=VaPu?v+RE4=sy3YcJb811iz-giaN*0Ye4sGVCc-tN0btV*_=vZ8A~;+WCrvGK

I~+KWUaP=xrc?2V|Ny_j!^+R$4|^CAKe z_j$>_d)mKXZ%;Wfof49<{_y3q#z5hxn3|*j<$zL^{B=?aOjmI#3!{jEa#9kP4+vY% zn?Ppl$^*J-?9Tl_vF7x8*G<$+TWWDaY3a6w9>F`7?27twL?ubmOkE42XHf~TIbr&_ zJSvc&sNw8BK(;L{AW2A2u+ioaKHd<;YXZ1Q6=Mq`j%2Ku^GQqybmmKIjwpd1ErS&9 zB|pF~0`}#-)rz-56H_0)4?Sd{#M$2p)%56vXF7NQGvJsngvkIBxWB{a-RGnJuE1ai zEfRh9=CPntlrX2b?L-=C4n4_}Jn(rdopRNm+}#@O?w%K~KwbF6y#|?C6-E(86w7ap z8Kt1C%qyeP(U(A*!F?G}$3Jhb7s@xtKkga7`~}n0Jr5z7HJ=cVS?!%)_WQe#pcb?) z3skOoQFd@}d{FJKnO81T5VR8LS0(|md(3wZ2+Dc_d6pVfxT^=iL+!DxC;M44F07NS zpRu+;^kEle;+Tt42F(dUJ>Dn&QP|imGl?IT`@PIw1ewdegO60INeCylps_E|^>nrd z-FhEKQ7v_~hp%xE&K}*w$=H~HL-R{I>tQa5n(>h1^YtaZYfpndla;w@S_p*HI!?0lbrvJi$Q+36JPvtTYKzmkSdAq}8AjD=QH!1nCWYotsozF{<`Y2QDWkp>Kg6HsfDGbEAtHO!)Vh*(Edc6C!KxqOmxZh2_?Q`ta8Nmrr_W+(y^?? zfUiSCu{*HaezKQ)hXpEsETE1IS)iN@4!D#v^SDoow4QqG;^&Ll9ZjK0OL{6teV-z6 zaqFm1;ArZSAZk5pIBHzwU+U+dETfBEUKmP~g6CF7pDpjFUuC*j;z*n@wZIXiV}=ac zyQiMa*)>|RJE?sHUd{OR*(0HJXPCI|H7Qd?(93nWz!cKIWuhtK(@{I`ueZn~bVK5h zN-1^-os^t%A+6XDzDEO=9h4D#koaMtQl7ve;3!xm!KZTSvi5-SUvU&Q1?@(hI(K4M=eHd<(u)- zZ;UVNpf`*o8hRM*hYpA?%kW%eCL`|KO|%Cm9D@!-J#p>`)>al*SH_SGmq8XHtzZ4l zV`WzESj{&j?s+^7W|7Qf!$&`;?|Q;hLO^G04`W5aR9P?{!r2Sol`yz_fS4J3Rz{#5 z4vMp1E20lqR)jtb5;)D~Qyk%=dHlt@cB%E7R{JFKzDus&qoIJqlV)lC8?wh?)eXDg z(%eKK(mW$l(@W&{52zqAFVU~|fjKblrjO`K;pB~`CQh)~K#1p|C%rJE1baq+@$W-I zDUVLV-Tlixtr>NxRbiQ2n+wVD>EO0qKbxd9BRYqRwXS;QgDKLVQ6(_#=gV&WkuYP} zrZMI3kPD+3P3usDxQ`3we5ne9xlW<7tXqAh<3%_O0pB<8azONl)wF}dV(NhH0`-ti z2G3oYI{|+@;djjrv}-Ynr=eebOvJYca3k1C=5r0eGCh<@R64~n*&-wz8zxV(b)sJh zzg5M{yKlg0@_p5QbDI(P-=K4Kf;*Oy)g>nAw8-I<5PbjV`gS3>NF2o7Jf#Xo*4%&m z<$s=3nn<_29OFc=!G##JX~K@#Id|ZhxGC^mOe#-Wl1k#c+I%ODdzmse2++3nD zEXa&?vdT2Nq5%n;nE;H>wgPhM2FU578^X2V$dHQm|5gR0^7|G?lpUQ@cPhEgrx2%8 zw_ij`9c@TWW7Ww|+PB<4d_DJC8l+$u8FL#%?{2dq@W`RBstI~}=m`}}_*YQ#nxcun zcKetz!!Yz3J6L`LCvE;n=HSh7VCPd`!$VI{yn9)}c&ChvXP|Wg?qR^IprFjKar-2s zS(>fpTpv#WQ+6W0yAXmSJF(n8Y0T6nNMS2|*J4?iO=J2KPY_c!_49t^e4MSb_AGf5 z(abk_ojjF{i8&WWyWN!nsKA-l&8anCFI3|%1I_o2U#02&K8wbDcptTA{hx&&-*hZM zIF&E|j=1SX&>Ak)G>5fLkgoerDz@FtVXbEVi9}h7M+h5ChaU%J(FZBHHJy8iW3nTM%Joo>y|v8E>g_w#YEBMDvv+dZi}sqVNA^PvbTmXX+zekVcbn07I@j!N z40xmU`UFvf{4FS^FM`eDOVUUSo}hWVYx+HmV*6-i_JJlNH-?fm@wO@-_H)lKz3=It zNY$4#bB#0U6u<}n8&RspmDLNoswnVNNzz8E4GbWdc#x7F(vEO2{#|=TW~x3)O1Mn< zLFJABZEfQ#anhnC>9mvTFMc zdGI_0vFXT^;KxAy-@V17p6LDcXX$VAJ}t|ntu?VvuV)xS5FJ*MHbjz`;@n{Yqfc^; zidx9ds)@Y)qzb&vF`#RIZs4ucCwWGj8~z23y*F1hdpw#~LHd~w$Hhm?s{H}qo+7k% zih|3C`K26gnSx#@L6=CCM*0F&CQ!101+hxe;X$(?nEz4%%SJtxV~XJ*sUh(*?o8$M z@G__(UjYrk+BMJ$~4s#7WPyx>?oM zK8+ZreHG=_Jp62^`R1YC^KybCF@m^Led?F=bGZmA-gySr|9Cv&?LQakF_EU- z_n#BA86FF-8|ZM?rmg!%ckLgbplza+BDZLHgVKpmadS({K}2OeACih7?l=u6QwS@J|TnJdWF zWD}k~qIr+Z`LVgVIYzB%bT7*&rcJYe@FYeNZvR>mgc>)RuL5& zYm*A*qO^f1fax=0N=g}s4kI{qT)C%=ho-iJje1~@xE zd%Q>A7k^h0FBn+@ujZd$0*cSrH9V(RZ&V=^2Nb{YGIvZTDEDmY=@PU(t*yn?*#UO& zeOE!WKcNS`I#nm}II+=~sY!oFQ?u)FgAr4ID^UPB(jTVP^nA2#&GSQa!&0Dqn{xR@ zSt~pBO_`^F#5fpfyK=99?_rZ^OVFqJ;6NYLIYS?NCWp86i>MD554Zy5&0+qg#4yn+ zUpGr0`Con1M*5f1$7SdVd3B=pqsaN33quXOaZcKV4qt1O6g#;)e5tpzzr9^n| z6TQbuWGDLy=+RzC!#9EO76bwI_&2|#TY_d(Y10fb2=q0+zFlD}QdXnSOe7MqP7 za_VKo_1RTpSDSs{{?qLI(j(Z*dnI(=cw>pj21CWO8jcS+EC#h$l?9c=dA0SIj~$j` zM}1yA#}fW4C+=qg@yF>6XiXz=t8mJ2(D$~?FB=LlZM-!R)-W3{Z)St@!HvBgV&Cju zymI{h96~x)!IjFPD}>$G-#A1z2J!Nuh8sJ3$E&6SX7EV=kBCERhixr^a+pMvBehtyQ5lzO|b9 z7}6t=0Y;Rw7IhVuD)i$6>j>o?b`!o6*q`Oah|DR!d4KFGr0WaegWs1`jGCo7i}A8F z9u0(d&R^UIzi#9re0{cB3l??GWAAr(DygRiYYwMyw@et8pr099dP5=GfANYBJyj-< z#S%EH2Gi8+FWzDb3s;d0?n{9wX_-dkT2{+Vuc|O4#D6S^cWCol$N%BR%QJq&3T2QJ z#g<@d`4b8;f>@Gp{^eeT8#R7xIk?us5IC85Z`nlNs$Q|UGRfuP`UmkJ!E)j5jY`-_ zsYjTrcq%2yazIrbE!4X2#e-r_<+I>bDt=ycHfs?eXgcgw#sCl8-MmaIAQhKn*>5qcy2Ya z_z~3K7>`dxOU){Ni8gtCs&4l|VJRd)e3vPI*__f+!D%I%D|@OUw)I8k)CZCA;-hc> zVyA@I*dku#2xRReiZI-EB?b37MDT8-oa!AXxm|OKGXhQ?G=#WWvyoYQZ%(40zY5@D ztSIL48p#Xo{N8+0?_H2ILPcM49ndgpD>HIS8BRQ=)JyY6B6{MGCZ8?a#(kv1R+Mw7 z>`B|KXpv9vkSXD=34H@<&zIhV)@v*cDKuV-@|ZZN7X0Tvdt2n=(s-k8qPJ$$RNQ<} zl&*-Ambho%BRj+c%zvcCZq#(cZ08ys;Qj_xbrKAVN2Wh=x^VXx^$`Chln+fk-QUT# zC5Y2hdXW*>dh#{b8TSii*qIBe(VSKk+iloe(jA@$nos9Z-(Q&v@pC@EQL}NM8Zlm~ zOCym=?<&2oFgT|pWP{4$Enc=}i2+!j_8Gk=ePt)N_Aq${=H{bBgiehWp!u*YJC|26F zyQrUZ0&cHqGKC3imZB+j2xn&(YB+|E#RXg6x788ttCR-pk?_01F>}J+zDTb0Qolq- zb6xhbf;3R=7X}c>gXVQ`3Fq|g|L?9kY{7X z2ZD&bU^IA$?d5}k7Z@~Vn%2$LzKWGUw7VCNbgHP?}C;eW5JC#G5LHB*?ZcJ%pU*euRH@&TF@PqQY z2@X0H<$)5Q> z{L#1Bg`x#%D+!6?@f)m^VADITjF|f(%i)(tZxR6Z&Z430`AsTuSg+LeT zlqbJ?@v!-hc<&`si%lKnAcjM(feGYX3GRaov3q}{fmOk>6}yZ7YLAca6={?7lTPGu zq4oB}@|`ZuT_Xu;sSi9mdL|E}p$ru%GfWh_+G`GNIL<`a=iI7tvbY#|jj}ktXmp5k z&3{Hcc$AwlCH=cqW~i<@hp!T^(rjV113iVKE`ulTA^C|_+r%}rJd}*~Xm` z3|Q01#e0`L>3ZfbrY&Y;EJDALACk3yjv1Ku=+yEt=;fYNbm zvYCyfQZN)mugf-av0UesJW@ikpC^&WD+q8wrRMixZQp{rxvwg*5k+DoQ6mH;?fznO zYFuJsMIvZWjVTQo7v(zksv`0IxV4vr$14i(Kw(&*#@v-lzVNN-OscqkUB?-R`^fv} z96~G^(!8gZJWO+53%NL!QmRYM377Zr(dg-xab#x)$l#05Y7EoRE9$1}oV&e) zK!G2DHJX~4R0|CKUKH`w2++xbRoj{V2tzu+@?@!-hhoVd26*RpfHvV!8$}rOWIaey zHLRXcOHvIx(AkwTZ|=WUQj;j&5nVt34*y5>4R&5tyX#1rsKXy7UlVD=+%2fJj!)}c zO{mY^WpeR2I=;~BE^$hOG-6d|(j1aT%j*bFdLHt4mTD6CCody`bJgib0xe8Qy2Z>0 z6Xndds24-GcP&S0c(}S(ge=~B!QAloxUfjZqcd^5LXdUU=SjI|DrI=1E;d8fiJ;*T z+(LXr`@2Df#f^FR;Mj%6%USyOcr&5q3Q`qvO_P=OP-<42mso7iQ<#jFD1CUXuo$2F z40WuEs3$mdeg>=bu3PbT_%Ng^)PLRXOxZ1TK*-i^7Aa^?Uo4HL=aD?wKJxSDJ*#I4O|q72w>x=h3QHJN!sSJ=>^TbX`BQ#5Ci2_`Bd} z|HQuQYTBtL8sOYP_xC82lfz zO+KkJB&Ka$0m&gy$<`Uk8H1eOYm+OoaE-2y)zDK(8<{188^5Rj^w9w#@6l1}!0_RF zp<$z~3_iRX0;Yuf(~McXbfI$$%_Vvk`)OF9ZZp>bcYS5h#NYWmINShyt;d^_1bw4r zDahRRjWth1T(nO#11(6J`5>%AH0;*=&~xLG3 z-2~F-(QmcGgPb9ht3eFenl7E#_LN@yT>_XZn0LGBb7X4+HO#=N!I<@wYA7L%@0?hPVxJn?oSDP2Be_Ino$UU6P$6CHDJ3%KJS;6A`G9C+`Obqkiu9*r$Dp{fRpI^+xo@ zCBIUOqMZk&&WPjbUF&2we(Fi1KH$SYx~3pgWPhkZGb87`TZGwE9;E)oVXt{D14vfu zUYLsLY^9t^iWenf0a`-{%D4dNNPrg}Yjb(^3YjAP>F?$$4IqswgOMFdeG;IPDqWk8 z)Q^9?A0${8H=RxBu)R&`603>{u_F#VmzQ)^<5a#ZBO3vCar;Zy5UEQm zCgXa3E{VbqLKBzK$CHhLX6Fe=^~I<6MYX_e|JcnIN2l%fXV$&OA z=E<<21O{O-zb{LP#@;KEwcLJ)PjD!38ihM8)^Wct8V|Kn+4vODb67Ck|R+`R5$}3u>L5pL@39$;UCUOZ+ z6?h1&jBT#y$0J+$xvg|@P^VYlClngr;h!AK_{sErY&R-I_>1|)(3;OH^PYToz45HY zUxtjXoiS8JX=Px)mzC%)4;vHB6x)TUmWS?f%Yh!Quv@ah`#UyHfY7bfX47|XMkaUh zPZ>Lzn?H`prl7ameulf^-`Dwu<2*s zqp!JpI=O$NkN+e!K8Cd!6~sCv1qky|=#mh?QG< zTZu1efGzKzSU7h28d)yse>rhNWB1sE^)%A{zobLJ5}lds{8Sx~~}My)pLuA*?1Z4%F$z z@LWVnVj1y$X&Q%KMXGyHNFDTC`}s@#s>XM-z_}fIdbg5gV(|E64H&(?#f?Dhx6o+l{nT5~r*tbJ2ys@2-Qr}&FCk8(XfcWA=BhP>6KC*w~3 zdhhkyYe$u753mLA@eT!CFPMN|C=~4M$s?%4dBf+3vHSjw=#>sPvj(FU7}nRu!St>? zq0b!h66esx!cDof#{IZpM%^VuS_rn=rfU3jpT^Ug1%G~R}_bv||s z1ZChqKU>vUnig-QjUk(|S{=@LEEEx@nx+3qRA!JVR{nw6QPow8iHG`(ui9N4#RqBS zwJZAK*tCB$)pz7Z^N!$?daf%0+Lm-D4V8>nio@8}$kI%RpBCO$$Af=q2TE}qbx35T zd*U_tXwudou^LN&)?rKV3NWss(fl{^{eD5PA=*~cOX&ojh)DV*RZ+aPV+1HsT}epm-7CMe*+{dVrAImpc|7nYZzGZ4FT-m~Wp zBuev1%{jk|Fm2kATRCAJTmR@&6uJXzhWV7^*9%~pAlPpGNs*(5Se{u@e-DM`&4AyK zL>;`!wh`=I@OiJWm>d{ip!}9!t8G?md!fOH;5V&k(Y5y^L}wLC|8iXEP$DE?0D98( zpQ?!sAIdu)&-3e>v7ijx%{#BGmPK*CDb!-+Uwhu@#4^s_u9K}X(24Xz^WCGvA4ued z5-CuK2A8;Z9zHM9DpQ$h5iV)Q?rkmtchKW%yHK{@Q2 zFX0^zLayyJ*lAj5IPSSqegR?`vm@4TM8aGO>=>?$2xo)JA`Mh$fiE>qUIBG}R|Cz} zTARoa6$2kei`mxMifDui!=%(%u5QH6>BBWq{7ZsUm!^Vr}UV z#T-kz0)!@Z=t5}Nzo7=77~|t-w**p;JVI2O!tiwjW!D&5udR2a2yijl$;@?I_2*-E zlckaOeM5Wohbfa}s5`zrMKf=>Qm6&V!G=W5v*qIqY=+`IR=R#Z+^s&~nstcl;>Xv6 z;uCzpq>4n}-;5%pqvmRe9-<_PC)2`qPwV^9RaDN#`A}V-Jv+#1!rKYgO>x?cK0fGw zC+oEVHGN#(z;VWh*TA!;4SWpcRE&sYO9oWVJyepGs~&88;+0=`c-T6oaKZUT79V zz3D)iC!c8GxvlMN;bTF@-n&mh@lqMrZ+5S9e5-kFw5Y8V=68jv@hX=`xhKLV1%NAG zeyYQB8})&Ux4*c+bG=+KI%V*i6mNeLGgKb6ZpEaw)U z5@f0aw@R-|)J!$H(!o3lXU8sDA}amN5US(^E^yS;n}FOyiEl;)`?GXulVgD-r0RN+ zE@nd~*lw2WU}ef3u?e}85iywaX-X>`+qYntWNbLyvbfP|bL}Kgm_Bx=U~gGD8BcCf zYsg*W?)YGZ-JcjP<^5|nft(>bHdT71iC4i7ENazeX;%hnRd!)JVk=^S9I zowIR9pvL;tjWN^O){uabfVFoc)0td@3B^u!s4(MfWoV~i>v%E1|S1#4V zpgjkm+Oqo8b$J4TUkBzweOz%+52uoOfwPhBI?nkyJMvPdlL}q-GJQFZpl;KqFB6aV z&*@@=lt3rFK3dM%=e>Yx5e3TpFVcUW4PwDvHCWpAO)AAImf$5i{noQ0>HwhlWXAS2 zQBsYKJ514)Yne!MmIPM0(+Yi@axr{~A*GD~OFULlyya?jKl`>!0QI3?>fLUJ4ed~U z0j6aFWafGgGH4Y{{jMAAk=HPgb=z^wb6&n^7LH*u4GB9yB>imjsxYo@+o_zZS{7LP z9r39U5zqqT!|fwj_uO)r=m~ds^T9zKKMefgY}@M)!1IkH-2Ht@u;f$J5@1D{cOrc9 z>9*~fsNf}IB_**#2&a^}xVeec9NUsjT_Ui_S_XoW9f5g((W`d3mO1x2#>8uvaS=8% z@;&1<&gjb*n_)SfvL8bn;jxz;PZ$9Bvp{7@mK}sC_ z>c8g8hRbW&zr_g2k>vu4io;*Nu)>WYQNb1gKhz4Sz8ZZ=0ckZ%Ecp3^!X*mkB6S+O zjW9j)%l&AgzloJAtp1GI#gfjNJ#zez;YS8}i3TVi1eIPQxG+t^S^R;~&wG(H^gRJO z52te8?_&MD@Xl8r1}!9Nz>?#@?p%2!E#Qr<4;GwISpnErdr%@>Bt4LN+D~WVMQDPF zI#xjA1MI|n{{kOTvtn%w6l41-uCfvUPOeO;o)gBHsDSWy&jb5CCn~#^(;nXJj{Ny( zQ{)7XEv~e6;yp@$ps&l!g}B?aPdX0;B@{Dha-rDWla&1bA5CW+*5v!PaTOJi7AfgQ zx+F%&K%_*eQIY~mr=wItVx&k9kb!g~UD7=mNO#BR8Zf~3@%ua8e>gn&$Fbde?(4eF z&v{-!AC6ZA4H=2KpNQJcH~`-$_nModu_c0}IACQ7)WuWO6nGV%u|r^-&8&L~D*)Ov z4a-&~1HJ@72pelYM#c^V?2bvbT?Suq-|g{1Rm5G&+JwEUVlA&+inV z#lRfX&F+f$s?|~+aS;L?)XC>)!3t?@(XvWGThn~wyV~;pyQ*%ce}3PK*5ivWw#=$z z@zPbnl+P%!n3JV?%6A87Mw7St4QUKuvT9&9EX@AVr|Gj|>Ka!eMHGFfd z;ZjM_Vd7Jd+hudTzpDeHJ11TpRBrkv~K5*CG2PO5Mum2ra?ez+n2|OM>2FK@IWCkhz1?_gcIRE_ZitC+kXF`4ev# zu>!l7+k}YTZ1@DvKKFt%3I|xr@ZuBBdnDpf-_s6b z7u0>#zAqyQHm0}p1Mvqn12dL+!g(z2)$BqmF3UZ;ly?d{-^=DTN1SM8yg>F8mrw5V zl&Exi+P$Mp-YQSz@^?^9yhV{J}aJ)GhEasa_ULMcc;BQtUbahpKh0RP9 zr>)_|2xDa8rq_g5UZg&DWdY%sRl9(qw&r>u+1cC=*Wpr`+O@W?-{ky>bU$t(-M2Mj zT}=BD>)jO?&(^g7mpUN>)-g*q$sV^yX z1Urp{s-Zf%WX6kW8bo4FG2z z|5s1JP2w3Om%;A7;96jDax^bTYP>pD)hv0e2`>nK^VP2~Kw8Q-zL%~Kq&R%;E^s{8 zT=GTSs0sTeV?C%zY7kf}hq>4ucrug%8=Rk1Ea!6zwPj2nbUzeA!EeNdqk22{b?(XQ z&zZN{^0zA>B;85IL{`qbqCFB=lHQ|CCZzQwTlF6GG{A8T7aPiYqe%PR<7}&LfsFeq z^t)FY8VidG2R0TxcLP$YdcHQ@njcgg0Oho_hUn%zx-xwk>a-84L#5}<%$Skr(WD^& zOKzv+e2QJ^jQ_%~sl;49?KkEaZX3EQ;mq&(K}@EhV$qgQfgAu3Rh5OGZo@JZ1)sXv z2&Es`@>bbU5 z{bNrgF=M{4sNi@$=5h%jO!&u%-`cCZPn1!CQ}cG6iNKM0jkt^}YAmNxoo?Ch;2Vj- z*2M`JfwJuQxviepvAA`aNV4I!0G=zLpCmCG?|^2DASP_bwHk#HmrO|`T$m9-RipDj z^H)fWga+{Jq~=b=ZCv4!tySFP2UjVG1LpZiN|7Cn$toCL)yjhNYK z`Gwb}U$z+#AjALXYKXG8Kd5{k9@OlS^(lbDF^@aMVxyGmS?WOlI|IH{PXFvLcLr)q zr=7e5u0XuvA4nGY&r_?1{eO;Ql!J&J#dX!cO(Vmnil_3nIF~P=Y$4$1uI@4F<0)GX zw|c)iE-j6>{lN9lfMdj6HCy-VtRrmWve&~Dw(m}ZF5d^viY@(wf+%NC+A41hu$=St zCN$cPSRP<9BDW>-@~|!~CQhpC1Bz45rk|C1GKnSSg0UkPw0QNR!M@G}YjdRM&V0Ww zU;J&_9+HLc9f2pFG9s(8XE}LVPb)7;F`Z=GL3Ea<0gT8lI4!1^%_aKPt-B1 z>J{wbJnEY#@`q6`Wd~v6c&fqpFsV zyR0+fYO;I~%Jv(59;hQ@#b>0ptvO@GooklIpZoeRrmz}~0x*bbp^LA<@*D%zbo~}| zYeiSf((p-1Hun{X;D9bOchDnW$?|9z4#W8aq3bPA_j=$~)rq zH7eC~E7Esboc}PZHsSB@fKJ`tWZ7a}7)1QbaI8I(jh}pP5(&mOP5Jxr_CO&(+84_{ zVIZ6;&;iM)`IJ3%OzK$m`JC_S;>|r5+0lm(%0QFv8Mr`MoulmTw!aj|=Y`YgE~|Vf zLvmUwpBE{$$QOa9zZA%0GtNTn`w@my1=wm%hb~S#dER!>+qgo zqQsqvhol`^nZ6d^h&58`y1Q{s%bxm%)2pHftKt%pB+;=AV%)Daa(QcZpYEw<(a9Cz zmJ#FrK*`!iL=~`gMMp)nEV?+p@jVJoHE2`Dy3l1BVwd3=e}Z&nO)dITOz4h&VZF%8 z)3HW(H%Fw4W*49FR_0c`;af>MGx=>(Z-!#g%(4ujm&_ZRhfv@ptt0ApJ=gXf@!egk zw)0&wy#egZy?&sx!5&$+Mer)*b4e9|=z1z8^|>>u%mYt38t9%Um=on^WO8x3dv|ku z>YkQ9=Bh2g*q{zLt1j?a=RJ;?0|R_dKZ##N4FjR>{<-DzG|Y1XMEleWG7Nseoi<7r z=+98BXHs*p__2Ip9Ge+17ka|Eed%{Z#%P<7?ZpXoiHWIh9S=Ecj1M-?Td%mxXKhITz|E9`gFrAtndKmv25Nju1mSRA1DvduFt1QnPrYC?NHfne%Ay&T#%w+GUO zp9C+Xx&ZpGIK^cl(%ui=w9}rk`q*S|9dLNuc7J?@>UWKR5I3M0IE3R9n0LDfwwh$) z8zcvA->r%2^WKqDTGX_zad`rv7;;YjIJ_81+$gl3ltiU^G1;caFxRYeq{;COXL~iM zxsJeXP{E@qh3lQoOXWA?TRUQz53}IBBntX;8a1D6PE5%T4kG4G{pK{shJoa$UI9*D z&B-p7L!Oe1kIgL66*FUKMwNvFv`1+|$V=4=!NLfL1)_w1rF!RH>R8y8WoF_14i3Ed z+_F;}qbm(eV1^#JwKv(B+|ohUT-mP~Uv{nSYKv~`!R-jhbCpR$g0m;srIjyWwQr*k zSNo%jTm_f6*tIO3z22&lg?OZAMO&omF>LqUm`q zE*~0v1knDFlb>8~=vwa-`?BClE>NeB!M&wFaO>euA~tv$Zmv%+6ev=3U9U$ye_NVN zxg8>pl()v&7z3VwqvJJ}YLYz2H^tmt#r*|;5a)XZZVnk&{}?9NTqWEnvWwxjp5J=C z$!<7@%q~^TifD;bBcB@=EW-H2?N{+XrChtz^apM>UeIl^U-fY zS+4V6P%?Ra{*4D;u7v>?B2vH1(~z74@!07 z-S^CS1BtMEz~{^t{I+l`&o?aiXURj2D(5Rte+#-(~kZrbXY~Z4V60v@2|) z8T_{Cm8MIbh4%M2AI|Cgs7P9a8-Y==~OJ)L5DO@(CVqBuj*M_(v5!wWut#||B_4!N@pmh zJ@xFOO;sI3yy}#fSvS4L`a*KQi?&+ig|&XdV+oK%o3%uCXUm zA~z)Tzaa?isSabhzeuy9M&-um5 z4|j)@4vbh z<|ZB7Ts~&0=grj=G+=%*sX(od>MmX?>+i}4)#_Q{cw^wY$dpvbVwP-P#FA%1H7O3E zc$;azwWdqM$NGj>O!1ddqzF{voo_K!Lr?3IFHXnH(z5B3ANA^yQM3L&l27hz^>q|| ziqBp%_`u$CI^0p8ON6B-xN`@SVu$0I>Gb6mTGo92$>=lo#r3p*i7X0k^2FeEYZZpp zO$(R?QO<<|vst*w!Uvq291_fI3E&&}JXe=24P5b=c3O$+82b#nfO)^G#x@(XMelra zKE`Pp|H*o;3?%R8w<;^bcRbF|YMr-n5wb|~2YWvW{14Wv)2U1^{a!Osa){hF#wL9c zdZBDts=!2l6X&*&xtu4{+ z=GU8(eyz~6aID*htskmpzCk=qS(!zjOVNCsBgUE55WI$onA_5$_{qKl_{ZN&X5#ze z#!NiKfxHCE(qmfZI4x7To|`6xmDsx3wvqKP%)C7i2PzBjr<;?GDT_GG=lzPgcF1#l zF_Lq@*#|!>a3D)6#tYfcES|p>(iTTFojbW@;QHJ+D7)jtVBL7Qr5nC9a+p2)`!o}O zy2%bX^Sc(j*7W%W)5Fh8PtUMrjb$Oo+v%Lobz1+136I`Pig|X-&lY-Ow;^t20?NQ# z#H~1B)`QI2nMXzRAe4?Xz?kg$Py>Md=IR4`j#554D!Vu1mA>)z7yskx#5e)ow7m&@ zD#;y;orgyrjrmD@LNQ!0NP>c~>6E=f%)9juB;JNUD0_3WfG&}RH`YlX%*(#k7VF3zfRIQ1mlg6zKyVDSJ^iI<{U7qG@UA3pn zaKBg52|Dw@xM3pnCXpYoaFGJ$n0?p|-TkB<$(3K}Zqc^ScAWILuWA-&z?)~=uKW2e z$+$_r<@*y@#k%7Bw;l|7^gQ1QC|sY z?GEyUHJpS1t^tMe+t_KX6v@Tzy;*6GC?*=^gxMd{x137W@W^n0&->!~8}noH(uKh( zC_RuAe6b{BV(`D@dZ&54nq&;M4^s8VU>_*BejP$$*s# zHz>Q`H5KzD8`j*fZ)19hisRxC&JXqfNR@8Tb>1b~(;5jQD;Xyp^ey)yk^4&6FTr^L zls5wJ=;@8T?g4hS&#w`Z^Yn6N$ncFecURFaZ{u(&I8{%d4l|qtvp~XsB(J@Wkhyq~ znBD&3aPz*~x#_Kpn@6&bW9D~gCz^dJLP8}ZeB<1B^~LuCP*B-rD$`B8%s>Sx#rIv5Q?}EUCo)xt_;jeAlnA z4Q}|j!;DSm7Tdxza@*Hm*%nrhPb&<*+GRMlzO-)WhcPM6X@NgiILcSpAuY|1S9&Au zobvB+7}*lQ#)w+J*(Cv^444cV{Xx6(i7s1OP8fxm=%i5hgIL-wW_7^Pq(kFjb-4$8 zd0$>ByvvDbtkrAmr3|v5OSa>GFEwc@nnb28f`O`suQ=1CnJx9ikv2<%wF<}sdXL@3gLaV31(%W-sQc>Fgr&F&?ta_Yw4}`lquW`_C$(0^ zt9*WY+lZK=bkoIy->;jjeJqro@zmzWA`QXh+7{`lt{hp{+^iAa!sap~#%G&wf9$%K zY`9C|8spCp2$NVonq}w}LY)?4M+Y2R+571@lWY>VYc9UZd8Ibis(x~wb0eK_9{l2v z^oex%QLAS#RSXzk2ciH<$Q;CHhqTE$-*)6C-0-ID4VhIP==5k;Mh6WvWzfROu^?QD zf4Qhg1#TawUGMHeD%pICG=|zVHx=$;lsUmERvZi$cz>tmPU=+I8<{I6EI*_HQd`Tcm~4yKNNVniQn6?Fo1PjkoM^EuYa&v;FXD!ejv5&7zVbL zMTUeAx78eTkeS80Vyfl!L)5ey2&azk&z==#{g(QHPPW~Xo~9ginjonJOgpDR^gfQb z;DTAP*R|(`iZx3`A9ji7+3JvAe{3Zo@}KMg#z&JTl{M+y&GVe6^bbk9e>$Y4tNNk? z?7E=^CJ6yARjc#A!s*-n9jAFV-Gj zzm28?8Y;!_BtzlZe~v5|DQ}|b=-bUI?}XNnH4Uq8^ay8F9g#yJ$E)AcyYsKNUF9}e zWqXfFt*6_*QxEn;mj9J18~S~tFM#}_83Z&0(UN%Rg@uE?F4I^m;*FYTb%Qty@;lh+ zWTt@2Aob?8M&KUBmJsxLR7oC9d%;vX8%pjaT&|Br>{swYg)~^029#pgaeuBCp5t<6%1NhFNSy73DlUkDm5PCC;~Np1~T(+ z`Ed7_E(G8qLgbb_trQLhhCY>p9*GJ3AWASe2R6tRFWejXBu;YAyb%}u&UKT2x_*|U z;V0u5XBSF_%1k%6Zhrvct^BSP=a@xPLpQ>Ln#IcK^V3J0tMc0C%YN0VK|4S06_RVm zkgveP_6e^ZFe2+yn!FVptsuu5FNpZh&F3=(?u($lQFv?K-;6ZW&^|#yWuDUg_~7?X zyJ9H;nkj6#)3F?R*!H&U;ltNpt3DJnXaO)!4+Vly9=jb>K9Cujqa^&lYK<$y1?2e5 z=N1G7+b7`nRe=uWU1;CeO!kwNb%Oh!7xgt=!jqnw3w>9rJpJdNr}w-8Q%^6LxH{E2MK5ekhgdGUfDAu*(;3MD5q%#^u3QtsJi`hligF}|LJ*S z=(TM?7AS+I4+3S7SWlVUW=H++T@7e2Gru;Y%lu$!^r;}N%jbfdGwqcXH>HLxPEmUHk{(408ou>dWQYu!Hy^=?bLES2hokZ8xi#R6tCj+2#7W6%2>mog zd$X+9x5dqlY2l0Cbbb>-o^i7Kk677gt>1*0FL+QjYax%NttG0124w70)<2s83h|V% z4frFfy=u4EO=WC?OdxC))~FUx=Nc>?-!ym%dX;c7+<8*j-u#kGmZw<%8KNo>CLFv_ zh>Kg8>vYd&eul^YPR_e~{_`^*!bVJs#i45tA*52lv&*F+$dhGhI@&OS!(~6M!2s9% z*aEvdl9g8x?Q8khVuuLHuzQ4#|IY&4Xy}3yWiv`SK9u#BiNOJQlI?%~9D}nB%~sOk z)sq00)Y%^J7^hU>9;Yc#@_L-jswc!+r8Zu3gWW56cY1OoHu{e3xl_kP5LW3gQ1JES zfyYBZ1KB%^g%2PN`hMeQyQ0&=HtA>^KuDC`?V4W`NXv+nC9F9wteVsjwRL^wQIdHI z5qr}FbYW0O<&%x}PB$~rJlg9&i@P7_m%u0H#=qnW?O4eh=l%Jn)KAL#dQ!ApqQqCy z*83vj{Wu!l11d<43}W*@ditTH*!_8~WofU(Wc!FzEr$IC%0T+#T27r_${{eOdUuKx z^OLgI^{oD&5N4+(9=^D#T*jGzHvMX+6-_l6FpZFuF)sT+(_yFV`1T)(1*GRi@}-Uu zJaks=c9muJGlK#X&wYQ`(!#>ah>za}l~ey1-*nsl zuuC@6f3%0W6<9^PO0fQ6HR>SgMOQmDpSIF8V#}eVX&K=xc$)i9)i9{n0}Ij(TEsuYHn|3 za4=WZ6-K4gPBN0zi&oRYeqXfhM+S^i8q_NsaJI>;=Ik8LxL_@t#`nxyd6$~ck0 zq=vSUJF?M)Z#pc2BX;tj_%J{JUJiJoB)Wc4?aT0)EIe;khw|o|)B4^T{es?;ecne9 z3ZPhcm9~=4ORQ2oQ2hwg$Sdw#4%iUm4ZoB*UCxa~^erc9(_c-=Ho=fZmN9&uhEC(u z2GwnX$`W}8=gZeNGW@c7aTFZ{Hyd{u(+>tu;ak(gnTN~p=MXtutc;=hi2yawF3cUI z;?TwHw&$FRG9uq5`+r5{Tzm&n{k2wvnm#ybs4-@*46&sdE3~QL=Zsvb~OD0`vZ4R0Doo z<*ae-EosysH8l?D?y32_`IP~?9x-pSLX@8}MBrdN@N#~w^EF?!L^vTJ^x~_@SPP-Wea{( zUF@$18n78^RNHq0F6s2i(|-Pvsuvl*ZeEg1(7OXfGEgt%D7yto2NuZ~)(+Wkrf#Nh zbG!HUu-EPFD4Y{LqW2o7|__=lj)Y^ zXz1z)aW~!JRU~{j&^?oF3eXT&V0WE6@x~KZciUsJyW=opTew z|6c50tm)?k8n`<=K$VBSHk&;No7vyB=RBZ6naEB!>a;cr)cQcS4SLX#1KLRmSQ$Js zuHgaZ$p>b0#HHa_O?jz-h$9WrGL}}OpNGJ}g=*d#k=t`+(B0sPsrfd=m>!qFh*UO3 zO(QG2R+fyk!v&3N-g*Erqc6}(tf?4Q5E@P=aQo3t`Q*xiQTFx{mJ#2|_lH|IN3&S)Ij|JL4zvs5~>i$6B_~dz>ksp`mS6Em~FKqZlO8%=up9g)= z_)}8l3;Bvo)vO{$I?d0wdHT-CV{YlFOilhY{IYuD5l^ytv{C%mzFlHCkH9k2MT&3a z#7}}`!1y5ap1jMKTZ-YnxT`vS6+qYu2F$dRhwFKHDy#x3qS~xuL}s{o^^X9V{+VE& z7kw8H?Q07aQ3u%_ep?6>G2rw*lg`xtC%Z32Huuzx_xc1k>^%JYP7tNZl8MsgGYFO;c~ z$TyUTq!6kauq1q1H07fiWs3F_3E=4`RR#uH;iVZLlUcyBooJlF?0ZFs`8lC{^7uwM z$POhv^~}~+7y*?-n63z$Y|2+7-5VeW*eMPL{hm}!&VU^~gdH*P05qf)uT?PE+LoPj z7Es*u^lT5i0d`qk7I+PzSwPzNOo7o!%@skDu+uJgdPf79!Ac4?W@2PErQklfBifA+f_ zuGF#TsQemY09MYRO&3`C;$k^vpd- z{}kLxh~VqtZ}=^v)U1R*WOFpCze_M8pk=V^PzyW&9(mszS81arncD|YK{w$}Q?NNLE;71DCMTpnkmz&`=hb*c43yG&1d%}*@PLVb4&sJ{L`AS%I z3{67q?j~r~5ho@|%ZU=%|+!Tz(Jfm%OLV9IKt6TLb zuLqIpddg8q9SM(;8043fm$P|@*k?g8{yLIxgA~{RnULK@o7_(bRoTnc|EwsV3qTe9 zF9N>>h9d~n`Xddb)t9PBA!(0_XP*r&IGI)Z2B zqkG{Qz;VvOG%m%+7=B`)@{tpQGc3dDXxeYgs%d>(vJCP`^Rq5vvz6@m&nsrKBrvmr z^IPB2k*r332JERP?bQxsX_{}X^&1N3&T=h<`-sK@Bj9e8z(~>qfG3NjIZ^U=Fyiy(QuFC%r;)TDzNV9I`3f?e>nlA)Z`!*cR@74mOXLz!| z!EAnFA>hh00%Cst>@ZS|W)VS0#@4FU0o+;M1_3Px@2_SQX20HfI)q5A1RVV4o7txQ zuk}TTRR(};hD+#?V!eay^Rxh(EU8&-7O;E3Oq>2$%r^iqJh8T{;kwvP(Qxbd)!u0h z3~jw+vQ^c&P0~SWg?v^AA-CzKH z{n`#4PuW;|(M-ax*Hg7M`c)d2XZ3K`$lSN2mgRmRxTs6<~@}Z zgsif2=_bW34MivWMkls1d)o27;TF&syI#A z_bt2CVK$bQ;*w(DjW6Diaz9F_goaUG!#QW#XH8UeZGiBY;~Y<eu3!mu zP1P}3aq86j^GhAj!u0EeC}EUYc`UDSGG*JZu-WVph+%?W!8n`x+x|9ADydXE~Ahiw$U zz4&s6HC3FXvab5NRENT%odD|`=4WEf<%)*rWQo5gEM5oo2~@($nhN_#e7PC~yhc|I zlL5Q_T>_w&{GknqLPnyvqK}b9@}c)~AiX-xQSVa0X#0?1;WF+?6AtdAg6IeGDNK&@ ztop$=f!>?debLV}=!OS)1;+Ginluid;FJHdiGBQwosz0LDQxJ)=1KiPSesvqw_YIh zTMq-(l}CoXc9XxzM_cGP&RtLTGWo)Cdw0t-t_rETezb39DaJw|9GB$nzT;oy*j~$a z)$kts{F=cBNqR+Q&{OoarZaZv?MFfT2Ag6lj*)l~5 zh<(IVkkfe0c!68V?NcbG!7fV*;-%Jw2Q_F6s{wj1h2i6nM+q8syds(@?FCMXcJn5O z+*jH!{i1SMQsbGdu%$4jl9ztOUMc8E?k+U<>g&`dff4sVrDOfsMulN^LKT8vrF&68 zOS0v8x8Tt-GGrEhawchDFaJgX0qr=+JSrO(G8g5BLWC{#s#|`V|}9R~#FP`pRFUQMCV2-Dh*HHe|b}OD%Qz$DTh|&k?B&YavCyJFBTZI%E+r zr1pAp3=b8Oi0t$UBhr1GF*pb&ZJ0TZv9w9;a-{$Iw^ZE?!Vln@cHf?HUygEv6fZaD@d=Q83g>y26gIbhWo|XhBm5~9(5X+ zG6uxF0ne#fPn&k=p&7|U&_>{*U@8Y}U5{e<*MEUE@#hachX?ElYVW5hfGMy{ z0Z$GH(jR8GDXBf}6>p_96)J$|nKeMV2Au+tf3b7b={&Wjd^---82?ER3`9kRl`sF@ ziH%Sr3kn?S^JRbm7&pL>Jx^8`#w<&J&mjKSdO?M5OeI#Y2LTFN0^rd>lsG^0w&H{+ zO>&&i_1=KpnYi24v<+&B$|GHYQe2WlH_;YJRai`3Ib&LLnD+u@aw^+wVmxC} z5*08`j=wR}J$fZuWx_GNj>Kk$PYWwM*1-S4)UXX+OnT{AJYWaq=iePzk2dyJp0of8 zTL3eYgd!v}v-zufbF~D$CES1D#Dy7g)WY%0Cx+ZdBTR)+Ce|qJuRt-s`!jx$%oS4; z4EwdO4hz;2fB~iDLzYf+p!WJT=Wg2hKAoUQEZh}q_)ZKYV|@Kqsd{n{9L=;}RC~w-`yt1$Cw=(obmXY)V1^xrMnjTa-wLZ%oT23m5%mN8IecLeMAu zvyE!i$UkX3Yf^aN>%VFBu?Jt36E!o`Pj@W^&0E~hCK2%~J=hR6c>sdkzE{30x1@mzZd z+AvagZRx8P4!f{$tBpq0K6Kf$_meX>hgEY67a4N9PZnNQI4@tAY@5!c8sgGwyol41 zMXe&}EM_ymf(W(;5)Gz<2!-$4qrx1rckkk{F7=0&D6R5}=c}lohH~4KJyJphY$Wo* z)=`sSa|(9i8TCe{9{MLWgAKMBw5J_)NTP<uZP9~-uvHM2D%$d@l0H`JdVh|swB#P3 zD+9JO3s>6!qdaJGznXvuy}Sl3#5a{KwF>TbK553w*;@IsGUdb?oLmgF<+Qp0!63`o z+y{i23?3y#g|BN!<92R*$8mE5qKM5n8t0)1K2dCX2D|O7<%-AjHUKz2q9}kg_OC&K zr@Z?56p7-yj5D_0{-RP^P2jq;PRDILEm`l5t(Yq;h_@rw9a{iK#N*H_VIaeW@H!Gu z?=Ss~0UjA(9X|o=PE1MBWE-SM!`;*pl1pKVfB+E0oO98%n9Z>IdgYz7Xh~GT9;lif zhIAA;%~ll5Ox&XQLDkwWM{hp2{&1eT2ng*I%=Y(Zt=q2tAJ@vaLl8f@xk z$#qYHh)4dVgAO=`dPKz_KZqzkaGDORCp^;AjeNv&{;V>Jg&^#m+9RDu4$fXi!W&sU z94p-;qK3ulDk;5@NX7~@SvKORCTiW<-)Ap#pzDi6yg zp6J|9N|4I<4j}%b$`NxOQ39HxwnFT}od!BO0vbz{C>6>h7C`Kd4QsNQ9YDM|?sU~T z$$wnQ;xE0iYJEXX34G$I56Ke&I-jWsar616gs1q%2J9Z^$^iiiS{F>s%N|cbRFi}8 zKxcF>T%Vz>di`MBI&8y+#YQ=z00b24$#!Wv_occPS_j@2^`7ziqztgIzE=EdXqeu-w)!=7n^zKbBlq!fu(`18h|lJiEh&~(jIj;oo)g6I7!?*@Gw$WHN&wS zQ!7~~SG;uZqY1J}A(1-4Z%poUyktidlQ;11yM5&{_yuTrl`H1iotCmM*~>CD{zSBq zw$05Tl(z~2qQP1;e2@k4nHu-k7FTj*uZJhhYk%kI1FL*u$o?U>$>ym8Bhu<@jz4O4 z!aOYhq~*8VxctBBGP{;;Etpi|iAyF`tAirKsIZ?Rj}toz`^@m1aiy^lU9Yo^Co>*; zLeW=W_lB*vsQ0Nsimg*?H4KT~5VA1MPcuZCY_PySjf$*%O#NmF-K>TbfI(o^mrKr; zYZ2jwLe!nF#FXX)>2y{wb@%uMHo_@Cp-Huw8=~Shv_r*uReHpt6g^I(dS&svpyj2L zR^`Q7h>Wc-_s0jEgj^hv~GIg+<^%%xAyqavG*tP?fVP%sG&+UO!+qULvTnlC^lk+roaDh@P z{Zx$7uQ%vS=cwXMxJ!$LZ0DN?RZT^`qGjBw&3Jm0%YXC)lZJkUuXDemPkO!ik#YyH z-!0mD1fmx=k)q>gyHdI8#1-Gu2W5T~B zoI(AX3V`$xwP1pOf(AF|Lyh}3D>{Y_VPRnj(i~A=E1cl!_YYmIc&)=xh}yd?bpkh`aM4Xp}D`-joP=2-HyvbNm84X36>uqiQTj${Su>ooC88PX*7@~DleJ>YzD`(V8 z{C_z%5l91Jg!099j5>{X4VSHVdPK4C-I`)-V`PvC;L7MbV&W#NCi%lhX+@X&Tv5qp z`Nf+YH=mSlPdT-tSMjb+q!GmJHCfbc>6;ItWGwZ_+99(TXgCv}C4_0M`nV>TJg#-Mt&l zCQG8&ExffLpz*s@u{T5PNE&dR`&-0$3CXg6Ph44515Fu<(d%!m#x2Z$5Ic%Kv3lCI z26)lVmi-ild_W$5sJ0r5p!Y*FOy;xYLQ5tvaoRqG88OP!p&I`@q;alX4m8#pr~*P7d1xx%H&n6VbGi zz}<`6$MU^NWv8>1I?)EDn|U|IY%f<(H4%%jrnw&`HbK=(r?+&H}cT4Gxrb zTN80$e#F+}@x7%y_BYa*9y7cVKci{3tig5>zWR9ob=SzDQ?dLn#gDQBQ?7q^ijho| zY}mteMxtcloJDer|0Mt?8NWqXnfFH=$Kw?Ov#D1~v7|-W`DyG^+j?dWRm3+rw5uwq z`SN-W5r7@MG8hUO)1#PtY_i#Q^?lkICO>=>ANZp_Gjp>8YPbtx{l`Hr_Q$+0cwJZO zwg7nHBxQci^c?l-96cz?1=jM|1O1&*YtJ`pAkQc#Vxx`SM;cKq^(Q?04jbMq@2K^h zebr*PVzRrDVlWX*=^2kcEW(@Y*}}=#H)ah0#UR&C<0XmbN^A(*;8p21n|qF^zrV|l zI#<>Y{((lca?K zQPPl!5kj22uwf6L{d*%2L3UdD=&Dwd*@vOPbNVwggnO-%v@J9GlguD|2T1hruO-|LE#skqj;~zRF1nK^3s#Ydbinn((;t`P4U%Z;x#9AknVJ_+-wslSqltYDx(204` zAusjX>6Y%0{==478<=d7ew8fITGM0u^<7rXaDS(Vtf>UL@&<*ao0#ClfvEyvLLyX zaJS)B{iZUK|1u)83r&ueni+tQMt7Izy;iA}qeNFs#v{2O{3M2>KV_B1kMI}qf$(Zs z(wD8Fc)mx0rw-@BP9J<-#UsQD;>?kWN%cEe~s&E9uof1{DE zFT@)BYa&9r-+hhmYf{*OnO@G7A!5)Ruf&N=uNK3)9|mQ;TdgX+RXR{Y`u%Js^$ zv`z~+;`KAq?mw82)SFHobJd1nI zpAWdZ;wJ~Akhfy=9I5EoAY@Nj3rhnoo4P+qYQ|WG5A7-@7}(?rjRh?)b>`51vv+71s2_wFL#rHX@3>(BJ>c5QS|y zbEJ-)toZhmALr5djo>shl~#xWD+n}n)!TJWm|Gefr^VMm2-uhjSW34u_kPkxz+gqN zIp8K>f`;4hj}4Usz43dUBo#wE!2Fo3ejPZ$`_H1jlP!l$woMOr%yc}wt6>J6fdF+A zMMGQYi7xGbJ55q)=2gV60N+q}gv4A4#qfF<9eOL&lg2?4-n3 zPQ|={u`Ykvl0SR{v*vbBA(N7l%)!_w{4yP_M^P?jo))juPX;~7s)@3*^01>_#|^B; zgcAx56Inz-<}20Ank;Mt`;6)L?Q0^(^gBJMK_!eq3Zi3=w-G@fOO=SFhS?s-)5J$C zb3edx=PR}NG68OHKw+&9Re@{%yVN-kIkKog%7e4mc(NmKCso`ciQtQVPhnQp6KlPj<4?D)bzm7;;77tnp*kH7E&d1A zInx*JvrwHfgHPP{vX|b!+1$_fj{JV|59KxXrco94eM-CiJD$12pmXgJ{!?;H>Rm|b zw~c3>IV8^fPVpNp*pYD{xx(9MC-pq>AlN>p-boze;@@T`cW2egU{qR8RCoc|FJr-ePxUU02(lQxw?O(sKX5H%V{q=@nXK&mDs9?vxcWdqX0_rxrSWB#)t{_aMY>sH z3?cUZYW?=M5&uWidB;=z{{NpOMP)mRi0rLwI=1XB;vf#$^Vl4s>^qYx+?p&m5{$OpIEz5mfonqf(d)c^a$p$ucwj)O1=-&~q=T?Fs)^(Wz8Qu(aZj%|F+_ z!jG75N*+huG!@SKF5u!|-K2;5570xMH)KoO__CE>#0g7P-{Q?ZruvDAWYyJRsdcK0 z+O|(?Q^x9(y)w~^d=X=_3eAjmWz*fH&@F(Dp{9=0w4ltNH3+?qbl1N5p=lNm{b)>? zCQAG$*&afUlVEiZI){IJ`r&fj6td&eEzR9?1Cc)n+6mNhdp*v)S9IhCy3n4A?~cT6 z^rLx@nBpyM4rSo-D6RoCfe9=lL?{=WW0at{tIsAnGy@kR`+6s|T!`pL*(TX5I{~>X+CU?z4Cf3ubG#eL&gHWuxbY8ETzy9iD^I{sFcV6alaJh0Yy02iwJ z)~NdFtB_5)7%+y*K9VY*F{r81eMN<6ZnflNe>dxUhtyxkn8SpKXxXRN(8iLX=4OmC zN4gD*;;CeH8s1t%)L7W zaop-Tl%3UXPcl_Y1rdI(&~bbKy7AmZ3c4=0*hJurIfB&IHI@j>&c8_xyr8yPESbI6 zNQrE2b4pq^%ElUDlp8_w>|otFP8RgIV4*9IWIHD;OeLCjbYqnBPXhFAHW;&z<^b_1 zg%%EJG*~2A)vHK{Yifo+Ew;j$34P-3F%zy-jNuq~GHL{6t@l6;DR?c8E>g*ouOGHQ zjxrxXZLG-)Q+>ZHnFju8XW#S6o@1fNO#{KKHL2aQvQBHIBhR#w!>_7MIhG!sq*9jMt`P|Dg57iWt-3=; z4LOA9P`vbYjxK9o;XABt-$<5)pWMOcDr1TZp9hC-64W97Oa2Gi=x;)krmniJG*G6I z!%G>H^R!8#WI^w$&$LK>+xV)!YbTwNxp)4fu+rx2!x{ldnf zP*!NSVjXd@ke0RE0G9fy+(z|Fs$h7BZ&qOLBlbabD{snok{|)3&#L`{eW2;T^NQC_ z(@E<7hu{j277f)b;|_W}8zvolZRN%x%Vdg@G=UNk2D+|aG(Y3-BuhUEv#@+-=y*+VARJ{o4FD7<@Ug*;Rh!W%eaPTrm|z^N8}7+ozS-ciko$F)`84VyNk1Hb-}+{O8BG&N0+C1k9y&^ zHfIhw-AqkI`4()D8y|qXq@Istb+B`fos^}Dm83lf29B#oPnb&D`)q9CJ zhGgygp(i~>RHPeSO&n1LU8^rL0s8PzK^UrAr)V1!D`O+WBGDFmgmo)IXsj57|6!!> zUTH3WE{Rijl9HD=d)vraKILBinby4&v@Gt9Vcsy)qIAd-#@X4J&stobAae%P|1*88 ztCd;dBwVd5)=eq}ND#5;J8m9&{jN<}7PRt~i6d0qWgi8)E%VrL<5iX!fmIdNXZOOU zCaXw(rG|07u0E$qZbBvD+Vc2{Ohb6tpfuSji%@kV4#;G7x$)|UZ(uOf-UGVn60U&~ z2PovJ)~}|Act0|LQA@+#`&_QA-X-c~9V4Y@q6Ukx2Z1(J-xvg064VPBLcb*Tk75*6 z^z|M`KUjN3@Na&N1bIJmPNLM~UyR8WsB&y8!&0Rh%II})1|yIXV#U__?dy^v@rjPy zdQa}CzaBPHaG^O%}4wWDa&)vb?No!y5W73m(kp- zn=>Y##AW8-SY*wc+f>ca`FdhP$tq{ArSWaY)duA8Yur!Lm|_3^@%r&}b(XJ>DMO7x z!fDtG0eIt75A5$Xev$>PcfaZ}Hd<&u6P;QVxk}3Vt9j3VBm7I72Ab3aHstC6lOCCcI0AkLR~$XY@4dW+-@e^poVqlX;ZZ-FuWs{bF)&G zZ>)fJ|`cotoJ6d*@Fan7skPOu#OvA=J zST;iJlXUZzrxmscJ~dg>g}g!ZKx!un3}QACs$;&5?2q1ajX9uk;k9#O_lHm0-mIMj zkNW_*lf!@wPav^(txk4b=$xl`oYz#xa`BF5mOjOXJ-w#=Q=Yim7Lj2F$}}O2a&~hH zRv(!?{{!rmJJRAycy{(xyH1|%*Z={|g>B8HihUxTSS^3k)#_B^M+4-i|B{;Ld?p2S zBx;T4UpZVO%?DEBO;zLvAH@bq~r@Ep^bSns)9DfC0oG9FO?*7y&uJH;&cHog;V!-p1vK;4 z!&_s^wRhUsec>7$+WT2(p>O5Lob~0*yV#=52;)_x5$ zqTCd0(LN~rsh9N~0B zS~6Ja9r*AU@LL+TGN<=dx4mPM=qY_IV9wx;GpR1%T35npLpzn1p{jYfN_N3FKT_o2 zQG2wGpfCE>z(N~UYT8n*AtMQY?$J(hoicJ&+X3rAv7BsgQ{K!5ecxZ?EElJ7*CyedPXNIPr`84oddoIid z*AoVZzr>+}UH92DGWh;@F4JgcNiOe6K_UA%q^M?dq^ zIaQOCcK|AT&y{AWU$ch(>_gJ}^7+_uG0*rTjR5cbb#7q6jrq&O>nz>M%Vja#bXdIS zQMpCHDqvdDp%E`C+^)Lmquw2|@FrG(kq;|$QnrwX`-YgZeG9v)u}ho#D3 zc8-c!JWEt+XFiM=$$fAOG#y~adO^k3!5;-rrMd*Fi7#w~scv?HD(&Me5f!u>tztGE zD-KNBj&d=XxY35ZZ+ILu>9-zzrOO^^I}JfxiLla;4{W+4N<-OgKzS+a4jf26jqBU* zoi_L9lYTE7k#w3wCp!rT>ByeO9^f3C+(RQj+4+KT-nD*2U%toQw5dK|jf9spYYbQE z*S70VK~+2`IXr4+e;en8L-JC#I`K^chz0uZNK)QaN^)0auP2IWsO!e?ASV)x?I zj`RtqNmp*(F;)n83-0Mt%-dOX<#vP1t&XK#?+enm>lp{y4hs59O-k90=z` zegsQ%xDsH6*HwR78dwe_6)41!&pISfuB($-YGk~ak1#m)W?huN<#zs1)&AuK5&pne zpfMW1X{W&XXy{?}t;AE^c0!X@1;;UkJ>PCG?(W}T`QTK?A3si+ICxButm&?&ZrvKY z+EC@3fBoKq{ZRf{4{2;x$yfQ}p|alPVN8nZx-U-wok@;JwSEHpQCWTO=PB#R9mX6O zy&wA^rx#-VEavSwQG@jR%PAsOqyCccDpz#5jY=K1sN!x3%cX`cHbp^r?PKF(I`+O! zrZ{IdMw>#hX!kHKpf|^Ruh_(DSr>YEXZH-HB~CAwGwUpG*j9lSa#CP^En#9K$rkB5 zN~ros^dp$m=sEaK@E-Fo_1$2yPHoJwtlWN=ICU2s=pQ^=Xyu3O&GF{=M>rYF@~;NK zw1GRXz0g@x#jl6tRE|%nec$O7KQ;K8?)5%A4LeqD;q@#n?u1I`@5}9BZlSv$@Fz)W zI6N}+K;!yvE%q3F+rpNr2sIO4vrtM$ z6qBRC)>^BZkE6UVz2Q4|Qos4M1${i^B;dkOKC3P6ryeU3I{VaY-Q*Qo@tXEsOh9GW z;RpD_afsaW11ms9kXQHi(y zTxdZKmA5!(EPkFfKY5>co~VRp@KK5Dq>m_~gu5q@?D~!zA(x$-`mfkV-qBETY6(tP z;+Jz{MMuusiKj8rtBpXc$J}!_Xzl=RRYmZ>7HDa_i;h2se7bnRtMmKf-)Ui&%@8#~}x-59@c-1g(%g}@XsjH?6wc&D7g#G@O^g%f`> zG}039nv`YX3WRz~&!hF{mLchn;koRe&D_)?os(o566?B8*vJdp^;BO%$t=O8Sp-}w z>4g3eJ_gq==1crP7*#>^chKRGJ;$|p&VePxY@@1X){DP+zU3i1;Rn)BqCLsAK_N3r z^}1A8cq*pe&L_0Y=OJ$;R0V^1uDMmiV?+C0TisBPMZfyg?0id>RAZ_~5@Y9rKBC3)Y?wl2_~Fe0ep6Xtd=8iqOF68cnP&k@LQohe7G;>39Je9n6C zTrQ^!A5Xbx!E{*4Q1&#tMtW6`w$rSJ2b1rcAF^ZOG4!JI7{7K#uI&px-j8uU|ECk( zM+(-mzsO#0fOR%K-IgC(RpZ{|=@{CU#^z ztj>h=F?P=~0!q$ne^5AVnC_4l) z2Ix?~`T?*0x&=3clZDBi#7C9sTNNS~u2ZQ>TWZ?DZ4|#LjUqkC2;!Lyt9 z5CYskNit_TD3CaM7W%yTZL`2T$8=&3lXe%J-xG_CuRyEQ7_uY$cM%TvN`xMJMpI_y zjtNwvBC}Hz`04{1%D@OBtdU?*A!)mcO2O%a99(uJ*ln;dp1*cr_>SIA)6{F*1F6`) zRaEp!3@iDQJ~8~|#}2lK1kdpBXcx?G`y#O(;+-tS{5(yPsvJ1uAFu^62s8h^;En>93~~zk z&l^RGmANATznyyTZNEN5}0xa3u{$6S05;0BKCi~&R z0O40(*dIvS2_!lpEZrV6bYUnjEc6oe7}`$3W4fZn@p~B zXo4}XXXWtS+>iW2O19$;#EDBv0KX15}qH@pQ$wdJ)k?$mBh zG-^|a(`r{0XY3@W_k61&af3?@a8svr!da>f4fmh@+}AqR!guu~S;6C4hs1U&XNl$_ zpW@iBS@pqy>dlbtf&fRDzQa9zZK3HoHzqNG-*FZ^Tks;#F~6GI8+R{Dr>EtX@)P@(Q^ASh?Aecs=LeVU&b z%jXDn!YCZ1(~6>ev{^Krk)UPe!T%PD_~V_I|# zfFj;vD6j+TTs>{!u!Y*u^JQ0(<(?-MV0YhlFs4o!<`(YS!hWdnIZRiwLj`6woNPg> zFXs){V_Tj3NHuo!gQ9E;KRCV|(Fhf<<@_LJSaUuD3ganC0+TWYYMiN9558+>0FAF? z5pqv&OE9Uk2KOIR(yZTqv|9E!Dt9Fac95Fnk^>ACe)NTYe){vt)ZZ7uQy^tC}r6)-B3AuKOY}MMZ4*|oG^-5%kSo4!aUi|vN%vl2K5p- z?6?WUP})7j8!T#+dKoC)#W7$Vd}HREQ&wrVZ>cU)dhk{a=G%QO)~pJv<2N6H>}o~Y zRuRgOHfVN#106a(NfiRUGET#0Mtr`m28CH%qW@r*MeK5_V`R(0?xM*DW|u^j`^wj8_`;z%a9-1@npZy1 z_BI~$9x_^j4TLGG5eKtYtR-9Qli1T2V=S4`h`x8<&r&DvY*1)MT4f&nUZ!s%o12=w z58u6fcR8ac%sqvga#nVGVvGoHQxXRzU)6vYNjZxIJ+j{GR?KbO6%lmMP6;SVBa08l zPX9znbbA*(`H-H3or3~mpF9x~HZAv3Ss4yir`TYksn&n1U!@Msq|fcfw50EJ*5jm3 zSzNiwbhig#M0HOEA#_HV-Ajorekc6<*TCPwI=g;tYz z+AT;)YaT{C<5fG-SQVF$CKb3pYF^A*Yvh#g`)iNVTTl=3CS>_%(%JC^5Aw{srEX08 z;-&9ErkWDxwy%du$EV3V#s$u1x{uTl1TpJHzSBD|M?Jx*LX#?QZK|D%Ry4Gas!ktq zvD!5)l8wxVaEaY>s(2zj_JUnpx9(zBaS}!Y9 z0vTvV864aS%BQ#h`}K~4J^UsNW`wM^s9=lBUFVM(k^EDv{tqyPr~A+Aa^x;&u(TfL z4%vrn6NC&BKvNG@fo6XlPF@=XnzxqAkZW_ z^4?lG1&GA!%hYK+w}rDwwVcK(bOJ3Ply5fB@g>09vhtQCZSmr9>tN9Z@N$yjm2~NA zx!G_97qjxG{-*o1g4|ko#|$+675w)McvrTAL-qm%x~ZEAI@hl`iCcz`zEe_Rgh+~I zihWEAW1@+O$Ns=I2-UJMPy0-ZzGn{UC;XM40X^^BA@s_<_;bp9U%HreOu%pAep4eJsB(r_ zUILZPfjv?8Rfh93{W=l@aScyM3gB;YNH2?9(y~2CQ66fWA(g#N#ur@OGz7ovk(`1n z>_&fH)gqq{Cu?$#k(-a>6pVXhk~iCr-=|4$S?L^^K}PycE{lM1e`q24h&E{-+>X?7 z(>b9CncA{G{QJ!2-p<&TdMUBbJP>^1>`?YA&PIr#@NEa$FqKEOGny0|mY#ZlPB{|y z=osB+-Z6r=tnr%Eerwz5nHPxa>zdu;U9{{|Wq8H0=-q)8vs8{~ei}CB8*`r24{voA zys+B9{}@(u;Z?I%<6y_P=OR0||Biaq&N2yj6-oioXW0_srfjzmfRvl1QA&+c^T3R+ zZ3C{5LFsr_Mw`e-p-(oQl`XBH<(>(tFG7ot+&rXS4UkZ)!MY=^e%sD|N7pv*n~&aT zn3XpC6?Lo3z7oa5a|;Nc9J*@AZVR)(3i9^$(GhUC+?O$%YdS5y$$89mZ!h`qQfzwH zeQ^|!8&&pg3|R-z#w3SH7mc}R#;gzf90(G$cCPDG(;_MTj*4(6UpdN1@%-b4ycUc9 zx$QHjC48!u7in)qmS>ej^eiuDM$l^)U*JQixp(R#kgS+>8$t8loi=6Ir*&{Cpk9tN zMHa`PhHf4xR8LgGczPcM&*uJ8<=I<+^a|s&9g{0JwRbKE{+RvD(GEJiw>}PT zv)}tjiM-*a7fWvs_m_8zdV}=L&0AW95|`G9J~&wh@Y^A;!HEa3>-npqS$}Ct#!*i; zKsZ;Scq#mIo1n)~X@T)!$|MnG%JA3^^wpxL?Slfe1vsUmC^dRiQv+_sUK2`D&Uw2`Bq^FZbl!{?eGPkE! z*bD&=2qkrvd;a|fgAU>kRMFx&mjmm|A4Fd>NQ;!|f5q!E9Qx0x{2+ZM0>|=kL)Be% zUVP9=ESSA;()Fb%h?mm;B(8``vUWjrW@WqzbiECTD8m6jhp^o@%i_%yu>z>Oz)Y7~ z_&DI>b$8@g6ej}R8IqsHa6PFy=B>|*{-GGKyjNuAUJ6>N5Qys3GL8Z=HrYYFIfLIF(%Mq%a=1TzlWURA8&JqZ&GyC2@V3@z-L$uq zR(B(nm%jCH&5slt#p{#ohrN%(zMBh3yjEQn4%;Soh?&AfF`2{fLJY?xvTXN>T2-@} zQ_co#xO%Rc<~?@IQ0fTL+^VNIT;Slg8EWf=mP&fFa^;yK8%(tE(Ut|_`0W;#^Cj8G zJ+CnES$n2|>}&N#@0R$|V~LW96?wDD{FXNUUMjzh+d%N$-ieQb2tNt8Tk8`77nbxM zSj6<~FEuSoU%R&CwSYg za`Y{aCdNiegJM+4(#_3Q|WdQs1}RCvh2nK*KBc$5mO6(vE8;Q`jS4{NIw)$r?CB;~`$bT`^AG2U`! zE*+APu-U$K!A?o6gYKK^LWlMjVJQ8bhx@UYJpIfUu>9ed5>~UUP zpEk%I(EOMllnIxh{2$B^@S;TdzYd-DMke6eoy5@G6ZJc<(;jH*ZKfl!0K3G9%1Fj$ z5P#XJYT#C7tXhzdxz>(8wGFp8Dtzr6x&Kx_jXtGpIj+@}#R(?5nq zWg9FbPRKyPHNVP9GDSAdTiah!wi8{n%%TW^nAAe5r%)6ff)Up#7ljoM^b)X#`4Y!u zE%}Awcw&I*`CF=Y&lvFGO-g1l3Q__L6(n}x>H1(Hq8hF6p}5YlfSbD(EY1St{lNEV z1Z}gRFxZv|6waS}fuc?KRW-v1B!Iy`v1 zx-uKYm-|5rhv>X%3WjzEO3j#Dk2HNV8 zxF#Ci7A&n)(vFz-xZNO0cDL4l>bBio6m5IL7}pcC<{=ZGj7(l;kE7qTDK9u?2}Km5%fxuthY_tS3? zAgIv7KCsH;SPY;jwnujevM=d`fDH?~IX6xh3KjAp#=Hl1o(wJ|5>Hg6q@+!Tt*!^)l%f2A-gV9%;_CNZz!%!5Sh-3F*?e($ppnt{cSAOh=Y2Do-&NabH7?=DEB1zM z57g!%6ni2R4ck|tSvIO8 zken)irU8R^DK*$x&(Vti(w~X*CWJ;Zz)M}KAABxy8i7>SCxboq6uq^4;bfjfO-U1$ zRS!mjkl3LU`iGMs;K-(F+*co%N;73+i^#^9weuI!X0IIHV)5m zUl+$4Jg_)nuc)0mO>N#O$LvIPr{L;IH3OpbK_hdXqKy*!$fjPnR|3#L;iW~wkbD-7 zZrQivIqfusA83}zXSrub#@o}xEF1%V?w5V9jjH3}Utp5Dl*TP1tw+M^Jbm+dNh<^E z+&yiLQYz^$?n5yitt2I*^8k}JOG6b)?OPVMT;+;cst7V&7lX5yH5YcKzCSjoh9=!P zYn4uht#G%;)aDwEOw`JA@*;o3a__WJUg(2sEdlm~dBC)&-_(UJT3S4^S@o;b+Fs)Og1~V=Tnz?648>D2a*5}_VOMQXfc+CI<@4B6@P6fH&AGMOSm49G z;|7#nX1Z4rq(s2B{XABwsag+o+s;4zQEj%sj@Db9cIfL?F;AY%*cnpbnPHjGIE5yI zd8;49m}~Kx#tSkSVm@ZmV3g^hW+h02Yk7?ySqVXao1Q>HEX@^8SU$< zKE|)2xoyUs(%I|gwoOm}kzt*%I#9YDtl#NE_1$cYxPo5`iK?!iYQ`C%X8KA2#oGPO zk0lp?t2vp*WDbC$Y&UHoiW_^bJRB^;rURc_^gCVWcP*=%IJc0kt4Q20n}c!l!QZ10 zZhj=FZ_fnOqO+V8CA9AkkYc|XuOIA}rEUpfn1OOX zzH1ylE%g!{#8)V;G&6T6#tF}{s6%iRn?5^2J|c3@J5z8wMu&A2u6=DUBZtr`>Bq?c z^6bc55;pXp)r5Zj%4*OcM=LB}?zC<|%V!QUHxWNLl^7yKl$R*uJ^tOSrS4nR$~}XD*Cx%Q=`J0}Jm&e>?Dxt%hH&aR z&}HZxlDkIt6ZY%+T_?9;GE`+0lb-yGSMP$b@jHA|o4Z4NB2mG{x5p+e^U%$1z0o^F z=c4qi{Z3r31?-^$^|E!N5X1M}kE;B62EL}ANj#eD^)FCKMty8KQ(>f$@Qf6j zkvpvd{uzT>S3;7`VF12JA8U*lr$K;LZqhw$SJ4ue#Gpy{#=h(5hO|o1qpXH_;82Pc zz;RD{RM~PYKt@!vK`wl6BGu~nlUEwZ!%fd@{2ald&AV-=dh6))%kP5SQA{Ugd@SOm z!p@VoOq~|j0$V1qK68^hbw#{`oGi7barqZ8V`=Su)~{%Tk4R3UF9EZsqLSUF-my4} zqx83|Uu+s|nEQW?EPd3&F1tGL=4;$WiOt#f*$NNtH20Y?(4Q-33{8B|P8^^19tkvl zh&L>ywT&}&TqRO^I^@*)Dh2Qm*!X_Z5%jb*Wu%!nHT>=MC_#NmQNNV>CSw>WQ#&E? zNPg0zRYft%Pvgk_ELYIODihf+lDHU!EIYRYc1abqVLo?oa`rf4Ti1-vNCi4tSm$Ie zQeRk~O%&QkbZd%qtF&+s+Ff^UIP2ZWm`lnpC&i)jWubH>%K}*UTon+a3tqhV&;J2VD{;ERj-g39_*hpt*`A0T=LU_zsofd7E8`5r9`j z`d_EKeR!e$!{Eku!|d!$)2UphN7SrG(e|kU^u(kjq$0<;92ZL+HOV`X-qkDelgf{H zvSw)T=xX@xp;l~5&i3FkWN!9OHGd*0@G%_&glq1zQ~yfCmJPNKcxjcIiVG!pMWHgB z2D^Z)l=A&?Lh||jmtDWo^w#c=LIE>-Ef!yh|8)X974&Fa)~xb#+B%*P%U6=%g*B7_ z&BoZY5+Kf9+T2{*7D!TRX8kk5^dr?}S5>#*(U;TGNe z*I{qXMv>*}0@ViUcFum+B?qlD)K;hg^p#?ing$7CPi0@%`z!bMx;s+=&@qh$)W!qBB%v>81& z8`qn`e}tBYPMOC$aBa!3JlnA8IHq5%t9%SqJ(G+yuaIOIUFBCgGy`SVB3OE$YO3SN{7_VzuHeu9CmaM$zfAwK>aMJ>KG!`fb!x%>?J^z!k*Kdf}R6Bh5A^MFRvKlJ- zXGKYh2EzjLI)C?h0O?IoaU3NuZ`-CXdz$LA&g}t@PToq3bDvV0iloeRAo59==gSjH zd&3bQI~{W9>#nmTzv%-%&DN7}egYXt+(-H{dg@EQuInMP3#inb%Y4@#guuRV8;{-j zC?(uxHYS&cEUcf=$}MWN6OP_>@D3>eh(c~VB$uAL*=Ozn4X(G2?P=I8+7uoD@mQO# z65stGG(;L>gz%ObuMy&p`My}LsP_f|tm9P`vdm$0^mT;wgV9xLc6;SWq96107iM|mubxn|5Bk4X4S8{$2iWEhb}kYX zAA}wU#by@w3yy52(BK!zm?upxEB|YpBCo7z!z^s`M>ZhqUnDK7LIbRy%@Bh?_gu5# z1i!}{JTz2i*tlvbGnN(pd3jZ#PvrG$((`C4J+duht$%5c5=uEq^U4a#?pVs|sdEfv zJ6s0rP`UbQ&9V)yeE=xy!kdAvJF3}Obx{-|^Z-A4!&y7Cq)q<|FpsIS|8{}8Er3+4 zazCTlXeRRyRkH=m^Tql@@j|07sa*O+=~c=_evnas>IM`FrP*CgYx?G;Bc>?6veSue zxxbGKLMjmHP6oWdF6)a*Gb*~c=sO7Ly7%G6-E;dHCjj>CsHR};jwBd;AFqFYIfeNc zs#5pU8I{rwSR?~qPwUiaXKR9sd}+JL5&P2iJ+Rq|4@SVGQ6iQG(2+u*3SJ@pZu4Ie zDyON|37@uXxgl~Yuur%g!&w2|0gWv+k1nmrUGFM{w&n1*xX)^_{m!U>c~|%^DqJ zSR%?MGt)z|sY8qjAUseG>RK;86bhQ~@-n4cGYybyR@5XdFwgog?(Kv;vrXn8%5Hl)z zTs<&h{_|=4Jzg8yV*VOs(pjcB+2fU0RI{|Gnef;yVYqD`PGVjV!H~Q!OmvZ$MD13GH$ty>MO}xJYHSN>f zQpvL_!21}6?6oO{3^vY+@C{LOF%=53>ipxi=c}qwJcpOFVTP)!TK2*O2_qDewBligNzw3 z&(=SlVvLpkSa$Mm%b31z{^o!L;FE|&CjS;>8^CuR1+HazEwEanS`PI_%ogVy{e8x< znv^E=34MOOYJ#YMj*~AT3w<}fHA>N$H>rctu+7in>Yol31w9ZrkAUv32I1jdw37p5 zY7dE|xz?fF%j?S(J@cS|?d|cP{hvF5T?bx=->-fTs?g2D1^&wM(i<<(9*e*q;%T?k zQL&(76%QtK$L@K&chfbt$vlkQTf~$UU9{*gn?X5%uuCyX>y9?)(6@N5G%pA^af9&$ z{z1zM6{%JRN48Do!teThJ7&^`U?7Uw75x!<$+GV&ZS=iPpGM|RTF%qG)sxh+`oaNT zgZz7hn0I4nu9p#&(5czcRSx<68?wcMdqzo;|8eo}FpS3EwB!XXoaKMMTr%Cj9lW?N zAN^lDT;FCG$9ndJLwbq`4{t48&+{P&IG3^j#czb})>r5LJu@{AY6(63&~AE@2C@gv zl1-i7^pXezfwSk@`2sn)i#`^?$BSzCB*Kd8Ufqw%?gm0@Kv$D%mK^(&z30@Ctxhq! z8P1=#w=I>sUtqPRzSk~R>xM0#Br(hW?~I%3*9sA8OVA8u{Rm+WRyoH{;Rlv7e z=inPB{4RO-El<*BlTxt5W7j;1_%SQtabLM+tv?}|-tD@9(N+}eoSulA{hQbAK^LD} zzw2Q5>Y>}#-c0?Rtlds|2oX@Y$v@?e(d2IXcKK))y49pBk>;oQ!PWD>ieO`TKoegJ z$FXs`u=e11Fs4k5v+6ZBK6cD=C8OJ4zhp5G0Az&l_jIIJ~D@UA|m!?C90W_~UEr6~lbiL*S&O?#}Wx&Cf;D>`;)m`|X=W zoY=kJW94rw-|G!ogQ))_M1i5YSZZ^6va0Tu zzAr!=pNOsHZHF@e)iYodYbqerd>8(mYI{5=E}V$@pX!Vd?XNuxB`bs7zdU@~fp)Vj zs?lK(as4^NEy(hxHR32G8T+5zIwDmMUMVo270K2pn?a+Eo;g%kV%$->SUUgeL zz9GO1Y!l+~I<9(*UthT8j96x?f6q%2!O#;G2Ve>=AOLc6_NMPQ_FsM*y~*!B z_H0uzNH0n6(mY77u{A4wilg~^M)wu%@iWUpK$|4x7G4i#TP0iquSWkYq6O7x>ln}C zSGhbliIVTrHf^suIx%fa`$7*BuLr7xux-d!5z=Je0=9YTlB5?%NJMYSsaS|!ePFArimJyiD8mDDR z{ZpjNrytzCBbT%7_~Kj3r0hR*V=PRxcKvghVtD#sDznwD+Ql_EP^SHM`*^3|)}|{c z;Q2A0$3`-cUF(j%bKL6sdq5u^Q26lW$9soD`L$FlwQp6AfZo8#qzNZXj{Z_AOJCod zhF*GI@oKJUIL*d>9XI8(zQD|+~MzFkb{<3o<>kd?Q!5Js|1C<6u#OG=-HjcH} zb`d+i*O*D0BeeaY_nq9sOT1OI-k{(9#x?SrsEzu3@pYQqquL{Mw*1z+_88SrM%g43y; zf1COu2>6v|mvzL&B8lNj`xGB`DxhBy3x>R`*~}CoiePaY1n%s2HE&{+WB-=ASo(>9mRQE)&sL5&OJIyZ^c#p`gGlrO1u+ zk#%4PM$}1~(L8)GO^VF4rC~SjA$7`&H7t48$p+UbiepYg%Td=Ky*u*bTEG7xB`(xL zeb|>&foYKQDI+r9C*Fl8#zeqMvbYA5c0=2`D@bgeEr{_6IC^WbKx&jeDogK>f8{E0 zk!+zWYtV#;H`ye{rc~<~(xUHA{ww|bF-+MP*=$?-a05oZbBSAPs$=diAp~VAcKj&#^1Q<^L6qig>NuhABZ&>yM4MH3gtX!g6(_P>EDju>pykcoRmt%jPu0#1IUSHCQWsU~V6+J-}g0Q_ZRwlHp+@D&{Jg@U#N z7>!V>=uDPwK|oT8J<91liyx-krd^&17jgj`2J^ULb?7Jj`GtmFbKvG<6ME06iWQ>945p2W+J4$LaG#z2#{Mr7W%6 z|0@!IW3gS?JCZL13c-eoE|Ebfq=FpV}>j`jcdL+doB`0h3(*Lhx=M~(PxQB2T^-||FX63H! zcJSZf8yywQ2897oo#P3*F*+&@?1}g~rWrowkCx9LS*-2xHpSoj3=Xv%^6PhH?WK_d zp?Z#lsSJI=kJwoLtuFL{rpMk+ydabtRV!v-r&zEyf}py^$=PZ&)_p_!Nu zKLrK+v@2N=gbp#aud7gx8!BLoxYqZS>zO_O)yj)>VHu=Fh2nP(J^r;LJ<7QMY)K21DK)0z;t`n!O!X)@JQ0Wr@z!!%}ML|@-) zrmOAKTr9j&iKBJBxZa*~+baly%&C>+0zg|6KnotcpZ1I%e`VJ4RY3{37NA^ca`&#` zrpJ>GPcuP#|@DJA2d8C}en>>tNh^Rswg% zG!`X_WnAPj^^0(_(!ZN%`^?{S@P^08bes0AW8dn_32J-OHCp(b$YdPnpkG&Hb}k<( zz!n{Or0|=VR=P033{#n2yZfR+j4T6ihZJ26S4+6{Q_ zQ;Gws?UDwP(ZY)@?6|Rdi~}18F&yyF2(v6XMMu&cYB|}GFwC=5I3GT*EA&tn18)D# z@%Ba`Obll|bwt0~EYBG*XX%d22_ITWbCRTCXUWf+8@nw5!P6ra@w#D`i9hJ&ux7^p zqv@)nntJ;0@cjdYIA0V4$82Y=^1 zXMgY)=kD&_Z+z-0F5`a-ocWBs-FfMS$Fl-8GX5?wwa_v_CL0*EmxO zi#QYMx`lL0>x%uo3eIQ_VJP8~{`rkFenWZ7gt#_|eOJ%U-Dfhbi~A2`$Mh5DnHI8W zos=-@mHX#-vr2_Nu&PseP^@{;tuX;MhptyynaWm@=E+{GDf$Pgnh>*jW? zZxmXl=Dd)vG%ms+w2ahMrYaenW%$7#Xyae3N@r?}JHFPcnpAeS?u=vD;yzJh8i_yf zNwT6RKmDiMMfMzku!#mx`HxS>iJYo2oOW^IsP^r~`2E9e=W^eWX0#7TR}Yvb}nJ#_atHR|)MbQNH%8j9~!{o{G_+`fz*5M;mHq&-+%68B^|7V0Y+aqs7Y!_%z(8`9>+(W%LV~p=wV2>N0fD94^d;DKo zROsd07I)@|(piAOQY`1q;%GC#z&-TENHl=9Tyjr+Di;Ehmv*HZCe{`CdjMeI!jf~deqJHny0%G1XydNi!uJ8D zoZjUkp$hsDbmqpRYr318w1$&m)R6eHC;EVjtYyE{+hMX~lL77xem*@hY@s_jx2lcC zIv@ai+1gg|Fg=pL@j@hM0~{!+m}g_~k#l68xs)~9+-paJ-1+q@k#4*~V^6DC&x-@SA3HJ+Ge3WW zb~w_vfVK4abQmCBIk@>$2YHHiiV4#1rW#J;1@r5#NtXq{^J`P^47AXTd|oxG=ShRt z5itMmh%yXuP5i+zE4S^Q91R3}tyQvN{&V=9PoRX!?-y6shobcq`HjRc70N^6Yb~tO zDOusD5BiBfM?l*Bz^rCnM%rDXq$Y>t_jus((RmD?C`otK`})>j%QlF=IMc57cA6Uu z@}s32QWmxqY)?t=j*XYW8oKnO#xMwDSI|DLnprJ`AJ3p&YmzWPBGdWZD}FF_sO9`~ zB+VJ{!-lIrZoY`tZJNCbxD{KB`DA=U1Y%V>9JN?;B;N|~V>d$HCcf;2-I|#{;*XFO zaFkm~Zu;!E9L9g@O!X(#NNF_Z-m9Lxoeg;ckFWf;a57}Qy%swR_c?;DDwsDzAzu;v zy}>(89&n>2b1GecE7}S5HOV144ClS6@{G2}xK&q0>4|ZxC({t3V=KC&hUAk%A5KqM z;afDrc6q^o($&roP(;qFGlPExNb?*Jp8@JUDq}b^2N+swF+0FeLNSvCN_{h35U|M? z6v9hqN9Qf3q|ci7w!`SgTylqelv*d(Yd}r`U7AmKCnA<)MOyJP_SrNTwR9`WOiC&) zh~eyu!=n2{S>lSRC~BY&vCH~nl&q@8M5{WX&iZDXz}g!z-u>;~gbHL43=}V$;h1;8 z`xJy3-mEL-6zF@F#!z$8plg%Wtb*K-rz(`#^{(H2((|-fC1y@`dyZbKn-g~osuHa` zq-TBD+;c~NMYx)~ZjVRoqw@^`E!C)@=q}@DJk8P67;cC3>?69=v^hbDaeOKNJrLiE-VCF{4SSZ0<_su%5*dIY_)ds2E)r z&ZZmc$^dpbvA3%H`R!xUbBj+oW*P{Nqk)}}=c?|p@#>R*K*!V7qa<*lg{J36*{&jC z@@B#laRQ$f17*qh0HFTJf#dLJhUfF)spcidZ-M*^k{5T{@=2fGK1dGiQD47{THQ*_ z(^zUr^#>I>U<7Py88e%#Hs18=u9{P&JrlPw2cC3P9o%c0ycmZ36#pZVT1I(q?EZMS zR1zK}u$AA^mRwlC&){HKRlomsJdExR9GqZu@?$Opt1;=v z$Aavd@fy#z4Kn^QlaJD0Pri=x=QWqaVcZ-#Q7wr5s{$~0t|&J{HWj8_ ziFmXEs5wRpWJ^Y0O*-vJu6x%!8}FG4Ox!0cExl?P`WDZ>kt0C4(h9J+ZeMa;(}C-# zLZ{tvFUxloN%j*_zp2;xTqTsey@0QEWizjSEe?9j)W^nQ%it_V{)vB5@>ak6cTeU~ z-|-e_Q5$TPEo4H7UF-?>g2JH3&~Z>2sTJcClAjqF8Bfw!z{fwBg?qh zxIhK7af9e|ZWSWUrcj)OtO!054R8adu;1?2d2cm~KWssOlnR6}SP5=C!B$Dimq&u? zQx-Y4bkRPtc7W{Uzc(ARJ%)K^1t`Bq4&Bk*X0@5kKXM#23LUauL>on7dtPNBILEW| zsn1qDY+Etx<=PX%3|$_-FU;r{`11WlA4v3izHQ}7eWi*UPo8ltWIkNNlmJZA73`Dy;%7BS z9LoP}%fmwN>;HPewAKW)??|~C^48-y8Fj_lV9Kp~seetYGL@4ejy#gsdz#Bj`N&Kx z53HwZqNE4g#XTJE2G?)qcHC;roif@c;?|ijHx%dElKdpU&Na@)MxLh>&jTVPDi(p3 z$yTMD)4*y?c&p=orH@XCmZ|`O=6$fT4;5DY>x1wEU^?2T+zY~$O|1u~w`nxd)Ic81 zG5-8kBpp7S+gyHnlTN(O3U^9UPAFbD0aSoAFu`0+gHdgjr?;nP<8?{xFRzN^KWUhX zAf5=|Sa>#U;0+C_xk)FWhnr{kgU->3>Cv;~Y&bo;*C;{|&E+uryLce&tgPzb&#waH z)C<5qN2$8~P14)2ab;T2ef3oAQxoUj{h-6z-$7efpH{BTo(>{6S9Cc8*}KophzFaN zi+KA@erv0MG8YFXItUtKY4PcZ;c7aEQ&ELz5>tYb|bjdML@oD`&F<+oU3>kLpDrWSH z2$2e_u!Gh89bptj7|cAVp4ez%(cH%Yq)$m@y=zdkVy9AIfy;^5mBt_v6Z5(`M-gz% z_*34OxeXsPYhn-}Ym9q%lOp!xr!&oiv_tB6sSul*VM6fxoG2s@Kvu8t2bTB1qWf;q z5CNs`cQNz&2zh&q0_yZwF}>vcK!pMlv6)LfbKdx&K9{x=qvVu4gTm;RNw$XFXGNjs zX^!!7yEO2oLG`JlP=fCjj@izoNZnI7{qi5J+P&p6)?i6Gp^yjuO1zsr=GQ-AWR z4q9PUB#;+vZus#k^)~?!%y&h86&E#@YJD~H=0Qij6#X#pX@DNOz=p=cF`?E>^cVH$ zLi%yXDTXt%gATT%S^kqIIwqrB)+TaTBzoIGPX17>awJcUssQj2O{=PMVme5b9K0vq z(EPWiFP{aoIGJFtJ6szw{RF86QN*7cDyso*LIgLPWS(6ZluxAZc z+9Rsky)~Gn8j6q#*;%^M@Ax<^uHKpa>2!%6QG}DXSk7;eh>nk29d)pH_+sU~x{#3; z0fC9RT{_UIm;R;tsao zL7lc^X)t@&N^@dF^W`4(K@vipKV1-^C-%gIec8LmyOA~w;VWO9)mrxn36Asjc`1ku zgUE4M;fRab*(X0*#2y>3j~sVWD)4bm+m8FC%_2x6%+OwjjSXSI&`l1`y?}vv>yX1* zNjERBp$Pi+5Z@+640$S@`OlP0`S&_JdoYtfPp<%rQ)ai&F3k=W%NBP4c@MK;0*T)! zYTiQa?nJDoSC6jz)mmK-ig`kP( z0anLHn0cBYjS3LHF|REg0R+xKv8j-quY?7Lj=dGTytt|R&oh4b`kJwy%(#xo>c9qu z3|^LlOd@@)U+*}D6Rv*gaZgGo7kdXhAJ0y!y>h)^#?}OD*B~UIq2T3LZrlb()-D+v zK*-*N(m2`2JOslLdfmdoVl2gCpBq6z{_@oq`KLl!GpWvvg3>bB>leR1H^Hwkb;i#D zgowP2Mi9;M}2PH~#$+bQn| zGtosWYi@9w#R~2lNTzH(sGvKVXnBR@H1x6w-&tLCwvlYGBDho`^bVDo01*`avNdW0 zaH+;i*2Jm>7y#bl8P84_Gurwh@J|Wz%^f@R75~5H9(1L~A{|-LC)(7^aJp~(T}I~d zdV@pKT(gG6+50BQ*BG??!=?AcyBE1$t&)SjtSB~})!py^MHLL~bumya7_zR3pd9K+ zV-R12bW;y-25c{tfG#tN|Dc1@?XxCgACO7(E5V@fD{(A$$?R?Vizg)T`kKHTm(}Q1 znG{$_a$Hi85nVkMjfDPjx#mogaLf$sr#UWvv%eJYh{!wn>^fspwf2+HS8-8mZpU?J zTBeh^&wf}uxOq1uJ#OB29Y=zCH<}M^_1m2tXfZ*nI_Mb&R%!k~d(~}NNWY?M+=}4{ zBelPGNht!yyh*T6UQ;iJYe@G=e(9!WjS@*YI{j%5|HK1a>isM4OJlBqQm_#RL{%4j3CvCS%V- z$0*wRj%EPFdvI;`Jfmc!C!9XEBA0u8?=8D9xuhvdJNX`6GJi&JWHNC#Mc({MZQ2_1 ziaDp6N(h%wG!<$4A@4PYMERyCTc~i|h59+=@Mjh+4A|`eM(rDEo>;0h08#n2lO?#W zDJ`llb@U;%XELAr`DBHga%^L=!5}wF*SnG(&aT9}b!1#Mt6d%@0lFQ}*UnyIIxY63 zM(VaYoNA=z`w44H9YK;EmaLc_+F+SG!jlHr{=hm^4FU+4wAMWfocg#xvW}#KXd}%( zB6Q(sXVl$lp;=Ah?E8&R^%TZGAI#%@AQ+|lm*C@+;NGu68auvYU`9`j`4-!CB(KA` zXGJmYY`rn-?tA=VY!jhJGUbcrO}84j4zD@Ixo3;ACXy0H!2CnuZefmPGnO0|mvdn& z0{fZE4W=ud zY`nt#&-_DKb&gYir)*t*MJQ@-E@#rJRR3xwUvvT@i?wdHj80!M@YgTHZlR%4Kbbn8 zoPml1dWr$m1MoxDyr5J6vj(tE`*$MjbVieH9E4ry~72M{&1V47k7sE}hY*nv_f`O-& z;$|i+5YYg1^e2j$X98BB+46&-8H8>9tsLZGeY8sTU!0r*168El3mtF<9Dq!yGF7FuPrgNZ77f9TcQ?EYoE=RD}Sj6nI=QPJ4T1mjUo0}qU zojDm|s~f(T*r)%Le`VU|X<)?;J0jl(@CjL!z>laY_{Iq;t&%&^l~c_rXDFW~xab!v13SK}IU z$V@u;o$f6$0MnK1xhXd{#u({_8l*^9?yqDRwHf!Z40hpL)KSs6DzaVA6FF4|B8cWZ zpUPnF(sV`CDDPf4pDrAS!o~$A8Do1HhLYx&-wAQS6?JSrUJIvDMR@1@cBlQPYO!MH zC$lMoW?T-gH#`Mt6uqtUZNcbhVE86w@b0u8*g{5x)bRG*K>k5tmts@BjMhwLd;ZIU z-!ouF^#0zA5k@&Og>-5u14Qr2g0A(x&d?-!wp*dtKC+)IU4%V&6$&BAnMqjS1C<8l zOUZc_Dqs)2+|PI5FrxU&moO^4SoU}ARUGJfv+n?`+}wijjz$1|W0z`z2Ma)FavSa( zk9ZvCUkY`+bWtBQ%pG3uN{-!Z0ueQ*TuJ(J+!%oQ$>vW7csx)U#_T-CiGMViWy2xx zp{H>MA-oprx)E1p^;FQ)Rga}*n`X=U1zd{mhh10xQwUb*@=ACvU4%KMF6yPN73H?i zVlZSV6e+i9-rsxyHlsz9j^tYamr1nx=FnHWdj8}DaZXJgQW3E2)Iq6#o2=LB2Lx9d z`v%Az58C2-5m>q{pSNQ~8gy4HW{^2Mh4eHHk(W5TKN!Pc7+1Z6XCS=iJiU{4};6=SU2!&9A%y1CSn{#0gX2h7U2wrWL+R;=6 zIPB-Uw<-pbp_Y2%X}JvwNmrycz17e!qvV-l%n+HyoCf}xN^ZUYz)+pU9(SYt=WA|G z++nKtlrA}%IwCu_ zm_5;%BaU>z0MBIB$DTbtRr+$*9c?plcPFj9j1xBKJn$?%zO5f0`2HiXIq0xn7TU|x ze^zmQTa^~23M{ko8&3yu!%gc|g!orHom6EK*6e$$k*ryW&^V{V`-%O#hiF0 zt8*Bv@YUDpuROEkVnD8vdxk$(LX(L1pig-TJsdT&VNB@U*JOA$Vugcu_Ex+%PH61$ zgvA0Qko-qc%{>$eU`pKQv;dUxpbGFG5m=?`Z`84`pSII|PQSZe1MbBN|JN0G?&esy zQM;fDy+3Luy?9OFhpyjVPy{!hvb4JhuaVV$W$}E^S>Y~$I7e3-!M1)!V?@OyMP}-g zo&^R(y`&su@JRE5GG1$?x$I9qX#FN-d9;zPmZCuRi&|bIs;Tx=YFTV7v{(5&mg~?0 z7VT%v=ZqaM8MsYA28==*W%tl+&`)!G_b@cIeD{GTJ;b%_j#GBvAI)b>@+ONd3%V}y zg0tiXB}gC({MZao!4|gO2lJv%kl$$we+2feTRo}w$HXF9!Jbk66;Ug)BAN?L=!CL@ z;wm=!b*VL{p-k(l);m3vHmRDxI~D=QzGGC=$pxfzO#< zsgQ1+ly8?F3X%f82iQUFKD~*|q79bH&34ZoI4U;hB6ELe6*1w;u2TIP6+6B!Q9-WC zy6W2cbc>{awnj^GM$YMn(9Q#*j;MCFPUEDmvC;0baHjM+Fgn;(#oMuGr7o!5QB;+ZtL z=Iy!SU2|^v9{3Nku{=}ar1Nn5$o1cGZFOL;MP#vVyY73k4!KLr%^sV5iwG64i->Qm zBkEu%oAQ4Arr*%L%{vP5FAgyL;8~Hdfz(kI|6)^K$Twi)&-E60@ekMMYTX&-IUe~Q zd3uzcaV<$s<$DPj=sRd={kZp^N7Ti(sro+tq1zwFclKGg<=!n~P_l3b?b9;+Xa^bJ zL^1={d7WZXb$b2AyG3$OQIxlp7)Hf0&x6DBb<3CQXlw)LL~9fkxBgjj0$YtNzgPe! zA?QwKUbJOP!G!5+l1Rzb?HbAE&%8jw93lT1+M+3{Vsavx%I9k=aTa;~=T7Btfbkcu zlN-BD{}5hkEg8jsQl6vh^4TemucDzK-JJ-U73B4vJ9@0c0DCsz{19>L#8-J&ZI&L8 zzL2Nbd2}l#1<34gjB8zyi>9akmktW0s^40_hLTiFf`pMVgHTE?PWmC{J~`&IKcR*`vso*vFr76p`7ku=LtQavVpW=j4GroXNx)yFAsB}a7L zF7Saoa*$$o97UEtC}2cMGG=81%}SR$`m=PO&;i*%*mHY`Ln_@INXv+dbdYz8cjj<7 zyiR`ww#DVk?1TrrT5`E4VdBp!g&&?1LG54VlNLHB^b|JPQ8?}DBYKRdepbeAu~1XK z_8Q$;z{5l3RY`uY=ZG+m&Og+dog|uqTkO4ABSJ-P2wp8$R)7_MX;2E3$(7Ic8#jaN zX>FxDJ9d`og_+Q9=LMdgt<`#_=fl7B+FM!vy^tS^KlS)2OjL1GVMBmS$%^t0&`DoV z{Wx>^cy#vU76kue`eW29_SpZHU6+KKzl>f5j{?Krl$(P`Mz=ixH=N3c+hn^3RSfbh zq7qiFF04RlqmNSkB^I$eu`chbXbBKPM)UT#2>ANNfmEyj5#xdGfx!lUmwd}np`E*T zn#xS0mv5#BC50JCVRxG<1Ey-qfNP)X`SfB>qDi;HNZcPc$%pbG=wco#%@-~h>j!5} zV*FLKoH}XeAZwDR*=OPAfgqL0rqJh!@O{51Z0G*l&FAOc;8*{oFWJ$R&f)*aE&6?) zjL)$Mmu12Ru}|gMVu2{U=WvrRUasZAF$hj< zNU4=P?nDL0t#>;d+1M%le@$GLKYwk5E=2~32Db^|6J}n8OgJ4}f~4w!lOH*iAs-e) zByw`thk*=7hdlygM>sT=Z7rC$I(A!-W?JTNWB3=G2`Ht|bi7LKETqEJUICTHewf`M zQFIA7u7mj- z8>VUU2jsy5^O@i0!Lk20`S*B?{i_n9#t@pcBZXaDY_lz)2br{y1z*fL3L-{&?%`o! z$0So)4E|J`uuUZAi+^D5?YAxR^Fd-?Zq}*hEt960vnSfQD~zpGW2seRuc|YV_dnH{Ng4Cc!b{G%ElSFoL`KH`D*%Mv1@W+e zVR&buMxfAvZ-zv}c8HVh9pYRyW4tjLPefyOSAMlI>~S-62oe;=g37;CyF8 zwei?rblAYw>?Str!7q|dZ|*nr2Y$jtZZbxX^w{?6G8~kk4uIp{+TW1gu(2~Xhbh!w zMFDH)Gmz55#iIyW>4hAXJhz7ln^bWJJN2jLHu!>R4}6k2w9tS`0SK6Z#+!yvOn-&} zofygTjhEFwtJO&ozwvwm>ROT-e;{HXrv^o+>+VwjEo2NgdZYF2IQVg@ zKV@|%K$>NGXQ`gDdaEYGzOnsa{P?*K&yfP>8w}8-P;aV74x=}6+)}vU8SaqXcBlC| z1lh&7qZ~^8{Wp(xs5fh?jgbb;xNH1Rfr>5tj6e?>fuJi~SF>a(8>a;?aHdSgPv6y? zFSp(&kxLTv4|P!Rd{wq>?EK_oEhp2w9JN>wHjy~nyO~Sr9D&zhd$7XuNs`~qje$HH zunYsZqa;Zs6KVF1pQ(a%lDCady15)-+&Sk-2@_ULB7LXwsD@3@B@Hrf{wmF%wDfaJ z)ITYhU-ZX3_7ctep8K4&Bm<{Q9;v`8Q~G2%l{+6B_^IDan*+Y&j=6-|{Jvv`(Q2zF z9C#m5lSv*DsF!QReUuN$JUzFP1*<`oULtN6Iv<$fY&FUGh|9lB`y%6cMbW;0@u=>ml zzcWZYQEfCxU@oEg1w)2ty$$C}?#21(Rds7CRNrCweo2=&GZ+XTGQhi*&xv^nWM_=! zkgcqD1)E#&JRY_)i#;vpb`NM)13arL@g+JbHlXyC9)h5}+wfPj8VqQ~eP{(03aSLu z9~uG29Os_u%?;?sn3q$Kqwbixz~657Jk>==z<~*_`tMYA&Ib+DDhJLQ+3S<2W;TV{ zHC;%E_8K$u;5=asmiah|DE8P@oh!aHq1{IOM}}-JTbGmp4c@bM>VMO>k0scD7ky1^ zS8;5TPA|$j7r?$>64z`u0TVW|!9+!cI?QXiBSE4kYAb(J+47b)u=nbj3^qoJ(wASk zln7A|Pq7Y0t7ChHnX|32JX33iBL{vln2IxEKd=Ivg7lmk&N;eLYpOjkefDi9Z`?Jv z0r>YbivcZmLJbgv)~;n<1+ZoGDMHXT!AY{l1s;%+FemzfH;bGg58<|Y$29+O{4tsu z>Zb>E>jsv_F0ro^qyP2h?KO=}!16FXnXBrI%F7dn+AZ0Zx@i7t8gccS#=HT^I@`Ri zb?--E`_`;^0q0s6wcK?A_fw|Kba2(DUx(PS{2E1Zq%2Mu3O{WBI>%0#uo+fBebjf36Vq+*mLQ<1rpYso3SEpP#ij=EJIwn(Z2u_?zZx zRW5nD3EekUAH5v3&+%Ez2<#Fdc=W|14pBw)&R2Cc;R;a*@@taAWrTnIJY1ErxJy+$ zDubf-k9?67H7fk(ZH9-8qKR}Rf8%e?YxTwrXU6|TF5TW@Zdw@FXg@#~c8}+30h%>{ z-Jzk0pJ}%y41W7(U2#D$Pnw*WQ`D)N5q={*FYP$w93CHf-+QE%2-DgZD_sO-9;;Gk z^};8qA9{L+%n2w+z8Sl4=jA|^D0bN^_GoeCL+l~*D#)no9nmNYkP=Max+4pML@G!v zw?n?!9Rvu7`$j%X*$NaP%Nzb@L3bqsXqfzoKu8U7|Blt5dP(J{%X+EENRJHXsiP!v z*+T`MZS8=zB-E(5~)WzZJhON?W07lZ;I6D+LLBCQboNR4a&%yzt|Tchd@Q6#4AAW4&dFJQsP()+K`c!NZWtZ0nv}N1dMg-F~O`Y?g3^og~04 z1l!wl^k-IW{qSjv|6>C7yB=eu_BdKK?WPLN)e`96e-aJf!Aa2(Qm?(vCBF)qVkgM3 z81R^J5la^Jp@<5##xIgtBx}ElX^?4U`w1Zu_7VL#7L3e*F<^NjTq89Jr1RUe%@dBkjnk26sPFvw?^_+ z=xl~e+|Y3nw9`&u|DritxW}fqv-@6;4a`(&85vQeOSY?dPl~K zWYp)E(pK#YTD8!v`lK*golNHZ2L3rKGsqvMXND(!dMA=}>a2chcM3mI8m5(Z zTd_UVmXzQwQked(`I2{UbciPP!JG#`##V!7>5>#Q*+$1By zT>CCm*6g2Ak~-kb>HNs1g#_MRFxhuLfFH2o`sHC<>Iycr^_ni3YF9XmxCXwy1)sT*H!gn$(5 zA80Pu6<+m~TMjL!^L~*Znd{`CCEFmTRe#0zl4$tn=ks~$RMi%9&5?U(&F+}&{%D)F8fP{L zOk5pGhH~-ircWRJ^~`Sy$ryAO34gZZG;|_7blPmED3%cbY0ME?94GJfFLYw5GFCIR zu_dwNlqEKR@KiSVIfP< zRn?Q(?UwHCUUD6GI!96Uw(^4gOq6&O(E-xMLElbxPd@XE?oH=F;&UG+!ggU=>xhG7 zx`%eRU*hjK#H=@5P!&}YVz+#^MtFM9^3_6i*m;a8bTq^M zEB=^0GCRXU@{m`%w`yy+cZa)dmM1-?E=`8~1ZvfPY9#wdiKsxthAif5DB|eqylwxn z9NmCh{n#I@=&8VDMLfe4!VyC}(p3)ENf`)F#&c21+M&?>w7s8c>ur+|e0T#PZw;m< zhFq1`YvX9QxnT>Z%{S{S@SQW>d3S*Rcatz3SnTxVEBJ-jM9Yzj(iq(ok~ZO*IxNDD7udnB0l z!lST93K0#@brlWLHn;Nbybn%M6Hz9?&fR@dnyqH}=Uu&dYFOcsoLKPa zd1KY}pwo-E88&W3FPZ>I<;)d?qNn%nX0zbQ~T8U1( zJ1y@wVcr4OQVPH7=Z>IAfZJfYlUaBA7!BmwNz(Z>Jg*L^#q5Jhvlgk5kZCZrtf)l4 zKxA9p@nGDJ2zIj2VG*M2dib^Z%WP@^mL@Xu3%_38W9>n6y{n?n11%2ZG8?JMR(Z;#dFh>mS43`?qL=D!ST#j6_;|24}W zsa=Op4~2ye55}ZXu&UDdyqZnsR53-VxcB(HnS^NP{DsOuTwnI_xK|>g68ehE%-GdM z_k(!xii=INMO+`YDZ>V2y5$#zZW?VGO|;dLRt?+ei|8(8@Z9_qn!orMpdY|~&yEDZ z3_S6L=l|%ce}be7x?8v@%;4@{FE99vZFbnGJH}YF-tm6N7PJ{QNK{lm=3U^;a%j8> zFwiBHvY%;N9c{uGf1NF^51L6D&1u~?Sq1vz`${wlfqXYLQ3 z;2WkH{w1sN#b}?9N7rHGC3i<|U~`8?1|KHm=`V{;$XJ!i+3=i`#igUg)g<;NZ^%aNySCb-7wD=4 z0^8&0BSo`P@BM>k>LH){8we^pWR~(?*1fW;+24VcPWvx?NjpNk3%-J6s`%Uwfy?H2e8{PHFr;A{l?A(ODR2fr~K;M)d3*!^nN z#PZCvPmFBzn%iE$-YWdrf9W2rDbX7yoiZI*KUkNIxNoN8sC_(G{Cqx2uFLtyLIII= zXJpVJ$Kx>Cun=Po56;Rr!W%gGy~IU#qe3>maVDvz(@&*s^V{b2yS<6_HK8XQBAW;o z7*cztX}!m+kgm+f`x83h_ynQc)UkRc#h+o12*MM?`*}f_kut(`Vx-RAE>iZ~uD?$O zj?WQs@Mp7$_G3l@iDakQ|Fr;|1eRI2vKnYw1w_m)^1A&L? z4-sFi`pVKqd`eU5g3LK$t8E-^u*WI5hdK9Kn|BCOG|iwgLH}{XJN8pky^zvEtL97q z-u+$yvd8rJ$z!wHdG&=`_aDNu77__BTh4EO4IV9O?VjiP_$CU1qTqSv)>KzYwE61! zM~mw(!h0-IGj)w4#+@qMpyj^_Ls+YdK$Ht2s;9GGio@wcA_HlXpNVrwt3mpfGOnI{ z13`wHWrmr2n**G~(7jyT-pYKxg}0&&JAxUPS1L7K!Z4{^Un+;>j5~BsavnZMXg$|Gi$atna+p+-t26TPoY(CO`Av2k z%ndZUwGNN$`eulZ$Eq_q?k+rbdm>d8LC|$Xcr@ozgr}ckoWd^wB@ozw(rxi?uy$jw zR!Ec#rG%=8NKq81zH^Wq++aonP_U9LF|Yxc&0xC}m))`(e=C364dfc6wZ1@Aqjlq(~>2g5xF>>02`zT##aP6N;A5QM<;+!?&S>FP}=!cKZGH%(LL z!KEC!dn4`!tq49GQkkyTdZvmG4}^c*XgnNxTsh)j92-J~opr_-14}0W8;JW?i`VB& z{MhJ*Gb+k2Rr^wA?UGpqmY|$T&{hJy*)*(Fq4!WeSDbA;ld3Z|JH?TTmm-nd*>X+F zsdd6+C}l6oUvmO>m#w2GhP-Uakvq8ZJq>D)x5F|2_%5p9L}Rccv+L{5@S9_dSh<&b zhpxyj?eLp9jz1PSV9#OrN|Z-)>r10AdKEOF?++H)azD(K;~LSFn6BlIDJo~X6814; ziwFuOg%gF9O-}8-oKqSbLhbdg1P!nLp+HqBH-#Wm?}cp?V=ARrHSgT*vZVZkxMWz% zA3{zmET<~gLSrRSFOROlw!_!9q>i@;fi0oW2;Ki!_mT;yGr92l_RDcg!DWYxdHLNL>%?$k*iw%Xog7j8o^ zsB>*6`AKy^Ur&A$`m4?+ZUPBhO!9Omu{G#W}PlOVYnpnQ_b90Rd8kFg_ zd8=jy*85Z)YWrd;RcY=rJQOh!s$xgyAn{9hvo3x(w4X&~11`a#plK#5d-VJDh~ZuZ zN6O?`iGw%4b&X{y;>jj0e)F)K3>u}saR~39CZwTiw^9McUkwW>Q4jrhTGJu!wL*>= zI#Eb{zMC$b6~_K4^r93~=#xuhQ6!hBgw2yciIiq6U9~HgL@m{W0s5CN< zD;+5=QIf-J%+N!}Rx-yBW^1UK7%Wtwncf`s= z(Bu~i$r||v!owBgDKW2Kbu%}P&3*~b7C;NNdaIBk1No~UYo_-q6Y;O)e$%7tFwFFG zFKseb)8croVd(Pkz?P)_m~LG7FQ-%b3Yo}i+EyjL{vT{jWxlufZUR+SpNZuK+M8dD zna{+_3R6wxIbmoP6UrkabhL4fU&+`AIG_<3H8F+d~&SSUf?V8rh7F+ zpB+f4bvz*u!}p-2@H|0qMe{f!5Yv_@Lm(Sh=1|mPafVWi^ydZXFvreMOO19z(#T|> z0Q~*~s#1FIGpkq)c5SRi^t8C7fH6US$8h8 zS3fY2ff!uzDE(1;xbbaI-*-%x_$^Ce%3PXWpf41woyW87@Zp~Lo@ypS2Mz6JRBK1( z6n z14IGwel{2Cj6|ZPV%i3e!OW~b1c3&gy+lE2WaIIe-SZm(QGw5T721Y4#_5)gnDJu_ zBf>uX>L**JpFxkU*Jf<8Xm%Kmgq`1@k!${n)%6OaLvxX0~>Lv6y$I|u{AHjYJ zYA|}dD5%5t=Js>{it>&q=1OjaMDEl(=h$k=5i>$4>mXkn8pehl!)=%MACeqP*xiIn zO|E&6v7|P&i29X34UT@7G8_Ev+Zer%`@@ac2_LeY7i*eb^YgNYmHhmHAO71?Asmyk zH0V3*M{-SsdqH?-{)QBAW*mBwJteq7@=^TPh?o(}O*%TUFDM+ps* zW%#vJ{KdLV+2j4B?eR%;tWHKre#VRRv7+VYmk#MuZ-j>C4K5$Hs+h!8%GmObL^hZ1 zHHr?LR47#|JNIK`8QZd86`e6S=Ia>HCKor<+$gYOe|q+Now+jl`NL;mzV{caDn1;l zv6+`MH>htKZfKV|%x8$>nWrpTY3Xy~+%wydTo5IKw>T78ei)mI2whDfe49cUDeTC) z(w9UL2ssTxzd4wxImeWIR@i~LprsVnNc;J(w$BdXlv^Fy?23}@&M=e4XWfA1@PY>E zZfU$%piX`#_%-ooW~Oi4I~@@OEB}R)Ox&yl>n4=hbh5LqgcJ4@D|35as|Td)G;iLQ z9`SL8q#fvzS7VJBUe^;oB7faBk-lNVZoVw&x{@U`R$u{DzoxN zNxJ%9qovt^6 zz z+xXX_=@BP(tzb-dw=mCv_@EkR?P2_MEK^8T~^?s$KH-Aw^Q=UPVbOE zxS2>7+@sY~epBTbpQMfR-1OvP&qOV5cZ;jXb)EM8VGHfYIZlj7e!dNro`D%+*O$y| zPvNx58`pmt7tk#I80Pkwm0Ou#Vd0cQ6j0m>cJiFAIAa&gKcP~ItoQY`&hrSrn<)ga zBL$!^PlUuG(Yk2&S91hj!C1z3+U(p2bKBRRC-&uf>h8a;pU^#0^9&|$1kl3tld4YK z-&a2}R#Z?~kN<<8P<=buYJS0R>3+AJUelRehWPG}c`DZc9ovSbOI46D)qIV zLMQW}d5?Ma;?IPOK54%y8B}b+qplaE2B^~b7h`fm&wZt)un???(IA~AyABsaIim`G z=!{XVvNno&ctf!nrWe*3tMKjB&Iey--&k-ze?2 zClgMHz8E=r7^b=VYu@YHhwe7j1Z2WcwqIXg70@P z%bONVR-kP;H!^9@UZwLDNIJqY9$^cl2lvt7r4UBj5m6#jVcF)UD_$h+ofio;;^ong z)!DWmA8+eVY}O@vw{Vu7r@b!b1~@VNeE=j|&gY}i&;#1*H$+)B(CJ2I$qlHe2y#n<~%ZNw28oQ%43r6yw z@)_t9RN#jwJF(a&%zE{Q3p%}p?3QU<+fto~W`z3i5>;3I8LH#1T;&RRG$aaln zC2=pZU0dBNTi2fdm%jhsIZo#|$LYTB`}KOR$9O_Tk_e?d7CU-cTcNEXwu}Oe-xBgJ zCY_QKIqjNn39(z!^0TYY5i&IFos$b28yh?U>1_ced%R;zSL#R*R)qX})?@Ba4ghPU z-eXjqR|!_s_^jys@yblrdS}+31VW2_aYO2hFnv3QEx&L~Tm|_|*U>!Q0 zRtAhkD^)W_4jL8(1`9_KGF$Pc)NVJ?s(8UWn;Itp5WKT_T4|K}4vCcay{O@J78%jN zZ=cqfVRymext_dn(HPfI`jN5A*w2Bf5!^DD02{&tPGkG@cj@IKN^iO@su9cFM%|&7 zdm7s8d2;%;^!?%+pH8QeoiF>#448h9$=|Hslp>%nt`X?!4onL(Jk*{ocSbtBmyX9d z3n#?l;9uzgWpZZN^W%UK|L4Yz0rGV5?+cWFllGTS+;2^i6)ew!hGcW6+6H^sZoh%< z%>JqQ3)z8wKMLATJ**|!^pPQ;_yt2{Ze}pCuiBj?WU0aGdOv(L(6{o}NxDP!Li`Oj)-_Zz3gwOa2Dsl+(+Qgya!;Fab(J*ZIa zs8ZrXdKz4f-IIFx(Uxt#sb@7gXcT8LCj@to2ds6z(J*Q^K+`H7AoMlMhCNtrme(RE z`_CgmhoX*_skE=472QwYXqrIMS|P&2N@^DH(8opU!HQ9BlHET)wX$1f;o+^Z%nb~~ zPk!$F*UevCpKvF$r{4!FK+)6@@UR@VmTxijpDE3BL5>x!=I@CpDNRcfJVysQ>cxQG zy?~GA$2TrUWr$6^<-@ApboUz8=EOyBY(lmnuWxwsa2cdR$L-Mn{7$x9=_U((v5(`U z@$)}-#dLiIix2A()hIL^D?$uN#}+v;gSL?+@$KA_?$Il#>oNCf?u6cnBDAk(n-bU@ ziw0PrCM0?UH!G%5-)h>07MEKAClXwl=aKk4E=Wf} zW7D#Goa6l}xx#L~p=rM8*!Y}Kjlb{C1(hcv)6120yk8%<%gi>~=zH2g>Y{IUZ zQZe}$pTMw|ccy7hDC)a-YpyWi>%retXf3=JrEFNQRd8xsJQ=gx%X=xhrE z&N9O?fo`%+QQX9bX?4^~A+4^`@{pHVMZIguPy zK-z`qoWK6eSjjj_JROg7F55XiMP@h${w%w_($X7yTEVmR?3L$F{Knfk65$fJ{g!Yzx$Ki3M7(k3a)+U%1g7yZa%qycyW| z3`;s$OHRH7CmWG%o`t5@i1=TC&uy2Y@h=0D(^$SW2t1$#~B_6WB*@IGbkMpuEak6~#EtBdD@p%ns zsCHk6u54w~mXrBIIdsG#3de`l|1Ze{wm+r>H(j2YU)2C(kM((=>q?`V!e^bw|Aimq zQe(6NL;qZdo_INhU>X|x(X`669e}&YVF&x!IYT9h#l7;ICCavtX{))AZ7@g*%&y*) z*++HN(-%4CzEH^UpzBu4^(8+lT(lawNQ{E%hwmJ(LSNs|8y^1yLR*_zF9p`4E6X%R zLfQ~u{#UlS#38qV0Wpn}RzSOVe$xr3M?ilcEJ#&t{V;a@i`B{ByZP0ZsM+HrD;6wK z_!lR!9IP5E0r<6+y)q3k&GLN9ogqm3oyt8U-yuqM6Gf(ady8NRuHfY3SBmb^hvqtJ z2J?jzd|VvWkCIuUh>>f6?{+ol4o9+Ew+y5YPQUA`5i!X{EA_EvzsfoYN^3!1x zBBoln^hsZE!2z-Vw^u~#VvHWI9!lf=c~fXQ3(v-*Uz~vF{`R!<(ZY~M+qaPaqzuX+ zCQYk^%*Z?I#X*#;fn^IC5d71N+_?)cs zg1UON$L@hOSEg<0K9}t@4nF9iA&HN9n$Dz!zA5v(N=z@VrsY}jX{71qrK@bc+8553Rhh_max2xV7YHZ2xzYxC&1wLiM$C-{MMoUeR_zL>m~x;<;7GcYObib*kJ zt1SNsIT1$Uj*KQ~uSh*YUS5{h!pr#14)Vp*Rh2gIezfT`lSu|+F2xb<77O)!6XOM~8>p&`0gFL%XFnAoMpNz^`2$+HkFHDzh&B(000=D;fbH6P=Km=7sQD@07N&q1Qeyc6T^|9_CWeY3k!dy< zTUTiOlLtEdd7R(VZ_ts4R9|B;dND4_;Ks%jzn@gfJZ?&Zi8Fjhq%#8qd`B3_Y}$&s zj~nC1Xg|)|B9~>{d^509m4eI=+@dg3KdmxjJVgkd6>xXyMM2)*>ZSN8Kr6xX0iF?{ zd!N7J=eiC_#kwfG5#u@dUqnU_ho?)^B`ctB5j;I<$wPgS_^|`a*C3R)DU+uz8E69T zj{$ddsF;U(VN{22ad)bm&UC%(OWG>8^)0eYM<#;)h`KGXj_&BQ^{D}j4DL#&BhxAC zB1$t9d=kDr!>j+S&T4QVT9V_IGMQ<84LP=()nwb=&al6cp$O^Q#P`#P1u6dU680;d zyU~6OXUD6r-=7bQ9zWRBnBu^4>wqJIyY95Ta_rXBs!vRjFyUO{m4sgZ{c{hV=Mwtq zv2@KcBjs(d0?U8Iz|9u%JPT!5--!29W);>m7Njk@9E^=xmS0lK@C!uL;8D4!WyB)~|PrJ2{l}6BD zp^4PW$4SepJ~Z%%i7$nY)O&G z)Ndf5{M@?uE|6bOQB?D>m(o~`rle^Q9f0GHAeA4&g(r5T!|(sR7QLVhAC#O$Z5(AE z+z!gF`nHg{(w=2*?VkhVG((0fU_F~y(&ssYiN%HzzD^1t^Amr?@%BDo_ZH$CSZW+7 zwZ}9z{I+zAkHwi|(NIa5Dru&>Y0oNYhG{IHjfJJ|QzD+AT!Ikxh}-l%sP2~I;3&Nt zxT54V_)}mr% z_yI_zyz9QN^APV0pHeXNH2m=!G2oZ30yI!4Y*$gAy`zMe(Q#)`xNTv47XV@j@Si$mJ5$AB`pitcl@%V-YxAj_K0(DG zCzm_p%9UHUNtjxk7e+L42fan-6k&Y|GwhaEeQs4}=C|PQY}Q$h*6BW@bja=9P3mJ# zj9kpPIw(v%MZYNP7#nvv?;oF$7NnAE_`UXrl@Ef#hkU(*FL$!=%T*px_ofRfWvA4) zTc?kjg96IWRL&hL>}E}4(8>(P|MqWznBGrgjHJ2u`B9h%9M&j$bpnufat%6cW#1i* z12Pv_ycPyomVvweE* zwd3&FF-I4P>NE~*Z&V&PRl_%J{xh52zbSb>WAev_&SS)|6*DIsHRv}*yU?Mdi08cO z<-`Lmj?1Kvk^<;5U!UBaz#IP0No3edjQ&gYaLf%X{$$N39>TFCuW86u%LSrgCDD&w z`Cb)@(`oi{wr{N-IlP_@q2X{Y#9nrkPj#*0KC1@oG3N*H&b4U<6Q6MAp#~i?9bf!o z@UX3X2ioibj?Hf5FOQfM2KRr8cKoqj<5a4G-G-7EU#Z1h%*CZ&OT%)91A-nV;GP|) zLJxkd%FdMx<_BSy7r&ZA3Et5;)n1 z2lHb?HdK0PR&&UdC;7;VK#&R(*h*8r(8fkn=N-&3zcZ=M0U3%Q|%@AX4N0=2OhchEjnun}+;8JegDS zfH?8KnXnO*$`~tI^W#2mUp9W3M=@nxQ7^f}YixZVr-Q=d3b#wiOVOKg6H(JmD z_)N<`yZ^+(O;rPyQ6Rcn4*-MnEc^=)lO22~A1T301C?ec@9zHi`u~AG-^@-D*opf< zy?P=%`$tsHbl-u$J~`vK)_G`pC*ZB`&t%tR|0YB;8j3X<(LqKly8mEhNp;j^xO?uK z(D)4JYy_|Ab?uV|f8839??f59WL2DAt?TX5t)rv=G3W+!Ebh!xO5Z6zcZvLp+Yf2d zwUuNY^Z9x?yn8P~4BpsJ!lmG%^e>qede&XJ8>$#ZkUTx}_WewzW;3nYWrQK89ic{qv1?pe6_PEelINFc!$T;`Fcu$Dh&M9N3>OJi&eE zN~EwC0(2o<8LOQs45vi@4GACJ8+kBf^-rO&c!w#9?c(;}n;;ds7VAp>$PKPg#iuDj zx_39(a{jE`cxiE5>O;fy@lQE{TXdtaqz{ewEenMbT0)BZoU<8pD+qVmY#rEivLf$1 z5y_LY1_GH^(T4SMzW*?jUeT6VY$oOQK(tqARR|^VO4laELa-Hv0_x_CC_@#z>lWMX zn5Tfp{)X!#4+3HVX*esVPdH0x0Mp_ngzNZ>A{T?p&Fc#N4nKgK~ucbkE!&HwsdB!a*bZ{u~-i zslwG=B}GWv-7j*4e?3Hr#3@`%u=*r_au2zK1 zaqi2ZGoC`ADJ|=tt&F?_uM?=U)PU8vQDe>t(R;0V!ml*voOP$kzSwwp{87m7U+-OA z9P`%%ty~DxU9NJ0?TjZ}hMN?7v057&N||BKF%xTTvZFq9uV|Ge0|pyDzAn60EEl?J z!UCSW&J#)ul*ACcF_nvw9gX`NrmzzAFSdY;4O|#+GppcyGOEv}?vf$`=*|2^D~6s* z3uCFnNrkwr_UF>*T&JMF@z}twB}MyyA*ll0p5S!fihdk@dc)-h<@tP-X~Ky69Ra+h zP->ULl>kPfLC=Kwkg8BS-cUUV-gcYTy^g7Un48<6v(P>#{B9Lr_}!2pE$)D9_kp@> z58B$>?=`72RKzra*vm_I`-SKfS%}Xky(o&8rT=6(0glTRnOv5ei44K#|^*(lEMuY~8$g8N2L9;M?s+q6Ff)j951-^Nxu#Y_8kVj%caRx68 z$fXLyi~Z{<{^5vCr$AyepY`XBDC2{n(Yp_~Xj{#0{183mn>XW?)U(ny=<&Xh))4A= zCT9Zn0ZI6;1~ljC4rNYZxtDTyGx{>L64;{&$zhS>8ch9aA32NnKdvPNA+t$-XniL- zjM_S|9nfqwMrlOlbb=tOxn%E7;(B_2u>!f($pV4u*(#w?4*a&xXm7uR*`0oCx* z%@4IKn^xmZdAaR>i4P|j!~JX;l5n({=CRO2d5;qXBE0(D;#0B{ZFcZ4ye!o+ z>DGu=uwt!X6BK=GE6u60WaNnf@$9{|?ni#{&EM&w7chJN{las9Y8JsGhDKm45RS+R zMkem@*v9~gqIhSZ_1@oL+VV)>)1r4>Uo7&A5PZMv`EbtVx)1NEvXi&YI(?>w>7}0` z%38?)DYpl&xdvk13v&L$SV#lbDo*_bDp{Fqr>c1B>F+>2ASoOG@W+aCDD-tBdz9GMg`$U z1tsttHtUTM4VX$4fgTYBWBsgo;(4D-{~tp$6n_m4gjX_Aj%ytm2|=%WEQ5dPxG_*^0tE!lH{{rBC0PapTr-kC?(Yz5#>u#E8-Xif+`0m?qqM zqYSBA(fVlviFYQ2+NHlue*~I0`>5M)JvF5^&PfmfLCYRe)$UArbsC4!TC*+U&G;xk z@`c!Cjy%&bC=wm#O2^8ElTQ8CTzo1Nsgtgq<(p#79|Ouc&a|9*aCZnYYu*Io28dIb zcYL`D+B%$WE&qp{^Us^Mk4_SmsksB3tG#9eZ~RSi9%j8Gt?zTAZ-N3bStVP{Nq;jm z=c!!^TU+I1SiU0 z9K(tsLh{Iwc%n^>6eY%)6Ph8biC3~160TbtpF)T$2LopcON!}TmcFKE-%XiMvt)~8 zXcLPfcpn;Slhw&YoO5r=O}-3xe_#f|%c1-prZn}={4tq~{oae4_VF%o)I!gF@7l*~ zvo{#a7Og3c?*oC)pquT5gxqk9P_7S)l0F?%8Se2E3dGwX5~8G|8!;qwZ)q_c${Y*M zy}uZ)M>QcV$>HQCz;ZGlf;^wDhDz#LY9g6U>{2& z94t`JIyOTpCJ!}Vts^d*NLWn_2R@QUt*8NnY_IZbnSOvquGhrm49^lWW zLUIHRjog_y?M)cn=rMh`l+BUC!X8%%cN%0v=SwA^a{5BH%f$jd{;xv}KDXS-hF80F z1hx$wgKrJy!`D$Pjd95r$LBs3gghv{XwS>@+}NW??Qo+wD`)-6#k;a zR)uBh&3t*AGlmp|wb$rJ%bL~4I!+a?f4j+mF3HsTr{er9;`{40R#+H2Et9JRx}(qB zp`1~Kk`o!P{r5`nO2Qd8H$>Vl!F85VR-r$pYBEtI5O=75O#6?Pd9sNmmCo6_rB4uw zY|Q*k=AB2C%fvI5j^A+0-r-X@(cp)wr{`1hf#K#p>V1Sm)<}J`t5)KAW2g~pnjrpO z$`?acj$!>a4zeAZ1uN=1Dk5bqAn8~c_yZ~91OJv#0xQ?-$?4>mmdV%d9tbCo$mKQN zee;9_7f}{^pW0gBDSXTLEmgBB_A!R4RaVv?Bf;%Z=#}hYKp^{5ZCXiS`D^Z+7_^H(*VPpfOzq$=fXUpo-c>Inne0(E(Jl zZ6m6|nGV6E{`~R7L^IzZ@m+d9o26G`$CzV!59rR-Vl=Y9)!E$|Qan?sBNVs{DGnS; z`c@Rj4;y1|e(3&{@no?EoP=587YVhk-8e%Mtr8Uak^s32>wfmVtv_rm_-Swd{a#Op zr``WGpe~ew1O9ibq>wj5Wupi*&C}Y2Lllvuc9UkG(-!!dFjY7CVv}P)Z(~U}a$=GB z&HM#k3@ukAm}3-`cWgFgtjAic5Ta98Spn0sOY-W{^lww)0Q%;3@fDr>0=Y=Re+guQ z%g=CWE|jNB@0V8=>|5anMpkK}Mv8O5c>beZ0E|XlVn!MJcvku+KU0`LC2 zs~%V~iX(-75v!JZi>OKS$MwIR0wM=@Hm!FdpY4JTe|Ru|f2kgnBe@AqM9%xmp=k(l zu3#x6dUSoat-jv`h?lnlx`Q&ED)xB2{P$g5bn1W~$5#1K5Z$smjVr)}tYMRJPP()- z=!Q4ns{YBCA?xwmusL8O=`QeB^7FRAxn)*BUPXoqpAqM6!khr`dgz{ zzakK-fEM^E&prNDMkH-EWFfP_A1RQ;PzND(S9zKU@KW z?&SR^RwF0m&CIEJzz{OID`kd^QqUfTUc1WHF|ud?MAcs(mp^Pd^PqKs7l-BYR7~lB zqQ}$2n_O(NV}(C#J-G6QR{!R6_X)DPh7@ptcBHv8!_Ig=AuOy?cn=G!9w|%mH#Ep+yH-3S2n5ZXlM}L8<{XtM{mtX}LprqW}$! zpG3yu)VRPP?&Wv{01O&shlb?^VDVBIzlmU1BHw(-bYzoZTVBHWtAGzz)YvdYixD9A zrhnp|;V|-2ZI;k5Jdn&v5H=9Th|yzf^JJ+6)ZFv6#jn)Kq`VZUVU(dAeZCkxQkqGS z0l|zAnGvQw$n(&<-fP6<0W5f1ZQS^9+UaP=5LviC5`Sunz6tbepS%%NchII5wh-g> z3qdA0Hhr=ex79u?@}D@tq5!Rb&oR~$DBa=yFK1s=Y$i~*NUA5cK4!B1aTpN?fj=9*+7R_G7oo%fBn9@K9XUI69)J_5yi5#f z(4sv$HWnAmELBv4@%68_olq^MWYF&Ry)s|#2t<%a#t&QZYo{i`lDzt)^$z!$oI<@NRlU&2 zFM-)hBC}1ywQN4-RU%gueFqw7z&sx4u?02JfaMB|oOM}TngNCh_W2qIfO7F#cQwo+LM=)Kj^Qu1-7mfFgUf}#wz-Lhb8y0@P*2{xhra)+~c=LslmsF?v$bd67R=p`++Mu`w0)nx==lI*}v4iisT&$^%>v#=g#Xr@+nF)qu< zN5sen4y0~|Z;gsyq2Zpht3MyL%j&iLO}fkGY9}TxE{S>XchNLKTdmg zmo8u-Yqi5RLoHbGDFdvU?m~RoEwG%g_@xNIe7|fq3$G`urOe;V=+-6yz>#04Zij7_ znmBaGT$*+HvAtUve|cZ7nWxbJq>dbaiwb-Ed)w9$v~TPIwr}O8>66(u;+=G<>tyV* zs?bC3HDB(Sn3479bsp8HR@B!39?nF^1wiziOyhta0izYPRk?Lz z|82cS?LYgZnwPs;o;k5AaDR;HwK7*xXVw6-gtsWWSz)($E~QNszD`j)qt_aBc?brV6U92;_88D41}PGHzWDp5;)PUKbA{MrUbIX z&;ZA#U)7k=h^MDiH~GIVo)5vpIU(1!{-m-m zH)ye*A$UsqrYRc^LEQ60SKi}s8UBusKG7gh?iRnGV7|qaceMRXiDk@v2PjiO>C$lE zTPN{izTXuFP7~OdgZ{*kkFent7}VWpy|XCjSxkX*m>(e4_O>aj=8N)w)$L}4n{y4L zw{%;-*7WKWD=wKPc!jEQ>kz9_OM3yLf0ikr4VX=MS4CkP9-tUE!gP==rpmAG<@@vccBVW4sN}X=?io}`tJUR{auO*pRiSCS-^f(l zOrE&K9dLI-9Anbbt1qooNcnKa^6x8Kk&eUr+T1#!9dLdURcfc4y}_V5X))>8-$duJ zjNy(I|5|U)9zq1V7}Z{rOkg`Dbyh8=0Lnj136fzErSxF`Yyr$+W`(;_ zxYX8~Rtb5gF5D+R&10bv?m;P)rovIxDb>afsOzZ)Zc!L+*?*8h6SX9!Q^hn;vIIUg z6h6jm)F(&k6z>iSbCBJG&ynj<_0{7KPa=Y03T4a!tajbK&9n5rrmM%?w4NizyZ;%R zbVzmwIX=>m1!=mN#aFANiMd!rmp~uqRKigwQ>C_M3KJUp*YPV1GZmpo0F(xB3$;0k zgEvKcgw}KYPGA!R;54uaG9k`st%-q`<;Y1xepAs5$;&he)@rbPYa8SeFg#`oK+q8f zO$3Lm@#;I$jAq$>-wz&%(yn*^#n6%9fdmcTQ;eetSQRxJQgPpJ=45Jiw~)0xBFsyv zO5LAB z$+vjoK@?)Eq4}CI%1+Qfvn{Kt>^T5|NL0niOo!OQfwhB3h*WDcp8^KUJThUqG`S za`{<(v%@s@QO_AN$kJDLuKs6~lWx0-yZubz!M7Bh*rnjB$^oB~E3H3oCRA}k)NK9< zr~8;(1&dqBnm@4A`J;1t%4a$Yy6>C{1s{u(12^6J;J!xW1d?iZY-R<>EWHaifkHP5 z7LTu^SH95^nBjokZKY|E@Ik5_h;>Kvf!Uk4^4}@3Ayk? zeC-fUHRbQr-HiF{~s0QiTwP z5`zFRa)Cu0r(PquhfVtb_6CP{SpheM^oXr`e^Li3`P0PgfthA@%@dY2?`#8FskZFI6%mP(HJCG9niD?*m7z z?5%M{oRF5mf2$&HUIxkuh)v-x$s0izJ#KHEYhQ=h+tLpf21{e#A55rpr9K4Je&meU zC6wgsCp}T^&$tREuwx?NZay#;w$%7wAC{Q$L&rgBgy18qF%qgiRXhGf<@f)Wr<47I5i-#`)0+ zfNGhV6q=iE;D7QN4rQhuPb*-fl?31^LC{nHM zvhs;`WL`Q(qE%IOsHbBrZW(;dvgPYP7E%6%2?u1?2|aBSTr75+Dc~Nw%3D6-T#X-; zenpP&gw`PCgO}z;ZKjysUl{xK8BEAMN@5>`B)ZdDE}H*@_5ZOda{nzXUxs2BTc3Ls z7Wkv|4AOGndbyMP1?xp$l~!mbHz2TNTR_m%2b@jf{c|-f4N+C<`j6maJiKzESHAWBlP2Q8~mE?Y-u)?*G5}0_PDkO{r zx^5ok^U(PZfw~O7kKOa%t9%P!pKJp~8_qeRb+be6>p4XYXIFBR7xEp1BX`Ej&#j0? z#0s0;u^oE-LQc;=w`&Bp{5ZY8up{MRAN&(ClZ3^cU9a3s1XE;t-X|TNMbyRrHxW5h z{NAoHq*w2-`PMHJX*-payabQ~-o^v<9yfz5R2cG`rQ%RLp7cSvj4wl+kALOZbGBiC z(wtQKOn`xMUYDRinwj7{#S54&jXP+P_dt!Y{e-JbajOON3*bHJ6Lzv`S|zN(RNcz) zCn(<+A2{4tb6SYF_t0(w8PFC$}Oi^TYQ(SWnkO&RVTH`|7iglM3y^guxJ=-%7jdW z1kil}IPZVDuSSVI@;7YKkQNE+JBvFGAV+Q-V|s5)deefCCg$Sc&XnNwm7?gL+>kPA zWo~aXws{PCutlwo-LQeb1n7P1lvU_~3vF2@)qc)wi(y}tY|eT6*WU%xtoS>P(r1a$ zdbcNvwU=~d?IQaWq3b#>Sl-)Euf&GV^q}L2c1yh%T(m=0pZ~jPB_vvXFU?5*#2ZpB zqU2Tf4+q*NXxc5PFP|Lk6e6l|ExNLp8CCd{K$= zGg&K-FP}=#=->AxMiPf9UfPc_T_8OiP)~1UZ1-sVM?<+b1UAJvM^3ESBHuWYv_JUS z54&i=(+TrgtK5z9s!H|U3d7J7V)W*{qc5=<5&A?Rz*zrxC}giF@Otdh1Zbk#)vmUK z&}Ir+vMVFO@Plosn1fIWf=6@1<%a`*4i@U9$3JA=Ihft zCO5&*z9q{?FKJ&NZmL5MlyZL!#6>x;MK_PD@n)`v^|@aL@& zfXqe^b~4mk9vf?)oF&>$*TasUr4I*o`Qmw8-EYv2OH=F>cE8w6Yt|3*Bx&E&>rj}P z`FnWg={K)9in&%a?@FiAhWtQ^SuEhx=M9y$vNe*+zwpNJT)mtFeY*%aknd7Ww!L>gNV``<{CZTrH_EKLN1)op8MHBqQz7LN- zYRRl{qXY=+*NWgLhP;IzH*|E8SnzCE#aBvfRamw-4)V#mzz@PwWX1VR+@L9VL<@#q zGvwzVAs&KCpC1&1CxpCr9x3CbW9PYuGBvJ?b_>bN&~WvFYz#c2`ZZ#3oN7hsE0y-O z?Wg(qEt$nIwvIz4RwzqF$nC@zu*#kI`K7Gt+M3hEzajp8rsYTg? zj3~Aw%~aZ%HMt@@t2;8hPw)Tg?V&X}z4wPJ`A@80TJLw#h?ab{Y8WhM%JUr$VrlsM z*$FBCEn)BGCM%z>!waTGKF&t@xOx9FCiJRbCXD{MTs;dBJk7ar>2JsFioj5`8>WWw!nUY9>Q-3QlWaO6x*#6BeF;g+gbU(wSgxB-T zw}*JCGVeWSBK;KfY7`k|5}{vF;a;(hqx1&>NG9NU2I+VNRHvYG(nMl2czuyZepyDo z#zrozAM5{Rz}M_gk_h#x=8_zEqB&j3IjiYvk>z9V;>i3N{t_oj&ITu?;2Y8k=VjFB zhCV}%n-B(H5zku_lwpq;;2y)#@j5v;x<=*3(c60^saex<_&~y+zP!DPkryq}9p;kw z;E?BF9USnuFn~2znirmC`Oh6+yqs1Pi>9c~?PJ`=Nu?`2}Lhwg&Y1 zu7c$Urt+)YX-dZEz_N~zALbuewWuF1MkH5qo@vA$Jl(ZjnLbon{78Lvt0r0C7MI1k zbEpU=VG8m2`VxJejH*|nBcFn}7Xs$z($kZ{6am^!u!HAB+bA}f@WlhPQ=1I4=@qig z67#c~5>z(-?)(rSOuPR`&db0Y=pDJrsFBrKtny`zt09F4fx-mv)S|9l>WUQqRUUbq zg_-9+`o<71`CEenDTamC7j!F*V@*=@9W8$0*si2Ri`iy^*^r7APoKT%A5?W@AQ*0lz#T!&xyO_a_snR@jK0H*Qm#2kbp1mH9+; zU_;bEv|XbR#_}jA)#}M2ST1wms?sVJagrM))#e z)GH6SWT?jQ7&bo%grIcqO#6HJN|`pyN*4BDuKll5k<4#XJHl&ZpWP*E4(WYp*@|mM zjd)s&GK%G^tv#oU|D|2!wbwP-s*=fJp8OWejuMquDyJvp)2$)%*zj{_n%SsD zuVkmmmXz-#QfVVLY-ZGMU2>xUi+~p#WHRhaXSiN^r?|a7u^}=%h4sokl>T3QCqL{s z{H#)+W%mA~c=0-B=GjKEztd)9h&$ zeWnpLzke$N5kBwFx6pXVEhsCOw?yh3YTl4oKRr;A`>(EfcD>@%2Vwe|5g<55PkAi) zYlc~i{`Hp-Y}G1me6K=g2EuwcNuUWu<-$vjkWOy(_3p)|_scX0c8gk_B2e31HR8=^ zQ6Pkn9oPeFFD~NBfFqDcnV1lKCPAaLtfv~reVLEQ>e7~DIHAkQPB@f5iZJvdS^}t! zc#yz{?WLq?YxYaBP#U1QZZiOM)4y0u329|^50pr`vc1HWS@h=<#nCKemL+4Ugp!vx z^8&Vlb8fZYGw#FcZFvcf-)G1R9E0Zq@o0Isy4;{N5ExdX`k3;8CeVwgusg7xv`)-? zpi8IwZ*?9@scSeFN)mFXL+`|k<7kOy%l1+*Y-|6la^0$>)MF@s%>w3oleG6V21C$@eKr>Bfz`rC~{K3pbMVnve+x2Mw6Ws9jX@i8{27a zbC(?hP3D+9Xettcs`a$5GtBHT7=<}|ZAdE=yrlT{EtwKiqR>hn@{}Jx9lmT`x24s} z*Rd7A*dC(8aR4KlBicG9dLJ==j+~|*R=ZRell)yf1XJJ@I?NLq>nR+r)X`8}IOV7n zVI%78rKaGmyE~5=6m~<=%}$E;erN2J2M`Z6aXTZ>&3(?0)@WQC=~);**6FVKXFV*; z{%yFza^vd53P>zdd%A_28SiYH&;oP-quX^JIqGH%CUf4h$HUGhSWa!pOi<{fhpy zHHoGlk9JDgX2UeJgN2`B_w0Tizaa<@$nn-v0g>LecZS*ye`Zk-Z#N7tkTKrsU)YTF ztq6@D*Q|fdemegRul~Ci#Yo)FwvtmW;NE`k8|rm(cKO$j%9-wWlk!B}dT+TSYat__ zkAr3L!2uFoz&Ush){8ijp3fQE4bERjk4Iot=tO_dKRY5}K>hkmrS1#+F5SpTJW7!Q zr4bRTHW2&VDL4AWlr%=rcxGl}?JF~WFkT7COwBw zD^I~8_-k99f?j`u2F5wr)=ST*eP27KMqHnrl%fenhui?T-i0Vq`V0B0?S>owRw<4a zIG$-1>Q;&we~>^BeqqvF_0OpTP~Au`IAP)&6~V`?3`IOkaUvZl4Sa5~9Aw?jqMy6} zZ4IMV*4#%uWjl&8ua>2T&btLk@&gTHQ&^NLq>lLaFFM=wzt> z-^1k@h@AaS@+E=FxpNoDrC>@D)ilPGF03hD#ul|@hWC~Pe~zlsflZUuolB(Mw;isB z$Z|Kwy(2j%AIQsanTu!eARMF&#)m>K6M@c;hoaVq2Y`|3zBhzrg!F^5o2qX7+1Fg% z7M@LCTYY=n;3SWa&hkFj<@nI`_{uAMegsH$gW^DWm>xIB;o&vY)w6u}1ODSOpBmk( z=c{hxq;;P9^gfZ=M@K5bB0RdL>u=wEct7OjEpQ?Gs`ON2Bd=&04ko!=K_jx^GZ%lI zmUe)9;w6}r+D7aQ#78a`zhQ6Q+5x*NS3Py5p)2xKq34?G2|JS(ZJv(#Dkna%^T`L5 z1D}4$|2JoQetE0y>*k~i;9e*T2LE8znhxt)S9N66n1QL%JE!dQ{>{Zon^)5GS@Z$a z%8VU>g#T1e&9(v^#SGlNq!<;uT2cT?~UA7uyY(a|DYmLK}3|f z|Fg~GqEpF;UCM-D<8bEOvZc=-dfv+L97i6ctk3WqL6T!*?D%`?yKdDd5&S9_T;6z~f@5K!-Z zN1+>Q+o@?0N4sE~_^GdC7e-zno3%nR$<#sOxpdX%2HNb^631p17S)^OGa|HN*Mk zflasxcZZzn*)bhj`IiS{%90i-RfdagHPXF;N&1-+t6FR2;Ti0S?D;ex008#gO8u!B zb1KBX+-V>{Q|l7(rqoP}EAM0P2R4tx1vNQ%+F@w3F-(ZJV!WlRXN|wWS)C)J3w7x5 zP;c|wYUqyEmOs^vuMwxPgDQ?wn(4n+=8`cZ`_eOtcC5v5KM~%@4OMohvqY3#i^R-S z4dygVqEU=EO#IUM&qT-Tn{?L8q|nFJ83=K&%yX?T1Jdx%V$7uYAsBV-ZR=cev;8wfd=HUaB%s%I4&U z=R$Yo*`r}Jv{Kx=$CB;L1pilL0l^^Kuz#bQ?)PHb(4DNw)6%c~hqU zN>>~6!pzDo^z#KLyqRjJh(=MJ z*TB7D59-{tm}!~py$05TZ@(NrXFfX%*BSxF!4AC!pb!ngfGR<{#Yo{SL;=?0SRMC~M z#Tc(E-$;73?@I2=84*@>CWSq<3?U9PRua`zW^O-bo~vsX>B@#gD23lA8ow0mx*irx z3OO6*g;(l)J(mg{pah3V<3p0m26El6p*H&Vpftryj~<5<#pw9&Vp}oQ;yNgItZH2= za3sLf0v+8}d1#uat~-ygXti@(xLke<1X8$@W+FVleL=Mz^tSCgw4C`W$Cs1{>>QVw zeQA1?W(y?YXRKjYPDf4FE)TBmZke98b#R=Vam*vY*Kfg*e&G;0H3`Nm%(d$@Qd*IE z9AW&oWIWE4tjbk_W@J5(Sw-olkTv)Xk>}yJh|QPIw*Y_lZRp3BPiwO$`A^5%=ASYuS@Ih zyDNvn-@Gq$zqGYi4*}p}oJp1APG(R{x8-HkMtpp&Ii)1(!@-neT|-U;T&|8ljX8<5 z{bqx(F=yyOe%|M)@@~r8`>S6U&)0ku@qW$snZx8dl`8J>=bdsGyp*xd!QY(TGIvUq zY3^f^&h8V5xb14i4p)F0l%tj%{uChN3btA~p zw|zo#HRyx^Sc)}n4;1V8CNP&4k!pWmzw|{~KVr z+uHlbF*{GI0=1>6^gxyjsxyI!3&?GPrIq3*D7NDWHg7fgd$(SH+Yo~O*cc5cfwox zyM_sN$wP0brHMEo;$ZdiUk?%XIsWiG9w!*S)P3%H-!JlL?sMDxCe-zJR>9-8(l};i zh4A_E-3vz7OOE3%vH#;+$SuoiwM5BGA(nXf!*?NXx7_tJzUbfeC(BMO_RTAFPuZoB>vQ)(18!^UO{G7w z>6_+gV(bl>R%ZY7wPI#NS;+>$PLWf15GVGdh<2rWiuer?B~si^p+I|F`F7vGer9)d zKrTPBo+zD5S1C;xKTJ@r{B=u35C+xXU_yYmYp!M&Azg28hNVx--9HT1^YBc6{N5n_ z`_Sqk3q@sC#Ly6U_jU=bop_OJ^n*wdaYMg@w8CDR=Z?WuU)ru}ce<1P%UCbOg9nu+ z4lZvkC9Fjz{8?~Qoioj0F*E7_6fbz>URjQV9I74|b%2BH*@C^mvG*lLtYBkzBf!xx z5q>})8Kah2^s#vnF5+edBDx8h_pW?7lTHrvh{V{`mQ8i@KA`d ze;iIsE>n^=uv)))YxC{u<^H%Z&gA4kt^;yhd0(1lB+j2RlscIO9$jQ!ZnOLt<%Nl_ zG1u~Sn@aPO6ib>+{g=o+l5t%#zFx<)^9yxZRPn7bEDq)-x6`R?k7n$BxSYPEmp$>{tXLO!~C zHcbdY5iH8ex=Uzjzx9}qYi@N3sIr&LSA|zF?})+%GoG+FNUa^5(aR(2woqkzb2T>N z!=JUOlgaN&+_igeHHI#WQNPr{KOm7ILeoPpL(7u?qVVrLt$TeTNYvIsSa$H4&fFJe za4*S!=J&)GkEE-HYHOJ!8d;s;cI#e#Lyk+!rJMgGpLyMo^?WC`C1o1lkhs?hs(+#o zJ-^B)9d(9MiRJ0Y{J?5hO6fVJvVH)fqNcuYemh9=xXEYTJ+9mce|vfN7Loh53yYD?#x6NQ!r(_Z4ka$gxR2$8Eb?e0 z4AE{~z%x~MMQf#@=`XifXK?e!Vb^`twwjn@ZS{EcFRJLpq)({Gq2k;S1)tSn08gVWk>GbX-LzKcWIQ?tKcWjepnPb{I$LuMt)y(NcV9PD-;s zmlAWvXt~XCL74^aeLb^KBB&1Ya*t~9{fP~HfA;$XcUsLHg<)FppeWSyF@i{d_q+9& zEQc1di)^9j+?Qu#Hg5hX!*(|_A0LudAM}fCPXvv_De5f43f^)1`n3{<0(~GfB*u~} z1FTI3uHd5#>+GCN@z17EsQnb&WD@l{1B2zxYGJu{TIV!6kB6= z9o}DjCGuUOeL}(^SuFVZZ@6fqNvQ!;=QbBaj_)(0+fkT}HO`eK?h7Axy%?7sZD`1% z#r$d>`T7p4Z==%i8T?^F#jnU_m57p6&>gFUCZHI#oBpg8`&jmW+~Jw zEZy-qjdJ#KxeP zr_pm4wM}8G4CHOdXsu#xMvAq~3|=XZIz>mf+f4BI*Qra|9R8{Cb)=rm{sZjlRUi9vzBxy=&)fa{sl}%GI9Y|eU}S9Xz` zKLk9@{vsYq5wxaQMYv;U);qK@TK&=~t+V-@@#f~{M)t248!Q7mNIZ;Uzt(SB zz1R_u51*cr5U~ByT)_IJYhu>VTQZe9{3Ek>Z(tzaD+(Ia*AL#go=Q=PpW{A~MuTA9 zO&#r^la9_o(QG19Jfymw%RUc|nS%>$J7&AMub7W>i!-|pEDrcW#dVE&aVux1y%x=B z`9o*XwSlWiO~#y?=aRlb^0-EnUI)B`#OUb#zlUAs^KK#3fe`(%WOm+}#dl9pKNvFy zetL-EOqBj)cUyrtgZ2|nt$kEa``w~I)Lx;F%8t&Cwfp0;?F>eLz`!2@b=3>1arPzj z+4U<(9Cg2g_>za($gPy{S|JjYYaTDIIy&=p)^oHyoRpGG$h{ELY` zJl^_aVM)%Z(`#~@A652G;hrZ4-LdSSEM>}0wz8%8zqa4ARH?vAdy|14|w3OZ24dvl^s~`K_ zvR7*rmTU|o-5sJ&X(I2F7vmZ3y{y$!U4~oJ&QUcklrf2O7h?BtGO$(8RL>Qu`Sx>O zCYWit?Fah$pn+;^lamg%Mt`{X5mvZx7-4Pp3ow{+N>fo$p-vj5NE=_`8$VInSL~mb zx0%(?EBQw+pv}ZlfyH$BL7!fDzy@GN_Qy3;0QA+Q+^mR)LRbQ#;+VqSW%;`~<)U#;NhpT}Do zug8zX5%N5osC(_p@O|67MJJW`QtQZhMaU%%Vg)U7;--4))UF+zSK?l&-9K_ku8K&3 zh69j)K% zl@6Hc<8AByguE5soHTtc?&w*rw6rH#zAB=Avt4LK1=}~QgU^R-A|eR(V9W$nL@0lZ zG{d&Z6u*2I<(*N2`kHH37z7#>ox|;+GQ3-nqD=m=ed><=M?n(X4^4~++OctEUzGDz zf3w?Rw$Gh9C7#O`sLBT5A-D#JNo9Zno|(xapMH~neVf`2%6Aitc<%2-h2M9)jPD+j zc=fuyp2t67<)3FQqA+Us`|b~991Z4y9Afyg-lttbmE>gA#z?t%RuEr=bX^pgHS0I& zY_>{4Y482B4+Xj#|53e7>)Jw0m6hsjiNY|~@D7t1bXhx))$_o6|G>_)hoUpa0)P&7 z)F2foz_KEN323&mKd~mp+4kRTbd_joeaT_qdrd%LYU1=b;+#aG6a#rD{62oAu9=DQp=MhIJo#>X+Qo$btsxwD){}oInnZ0*KL)Z zc;l_CgDkq~`&Is_EWZsX$n*n1%>|P;i6;08fbytcq!y@#!QoDk=5aIhD}|Tce6U?V z-bCAI-Dz6wfbiwoCM>;dKcaX5ly)BvBK9)|$E(v-_^P?SCPb$>DhPT513MfIsi4)# zJ9C){Tr2rAo?C2BYM>fU_Nnpvse*O)!Du=jL#F;S;}va)IdS~xNqUX~H3_n*?p$5= zbf9H5<&TQbY(heF(rk`9ERK}PAJN{psIj)8*tU4lL3O6P@O32N^=f2(-Q=j_1x5J1 zGE^o6CU-SCv9}1tJb*4KfIZerR*9$ngJK*j@lw#Z#5;@7fKkhE=Zk@HZtQ87V`#!mrCS!SE;`Y+!pi>ac7#TRh)I+}uK8r*^bsqd=7&Pm|Z3fM<|JVAJ4!VT$!j zPLw@i`s%Z7j&Cf4cn|dkLFsJM=)|NVN3?F&b>6!IpJLX}UTKl~559V#tZV?k&r|r# zMVd>s^yywiOiS_BXapVzgLNh{9rgtN=#eR5=2P$ib~l)=02`dGP??^Si*R^n?&AYP z00O}Gkkz1PrTl{h9v&#qfFjwRDt+nKP5GiYU$9e{mjtSpW<)_AJ_afrCUO`XJ9}X9 zz9kzfOzw2}SKei%)BcX*P9EiKt(rluO`pxKB zL8{M(IOP^LIpTEqBbnD z>1RgH27fC&3K`hcRN)TBx|PfS>!>0~SSi^&BC^N0IvTr#Nfx8sl?GAkvb`FuE(oOI zlaa#>KijG44=Fm^`y~6~xAM#Wlx&RDdfGCi@~(*DjeaNco{R?x7P{qph&azicVcR~ z9~RJ|5iwUfnsX)u@Wtv#w2GRiyST>-SD)FLma;u__ z;a>eLuppy;7VRHf<7331C)To*mDGxZY}v9*xO>(x6e?0YjE@}32~U;H=pKJq_cd5r zJA+saIws-$dfj!&6#VJWzA7bq5+$ApeUuuDgxYYQYprE`quE;`K($h?t7?FLbmSxp zjK^L}l#kstq

p@36@_btN&7Acu#Ge4$!rRyrb|HBTzCut?nnL3upnXuzj66 zlIZ#`I85VxoJw^}DE*w6sPNl&Pv93<;2w9UC`OuT_y{JPOu-YnG1v1w*kF%V^zAO* zJ^u&_Pp5r$-4-5nu>1A22DzM=pI0%AuqQ{|j?lb4&_DTmrwA@MZGl}9-wWKKFyP*~ z-vZ6=tfTP6CA(zf3MK&M`7L@G=o`#@xNG&Wya*oEV0EPnstA81U!$9b^P1XoXg9)N zJi@h!cBT3L4d5atFA5%2(mrR9f;A!wOYY#Xn&@?MoF~Z$E-d1Bwc;k%QMh@@lunadYD-P`H z%;T9t(;rLS!$95hq9B&`im@$q&=P#NTK7S_KDNfCsXZqNvD=6B`*ItBT zqb%yxbX}MKGDmJS68Tr0xKkFAy{WNsFqUIIoqdfESc9LC`F-%A{5rri=wsj)URa@A z7{vfCU4=Ubs&t-ci*nBb*7^>-?}rJKpHGD81UZ6CC?d?%WXd&zYEDda@E#1%(~R0C zGv1Zlgg!fkv{X3*B;we2k9Rxgn++5QCvZSJE6$3jaSTdR61*ys!+E+aJk4_4{ z#cPdQqyxWCLIUQWP-tjja&Ba`_msS9=-TGAbbUm<)g9zIYy5?d09YsP=Q_ zQ;y(Ct#d}Reww}%>w3{&v+>u?nV*_Vbo-t9!eiPOv423#A4BE94M|K}Nm!0jPUN0Y zL~!%uMlse`nO_`K8fNXT8Ok%P_ni6agwf&kp_j25GEfQFwsi15XX)VONpoK4vpE_w zb7F0?=TzXo^ifk25F!<-(wkUYk3tGQqBhxmABa6$eX>R!q?G+;mtcI5?-P{mtYyz+ zDpK|i=${nO+tF94QliA>+BW98fY=<7@i6I4H~?rduyU^`G=fPmHM}M{OzcjEF*Gdew=w=NT`k6PrJ+^~f_Cyzc5a`LB&c%-(=RRIO z_#lP^(PzN-*?p?xR)kT|MQe0+PS47!7Bt2mpKUbR(4%pLpT3T`ygfWkG&Q;2`}{=@ zPpT8qkTp+-DZlIl!?B|)OEFV|k!LnUIhfCNwE&-W+0aq*q;&XEVO9=i|q-TADO{WZ4-kDXeav_V|#Ta%*TBdXUCh@=+^A(Gh0+_SbjRv($C#~Y zz8hwVXSu|1;~;dVsX8c7U%8x|b^ktjnU(X2a_NMB2zL>1ivrl3&ed8a;V6z{{zgvF zC2uPnrQC*$zG)n3N01l2RCEwGB@XINv&aJyjt}7O zSx;DulNDfcGXuVWk?$>+fuKJWiVb|I4?6WWTc71H_plRUs5k*(Bt>KVkvgaG5sTwK zEsxR(9RVs80je3`kuLkK6sLb1#zYRqKn`UXKX7Vo!$lTHEi^AQ(ZvIN1{>O7McQD- z&6o3<$DkcD8omzu>@hrdXt4ep*z7n>0~9T9s`}vB#nRt_sn3a^N|y;E3PEk%mHrR2 z=+DJMzOp#Dv1qX7dt8XOYb1&o@}-leYIKnI3S23=67!J;b1+eMB~9aY9n^?YzNKHR z9{q7+mrV>|Q;$kcM3uuP#j#RzP{Hng=W+H_x|Z-)Q>&%L743jfK(gE-PnD@}8k!gu z3aXp@HGm5qCA=SaYLa27I!Sw_lf5-vRsgJw>j5NT%KfHd!XX?OL(DB2A+0uYcr}&r zQMOne_~Z3`~KBCVJT7fIGi9X%Ru$`E(1uO5@vvlo0w7t`v||Aqo)*R z-!^en^LqcEm0=;J{(d?Un=(o8OZ+Qkc#+`CE6&e|-VD6@xOHjx~PQ zLFeMMt-KNC$O!I2uep`@!j(F%BT3Mu+38pNsF}O?4XvT9GxDuNL(W6;0@yn-oWlo8 zWiW4ToAfGsuU#jT@-5<206lCnqftX=k&}tpvc9D*;Gva|$$|qQoq%n~G)zT+EFOV8 z@_98fcM|Se&#qn&r(pmRsYDDIMat7*L)R%t{V|HXsH;HT_&8#Z1C(`66?L{D4 zi}1ZjGVCn&wPoyqQEDSQigw=zlGmB(B_57ooyrDV>P}2gnfdX<&2jc}pz5T;5d`e= zh6GW5WkO&Ju;ymOpEqKwbxlQ?q3_G5xR-^^P=x>3*eI){LY+2EojdJ5zX4QWcQ|f0 zhG(Paq_#Wo@VhsehK2@Wc)yN;0jvhzb6RQ|1|ibj5+BYmM)Qn-$nP1IgkJ;N<^k_O zFf^MLA{z_H2a!M#nx0=i*&y*Hw{AoYm~XV2NB+lZZY5RvS})V~KAXvFx6|=gH$!K- z3rVG7Y+0a2&n2)x;vQn1e|cm6(#Foo!NOd}p_aqqm$OlzhNyifxXLd2lA~9)wIs5$ z_}XZ`F5OBUGvGe@jLw}XczCC24-K{rJeR4gt80l+FOMj$f}gUo%na|RtgG7RL;!{T z9B}!5NW7z`^*Mc&vu!-|3(kWNdaDna^Y!(JD`j%`?V>&}cn8+Vb00UG&l_GQ?iJCh zbZVzB^cwiV(!XZ}8ZlATp3vh(BZkUgL|(F?VsB^qxQtz5kOATrS~ra50a5oLXm4eM z&a2oz2hJy;rCD`_Ib}L+c)Mz!Lz}$vuYci5JNG+7;XVnV8IJWHbBwLO7&EGs0$wZ7 z6fGnqHKUVcms*^?^EISop2QwCT`x=4cKp1%yaaTELX*Js4pNma;-xGQJuPf6Z_M4S zdNPv3q9290$Gtf0&?M!)?+q(4SGj9NkBelPjmEZ8|0ZGD|N5ZGdGT$c0KQODQjN8b z6Ah53g_`2!dBN9UphW;P3am(q6#4v5+bVgjCf`Rb7^WZ#I(m8)5&N~Bk3@b~(M#++ zJmC)yoPamdmtU9C?*Kh$hN&>Fpo))|habJ%V9AKbi3VuB?CEeFMG$#@jk7uhbB)wm z33ie*`i(Bl55xet#9L-SwF`pgAc0zw`XVv5D%6421C2Q4x_1v&!|1d z8OmalzRgE?(eIa2mGslJ|3ICCefAT94x|8lWk9us1d7KjPjW`=bGJDty{6MrNEZHs z2#f-?GE(FN01!%*bB6TkHv0g6a5+TmXyV{N<~4%_33P%*B}gxc1iWWTz-r88%`3xC z(4X3Ven26Jj_u`CJl*Id7H~Ta*d!0YDBOfnmlY(W9&`Qf5ma>{EfRaZmjSXE7 zhcyWppk_xzs652Kwbj~;_I9Bm(|u?jXVn}g9<{bjl<=kbG%4qwe|;74_@#m+QHnoa zYG;NZ*?TrVm)hGv;vdkCd4&>e8~DYb<7r8FmJQ`^#c!?KKP!qrH(lOtNX47-4`>(a z&$MaxI;z$yonCNwD&^$qh5MZW~2g=Q~_aWvG;5ZhPMQ3fG~+#P0X7 zDN4~>jlBgz?Ob_C7@%z3AzGXsM0nEN7eX_Gh1gdSEb!pvoYKMqWSz-36LkUV)HI8B{ZO_pXC?n#ex zJYwoFTt_0}M)EHVFsWELnE%U-jyDHik>Ad8vIG~JpvPZiHdxia(!7}KhY6^ z!j~T9b_Q~v0hdVktolli_TVj;{4^VnYunuf=loRv7;|9ma725O&MIO|y7ZgMv)b06 zt@U*+-h)%iGw!S7isHZmK11<8!WJq{rpbE&QU~tB&YdN}z4DIqeyH_deCc7iQhdWd z`d_6&Yx#-sf5mOl32wA8(+Et-;hD$z6eD7n&-qv4r2f+_}x6sgjBJ#yp&%(AG z;k&$FqNBH39!*`e=C&8MWETO*1q*$1Em@RW6M{D7}(DA>5*06I)U(YqkTGJ@JUcVDwnKK;nDJR%5!}(`65bU#@Blcq(OZXp8I+{|AB1&+jgtS` z#{2K(FuAD%?KWtZQTo&75So^D_2kp?SW($qujMMXYPrFbTD)lZUAZ*> zM2prFa2nL6Segy?EWz2PRZPz9f4@B3{T>D}INTsx7W-OTBLTfxoHHsk6b@KHILQ1> zb}OjD;@#NET;JZs8#DP2D}k6OM2G`hmNIcv&lMzES<#MCGb2*;wFsYTcl^?XE5shZ z;6a=*Wf3@ORNyK6H=R;=@IbhCe^T@Q4LE?sq2q-$wZG&cGw95UctwMQ;F@Vfa`+QY z*s&}3`D{_PdFpmypw(!g-Dq$`*&yZxImg!Un;pKZgf3F~pjhYLWwA^6V{T_-oct5l z^uQ=6z{N1NERv7)YOGQOs$Wmy0I(&}OOU39P5m6u^Gy(wu)%ig4Y)xR$%VS}B`nVR zY$9%_1hdyi{8p{jnPo*KJjh#RUgOM|Io05TT7y|5bdciQzo}|!YAOI(BZnwDQ_R!= z^T$9nOD^3+`iEDcoCEgj>+IC$%%Xn6(BL$#R5?K`7y{8YuIK>?_A>v3pq5$?TfnoO zt4P^PCm}%S#^|!L;)=4kDz^^J*+-_Y;&TrZd}qE3m)MiuCzMNxY~m3U7rXVKGS7zALf%jB$ftl1cmQN3J+0 zNr52>Y#<9C=zP_(hSRlY!Ks{f)w@@K)+Ny~_xkwxkpbxazQ1hr11ri7s7J@F`30*# zPdy;HepffWg3Socw*I{{wkx;GT$F93q%=m1bT3G@^wXseEHDSsK3!D+bT70un0d6( zk3N@Tw@qHS&z(8j94Q{%g7U4$DO&*vt-6_%(%gamk>?F}1 zz6WA%oP;kg+|g&WF{`UCn`O_iWc5))3VWGem40oWw6 z#Z@m%S(7^hkx3rAw>Sf?$_Q*PJ|`@|PAa&(Hf0a(?;zpXCL~f}f$|_KuF7 z#(Ftbp$81Te)4`Hyqz8q;rWjhH5lnS_dV!IdqxOeU0t396RO@(dn|P|<5PBF)4B0D z*z>G6yi~0!B_t>BMtl3@ zF9d@H=>2RM$nd86eH!IBQBtHfv@oAOnP$>9WQP4G50*AX`Gw*V)fi;zbuP-WC&qPt z^XcQxs8I)KZ|XfM;5I(S>AvRf>+vwMvk6a)86E2236qBd+RC2|v70pjU`Lk<+6GYA zJ+&QgwBNpkIYhO`?!zPQEoO=SYVfni8ZAw`+35kMDmyfA(ao?9d$O6Nh)~ zxZ-Cq>WC;WFGrnj*!h210Qvms6y3dVpPrLUPc^S0PK&lpZVp;{W5Qj-{#X;5=^p~ zgq}fkOH4L6z$e7`Cz}a^7|?H(K+N9+A;F5^q5X&58pE)4WHtCo^j>ye=gNXAi?(92X=nXUffK56$uHJ^Z3y^MCp6>hj|z3xIRl36I24f}6rM?_8K?{ThC!-?L;uvmGfLgBe=~ zyE^J}8N0LKA^i?g-m-YN#A@e?bLn{DK$IhX)FRKCsE6&Jwj8mDpR~CjJgMFNxn$J8 z(x?Fn_*Ma32Wzjt#f^4i4BvDgBTu7H?P0_n&7*3Ba4h9K{>?#u)}BrPCCqXx7lxoD zaKG3R76wYP5L&$)CpMQiwz&BH*X(zI)9JDQGj}UR+juZ*IM&?em_%Ae24S`|IVFCN zUj>-a4!N?dm$|;*qXTAf_huxsG8JbkWbc5!uTK|5w|OH0tTx`U{nCdhm`=RyyNUyp zBk9RDfeM8^{CoK>Pg2@=!F|V9qW}5X`QqQcDtmGBAxX*XJ64nAz5jmJxtTrjh(Z~UqMLxy z&HtZDS#6Ro0;c%YaMM51Tw=Q*3;;E5-6z50U?519qD|_(G9L!Nu6h1xL!aZ!!*^w3 zW;M6AF5jU-fKizEobgBkX&^8vM@3%s+&~O&C@10K=R3x)M!rTh_s0WVjRpl>AQL#k zR0e3iAX5Us210~|PS44b>B`%k+;!ZZ1k}ynjF0IVIj;E#A98-V(nOBS@+7kR9cz{0 zx#Lx}BoiGrw=`$Fzbe8W`>Uk*vs&efUs!+}uJ(+tvZXoygh0S-mjvHJI&rb#ogFHt2f_Jo z$a9?W)A;ezhY8b%!1Rq>NXRhBernz#y^zHTt|#gbM1G#Hf}JTP)MiJADCX$1VO{k5 z+0~jmH9wpL*`f|*>_$tlkDVQk0Lv2PS&Z1ZraUnSQp~a zGlu^5)s>0id5?9~5Q*)IMf>*t@dW0QYOmEDUYi~LF-MV9P(X|RRfSe}O&2N^W#`4&ZT-NwDv>6Kd^S47d> zLw&{TY3>2EX;pa z_EMd-_9Cs3ewhb>{CnO3J|AK3z((g28)j~qMY^`6eLCA1LraRx2FAMjC|fgmAtW=$ z*GQja-l*xX=jxWWOVdwtcD`_#xYDElY;N>7L4?8fkA$pe2v+qiyGVPQ*56 z=D!v)BI;+&yX4saXdv%?lLJ04(pW2ZZN;pl>gIoDb!ptmdns5ujy2Ic;U{;KRH#jY z>C?_3pJ=OB&hiT}#acgB-i5mpux8PJpjR>IRS)nn%^VOeVlNF&B4wG9J9jifYOM zOb9-7vTu69EroR)@}W=zzHk7>92e*fbS@MWMvD9#8kn`$(`asGu8B^oVbaXx?Qrru zGT*b4K@M%;Ruw+-O`xL>tR$cY=+tv~ZV)S5KhU?jnCJGhPdyD z4p~c7=Uv%MFmPcFTyH-uw}7dKhKJetxsg*X8Nl>-O+EHPW@FI&Aca$I;(3U4v!^)~ ziVc;%%_~e5bdgC#t#-$0Nu=Fk1t}X}Yb(>1{)wT14lF1{obq(T(|YY1PuRE=Grl~32!{_>H=EyWp*mrWt(-z={8YyL~0R^2OxSyt5q*W3nz;lL|B_m zHTlUB`-(S*S&pm^Pybhvx;PP|ev}{)*8q)7AUCbd;J`Z&e#Y(I~!k&%kP9=ZECe0fk%>~8? zOG^IGk3AfP>3UAWs&dE!XBqJD@B!&+k{p%VgAPxtm@VRuPOAtE&&J))L#8jPkqUmw z0!guX)_C?XXwVUSb!A_+1NHjy%7fyXQGk;+5v1{-K_N@l%rP;@h}^@Gx0V(5=z+{u zwW;4aVXM}iQ4!~oq1*Zm0tXqS1R4e*=Q{H1{EHGLTtSF4ow@Ov$+DCTG3lW)4)Pi8 zP?0{q8*`_0A8IAw!BL8JI7)hCfBTa#ps_bSmPD@#W1-9+&jO$LTbQ+_SZ@6t$cau; zZ#(qt%n~p(fdF8MX^WJZ8ljVlO)hQ;Pico%g#r`PO@|J!^GjIEI zPtO(UqZ~1*XX(kOvpd2P)9O{uirTezokmTKSe-Y)ml!1QQ8zD6~swfG7p%J2^9}E_FZ_*IT9~dxtvWj}A_a z7@6i*%dzf{DR-G=cpx}X(-7Dp-O{s@<@X@gC_Ww@FnfI#7NJUz^;|$Tfp&IwW>X5d z2B)w6z$8(af8WpW(1F@zc1Gw_(5ciq#Zh?VKHU#F@^5DGdB|=y&XO0a?un>X0c)g#vwD2Zg5Wl< z_Bn;h8h$gL;CmeP-@Bn@c!`Fyqt1RRku#9EkyuVWlx+T6ZU9&z4}w&fWT^cGW%!ur z;q2`7NF>9boCcsYId2|+rFu;eiFLf+x3oiOH$5!M`jpYd(58=O!iSz6*FQ1A1l_#KCC`YZs&L&=~F~@wv4k=(L;2AX*Bed7a_8`$3b=l{OZHN&pcNJ$Fa1YhsMVHkbsGxY$oZ1`0r2 z?(5Z#6b{5Qq@NNt7>bFR+0@gM5U>!asi{rIr|ehXJ7~CO>i4-xv9U%Ud^%gJ(%)d4 zjH)D|wV^Vp`oxY3lWN)9zyx?2+zx92F~mIEQNB-KANIY0kR4Q*X&rcONZtnp1e{{p zbMj251#AlN;CG>#JMv;7;A~WKocC_J1kqUOoU9Ku{FM{wzcVNsjxmG-op1qAiH>@) zuG=OgqdYJmn2~8oiu0xrm#154J)zBrDj;q;JU4;|dK%wcDZZ6~k&x*XI8w*6{dKpC9+LH)g4TuS$14heO18(LiB5 z7JefU4RS9{(`Z;!&^qPWlHiOLkW&DnE;CP|F=^RXMzqHCz}C2j@xwue`xYAu(6t`U z{0auQ(`D1vsTHSf<@u=n#g7a0&e$Lg!$nRLg4Cq7*XGOwqfcA*`PsX?K*Skn(*tI^ z9!t0veV?=qV}MgX=6C0Y5to?XhRxEysRUT+AO?YAs}FS2Y1uyVnEwni1&_W@GYM&% z3P;zyqTf@rbNkJ@a}FIcJxuwUxQ|miP&O~wNJAD$=_v>TOyj)^UF?bK?ETrZz0Fps zeASK^eHN?jz$w&P2bsc~wpZoV3t*oeY8-eWN4E92QBq9-tFg}a$*qnFp(Ihl2)C=!%p-#+q2tkD*GX~k!xWh08A`;g zp5X8KdieO=>0r(Jr~D3e+aHR;xia(wKL*^wq&#R0z?fFI5cYi@{( zKklWC@-N1_h_RAe`y-@0o53FUf9Qdo@Bcu7NS~{q?Ir?@tBUlw0P?2Vl`OpzsAK5o zxuasP`s%UI6=6uA+2(tDo$OTh=(oS|(^&}cslA4g)PCEWuAY5Kc32Xb_;xKOF$>F8 zOa|n?XQ{QagE)uzwiL74K72otte?_T?wEhw`eoZOs+W%~wi-DKS38h#1N{NoPe9gv zB{2-B57wY@qPeQweDDVqJ7eU*&+P3Xs%#-96alLAA)>#2PrDe(uwjVul1RJQRT

t}yBf6qH1*CWJfXMDHF}KMk?$g)(l#71ABE*RN zrbEF?P>3m!cE-nHuCr*t-UZtf`KwjJcJYnh#V zDYNhUBsRW2$&mxcAB5uereQ=u@!jNsEzJRY$>clVp%aIpEoTH#9;~~lfX_K;6EPDF zUIV6J(JI%7%9ZMy%=I#8UzKRA(>mg!LYWg-aAGg~F@$-livl?jLzPmAEg$UOi5H!7 zANr&d9tK+oDPeeE?nw8~F5IAe`~sA3#WsIZE9lAQ;ot@NwliXE_NU%3`l<5LMTztG z`B6Bcg;_qDgDjX0j54{SyUc&yC#4dhhj9g6v?Yo*v=m!Gm&SL!DOiwgOZ3j`s=9jo-2w^a1CX-Lqu z;(%G!eNfGc`r(TC#lpayTDh4KvJ(5hT6ZGfrrf=?Jehg?8`zUB=KvGesMVYwg~otH zH(fzdc8qeToSFF-r5*I0U6mme1dQY8YkVs6@Nd7WW4Wim&yI%9{zN_`CU>LPugZUQN5r#=D5AKr@dgb z5{+3*xYGj(@DB*W#OO(+JuHgaFw6&k?m1~0p!BmXx0<)>8_FDo(5^b^#Jixhx)d&Q z19NG$fUm|Rv*BEb2)h{O{E3IpDG*RK$AtY}>4Usobj+jnhm)}kxDb^E6n)6`?fBT{ zVS)!u*nl}Z;@v=k#{dyF%H2S|-z3)bU=BZ4+#tm{i)dR$tTlb|ttj128D!K&zn<4~ zh##*#C3FKV7{hz1J@0e~7OB`f0(+_x{{LUkR-#GR#|4tZmsy2w7it=JD!n^uMR&-C zAL*gP;E(tn-aBzrv~nu8@-yfW7nh`1{Iyx5QL|E2kjdtT5St=)y$))I6dKSQv3r(v za7wHTbQrd8j^VuDO{((BB0`cBTP#lAyPi7@6WT8wO@4dLA#<<*_wO<8=1?p^z zHidXSIJWWZ&sUeK2mAnCK>$v-<3Ktl#xXRB1LV7Dx=8i!%-D;Ok+5lS!b61c zxH3!o1=K$24$gEU?b`UB&79bOw4Jl>Bx+fn9YPkBB~Sc9R+WK6T;^-cfmt}it^Yh* zTuwQAe9NA)en7JvT#r@_sBtoRAhcRyB$OB}1)6Vwe^kdnwjFS-e?8hLiJr>SwU` z0(k%~R}_4Tq&yl9-9&RhYRp0Y{lZ@%huN~;hZ5_o?wpf!IO3G1_89Ci{Zj>E5O5k9 z&NZ<7hh7;t#tH1ltGl=Rxcfm?zrcMT%+R1%pfySk7l1(hoC)%V15OTv+g}NSD1dMg zo8nI$`tgQ;uiEZN?soP&MwTXMMiw?KdmX-;uPfvK6hWaCGe{}!) zzu*a#AP2N?pZ3yp1L8dlpdCS?tSNPt*PpEf;%3=LKSGVL&iS?_xM3sDB5={DAb^I( z1Q0++FS;Xd1Nu96A3rs>Lf+d7&Dt{#Lz+w+4zuav;3&=)DE-r9#NEEGX#t}W&i{|6 zw~nfUd%lM+-QCh9U4n86X%GbI?odGb(%ndxNOyxYNVjkWL_lfjM!Fm1cYHqY_gza| z@DFR<;hZxwd-mRg8Y890SR#^LLW=s&QwQzMGeqNGj@BCev#vydtcU^IWUT;7NN8;Omu7B7?A1FO-kXr8qkj zYens?#e4M?JTkD*Fu3ggTq}~weRn{#$7oiV@gP7?SrUghA&~1|zrNRJl&r47qalHw zqPTHq0Eq%^r9@Bs!F=<2=aC-|Ln1+~JHjv2-VPenM0C9QH)5>`y&F=fw1b;Y@BAq! zFOu)n*4Z)JaJ!e$a+l+WMv_)^aj6E(%qO1qf3wilHI&iUQe!2?j~^hwPDpa>tTvTU z(!^4z<6CQ*-p0H+@?uiCv2`4WK;)aP@vo-ZM-GDX+;hCD0+)2jC!hO<+>nD_8a3Ne zyGEPI6+hu8DrOim70GCJlrC)iP1WE0vxc{kR^d!rDUglKZYJN(s}OyjxHAXLD8!Ml z2j$a|_J=HeZ&*bV)1~`(ia%BeupL!)RIi_&my|Wdgfn=>MY%jk-1hhBum3)J86FlE z_I*8lhZvK&N8pWJ#w@bp>dxOQ znmLjZkYXw_M1k63M<25M7e02f_ju~EaDVxJpZ7H+uu2ZYzfhBn!KS8NTXf9k$+v-n z7E)TzoPm^~k(C?t*Kk6m2?|RxL$`=m(A7H1k*u+-^&4~mv_4@hhux5wWQQO@4 z3Z#-vDsa%WamK6k;cmuyB})8cZP_k|On_B_9v}l}!+h8Ile?kqg?kujSdr>ruiEOu zPy|US{$F2vY?)63T1__$@_AE(GqfsBxrf%>)q zeTIFL%aokXWDtnEg3QS67Fq~=t_~%6iGekkuNde$IJvojNCi0#46mB7Vp30|WG zP7pPEnHzEE#*tF&ON4GJ^c~)bGN@v(CImt6)_H!*w0thY{ZWu%u~O1M-zKU6Q8=vr zQvUuqNe>%wjdZ1x*q^VNozKb;Kds>i7cCDnz#Or`%o2KixsKYbH{!yfSoD!Q<^!h_~SHHTIo^tVk}Zr*{qvg!8Z3Sl{GVqKv9!!{O;(5D8H+ zjDT8UWdUrWa!t%OW0|gmf2{*Ad1%TALxoKCV?wFBPr;2{Cc+xpL zd^o=O3G?;q;wJm-^z0D)*x+}1Z~RBzp~wd9wj?u ztt*ofKKx;KaQS%FjwZ=c&`#v{B_%opGd_vM_=QxPO9miG$u`R0JuhI9vg@yUD?|7t z_!BxiX6qksgi7%ULoqZ6eu37EkP;E-I&Fk;CIk}obbAH|(E(4EV2SXRZL~k4MB=9D zu#H{oiZ%a*XQjA#ci zxWJ$l5Kg*OduC^KZ<0Uj8b^=9paZZ$KI{|(UeS2?9EuHlASwbm8PC_H=mI&Pfz}au zPh_!N+RUdP@a^ zS%5?2=GqeCMrox2`;PWrmhO7V1cS`8 zv>H6n6^o}=qEr4x50+(D4EiDm&PQ6aG(~^*KeQ-CnZ7X}1$DZJu7W#j(t;z?8p(jr z&YHh-)ItlTe#N zse@Wn!cU6@2=V&q7E9<)B(P5>MEg6n>RR=fqFpnmwKb1ER|(oeqT5P4jP z$@_+N>^WnGnbR*$djC*#`Nc+DPj~CD$bw=6Yj6n}HQT6R!Tm<};7>Y~dz*OwzVodA z{|_SUM&IoA*Zh1<#WMDVv5YOD;b91A_9Fg{f)nV*BW&mwdtb8yGn;~FqmNBSopc#V zxI0OBMSk1U{5K1P+=fd3`Vdpyn0Uup%zza5nRI&GdKIpi0*d{s2n@18v0(tIC3s)`e%-egBA2DO?8l z*yBeT2J*C%dH2|VZ$ z0zyvbB^tO)BE*BDkQr`Q$T5&7#J- zM}5QWJn(68+<`DqN)HR4D@%k;m4(OCC!vN)neirycI_@>*?FdBuY=OVLtOb--^}~@ zKsi38Oxs2QVQI#$C|;B2YP%iNG0J76LfzhI=D$ zSK7nr@*<&pnE|0J4LZ=51W(8BNoEl1`^#Rf$HK9zfQZ& zAZ;a6Bp9(W3=uNgQMEt{&<>mkOUU?0xn2!SwzyeYS^}mnIWN9BAF^+ka$C?i(wh6? zcVMY<_;GjE|-m_qAVv-1|7>DF<;cu{vI^zvrcF2szs7hBqWV8Mb!^PnHZGTB??TBvAQE?@7^ z2<`;1+wPeNa7&v3h>)!DDXU%Z}mpixPgA%06% z3W1{e;MWGXpn|XND3oC%v=Z#e~H4Rf(*e; zK5{*kfdHs_b1+$c0!m7G^PXl`&`6927U;|yyP;t9#yIko`N;RDKr>3u(A_VhJ<0D? z(rqCpQrA9Xo|heUa&WrHModU=45gLhe9gj?LtQyrOr?y(On1XGa;9}Rf^>BL(CM$t zU-wXW)oh|8et6_>VXWOZBA=?+2Krf!KU)Rq7K4^TMFhIze{dZ6(S`L3PS4z^cXU8*&w{yT{zk zR6wMLEP|rW7UFCZbGP>TU2n?K`~42H#EbC^D7J?*{8_`Z_>oz2RSbww0WSk8Jj7%2 zCa~JClPuAv@d`i^dqas`8E09-BW%WDo~sKAS>QUU=PH3A5NpqG{G)Hs$`kb3>=c1IiCYFS|0E$G|Lu06~D{phw z719t~aI;YKlgJRXNv)&TpcD`kz+{70Obpkg$7K7d$)vzWN-DyK-qTZnk4WWqEiVFQOJT~*K@yps|xdyOi!0t0;qCy>>GGPFUDAwee zUYJv8Y4Y=K%4Cy)KT1ffz2#H>?GF-C1xio(6$0rpB}RXArZ;$4 z3YvX1HUB6<_uOanaLMH`M}!2OX(d!i>SH^Phev%9mV#1HP{L401n&nkDMHiQx)XzD z`^H71sm0=})Hy(@PidQ4WG;X0{rT=nXdp$OUF)Sclh(@%zpjgibUv<>`2|9FvB6e! zP)U5#p+=HVmbloEN^}BVbV4pEAb{?Ba$H<^u0Id~|Mta*MddYZzOi#XAB$fOg{J7{ zsx42mSOkS!oYU2_7R#Y*-dFtFqL+6VMJ8+c4?nVp4Hn{FD5$s|7W{$3mJaUfIKIpg zT(pz?J!mV+=6?GcAIl7Ec$;;k{Uub+GE3^COHx|A=el+0!1WPae?D0C$1hh+q==CUJb25DGb^CK!&<~I%u)UkUs+Bg5Xzh9YJX+D0;U> z3~HGP|5aQs?8y01{K3o2%j*RrOn!~R8#v6}jV(rt!g>{T9s7h@BCW@O z*%Io`)2pV5h;m?-XI(%k*qVgxy%tC(41c~V>bI1hq^KPog7`2dq~gaGH%sevcADZ4 zy6=zGmu)u|S9WAM8RJ@YIC#4lrD;|SWvy$YAMmoOWxstPt;V`2$@gskbZ)OEQ&z%^ zjzOl@c81&TcRfm^3}R$IIYT14O(Q#YA?lln-D(#kR4ckn`^5o_;6Qa(WQjY5{3J12 z?t`V+{moRtHT|z{GdJY5=7z)lzY1H-pM_j}#*~bZz}H{T#_qH3Z^Xut1-6Lxo$h#b z$a6YBV4Axkuzs4?5;yC~0n6jzZt}E4FEE3uwaf$3d9gy5(w<{EJSj=QO;h6>kNy3j zLG*G6zOA)W*n3-FrMF#PleX@_0vyK1D*hcMhws%LyucG%5+CV5Ttt@y3q<6SXeVha z?~RZDJHGLQh>s34HH*Jm6XuR$&Xk+BOUjnV*76)=Ki8^KO=5ZW@{QC(N1Pw)$b||P zzIWArcP7T{alg|Y4L2D!%*v3UzCYrqj)GEHvi>Y2M1ixQ#|kc*Q!C&$_ay6 zIipTk@9qc9mtYQwHwVifj$R)1?hm4$rkce4IC?N1kd;C@ftI-M%lPkUBZr87HkBwLS5Vw!GhVC6-`cT*v_18k z$(+f%1aHo`a}1iHiXVRNr@QJe3yQhZ0zNn9>PH1lM~8BEI41fhg`d8&iYqM-U;l}V zyJRQzFF5_xnbo>={74hp$;)H58p zYV>~cul9$}EG&1t7pIHTPW9a5!yn}QjRP-}u|J9^%G0ioG#DXS)~Vo1p#SVjeGkjz zAs(z6BsEM7klx6g(|Tu#Bl8G}3uENVI#)f+-3r#~V zpW8qDg2%SOP_}1h0(f99c!3$8sk;LykhPXg+5G(Suc3H1<5B)!Fi`mU1D746PN&$L zvc>UwVr=W8LJ=jLz*fYeXfnQMqS)Qb@qyxjID3MSH*lrc38T1zQT)l7xmVR+CaZ6ax+qea*;^xs zt;sI9KelsuI*w#ey>H3!ZfaL-Muq;nL!FXey~wO{DSDXQwCHY*Qo3b2Oc-3mo2L|+ zUbECBn~>UbIqKja%0i9VXbtC&7Ouu(Ii0opg__N+(VI-Q?B3NGEfT+fs&Dr0u_<9A zg-~deqC}H@wSV3*WZMfs(AEM`HdP-o)I!wwRV$`|qZRw+vlpGW>^3Ya)qjL@LwBG& z5e!f@8A&ZZ*L$cl88@BJtw3n=vK+cD@eE9+w$&(ELuU!~1rV(oj5Yg@(n zp>!^PMVCC+ag>x|EFNy%IDmjY znOk9Un7CjR>??0b2Pl;>f+C|_q<_KEFb4(Nn(cC0OUEC;{~s9JW1M|$C4x(4bMrpA za}VGtO%f|d662(pTKja@PL$s|VXr@I&@8xUdvwt$Q{Z~5&%!_IL(r`A9WDOlE(lN+ zr?a!qe26S;O0kw|3bA%uIJMfM`=3V__K#$2d2* zOqS@M{OZ(WUSu@eIlzN~%A@U#t=Hb=G18^+(G=hV!4Hy=txBUmwk6AoSvLz}T-hQ` zyY%a2lAi>#a&=}J!Ax4;yt@?{a9$<|%o$@$YW>OD)aw7>edho2!&n&w5Zbr!a+Qg^UV^)=JJs$ksSL=Lw1d0Cq=$m3BKrvc$7%$j=;trP}8_$YW{_iE; z9RT<}Vc8<#XFbM?w*ks|$sz2jh~~8K#Z_IT3=iK@FGe(D%>+!{rNn2~{js`NV!?jx zq1Tbo@#|& z<3r>6K#C$ItzjdLW=)L((^zQ0A=Pwj9Cxc&g}gOQm8{hKFHoRD>QIEX(}#v+YuJb} z@nsQySrdbQ01ldOa_GJN1>8I0BTryIMn>|1>%-BR*;sYOzB`KAtH0%tgYLImXU(Z} z7k!r&85?oW%uSpxJ!%#JqyEOFz?R#+S%DS@5tVMSh_Q9x2iQYzNs962k&82X>Z` z^7OQE|MkI7?90@%4_x3tV(Zrb>@81c5Bkb3Jwj!3i7;pn|rQX@*D?tM|gAHF&Xc_bQ$r^QLeS z>R;X@!aLS|+2%+vjJl-^74vob+uZiRZ~{M4hL@NEWI7~TOnTDjeD&%)O?Goo90A)x zQQH2dDg%)}v5jv|qX;*wlzKZR$cYasCh3fF(J2bU=%09Zk?iCS7)XW2M^J4$VRj-uhu+2>tD$X9RcFI|a zUg!k}I;3e`RX6~K>WcVh1}Q203Aik*{(C|BL{Q*>THpH zS0n^FzmMVfQZErV{HXhx4|T|%-k*miC*^p%lF+Ddh2I!-=rNshEpcK#c?NejT`~fn zeWdctucT~Ase#dN)#cxNDp~2D7H?zrn{A25s`FHbT@|6|kq=AO_%9Q?U-jMa!XkJ7 z?~cFi{&p&c2UkdKtnX%TA*$JmU{|Rlw>pJ{Uhu3`Fmi&7gFP9 z*cs4}@6R<-COcDr7h>u)aB;_adTnl?90)Xk>rQn&#-g@)&Mo}!zU0MiQ6i=k2=W-V&574COc^F>=4J7 zymP#ah;_P(q*`@k_b+9nH62+#8jSs0M~z(PZfXqmAS?|#^e2&g^YCurhs1q1N>R~e zK@m|w^L!XIbLMeyU_ZK|vqP{HMRWShLj;av)ubb1OKSRZoyt@MS60MS#hRRW2i8Qj zWIP)%^a|OM#rD&@X506mKk4eNF%|=H&z(oXhIHzFxd&S8td~BhscVIU+h-6!N3Pwt zW%n062RnStj=WAw&1?m4htW#X6$qryS;PX+y%0Pu1vJNGO017fND>O?xSofj< zio{iv)`R|WYrMA!{_~>BMPqaG;-xCk2HI4yf*R#iAuv=B-slUam{4bFtw7czpcmJR zAMjGQ>wL*XchTb;An$YGrE|;eJ^$>o;tDg=U8+XP zkA-6U-)9e7HKuw{{`uzDFaJI%B}^>)TBJQVm)LZ)Hgfmdb}8vu+81^V*J5%l zZXtD$B$fwEz&h1_kZpQktUB!Egbd(1v8E0~p#KP_M`x>eOSxZWFp$RwZsfYWcF|5q zjJA~{7RPb6#LOFoM!3}D0RxQ{Yo}1JXc<%L)_OYTz0h}QAAyjK(aV9&^SWt^c;+$| zkK}~g-Q6tH|MJ6E8r$!%C7$q>iK4&H;wBfj^0?gB$5X9rau0Iv>UHv$9KH$J&bn!| zGdp=`xVp0G4lyOjZh~ zPohyD4hL`|D=APnt*-kHTBhC@^{+=qg*Fk5NpGR*ujzl7BgS|hb90wO#Atp zPlMUF%|A~?5e0z&i&jek93Z58-WNz7X(~Xo*P$`}#9rOm9FOzmHxCAF+21u%ZDtoo zCKe{jkauZnTmzniDj1eB!+(+0O#}x7zLRYa^r(M!v#VLK7h^e?N?gzicE*cM{kOK% zoU6|jrdo;>!tSGU)x&Z*Gy0b1GDI2Bx}@5)P1KH?_TC=Ktr#l|x(g%1L46+eeh2%& z#qL!s#EuO8U8_CBM~$nT7M>p8Y(|~JV!M$lli_-do@|3-H87yYoeD}wJ^=w_n63bd zZJ%q-*p4u;&QPl;u$<&=i`ny4OH`HArJ6A(4>U`Iacz%*_P+qjc{Eej<;)Q&m`-BG z4WKHaQkI5_t?K`jKD>j4y6pLy>iM)eNC#L+()xki} zTnNR0xt6(y&$eMc<)?1dd@5B0S~_t?h6^VuP+5*Uo~U-2Ue;V%qn6jCKd>!UW}-;* z@syOtqwI~nqvv2y$E&xc``^j%ON+CCweec-Dm=Nam0|(J5eqY6H@{(?Xb#LJ_pnt5 z!hTr`d9nCi^hpg1PO_b1hTV60e z8X~hp7^>n+|8~RIB@TMAH>`Y?9c}T1Sh^aNZV%|x(bgq2e7gZXZ*pc`o)$;ywhWg% z@Dj&`Q12g1TJbu;VVcssjk#z*OhjC6;%~;&?Eg+p)z>fUS-O6@44&f8Mzdp{*VS@h zd$7~Z6U=4D1?Y{$xg01vX05O`*9VYbN3YeO3?G^Vz8nzhx!m3%DZ|5HDbuU~hFwa9 z@_$s{mKl4x7;kVB|FbsuxxEDxkCZTO`g&h=CXOYx)^%#904| zCP2?;Zji7xTHBU3`!vi9R7(H?1xYmdv!1G}tLsJdmqiA@+8qAB8XEYiOYQfwUYUGnk9slyBr=U4uN_4 zb0$o=Wr_JcdAuDCfcN(!bH9BSAzO%rvw=ejZ;UWkG*nzY9nLrLd(NIX_)%6WRbLPS z6gj|L9%!6Ccp8_dF?i9f3}lIg+Z0Cusrnm@I{PzAmNsiGhR22btYW-OhMN26OACpE zd~EZp^A|a4mlbi)=}xJAp1lV+0_e-=7op;E2@cPW2E?qmlWx7K=6Y`)-kpBFv1q#g z#8xjDz5T!X;mvf6Q?=i>-$X-Ge?A}e|6Yv6TJRnTqP-e;wT+T-t^dmmOQpSosaKV4Z*bZ$vLtVD8 zM@^u3YWO{9Uf4J|^c7=fZ{HT3%()|86`SJgaYopdi(k3hQ~r(rp1WpS_{j11WlsOh ziOKQC4c=PV8Et6bbW4i%51jX4_#7?`elI7clSIBMWGpj2SrOci5e9tpue^cTBGsZ)V@>Wx zDm*UKK_s|=Oy)f)gZjdtgGcl^@*Ts|;W!7yeof#|WF=;;OIpmOuHtzG7B*+AR!uqW zp1=QL&7TH#B=ompY}5+@L@OdV(54Zyk5{!qORZd!_xbZMC)O|jl@HH&skc$o>{>O9-1^(N4aifI5teEh`he6Ph;9vqasV01hNz(xYN)etr&c zH)OA_95*o}H}5B(g=61PcET=Z=n`@X5*E~K`kOe5W;{uDP^ov;_v87p@biv||BnkG z_ctAVGVuK5GKsJ}p^3BTDQW9Of?QIvfBV-d!ZMn&@TOga59~pF~hDL^v@w1tC~E@j%bpcon4K8*+sPcd4~c#2r0avVFG z62{4VKPTBH8Gc{cQj)brI!>ED5WhiEEQ{F642EmmH2g)l-%^SDi!;yVl-ryo>=#)6 zwWj9wD;Z8X>a#@8v@N*3_!mikAqx*59?IsS-6lCM;ke7f+Wp|paV-XiZYj(B(fwU~ z*O90-g$pImIKI@g{%M#k2?NN_5C0Nlx|cLXf6wr{0%^hDwcX=D3e-_m`oPnwAAd|5 zpW&yar7Ax*;K@0y04<8X;kGun*NBO%S7o4Lw+1|t4F|0Oa6%7?!_9c?5igIoZ1#UdR z&6&LM31ScgcsYIF#O#4VJsc48oyZ}oSek02r>qXsYTmDC8Y@0aAVN>(QFHEGkiLiE zHQ6anApgd8I_-)yrd~ z>d*^qni{n$@-4|hwa-ct9WhW4-6RVc;ux0qYk%;pCu?qXE}hdBa7P5!YaGYUgst>G z4D%Xc)5XRhQN&NQrRX|aY?QIpWyiw3J?8v!&&+2*<{$DSW7Wc*Wt&UmyL6&oKsMmT z;<~2nDAzVkW!JC^ZRRlcxclp)mrI5j($?wF?)fiB3FtGFl^ENh{6#qt(%ypYL?!|! zD_q=fRMz)@H=v^;;v*CIzC>kS5nTKOCK7-}CM|7do$*1HDdJR@X47Ls?ao7M_nsZV`oND5G`jcx-4+jD=2XQRJnu{Q1+l!@0~T&{HQFRS-Uu}R zVfN^xEux8L^t0QEM7ya)KS;dXF8z+scu*wUVA`cwr0C*{CENNx9PF#ss^}%P6{=39 zTxG2$o#yYE?xues`Sx8+{CNE@{A){4_LXCEMA_nn5Sx7a4)p5dd}eJpnc)d%bD}Il z(&pd#!ifK%4c%-{hR^VF z!0AQtOu-B-!M&*AT7*_-q8x|Nx`>m0oD}-h}XqY^=eYghJmEHQa98n z#7$(pUyORx4p`R=)_RglOab4GESM}0&CQfLaL>fHolB87V3UOAbKAAR%K6TLVp9@Q zxN~`Es}S`%5mDNYw+RysgPYE*DN&#(wCq)n>q`csuGfvh@3mZt;G>doSOCQqBbT5vUH;Xj zEpKcTd_OU5VasST|HsZ~9H*_Yph^oeNjTE^;XM5JyM|c}wDq4f4gv4}ILDoBi8*ZR zH)jU@hZu)8AICTyhVCuA55KnIdC^9!+?KmoprO-oU*ED88b}%3uqaPf>N2InZ=6A{ z>hSK-<((0jecKm;5nU04lUDDR&|NzLgeC_cK?x?_8U_|%=ZT&C%)geyPDvtD`6|8} zf=RNca#23j!DVy4 zR|-L;8O-dwb{~d#>Ud1O5jJ1EP*LAZm3cb%a_E!rt;tyElXYpLEhoFfw zJUdSnwi&w?x{M(+TNW|5i6#9?aJ{JfMPC1kAjk zPUxs1E51~dQUu+1amxrcs5129_GDGBKRuRTw9qZ)Nw?8s-RKdVMl+0CiBMV%k44za zE;!UKY#B2@yole>+RRxRaE8CkG}_)-_ccfqbxY{P_#aB#_AfgAvaXd9tcqb!E?qmK zVQY`HB-U_RCzILz$$a})Y3_YPqUau941`uVp`D#6dwa>3^@sQGC`h9P>i+~^u@6=4 z`*o3W`d^_Zy)K)?ALeLIRsC&%cnRsA0~^Ezc!|bWXipjO(en(s3-!wisM!0+U#Mb} zm|fdO#Nk*x6K~yjUpsmv0bj{gFFGHQ0^;%Rd&PT>&U(>I-7QhcxD5kKMgUk0UTEON z$(WQ52&QPJd6wj?snNVKPfmfvj-IAiod6sfT`({#4i+*BAKOmHGQ5-8?fzyk+N1Pq zAxnPdaMab1d@{xcW+_T9&f(2I)~2JmJ(boyXt!kD&Z>=OP8l=Iy#M5@Y$o^O8X;5x6exCyZOr?@oTjE zRkTNpECc`$D7{gU*3tr-=`?LEb8dhT4ouUfUZlc7QZC_slds7MuoNUz(@AW=SOM?> zP-1`jOcGON5Do^bx&pgSj^30zAywVO=P;Vn1_p4o0Pn<|IYUGFY*Y2{e0uivoek=7 zdO_>`k8!w|j(O`K>0aw(FZ9bRQWK-jEZhIuW^~8ZGxZ=v()l^O-d5UL{f?w!_g0ea zamUgogSBT^hjKL}Xj5VX{-3mVBcW#u9MLdVnWLhCY!3Hk(nxA0)rFBjJ#x4@I5T3{ zrg%zq_lzJ!y!rvX_{SB?x6fP9(K<^)XfYWE(dZ)(qilW=m*F5aG&BI{^r%OKSJ<{| zHV~oES^(Llj>+8W9gF*|#~Ndn-69br@IXY_?Cx^nxsVClkeK(! zJK$g}wTka6M!QxA^%R4|ozWBHuGbH9_YF0xm|F-$S^Yhs#g9aXion30k=}#qE9^O) zXAyov2=BV*@JAcl`6FI_Iqj0U^F{@5hDaQx8g5zaTJjJzGr(ay4ZdgFNV7WH9obS0 zj-ksRvU(V~HsrGAY9)$Mgt}@p9r)N;3hCUw9upL2Su9E#{%>-q&6X2sL!VMgw(TQW zedr*2ri>YK$&kS!IPW1oK=Wpnu>GL2LF3m#^?a6$%bh1%b(kBA;3_t!VQd{fPk$an z!WoOCWk2j3x%KkyO?11jBr%qI9^5Fd3gV71i<)OF?h=+*kwbuI3xbkKTWG4WH-$!O$;#Oc!G`ql-2+G%5$FWy z1rV6-KhMnesM>lyeE&bIE0@ZCz&MIGr(jbr@cHcD2qu_jZe z9Nv{s%bdZ1rfH2gX7bw-p7dW|`-u!J>BYY@M?7sPV3Bcw$mjB2`6zF8@yIq5E;?NP zj}o%fr=i9raRlS4n6h88EmA0j3$&B$im+kNz0b_pk(q67rxv8TbPu~UzAc~-v@p|U z#l`gGs1Cc>cf#U9zvqmaAgv3**t-4cOy4lg&BH)TkoNF*=#|WOp(DZW=y!#>PlCOY zbh{Fo-Mdk`2&E#h02ANB)skkpfnPw|E zfj&t{9$6trCcZ2FJFj+>Nap&fo^3w`rfadF)X=Z`;7bn%z36-lh>cIckUuWqCRK+Q zb|@Mwir2l2mpg_gMjpxOeKA_BAgXd$6lwggS=Noc?s&@NQ`Py<6Pb0POg*xQev#eOV36uo zidYTSlr{HTl+OLJL{K4(3PId}dLZ#^Fg36nBJPvwCWAuGPKO_~&OfYXhhNFC(pojg z8eczDKb5M%sxlY)$)3W)m}Za_m4n!vDJ@EXrh_6ih5vnm1o^e(b%|fvsPek{B_X>D z$u-LZ^x~>CK_tEJd~bsFz9eETli9jEC&b+yH))$kDqEYfbrS-K>r?ea_e}_oUk8(+ zmHlg|rPVeVo%h11KsSyoDIq}md~vfE(t~jEs9Hf$HvJhr47@q7kMEFXzr5!Ub_?%N zEAIie4gib5|G;pZwAUf&{EFgq>jaax(i^k+KX&QsFKx ziLXWAJne9Y7q@voX$I*oMxaHM`^_3cKmBRB#T%Tpy-(RSc$;stF8%^$BprGIzo=l8 z*5#$U^KMaJPV(10Ws;v?C>_VE?pi0@-8-qtkPStGTfh?wQhO<~m!Q#VC3-4|EKN=qR^vFdV294hJF<^STKADpaKB$C5N4 zhRfRn*Vjdnr^SRz_0uV_ z#-y2s3T+Y_Np1v!7I=l0kUiz(ZH{fn zp<@dYH1Th7_-opdD#5xKo7yDhv~_0&$HJTKUNz#z8Sbfa?T-SQ4=yxy42WQTQNbOg89e$d~~S zG>bZU?vlQ`Y8La&q6}fS-izPnL(q>f>=&`$PWA%s1eM-CH z2hMa72p-s+Gp zgVN3m;r4=7_g9viVYh>?ajzW~7TgUll-v3nMHcroNS}@BSxd7dSRYbxVor?IF1#r4 z*kEL6NPGrvazcD%R;&{A)e0Q9dVB~0inT%>2osQTQ9??WL2Yy<*(`tdbbzIo#E-Q@ zOJY@?;v1#^CuQwG_J2&kfQL;U*xEr-OG3JgrSsqAlXVuS+sXGzDk>pJ01iRV9gCOX zMVG|qC8Q3bLkD>1mOGbAt69&dq1cj$)SFDe+pMd@(e3u9W(W?v*qgSnv?PV7j=TNX z6&_VF?!P$l5-ibr5kUDM*Qycb8WMNTN3)}`<-ye2fSr|L^7QhipW&*3IiqxWEz!T? z0<*;Om*LGr$qlfcSCvXcgr!)eQ|V zxYjJGCH_>VN4qi2^JhWD86JJB9pgy@_%kGM@4v$Fm z1}deXg*JQ3Cp{PtcHS(?Z$6`4XuqR{w?@azvRe@Rk=3fS`JO*VQKR}mCj-bTs_d!x zfN+?MiFqT+nLJMmwtR!+ijR)kd*-$(x)T16l8CiI1$7cTdoE|cyl_Lay%G=_@u!b zl6izygnVpE_t?PjeE^4?Li|Gvf#z^Y z8W%buaApsdF~^>7vX_QZq0(;j289S$edPsJTzVoWB)FFjSuKzibL9pfF?QcM$s05J zCKn-)|7_SVs|F^b>5=BBWY=E{jd9zXmL!(F-c!CXuM4d3*q7)s{Mx@Ei;O5~2!p%d zpIeE0)Em5v{C9Xxn5(5&Ik``NbDd6@OADkrxLap)Tb2AbaFDEx+Xkk3GDlN?bUg|r z$`;r1%5zWM8^6R@ZznzIpeHuXp|p%;1Kcl1RPsiv@GX z)2xQW*Qk&Kh{1`naSs-X6oRMJ`5TpERk6{-zbr46W&Q6IR%B^{Opb@;>I9I_0ub^L z2O&W$Ug(cpab+I^k29g8S=8ZxAIP05+h_>?_9io7wuKQ%5;mB(rtR-_n&5yJi)dAx5_vFH5&NFCG=SwZ0;(T8G5k=%|y^dv>dVRC51+2 z)&T#I&S5nlm`D4KSc-J3?1Aon^PO1d%9ip&TI}*ujssl`9`s+vAU$^404JztQy3;_k(cCG}kMvxHnidhvG-!)=Xs31K=hmxfAzI+x9ktS;#_TXpecXqQ&*4+Dm%;#KYdAq2B}Endg1jr0cK zBmuuU+s+^T5m=!Kw$B3|E+4<3E#?w0qu%#q%&0I1RgdJEUG6je5$m_9nQb>6o`)3! zZP;PqyiI0E-@bjrj~=MyOY8x>IwyFtj=3FYP<}o-GJP;trl8rPH5D0;acItnffZpP6|kz`uMn_pcXht!S?Z_}Ko#qT&8i#4L4ZHdfJc#^YZ- zxD3~qS3CcYs;`cU@{78rQ<@>9OORHO?i7$xQW^wl9l9IoPU%uoy1Sd9Lxvt;=K>!gJhtpqUb7K?t*C*Gz|!DR_{R_* z(iYnTc{%0W%v`7YS6ghvBF7`~(Dq{EL!I>Sj-qeiV-^Rr8~j`Mw2$RyhtN0W>24_dVhZeQIXaOgX-E*--dDB^gz>v*JR7y)n%o zL|UXlE=WxJ)WG&Y-WcTD7Pe9hQ9-&hK#Y&N=NSLx^!_!~qESP%K@u0I_|XLQSgq~! z=Wn*+>A^AoSQ7!XOFtsYRmlSFgXYz*ir-V28oB9U?iw_6Ac{6M%{WsIM_unxVee#4 zDSyEl5qR`Tj493v*}j0Cc4^zSi%k_EJ3 zL>*#Dp-}L@qQyeu)Nl0T`8uAbUkrfxv;cROAV)Z4oo1R#V9Lk_acdeNBu~KuW3xfI z-aLT|ncHI0w|U_+^PdMShnHDD;`Pz}avD_J|2F^Gut{F_uIP2UQZc(}_MsQej6L*! z43kY}J2rgSugYbJ9PoN+N@Cbn-uG_KjDyC?PyqnBFhMC1zi#I%_xu1*k08&x< z7&2w&xro;qK2``fz*_1UM~^RGhWAFTsEP_`M^p4`&#^~P~N^9~*q4*Xc z8mzqmBgBHL{uHg?Xql)-Y?goQnf)(8k5WZq6=uCF@2|#;a%?ysx72#a`N>6!w;|o} zNQU}OnQAk$CCcE9SJPJW*meE65Ho|#(lFguSzcz0IaDQ*I3q&QILD)4KBUW~o0uA? z)@^9$4D8@ZCG^+pWJTcJHM;E*s$>d>G6%HM{?P+ytpb<@aby%d zcbEJ4QL_K0tphm(Ti}D{%l%4Vl4NA0%zm)EG@uz5Dl7l54a-pR{PzF201M8uDnK~> zj}~s|`-qd#65Dl<5q(bjc5vHa4WadFabMu!KvjYF_=g9p(w$5xt({y2do-RtOPb9p zgg3}RmtgEBiOE)NSd=xG2pe|Y)eXyhL*3!uI0N{h0NE1#qq7h+yC z!#vCky)P5o(bjv2ponGYa7@(GEMN}E`hH)1lviiml*umt#f=H5*NiuiZ^2lnH)^%- z;&eW+5O;4!VSWIn9N_7nbJ|ib`%OEtZsdb)bvh91K7#;hqR*OD_D)ntml!EpjUFE& z@bYMB@n0DC+~EvvRg=-s$p8A-S60qIj3qg3@qKsdU!ny79DuhU_{qbV>>6>#%!-c~ zpOO;WKFDyn^Kh&Nc-zEb`bUzOi>ftx^rplq<&?XxB*&#mo*D(zkz9oR(*psq*|n}q z;NiOeJq2kxj6lyKKw?!*+597W5Z+T3wpcb1^?m7^qz^|Z)Mi~27pbDx-O|;ZB_I#G zmA=4Z>)c!vPI&_P3h>2AB22wSaFsPr^->J{SMM`dyMlE=brJ|b5CK#XfL@vIbpRsL zArz55M&@Y!F9e(|4o$0y_5uOU!$0ZTS;Q219(zDa z`1lL0_-o!QhW~kwi!i+#KWJW)6And637hBcR8Q~%=z9ynSWB2I_-$Un{GsJN4;$xn zln(S8>HTN?#I`f)Bt0vdO*BJ%P2C_Ajjtv^S;}v7ZkAN9K?`Vu`e4Je07!D4>4TUD z#*ME5UB8zUvS1h70C9x;&;K&H0PzLjNü=X%?XaJ#7K8C8Nx5?4%a=t^dU8fs3 zsz#67?|}9yQ|mp#>gH$w3zgn zH8r)KNwKX30i72S5iaTCD+))R`~fcfrk)LX4uyv`HJJ$dWT>1iofW4bGhs77yK+413p%T0$4AhP{r(QidZE}ETY&72Sx-3)A57>d~5(c z13V*N#lq83$8lJ;;SH*6wZMnF56c)4@+AHPbj+iYS?Blo-PIfrJv5XGc z60`krnc>(eJjvfXRc6E=K9u8}t3pRdgq8+hz^MiC`$P=Ler0eb@@6*1@6rb))+u?ta|o$eJ@=Vxle|G5~1+pnqAjJZ0GR7WjxJ&@j#+c^Ww`H?lcU6s1 z8c^YozK01&EEKpxBLvBKiw9t%EfCCOM=R@>9ZzF6YXWQGY@7qL06L6jtLXgq?`(^! z*`p;TV4h0%0VHuVW>WzRHfjx}c{s#7omu~SvNZk_E#sIHS3d9mDn0&6o4of4&eYGk zG_|h_nBADM7~zB#rP!;z&_`LMsdo0M0k>XzRobS)7gpKP7geF~_H`Bj#DjJlz$kaWF1Vg_i>F0X&>Oh@EYU0%@(|816X3J{+opY0 zmV4P)?YL{`kd@|B++9_Jc*ty!L+RenL6VBbINcEQ2Hp`nn|`)KlvZ`dM16QEK!@Od z`xc32z{JAEWnxVCoZTV)Srcsy@%ArY^!f1@{ClVUV|7n<i)`s`D>w)S3~LuK_e!JS>BrR=$~uW1 z6g9;tlIPA31=_tE_8$y)MV&%mSf<@-i+4gVbqqU+eKmW2s#m)|!dja-(Fv0&NgLI88XFYZB(YFEvTY z9pS=9dR42xnQU3^%^$dV^ildkg$9S-JMvrTHn!s=2c3vFFUFQ3=!}kF(Um7c=6u^c zMd~h8CGTI_JkW_XjV=58bw)W+h)B~eCKq=sFpTTF)PW(bCwsKH9maSgyWJ_Q$1OsX|H)H=C z=FJjjcZB8j7ktkmXD=3UE`+4Ht;F#$AS9%}HT&7`4J>WA4LJMmKnG1Wu9eYTq`9DV zf8oEg;?27NsN(q5s($OO(HR*E3A+1ZiFJ8tUbdAi<)ac*oqYuYZo6TjS?;5_Q~hy@ zQKh)n@fTgcAQw~aS`Y+L;@$~<^w(!2Xy>pN)~Y?=TCo6XPw7^fYmhBGo;}=3-|fF` zBech?dUVMENY~|IaGSodBSymraRpVko}a@W*}t=l`R|29*P|XjYcbQ1#8bm_y)x`_ zhm?p2P}Z4hJ>SOqR=J&hxSR0GMBA04nu-#d8VI!TA4eanN<3q#qx+8hdnZ%uWtniF za@UeqMo29eHgLMW$LbMq%&iVBGcmfRP(U1RV=;iz-EtKqJ!ZW8K;R#D53NVhwCZY$ zv)t=g!cXO~^XarJdT=G;X1RFch%r-z7QZxvDfoQBb!ns}v3&9;3;td$%xgmBKqctd z#nN?Qb=~F8aM`f^r%J}Ei|m)el$xCe*wPVSi~lb-;^f6@$}=VUcs-BwlRaib@Gooh zg{&LY1(1)f-Mo}emY2?ZkBrBm&>14|HmXm+2_+hB$HJ@VExUGtReEs-KKnl#*;9s8 zfc4Vb(A|`#k8c^7XwS3?H(HPL5yjA$z@Pe4cD9-I5%#VMN@M}K^|qE)Q}t$8!Jk4z zVEEnHPN+ed2qeNg-XBkE6GxaC?QRUarl42~(|a~RU4%_7n1p^x&}xw?VZrU`JLu^z zzZ@G0&E;t&dasD>Mta*g6Ql3T@Yb=>Lv>Z4*}FQ4NB`f}2o1qtkGO&isr!{2`( z?D~DSfzN80mz1+;djV0`qKaNKsIv{AbZ2uqYf+w-)%GZeP|SAI7fY|))A3I$h$t4S zv#PZGPU*p!bc!X1t6(o15+-5Rhf;mu&ZfatyO81PrB-n3A39`;TgA@foes9a?3QNn zEtB#A?_w@pSOJxDq$%bPZx}D5fU3jTYSxv`Z#rX})v;7r(c?0B3|v`V^ipCe($M`g zf)w{RL_n<}*1i~fH(N0k_xxU?;3!*Myox&EYWEyk_#eZ|LLpn%P(bxjdFe9aLn&~%4IIxrh-1VR9rIh76dI|8NYil?K2)zn3yrirA%G>!(ZA>X#nlH4~C$yT&LZ_hn9c2 z$31#(pY{&3&$p+%q1twy)L$%=zBfc0VpDqm{1)Rjc7Z-siQmoU;2*EiNwrX_Wg2L* zpgaq7O1~bFY@3=z9m!pWFS(m@?SGE4cSKmr+b8PJp?LGYz;zdS{FQ6`=Jv;VU3lh2 zpY?vj7BKq&oz)P};~r&Qw!n3NRCqiIs!@<-{7o)v)}^lJlig!uIDm&5X4wuIF-X*( z8mS}BdVcvz4`&xkV7wQ#5E}af1Qt#iBOxe&hz11#$CMZq5YhlP0KY}lL})VR^!-uE z^J5zT>oCp<*jGnruZrD~6CJX#68$f1BnQRqL^)YqOWxDqN%EA^cQFqf^E8;*j3Di z!OoKz<|3MI36o_vE(O%ravi^^W2Emz(zT`WgGhB${)NEhgj0oM-YH4yoXZ8$O(Rb6 zN}hTZYF5AmcgxUigqNI-R@u0>%-gd9Q)0{PC?39)#T9*eGL9oAS$7so^_JyS1&>HT zXSyCcag{LG+?Bzvg(T7c`Ww0-+L^;tR-cTtl{h`^C(3H_Cc@Vxu}da$b%UzdK%s?>hGcBOHHGe3 zM&eHSoS)^8C&mmQ1J)i}yyU#NNS6dIiUqHd0ZW7FXLh)|gK87lmrhIaW9j!D#rOQX zp;X4={R#gXobtSzu&KJ4{HOm!I(D}4Rme0XyjcF?T@#D9qVy$FkLaz+l@kAIzIm`C zKXwqS=U>4|=P73~OLWhU`qikS<=4vskY)UDhvlDqn$BC7eZCgfFxt0-rK}V>unFHw z3A?@4PII1bO37GehcV5&ADDb2Ho6QK&Z5xql1M^aIVwhVb=*!F~P!roeicSR;Hb9T36+Vi;d?<5Zb{k?EZ$2pm zh)P^XL=YHgzUd;19hgP&)kqOPkp9XT=`12Zv_TL-1M!w-%rxiBWHQoHT?V)$bZkfk z-ns=bXcWN`2`yvizZMPw-M-ZOn3=~@x%ykF$tBa*4T5T1uU<+)=l^w0JpR&_Y)qeT zSzl2xv`}5$XBzRw?>#y;Bt5JhV;6vU0y?Bxg*W08MahO|jffIH!J=JVrP1dq`eRk! zoEu;}8Z*Z!u-0^d;abTMF1!nv!i8n3H*6}$_Dj!!es3Ym!OrSw=7qH>^lCs=thS|< zh;B29EOEw{=Ako_R!6?sFvO|t(X8o$fNBk4_xe&!KRoz>2(g+TN&oR!+LQsRzc??n zKBtdALpYb7t*3&oeWaxq9!40HLY^2ahp#eqOU-{N}MQe}GicY8>5OAf4tedtNvD>mz+ z&vrPitp1oQ0Gu(iN0fE*Ru)BqUa3Xzm}UI>^j${MWqZ9PlKZwDfn(CCdnft(kU9kg zX6W>PyAio8;0Z9^Q#;-VE1pmTky^_2WEj~|{lrSdNLo@OeoNVZyIDHCgvz!gc&lTb zL?aw(egsn9q~nM#s82IQwhvi{u^!!eNEO=E5JcLhy3L>Ugfik)Y{?DMcaK`=?haqc ztAzK1#beGwm$M`sT*-mUJ|!O*m6wA6?4|e~_S^A+`Kr7+!G5SdbPw2@dGafaD|NB; zOqiG?yR5Jzx4UjJLvCd{X2F7X25I17eUE*CQp3LMOD>t1L9Wo~D?FQoctA2dyu0a& z{0fx?s18YDuc%Cp-0x_-I4)QfHgN4&+IFdA>vd&YsCYFX$d*7-^{rZ*?L}&|BjNZm z&}hIlVs{a5oVGNjM{U$`syOFf*$aCGWpLI$9O(kP<#4c`lISB`NEm zUCaa(X@WjH>h_6o36t-(gPrzxr$e$L3 zy3EfXx@dc3CYaWyN1p(4DLmxxGK?FS_x7h*v|GPI$>(Y++8967M0?4cX!!P1Tljj- zMv`urV|4SNY#)DC=fDx5z4Q|_RHDJ*Lvd1~Rqe16dj+U-APE^`?J4DYb4mZ)?kx$V zg!fwK%wy(A3WL+Dpd?(6E}jIoy5o0-(T45XZ6u_2134XV zg&s`8am;Q^YlMeOd+Rn$;ZF-~B0acsah>r%(O6(Zh=Mp~B4 z7+kSpJ@#?V0hK)taZL6RfWX6QxtpzPreX8v0@AK}XkOm3z^rasMs zlmH#Z6rbLby$&9Elf9(B=eGRla114=Sa#s9Ay$}XV{dA0d;3?S5pN$=V4BD_`=W}H zVH)=~yKPGdeXZEmS@$c6gE#M5VZA@1}FW5dtb@|ZV_TV?L_uX#i=1=@rO>Zjp1(FU834w?TJ zPH3u2nC=<;u4<9ZyL4%<4YB?q9^=r@^_7Tjw9RQiK2%AHcb|v}J1!>lz5OL*2-!ea z1|Jt6VXDx5@R_%xL(x!E%0ZiasPvEiIU(S2fqV{M=9c`J!rX;=dz{(I0hv+xM4>}= z^LvdHys$*DiW@bFK`DEEm~r4QnHiVvvMcj@IH$cYTxg7;fq~Z(;F94J&;>%y(L5r4 zf*JDqhn!ueJL-cS&AIM3qN`&v`EZ*#mYeH@-3K zQ)4KckPp`Tib(t(F%m6IV=9FO(>>^qUYjgpyK$5=U48H7;XJx%bkCEH<3O22)|3F` zXv~TnB!ayfpImV+AI@$cb!vq5o0+fy^Em8%-Y1P%yJQp!5K$wqMDK8jf~Maqyc{RU zoK{JV^8Quhn4%Ia!Cw(c=0s9A{X(ku=r>;G(+5wmTg&WMl|K#XPjws_g;`FjOJLS` z2Irz{zUrA|!=1T5hrdT!jG`U+H&hQWmh3UENZNXj*?WPB?z@;-uTvUQuyi~KxGsTA z55J6p7Vz}5_N0Mx#8Ygx4#W<7r;W@EK#K)vGaD<`K9v+m3kTjj|Mfh#6bu(0zxG7c zJlti))BUz&aI|e`BH`z`J=V%oXg3khj#M?6X^5cUR~4l@%8CD8!q`mOEExeMdBL`| z4+s+GL-GG z9w7W`$o&R}d9y@7YXS30*xf6!`m0!{o+*v+mz(~r~A(jH&VfsAEOx2?9u$a0f?z3Z?d;)>R%1`up2inVk zS#GgX0;=JRLHfG&xky%AZzHQ8MNstN-A+Mi1*C{m4jIS}VYAhw1_!-OIvjC$2p0;s zHBG{Cf2k-o9Y&VqX6emqqnv*&mgX%~eC&N8IT&VKPsUX25&o$M>@>I(OyI7!3$@|R|6K(~< z!UvYp`Y0CCC9U>`s91Jsj&uiKyMmx96CO2odoFRtRy zZejpT>LV-V33@mPZv6P?Hi%Xum=Z2Sc^9@~Wgd%Oz+@Og@J*hepr*`*+nS~i6mwbZ zwrZ3|lBi4sqJ*0an4C20bi02JmO`fEb5S46z;d`EOzY`)8QhV;gFdT6sjpl638M1b zzb@Qjd5XbmXPYc<>Jx~MrkzYjHU*fci(c@fG2Y_Wy$QV2>{Lt?r)N0pg1r6?dPp|IzpUn8iD<_> zQr*VnvCK)B!nCzE*{KV$q|it+nmdSw&$Tb+Qv_Qxa}-wec_ob7%^)}L^I2XBEhS$) z!g>;bth%hWfe)O<)ELl4?@I-NXE0iWx=8MR_iibV3{h?rAW#{hdUS zaJ(3g$o$ZwWnwxTZ+uA7WV?+5TLyf$mxQLq3^NJ5VkYuYiDN*xyhk`J<66C8Iqa!$ zQX3NQq8TDOS9Gsz)8bB--&vuk9}zAHug0ES9z58_jcrpkC%tZ27cSvmRja_y68vMB z9u;Ce!7K`d8m45P<4>hJc7f!aqwtY6@nQ+_#-wjgQcWC*=(pRFRTK8zat-(>akwP{ zkaK+Gmbljuf*jpggKdxyR`RvB_l{o0b6nt{uRo*Jf7d(3YrKebvEea*^q?xhK{)pl$t{mDqEKwR(d+BkzmE!5e&II20a zC;B07zWGF_OdE=QMT-$4ncuBE&`j$kO=MEd9dvhN-${g52v;WJ@xM|^Tj!6F{4;4o zy(S80Sl?$czcqhTD650ml+yT8_IuJ0sB9e1^_lroddM3^J#$c25AC_&FdLf1m-URt zrq)a$EEAN@g3L0jMrRmSjrvMTvYA-vVGUk$?w#1E&Blf6!g`)3|h1k$U#T=EZ+hq$H1*B+l1IB z^k)T7YAQi5a+SV#FY+@O1exD`$$;@QwrfcA1u)As#&DygB%rj3C*v=828PWx!7RB{ zFBgRv7o`qSU(E9)gyPji9o;%)Ij&eTCq47O<2qnm8`qR4!4mG9;9Y9Y4~3YlQpmEq zaE6MlOu3k!8)-^kdVjXxtAr|BKU?(|59&~ABprO$q&L@)t1Gk7RX0J*OQ)5SVY<0u zy}24bAyo_)_^b8thBoASv4W?Wxfs?c88m`z3CxnC%Jz8@WaO{0~g8qiopt8OL{FNM}6b{L$^ zSWja?u^f?mUV9%eSnO^Q4<9O$GHD=7t1S`?-=Vx}Q-`!&Z5_OdWAP@ph@&l@@1+|8 z$GK#L+X});IwpmqYQMl3sp4FAp&vP2>A_*2r{M;d7 z`rzGN_NypX6xZCs$4yLKy2Jg|={-H_gd+-(rU-j_?6oaS>e36a)PI;K4l?V8AN_7) zc{?ol#27L{d$HIrbm9Ha&LH_ciG7<(AY1(9TuG#F z%%5Yh5N=`>wr!e;^BDWvh~)y`cLgix?C8L;lXL;FlGIV~<16dfr z!=?{3dOHn|Hj1Jb1aP-12M8~{f|rkqynp^Wp`Hg*1D9W;L6AS;K05s}K$5sxggG-( zpE5C2b?%f895i2xWm@uHM_m92OBJrp1wa^@0DtD%es;oY_6Jkz6 z5Ma^hAj(?ZZK-R!9t`_&L&iEX?$J8xIaEq#%8Nz&8L@Df8ZH!)qZ&`Wns3iFlA6NK z1Ci(8&iK+1NvO_X1D;@k7tGW5_lg}Ck1OPSq4}QVf`*qjIFQV|k?+E2!mn5$uXRcT z2_~ua+;V;)a|rW?-lcMw(~Z{}hcqjG35_7K`xWG)Nx=M9k+^Z@`Z7n=V@-IIriFD~ z-&zvNa;(3KS3fasrTwN<)Q`g{SC!AiHu?FEA++|peVy@>H~BV%@WfuiXaeO5EfVKl zXdPc9^lLd@mHqZedR10A1yD!mB(0YNy*z&v2F!M3WxGD`Fy#b8I5L%*c7cSHlnx0^ z+_WYyB+q>*FUqPh_b+;n@Kbg8GX`5)q2_}_>L)$WKvU!(wI@N&XZzZcBEngdcJ*XK zURTaI230OB$)kGflS9odDyWxd64nnwvnYWPw5zjBb1x;(UBIiz7MlsYvo){30pJ#{ zEM%VY^PKmVJKkz@f|6g*rVXsBgG1s9d4LJz%&*h%Z1i-#dM1KngDi1-N1|xn5f;#x zjDtVls|GekJ9@J=U#SsK>Tjo}sFRV+<~>_^fxB+1mb#Z%27a@Gfv^~IQYqu?5<`C% z;{9!5K6n=o-o3-GrW^6siUR=w&`~7?>7TaYGY>hphvY67L!!bCs@}3*nlpQ~ywts3 zwxrnmK38;#+C~E$BLN$BbL=d_UX~qnPl*9-{PSPQv|@N`-PtKffReP#NKRw2JJ$|mt*bFJLUP?qF_RKQ9ezDPwY{wqw=h*LIFE8 zS8WO;GEqdg@y=Oqo;BaqopRepyGV&@fE7zmYJ;q?nLB||lc3iDZsm4GfmCy}rx|2Q z&3$a(Fr4$-w+on0)2VGspVhJZft03G!dHmc!JjeuF$Xb#h`#^+&csm(pNYI%(+pRaU^rC zV#EOpe1PU3&3iH2r~j-q{r<%- z)$01~;?|&m+uSlDqYq_VSJg6J+Fz9xqF_H6DB(UTL-a(jtK&j)ZmH{Kr7%s>zt#k@ zvF`CR^qt&b-ap+r?n01!TC*}mEpK91lUEgD2~2NU$NFgC!0++GO^|3eVi`0DlJ~NMzQcE_kD)Q`t&FyYF z(A{ze-Se)pGw*q*N(JGKGLBzxjG!IB9f>wB0``ZQrr zejQ!bYnBn&lE(Q+ENrVlvUmAjiL!A8Lo;C9!DAuS0QHQ01>%>=AA@K>Fi+rr(j>#1 zF$Vnq>gV95(ih%7ME#HNLRJ6bXYYu<%EKB~uima9F6{}u=phlFBEGBnEJKD0r@zg> z(S;8ZIpizqW3Q?+sS7aysLy=)%*#{Lecl~mRXy0TSThwy7wTiFJ@4Q4kUf?%jGtZK zMRO@0k->G{{%r%gNxFq$svq}eSc-3okT79^Q}6A~P!G$|I*XJIp(;YJGhb=t#B>Zh zl-kuR>LZ3W+NAdkUxBU?-IxbgPygIMQ;&Bdz=(J6m!7VqZ_z7%INImvl8F8Ep*J9_ zaFLt3s7u$Z%dHXZ03s$wYj3nQIRG}HadLF7Bf8ztw|!0imtLj%(cS+&s!J-Hb8n=; z-yf&3X>g;hdSM&(lS9zS;aPMPODKpha?CmlJAe#LZvzP=A)bQ?WBXHf-okz&&$j0K zDbgmDwjZ;;S5qoBpJXZ>5lUnA;=3-4c`Z3@Hdbswo92#1|F)E zqk&$W@DDGgGT6)K8aHR3ir`Wf1WB}LaV;<}%20-jV#eVgvKdxAH(EDl4s*Jl_I~2p zr!OCa>4bIS5-J}aDrSz8`wU`0FH=`3XsaRI)lWZaX6>C8fx!5jn zq;np1G8?9un_>xx-dk;0yb~JrWxb!|cvcH=j6#KDuVWd>a8&N;rz)=xF;Xq7V`}E` z_Pd-*WE9B>n@eZNJSL;Ef>wA7x1P!{!$nFkR@G7Ub|8c{n$p>kMzQbZ0Q3Od^M!6S z5H1sz|8Am5`vLa*hf}PDH=Mmpd>4Tc&WD63ba-A$@8-Rm@|DFN!^6T= z?*pfA>~XwoKo8oQmi#j&?HXvpOThv?KiZ9a!Ao8>FHR>W0k`1}9LhG;P(|bA39>a|IJW5RUpOE= z*3x}A?$6+qhN^`K8nDiQ31DIE9q0#$7pT;uDZ^{3x7p&`*ca}q_%a@wTLLM%JCt+G z>Zsc+8|GPWcyteh58PvfIBUoT@}vJYViUbJVp9*T_Ddu&=@*#JzjS3^Z%tq^EmUNr zOD;k168XYWTf>Gvd0-HSy5se9xqU{UAKj}$)4vdnAwaJythRQIi$ z-YiauyzjyO%RxhB(W{J-Im4d-u2&S!zP(ahQ6|H*lQ!6WI!0eTiedYz{KUVB@&@ZJ z5#2=w8KTT%ru#g-VNe5jKdZPzKUS5)iq{3Nx#3%P5bF+;aaD~ffrzUZq59FxQ{Eq~ zHJg{WlZ3Q)alh}qCoW%t?BxdU=9edf&lw%s%!yYAWZ6Mq`}aMcK7clCJ)=*K^!e|x z|C~zTEJit7?(YNmv@^R%!mIm74|}DoBlB=2HVNzYP$6hOp4aLyfr>SSySSR=4-#ur zBVtEei43f0O-TFBDoj*Oj6`PliN>$03C&KrjUy`oIa4jV0U;3)mj2E%JM-4Ts{P}r zO)_oh!_YKhS~6K`qVT+1PRDP2+4qr)Sw49pdK-)U^@m#0%a9k(A%fv;@Z%wHOrY;=?%oqq;%j%#!# z^L0i$(P=?m9F>uaeSIyXg@6A9No_)*oZ8VYPDHx74c>~!m&dh zKS+Nw$+yhoB1jBm$Q8<(d_{D9lWg6X8b$y>Pfu8QtoogFJ(%8x4(h{Ll^WYC_}){U zp$sZAl$s2gXQI!L=Qvovh6ikFOYK$-IK44C7B9YVtZtwQV?ks=KA1qecoeB*sLtdb z?jHkt*$LqCnxx<}*aW#qa?+}^(ZhI_}v5T=iOz~&z zxBB>4(tQg~MU9ewZjWvJE>;pdB(@gt{AVdslv99TXQG_^QK`tW4fPN^umPrT(&g3k z!ciOZUrw9*VK9hYHr=4^ao?u6Y zSKMIPPtv>w-8x=1sSM`47_t!FC@2E__vr4F4kcSIiD}YtJCBb}U=N2emv}WQLa#MN zzX7iyX2APokszZa{KCatgEAR64SZG1It-rQQ)I3iFuus+dq|_P6?m8}`KinkP?cbE?A7%DRzX6K#fbkLK?a=)18#16+vkOiqM$UVf8-WS zKXE}K(ARdIfOd(fdwf7qw6XxC7bj~nQFO0Rf?%_7*n1erjwSFr>6@7KB!ngMZGZKS z*-wRE0$)SlB=wsr)21Q6#(;0+!$j3IerFdg<9R>tBxt9a762ihWy5Ul^2ckQB3ERH zGYRF~ec%`3E;k*?@uDCrr8IR81yHXtG?+tAUFB!*1ARB{CwVuGuC_n)051F0FUc&K zt33M#NHubKynKm8$H?f7RZ3w$F1jeXYqU8uwZj-GU!CYZiF&p1w zJ~k4Ca_axCGp3L5OG5)MUnl_hENs~-BcB`gI--!ENPvYPy#PBToafL#+UZJ?^iEPa z2W98@va>CBbY@(kW*GQQ;8#W+T47AGMCdf4%@p#P@5NhZOPg{0_)HY>lFNgwx)6+lNf(qnfuDF{Uoh?lc+02iLAKw}CV_4eU2!jIYy>1I_do z)P2^KVE6CHR*SnbI0LCx5T0d0kUFj3(dz|ohhd@HCeb`Ytw*&oj^yj(nn{B~+UmUM z2<`cAA7lw7rSycz@MaU8k^WiiEczU~q8{A@l{TE8Kzb2srjlW+MDU3R_fhOfz~<3$ zNeTGDL&fJ6R{SwUhfE@rI7-{F^cI$%b598lwYX4~MJdyc!@|b`zZZFe_}{#~>F4l7?}q8WE2)m4#k8-VWcgD?Zd#w9WP7@HCrpkf%frsy5z+BjXXO$#*k{byNS8?Y<#Gap%M1 z&T)Y95*tO5G314m&S(0sS_34%9u=rV^wUbVU2`O55^MgrH&xXrXJw(3L zRn97WhDpI{1`uTH@QbRAck`V0t(&W{HXrF}YRJ+*v~-}R{jAVQIY_3VHht;=Dp7Bt?y~n&Bw@AAQ?~8{I0CX zJDwK`D~j~My(l*I5)V~MjuWyPd)G#902H~1vAm7&HeOIHDmxp+{y_rlop|@J0(-j2 z*0?cpm7_s`}rAF3ENBsFbMb8!jHe0gvh<9A!NqmvYeL}yvcM_-QUQHeo*%H9Il`0;beKU@m#Efc%&)XNjlK807^!&wYf4Pc{8flj1q$ z^)P!37ACxRp%d4&%U2gw?;wC`8o{>}slIH|rKr&VCKU%3*F_|e7T_IkTKl1!?@ge< z(2rX=1*>&+mkR~FgG#i>kQoAbO`?2F(rnFdzWjFu@~AxMv|0;5wGT)KggcP)09ml@ za>ASXNr=^etaXUn@@qjACl9(v&Ucr9#J9EmrT2kGZuY`~= z-B6yx!C+ByDFDxU{o$SHgG4*zK7)zeNOL;ok%ynm7H=9hv5W?PVC6Mn*(H)YI26Vx zn$}w1uG{8fdspkSoa#CQ?~xnPAq$U|g?-WROKPW%MQ;o;VE*eH<5EX5I2^mO%cS%z zdm8zDAWiL^fwzQV#{fnS6k82!;<`@%_%n`u}Ht&7~W$Qr{zmB zYlj>AU4=#QBLUZ)PgXYeC0}QQc8)4v?(0PXpY*|*T@^}6mF!8-R_hG`epUS0zf%Q2BSMX7@|p1s~6vKtniUCvgS|G zDbGSeSuyt?RM6j02E`bq)uI<5bf%9X9L`jvIR6+d1J zK)~mHQzxWA3iyl6A}Xi+YuuMwqaUPs(PLY9M8i{U9&$)N^Wu3zNRzq8vr8;2gUkkqfo^zsXy_qu_J1LMS)HFa%FQ^N1ZIulbd>27; z)hytxvKb<_^@~2ym8iE4AlMV5k~`FT67-=`Zr6dMKh3odVQFq?^*@S$!U{}3BLG$a zl_|0(lfxN~v9TESgjI7JW4^`#RKhW@y3jKA?<(v=KpuZ{*R`g)+c|0R_?>3>egw;$ zPjXY2zlLq{0e|mqYAf)f&qM?PmFpbUlEcAweDlUCq$8-q4cc7|+9oO~>-r?Che>Gt zsPA?{JQ&l6!q&>_7FEt`6%=`0`G%d92~pl;RWg+)2ILEjsc7(`Z!`^{w=svq_>^7k zm+bI72x-6b$Iz#J-HnBqy@+v8F?Wn9R8DLUXHDBbzqcX!=jBXv(A-I6-{&8gP1y92 z`=B+qXQPiI*HUbbc~JdutU^7scZOy&mk1S@%lG+catQ0c3y(+slLi%MH~od%-eQ-$zb96-dSEqB|0_XAn8prsT13s~n94%-w2)=_wGViPP(V$PW?V6mk zyy;6v%KR6<5c<9RXIphzGPdvwlk3a^%dFpe0^{umA=Vq5an!69wWWzI2EOd z#d0LK@eZ(oLs(JyeG!y;Yc*j({v#vZNNUI+aSGp!BFIWJ;3D^>P(%~;5&C;t0PCwjIy`ux# zE9N;T6oTa6$=6yRYJ$E-q1pusZI}|AK@gt>!V_Irq8xuFwcP73S@kp)GA4g7kWFGilzEtoU}&gxGf0}3k+U9%?cJ3w^!GcSBWjD0(p!=)?Q z5`o$;{yE!4TGW~DC%`8$mDRBN%FG%LSFG2qx{1vTg#ho%VMKf^l;-0>_WQ#17*>t0nI)}_}8G^As_osYj z$mL%VEJ(Bq9GGoY1JnD5TYzgj$I5FM;v&DCy>o>`Y2i;biy%xdV={%W&Iry^`w}S- z77;m+rzoj33n0y5%n83VJFPz_zpI*lYm9yn2jUWeXdj@`7n!F2_PHAar0jZ${K?y-YL_k7H8U}~%4naV=K?G@}yF-B?lukir=#cLB^7+2MwZuPI zEY>qT_nx!Q-us-B$~>A*6Y<&{fD(T`=ck~jKS1S^NUlg6nOax3agbe`jO>i}VTCs_ zcael=+x~88NH{9b7B-}ikD(WV%8OnRw;OsRGQ6Dr?Md<-8u0$!VZeHEe68gw$Es{; z7U`D+nO<#GQ!aK=HH|Dz2JK(brrYpY`945zn8YF7oTtfy-u&GriYCxs3*fWmq7?oW zlM5Thxba$lIiwa7pYf-*3W=XfjeG<3vcd79`$!J%0Grki(z!^kXxs7VM;c~IafK5` z?t(jFD3|d6^8$E(?%gMjGz`bOy$tyDa~)YZi*!EC^gXV{98KptVnEN+oLuap^@{}yRE;AI_Bgp6Wo+crErvZ}?rLnX z1>1vD|E0g@nak|^3rc`LstJMjZjSif%TmW4g(iF|^Y6`>(>;W1H##k6 zfhtTOrdLe_AUyvYBNaxWqI#&>d5_M5PRmqnjJrZ2te$_ZSqaXpU*|>^wJaXviPYK5 z`+^U@)QSw?;7i2;?VAk5re7t{q)m6FQa2eW@M$4HJrd-zO5$UxXKafsRdZktFUTD^0wl zXYeRsAkDk)Mz-rYbeuYas^U5{2A+qr4gXMKz9aXiWw*64*Dyq>;ci#M1STzH0mqm) zd!DB3Q(;uD6QibV6me0+2zM>4e~v$Zq?BcaWR~pH@#|kVbAe}z|8D+0?Z@c(emgkV zB#h4j=&G-`CRD8pzxvNc4>Yc6E}>M|xi_f43=8hfg1UxCZ7=b)gxR>T1w zkFD3#%U*PsDG@gpiB`x&C9meZ$0C-h^Ln}Nzo+iCyQbP~ZjRU&VzIYFKl+s_9a6!n1R#-J&0R4wSr=sg$jBrGtbq|vcagJ?Fe{2NBr6v;r}PNO+be)^vp#imBo>!1M&G`Y^WcD zWmX>jO5voM!Kl=_%_Cd?*|$LvFXH4x@NO%XyG}WTSI?!bCQoBLEAkApvG@9lNvNj; zThlLtC(9iR#eaqDmo8kqQ?55wrIouUXaq((-e=qXOT{@Y$f$vSJvN7+H?w&@syW(G z%554<_^!(1U4u#`AFAxd{b+Vx-Ej7244*!QMIoXvluS#r06ck~5lfdVsk)`m(^2lg= zn>`iF@9fRD8_&$r06;TxK$^E1L)3ULyI33t>+hABv8*Q$6};|KzKc>u>$O?dXr2nJQHOVW^l4C(5B|(<77} zh#e+u_l-m5pNz5C#mx?M+A%7L5YKhwL`ZPI;u5wQl^W(0d2&y8zW?;g55Zh2T0-VN zi5!t-mL@|Qk>8sF6+rd)mlU;tdw3$o+S0a*7_PmbBHl);>~=Ry2w49Fxxo`_hC2Si zCz4(*#;?g-@_+sR(*!-<#naDC=U5w^n5GL2H{o}~y?+KG@F>sN&Ox1$IYRTYl76q8 zy!HzQ+!Ehw^Yj=CU|HEt@o(`i_d@v&@AYUg)VW#F+J!63Z5RC&9sZTWKk$-JC{`)Q zkPL}$zOHjxrLVGkmU>{DERdAV^jnR+(Od(DcL%-2MSYnveS`Aqz?6bCVf^CmI@KUN zZ)F@5``z!zP@s^>ok8ulY#!E8$fZ!sbxfRV)klt3+mECFn;9d+s*9?@IFe3#uL{&c zNV37B2gE4;4?9Yr5BZ#wQ&JJvj6^t+Cg+9Xzb(}SmiNg!0croDBtWrJDK87khlraV zg>>^kSwnwdLEdtkq#oTp<|IYq+Ps=m6+=?YrpO<`?`Bj88`3nHBu;@o8DD#yOkBt7iZvypGgKz`tq&y-LC^PuJLazs_6 zd=cl1%)Xb;pcNylUio@87}L}%8w{*`-I3TZQdZXG<@D9j@_Uc&HlaqN;YG`U?>0=B99{^Qu`l_Co+@j=z2xp zV(eM+{AAx^=z~o@7&AwQ`P>fas=QXNW9};C zls)iq)909&bg$5SC4EW2N~_+@A`)2oDsq`C^e5AQ!JtR{#J{2^;cf@P+)g=&?Q{?K!MRn;Gd$8xk#_2aerR0^PQcU)R)#;(Pj zk9!M*ZDbs;=wx{(j*=)Th5(Yt!F7i@{G!V2(;D1WCWAh3Iu{OqnCPNC(ob{>H{2^f z-VH5L+7|>=LllEQSZ;6G<@F8wT6;HgY}!h`>35cK`Yd1D=N+K)zw!4`A@7y`=XL-0 zBDw||6Cr#X8QY`Z``wf*L$6OR>*y(F}aRW19M zj2$TnYD;W+Mb;AL2UR5WHFn?WRSifVZO@&2`SC7RF%h1Q9p2ZY820w*@>47jxpRZX zheOU39%!3Iz(aAi|5=fHyGp4F)4Lnp26_a`^enO=u|7s84}EQ(AFJxu$3}d<1@iu{@B3war*8}1_RoZW*!6^$rEWU zXC&5WGaQz&D+UU;Q;nglY)**%t0e>Tj>{ynsXzQvIf1iMTZ`uYyM+qrX2iZGAy%#v z9YinlZZNxlI3N9CK8?0+a?G~|Mm`dr-|L$iQRdynsJtN{1!Dau1VWvYpy-%j4efR9hfoCKPOGqYO~hA1>qc&V`yinY5u%(yl(cq zR%qq7C%NtlVJ~ghUaFG~fdLJsEE;q^S=6XU7+s3*oKmF^AH65=wS9Vc(Z;3VM&U0_ zfX%i*bcbyI^Jx8CUD@xI)ktK)PXe-@I#dZalQFg z8Yj6qxsm#-rzF;%wS{Ym#Hz6|rF7t}UiT23=2i7E!G>{QH5l5Em!C}xWErnwvE@Z2 z^nYu~9Ysqjm6>5nPv5>$87=zXdN7xsK0BJlf?2;HmwXi5Zef8;)>%{){kF1vBghFf3Xr*ST2aSxz9!!jh1K2lham zyru4m|6MB2En-yDdDiLXv*ZX790=9ECs{V5>wUaYt!u7Lk%gsg2h(4(d`+!oW&xc? z+~0Jfgk@|eG686gF{2!Jc9*JnOA%^-`;Mf&#EB+sGB2}9qp}GupD+BDT`udNF(CMA z3$^-f6c8Yg4H~jLr+`bvCYOi__6VA#n%aI|iJXltxe(lCDO-6~*S_6sj6v>qW^k`} z9k82-dg%2)!@Kw(xM_)#eRZ~X*$uGLMH8-UJ_;KKSa^cFV!Df+2x3}8xKc)Yh$WpY zplpQkPWhrU6l9HF-CtQM|8ZkF6|7fxjkgG`#9Yk3^01|2{lg#UZmidNTv7p?yXbUf zc^wQ%x$)ze_{W}ejy`r6|K{o*H+O}*PD}Z#9spQ*a4h|L2v})SfjYOiyfcY!ynP~{85WOxYs>tyLK}kcUVXdca73sdFr5NJ2iX*Jc z<&3HYx*Scek+#z{=99CMt9AZE9QB*PKfyv#crVDHFR1FCmM{|j7q;CA!h*nuq0X*F z%L9)|F4H1&I-1XzI-5_`o@f(cjs78?HJiIsQk7k*yD6Lq@D;Sox4V~GCh^kJfWk=< zKUUc8q0|sdmR7V8<*2XrzBut8{odfrLc0xiM_5~>A6YiTmj!PUaL!2mHTQ0B6$=M8DkVd3tFvdYWTL|-gT%u@m2NP9)@ zni&&cFRjs+%2^aqUzBIvhNtvM$JUc3eSj~y>E}Dn?~=oBMxs@YEu_>ZB_1+{y?lf8 zjj#Y?Rg=341Kbnc`?}`J-Zz<;JCOkAjSit6GKseWYFP1z&cIEc?qi(sldAKaw%O(ywJXJXUHiNk90f<6`uzzj|D-ucqz(Ma3u53Bc1 zCYBtbmp=$j<8{KSz}4$NQEddj@9YUakOoexC@ahflW(ecb?*LTHjA{4EtSTOW#f)S zgEE#IlvdTS-*7~?{G5H)>$FP))nK99(J>0rEJ|`_yv{#4WTrSuy&;4vt_OX20Zo=N$R0=vV#+o&|fp@JEE@bYS z=BrCgvI=TM5-SQ-^w`6)G7V6mSiO>1C7>o=;JA@`5IC}Z%U%WVC~If;2YAmVGor<) zfR#NhLNugHMrW+N!jf$F);{+lh|jfyiNT9B;=pbV&ts$vc%0GHcY3gANCiw*-g?+K zJ%+@nG9zJGRep7l%lqwF`>X~}lti6icG{9}6J}<@fA%PZUut^)VIctFoS*G!5NHlp zqyTXVNU8X@kA=hX;Ew?=hL6Fghdf?1;eWTlxDTZ4>yc}u$tv){);&YH-kNC~sC7Y%Q&Xa^@(xl$(xd-9^9i}>Aj z=7)>&obBs>+QmTi{|4~cpX#lB{v%D1svBm4t%vFjbde_A=!yoqm6qMjQ<9>bXZt@Z z`kCuv#zJy4Vw}uA!`Ch|aGIe@uDb2J3^E}sJ-j_GsmksGw^t)haP&b&*tlp^lSkNs zw9hc84v1|#>&qvo{!YK3=E6Gf@OdS3ObW;4YJ!4%K<>46@SBD zHE}Gf@pFZ2;aK@T?d)XMhC2<^o{~@{%;#{|F=)y@*FU;u!l^A>ZPq=U%MX`X_vf?b zY7$iZf~CKukYyb=kWK?TylU2bo^gHRTf5i3L2!ztQxR{l7rK5BOk-r`_%TLd4n*Wn z0yb(txv-&kw1$1lC#xRupN7apY8K22wkD}BD$Rr8k=U`q{{_*MA9+Unja3T)wPoz7 zM#f!UHP{GSteF|fZVAz-a!cVKhh%3N#eBw$el2g>+@Lwoq%VAfKWV0Oi)cz|S9twU zA2(7)!0kP)jTq|_B#@6%9i?BhO@UrPZXWQj6z|JW2e`9y@zO~>{mobS>++@T;RE7j z3c8tdQ$tql(a8F;f0Ne}olOOPE!X(%O-ststprx8>y7urxC;5}$%8fq2bwUjwL}ha z-WE=V!|lZDUdv66QTkQ`@09CRrMdmZiN6&Qn5a8VXxvG?a1?my9dU3a@DEu^H8m={ zi*vb_$aY5&?vyC~t2PaARwa*{7H(o3%G(=y1K=6sNTMCQTcdS&g37FiiIf2lG#Rfu z?`o-wFd>M{m9lJ6^FgtiHH#RFmGpN&$eO*@qpXH)yyHp5x<315UmnQk43wi84Hq4g z0R!|Y+xM+utJd@zgS50k?mN6$P#J3T6r zeJ@J~0zooRr3>iE;gg_i<}x2M@Y#_)r_R zvY4X==_QFPPn0IVY~(grYi!FGUSj)gL~m+6bWO;ae;c~rMGI7IWaD8b*|R{6QTjdE ztm+R($G_g_$>lc8?3Iom`vM{a<+_UrmKGWqiQr|ISY2PHQOTTR5FcE_YAukJ^|ohkY9dp+`u!CblS6nzfbu8#C# zPK@>kfZ)Sm<4>((w_k+Qh)ISy6e`&E+y9H&6xp>f%{uvg@?YAcUBq}oqSQ5Qg~4bn zV}$$D&uMq?h@mEoOMj!&t8}i;?L7r3PY!=@08p5XZ8d38=fPh*pr3D=!wuumL1g0H z`&mTJi&(xi~DZM0-VsG@!{anQMmw%`;@8dW|l)K7pxbb#Rj{o za><$arf=6DhAijeNydTz1mDz%Ap*H<^J}QN`;KoOiy~Y;m_FWxzi*z(JWZJu-_?h) zN4oC^JJW;{^45xwvN*N7a8pu9<&;9WqI!)Fx39`Jl#dA_>E?l$-SV~CNAfZG|1 z&BUZ`LZy-g68_BD`pfG013Y`4<=ze}wf#3=rF7_jA#qE(+sIl@FFn@{i9r8H!ZArX zROH`UFF=inVeZFgXU35|z@14xo&9~!h)p|2=Kj8y=N zRJ48Aq{Nm5!HZb0-PH(DksJJKlCFBE^8`yRH&ClBjALM;{zx*N+vr#}d}6$#?Ml>7 zpf?O3;dg2zT=B%`W4Rg$spOvD)mkP89!ZX-7op_zLWxGCBOl0pz@g z1Wgc22QDDbKx81YQwZX{6WLhwYkN<{7SF<$6j2}6se8yC`LNk*sWZQ!fASgeaqKIX z8DFX;W!5ifE!#Cs(hCtIAy!l$AgTYrFU&q!Wonl^8_Sg#$rI;-%>?_%k@rs8IPO%p zGnM<@Xt$C-CFwSv5~9BRkz$j?u#IUhw^+X3S2y>_OX0tA2T9%4Gc6kB5G8|u=LtC{yj|j|^PcvWX*ib;N0K4O(tfBAmgWBdACfOehMOXGoZ3UMuAnYC z&Z2ps8QHdm=e8tU-g)Xl2z+fb>>u{BUUg__Is|`W?#%$v0dhKAycDC8!?Y|fJ7OcN zB~(b`Sdb=7GIVs+)$kE!h|bVBmJ`|K<+b)IzV$R6-mLv+=WV=;egj25`cX~`rbRGo z#QpjPCdib)nPRqVFpYpg=CIKKgKjp9jF} zL@={ihn}TBA7b{odK9Z|B^0>UoQl++M^ex@MN4lE>pf55h^qZU)Qq`y@$D?gG|d-d zfgj8FCQQm6&Z37Kj=D0KcBg2jSJXanqtHdrAybkBut%fhPirfH@C@gs0>{q&Rcsj-4!rALe=%X-qPlFXe z4?Yl?I;M^N85YUNvo<2!I-*vj9OGOgP|I6ZJo6p3>2x0DcWsOc10BBk-4tQ2=s#L2 zeMNL`84sV0h+l=v6mg`&Y<_=`J=oR(lB?qVQ7QUftXt=?iPX|$;|N;p$Lce)5GJO- zutA_*k9ry0F+jOzf43rnpu~QHB%95&?4O~MrL&?yR<^Dcv|Fusz|}`N>7AkD;}Lg3 zzj`Gk<^QSLin0ErXT9sfJlV?ov9fxI(JtZTiY!MlliB@LEdP~D1!@%BJlPj^+54km zAfPt28y=vUVP7DrzoW3&hJUb1_8;$E=KmkLvu8#Ds3hbNRdw+u+=r-&0TBfCUgQ8T zp<;y=9Q`L$MN=mHly}u3I#qQ#cCLOK+r%V1b~I_f--v7|fAS>y^obt^4ArN?lzWzI zQXjG8LnKzWFCy{IFFB&{A|CFNDb9rP*sb|4%Qr=dd~)Knjdr1O|Mk8x>c@Vj3^1H8 zyv9zid($#(x{vSq3IqA8%yB<(_MD9wG=#KZx((pSI5vke&AsX1^L|SgqD7C|xzzC$1ewEBvx}w~O{;paMjQWwD!jbRWit;s}?Wd*ur7P_q|T)&23_!s=9pdRw6{y zY_#J#utv6p0XcX%l0n^f5oy$$gkE6AZ|^Xms8WPd4^XamddAg=RLCe6~~x~EqBzKF)l+FG1ic#Kvn&^(EhT8vf4_B~UO8W(xl!!X@(T z#rs#)s;ytJr5}(f_p^q1zk3Ljv108eQAq}*H#Eg|rmnMu0*PKfYSqUZvIXfTz zSf*#80~V=ozC?~An*6xrqoC*VjDytZvc?aVp~Z?MJwltV1BMmvXh$Z-@AH56ufter zrR}z~r7==HZrqLXTc^GutDkAQ8EW{6`4h5$v4?k^HFNYw$wjXR@IR_r*oQ2=XkgqK zG|X2>XVSaloQl!5#HBxWZaYO*8q;$RKo<&|=8xn^$y5H+4bRqft>V}%*ITYl`_-@J6QJo|^~$68c@<4&bt z3z-A8yvlQdQF_1c00>LuN-QxE`+mnn*G|;5CJ8tyQw{}ACHY@Cgrk;)MGvvkr1Ol< z&A-{y{m${OBsw?}I(G@+3679>=%W(wb__rx(8hZiFdAvN$EUN$H(u+jI`w;v%fZ2nUzk0SuVLH^HeKYpMLgSURQx$$d3{?3sv)$Q$D1lH+rvLHNSYMpx7gdS2%Z^t3^TW&8Z~CF-}rY zn+XY9(*T`7>86hX`@F+_fsXm!c%i_5yX)RK}Mu%Dp4&#j2qnVC2cZu?$mr7f6s{2ewu=t8{ljN%q*lc=($oGk4!f$eYQ44!9}d*~xz_ZrOJp{4_AQPU6BYe9e!E;g_LYb<5DJk|^=nkTdIV z<>ZE5KOKaRAyahi`hE!buEev6dMYyKD&YGqxfnxp+EBrwLWMa zNG|8(Os`@!Fu2yl%D=&LD<)`meX;EXb2@mGAbp-CmUF{NJhPkpFc>-)f<1Sdo7_kBZ2}DT45zhU}E+oLL>ydn{0*bcgWE&rS(VwaSLD5%(9N za%#k_G<33>yH$p-Koy+~0fmN(x+1uAPX&P$Pm|;x%bWflM#6iFCnC#E-JEtbC!BTa zKqm%CcmsD24MAYeXgS9S1B`KPy9AWKI8^>&yEtPrY1Xa zFSjUfBl|d+bp*=mRd{y2MJ#qjtj#42MkROph1+&2k+s)aO3xG>fVQ4jEZ*1hWLX>J5hA zc-Wn142Z2j5*x4s2-TW&@7BX6XvBXuN+6rCtH60@`V$zvNMP%}37yN+5jV2t`-0P> z==nF3Q>mOK7ZMV&J}*A0*FFmzMfXrH_~%(7`4o@;BR`#e*2om8C=AW`Hq$i%Nf6@ZY5fw^=5N6IYmQQ}ubd^6tWL7~Z$=Aws=D)Yb%{kOc z;Go88$tU>=Mx2yc0gbxy=$kEV)0fpim9es;xcyL^QmQE zR0Mp0Jju`a#5;6KuM_0&5UG;c>8!g|DWuzX&FNv@n4kKP76at|*I!ou-kRuh;cIr{ zTmBAIVj0}se4>L!N$qW$Okb*g1k?)6Q2R5Vqm_}qJ#ZI_B4QZMTC?g_F?3xg&6@Iw3P@{ z&~DInCQLwaHc)YDjboHrH(_a0BQYY7S_~jkLD+K1Q$|zN%bvS0>GS*?4&;`<&4H3R zwg>z2Pbzg+F*CU1pR|SkI3_X%A&ywg4>#M}$192jgZ!eopfxmOBS3cKBEV&*sy(a3 z&mqFM1JSD+HUO|zF7zXFCv#pHqiAFXpKA`&RFIRao$=>i?RIzjA5x>in1!_UG>y@8 zhWVM3Nsp5ZabTOaevbt0TH^p>jbI;QNoC&!Z9(Ys;8!~L-;5)ugLA{trU?QZG4Y!T z&e1^4LL^90&*!>{vBjbB{?mebSo!`m6xtuK^>4bF?^yoFI*s<`bn#_N^me-MQKRoc zXSA+h9cL*x+x1o%-FK-CT*Osnw>mFNnTo-P%;wy;*rYfq(170js!vuGRw&zw?9vpN zE8D7wgM)+I*3Wdr&hF8W0&yg~6zBSYV5$M+_nL9KCe7Eu^?&6#G&_D7~&noJ%2Prc0-PJU@zm+N%tb1_W$;JB& zmtpMZYJ8D1wiSDSf)hA@Z%y#}3v1uDDN(@iQVZmrd!WuxL&WTag+1yjHqrvs)C? zFjhlc9lIT{|KRbhb?@0dz}=uC^II`JW%mu!&AU!5vW|@`F~}jPGoFf;h-fmnmf_wc zr*!hK4FL$Xx)fa!@CO9kq2^{OBDyM*_8zloY76uQ;H14y2lz6LHHOV1v06#Wo%HrOXXYnag80g-kH#=zw2%eW3=iNhDHCk%X|k-#(O=@`Wn$Y9cdH++D#1}%(Oypwcn)5xMPdBgZO!?lyh)!!9@aKYj_ zYg-xC_FH5nH+gN2@n*G_+CMiO)vk7^I2z4Ez?O>+tU?CV`kZ!thc_6#{*}%T6e>T5 zVu+tW#4dN;yU*P}C){~8OUOpkmcmKV1d#-vfOP?kxqB8itPjS-j;)>4L&^L(mJJ-_ zFFM`ki~kG5jFlZBm0uGGn>%q9=bXcRMnlfL@VCC;YT{I{Y&bI3Wiu=~N5JWDZCc6` z;urYB!Vm0djMlwhOgZsu;!Y{kEy(j9UJboO0~~T>mwT zyfBI$_qQSu^;{$g%)Py>)3JKZR~L(Y)X+yOS1bC9@%ObjCQCad=fi{a=iZ zDku(%+-iM*sbrBkHFZDLNRSoyd-u<1PhE?bd=1}Qrs3sEz-H|tL3jGACDppf>MSdM z{@M=TS2)xXpq<4hU`%;)Mq{95}T(gY@o+sal zlxf3X@&8|JSLE&P>soAzVNpc?5n=j}r9?86l6fhee_GF=5B%c?zMsi#ha9I!o#%9) zU;a~GmF~3+S*!>@5{>#$S{R_rYsEx2lsYT}S_>!rY8#1;?^7q^wFmC1czZQ7m}2J$ zT@m;oEHY1csAx&Ls{t84LTq)e#W$RU+uL-PM`R`?7BCL-O^u8{?2ysNv!-4xq9R?* zx{Q*rv7^WuzCEC8gzRIT=hAC_uBQU7rx}Koqp4H^041iDajR$7=O8z-p1TZUV(tZ= zMxujeCxgvRsa2~IO>}8g%w}R=KA8pb6=A$o6tFiowS77F@oGwpJ!e*Is<&Rtw*9lF z8W-+P5Uqk7hwb<2`0r2GdXQ9LQB@uCVgder6e8oRk~%tQ)rd;Dw|;Wvb-6Eg$69tBOP678vJ$&8ZxmT-nnb47@535Ic@*01?E&l+}XO(ZD(Iz zna%eUb?}*P{JTMC{lhPX=mvtz*$+X5?+Gsbd8gEHu6S^0lKy7jWMEw#5S>0AViMeP z!?`Zeh3uK(Tvwk+FjtdekNSr7d@tgc&pVh{u=0maN+Yv|s3P&iI^SB#>x*MM#RfSk z+sWs>B^|Zc%QKk5#<{*i&Mc+0?Zji^8Y{yyP^IeL@6tOpfn#SA5hEFz2Af_MtL}xVvK?ZjH?D++qmG{ypGwf|n=Tsr zt8+P|4W7*JD4)v&HxA&lScJI7LnBarv*uB4={UaNDNJ$CuZgy7c-P*|+Y!i^Ap-WT zh_*JbMoYix96pC(F?gDKafHYL_d#`el04(tRR+#U~7UCBOn zx=^lPZ#+?pG>R`~7)@8#)@ghiR~TVUdZJ2$4z3?A;4!AiW-{=r{30^vv%rnY(p4AM z!)U^2Ee*sY0Yd>4OGu#Xhb`&f6|zjDgPd&0W3>*<7pX{&i`D8Pyc2M|mLn3*Y4A{< z?`en+(W238f%J=H1^rY`(Lwtv&C$w;Lb^1Hy6p{Y=j^0k-&Ule(S)Otrr$3h8P)J- zYOxf`$|S6c(qK~tb`PB=17lhaQl;g%Y&p3t^A10Udi?xdo*yNSiw`0OT{DVIga%6f9 z8%9iyKOD`c&pdi8==wEhcLkCM@%lNWVj243`iZNiAsT}F>UMwvDrc%*V}nh09+w5fgTD@a%=A@wQrWIsW-jz?dlbYSp+LINY9fy;c%4 z!5&qedP;EFRQjkoU*T{4@z;Blv>nWyp1Ne z4bvwEB=I1g!N6LJt}d2AEynMs$Bzq{fmo3*~hVeBVdhbNts%21T;+bCFZ(MIMx z$^qpzRUs*j)eej;Z1|myD`5UFnbS?@#V736HgzXqUN39$R-2op{XE zPFG1soI3=nr8pu{JbQ$CVGiJYqS{dpl5akRoW=LzRr+LO)p8N9#7+2y89R+U>o&zd z7@`oQRnh|ElRK1oKMPK*wrglE4gVIuu~DoKi)4?Q#UgzPXCJJ4+0G><-0}k3!IQyK zl}6v$oJDe}5qYNiXre*hEK;_4K?-uxIUGII<+b=BFUOSnwa2b8`r-faz`By{?_6Q`u<&h4e-dJWZTe81gZsK_ zI-p4FxvHtR5EnTT!_Tl}?sXz7{n8D@3y$jrr#c>>s%8ys|N3AJkJ`937IQH*_$qFd z3U{7->BO__@M#gvC`;l~8nGG#$@dlQ!pFa5}<&aZK3HsgPhkaRPT^*h-+I5us) zKL}+;J)=q6$ojSQ8V6y`IMXaA)5w{7!O~Q(*y$y^T1(mI{({yq}xA&gPFx{T%1s081!OUm&bc%}5@b-NrwIsnE zo0d|mCwWgX^R5qvLlIRt1YX|j*rYaWgSs!;U(4NCWAq-9^r36WP{S{lVk}MCjOAey zl-XNJyude0^`4okUz5~8cI1N|Ro_8yWe-{JoAdoUxzr-$Z7=R^vQRyxsrxNs*=2xE zD061=_U)sLwK;t8t^4hJ`KA(|w7-2d6iHftUdQCxyx=kQWIsNls^$r0M#hhvz>Qnu zL(T*qh-nlDr_p&<;@H^tnj3P1Y`8f{S16$FXB60+wrA0A#Lk@qb57c?!=z?rfb7K&+E&rSa}j3->VcCSbbr zarYcotV@!1!a7w~s@d@ZnA?7KG-X9{ zvr3muEmqHPFF!y%TO#I)DUmktZ;NZ*^wknCcg|SkF-gw~y!wP=_YA8JB|&f*+g_c< z9tEAx;IWSv^v%Ryeu4GK5dJ@IX(LV8!KJjp$6ppVd&dKD8Orx7D*@_Nfs_D;UL92=Vfj!BQj7eia zt1bpjaAFjK^=TVy$lF>H>Hnfq6H?)8-r*%m`0go@X#%h0aE~1sD)K=^u)9?#v42L9 zpGZ6Z&|{d(oh>z->(^9UE;!eUXgvRx9|33bw7o_2TQI(*6MGpU;PR9=S5uvL;^a0a zrocIR6HuSbX=2OkpxNVve{K79>L7@rxZS9*&ESFqI`ci}YhO&NeZ%i<8{Q>yNFD|S zWZT1<{31o1V905XgGshESZD;F#r?F$DSk%?@4v%`|q3A9tFwv?e%X>`sHM{tV9W8XZ6>@!u;-)o=jZ!D*O%%&wU9p&>sn@s%D}4sp?Bi~ z27zoB<@mQ?6e$}lYb-Bima`$38;HY!o$xMKSvYf;kAIMJ?risdN+oH=-*#8l$1)q# z5Yejkp}T?vOXW{~Z^|wwC(1{7J4FVD)OSqZBRIA3b0|6WiN?GJrch6fLp1LmOn7M# zpJD>m?SJ-i7-s{9Ea2J;ZESiOfSJ-V!SXO;ji;Lo{~h7{A@;W@hxbZyNBi#*~-N-lGz9Tb*8e58@8OyPQJdKewpRp>Wk6aGCp8xq`Op3+}p#g zLa&Gxw|&gF%+LSQ3o74DEsEsvcuI7@^7*|6NlV9DD|vlo4_tYY?T0FzE^Wf8d|ctE zbL#YE$hBLonusNwVk=8;sm>xYR|2vZIskx8B{vv5*3NVg@)5IJM`$d8T9vIEQ}2@A zB_YmA=3II0KkU3SrSW>F*_#Zat(X5vV#TG6Sju#z4% z7<^EpdzsJMy)`jg?qS*_;InyAjWE!TKy6v!TzC{)OC4;B2+|t&p>uY(+piOG9`enI z*6Vi5J091`Gm*C;I;Ii>lmBLv$D3`{#|nmcy5yA3*g*h|%i zIk@-Gm;#py%LY?U1m~?dG<9fZ{?AJS7RIe&ZsUzd-g5yKTT@b}2lp!Q-K}(qDXZFW z$3GBt7mQetv1lwuwfqjK_1KH)@{wm+kyDFZf(fxrkQyqhC9-|iZSVDb_{ilN%oDjw zasC<)h3xQrYnQasqw)a-Gjgev1Ivz27%Nn zsLsQSIWJ+Hs{@VOQC^4_tq(>Gcn{KRC3I3 z*+Dm^N5UFB17yPN-Gl!`=e%SIub)xPh=peFZZifR*HBHFxKGyXgrl}L11IgR#fat8 zrRB=gx&F@!aO%+ZQQ5g7Npbh>8lD&0J$+vZ?wq9@*uX=${q_DHgI>jc5!W)QBE>2C zTQYA)?*phu ze40begL!1bPK=^*H$_+nocZL>=Qwhh*8R$d{2Y)9bNnU-Tjr#TTqdm&Z7zkS?*4vb+sku#;2KV)icN;g2&j%sDixDkYI7u^>-v8~ou`+bcvZp@s{A=nz}aLw;M^XC9JQWft& z+y-~$4}DbV{3YB-k<$Z9VjLgR1An;2&uLOm>zSeiR$zBiI7LStNpomvR7G#d4~gz7 zitL)DHC49dA};aJmOIbJ?^PkCIJm>~GA(A=3*3L_Hnb*@H&_vUZkimRM=z7&ucS)` z3`mom{~?O1a<<1FXt__c7fE@#trzw&bJO~*l7E{yS+Dx);&jZL5u~;EdoS;=u> z^8T{%!LPYYN(MR>jOEje+J;D}RcY#6Yqu=Y7qzt35hrcGPWV2TKAv)0_Hs4aypY^c z4c;}+-Zcul%zYxlfgjB*+seK}CR2P}o<8T_MdXB%Bi|NiR>E)HQVcrcmp$&RlxB)%}6sTjHZsB{1O z2#e2D7U1Rxi@-%Mrtl(U=d7`JJMgn13ZODUiM>Oxn)bT#ZqIUG$P!PSR$QijR6a6a z09oJ$qJfO|#+H>5DW)#7pi!A`{%Il?wDH3~XzfTWW{hWJcGWA={gT;s9SDUO%l-Kd z&II49^LY}{HI}8n2~#13a^R~Hl@~ZAJDrqwI#rMF`CjOhYnHFstQIjzfl5+wJN%mn z<wiVw_$5lw+1MijvEZ>oguZGZqo^ zvd`d6`i)Cz>sD5%Xx~(m{ks$g?UO5)>nAsm{YPE=v{}r22En1(`CL_<#AoCZDgc@q zG;Y2<^#wD~q}JuWz|i~a$x|Ej_?sDL)&qN$#?4Jm-rx?dW5;zQk*NQT>Cf|q&%{02fS zopTDRyo`8JP6?9V$~POQuWBTERYNrmM;=~AefgBbY_#o@urryar|q0hlN)ra$dz$w zsk8j7v0C5%niSGIcb>FJKAMAsD_Sz!^%r6lzKTDoA9R%)0pAU{b5r$-Ug;>tJN6P= zu3S+IYD0NZ-hK46K|IBt?}9>f%16_4oTCcqRsG6Vhx9Y^K@}luzAw+o*tug=9*>udBMlx+4bdzQ)8nH$Kr2jbTbHzruS8lrqZ{2D)(YAGI_j>Jx5F^f zDSui1!IXLY4?pF0K(vMJVkxJTPLv${>T31LXtxc{aHybBadvno`1NpQG0!w-dj}sB zuyGFskyp5ecJR&GByf|DDs`1BF<=}wLom25mjmjTC$J(OD@8xcJ$k{0ff14V=S~|| z9|mi}nNqaGEFT*`>nSVsgU<;l_6ZVwcbUdzF|(N*6*sT6L_8**qSg_DPv~W&vDbHLMCu2R19qgf+IDC$#TZ9Ww3_&_dQJ0`d;K8_eWe(_Vx;CG%lVvGDn? zZ7uXy+1BGCxZIHRBnDxqtJvR_cW|Fu((n6xK|uZa4`0w2~q{ z1ZdDclEFl3K|+a;`uj$j z@1m@Ny;v@C&Br_~U5s`*z@bFlCRo*+$kR3z1!`k14D8A^?h*STLXHVB1MRMFS3!$_ z2KIbww^H!lLiwAuXV3wP2uZd?K2r$IoTvCmH`)3X%9PUB+}H}U`4Y*H5%2GJLs$$A z%0qU<(5oE94Wq6fXo-71m-N0AO%=@Ab)a{7A75jliaP^U1Ds{7a3=Bp8ss%;LE?g) zRc;_+h8-#{d-w>OL`Mi>hhpV1`8VW`j<_Doc^f8!$@KlK*x|a=%N?3~+T8?d5QQhmIV^2AsWn9?M$KQ0)#rsR}3acT+WxWgM73gQ0#b+9+koM@{iQ~KWqXZxOWMj+)6&*u_7LBQnU2|C1{#qROgG5h2?W5 zb8dnAKa?UF_Nk2!(~fp>YHQbthlPbQ!%MkLMtRd&9)kYd`8 zWI=|s%#29{US(5G%(ikG<-J zpiNxwo#@tAi9N)V(&*BoVH};5FyX^aD(?z=4+*ouMgQhYL@2`t2MQrlDyf~I?9oqE zOUf&IYE3zlZZz_bEVpxC4Ow&tqq*suY@$jFLdd@@y6@e$9Hes#Y|M+{u)-3|shW;D z-}U{>aGl8O<{-A>lAZX4pD(oBo8k9Z*RFjdp=Sl!lmg{0hNwKd!kHeFS-M&d6}(G{ z5fTFtg@UjVN5A}9olAq21kN?vys)RuvUSKR;li6f_`DveGZ1f^*KIO|11eWL)1jb2 zYB^QuX<{=vin#F^LrL>6x~mH|=bAU=cF*4x)wyl4n)%hrgW`7_RzisT*$TO4SFB~l zPnm)3sS*9VugCds+@ZfP~+F{9Zh2=0Ng7aB14O*WUOf~htN=zgJuIL@g*grKp zpu#rM?3o%J4D)>xik{BP&$SKCWuyj^?afR=mZQynUw1L_$=~Pu_FFA;LChRB7U_Tf zite<E8XhU=FJ9S%S@rQfiIXz*?5R{lJZNRUx!`;sEZaE#o5t*L5Qsz+%#qs`I zPye09lc>58jua6Q_j{H2-b!tawg*}U3d5pJhb=3)`4PV{O0mv-?lrNY)^#0WHjENc zvx1TZ?C2dTm|vEGwFDUlr5fN|$#gd;Tgg92_5MH)i*(e4Nr4?(yTXlkw`rh;nvI}^ z1ZT}@(q>=Dox=Apu{g9)x;it2wtCxkz(e7(n^RHSNdC^cMGL6~hwK+jwS!FplhJ#R z2_hSEg(7mit;(YCX#C$`!S@nZs76k|RCzMLO}?!&zkgi(On`Rn{>gfg9L{y-3V*Ip zXu$GHmHlA8Fx`~TuFgGt`AW;%hLWUEOiDFsz;xi#bLcruj~+kz+zl%EUrV7xN&~|7 z$eg6!`w9%ob%Jf-2JWwf zJaOI_zSsU_!XqK-I%R=H!!&w0v)m_cgiASJ`y?-0ux_et{(#qf-{@C0mBwQIs8`Dole6QzAWXBwpVyx z!En4MHnir3$rMCpUh1>*sZIvtTKz$r_Je|$R0B}44UTSMb_ybQROUZr7wV3gE>yyolXHTkL>&2jIcv+r*-t@6I z_m9k!SjPYe=(k5SE^dV4Z?2t$zkc}BQku(7YkzNyibOq6PA97IeS%I67YT9y1ze^Cc#El;H-qXiOKc)== zy2hGzOa&rl`b6E>rV0D^vBGTI z)I?Vh+a+#fD%H@rKBRx?YKodVg-Rl?F-|TtVVpfB+nQ*|l^`@E!HX(0@xb|w7@?F| zRB=|kKQw`&m>`~98BT7F;|nXg=!aQT$G6P-mBjx`yGJ<;`O4pW{=~`FavRD%HRZ!Z zKC`>2CfRfpgk-o!{#9n7nZWINKmX6(O-Hq3MK-NpPVqS_8yHC$Lg5)YVOlK4eJ?iB zn08-3`|`&llBGOvkVi;#+r$>wCI{{-t%wXhnLItaF@Z*<;mp_p6!t`WE$*RVx+CT z2O9y1B%O;VYJFkF7Ra{Jp679Pg3V?1_v-u_)W~BUh0TUm@}s+WWttXehd<3VY=*Mq zCv9Fk+t8oN(V#{@b2IYRjNyS&Nm_jxgUBt%d8%ox;qzb5M-Xfa-KOm@xJ21 zT?jCrar#%~Uh8Llal{Qeb_{R@cz7S&?+7MR7PoJSmHqKX5`sg9o$1e{%KqBAd-78I znDKYmAhF5Jslf5K{o<@oxmB@1R>vCX(-Hm%KF}Y0dvMbkVxECn2WM`inha)eHKd;p z`>G7$l7UGFgW1eCw(Qp)aC-#{5krKu^BC7oDK9Ma(Uz)}jK!?% zi9GG$v&9W8v9Ay&5~nva;u6zQ`iLO%mT64y(vIjnz9_xOu1DE{oRSL1SkD`4IElz~ zGwm&z6EdpcMF@G%*fVRj2KEtmVqdNz?8qxk!lmta=7S8O{@G{7T{QDwzoD6$%CvbI zh`^hxxmod-tkvL3KCxd8O?8j<5W18bIaz(%nMs*VF zA3>!4HHC`}^^7a-cx?CwK47VB^o|(XCFd<60z+alG4M5eE0#hE`xSL7`N+jnEwcy% zj-us5Q?LR$!$1}&ZM6EI4!8-IxW6k7W!l9(e&1qC!?hD(6$uTafSfaC!#pqsASol? zH(Pxu&)CcocG*)rgNLpj;5&G@TKeZ;dE@ch)@9;D{H?Lun@9iWLT@HAnIe%Kl|+f5)ceZwoFTL?>L2AoWi8@M(hH7-^AGXZ4a`$h`XF0U+Hn + +!!! note + + The planner can be enabled or disabled using the `frenet.enable` flag. + +!!! note + + Since only a segment of the target lane is used as input to generate the lane change path, the end pose of the lane change segment may not smoothly connect to the target lane centerline. To address this, increase the value of `frenet.th_curvature_smoothing` to improve the smoothness. + +!!! note + + The yaw difference threshold (`frenet.th_yaw_diff`) limits the maximum curvature difference between the end of the prepare segment and the lane change segment. This threshold might prevent the generation of a lane change path when the lane curvature is high. In such cases, you can increase the frenet.th_yaw_diff value. However, note that if the prepare path was initially shifted by other modules, the resultant steering may not be continuous. + +#### Candidate Path Validity + +It is a prerequisite, that both prepare length and lane-changing length are valid, such that: + +1. The prepare segment length is greater than the distance from ego to target lane start. +2. The prepare segment length is smaller than the distance from ego to terminal start. +3. The lane-changing distance is smaller than the remaining distance after prepare segment to terminal end. +4. The lane-changing distance is smaller than the remaining distance after prepare segment to the next regulatory element. + +If so, a candidate path is considered valid if: + +1. The lane changing start point (end of prepare segment) is valid; it is within the target lane neighbor's polygon. +2. The distance from ego to the end of the current lanes is sufficient to perform a single lane change. +3. The distance from ego to the goal along the current lanes is adequate to complete multiple lane changes. +4. The distance from ego to the end of the target lanes is adequate for completing multiple lane changes. + +The following flow chart illustrates the validity check. + +```plantuml +@startuml +skinparam defaultTextAlignment center +skinparam backgroundColor #White + +start +if (Check if start point is valid by check if it is covered by neighbour lanes polygon) then (not covered) + #LightPink:Reject path; + stop +else (covered) +endif + +:Calculate total length and goal related distances; +if (total lane change length considering single lane change > distance from current pose to end of current lanes) then (yes) + #LightPink:Reject path; + stop +else (no) +endif + +if (goal is in current lanes) then (yes) + if (total lane change length considering multiple lane changes > distance from ego to goal along current lanes) then (yes) + #LightPink:Reject path; + stop + else (no) + endif +else (no) +endif + +if (target lanes is empty) then (yes) + #LightPink:Reject path; + stop +else (no) +endif +if (total lane change length considering multiple lane changes > distance from ego to the end of target lanes) then (yes) + #LightPink:Reject path; + stop +else (no) +endif + +#LightGreen:Valid Candidate Path; +stop + +@enduml +``` + +!!! warning + + A valid path does NOT mean that the path is safe, however it will be available as a candidate path and can be force approved by operator. A path needs to be both valid AND safe to be automatically approved. + +### Lane Change Completion Checks + +To determine if the ego vehicle has successfully changed lanes, one of two criteria must be met: either the longitudinal or the lateral criteria. + +For the longitudinal criteria, the ego vehicle must pass the lane-changing end pose and be within the `finish_judge_buffer` distance from it. The module then checks if the ego vehicle is in the target lane. If true, the module returns success. This check ensures that the planner manager updates the root lanelet correctly based on the ego vehicle's current pose. Without this check, if the ego vehicle is changing lanes while avoiding an obstacle and its current pose is in the original lane, the planner manager might set the root lanelet as the original lane. This would force the ego vehicle to perform the lane change again. With the target lane check, the ego vehicle is confirmed to be in the target lane, and the planner manager can correctly update the root lanelets. + +If the longitudinal criteria are not met, the module evaluates the lateral criteria. For the lateral criteria, the ego vehicle must be within `finish_judge_lateral_threshold` distance from the target lane's centerline, and the angle deviation must be within `finish_judge_lateral_angle_deviation` degrees. The angle deviation check ensures there is no sudden steering. If the angle deviation is set too high, the ego vehicle's orientation could deviate significantly from the centerline, causing the trajectory follower to aggressively correct the steering to return to the centerline. Keeping the angle deviation value as small as possible avoids this issue. + +The process of determining lane change completion is shown in the following diagram. + +```plantuml +@startuml +skinparam defaultTextAlignment center +skinparam backgroundColor #WHITE + +title Lane change completion judge + +start + +:Calculate distance from current ego pose to lane change end pose; + +if (Is ego velocity < 1.0?) then (YES) + :Set finish_judge_buffer to 0.0; +else (NO) + :Set finish_judge_buffer to lane_change_finish_judge_buffer; +endif + +if (ego has passed the end_pose and ego is finish_judge_buffer meters away from end_pose?) then (YES) + if (Current ego pose is in target lanes' polygon?) then (YES) + :Lane change is completed; + stop + else (NO) +:Lane change is NOT completed; +stop + endif +else (NO) +endif + +if (ego's yaw deviation to centerline exceeds finish_judge_lateral_angle_deviation?) then (YES) + :Lane change is NOT completed; + stop +else (NO) + :Calculate distance to the target lanes' centerline; + if (abs(distance to the target lanes' centerline) is less than finish_judge_lateral_threshold?) then (YES) + :Lane change is completed; + stop + else (NO) + :Lane change is NOT completed; + stop + endif +endif + +@enduml +``` + +### Safety Checks + +A candidate path needs to be both valid and safe for it to be executed. After generating a candidate path and validating it, the path will be checked against surrounding objects to ensure its safety. However the impacts of an object depends on its categorization, therefore it is necessary to filter the predicted objects before performing the safety checks. + #### Object filtering -Before performing safety checks, predicted objects are categorized based on their current pose and behavior at the time. These categories help determine how each object impacts the lane change process and guide the safety evaluation. +In order to perform safety checks on the sampled candidate paths, it is needed to categorize the predicted objects based on their current pose and behavior at the time. These categories help determine how each object impacts the lane change process and guide the safety evaluation. The predicted objects are divided into four main categories: @@ -407,77 +768,26 @@ endif -#### Candidate Path's validity check +#### Candidate Path Safety -A candidate path is considered valid if it meets the following criteria: +A candidate path is considered safe if: -1. The distance from the ego vehicle's current position to the end of the current lanes is sufficient to perform a single lane change. -2. The distance from the ego vehicle's current position to the goal along the current lanes is adequate to complete multiple lane changes. -3. The distance from the ego vehicle's current position to the end of the target lanes is adequate for completing multiple lane changes. -4. The distance from the ego vehicle's current position to the next regulatory element is adequate to perform a single lane change. -5. The lane change can be completed after passing a parked vehicle. -6. The lane change is deemed safe to execute. +1. There are no overtaking objects when the ego vehicle exits the turn-direction lane. (see [Overtaking Object Check](#overtaking-object-check)) +2. There is no parked vehicle along the target lane ahead of ego (see [Delay Lane Change Check](#delay-lane-change-check)) +3. The path does NOT cause ego footprint to exceed the target lane opposite boundary +4. The path passes the collision check (See [Collision Check](#collision-check)) -The following flow chart illustrates the validity check. +#### Overtaking Object Check -```plantuml -@startuml -skinparam defaultTextAlignment center -skinparam backgroundColor #White - -start -if (Check if start point is valid by check if it is covered by neighbour lanes polygon) then (not covered) - #LightPink:Reject path; - stop -else (covered) -endif +When ego is exiting an intersection on a turning lane, there is a possibility that a rear vehicle will attempt to overtake the ego vehicle. Which can be dangerous if ego is also trying to perform a lane change. Therefore lane change module will adopt a more conservative behavior in such situation. -group check for distance #LightYellow - :Calculate total length and goal related distances; - if (total lane change length considering single lane change > distance from current pose to end of current lanes) then (yes) - #LightPink:Reject path; - stop - else (no) - endif - - if (goal is in current lanes) then (yes) - if (total lane change length considering multiple lane changes > distance from ego to goal along current lanes) then (yes) - #LightPink:Reject path; - stop - else (no) - endif - else (no) - endif - - if (target lanes is empty) then (yes) - #LightPink:Reject path; - stop - else (no) - endif - if (total lane change length considering multiple lane changes > distance from ego to the end of target lanes) then (yes) - #LightPink:Reject path; - stop - else (no) - endif -end group - -if (ego is not stuck but parked vehicle exists in target lane) then (yes) - #LightPink:Reject path; - stop -else (no) -endif +If the ego vehicle is currently within an intersection on a turning lane, as shown in the figure below, the generated candidate paths will be marked as unsafe. -if (is safe to perform lane change) then (yes) - #Cyan:Return candidate path list; - stop -else (no) - #LightPink:Reject path; -endif +![within intersection turn lane](./images/lane_change-intersection_turn_lane_1.png) -stop +Additionally, if the ego vehicle has just exited the turn lane of an intersection and its distance from the intersection is within the `backward_length_from_intersection`, as shown in the figure below, the generated candidate paths will also be marked as unsafe. -@enduml -``` +![after intersection turn lane](./images/lane_change-intersection_turn_lane_2.png) #### Delay Lane Change Check @@ -489,6 +799,7 @@ To do so, all static objects ahead of ego along the target lane are checked in o 3. The distance from object to next object is sufficient to perform lane change If the parameter `check_only_parked_vehicle` is set to `true`, the check will only consider objects which are determined as parked. +More details on parked vehicle detection can be found in [documentation for avoidance module](../autoware_behavior_path_static_obstacle_avoidance_module/README.md). The following flow chart illustrates the delay lane change check. @@ -531,49 +842,44 @@ stop @enduml ``` -The following figures demonstrate different situations under which will or will not be triggered: +The following figures demonstrate different situations under which delay action will or won't be triggered. In each figure the target lane vehicles are assumed to be stopped. The target lane vehicle responsible for triggering the delay action is marked with blue color. -1. Delay lane change will be triggered as there is sufficient distance ahead. - ![delay lane change 1](./images/delay_lane_change_1.drawio.svg) -2. Delay lane change will NOT be triggered as there is no sufficient distance ahead - ![delay lane change 2](./images/delay_lane_change_2.drawio.svg) -3. Delay lane change will be triggered by fist NPC as there is sufficient distance ahead. - ![delay lane change 3](./images/delay_lane_change_3.drawio.svg) -4. Delay lane change will be triggered by second NPC as there is sufficient distance ahead - ![delay lane change 4](./images/delay_lane_change_4.drawio.svg) -5. Delay lane change will NOT be triggered as there is no sufficient distance ahead. - ![delay lane change 5](./images/delay_lane_change_5.drawio.svg) +- Delay lane change will be triggered as there is sufficient distance ahead. -#### Candidate Path's Safety check +![delay lane change 1](./images/delay_lane_change_1.drawio.svg) -See [safety check utils explanation](../autoware_behavior_path_planner_common/docs/behavior_path_planner_safety_check.md) +- Delay lane change will NOT be triggered as there is no sufficient distance ahead. -#### Objects selection and classification +![delay lane change 2](./images/delay_lane_change_2.drawio.svg) -First, we divide the target objects into obstacles in the target lane, obstacles in the current lane, and obstacles in other lanes. Target lane indicates the lane that the ego vehicle is going to reach after the lane change and current lane mean the current lane where the ego vehicle is following before the lane change. Other lanes are lanes that do not belong to the target and current lanes. The following picture describes objects on each lane. Note that users can remove objects either on current and other lanes from safety check by changing the flag, which are `check_objects_on_current_lanes` and `check_objects_on_other_lanes`. +- Delay lane change will be triggered by fist NPC as there is sufficient distance ahead. -Furthermore, to change lanes behind a vehicle waiting at a traffic light, we skip the safety check for the stopping vehicles near the traffic light. The explanation for parked car detection is written in [documentation for avoidance module](../autoware_behavior_path_static_obstacle_avoidance_module/README.md). +![delay lane change 3](./images/delay_lane_change_3.drawio.svg) -##### Collision check in prepare phase +- Delay lane change will be triggered by second NPC as there is sufficient distance ahead. -The ego vehicle may need to secure ample inter-vehicle distance ahead of the target vehicle before attempting a lane change. The flag `enable_collision_check_at_prepare_phase` can be enabled to gain this behavior. The following image illustrates the differences between the `false` and `true` cases. +![delay lane change 4](./images/delay_lane_change_4.drawio.svg) -![enable collision check at prepare phase](./images/lane_change-enable_collision_check_at_prepare_phase.png) +- Delay lane change will NOT be triggered as there is no sufficient distance ahead. -#### If the lane is blocked and multiple lane changes +![delay lane change 5](./images/delay_lane_change_5.drawio.svg) -When driving on the public road with other vehicles, there exist scenarios where lane changes cannot be executed. Suppose the candidate path is evaluated as unsafe, for example, due to incoming vehicles in the adjacent lane. In that case, the ego vehicle can't change lanes, and it is impossible to reach the goal. Therefore, the ego vehicle must stop earlier at a certain distance and wait for the adjacent lane to be evaluated as safe. The minimum stopping distance can be computed from shift length and minimum lane changing velocity. +#### Collision Check -```C++ -lane_changing_time = f(shift_length, lat_acceleration, lat_jerk) -minimum_lane_change_distance = minimum_prepare_length + minimum_lane_changing_velocity * lane_changing_time + lane_change_finish_judge_buffer -``` +To ensure the safety of the lane change candidate path an RSS check is performed against the surrounding predicted objects. +More details on the collision check implementation can be found in [safety check utils explanation](../autoware_behavior_path_planner_common/docs/behavior_path_planner_safety_check.md) -The following figure illustrates when the lane is blocked in multiple lane changes cases. +##### Collision Check In Prepare Phase -![multiple-lane-changes](./images/lane_change-when_cannot_change_lanes.png) +The collision check can be applied to the lane changing section only or to the entire candidate path by enabling the flag `enable_collision_check_at_prepare_phase`. Enabling this flag ensures that the ego vehicle secures enough inter-vehicle distance ahead of target lane rear vehicle before attempting a lane change. The following image illustrates the differences between the `false` and `true` cases. + +![enable collision check at prepare phase](./images/lane_change-enable_collision_check_at_prepare_phase.png) + +!!! note -### Stopping behavior + When ego vehicles is stuck, i.e it is stopped, and there is an obstacle in front or is at end of current lane. Then the safety check for lane change is relaxed compared to normal times. + +### Stopping Behavior The stopping behavior of the ego vehicle is determined based on various factors, such as the number of lane changes required, the presence of obstacles, and the position of blocking objects in relation to the lane change plan. The objective is to choose a suitable stopping point that allows for a safe and effective lane change while adapting to different traffic scenarios. @@ -673,148 +979,32 @@ If the target lane for the lane change is far away and not next to the current l ![stop_not_at_terminal](./images/lane_change-stop_not_at_terminal.drawio.svg) -### Lane Change When Stuck - -The ego vehicle is considered stuck if it is stopped and meets any of the following conditions: - -- There is an obstacle in front of the current lane -- The ego vehicle is at the end of the current lane - -In this case, the safety check for lane change is relaxed compared to normal times. -Please refer to the 'stuck' section under the 'Collision checks during lane change' for more details. -The function to stop by keeping a margin against forward obstacle in the previous section is being performed to achieve this feature. - -### Lane change regulations +#### When target lane is blocked and multiple lane changes -If you want to regulate lane change on crosswalks, intersections, or traffic lights, the lane change module is disabled near any of them. -To regulate lane change on crosswalks, intersections, or traffic lights, set `regulation.crosswalk`, `regulation.intersection` or `regulation.traffic_light` to `true`. -If the ego vehicle gets stuck, to avoid stuck, it enables lane change in crosswalk/intersection. -If the ego vehicle stops more than `stuck_detection.stop_time` seconds, it is regarded as a stuck. -If the ego vehicle velocity is smaller than `stuck_detection.velocity`, it is regarded as stopping. +When ego vehicle needs to perform multiple lane changes to reach the `preferred_lane`, and the `target_lane` is blocked, for example, due to incoming vehicles, the ego vehicle must stop at a sufficient distance from the lane end and wait for the `target_lane` to clear. The minimum stopping distance can be computed from shift length and minimum lane changing velocity. -## Lane change completion checks - -To determine if the ego vehicle has successfully changed lanes, one of two criteria must be met: either the longitudinal or the lateral criteria. - -For the longitudinal criteria, the ego vehicle must pass the lane-changing end pose and be within the `finish_judge_buffer` distance from it. The module then checks if the ego vehicle is in the target lane. If true, the module returns success. This check ensures that the planner manager updates the root lanelet correctly based on the ego vehicle's current pose. Without this check, if the ego vehicle is changing lanes while avoiding an obstacle and its current pose is in the original lane, the planner manager might set the root lanelet as the original lane. This would force the ego vehicle to perform the lane change again. With the target lane check, the ego vehicle is confirmed to be in the target lane, and the planner manager can correctly update the root lanelets. - -If the longitudinal criteria are not met, the module evaluates the lateral criteria. For the lateral criteria, the ego vehicle must be within `finish_judge_lateral_threshold` distance from the target lane's centerline, and the angle deviation must be within `finish_judge_lateral_angle_deviation` degrees. The angle deviation check ensures there is no sudden steering. If the angle deviation is set too high, the ego vehicle's orientation could deviate significantly from the centerline, causing the trajectory follower to aggressively correct the steering to return to the centerline. Keeping the angle deviation value as small as possible avoids this issue. - -The process of determining lane change completion is shown in the following diagram. - -```plantuml -@startuml -skinparam defaultTextAlignment center -skinparam backgroundColor #WHITE - -title Lane change completion judge - -start - -:Calculate distance from current ego pose to lane change end pose; - -if (Is ego velocity < 1.0?) then (YES) - :Set finish_judge_buffer to 0.0; -else (NO) - :Set finish_judge_buffer to lane_change_finish_judge_buffer; -endif - -if (ego has passed the end_pose and ego is finish_judge_buffer meters away from end_pose?) then (YES) - if (Current ego pose is in target lanes' polygon?) then (YES) - :Lane change is completed; - stop - else (NO) -:Lane change is NOT completed; -stop - endif -else (NO) -endif - -if (ego's yaw deviation to centerline exceeds finish_judge_lateral_angle_deviation?) then (YES) - :Lane change is NOT completed; - stop -else (NO) - :Calculate distance to the target lanes' centerline; - if (abs(distance to the target lanes' centerline) is less than finish_judge_lateral_threshold?) then (YES) - :Lane change is completed; - stop - else (NO) - :Lane change is NOT completed; - stop - endif -endif - -@enduml +```C++ +lane_changing_time = f(shift_length, lat_acceleration, lat_jerk) +minimum_lane_change_distance = minimum_prepare_length + minimum_lane_changing_velocity * lane_changing_time + lane_change_finish_judge_buffer ``` -## Terminal Lane Change Path - -Depending on the space configuration around the Ego vehicle, it is possible that a valid LC path cannot be generated. If that happens, then Ego will get stuck at `terminal_start` and not be able to proceed. Therefore we introduced the terminal LC path feature; when ego gets near to the terminal point (dist to `terminal_start` is less than the maximum lane change length) a terminal lane changing path will be computed starting from the terminal start point on the current lane and connects to the target lane. The terminal path only needs to be computed once in each execution of LC module. If no valid candidate paths are found in the path generation process, then the terminal path will be used as a fallback candidate path, the safety of the terminal path is not ensured and therefore it can only be force approved. The following images illustrate the expected behavior without and with the terminal path feature respectively: - -![no terminal path](./images/lane_change-no_terminal_path.png) - -![terminal path](./images/lane_change-terminal_path.png) - -Additionally if terminal path feature is enabled and path is computed, stop point placement can be configured to be at the edge of the current lane instead of at the `terminal_start` position, as indicated by the dashed red line in the image above. - -## Generating Path Using Frenet Planner - -!!! warning - - Generating path using Frenet planner applies only when ego is near terminal start - -If the ego vehicle is far from the terminal, the lane change module defaults to using the [path shifter](https://autowarefoundation.github.io/autoware.universe/main/planning/behavior_path_planner/autoware_behavior_path_planner_common/docs/behavior_path_planner_path_generation_design/). This ensures that the lane change is completed while the target lane remains a neighbor of the current lane. However, this approach may result in high curvature paths near the terminal, potentially causing long vehicles to deviate from the lane. - -To address this, the lane change module provides an option to choose between the path shifter and the [Frenet planner](https://autowarefoundation.github.io/autoware.universe/main/planning/sampling_based_planner/autoware_frenet_planner/). The Frenet planner allows for some flexibility in the lane change endpoint, extending the lane changing end point slightly beyond the current lane's neighbors. - -The following table provides comparisons between the planners - -
- - - - - - - - - - - - - - - - - -
With Path ShifterWith Frenet Planner
Path shifter result at straight laneletsFrenet planner result at straight lanelets
Path shifter result at branching laneletsFrenet planner result at branching lanelets
Path shifter result at curved laneletsFrenet planner result at curved lanelets
-
- -!!! note - - The planner can be enabled or disabled using the `frenet.enable` flag. - -!!! note - - Since only a segment of the target lane is used as input to generate the lane change path, the end pose of the lane change segment may not smoothly connect to the target lane centerline. To address this, increase the value of `frenet.th_curvature_smoothing` to improve the smoothness. - -!!! note +The following figure illustrates when the lane is blocked in multiple lane changes cases. - The yaw difference threshold (`frenet.th_yaw_diff`) limits the maximum curvature difference between the end of the prepare segment and the lane change segment. This threshold might prevent the generation of a lane change path when the lane curvature is high. In such cases, you can increase the frenet.th_yaw_diff value. However, note that if the prepare path was initially shifted by other modules, the resultant steering may not be continuous. +![multiple-lane-changes](./images/lane_change-when_cannot_change_lanes.png) -## Aborting a Previously Approved Lane Change +### Aborting Lane Change Once the lane change path is approved, there are several situations where we may need to abort the maneuver. The abort process is triggered when any of the following conditions is met 1. The ego vehicle is near a traffic light, crosswalk, or intersection, and it is possible to complete the lane change after the ego vehicle passes these areas. 2. The target object list is updated, requiring us to [delay lane change](#delay-lane-change-check) 3. The lane change is forcefully canceled via [RTC](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-interfaces/ad-api/features/cooperation/). -4. The path has become unsafe. +4. The path has become unsafe. (see [Checking Approved Path Safety](#checking-approved-path-safety)) Furthermore, if the path has become unsafe, there are three possible outcomes for the maneuver: -1. **CANCEL**: The approved lane change path is canceled, and the ego vehicle resumes its previous maneuver. -2. **ABORT**: The lane change module generates a return path to bring the ego vehicle back to its current lane. +1. **CANCEL**: The approved path has become unsafe while ego is still in prepare phase. Lane change path is canceled, and the ego vehicle resumes its previous maneuver. +2. **ABORT**: The approved path has become unsafe while ego is in lane changing phase. Lane change module generates a return path to bring the ego vehicle back to its current lane. 3. **CRUISE** or **STOP**: If aborting is not feasible, the ego vehicle continues with the lane change. [Another module](https://autowarefoundation.github.io/autoware.universe/main/planning/autoware_obstacle_cruise_planner/) should decide whether the ego vehicle should cruise or stop in this scenario. **CANCEL** can be enabled by setting the `cancel.enable_on_prepare_phase` flag to `true`, and **ABORT** can be enabled by setting the `cancel.enable_on_lane_changing_phase` flag to true. @@ -869,7 +1059,7 @@ detach @enduml ``` -### Preventing Oscillating Paths When Unsafe +#### Preventing Oscillating Paths When Unsafe Lane change paths can oscillate when conditions switch between safe and unsafe. To address this, a hysteresis count check is added before executing an abort maneuver. When the path is unsafe, the `unsafe_hysteresis_count_` increases. If it exceeds the `unsafe_hysteresis_threshold`, an abort condition check is triggered. This logic stabilizes the path approval process and prevents abrupt changes caused by temporary unsafe conditions. @@ -897,7 +1087,7 @@ stop @enduml ``` -### Evaluating Ego Vehicle's Position to Prevent Abrupt Maneuvers +#### Evaluating Ego Vehicle's Position to Prevent Abrupt Maneuvers To avoid abrupt maneuvers during **CANCEL** or **ABORT**, the lane change module ensures the ego vehicle can safely return to the original lane. This is done through geometric checks that verify whether the ego vehicle remains within the lane boundaries. @@ -919,7 +1109,7 @@ The footprints checked against the lane boundary include: The ego vehicle is considered capable of safely returning to the current lane only if **BOTH** the current and future footprint checks are `true`. -### Checking Approved Path Safety +#### Checking Approved Path Safety The lane change module samples accelerations along the path and recalculates velocity to perform safety checks. The motivation for this feature is explained in the [Limitation](#limitation) section. @@ -945,9 +1135,10 @@ where If none of the sampled accelerations pass the safety check, the lane change path will be canceled, subject to the [hysteresis check](#preventing-oscillating-paths-when-unsafe). -### Cancel +#### Cancel -When lane change is canceled, the approved path is reset. After the reset, the ego vehicle will return to following the original reference path (the last approved path before the lane change started), as illustrated in the following image +Cancelling lane change is possible as long as the ego vehicle is in the prepare phase and has not started deviating from the current lane center line. +When lane change is canceled, the approved path is reset. After the reset, the ego vehicle will return to following the original reference path (the last approved path before the lane change started), as illustrated in the following image: ![cancel](./images/lane_change-cancel.png) @@ -963,7 +1154,7 @@ The following parameters can be configured to tune the behavior of the cancel pr - The closer the values, the more conservative the lane change behavior will be. This means it will be easier to cancel the lane change but harder for the ego vehicle to complete a lane change. - The larger the difference, the more aggressive the lane change behavior will be. This makes it harder to cancel the lane change but easier for the ego vehicle to change lanes. -### Abort +#### Abort During the prepare phase, the ego vehicle follows the previously approved path. However, once the ego vehicle begins the lane change, its heading starts to diverge from this path. Resetting to the previously approved path in this situation would cause abrupt steering, as the controller would attempt to rapidly realign the vehicle with the reference trajectory. @@ -992,7 +1183,7 @@ as depicted in the following diagram Lane change module returns `ModuleStatus::FAILURE` once abort is completed. -### Stop/Cruise +#### Stop/Cruise Once canceling or aborting the lane change is no longer an option, the ego vehicle will proceed with the lane change. This can happen in the following situations: diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/lane_change-candidate_path_samples.png b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/lane_change-candidate_path_samples.png deleted file mode 100644 index 8578549bb1f5ba6148996b4fa996dc4d79ecf337..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 246773 zcmeFZY53%1nJ?TRjy5hZI?AYn;6Y>*gj6M|Bp^#ARjH&Zsiaa#B~{R1lFD9{s!CN> zWK$f*4P016S&yR#2#(Uiu)87BtcrlFtwPfRLbD?@O}|fY^vs8O&zWm{KfE8#b@jh0 z%abS1axcI8ci+{Y5xcFo?fl-I*Q{CdHkN5fYu3E|jx}rEaNe8$23&dn-`}}E_}XD9 zwa7J>-u4fVtyx1HwQ6dsX=Zy9Yt7y;^{1n~tB^ZeuJ(o-dsnN?iDj;$SqKin_33Qv z*`782)4eKGt$q~3K3YX(sJb^?hfwfQf%dQ9mC>Kt>y8!vdq?R05a{3^wMu1gm;^_h z7seU*&hXk%HRQwKs6L-hEY&hP-fHhEjl$UeaIJi#!^k|hca;Li6ECp9SIaVkS^3B~ z($oFD8E9T1_J{U|!6nL#W>e6Ju0U0A356hZ|5|zDf6e57HSX)S9(n)aZRI2rD_VMB z#;?!+&;6D+td;Kk>1y4XN`A7+uqC}}c?^LTdh(|kukyL|r#53N@k}rfurf`swqs9s zB7F+F@&0}J44>$1y4O>{%VL?s0a3RaC~XG8!w zy;fF>O&whF=*kjVjlmtMWvH6pmEl2m3>#KBQiHiy_o!5?HbFzU$@C)d?HHWU9ukg* z=4iWC!F!$V1YGVJ6T4ZLTDmPGbx#v38QWn8IEP0x54&@M;~Jc(L6O@;4HCP(-tbrI+Ew8Sa)CaGfgDzz% z<<)A46+zvSk`}=LnW7DKl50X_7^}FFWo9uB1!FGM*;?0+vPC$<7f4sH!R62wd{1;1 z(YU>^3}n_pYXRoX7W2iJSU|O^2|6oRuUaP>0|A_5E1yU#E5t^Yf!VrlXEhDnui^Ma z8j7|*>=PJ!L64#sYtd=TY4SZQ zOz{eqsXWtHlhk4RpyecQ!*bEWki-faIXy&yN{~{9RaS$@Y2ZL$$WajLU2Bpx6ieoH zxUm?3wI;EGz?~|PN^&-?FusHs1{4vi87JAb(DAV-5Ycidsa-BZDO)`uo!65|9V3$p zx6*3CKt0oP}7tJO)EKH-Yxpt|6ajhkFT zG|H!X1Ge5Yb$bTalMXx_f=i%LD@<6dN*T!vBIax{~7*lY=)LqbtL%%K;cwNtYR8{IgWogIAClEPR zM>ExJI~Xu8V<5CQ9z-Kp071B=QKdM_im# zralAtsX_2FBJ3h5GmdDnHgC-apq&R9E?l-Ce5XJMCa1f1sT*Ko+zWa;RRVyE-eOZG96GV_{6}e z-py4GDtBukHy}ky5Xgn_egfo`wi#aSmAfV_J7U`F@bwzeE5JDlbv@BB!JFx_oyqiK z8e2vZIPQTy8T<9ma;<;^A{XGVhJ%LWj426@E=Pj_Y(b*I_mDO}S92gn zXnO9~8?jL-qKX zi}~dgfe)pnDKqvkn+XR9G2;9|y+5UFt(OiLULz@_Vu8z)soi@QEp*i7}r2!b_Q={9#nNaBIlLl5%ylJ&nd4foPN0%8MKTDyXh^koL8r@Xpif$Dp2fTcU!4n7(i?jV%QY%BQ4r#A z5vpx1Nft<>IyAE(gtfeSfcmUc>ZQlFgnlqiJ9@qEk`Zr0kRaj)(q=+jLs*FK%f@1; z-fUAj0UNV+GF4wXt4Z1D@bk5#XR^XkkUFY zS29%bFx9AGU11K?iAGqv?co4n<=#+$a*Xp~hHvUt&~MeWIVCI`MVwTX&cYFF)iZX+F3gL^>g?iAc6B{GBBROovbyYcLb7zcH!F=_lRVj6T zTnlBI37kbWmWIMKx5&7rD=c zPmjllqwAcYEgMQ7xFoX2cZnJ|a5+P()y%q(8_l7q(yA!`M5k^>AtcH4n6Gh>=F z6^WG=T;irHpQcpOjiq*E8-(x26K<7g*~$RIIZ$8s7n2oB*?1*bhQl#K;@(_smaZ!5 zsZz7zcJd^g@FGU3Lt6u5i8;TENr>H)Cw(glu<=l-(|SXv64NIaoIR~`Z3pQT-6iOQ zohO2xNfli*(Uvr3%n({71>9Mf`Mg;eB_f()oD{KLtdnaseyP$S3ZARFR8Sd|E^N5K zyIoo^>(blglFN^!DG1K?aI z!=g7H&zPn@U(uP}7`82Ju0k-=CYBYOYl?cTk0~0G>>^m!@Jej97Idwab(*4B>R18C z{V0Wcu3p+u)0kJac}@$Aq$kzRXkZyS8`t2G9M}~?jR-bs7uH#2MIO|%Q3mESFD(4n!S3@P2GZp5M!!C14o@VN@)z6{h7

LdsBQ>aWdh||*H5u_VOHG~ z=t_&z7j~5$R%HPR4Q1RQxjNEu^=jZaHo))ZRD;tVlLxKYk|d~EI*6<$GUf5o=sTTN zCz#KS7NRJ9zwX6chSRQ21wE7;aflsLX?q%UyM5A1XUP;@G9W6TTdu4Pz_&O=`MxN} z9x+sMYM$~=QwWBz&$uc)EG(`XGMtGLt5}=WI*qZ+50tFXo3T`+e%sdNK_Ju@GSlzY z;2UQ(-RFmz3Ql3~1GkJC4z}ff|#G#!8H4;DA%Q zc&J9Sp(L$AN1L)-r1zL?j@DEy<>P$h^+#ddSR!iM9%68US4EF9Fv=*rO1d0N)84Eh zpfdp|u%a7sk83Jj2^Fwvh3cj36v{@+a2h5}o>-J9sJiIoeSk{Gp@ecO(g5K^jqi34 zO;Xx@(j`rJRPP~*Uyt0P!3RzniC|)FB^Yo`enAb$Zc)iALsj4*wrIp++Ys2ShC#Ea z2O?RS>Vto1e>GIc>C8vkus3CVw$TE8$at@n%Jq6nkC`DSBuzO4`!+2xBqH^d(sHhX zWfOLt{zxBKEqFlH`(b}60LY=FwQ4-fhXBq%!gSyyR4Z6vjpf+$1-GB0xtkbMBWaSu zH1pay87vyvbeZXig}QvLs-g;=Xf9~PF=$o-qINrG^cloReh+Qa{sQ0?(Llz-u96Rd zEM~2qO9;K5polF#<5vo~EWvP88b`^Ixms(u=uahUX(tk@(atica&0exz~E;fgw~~s zHPHBE-tF}YvF<Urk3RHnCFVYsBjlbRRU8EsTp zw>!a=c0#z63c3p6f!G|Bi>1Zkd@1!^W6pC+v|dxq<`|d8^(Mj5s;U|pDwgIughNtW zb|%ey>9grnbG%m6B1nU;4~ohdsni^%JyiOVSsfVM$X(VYtKTkKKF8LG0BkBZGp%_s z$2B@9vcxD+s2UJn(^N%mrjn6iwgCPjk-2GTq~CPJF*V_<1qy~pwkRRM35N1UKH1JO znJ1lY>3}qH?2r5uVhu>Gk+uU-Ty-AGqmd>0i#dokvv9CPZKW!-m~JbOyYj5*Q>~m@ zN)4r}Ta7t1W~@QoSxkEBd_2>K3MWo-;@u0N(enVNohO5gh(f7NPgmLLwy)|vsDnZ_n!bZY(O=(&> zgJyTUB1Ks4Xb4SLMZJ|5)}n41LNglpo%R5l$?_c040@!C%@pRLc5gTqXH97UOOhx$ zY1osnMp|hVI^wIfAkv6*nOA!(6ICH$NHk}%Q6eiks}r=>s3|pOMFxYKUmHxEs;G2( zhJX-yRcy~Ecv_Gvh_a%7T(#(Q$_^78ZhHEVwcz?_HH_tYi|$6eFqP822z#ymME2oe zQH>;3875X(ohTKFCW%pJ8On?9Oa`uKG(7%reX!YP>27O+E?+PDIXIX}~Z^x5nd|mSpM}X=p3Bp#%LV3v}G$d*p-> zRE7%0nW;*%Vp1FU-8i31UKt>xz0L^kwVVA|r>nJ|3=Ls3nGR+kdLo@zEVa*Z(PrDV z-JtX@i~{;-_#`H)ffUG#1>b2{Ba3Sp1y{w!6MNQ@6ihM@UBej4*Xl#9KPqI|c3oF% zM@cbQ)sc`N%$tfaukfCZi&V|FJc?*x61g%_a%JQla6yqRK*^;0eT601e z#8S$_$qLvd2{SUdFc08Qt{+=Uj>T+O#{Gb*o$7vXu=J7f^@rHy^71ErSl2J z__1uqsa+L-V@zEo6Kul;Oi_y!1XmpRt6pn9H@zuB2N{r{*n$)jFhdGEp0GKj_U2+< zU`uH+fvweCM{6jKb`%{Dd}VY@YRnjhJ;0DmNky88a?p_i4+}C;t*}AZba@PBfav3d z9fWfO9n1N$8i{fv4uonPxI?=|s|`|dOFi_L4wyH&5@3GV3|e)coVGLu8N1T5Wl<*X zSx#di)~RU)vns>L7#Ko2HEWBwisaLF!(IB=l2Xuai-YuuBoa<(4Xs?1qR8Wm#;l;~ ztq>OFrZsc%)og{ZzDEvnl+D2++ZH{_J5w$*XFfDo4SSii1UPZf7^wjG&_>|3*QTtx(}s_0Wc+E~ND_ z-L@RntRZ1t!Nv&GsiHHrq!^M3BG#5<3g~d)cymCX4cRIZApNSu^r*y@!c?hS6!7cf z%v*IN+nNe>Gpxf60jMbHw)=HL7V3ndvW+nl1DDA{J-b}dMU&=2r%2i%ZZ*QZ+J|6c zX8LVDYjgu<+~iBCZ^a|CC5SJWH@ z6$?rteYr%9rA#lJ8Jl$$z$VdDL>8fA;qtiQEMrGrW%3w?tU;etYnCifmV(%QhjGRO zG=j)34b6E0p>djIs1_T$`Y6GyNzz4{xz#d*TEtdTsXNvtBXbM_=Z1&RtDOinLm^o; z-0EO7nzegz4_Q(kiVL*dHdbDvEmQ~71u;#Op+t2@L1y`CJi;M+Zs1NTs%9@4cTGfN zMhKiNEfSHdQ%}zNlXkc?5)VZA^vc70512`F5nFO34+}tP%Yw;?Ats=9F^723aHwG) zYynT}s_XGc++_l!9ds)s+Mm?urBcHz zV}dSKeT>wXs0^#~eh~C3qr$AMf^1yzov!Ofd}{=ycDDzmij70+h>I-1L9mMzF)TE4 zNc2_-T7g=4pbdwK4rP2imE)RW#NMo1h9LvC1F{43a5hUBKkRfDl|&6dRH2MptI(LH z>3Hr|x|480^@ng(f*qC5s?7w9rM5sTe#t^>V5%Jx^fhJL-Ox3;6`C}nt}-R5plXPd z)L@l`+nOEW~Vp zPy8&(`nstuY+FTuuck(`N~GeRVnEY;k_VB68eTl`6MnwL7?vnto9Qw$V^kV=1nvNU zzo>hizS)7z%5++EXJgZ~&0sZJE;_N2aZ-u$iki-8v&LXGsPhw)9S1FJRWmtD^Gg;J z666ZZfrNxzM-^rUf>gk)OdCUhdBKd+oSbl@sAT&VGUa;KtYPz1uiP4N$xIo5Rt8p6 z>CA!n_NvpUEx>g(Cp)$b?k8wdH(Qa4m0^gGWfUOTaF9ue@R(L4qh2vRaqht(&2xho z?XhCDYPA&N~yhag`_DIDjC;dSd;4Ma5Y5yIfhTc0`q;K z_GKf@(ZU7Y9}OF6+Nfz^lSHa{F0~7Wwvmvd;%3$dJ-8CaVnNLSu!^=CzJg1F2Sxc5 zwlu}2kb2T~x`Bm>NvqrMwa5x+1_D5r;zELYgxsI4fmMuYrZJ5MDQcqPTp*rmEu%H_&{;Ix;`4umZn zjAWKtR-cU-w;Pz%<)RVP5v--iY7)vCr+A}c*6)cEcWO5ZKh`4Fjb|+2Fd#t^D{0}m z6gLcmX|K_4dbMs54ulcggrgvo4?*jtMHkhUgh8!Fkw-VPDxPS*Opccdj6QR#co}Czg3gdd(V9@d>Q`gdvf>HZ` zb>yoUs-?NU4A@SG?MD<J-z^kL)EM59d@fGaC#|K|Q#^q)m`SB6(H!x8Cc{C zf;u$wk>OJ-YNE^=`dEQEK$x;X8u?OY>@1ujU!M2A}fNYV*B%}cq3i@)Vh|zH}a<=l&THKR zTm&H0Ck?c@m@Hbolo&$OVcfOwS=tlf)Fy{a+W@KKWi}6!%#wN_*fzRTYz)+gEC8$_ z`)T0|BP!sr8eX# zK}Q1KY~fZ)y9jdl!*SK8rDWJEjrvq*7SO6H&=Dc{{iq9%Y?; zT5F8S1t43ErB2~>*C_2tl4x^jB%&A@&OwseTNYCSZeeq30Z1^autu4kV{w<#@a3vm z^8kpap=e@utFeK!Z@g}vL7{pZ7sgaR7R91a#NU)YSH>%xs!(t}=$O{4WKPc0K5mnc9 zb7EyV8w3=BO`|?mXIctKix(5%e`t=cRH*>K`R2p{NCp!qqR*=nkyS)-aEi4(& z6rs9`VYeKU$W=IRqEnh8CsdtV$Zew0Gf6V!GmG=f{gX&gZy=|B7ioKzQU>k9!g2CE z(nG@`VX0nAY(5I%zT^tXbgVP8v0$}aDn|3Nu~N(s7bQc68Ko;-Bq)2VPOZRcVoD8) z*=eIGNx36Aot#Z^9HjP{oQ~V%3PfmH3km`Y2}dAD(s%o1Z%GXwns!@NVst4COL*F; zEgH+IFVvTFZ{mv-NxG`mK_yl$I&O1e;ckmT;VO$zv^@mncQ4nOMzAaZP9{ z)vg`)@ud%JEx>|#2hhK(+zNddbb|m=YdITKq)ttTm|p2pC^x9;Esu4$VqV5yQUooA zUdJB#H84O_w3lwh;`BN`4-|!{d2Ks&1>kfP+e(L6I%+e6d0oLrt`7ptpqfTA76;qz zvnv*=4*acG9Dc1)SI!qxs{?vStyMHLnh=z-&Tzi=r3hGZ8aiAeu(iXELmt z45KcbcdgNMrCJion@hA7E&%V5C(y!9?ap|)su5FZ$aH9K zhR9{)Ory4`1giiWX2Wm}2GMf|HDDDRohD$h{ncW^drYNU08l~G6=9$XaYcL#N|5l#P0)3Nc&o8MS^K7i$t2C=<*B%#j>JTs!=je2E#s6rq!o< zFqtuaQ|%BHL~aO-602CXO9om4skGZFQ#ToFZpG-hA!8u@FEct&PPgXfoII3RWw4q| znwR+N< zPvtrTVv_klvIk3m`BqiCJ*&>)LDOWrFyQU2h$(QbL3Q*tSC8Wk+jK0nKPJeC=?vS| zrb#rW0-`CQHqy(j6qROPM!gotMKL#=4M|!PC4Qg|P)KY}1B?f>o!IARMx6U)P_R&X z6Jmw&nCQ(oN);5c^P$s3$FG^wgRIG-KtF> zIg22f?}3-pX$8W-lCB!?P&D&G2Jw=?`^AXzTRiU7*g6YX*C{lRys3{tjX0a-t^%%~g_<3cvKqm5z7#c7p3vw>5r(gm`dy6yrA+o>QN|n-&zsIfMo8Ob z6zTvT0%Z!rGW)CPm?w%E8fX^Xs;Xlv?hpHYKhPnf<=|AusiCUs*E?8$;Ckcce9nfW zWmak8gh1phoeW`>v6c#{h+Huo52gvboK^95Gw76-dOi<81zx|GihfT+lYvNXK*_y};kVZ$Xi41avlnq#2llGik#eFm;`wRz{ z5?_KL2YC2cSt{|gmKU*Pb-J9mAf!kVAVsDv07Dur$Q?S^(znV|7_ws$BOg{2$)Q6t zA*2N#a$uiA)f_a~VXS4v6y@tC#kM+_)642P$6}@Fu7barFeO+Zcr?E1xe+H+!;x!d z_zEQd2&Z3d^t#5R&ZP;;pp_iZ(&7*V-k|&lABL?yAuQo)GZ4q14$ne@RZ0OgW`Z=s{g_ppQVB3e2@Zsr@lok2s{3GC=!iyXJSN4NR%TmPR??0xuPA z1B1y5)U$%1CU=7l;<@uqBNi$Z9S{%wNxd;5`q*UFu1I4TrHW2fF8#fY<`Llh4RhS_ z^v0yd>X_b0MWQCfQd1>Cg54`XSyM~a64K9-zBQ9`Vc2)NIS{ULBPd#*X~Rh{#!+8( z0b(bW+HlIlnnLJw3~K@iLV7t|o(m-=cY6+rGF+vNzT z(rb4}oFDf=;i=pqwTQxC1XOX_!^pzMwOrDBj#1Oc zP@ptUz&fc@H;ZBpD4h%oV!lyk@kVV8UD4H%G+4CqRBh*zpkGwEfha-|X7FKvzz{N+ zn5CiU%2M1+;4uWZfg01U(QU1Ytj(MCNw0zcf0uMK4u#8mL6*pfLoC&~HtB!_2~xEL zQ<{LfrbwytO?u2IAgzdkIwrnmDiuFohzRZmW;jwZu<1z?8WJN1XB|_8eQRzmVcf*2uIqgT2rQ;uN|YsH|jLtI2NamIJmk!sQNB-b5O%5r(s_M!ePj`-mm zCFsRC?e!&XrdN?>vtJO?+{i`?1nw#;EeUlp${Q`wssp>gf}Cw@X~8U5lHAdzga`Mz zwngMRG?fb{Q`wa8+k(l;6{9xjX)~-3#zVVhz%|rGi^yBuIpbw#3EO#2XG8;k= zQR~NxJV3KJYy;;`yCBpmUav;d}oq{eav7l6;B zJcA}pyp(RIh=b`c7&k4{w54=}EocCfTYxN`qq3@t6M^mYWQM6N+^*y#D>BZC!W@}} zx@tx`u>dS)BPKHnbXB7E27=8dVUxj=F!lA(h+wNAH$Qegzvu#*cNq;5vQa|@HK?iq zDqw(uX9SS#Z3%AL8n#x8SyW0JWQ<~jPoz$XGC@8T-tGJckXiQ*Y$DK{0aZgGnEZpx#h%(e#%Gm7~ z;ALi0?e&$FqSjYzYE41aRmRd52X$4dfmV#Wyq{f7=*FyImm4%P&AhK{2;z7$d+1umt;M$-5gr>YMEaR3%qRG)f#hpG6J@qCU9mnN-B0LK!KUn$kK+8 z_KfU`(}6G0Nltn#dj^1FISJh91P!l(vn{bUYA#;Cqc4ViQq;k+xH|uB(f39jBazOx3U%qL{*ViLhUeyB-P*Ha8P+I9)bve2jK&w6SEWIt!KS zKPvHUGM|9#e*pR-yE6_C%T8a9K_?SOBjD0^T6}4wXsc*eXQ1~*Gl%J)w2;nU(VQ)OX>{-+31VWfU7e# zE(SkmfP&J5#IZU^R&$H(vvS6u;5pJ6gVIg#d}D5u^Kx2zh=cjK)-LA}R?48ppgCjHBp^*yXeyhWI{fov;aN~>%iP9or2BdqdP;OjF`Y_XQ7xO1ofek*I13MFWmi@l&C0jnBM`@k ziGwiXI%14-m$%ZTUCLggpvh9kNFEHIcEB&HaCfTVPJ%W}uJBEFzMG7nd2igB>=1}g)wwPTrXy& zh=vo$NfL+jy9A)hO5SB)fPE)ZKroV}`x%UKU-yBYM9|QVN6>8IlAsw47iJ$A7`1BR9=39i~8LrfH2B^*-5k@_*Mlfa!hR&3bRz>fhzX)MqNxRj1R|Gw|_ANzsx zfB!8d-2D8lPad*n&7N!6MqSR1{KJE5ubD2l9r~KU{&Keu|6@~tm^ ze(h&&xsGH{{rsmt`+3X#qWrDdd#byff89q;mA?FePk$SE`OqVuc;^1C*S~nx(dS&hg1-&tgxi|MzHjt|`Zt$)=5AAkIsONjs8B>wUg^v#`iaxeJRV=L&dT;3hm zKl;~+%ke)v^&PvOceZrFoj>|3mlp`j8~)1K{9j@D&-UQ|3d?^g;{SgZmXF{4w}0HY zecQ(GKXug;m+$h&>tB1~`VC(Z4k4ac!=13#wJ$&V^_xGl&pFzq*S>h)vp;;pE~j2_ z?y*-r^0ED|dHTnjj^4QS$f0}wr@!^X-fg3k{`JwX1*czp=~WjUbH}-_J%7Q?$8LQR zd)tpUZh!5i>gKbS$*Zqket)>{%^$tufp33m_vq&z*mMWA%XIeAC9`9KD;LUzul)WSPwug9^^4}Fbz6$vKDeX#p{Ebs{@kIP`scnPAH8+UCpI5+ zb9(*O2P^lV`?h!fSAEY3H|@FSVF$hEwl7!S@#jaly}*?#_qn0h+Fg0^!F1!Z=Wc)X zf+tRR_0`RX9?;qU%10hK^E%s^L20B$>l%)%)56zZ}-_^>t25`kN^9F z|F^g1``qva>>+J%`1A+Q0#Ew<$KJfdeK+ODzR}%ha}GcLi`~Fmj_Du%55vQbzx%Bp z_}{@7(n~^j-gD9Pq>SJMOsNe&e49 z{=+G*jFYn#+u}8j0Z8-m=_uu!>Q-^PSCLyaL8q7f^4{b- z|9MHeeR6(y64W`wAUUlGiRm`{?%tUq2JBjRrlez|x3Z{Ifi z_Q~ff*n=xjbGGTU`;WW+#ruMr?{&^ycj?tnUG?nOH@^CW%;=9)$yYYwfyGsLn(8-&DrCpcbuD$^qGr-g436f_MDgp)Wu3m79mo z*~+mmUUsf><7oS~!w&j;-Ko{H*eZ>+d*6QJLQm9+?Ss_cl#0VxeeR+ ziM!4^`nj)fJmPNf*t6fluJwNU(c_-~#vUKNarg9rU5`Fs6WGOk2&~jeqYF0v_&wXp zU5=i)VK?=qFRa#lVavy!yQROoaOn+SsNMJNuf4SG(W9<7=7z`a-}qV*AF$z%=IPI! zdbIeI`MLeR&%{S%FI~NH-9yiwe#P_GK6Ln2{5QwHVZ#N7ZhP#-{SSTa%-c`B_N9le z-u4pE?JGX9Y2TwReCpgYUn0J>`QR=2UHOKCp&P$4e-sS()nglXzWUnZ7k~HCOYeDg z%O0;iebS5ZsawUTjy`ce~7bxr<@&mAeBzAm|U!*8~2IqtaO$4_`8{Xhu+=I+_9yB#sF zw|;*4{m;JV&gO3G*(I2Kh*}0HqYr_vH_m`;I6^N zuf6xOv#vPeQ&&2V=Fi`L+-sNJa_II~?|R{k%|H9r*Td22M;4Dg_Fm&rhr9`xA0@th z!^Vfdn123<;|@6HvChTLE%ycAUH8z|hh7@o^K<5fpJCU1?~!{Cb~nBDbSucI{h;y%e(*uhecYpHXZ9tbs z>rOdy`*(}GF23mD+qS>y=gX)#=Z0g>-|sJ`^8a*j*{R2`d2+w_s@?Z{-S&Sq+i~re zKKRG}mLIEoSg-xFT5pzUf_^^Y;9}$%DN=@vnD}0_C@7POo_I@}1xE{KcmYMi=h(^ekclPDu!ykY8#yyVv#Ji;TUifYxtIvM(fMYJ)*?a3~?Q7Okd;j#S+g`Z%#6vH? z&%gND3x#7Y+WC)Pkk_8Eo;+^2|GLxOdE`yEFTe29e>u|p+w=HuBlmEZUj2uozgU1} zJL=YxcDnPbyKZ^=9UuCaGhUwmT0iLrZ@6i%-PKQC4Xn{_okw5Y^R$=Gdi!ZF9DUgJ zFPuK|FN_|)@Pf;K^69-ky2t$|x`)32%-1zLpJ*Su$Lfyyrl0S1$|T+L)DO-+@q4!& z{L%woKK_Y4Py5&VPdeoJ^G|qc-P(ID*vr{*aOIZ0*FSX8=a0F5+lybf&$#oQ=iPek z_TPMJm;KKLhWnx?uGvW3(t1mDz-JV4{Uz`H;9>8(|A@`+Iqs9sd`c#-x%v;^?+~v( z{gb2r32woMZ7l)$EuTJd%jm)TTkmx~`Nb=-r+#qHk>-mWr(wT+ez55qZ#i?1wWn?V z$(z@1Jz2i;DEpyJuYJw=BN&i#=_yADSKj@m3s3yqWv4uO`Tdt}{@pirKkwEX-yEI7 z{Tue9=gxigk$sLi>1$5wspg$q&p+wdgMNN(@X~|n0r@#^AARqB09J0k@sJn4cfuh% zLW9j0pbvfKwM)PJ(p8`M&Nq~o|C#*cMQ2`IDM9q1zq?w#yYp@2x%2LUFaN=lkG<`V zhk%Q+HXifRC5QZTmDyW7JN?=%57+m7>60JZ=bg{)vHo<;_{`(So(o;_KmJc*`WIwy z=e_`ETpQi}?|7VU?z#IFzZ~v+{? z`5hnn_?b@~xAxZ``uo$@9Dd*(!1`bBe;4e;{py1UTyVkG-<|iSGf$qpFgIU2=(l(7 z^z=L4yZicIUVFg0D<5CSJn_WI&hfQ%&%ERDsq)%EANbr(|9bL)kAM4ww}1GA@2{S| z`Kq8V%Z&)f=E&c5!>E0=|T&${%Z`VqX?Rw8+hgmFyDIVb{;%?vUzGsf>p#9a@bCWw->%&0m&fe;fjdu}mTuO3`<63z9Uc6`FG1r^?*2miiuJ2= z|KY>Guk2Oad(?~fUv%RC_~n->Kl+SJHXqybDggb|buYZ*c}~QCdjhZC`PW`?{kA9XI^`Wd1_9lz7v1KryN3t_^ZSDBW7uvi1YNvy)Qh?C_Na~uM-*Y+n?zLxx|N5i9 zQFeuXd)MTk9ez=I_cA2d{p;KvAANX_3%AaGeAHv>@B70!UqAVChtIB!SvS1yBc0QR*D-D z^xVYz#SKso`XF;dZxR|HnTB;?-*-d!l5`9c$1ssZ@Y8y{{2AHjY9%@~@t?63#y3}G zWKb#?&!u6u^dX6c`S2#QstMF1o}N&Lwn@VX%i=!i?D7P^1?EYTxGlO$rqgU~NNUub z=gpx!KWB#%A0@d+r)pVS%Y;T>X%5qELLDyROQ`T;ra~G#q3|u8y2KqFbNNQiQ^7C; za0V(<2j=UX$uzY#E2>S>10}9y%dL1pNlN}T5fY0ANlIz!Wa%8y(&wu#`UIK z>xXSkDJ>JcvP zXOTnZBE+xa-5+t1h^FR})DbJL-p9gt2iteWL@D#wIXx2U+GvDiWB~*~oVy|CKnd2h z@hhny*kR8)c0IsIg3YXasLOK8VsoQduecj}N;)F2sNd7A_DC_KeIw6{{S|t)ouoj| zFNqUt{aDH2XV*#`pFcJruPs12`;sduD)8V?xfUMlLOfN-M;%}GkfbJHlSmBPa`lLs z0<%5uaZdxPit!_zZIe^6X788Dcv*{7KAOIUr&0zwA!ZIevsT1fsnh=UUvugm_&G#x z66dgfSx!z_Om-P0bxQ-5RekO`NsbhA^i;cxQ=^Aeh@0lf)u~1o|95k_xb-Zr9X$0s z-Z9jNJ?n(lY?`jpR8zG!eyU$-%hC8awY-RZ5p*sWQ|jlS{96eaUeQk--xYn*b+tHb zP?g$MY9R3H({1!+8PaTHs=iabg8Y8RMLw4h3~S)y22Xj$_Piln6F|Y?j)3Nw^|Qm zpvQNGp5h5#3cRew`Tzeg`EJdkg&#^Zxhy-Ov)5+^k(`tZwIAZjJ3}P^0!XJjQC-pe49d zB~4ng=2z&w$UY5R0cW32f~B(P&8+uWgDfX6Rl_qh6%ApSR;dMgE9RsF6y-&mqFzUGhZQ**w|#UCas+%pD!Wcy zsq!ZYqefHiP0!>o>Gobq&cakY28RGm9JDX|-?EHk_RB_+k=J00@nEr28Iz*c(J`Kl zKdRS7=?mr5$htF`he2KA$!N`F-mkX52!nFsHV^r%Q3Nu(c6C~ZnKb`w1unU$CQKC( zr3DZAj=lvm^FR~Jc5TYwmYPn~Oo0WI@Gon^1}D%^KHB3>d_14Vb%!IBs-v1M)(+uG zK+RdysM*$YE()!=U=!kPO4MA%L|C2~c!wF7MamHL3jzkxW?toUeq~em11iz8r8m*E zkBVy)CLE)vkC!Ei+3khcUq;e&`K{ZZ80lM_$9t6}R=asf7VjH6*g#NCXEwF+2r_mh zUGgY%-;ubdl0;%zYh0CWN8{^y>LuoboML59HM*(f)sVlcesK!H#^Md4P&~ZPBE1(F zWEWra9qps^J#h+gKYO^{ri^(AFY7c>afnAQYSeK`eLmiT_^nKxFc#|NBSq7Du_R?` zj;P`7ET`h;ZTe6xBjTNuh^{VE3Cq#5_|nRi1VVvofJv^wGSS&TTqk9%omlz6FVbBD(Xos#~qTgTu^i)99^l^mSxTI zWGDc}!?jAOWz(5e^7G0sPS=KbPb!8qnF`-~O7tGjXwR70(Ud|M@>-{QsSDr5UQ&IL zr34v(>l!mH>w z4epE(8+Vkn2*3O*(@!Uj+LpE4*shHj(Q?fbQzH0LZI0<0PNcSJX4VE5^`N7@Y_-ps z!l1?wxKQ#d zUG8Y@X^lvnLvO$@f(?$$FDBYfxSpZSN4;z(*pGIp`PX3Ivb}6RArYeyrT;`>TT=}; z+cn(~Z^Kw|@pdjW?FZDu6oPa5axZ@>ubf-MsoH#km6>d@?Qma^n`(swAo3~_(M5cu z4}Kg9bH(AehN@}i>+()=oEsCX!N#gm2VJ={oT^Z~Sm}HzE;4DUhl536S`$T1iE=KR z{owB!)-)n|5l*0WircMN-tiLgt0DwWGxm|{ZDlfTP1E5~73y0n*fU53tp#z#VeMeE zi|NeEYKsKzL7XQKnV>v%KEkQ2s&7U$NVb01BNbgdG8Y`ukZih>CEhx=w&6Y2VQPW# zV~@H+Zz1fxidiWK1;C z{>$Gto1F1^;tJ!eT6p>tS!yxq z@w?#9zX=;g*{K#W`t`yt?n_=7=Nx!MkB>Y&d`(R}*$Uif%cE1WD!c>BGrf>)(D_H$ z3${GQqq!s(Er0t{3xH#>ay-!>fwJX!Bd!rb44j|3TfAn!wq>U!1?oh$QAm|pw5CPW zYhY&>-$+iqGL8~3O7tVR;dWC)l#L@GzH0U~Znykd8 z2*d@_d?Y_n5ghN7&)0?0A-RW%fNQp9j6V=cZhd`{I%qojsbK}HG^vS7#%EV;LvKpQ zBtq@YDNBvfm?!Vm?_ZxHOkiEOmXx$d2~%@Iw>;Sjk?L+;q9 z?YuGAtM6A6wSBjkJKznha^6ZvSf~0fTs&lb=G`wZB;3qam;Dc%7Mi8G>zeGgcy9ZN zk84+C_Fh>JSFDJMfxM3run=K6ZYOPaw+wIamgqJV!lUhtXEUqC(J6x0+sx^!zs~Y@7Uh>vXvG8w(9DVU zJw-B2*po72@xFBcB52|UAFAKJni|<)Q-RGIDATvPCH!D?Q-KKCUN1x`HPL z`$kXO)MK|drSMP2_vWcXy^ssAilbFYyTUJ~LwX`{S60t;g7G7udiv)%P7WSLg+Xjg zre?{aC~5smZ0g92JH^s~Kgzaz>5Gj`{QTYG(7WQYVBL@to0QGB@w*Ur=rlTolsfP{ z>dla+%O8J(S+~1Xl^qdPEmbYrV^?iIaA#kke|EPG;nG~rZ3Yha?4$Gsc)z|V*+U;+ z+y6rl{vX7}&=t{pC^SlZzoK#nD(SqH#K9CU{gMH0cWTe5Oi@`QJv9KlMSurD|AO2J zY+Auf6FrMHw!BOXkVs3c zHtnm=6(NQiX|=pam)|S%BFOE1d_vzN?siO8rv`)|wl_ru4Pxap zj|0R-;cdep;y)kdxx2H89g=nKn5()WhPONzcb;xD$dIp2N;u*M1Yo>-Lq6 z{fc(#kUy8$>0D&iqoqfH8o*M)f6;GsE@K=GCc~D`?_s$kLRMX7>4ux4uZ-79Y|_;_ z$^IqcEI{ZLW#&@~OP?xFwzqPwMD&?_HyU4^#tf$r`c4K)C~NfyK^br9)wIbvuVpUV zLD<;B)9!GuS<9V5j0^R>lqZ0hU9x>Z9HmpU+-a(d?yo&Rl!u^G3R7`+jyd^nm=3;@EPzMi4@7B%dda}Tv;MyJ{>zPHJM%A^)R{G zj<&(~dKC#JU&N>1_Ir1R4NVt+)~n}9gpv4p1ou5^*PKS5!SY41yrld8NW89kGWC9k&} zdWPLb(J*FNU!Mh&hhB!>EH2lwDsU39T>I%66qUfD4kJJkKPZ zUsi_Qtftvx#253j<$Vd-cu#zzd%t<&YlC=<<>3vG~*N?OjnW>nr^R zL|`?Ijw#bxiz`6g+uu#r2Rz1PzEzXMLb7Zx@Mr#%ZLu@M?9Yh(nagi@Wv<}-*c&Z8 zUvT*}BYsxe>C{13iDP{LTx^kf#p15`F)dT3Ga?Pe5PmX;&s!p zA|}?O;hjWvbR4YtH`updkKb2gPM>=^7eOW^`p~(V;GK#C+hi?Ht18U3h2tyMmY+Bg zG=PC3@p~=R8>EbX>?ee_&a0ob7ha> zJ<-GI*!VQ3xJxg12O?a#w>r%=ia800H5)QR$3d;D$IL?mfo|K1)o@&?1>my#6%C!5 zx&TG1gT%ZY4%J3{UWNs{1*fEd(MlUW*C7;(G9ze4fqwk|r6 z8sn(rmV@;u2b(F$5^aM8=TP-7!UW2$Ik$#5X7F`aj6Hu?7YHmFUv#8RHHw8>E@DML z4`}C{CzUtT@1mMU4l40}kmny28!bkc5pPMD@jADqVPdisx@?6v$tKct^%SW~&wpGH zbiEUDD5+4fb}u=M2#rmB{-{#=PuHvJhoVM+Od9kK3$Xmel*F&wE`?aCv0>J(B`*jE+g_GOmU_zZ_0`DAp!Z6HKb&&{4T4vsS>{x^pt=v1FqT z`I?YbF}5ZEE&u+}EVi*${kmLeArSd)WG% zK#vSo+{Y_))3&+v<}EV<1CgE(m>65$+h2r5DQKnZT&;0|_#6tTf3|TBWL$UwfX69u z9-nsMz;1Iw70%N(Oi8HU{{hUiW%Xd-cVH z!F(W^<+*>N;~493qBTZM20A9QOajHNd7zEXrFzONd=o`+V8~{L?Tp;Yld#gH#5`*W z`Vk%W6lS|JNKC%F9JV@gZ)wZ;B5>)fri$G1pNs>&1Bd)ADY1>)mq+Z<=BO( z&5f1g@EE0ok6KskWE}IFmH96T%X-2geuizDq7L{&Qkt>NW>iAyg=09i*oQZH^SAu> zCp?H@D5#ZUhSiGcc)le)ESjGp%wmr-u-eIqLky7E5&@;xj&|~~*}yr2m9BQjuM#xx zk$e`4Vpe0v&$Rh5`NB{yom4JT^W}>9f)!BJO2hybZdS{xJT?fq%>Mb}IRr1&0~)=> zs^~!crFUWp$vJ8CwdH^X7KzC!zRK>_ViuJGD6P9f2Pklf65h7<1LRE<6mRrpnc3jL ze5Z&eCt7r(eo>#RrHEHE#qOfz5qfi$#jil}cF8>Jc?fJ=e*)u)xn z-re1&F`ID5i0?45no-g!UOd+3^|-6wvncPusa>iAf)B#~iZU zV(u2R9?bZ>__35hi${TW@f4z82&i26@_WMrnyyf^%-JBuBwxR`EanZ8t+ldiGf&jo zxLTcK;@(4^O&H7O&{fLidQY!7WnJxCkEMLmiRKq_DiD&qRo_L z?me9;%UT*aTFjqBv^!%Uhe%~T+TG}{qOUH_@!$Mx#dkx%Yd=}bw z5KWQ?10=JMr1U&)<)FD)!5w;Y$+xB#y&Z|-qmx_LciJ-&?p$TAQrp*~VV(P)N55Lv z*UBr&B-FrjDM0OgrU`gGBf?%r$tPWUu|dIa0iczuBCH>?vfb>C~Tnxn+V ztduT4k0j%!#QWw$1|o7ai7*L`;E{?V5;&Hd{Oc^zGc|BaDqD~Fyc{_tRMcZX3<Y_!I_bw}E7( z^AtLEE_(DC)}jy8Ep^Q*Li(qRK*BK^_O%oPHA_)FRGA;wKA1C@vnYEF1uI;1IH=j( z1x#Yy2L%pkzHaNg2FArCnUx&{lvYiHGCikW90k{W=PbwT7n-+;D9iS+`svXar@o2h zdcuXQw@agO6%&ztlQO-N;nMsJ=DJz!7&q(rjQTmwX?-rVj8?EEckdknZh@UNC)^35 zwYjWjiZKTiC((G=f7z8z((>In{}MyX?M$<;0};e|*}PV)VySULKha=xY+vc8&7e$K zQf_^%vHMRk=ASaDe`ggwGwL7y~kZ-#n8V~)@X$@bB7fo^Pd*wSD{$ITsuZg(0_^Ysg)1R?6&_)cIg?iYX*dh5>1{wzj+smQ=3gr*9xn08%7Ee zGb2IcG1pg8bI|e`sAnz04~OVG^%hLHc0ldYgUFq>g_>mLTR`y0qAgW9QE=hkcY)LGGI$^4@r{MkU(j|S)o3r?xF<#gaiIoTcmh{(Bzl1 z_ZfY@U7@^2*5K*^rz`863#w`%9pOSU@|%^1-}A;<2}RmOj(-wY+*H)Rps>7p z1J%Ui9TYJ=&en#*;AfwGtpcsw8VVNEC*av{-j6j<*t4h+FcS+@4MP3t3U z{X##>RLOjsE<;~!_VxfLZ_)M+5VCw^H@$s({IZx8cXs3_i*(HTa(ft}up^t+NXSJA zIv=umWmH?N+z`4hs<+Rwh{E%M5wv!1^BB-?Cicq!<@)C{~_g~VPW1NW@a zeOK7 z&2)TH+?>sGabOq}F;+q{f7al}^9ade0?D_C!~M zMwVS{NAoeVuf$3Rb`C>wV!Lh*@`;zUcX}-VI~bQJgOK7l>3T+T5|nEu+=m-nSD|hb zL^&~DEnYu57Q=Zho#&jlV+dN~IHI<6Q$;GYr4g|T@pp&O^+zjXgRYgCo&i#&3i0a; zJS=*iP)sneU)yWtxI)2xugy_%=^;oS+Ti>UoNWh{B5Rr z<yIQLL2g zwOj&c!IRUg0PfNlusiwbAjDAV&jUjxb+1~=iqKq}L2n=zHFMN3j8iimQTgVAc`{*D zQ8R$@pJ%J*IV%m4ZB5ygI?eK{(8oYnn4X*K@omn*1}Tp=^h{5P?553cw82NvMQr!g zkhoGle8P5I%N@WXB(-0HOsFHLk-o!0X3I;P-rH`Q%@Jk$6En4RnVI|Q&#=jC`QLJ` ztox8{U)tB^8iWo0b?RYx5BX~K(oQ`(c8Jcw=3l3 z%SmkG@z%rx+LODjGKI^uVi^dL>zjWghr~}phS5KhM=yzp>1LtkO`NcJMeTE=c7Ktp z;J|O9K>vyMW;!x%I7BlP$s6b%=N*WArwqGIXw}dSf!fD`^P#}AT^b`7(wQGfLFkrf zTL)b~x_LgAz0kt(0;{t>-M2k&c;Zpv@J+6Qk66ct7db29N3K*5xh(HN7DNOZ! zlz>Kcq&iG;&Vwknv~-~WPtp1U*5n~s>It&S5JU?>>F50z+s~u}*sO~oPcCHz)+hd=dj@x zccbS9yj{gU&B(|;JtZeONl?B$Rve&H0D8ADAxIKhq6@(Y8f`jV7y!6q*y7sHZkqKm ztg&`SEF_pr1+IOg%v08_0B-fp1m8{&H8uL#(mLD(VJ14SO;>(rCf+bBHsPQlg0la5 z$zh~N!h;}@;zmJaGZX4%%z}#V;xVWTl>8R8VZ`SvnSJoXDkLIjpBN6&{!4QjMELSa zIDH;WTr`P(v}F0Pj58s$`QIelgG#%y40@peHdz`Do7S2HJ-S9G;ASb>B1Y+cSvnz~ zD3IW4kAxcscoJ@|Bh{(qp6fccW%FsW5K%6-<7y@4qU49V()}A*E~s$Yfl&9**kbeH z{Jyd&M4qu{VZ1dM2M|YNkY3G`cr@*oRlb2`SMOJy<9VHXL`LU9hd1Viuk)+`COQO( zp4{#BWikLqh9F7>a+3_eeNK9VfK&cf47tfN+r<@XBe4aM3iCZQ#SwUNZKfht`Do@q z{G2~zymcN)45u{5_v-XdLBERzR4~z==hHmnEGe_~LepA>n%<&wpl_eD6p9McmcHC$ z>5u9h<=O(mI{n%sON-Ue_R{MR-MCW6nNZTuk0@Cw);4f!HnxK+317$6z0xGq@a4-B zA(v=x7TX4B;I=n;LU!|ruB5az%>uWM9g?eRIvu$?_rcY*+x>; zf1rmNHJ5KtDKouoe4#I`G%Cq=Nl_$`IvZC0C7CToA4xI8N-Z1AJqETL92?&o;}q}5 zGsnwue}De0V9pz6mHd6`i>LJybVd3`%}xVG>7uE$@3S7m{KS0LX@EmH+}}B5uE~T4 z`hS#6r$#X?asC>sT^u+RyL?xyG@&*ScS0<|e7M5cYW z)6e8*;Q(*B-SHx*KPt-z!Jq&Sj-_`B%I83DUm` z0kL9+>Po5CtGbR-@&w){{dRuhl|cY&wOHKK7z&tERE{MaP|o1cJg0|J7NNsvoAPZo zcaTD{@Luo1pJpfr=&Wd;idnv&_XwapH#I12SA=>+10g~6B)s(W0wVpoLn%5U3^maR z;BHHXY+^#X&z6r`$Bfd7N{3Id$+G3w+l=%3D~ch4zU8L~TS;5RT7H7~ zc7o(WbZ|Xw!g$nh`ExZ>QJ6SzXK9?5(`{Z2+?@y~~9tUZqD=&iZ2$4 zw)#9BF~szGLBiy{K9o)}i%XvCX7m1q!XorsB6{^)h_;~om|nNILZd@uzwFxLpb6+^ z#wCb7>A9Hn-1Ub-<<4)6>&mPF)0oy80cJyOPu-NJOB;`X0aN^AN6t)OmmPQySJIDN zOhc5(=vM`OZ^d4B)7z0lDrXUR@RoJpFLJh-QEulRA#n3eB6?v3gtxCoKd-G+tP{Af zGKyhS2gdh`?OF7ZO zJea;t#Au549pHH+``NFM^Jfz%Ritz4xYq-=?^lE`(jo*w+GX>+#NQ+g8JiD_#xSuw zbAz$w_V8;@*m2zNWP3RiuC)%A?DFX zlT!&F=!3~~<7m7qT8X#C&)v1vnch5aIx$eDd*$XzRa0A+SsSD4qdkF#>7R?N*J@E(ggz@%w+Q<8EZzp-ep9H0 zry5-wH&GCQZZAi3&KdcBB&pS>hKydGoN(ZMJ!r5t8^+yjt|8%CTZleYFL@zP*qTg5 zjgE-NSV}pZA=P7vHfW+jO=tQcTZtX*vdzJR4gCtsc5ff`)z|XLMcI_0WZU=?CZW5t zbm%-YS1S^Y_%=mMJtm*ICe-Sds{U_@G=+6a!C(Ev}sSco*E_laRXV?d-Vy`uz#yn?2 zpcGm%7>8+_M&v@)iB1@x&t_&;TKpYpdpi^3%yM1XsR=Xia+1p@!HR4qyQ0m2zRiVz z_N^Xg4%hoRv*@VpKi%6l(WZS1A@IZW?3GBL-#xmUmEy!G3v~rr@su%Mvudo^5z&zI zVV42bEJpn6aMgC94BA`shIU!)4aM|dFQ$Pn9??r8Ta`)vRueK6GF}?-`SP0N>*7a} z1KEDY=CJl7wQ zS6rB2dg49M>kf-SkmJ7?AGTxScoHj|N2;TGB>P`@Oty`%!iyJtNM#t?9z% zQ{9b>4~j>r+Z=f8a5V?au+Aps+?6p??~51gAM@HpWIZ^b%Qw)8rDi%^oNUz=)!)O? zkjYSIFLcSjlRn)51ee!+dJqlkwt7=3XoApTi*mp#?HklESw|_4da-z33d%IZk-q3kM~~K*n~Lb8RX<^x+u{r$kI_SeOSJ7^FF=oGBUktR7|6TZG*5F$M!`;&8|<4 z2n5{DZAojhxp28n`?UtS`HFMvjm(XLs zo;h;E12g2yn#q)~VZ-!iLsGQqG>#m?WIfdNKBr>RL?}HrOk0#%>dwm9Zn+vGL#`2+ zo_g?4#rj|H%?_lACL?_Kd&=Za@vaB^RJ~2HzhDy)nj$46UY`xxqE;wFp18O(;3tmUe$;otG1N z+u0B2kB`fQ3p!;gpQHdqnsJT;wG4e*{(1m%p`G&$xX*-B#Liz>ZL@^xes9YM`=qH1 z;e#ayu>!rJDjkCIajr!~`J%AT=ztRmxt=0`o;~79DD|sp@o@>S6M0&xhgW-DM%&6o z;gU~yWc)HYG_6V=wY!z>-8_y(*%C*?O4?*y6XbU8cF;Vhxh%o`%cl}@R=UJ1Pk>5o zggl{lQG+c!O2i6mi00kAL-kIvFNc&@sF{|M1DUQ)Z3uBWv9~9a`N5@EcHwn%qfkn` z)EM8ZYGut&it{7sgfKos4fDizq%$+BZNh6W9lKCSg#f`Q{Ba?d3zrj}wR5c^1Srv0 zH_CYh!Zyvshj6+O-zu_U=AzX%*)=IQO{W{ITI{(?#D&=zN~}4ilc4pKo2^E-HPh14 zp^W|ri=kC3;^I%sMUjO_xi$`#mr2p>^n5IZ6b(cs2^<=DJto{xUnG?&5Ns1kc-a*vu-=2M%nam7PV<@sMHBK=bCBf@bnOL7>mZWqXwd+)AV`@u8e^MRfE zJ5R?3hbn~&Igpc{svSJ`Ido9Tzpdddmc*Kb#D|%qufjm&3!Sr10@_#k4$t|?v20;| z$&6`WRkh1ENS?FHs;1}B4Pn}xBzdzaG6D=PwKdZ%2;{&Y{Mdw@WEa4Vv}M+ns_*ME z-FYa!ae4e$q)o1`9}mk5^{{@u?&4|Q%FZS|S&rn$iNgi~U6;pHL4vm1LPV%un^M zj!d1bu-#&=8{^WlnM%j8C`YQau;duu6=gRq&%kyaca`HM^P-B`Ks4TS95wJmpLOL z3-YsMU@&)yk`j989AsAjW$2*lb5nElM$06yMa14OkkCybed+p6)%0ly9i=&au2-hA zIa}$c#4;F9*c0R99-096Xdfu=Kg(RoL0Optn z^7sD6G7%2KLyIcj%a(A9#3hdXqJIf3viZe1+dr<{pd9 z5-gFI4A1&x`h|idFl)gm^}Kn>EGRmPA;4Q73`K0NJ)c!Ky;*!7NJPtZ>0Wb|HuKJ- z*-vb4j!%Sn>)sALWR)%7AEbd_dO}IwK81+R?x-U&FFwC#cIM}PeJEIBt_>h@J<<_B zA+@7x-q{o=wAvNupeu*TCH*f|SyEJMOQDIiRHE?Fse}l>73KyEhz|TqGHN8{x)17A zy#{#Ds8!_D>luVRkVv7A+^c8zdP3q|v?3=qi5NET+gQe{28DXb34^%vVPrcvW3 zqq0qDp8zU8apoc_o7*tF_-nnvT5i&LQ`$m^9Hx5?*5RTLPBZ3b`iyimAC@wj$LbSv z-tx0O6RsF6074y$Ws^a=JA4?}J7n7EDb4STw4piG+M26Zb1-J=aYSlF6be%glq)`q zg0!iZl*vXY?Rk0t4Ehb?viG=4NX-;CUz^S zjF);JM#|uq6<;Iruf{v3+znBeEo&lHhdg5}1;{sK7RdJ?8C@$}9=kC0>v-XzK&kD` znKPiRF`Dnug-DUU(sa-=`QidX;mY#}7@4~eyW#0l8VPb19X{^j$K(eVV@OW>GP}!GeKB7ulLaWdFOoqAyRislmE!G6ORNnDbwmW_1sd}Q`Zf0VgGHU zHilq1722(+qNDUr42h79>NT(C7>E(Bi0?o22fq6Pw4L3VPsswxgV|=|8kLe=R+WI>H{ruy92dBj4TL-}lq_-QSJ4Ysf};D3-3uUl6U&Z@eD|{?!cr zy7RyMP?>~WflY1j{_z1S-ypwt9({AqGz-4FVZO-eM=SVlu79gu_N|J8!NE!N*y z*8j4IfA^>VHxKY{ZSemW!y_B8J__tENyx+(w!v4R=%|0dpLMpS)^yXqoan!`y$zpH zl>z7Y-ii3=2d8;W`P0x-bwOl8K`~_S^?)B%9qd2&ig^FZ0e=n*BQ!xx6#X^fZWbgFp~;~-X-WLn767~o!c-Vlz@tpg z{t>)4yvP6U;S4$9Eq%fTF8rYEPdt&05P=BcZ=5&nTq{|J$ja^~cV{&9tYza8|^+kpB9@lJHlk!ag~i5d%f@5+w_o~$ zv+}O&fRh*SI6d=+R|ws`2&}Ts9W!XNSU`C+0BEnjCn*N@pZCkzoj>2*@$Hd)4!{u1 zm|N#{H||-b0KXjwAvFd%k)G_mBx5dw&@hCFyDeWA1GodU?y`4pqnUj012{Cz)P{;i)2-`)cyCpc>uNqDfpqZb(v1stCc zBJ6gvnFB=U`1szHwxaR^Jpfg>rVzE4(75>u0<4PEw3jaw!2Scfa>zn@`+s^4PeCB& z9dS9ux6y7?kNF^C|7|4bOI>FzxJ3cJ0s)+ksR-m;CEyv59_y?RLg%pp!a^5l z3HEmarlEG+t4~d|lIWBH(m-&0Z5fd;jm{$a>$0|w752Ml|yje4a~ zrl1RW7?j8p1a}V~;A{&gE)rl$+s=a6J3rPt8_ni#Z94oc6lyG^dizm77*llRLbt7f z8uTIg)E3n7r9VStw9~VQ;Pson??lm;W|c7DlJiC-U?9V~CWczlUf{K!z~u459ojo4 z34zG)7L()<4L)!jX2_`26~TTzLr5HiP)tAH*z-L=@x(!~HY90wQFTKE^EtKe6{4d8 zv6VhDoYIF{08=2)F=mM1F5ndrp_qW6C|v;QOP=Zy__QvE7(}UfBSK>pU_3z}9QBm4 z9g}pR&ASdHhZ>0P*d7S6>+)TICacqNsP9EsjdYv*bWqq_CTstYTmJ2OZgg{-eEt?m zU{U*o3~a2*LwY|dja5?HG|Oj0OhBTs|5gml70g7qLlc0JY=w%Ttt$-L-O5H?QLlMU z>f#^GxExH3`%??hXzS_FKVuDIpy7->Vp^yhkmYsAgwy6##|{aY@>ze_pY`;lMd;7t z1m9lDkO!H>deoV~y&*rSyzt9ekag7oEGzlB2^mfrijYHAr870(=9a>udkX(v0@?fx z=p*)!2-Sw%upa4zizOqY4NUIr(Fh-*DzM(V(CM|lx)Lz|hDBWfkt4VjBeM{;HAAo6 zQ;+scq0fjkXyW1u2%J4%%nNMX^NmLOV=Vj2(kmAMcnPQ|mi{5Ao!iEWjP-*CfkVz# zFxc|Op4e}y>^}wNyW1P>LG#;krhaG?+B{T9IOyOW$%Td`-0CXQ=OkD%_Ix*WCBsZQ zJ?S9@P~~onpnN|>m^{FAH`8(0TE5=T2FLn5-fZ*66TdM!Y%t!9FH(a9u&)`E`+vOy z{J?VcQ~&y!QzxukJ>nmIYN-KErHR`}$b`~im}z?qqKQsF4qWVPE>VK4n%9$-o~2_0 z+Yw7PTS?EzRc?pD3{DmN-`pGMlofi`!R|0XK1SXQRdVX0zZnM;Sjz|TLdeW-jb8IG z$b=Hw@=k7iwtut88=v%F0Ko5I0(IODYL4pzoqpFDGLcS*XuB#DJfz`Th_55N@BcvvU2_SMS!Gt`!8qg3l`F{9^7QPR>CLZkVfu~-ZmmL; zcsmSXjZet+!^09mDl%eJ&y7+bT@?JSf9@&;3Y6i+!N6%ZR%G^RCuGP3LBL^a(X|W6 zQ1D(g4<9(uMPSh-?PWIqg++J3aSVvbJh3q{8dhzK#x^SrSHo&n4n~>9y3~R9(iR1+ z%Yp=x^q0%pzuo6Xx+!FScLXV)PzVrp38SZxAx8DkJ=8l#MW(50!{pB807RfG2v%Qz zuf7Zdwh$Cqy2wb^5^gTNFi7D2g&Sc4oz&!$H&hl5 zs4RHA7j-|Lz|Iz98Rw_#6E$xlJ^G{!=NonUO=rsw&T)kuBGQhH_of z^XuYP^6J;G7wA%AFRrhxnlyx;3SB{G>Yzck%3p-jEwtL5nIjo_=H?N8&8&QZeu5MJ znSge4uG;iTyH9fUC7(CXliS7QyLyTpBxCF8|Gd-x-1DD*x)-^Lrt8JhsY8D~Cvwea zSD)5&&8W|ljZtFOakz!a&gPfbQn!*70@+XaZrM5eN@MNo((uQZ*9sThV5atsxsgU2 zOEK%Nqi|JGLFisUU2LDz^s9skx1|qf)wgeSCaoL4nnk=CmhSEvC!Q zToOC>$(;S|zhBIMyULuqL}+O9ugn>X{;(CFT509w<(tzrg}Tk$A#*u;_N-PKI(_dz zGz+hq;_KU+Pqgdi{C4MzO;1Oz+IEY!jN^yIY_Pfnqv|a$uO!~hEYSP);6aPvn)^Qo0IER+r~( z$nBZBygGx}FO+Ug9@TI|aip~%*t9WHyRCRz{&s6QId95TL6*ySOR89}xo#0m9ueBM z`_ISt5A2209v+!%v_{~EYbq@_d#1dCIF^2StZjcPggLHP?}%Q#5bcmJwWnBX?nhtc;57hcD3KV=vY`I>3GO=mq*iA3BD*@KeUDjURp!`N(OVq8hvOPZZIA3+I?wR#w(!@pD4$5^mz-%>LhTVlLf<*3A3&A7fx*$70K2GoyA<0D~I- zFHPJ~9rzz<-n5O5WD^a3-y)#5s?G~*t1E@162sTDH(OF3n|Mt3m6rN9s)GQUMdXr-yF+N81GFd@QgpKHz)hnM+by2Zee6KU*Q4yUWNdsRI4sb z$X48pI@NnMMfE^^36v7b7_U_v;@2)kiH7Xq*LW3Ej%1yI@#hcZ|2!)d?A!(S zqY23fHf8BcM#y@VQ*^Iq>1p5g_2qV3m@FJA1?W82W5qGB02)=Y8X`sN+gt}8M#3?L z4Dw}nahG{8Ax9BqD1LIeAMV{HH81a@g4w&%Zp52xIr#8QEP|1C=Y zxXJ(a=DWAE(R#<{g zi{2~|rzyR0c-Z{OJ&wE6KV_vmLR7k1V9{#cz1~$|iMYRqdr#Pxn)a7_nDo556)*}^ z|Nk7ZpZv+k4+dC>CP)wV?Av&;yRso<8$41gkPLRp6gl!yI`dK~%h`8o13ALZ-Pxv1 z)GxMAK4bCmT`o~gK2Zvn|Mswgn4h60nC+4%)Fd%JJIErjZ5~U4QyD;AO8>(M86eA?VCjrHl~T*>L~CK zDka$Q-&PvHUx&PXxKE|G1ZPb`8Fa+U(`lEv7St|5b)6!hUvj3|%`fhS(?>$dAz?G( zGjP`m-JVAKx(cnMzyo#KQ`$0h>#Oc;KS7S(t5N@H`o4^}BwMy;eJC_oymK*--MZ?9#(Bb!<7CH&G=Zyu zLR#6C^fzsLUJaOgzPy^OD%J%DN-|R6)PE7{XY{={S-X4PE#}yG@#3?}Ox>b4{rv_S znK~vbJ&zBHoF3@B{_<*PEKB)kNUeftH*b4)XZt>>tW!o+^dIbOu>tJTuJ7`1w)6;! zo7DaCAu^m5tozB%L!!<-M<5!3*)S&u<)-cw#FQR`j5gPPSh-e{O~(DzjsvIP%t-P4 zq-)veb9NbQ-r7{tZWiixc!ObilTfTO?j3$+Ol%T2Rwg}`zXZ<=)$O@-GV z;YiiPHgntdm42v7qiMA1EpgG~cNl4~pZIuODNIm5fAWB5Fx;RXhK5W#QaYwyOn{e! zxA@}R4*o?+QSsi5cR`0Qs#XcQ{{9Aq+Ogx=<3nN+ef)(bR0)~=EI;O_8=v9drX2T- zpn5yCV{&KxI^1*?{#&L8o~PEp_Xb0Ps$A~AbW|l&pgGS>{lgSG_U;y&BCF0Lkjp;l zB{-=-4SHj|Ie8Y4Qs?UVvveEGPv-b%__~J`6%~n>Z-5!8I=8)N8gQ;Ec3;Z<<=AC8 zo4(TV4|aW}F3nJF?RQ{5YZnihX$@sLQ6VsthHlH7j9U|#(9cz5A>-+xRk-wg~X66|`=bZcAd+oK>-aAuq8r3(E z90cm?W8{R78aJLb$}8DILC4?dbnz0`NzWbo@&0ZNj(Z122dmFb_UZ80Hl-Q((mJtF zUy?QdRI-t5_3C@Lp}hW#_xGIIMENAW|LCB;+^v8A+cc`I#OXM17mnCfzwZH4tet)Z`lpj4cl&R+b&J zdF}S2?{v6T=;?W_^v`76sBQ6}*!~u@z`>q=uXR*xS}o65dDpzTyL~UpYRlXR7bX;) zI3%=7D?0OG@2vL=VY#j+;P@p0FkdA9+oB_-fAAq44;<@vPI3i8ZltJm11hO{Dni+s zoDa-Dx9stZK-eh?PM?tT-X*#tYd9oqw3@V%O9I676%)$YS-R4-l=C8b+>pOJ}w zfToG(3tnxQYdu?pky!Mro0Njj$`U}}47DBF9t*e#cpqen1gVg--O{PQ8saQR=DwV81x1#;|o1}addLna20S+JW;FTP@bg*9J@2f-xX(CnccYSBPh`4;qr8Eas z-u+|F4l~dZKEX1-u2oVv9n_rbg$cye+cqyx`|PXIxz20eaTyhZ;Fr%c2sWp~PPm`% z-js0b-vl7Uzwx=<*b{rfJQS79T!!uWc}_5WWDEpvro$B=r)D+g5fxN8V%%7X<4XR< zla?9vg?WyTixvtGNh@QjSWa9lUFID`SW!RMEKXZ={=Q9N-G<~E>F2`- zpO^aMX#LmQ{1J+i$)l>`mN&!&#d|KnSBTTU-VObjxLb zOKW91__djmmt1CTK3E~Z(al=)_Kyqv^?4!cUGNwPRvBhbj>}Qpc~e_SUsFY2H+BSj zJ6UERAL#V2_DbY4ZQ&;1K=T5GDFJ(^r8-0W8%@q+TN#v@8{!@j%+WL5vMqXgb?=M3 z`|6u>?JX%I%I`BuJPHoJyM)MfLmH8*Dz=Z&$RIif&lyx>+?uU;Ksjl?q;$NyoEd<` z{?iDwu*SeL zP-GZTJ!H0MEqfcUl!%jEdL@|8_B2=oC%hWZj8gwY;bc{6c_(+UoL&l$zJ&ONDqqL2 z8L?Fyky{rOFcC^WWSWH%dD)6@=t!h??>fHz`b1`$Y^lH_vBf&h@CuA$T3H~?LZ(Yr zyP>pX>jUdNnGW26XC}=@W6#9i*YCaZyOQ2>!R^J>Rb?@9;l`B2E~RI7W9RqFJ-If- zBfVy%C2RKz^3C^dQ?ofd;srA7tBd!m`5b zIT?IIlC2ICUNr;nB3*!hSsTAWLsD?$wWNTVe5ts3<^<_ zW84H6JPt)%^y19E@+!-|nU=dD0*-<2W7^m!i?2-X~(Sl*5@hl^qHouhQ?ky zcs}YU1Dn!J_z&I~>=jx{8QUQX?opUsd*3%iIgyvoPTk*Q|LJ){vbNt7(c6LMiAE7J zp<1Yv4$OYmj}PlC0l*A;2H8~}?A3Wr_hQN$g+wtr*<00}5qbLIeVov0_oHt7(;AdN zi_1ls4$$jQg86X5jDjMOzd1~rjxDXT^cyBeRmnuf~l z67NHYr9{3nMC2PU9_~i%TMgn`?5GJy$-WRD?n~#(Ug}4y4V?`-sLFxiEZTeU)qE}Y z-S|ejo{pbg^EIrLF%zvEQDVzY9+>=PTMyLaWD zo)?|iy*K0}Q27N=;!iIpgx_C@wBy4tETlBSeFveTZ|@6X>v`>&mIsg4b4$&t~TdsO*uU?8iG9ov8zUB z03=cUM08DAcH@D{3L6p<5^r*efr-bO#xL`~c_mt=uK)EX{zni_LQpwSFECU+Mv)Z=Fkc>Sc(M6|GuHn3KiHVysGNCSFc_HKnF5lNuAyf zmQZL!HFq-rcb8aX8n4;#_^!zqcM~BGKse3OPbgHNw?G$ zK|Cu#_~2(%NWCbfTHxY*Ci7PHJi&)TPH9Q1%6E1oNXGCqF-ggK`aRXMlK_eWtjU7h zsh~*xxlj1i=Q_`2EMK|u)=K|iPn^6U29uAkZU#$7()~$U{WnbGrb3k1%D{# zIo+$XM0(S;nlCrX6g1VXFBxXC8HEb;>zm)UUiC?u_!C%=Y@w(y}J}&VaAn zFXz+Oj}C?jUpF>ukCvg|Cg_qoG~2sx9x8c+bTF^41TDXvEL4BSvTXl@{!k#&j2hk# zZJ9l$kn_o*tMaT_u_rBy*HI$t9MQk0tEsWMcRj1Yy)THxo*AIl9+OomC2O@-@h_!# zy8%B4i1{7Gj`~~?!02VLxhP=wC!kc%W14 z8F23fustD@$mcuRmqM2TY4PdlVSc+&A?ZilJDW4jxXwuq8OLdw?T(}1Q=P76*MD}Q zv?XK=f6z0lKKU6~G$QQAJ`$*-^bwDxeqK^o*o}MlHdqdmQyuURghTeDx20i>Vvcw) zzr8#pr2P<(;x1XZi%pF|cn+|(%ENRzHDr%H2)&tgk*6poS%Z$6a10QHX?2to^DN^O zCcl=O+)$m)vmFUBZh2nCua~Xodr*~*EZwji|1Uz~?w(f*MQZQz-YY|w`JPpq;=N(? z{sl_}fp;{#zHHj8h-g#-Ib}P+)%zwNBL98zv^T1N(j}|tcRZb=1N_wOY-POO*~|e2 zwpX*^V}+~1mjt%3YV3oZIHOqyt#>QdYIsL z;yqHSh6EJ9zxxt}vLRO#mOe5Ru?_2$`IcW>kCK_`oUpGSo3<~ij8ecl`VV@e9WOX8 zlx)asl|mHNsUfpQfl-Y_-Pd05P3L$Wz3aRjDDPc-w!>>R)n8^IqO-RuOpWC`&%FiL zGgHzw`#hxPb0kTvZkg{X=m_+&HG%^?p^n2mH8&CGlDt$`040OSY4OnKd=ytvhv@N+ zZkFGj9_;2(T6fL_nhfT|mFG}m97M6bnc`TEht18p^fb#+G}T`?u_@c-t2e7AFCil8 zm+W?;R;75|WS@6Ua{{)MdnnSH$=5bJ$jM#%RffF^6Kb4(ZR0rxj}n1tA`R=}Y~F^a zU;H}S*}V`S9VYnhiJ(Ong>dj>s#{JK@?+I>RU0n|RThN#?p22TcR>yvPwPtN`c`ts z#k7(kaq+U(gD}lI>Dv<*8`u9&)&GB`$NtAZFoVHmfTH5W+R#p1!HpF0S_LiwR(lto z<=TWl>+g*VLwb}56pCKSoNj6K^{lQ)aRX~A4KD>bImh||S2*FyqSRxDV;#L{`IL|< z7?-VD=L1H`|6b(#8n*ZJ+~z`)65}u&h3K!Yp|aCVy?B@Gt_Qt?G(|F;aM9g6DPsDm z2d$+VD$Qf-kr|2-qBV7<%36UnIT)J`onDp==KenXcMAQrvAbtQ?S@+7J6jMQPJ^(M z971M1&nsrophWTZeW;)|K#dMv4MUPmW8J-eXyc6d2!4T_Mu8Lh#m`vOGyK`YjT)M7 z42R9>|Dz;^|KeS*ro8dD%uMsMfX@;L%X`3M5-yTkD-UZ33l}@Qq1JYiBcz4leqLp8 zTaxVd^Iyl9_H{Z)zkSHOm!O@IyNeT&g&3BhNvRblI}qx=Df;KFzNE zSm*c2{J&n?fB(HPXzM1quD4!a6G|`Z2QH^`XjayCuDiyTc;#+Qw2U8-5bc{<6@?>1 z-XL9l9{iB{BusK>PrOcTj2zQwANhdchE&ihQQQ624b`UEj%ZChU#Y_RwQrWAV5K3a zRs3-&TAIb$$9i8c^}MGo4HYaP%jmC6${az5*lt~f&-?JB__K8z`5))YGh{d;oQtrm zl&6OS@UCEL7-SaLddx7Gi{eYP39UP*QNs7Urb%m!^%0>RbxpQ?raSDcWD# z^BgmKEjQT2++OKn?YVAl)_DQ%2GU-{1A*U8vgZ%r;Ip4WM%(A=v#^rM1q&~f0i8N3Hr z>Asj}qf*D3lN9Dw0S>SXs$IFjq-6j2WR1-25Y_7*qEopJ$`s-2wjVusL^jULh)a1W zD$dAAEE&>H(Brre%dR(fqskJD^cjxxHO2Ya1c7QP+pU*x)p!3wc_8QHh?U?1X&&>L zd5kS6L&?mD?6@&s{>bG7O|$el6TlX!yB_vsaDedE8|tfGU$p%?EYtHo_^@05XcwHh zK6nuU1xl6+_j7X=(ogbL78eTn>6=X2kJ#|`l z;>3wh?$lbNvwVGee&7qMdP@4X@><2rXuSR(f%w0DUItd=**ESE2S;K%B`H){RZcE-RiJCt&r@2EfE_J;LV9n%xrdPpAvx#E+m%8Dc zCO1W4(j?PNnzb(Q%L_MDr}UM0@0M!ha(b+I8+!O|`|(d3m80uZG)-UH29j^@5V-X5 z)$Vg`$Rac{4Kr!s2_7UxHZ8L-c+-<@yPlWAYgDMj*JbFZLcuUl`Chi^vjM&plX!fq zHVC45@zpB9X}3*9gmWa)4Qk%-`+y6rIo_ynSxK0LW}W%n(Xh`dE&-{uziPA%iKI;% z728w$=T77Zy9&KNkZWk0SW?@X@2pO~c^?CMUQ>(vX6ZDSdAA*zv=n>5B-KI}i^uF< zW#V*h9t{+fu+mIiJsffpHH+>*ePX^jqvabE5djrDlIR(pIgUa{@UPfE%X8y5*8cy+ zMgIm^{FRU~IZ7g_A?_9FdeRYQPd32biRUR~$ z>%O!C4z<^mUaqIeM1HNa%BZW1vw2jP5^W<|my|$LCw`PI(Fg%gsJBgg`9gydTv>G6Q?qtkbz1grzgFj>2L%|<2qVi|I6_n zMpN$qt|=&L`xk+iIA3VcHocxgThnTay+*y~>l0L?auQc6L`wyI5zizhMM@BcDjx98 z0m)%!g6ZWlwK*}o#8xWh`N_L9gcVOAdZz{j+ko2K^az*ZK>jSFbsiFfT6~zct>(2U zX#%dLH<3y3b!4wmF}iE>pj!F`FY1xVO6RUo-S_psUYtN|7-O}XpS`7CY?0b8>ZoIEYVKm{=r0fwaUFbmV9Ng#i_3PWp z3JaPin(2lQyLNlgaK3f&J^$ao+OM3=ut6Q&*Zb8MtIF238E9Xy+r-RYq%R*__DL!qf& za76IpJO9dp?I;J4clj*3-cZcI!&fdy^Qdn4%xnb^lT?p}vndp$ZM-rSkvl)l&rAea z8nB-TRd1*)G;e%gaL##h2Lkb$q5eosS8F!gbL!Sr(uG9*Q`T!_gc#tP{D6Bgl%)B$ z8173t8@_v@ry?`Kl1iUijzZ#MMM&$HNB;Y2=>wlqcHnmA*tZXx2)hQNGEnd&n^jJ*T<)Fwhr`2?iJQ{Y`Rxgvm6K5*EFcJHN}iENW+tEletu`mu#JZ-_Lapoo4S z#8q+an5GU0ji|$NXFOJ#!*OchTX{LbMx@+(cd?Fy;f=$C)bFR(Ik?CO=cF1o)DlH2 z2gPM%!|A8yNx>62+0EI8wu6m3X@t@bPwrq*OS^|8(!8JR#RmfELa(9<6KxcoWtQSck7!g4`B@%8zoE>NV$Oa+EpvUIXn7?mhrx0#2kn3c#U`@7t* z3%|U`aA&dc#!AVdbLGBBf1Yc62mlyxJ<)O!>@%-%ESEyQqC!#sYtF#D|^Jzpg0n;!+7YiUWxGkh4=@_ex zK$dA4HY5$%xFo8j@1m-`GwJrk;E6}z(EM}H#hCZVs80+U8Z}R9yV69|(JNVS#3>~j zW>=x`Z!A4xxCCJ;g$3I3QN{WFwdQdiT2pH#n>fXng~ArXPOF+OEdSPLzsV{g#m_Js z61Li!JS8y*jqhA@))+N;*G?FipWzGd_djY9Xf;qj^fcDN4~d`@S?!$;O`0Zr@w%hR zeBFjZ4V;5kiFbQjz|0?RJ*!E3VQ6?nZ2)|GcSus$P9+Miy-+yj9}cwJyeq2L*K6J- zddt5@<+_K#)S8)%iP73t4QzusMHz~5XEqKk4)o2`6qXdaEh}%Lc~dF$thF+wCP(() zGAp7G;VTkVNk*nP5+&gc4m@gN=qN3@Wf8-`yRXYEF3y>GHTSNsfhmiL$!k+&I?-(a z^3^=&4FQYVFdu#^Y&nFTdA#?hWlp``UgrgvygdvILK(&%K7O^Md6G_knNQ1SDZXa? zVWK6LKi(6w~$H{BmzXuxLEvv5z4KqJ!yD%dsP!Er}i; zN~F!ygo*kq(0xyb9&_G7FC(a+fA0%aGux$^$e+WsUuLxXEorClV})qxhbU{s3|i4L zE)Frxte)Vl^rP!<@IEoTUYGKs34Dh5*vHpWqY8X+ivX=rbN%SSq;#Mgdanl40})i; zwP$7Ld#rD2$|{6^AOfzeu*l&n`NQ?IXeZnYu5Z0FcQ)_UK3u2E>hDL47mbmi_Mcl=bdoPe(S!;!&Rvu1#0}hzZzQRzEp4!V5 z)B)_Yika%lvGSt%U~isttECMR2q0*>X10qnh@ke&IJe#CnWmcRe)XnN;P_qkERXM09(on` zLXwt-9R-8PHCky@0nDHVJY#FvudcjEctB}x?K=~5k8oN+&z=(h`UM_hG%YC`*KbS-bAndhU0_W+6h*Y~@PM3wi{|b80)!jUWowhd zrg$qjtwKC}ISUiC7aKPG^P7Jg-QtF$6)-vo0B=Gc`&)f{s)$i1Y;Uo;viDNXPGOId z(ax7T1LEFoVlRCkGArBgeZz?G2SC@n)dP+%UyTZCbPY>FeD)=yWU_nd9d6}uNaxKp zmnh3;vM>`#-8*VK+#($%cl$R&{m@c#0k>Bp>8<7 zDWDfHh^Y{Uz)gq6miafmKFYvQIG+Wj`U&kBO2*TZC4n^e>xQ2uJ&y6PL0M&)>S^<& zt|KN%5aotgx5qb&{NcnNTizp1aWCYC<|Bm*dK1sd?+rGdTE{DMHI;YJW<=2lwHDmo zSDmng%WE*!$go&*s3~6fYRPUfPp5Y>^fmvObr!jQ#zo;s2ZTP_sm@u;K1v8fU?~of zs4KIpG}N%Y%sJWUnLcYfyMwT1TNTzdoDd1V8my-9I}3}zTus4!&^Ak!XXw|u{{5n!({I{<~xakq!FQ%PR{UM zv^ynPHYswUC5K5QKGb$8$VWs8m*K)^f9eB|-IRw6Kld9)l9YilwOf1Nus02$?g?$- z%C%e1_G^-;Y1+Y%K8`fxFK|RCKCEH%#Tg1m!+(l6t=fTh0{$5WF(p|tL9`o3sK*_P zax~}=x^5Fwm!#=UW^ZWD4UHs>WGzKM9=xoIxeM$W(}ILsdE?_ zY=ZhZp=|j08*N4#Rg!hN9G~sEBq6v9al!q>CkM(dEaAanMy zt2{ii1V*~2Bxrl+wsn>^|UtR!(ocD&)A0XkD zffg=r$G@e8iJ-!iZMB8^g!fz%;vVXswyvfo(UxNS zh6TbIia*#>d#6Jt&TAlR8i7PfK0rwt@;+>k*$kK3TPS~Q^v;vsAnO{ONLuSyjt)lQ z?-OlTK?T)pfuXp?8?UCMf1981QkBU0X8@&w2ej8W%e^>_!`#lc?j4*6ulUgTR7Yw7 zQJ)RH4O|ryD4q>YRN=5aK&0`PR)DnVdCvcLG!c1lIlm_eaA2rzeturkE<@aVS4PjP zi(wuPXcO$YB;lN#AeixySr~npFkuf}ntBRu_Kk8<*Vv=EFGGhz6%#yM>Q#XO6$2{x zlQi|0En6l!GID{id7vdM0zFwv3uBkjKqI=rgp{a}`y%2xRcUF`YE$|V=tcR0`>7+- z`QkhYaK9nZWk&GHy+{uey?6dQ1so>Xr<$k~3xqO+3}asCXyY{EEe)m~RcILaQG zH=I+xnuWtbF|;qfvl#&|kgeZ{!2tq{m%AC~zIYPt21_32Su4t1&3vbv+AW0B0s z4{{X#KHqHMf!^zFspGqyWJqKV>r(usQ)p(bC@2&RGv$YN)S*eGCb<5shAGs`0QdiO$}!~XNb$J0U-oRxM2_MQ+ zm;4xG{kn(g7fSDUi`jpy(FbvyxGt53HKXQfy`S-<fIW16ASIC4-KZceTx4 z<(%z0oPU(CJ`+_%v(A7HXvXPuBYXZ4bkml5eN$QSWa_%xx*gmbl81-0?|9VjmGtlU zYDxfy<4qWw{&q}b3B5FXFn~LatS75G>K8qUFY(IJ4K@2Iw8)yYABKaG=+=XNmoBiE zl^kJXKe|oRS{#6^x{IZpOnSXO=K^<|dLar*l)&C3@@UC`^F{62dfwq}*@+lNdF@yDHAsR^pW(9LFrg;s zJew8{y{vRMTFnV>0?$(V$Asp$zzkFns%?7x-vYQV|j^fX9;c3&jc@aQkrVT_bv_rt*$Z1Eri3>x8128Kh=-0%c z=P*Gtr#>io)92LIJV#|H!?e~9Y)s-bV{pfjr1phgUGev*$w?cQ%@M)tE&m>$f83Vu zPci<$K^fva+Tk`dH>Xy4W+W3iDh)EEcbxMIws2+UXsI)DY} zbbBkqIE)+F&A3f{-j8A<$|*ECwIq3SnQ6^{gP@KSa5^`RO+JjUkr2ebS8-j#N!b4O zNCnnXCsBPq%&MK=vfO}8Gy9W1i*+Es{WCzF*Gqft*NN9Y#&5Caf4+7!K@xqEX>(Dn zRbX%N@{?LEl4EPm4kEkqheYE{kAr7&C=Up?xJLk8jCJU-xe1`8;&D3sSpiphE3P`6 z1~13O(WCDJn5$C%+V2YJYNEycpjukV*u&W`L(EW*E&08cK*Qw|>}O`Ep!Dy$5rW;7 z4UG^d$SSmQ?W(>wBZf00Os8s&u($)z`63XOj&uK?BSfV^jo z@=f2v>$Y)-pfk!Ks~&`0BrILN)?=|}iT)LF!k#PEQ2jn1&3u5AOY&KE0RsxOS#_gQY$BC2#kex1297H|3V`_;YgvbLaJioU0fo7;{KB zt#oW+o;y5?YT6uR_V&cdN8UnjLS2^+BrXZUCt4BOURr%j+Yx|(IPFjhdGgCpg&Mm* zpk;fvggG(EpyLLtWyn^Y_#?28_+9pBC0sY#BhJ3K0)Hz8y);|q#>(>D%Etg0Ixn9C ziU)Y?$0PJ(j^y8gCGQmE)K;y%s1`x$7QFHsXv)5RthkAD3SWV40F4X>2r)kWq7yUJ z6gRT!w&#~#R@Fg7)6K5(Wz}q2(ouJkKu9zb(0=sCBm}qRI}u!#Rk6lP^GepkOL9%` z@P(3&2PcU>6`~m!iB%xP6;wLmWDCs=&k;5ft3p(Mp7-F`#m}3Pg%-b+=?kTScJo!< z4x0ecUG|Li*cOdkJ2`}MUC7d&$y`of&9`w}xY1?5geftjg!eLkjQ`TVzU&!#Xq3$j$T^!j3=1pgHUReF=Mj<#Tk!3U}`_ieZ zZ+Hu*?EA%`Y;Y^Y3nu#8VS9wb9R;B;eoSLXSE75u9&7xMj zq$`lCfGc2ojO`J*+g8d-^AnIGKZ68e5|X%g^i7QFuc;C{RzuL1K&5Y7F*-4Exbp)d zVKea@G>vQ4uAQ{Yg)m-*y0pv0wu-P89N92r3R0jx*Hx-S2VEW<`jre4SAOx610Nk< zKn{5KE$OIfOYhe>3}4#3@NLg;^658i@&A1LfBe(SW^kxa4fS}{?B1}SWatE+)7R0; ztmOu~U;nPCZ>)5~Y@}Q0`AyKuYx-h{)?{Bu8K(j`B8Pa|)a*KoRuHlutVn`%UeEQb zc6DvmE{4Arne~Wi@-(35t$d|TvoVVCz62?-TNtu2(NKmtE%z(4-YszY(+98{g9?-4 zYC`wc$6pN`|JND%_bEEUiTFQxv#W8nh$w?GbyLc~hKRej4p{ya01IOaApl73n*`UK z5e@P}86QY5r>%JnK}Mil8MAwbs^cw$y4-~Wa=h)};PyaVGi|6WhBh{`Z)hVuQz)OU zblTjr{Ltwm2hPMW!0L5ly|Sk--wqxN5n@0D&X#Ar#Qi-t$*ODy>dTjQmV}A3#J~O# zshbM*>UQ^|gCwh~-^|v$@c8jE_HerquE@~@8@hD9V_!R#VPc`}ps%BIuuZE8F;t6( zbDp|A=O#FJWjMIWGPgjvOc|^;BHJcIjv#*kI(tg46il8MaC?2N$zp|GPWOMbLTW2s zZUF9U!0N!%e}C`4zQCn@XlPqE_JPLj`DXJ5{OSPw>d%K?wf*={z0&?&9BQ-wSsWHq zldqvVum}9xwB4D7st5Q;vqjcVtlprIC0YSmlf2RPlLZ^4&zBoA4-j|{KzvNgtwsP6 zeHnV^8zuTT>CrEa@5Ot*>T;%sKA&~}rzQ2}T*9={qr-zAwz+XrkJjQDI`IrM3a?3i z)Co7ZNHw#qyy3(DkS_yHQqt~dzO~B^B%nJxc&fv%+631Pr;?o``V@(-?o8#nVmf}i zdmHu{w~wK1$rsiEuPNN#Bb>w#n>^DK`*(ojSqt)O%o?^1{VQqk&Ma*v)Kg~sa+|yl z6eP);Qflzak=z~XYKqVO_~oPf-5^^M*Vniyt@KM4P{4k~(G1NIW_NUj+z04VrQ-^- zUN7ad&s&U`cAyr>7;&XF$M*KhcZny#VdDlLdwM|Pp4Z5SR52uAQI_C4P>KULAVZr3 zONRfE`+xBl{|DY@@FjYDIk=m5c9@XbY6mn$)Ec^ zF@Js-B^`VK&y$%T5wpUE_k`Gm8nBIMTD}kSG1D2|;k*A2ou<3}Xdkq44RdIuK(Dv~r*8YMx+eOgHi)(k~uzt9A&ShT^dh&`m^mpi;ex~l%gTa z?$QTh#N-b2b!7B>mG2~KD57~3|6AAfl+rM>5_atpD0D4NEeJdJ_sR@Q$k-=5Qq-1# z$ol}Z742G*LGwLneY`DX#q9J58;sTYI!qLmhWC_~r7ywLJ3{#NX)BgR3!zv13A!E! zUyxP5>8mN}{t<8N9tz=LismFX(LzVeCabuJ28-d%q45aOL6`#hvMY=EM+6_u$`LJg zQ;0lG(A}4EYN1Rsf&{91s+gOI(>mBC!T^*LBaziJ!e<@mS;5^*dQ~2W{M1l%`)QjzMtJ46DIPeSg z`L1%YrlEV?9_u^~dSw6?*)_X0^pDFNn~9iTm~J;MgCC9&M=V2)>BX@&46#w~Yy|h# zNZ!n(Qo>H1X++Z&2Pa5(mUz%nmODTGr2h*d{COpQM|u*oO*fKQ)6R{E+^Y`?Irsj` z_kT<1-5P!IGcQxA*|gH~2!SP1yTB!5z&SkyZ0j?}X;ZIa#E@uoXMa#m-ul_nsBshx zNu~`mm`_5$1>)Ya$)fF?7^G0ld=X}^6DLl5w9f45b@C)UDNR|^Ffn=hmOo_nn`yVi z+{mT9{8_yGlc9{vJ3A&wt3J3NJ-G6?TBxgm`Oo-ukeD0B)?{5Z43)>7Xe37~>5%l; z2i_r(*x-W#caii<@S6AFupD!&h@s<01Njrd{*R^_1umN3hiRBnCii?pubq6Z-K8?V z`eg0z^O01=UVNjp1670;ySFfr(LNx&eVB=iWL<0-@GGJI_Yd>$l+Ll!3{2UT9xHZ< zZ%@`@)mZucQQTzRj$d6_irE$>w>KYDk=??kWz5{G=P1XMi%r8+9ec z8RR_Pgo%8m8zsQFh+Lh7GJNTX*Z&;P`fu#{-~Y-jh78W&K<(Us;C*sW>@2BSKQ53i zH^}?O^YPk`7t*+~GU*P@>^u_EpifXBOo9Xy+Ag&^97Xsz>KVseLv$Hl0G1?kd)Y;M zSoiH72);SZfyjVw!3hO-1P}g`i@Cnfz}b~m|7@NxBEAY4FMeur_z%cAQB*hKHu4}|Vo_XFBqR(C@NATsh`b7n=xeUD-!D8rn# zhBeBGYK)kJm6rR4;AwIHGZJo(tWbS+!5d-pd0scd*?|iF2}vit8@_XzIBJk0MfeyT zX|PQ2{tkXScC{~(`nL(s28flhkD_AA4eMG6))uPXlBQ5ywnU-)zWn3owWMid;|5c+ z5{d~bazv{dO~kL>|H~t*jnUk9O;5mj4TWnEoG0R5bOKI2_p8k1Dc%NiUn=T44OZ6= zW)G28$!$47wovV9ir9 z0#iQ3rAOzbamCH`?pIf>_l4QOKKC>P#Lt+`H`bY5WpSMd0_eW_Xp@MlQxzQobS#dH zKB90gFo5w-&mD&B8i|wXYrR?I;CGfdqK>sx+Qa6bb-*5=68Hj6{=I4UvJ^ha(Xf5O z3_DlP!vltdOIPJu{EC5lJ7rwL%^z`ikW9Z=gu?LyEq>oKvI@cvIqYL6XFJ+)d~9MO zHMb1qjoB7e|Vu2zqGm{4);S+vWNXyYLNpi9Bj31urTrZ|T>|>tIuB#xu zQ$nUMHhlT=KRA&$yT0dgppZ*Hsm6yd*ZlL#3-GIe|8D^;1lMJp{P;hJR>Y)6K)rCy zYaPaE51ujn_zyijU_Q|;g-N)6P_~-eGSRJoSq>b!r<*N5N}Pk0N*9zTT{3>?c6efs zJ7rmAqPP-SuQ1xk^Gu+dU@lGo5QKg_3SVGIAR@hqyXHQj)&XOoGSR6KV|iV+#WwhcF7G>N@Ot% zK;M1}o(y6x;lY7@qX&tx-1L=lN;BJwLrWtzoj&nER(QjS6BK#9V$DMe5 zAg5x}qr_Wc*EoNGXznkhu%$nx3MnrweVP|QC~gg!w!uTQ*=PI%0%Bji5*dOUX+)RU zw}VYYLH*T{%B93S4^jB=<%bBDf#bD)I z`Ii-hYJxLb1G?Y1BG$+qyGq)pz?;nF9h{i1#u*rB!Xr#!7KLJLY%En$IxKh0kKe^S z64KHNk(ZZG7%pD)u-~DSpb}P6Qt~$VhHAk^f}00Q-8uuQ#EC0IJl2WCoVSc@8w{zQ z=Fqy+zGlzfy+)7*sH!1*NuN4(s*={d5az;gBwm3Iat!`|h<=%=%hsD4so6(jnZ(sq zRP<3TPqeEcMP(FK{Cz3l)`8!=vPYDY)LOa&VWYqCX?UIc(Z=KEM^z5>|6qS&T1i)} z+fj*e*OS;l@S&|2A%N4m|4j3gb-Fo-YPDRur|o5jJF_4x*C}2J&rbrO*o$WTB=cZs z(lKZX7jq7o%`d#V{#XoL4{QuCjgs@C3Kpl5Ne1?%un~;wU3x(+LQhyYC3b*-a;+|N zL&qz0{(7ReY$zgOeUDhEk(f~2neSi0`sY`0BxRb1z{}L3YwN!ur0;@udokW?A{L#{ zyKIAPH@UX~P&t)J zo?FH`h9*a~<7!^Tl(qd)jwxiFlzZ0Sy8E}#Ev6WmbztmjMda=c#@~Om-p?N$L`oPJ zs6woBS~J*2vAXYBckT33Oe$>b*bw8+4Vre zA4(u~Lle8`8$Le1<`F|g%?4cP_>MaV<&@60W?OS;#==TMd*nS7ZcaECA1`4NZj2f6 z+naa4pV}pRy3pzlvCM`vaKj@CaS@Uqxu-a>5X+MiuurJ?%OY667)0lO>~ni25Y0+W zG;2Aa5r)}F6u!Mep;GNxI2wF{EGzjed!6Y%Auc%j6RV5SH6?~~ToO<%!`Mt$gVR2=h= z2Kw6zT%Gmess}(w4@^N;TBU*T8NfS`kV;xFC(A=pV^6e#Vs_)Z3$?$WBF&$tsF@V6J%v{Wmnt)ZZ4$fJtFVpZd`|wc&EWWn zQ0c-p1w+-^xR++m=JCBWt0-t9h}3c73g&njVRYYAK+N0Z)~>M_%#2Y(|9yLUS67$r zi4bD4*0?}Q$G7El&XaNho&_(~)qHjU3By5KwC%qaVZTt$H^Nt+O5*0QPgah2f~nEc zLdNeMV6}XN7-<9^AJnDakdf=)(_$-dw@pdO>)mbJoinineq(_j8VuN&tx8h%vRn1a zE}(j(+5%hOG!1CRyw@?$SVl3as&BpPSK-3hGS(bP?EG-WhcLGyjaoASljDVukr#J* zd-dbDC(fiS`+G4!2)lsPLdaIv3cEdP)gyaf|8g&h-}l+7vTQ4eUPn#r#>_|-*tP2f zk;aJGVimFL-IgXE^D>xx?7jB%=aMkXyLN;CG)oGDKB%igG>q8kHY5fS!f|*lcIVLojmJml5eDu z1eW;x;U_Dxu#speBtCI7^&=mj3+{SwWEwe2JMZVmQJw@pJDb;nBPDN^J9g4}XYBof zBd$T{D}G#*4y{#PJy<^e!r>`%Zx|hA2yMHNnTuo`96O$~qj!ZQbrYrr55S^LZur#S ze{1~qAu45!jkSM26~-+aL%B1O1fFQDCnZ@fNga+equzQ4<(3EaPefgNiNvog5*GMg zSo%_(BeC4m6V+o}W1~v5WxqsNFl#>a86`u*I8?`q+A49Mcu~!qf$1%|D82iAa6G!j zl}oc!K24K?PM1G@`c`#K&B8dE&P13ROJjK4&Il?t{uEZ5N z$pfg6TQStiAennsVK%RosKWn$L3lTb*W8CxS-0|Dv`pn5|J+&tK6J@mJLdkd$35QRhIYfcehz(GP-VsB6@;!f z?Bk%y1ub*|Em(4Hl{&Z<4P9#8^)d;8g9hS3fw*}5;%uUFDStmtaUuC&tp7xL#}g zb1c2f@+g^5Q+GW}OG^{JJa|pBu}s9Ip`oXU*bVA{qIG@~u|bc+Ygt$C^2Nz$!9F;z zlFT>i7$ z+~DIS%pk9|0g;owu<^X>AFurk13P-Zuu;+^!};UKkHl@gyY*1fmq)W2U$LgEuflcF zQs@fcWju&i)E}d4XA|z)i=wY(A(=II^u$&pl|ri(M_b*N-3>C$K1FnWJ?0orzUcPo z(GH?Y!4xmUNUars+nzu*l8&Lj zbGPODlsnj5XKrIqZXUVOYCXEq?coi2Dvv{^pX(6e$E5qnhv+T7Tr?(cLLfuO<&~R;i>Hfg*@Qp{JR#8pHIk;a+z#P;Ap~(fRU|#($$OWc5}Od>RLHC>WGS_ z59xHh>AAQCa{r!w6p;rK4r%&Gap}H!N@<4&vwBIvwY;Se!=d7GhO?Q^(yrj#o8tP- z1y`WWOg!&NtE4~safBuFaueUff8AA}NWhz045};LW?9dYrf%D|ttrdMuPx}9CVho} z*h>S0w~{i-`Xbk?(?%+f4|R3bB`dR0^tP(+wds$5U-rPRT}9+Izn=546A7h8c29_- z@q~YSGLx}g^{KrdLWIxVEJQbi$62u^t~KYZfJ@;PRfGV1a=fldZ_~5L z`|9cP*XtAOlBBk$8@Fkc2OU*BbH=BrsHpd}`t=ZM4RQib6;`d$z_MG87sqqDi1IYs z?#=7hAA(P`ZgfK|*?;JeoPmLXixgo%CMt&Kicc^1^&1sA)w02*3+G-$#bkT z9??p_aZ7&UBU5S!?<(VTE4Ce#xF%Voi>X zfO`Se^G=WLSbNMiqq_|&PypfAXmYOBzz#|Wh`I(`uW~Ux-?LXD_N+kC2<4=uQ3Z9xdo3qbdEvipewlYnk$cCw_2+Mo6jeDjegRjA5lngL-q?dwNwu=8#&Xpy|NROikeC>0j=lEk!^3BxL%!dyvsArhe z_}I4BiLIeNF#YlNL)#ZC#*Z583V1oh%41=fxO>lGg`L;eGh6jYyPLHqZE^e(Q=aeK z{~If6k&mbF9!^G}I(+yeNG|sFiBpzI~N& z8c$go#w_Jh_rnKA9T+W*TMraRNm;;$*7HR4v|**tRbFfP zZ^Ny1$+l+cCN(E1!o#WP=(KD}vN(R^=hI|FoQ?_)ZS{Wi$oNOuZcA?cc{M))6LO~C z6c;mday~4Oh#T8Bi3igp>Ku1H_UZ5J!t-Um>y!#}nULFjLPJMv`yrqtK@D1!!#~A& z@GM;gWF$}no^`3~|6y1E84Zy(MYl+!q;>)y`C zBK5Hq)FsaKs-LgxIXCE&rhWJze=!RCHuha;KFZmgtD4AVBA@BMb!wnqDlf-YdHT}@ zPP6(!Zl7~yKfVQsa@ub&s)nO|ui{GtssU6%Z{ECV3K8xcS%HA}1Q3ggntJXtVFaA? zE0|wVWVreHOn1-}_R+={9VTX=5!y)HrBw$tx4A)^?Zv)ka_%W?53T|FqK6Ek!^Unu zej$FlNlF)na{2@W0r?J|`N^LDMbU4FX}{_$2?uWpEo|iW_YUKk=r%w@l-kEBL+dj> zEzuzdDv;U4O3Kr(q`jwik!^ezaI2zR(W|?hGe(_j;oRt1##hBPH|z769)5rN;(*J2 zU$I0|aAESnP;k)WP84)TIUz;2RzrT3` zQML|N~N5t%#l95(AZSl;(W+dskQsQ9psh>lhi`@$0O*?|gAsA6y`NfoMV^b8l z3gLF_e{!3ZTqP6AP`m_7xWfulU`v9=EPCKS2OUT`FX-&lX|l~!RQnkjMPYcF;QNN* z;Y2%sEo|1OgRh_BWE;ib>BW-zwX?5)JCddxj(YL@b*m1y5>fX) zteTstw#BBTu+JIE|J1HosE8Pqi1MZM%kX(H7MNO36v7!jvMNt6Hw>hocnX1Uylk>$ zw^uI;>%Bgl4Cc)ynFbhCO%>7yaj#l%amJP#FWr9M$XIa=W=?tZ&zYpnoJ zfOOgy(b(_X3t}QkiJrm}qBde6R})5!EiC>&&fYW->bCD2KZ%N>IwfUE63U)6`_f_^ z`_5RBeG4-f43VW2$-eJ9GxmKe&a&?eh9PAe8kF5wo@37IzMtoQbN~O>dA;cky%_WR z9mn_kS*w5rmhx%?xVm-#`awhqv4}!mzSkBe2fg3n8UDX}s5NaRtw1^@LA3hTpw5FJ z(1)l;;sYP;gC?6%PzTNc-ghj=7C@HQGyFEFe02kl#xl$15kUBMTQ4PE<6Zl#L;odc;Je!0+Z%&#I{;@mc5VP% zhNRUvStHSk8GiT#;0YU9iswM#p^%;h)E)+J_P`nHr1c+EokjsJ zm@u;X5L7FIrAkjrD{E&5hTQMGauhHv#5XW7!JVkK!S=Z9@jyyEGi|uc!w*Ux%_xnU z!QJ%qGp1;kF*080izJoXw@25KWRXok zC@?Tk+xi1c&c+}w0!8qpCQy-5ZJIWk){k#={q@&9+@A_4GNS?F|2z z9g>HG6$%xCrW#saT)ZzJFho7_XC8{;uI^ges~LiUt!=^R=;%%?Ua{FR9^==l3V*bC zOGJ6@^XvSEM+nVF3e;4U-X{fgF7B1gGxery*d+LR*;N-)>%1PkW?YkMl|;2&ba`Ni*cdZMN(0x#@v;K7=!*kGLzlsb&@8Z}s5ed>M8e^HLG0eSjU{jij{y-16X_t~c?kp=`X#1E zfKo@@aRE|Tr_C>w!v6zX`5$P-|2j!LLW9Qy>wn;{U`+QXFE_W2iEk6IR@;Z#L9$5U zaUA4dzI?%gIAcKZ{ykJ|c+dBEVvId9;R!9cX4CMFjy%hzuggoIgxxS&7ROLKFc|=bODz;=?%sp(!qg=Z2JVSI*xs% zdh~GoCy;psJMe0T#ZYzMxN(D9m`BY?+*xaFc|bBc1HJS9at}U^U1a<#cibH?n{C_;# zz0YsJRj4~)TBG%Y6H@lAi2k;W$NHt11lst7efV_K@3u3Xbn;kS+NQWtab~I#agx}J zNj#MOYe5UxBmo#e4VScO^G-3{u4b=aUay)@C4%L@j2*Ct00wsic9mVxzo(9GQ`F2L zB)y<|4tStk-2NH|{$AwmW$zW>_@-xNwOG0gwC1&gfJJ$=4mv@N&JE1-yk}(a0cRQv zpk9VPb0D#070gEHUr6_k-b=s;s|@5kR1Kd1C|L%MGXc`2Z}APROSMhC=cUk1Yur4_ zpvU^he}ebx0kaF{YiuWMT*T^Adb1b)N3!tl(rhC(a4T!{3af$gi#)jCRr##vWQm<@ zo<5-2-tXXLv8P?Jbyti=&FA-JybfKop}b%RB5v}4{%ukFaph~;+6E0Z&RG-t!s~V8 zC;3i+x}NvC9Wj;UrAp*gOA`l*<@rv1gTIh&1BpGC63dMDFbrulS7_qlA>pP9CUoy< zXlPD$>wZoySXo6xL{uqOFSDkIgJL|A;kAvQg@QIL$%OP;2IVpclBv^$;aU*YgfAd% zM-~SN=DPKD$LzxsQDC1Y5rw@1?w?+fnE;L7Jlw6BAV$Ju^#fdQ)NpNqu>(vW8zmJ} zv-`l~NWu?I*tdXGV4cLhd^#a%37f!BeGUM(L`o2@rbdEZfWhUWV>OsD>O1O5ii7{; zPUR-G;H@-TH4PTz=R53Y$Q&VXk|*F}1Pl%uI4T5rq=*~3R@)lv8!J_?$!C1HI4(?9 zfA0e*)$Zy`jn*1PiY3w3$d-2~J`mQWrOScVsSmo$TwjKnq?@9)%8Ivr`_8a1q>M+B z(EOyqaLss{#pD+J?e4$>-R*Ug<(0PGsGkdyn`)VbE#=5v^K!*|5*(o^8`Vl}=q*gh z%U1JJvGH~NhR*DZ;g3IR6y~tAPvluWu8n-Bo7(V*r2FDCt*HoZD6syQCqB!Uk`y9N zqE`yon{nV%rF?QhvVwfr$(P#-Ofd!O$vHgehMZnyl8p-ow!47Ibs%m6OcCk|+LD=x zjLy6b;3C}8hajn+f7?hXN{)=~4RFi&eu_+u_5%(t5_V3c?7#4l1pA*IO|}Qm{RE(b z8)^5a{KuJ5L8M7RiXA>)eE{kE$L6v?a6ap`>FeH`=*rff#Z6*`Fepa9#AD_TFcCMf)F z&u1L>S7W@I)zFr|1 zCC1754CDmGH_BkGB+0lqInQ4fZT~OYA!-lSFGn2&l*YX}DK@1N! zmt{x6;h~PUw#rrwOnHIwagl`M`T|1VML_KNUl)@HtKHq*0S&a<0o*B17y#Q=o`?W{ zoeMT5ABRW>Gl;bPBrs26Mv-8#g{L=QEHbJ3lCz*sJ7@R7kurI-ZuxrY5_oOF*pv0p z>!%UVqn;uu^25VJMi4Ay9&osnC9qbI>ROd?MWax7weg=D!NFhImo{mutn0_fUb+-2 zs`}Cm0nFEQDUkGf+Wir{TrUui?ra;i9*UuZ3u!IES08zi=fAFMgB~cNy}aq2k?_pI zp8=}KO~DmekAbLksq0lfA7S?&XN1r#xlFb#A|D9pVB0O&0OI2@EfiXA!m$#?5+UiM z)#|saqq;fAC}R2Q{N8$DQPKVXdT5!`KLLNLD2T1*1J&JoieQj+$ya<*r};AN#vC}R zeF1(QP)!688xB(yR`G3j>C!~Wu=4C+vL&g<^uC@<@NNNBUvCH(4dwCo_Ns$l4k74cZ? z{!e(#t68-|4jiASU*Ec=imOp6)zz)_!AYW2)W+JD2jWKxB4=BDdt&22zU)0w=WbyV z=v#y!8%xH(k|9ummHwf82-A}5u+bdnLytN~Hl^wU4<(W4$y+7SWzG`SRe4C_^^^?s zo<^Z$NLYz(ET^jd=#z9wFTJhe6FIliI-c;0IAAuwZD z#8YaW0Za`K3K-GR6R;frjmDLz6kLcc#K;?n>qvbA0IG=ch1{qR5cJuyXqG>-+dI`^{1xJ@{OA>s)jfqgakQhqEyw z)k;^^FJ8Hl*lD%f_%H5a>Z%WziQxcUn-tao{G#7p*Gw!)}Xaf351I5P>v^ zO}PVra_ucw#+DQc1U!PYBI61*-M}Z`B6!flq)=&3KX5j%>epLVF9MxL7D-1)f0RNz z1+0xBcAgFfJAmq07DNWs$DWwVv)=!{rPl@~c+g1CN zChb*qoWl<0e%aYNPoDHl?jpb$=UUG^Q`g(LWg5zRsxX(|cfHO#oKf_WzFyx~k1lT= z_vWbHw=RV(Nn*dh{?*Hb(_)*Rrj|&1&=ti(J>96=qphtP^?v*<%9Q6bGmE5=5~v0m z2Z?f_TMA^mhsj@S*2pYwSa87XI)XyjQ5ehD$@XwsQ zK@!Ik&`faA=oAR!)&QJ(*+@y@keoBb@ixPl_UPs9n<-k3Hl1%so+DSlPEj`kTas@p zh;>zvW43u+Z5srb#%|b1KGAtNO<(9UMK(lfLH-9|$;VylaW{&}M)$9<%Fa>;re1xN zyG#kTP}Efdpm2j_8xNyHx^DaNuKwdpkDwzCt@3j<1?$d0SYl8PEyV-<_S52G?5!IG zuURCEULL%p-(TZ!gTYi*j3tF{XO>^KsHpylYD}rh)(jM-pGYt-Y&nz_l_D0QJ(J)( z)D75H+dzX;baTtPK&!!13!)k1rI@st5K9)5I6u`0X5XqG%ps4GT;Vx1CtJ{`<;Uh+ zBE8z`HEK~|G>g~xznwWAf+0Gn(; zas&~=b6UQYxe4LyT!alw7XUcOJr*i5Yy|AoVDV)v;$0;|_KoSXmKv{$K;tz9S%pCI zAqdaA>_`CR1fc9oMH1`;um5=t*f?vDFH_d8Z!5Mwuw6&oWmMB?(s8gv-^5TWtA8*( zJ~Qr~=H}e*8aInk_?{2VP!mqay^_98*A>kyA)%uY#oXA4K~Z1gNK`W)o2Y7W7lA%S zu2Y)ij-M>;ygivmlcRJ;oa%xRv{LJoCBMd=Vy?X}%-l9wrYzy`nj?4hO_>7LQS~BVcuGErXMttbJ~bjd1ui6#@)I!58~bK}{2K-A zz+%z&Gk);}W4aufr8wO()325Eq-ZukDKLzO>m7Lc1JeAIzdO*mJgoX}N%Q}=(B^;s zRNm!UQ6e}$hqryCO)7nB3j+6&Z=C#oR~Hug0QL9+J#Z6x*Sr2siAwzVvCGW|Bi%_& ztr~Sg%$M<7oN6^?1N8^98(5Cbh0fp0OFiozCwqshvb{dPAk=@t)1P4 z+H4R)MMv)hWue`wd(-;~_`FUy{BA{z%^{5`ERkw3jA#KIm=>lEc z?j)kPMX>bHILj5%MvQdFN4ryQ2jJQVoc1P~Wp4Adm>U@t1qYKaG0+!hRcJj`qSbs7 zB2B~8J5%&=yrGiW-F?}jMoq@ASL%hb%4+N{u#=1N-;cKL@{(BTH|S5HRP}Pz^5{gZ zeKaehCCp;0ha6a%y(Ma#EQ-9o?v0|S%(>T+igFJ4fBUffzTtPhDxft@?yT%dp{@)N zb$^IrnP7jY%`#JO2yndXE=^=J2>xFOq*qO!*HZCif!eo9YVi}|{22x!j(b5YQST-# zy>;YPbqpx3P_i@gkJpPzHvtV)2)_I;t)iys-I6!WaS|J3y ztvQd^1bE$+ljV_!PK}qC{#>H-fHYUIL|+IM-3|bM&Zj+}GdNTR zN@i)l0o(*`bp1bP-$ihrjfkBU)fFjo^Cxt4=2ui;x61_mqj99k@777JpSmo2E>u}z|TUTF*R#vZk-R%^)k1p_N%Th4b|cL)Ja!V z1))|ak>LJt0{RnGW#vaDx~W&|@U~{YNpRq)L+Y&yHLg*r*T39up7KA?5&RLSt3h&L zjsr!!Wr4mQ>QE~><PsALW|3&CCv7vO5tgu8ZDg$L^BbjCgOkkc2Hp!T(EjV;rM5!P%@=J&AW72 zeFO38uUt=j*X$~fsV5qH0%|@UmMWTVJD{y)$r6rpW%=y`Q`QOV zWHWq`H%r6VJysImLckhBvsyVHImKjFR)SsH`qvRRQTdR(v|!r_-+3&Z)VVLKyN5|D zZz1**-)(Ne+xL)e%So+^OFfmI;b|5_IzN`SCz?k%cU{|b&k-3)y@#GV`E5MMcjafB zRPpLHS2H?!8_*Fp1?4YD(ipgJKSHF6CVFaw^9#- zY;;2s$L%e5T67DbFxF!Qy^=&{`rQpaH#0Mp{psJ&3=)`m40|gb<7@mI!SkY1ZjMc_w9=I@z0XYi3eONG($YS@|SS{fx`W4{y4>N3hlCQ6b^@jO60uWB;X< zrQ#yEQzQ7owEbJCrM!5l22(1WJHvjb&<=C@zo4}!wA((C#B?%bz#H$4kpU9EcSr!Q zO1L!UD;*=D8t$YPxM|vHaR)PND0$DRO$>(~u#)xIdJZm@T^*zYIT1_uS^bS$iVmTg*{)_%D{#!H-RDyNu4~|>q1<6c=iGaAQmP|Sd`_&G%p5xIJ zbUbKyUi3B+l_h(P2M-xj+Z~rDPeM+AC${S~bgJ<;KH-#i7}OQ}!(pXrRn|!fKQ++; zBtuPLpCWht28@N{z+z5Ufo=)@-87W2pP^IyC0P$e4z%@YyW&BISp}9~!A)A``Wx5m zeZ|(Kc0A>5-fB+>yd93lnNR;=3DviK^4+`gPNzZnR6D4{Lp$XD$^Ma5-wi$uwXwOu z^d(s^g8oUD|K`mZ<%quq7*zA}!7E>wrj~Huc}exD+jLGhk{CB%nM)07!%LkE>EQ(K z_jPjm1BHPJ5gig(vACV5GJ_uqy|_hBHq5$wzt2pKxTe2 zao4h=YIzrEJoOemiicro@J7ApOgDJS0IV_2STFB&4E%anNYOC9MzX&IY)lXz3@kuw zVS0H$O);nId6H!*)z=ikGQ6Nm6C^ddj4J<#yyD9jj`>v6d8_3ENB;#Q3oaAk@|_|7 z`P6lu85_*x=cb&@)QXb!PKIvL72!?OaG^!BYMsbBw86Zs>9~Mv_|g7;k%h&F97bi% z+!puT$4t5`Cbg1)N0qA0)%GU1jwn$=eS71_btU5-tYBOm8$1i2du`}t8lYgdXQykp z+EU3HxALi^o9oEXVPd6Ehld8m+6Q?&e-J&K1*IAZawAC&&ECGg>einiL$!<~z6KiH zrAu+NYBLXo0)K!$3QnI!Ah##^Uyh;Q-C6*<*aVOd07IJayt3CRHpF>Uuwug>Sg*Klq|G!?ffAe;n5YQ4J2UxnT zl~s0IhOp8ZVp9f1O*0V`bS{3fy08V>-0KwV*Y-#1(CqQK;~iKiugSfY(R}Lp3I!T( zf({WNNCz2)(uKTxslQ7JPZfPTsAiNmj($FHe&3;y3@(Y1`XK_ zHfoI~b$SZnw3vmr?_!(vc}mC1CR{KSg9BFNpyu!HY)CpWK>>_d+-3a=SUy#<}?*RIc^s;rJXmpu}nN!rvX^7^K)C ziACh$7vm;5hGC-R=ubUBvo&1hs6jcRIN3tslG#B-jE6ajhK(L5tw*Ssb_s~${;U|hQKJ2_;He&3d^yo3c z$@9R^74uiP$kZ&SjTlAnNjkywH{b*kz#nKu6Y^m+9pl!xbR+pn)W3+bfAjeveTdyl zU z9X^0Erc@}k>PoBP3ED68diEf6^=Z!d=FRjJVR5}wPZOuY+}Bl2w0ftnbQj&F@>rU$ z?}C{VgnsL!h>kS^o6#xIyQJHve*HQcTF05um39tz%>{wOBe_BaZ`BdQDPlbF1BiKs zfq(af-!#b6G+8hnQ;E_RC6A|p&iSsRNM^|s*AD+Abzl*e1oltSR2%wsa;2Hjx+WjI ztSPigza5R|mwNu!n^%`oU293u?k7oI%Z$WjnVDGw5psBC9sF*DqdF<3-au&@5K)wH zjcqn-k~s(%`RcQlSzO$wubf|y!P`Gg{%3B=S297q*Rr6EzO^^_&C53HT_^U5dk%p* zF%d%&O1J5Jw?gMt5fXcwi9fnn>6@IB?_$vU{Xj}TT9yAjRopN)jAr5vx9VYNXs^Ki z;cRvmaqk=S4t`eI(qNnpZ+5dloWEQlsZgTudTqTdIa6R|C6mV)!^^R_^ngvy0`=qj zIEa)auh}y{r$>2J@Ut;pf+#Mls=7KpIX1UbLZY{~N88n_?)SS0z1gCVW{_0wcBs_) z{XKY!%dC+Q+xWA{MNz0-ZjLG~ohk~gg}|>rWHCX02GewDX$?CcL{&|B)Vf~5e9Tgb>O?&wD-nTCj67XUwbamNRTQS*AeF`w{`F$w zM5GwHwyZN{BWCX>+`dqR!OV_*6FRwe<-Dp8Ap$P8V)D#xx zsGP_zN!$T~rKJ0XV=8YFy#E9Qolejw6ss!WKabq+q2McZ1VvyL0IwV&DRu-L*5-ZJ z`GD~ZOLtSuIf>+%_xqAxqRs`|CSyJQ3M_O5QkyNptF_5mfao(Gp_p;(%OX0vAnyI# z`~l{xIK;S4Ie;r9%E2Ol^tsVeUI8G`u&dOK-xi;I1)HZjTNvd zM}qIGh7`8_1g5s!h8cSPX&jhVI_BbxlH|}=MC)2ibk-g?N)#Si*cpyxa{^hFWF27+MQHYVQ0{KM zB<_$CY~C6-U-$v6aPet{Ds(-tFp-7klFPIye-Icf?!%VV;k`rkv~*dK@7}S?_g$JT ze}yzIR+?9wIp)RIov466V8^Q9Z~#h-wg#S$e>NtVS_14*5*7}4^D4n+x7BmFX!UxqFq=xo}WBmP5sQq}WuzWap(3MZ36YAE*&E`dBgU1|zrk zB>MLrSUjKSw4_U^alSB!$B9D(hbipak9D|~mx^`GZJ%6hyvg8pI@Ql{E%fT$mY6 zcL3KZ<_{R8K{+iuAT*xJ* zEJsSv54&8?ly*p5x9Y>*^N7Ou@YT+9`l zC&0irsss{dG*u%ay52vas!Gv_;heP#qgtS+@2P~BGHQx}72EHvVe!^4((*u<(`7 zxWJS7`1uX8`|`;X)e!uN6WU@c%HGpy?DGuC2#vxP&U-Tjku9LFmyT7yjkw1FwFUI! zSVv8X)IiFsI6T^SaTmW{wI&F)9k9aY-?*+kJ?-(rwl_J0-_9hZgO*uq>hy#fqE_8B zAo+WH>Hd8!z0R-*=W*r8+???Sg>#}2Q3jpt;dtrmzW3ytJvYtsUFXVV%*#jBmGH92 zMOmUVq8au8flJ{Z?V1sc0<41HKKIT$&Ff;@y6G4xNMSy+)`yMT9Nybtc9@q9aheRX z|Mh{*U&-^)-30FY4CLN4wKu#5hXqo5HXIPC)s;)Ku_S1<9=&E`EO0RhI~Um1>`J}jg2vtT}z{`z)MWSRB}fQLp|cFuB1jM z>x@yC#8wy=|KXzOik4hj1Wf`4UGP_RlIIHHOJAJdt6#;yK8ms#c{(+*rIxF)qQ5_< zZ^UtnC~1F$U#GubR8%pXVjb$(*}3#KLdP9e6Tv8|qaDl1{XR0jRE4gQQ9Pm0>M;Vz zVw0P@Bs!m}(Yq`tC!Vb{h9758E~kD$mmvxz^YrA{{(ut}%6ol*J|@AI#h~7JySj{5 z!i+!k27@W|1w?5&%(Xs8=Jr!5X2&}Zgha;IWSJOmqlYU5L&L*NaJGRmK>NJq43yEk zlH%!kS8hw@x#01tGB4$CQBiqB-ed#OR660bF;t&e-8y}iLGF+5V*~y~>n}p^sYWeA zy}+bl^Vp&H3agj>SwMJzIco_h%)+m{uT$Oi(tp->57BgwN4i}8 zA%H0V>QIbaows-m^k&Z!`3){OlTc4B5Z&^Ul$AH16-!m06zyUYh7WUSdX8mbfA+qj zqk8$Z%FPKLEfzA9`6$SwoUr<%UKo*w2nQG0i{Om+B@B-+PIoqF#AIK7+u393ae@DakL|yY$~yl;F8lpgC}a=gKUE&;@6#yD2_x zU+LfEq}vg%|HtQ`Z;<4ztX=r)6EIsrh~Lhk-n|_`Z{YNYbHiJ3O(z0>tX#qqrrEnv zM5#@yo{Y>R3me{F-c{Ey@Nf2_7SC>0g{ATG^6Dul1bO|O&P4%5x0ZQE)w_4`;Fh8e zqm7q(s0}nea|IAJ#Ww})XsVs_GssfFFACfB9!?lKdT(W6Z%Y^57)U*n^YbRZt&iLc zJQfz7W{8QVxJaQWAB|KZQ;@$_Z}K_67Nv@MIfmwl?he5*Z@|7@|;@&xcSg+jPlXZtkwe72Wg9UPL zsucBOJBq)$pxN0bzp%P2w?4R_msE%7w9a_UH74mRoL{(M8Ku2e^ki|AOMmm%0 z-o5*>vTb8m{gn`$M$UD?kHdF*HgMb<6Kb_Tx=L++zi0&2uu0 zD?6W9wz>XdNoF8$K9#?Ur2RGS6WPat+T5tXd9S7Ej#LTbLyfI=F}gPaV1bd|50zsV z79Jam+~cu0jF1aYcel{(0#59qgWd4kzRINhiF&hlvHw2)@;CSOsfXO^R+i{z{V^)9 z=?HpXTfEK^2pYly*M_TNDe}mlkwV0(b=g+a2ea49qdMIN1q1&1FI_x-pZ>7f*&tA5 zdvUzMUh61zve$BfrgIM%=;r>J3Q@AQo`{R*m>kab0QeKv_&OEO*RQ@aa!11ICuaxY zKi%3^i0*COfyihJTbA{SBv{ z_=0Y0Z+}jD<|yTrv)Vg7-5-Q|rp6Ca@q(u28`HBB6CRV}-E*Tk_v=mF3v$b*(=<35 z%~V0!g4-$1b>Ax{GRgp^{+>(ONwVJ;U_*gY7$_#>8BwdqJqq`S?%)tPD1N%>HT(d0CHS>0{4MXfd6 zeqe`Ldyd@6(K#cm-LziGY1i)|)?C<#vX!e;5}7nxj8`pk)5FxcFbd$qC@+aPeZ9=V z#pM^=M>^6zS&-4?hy)c@)6m(Mm6ZHG94AF%x&j=Io}T{Dzn>IUa)H%%$+}xuyM$M5(A8Z#~jNS${1;Vnrmv zY2*7@Z8$j)oe^zbtu8L{gw886sdX-~AQEtcTjJ3Q)sqI%tCOo%GMYEXLlkp!ZPb*b z2WCsV6wA?h_cZ^&Y^S90);AXRC!`$VZ8vJ8qMg0HbqK5c>o8SYVTIj2uW9wd>8K$l zru?tZrqwMmuoxL%y{MQ!pR!8i6tOEwpP|NLb(0tHgtYs)>2X-d)%-d^3KH%h=0wC2!+}a9O z#mz^SV%2Ia%~8*2y}9iw>giBD>fZj%KXFczMAoU@k-_UO_kR|?#>b8eZF+k2WEY(g z-wpEcO+XCIi~IPSlwW&#j1S#&C*jAhSjkUAe)`iqI@zmlp8#f6B>FBtzXqvK5{NL* zXMV8i@?==$HG*vzu4V}5<>mPV12sGEY6ji2VdLPDP)x{*=1*p3g;^`9iA-Rdmu+qQ zOs6TGO%jW#rK1|%I`;NPfDm^H@6m4EMcd9PVfpC~%{P0OEDnM#y3!k}@%%(!xK7(W z0O1>mfUm&f^lv;g|L<3_{3ttw!0^c5Ra6bEuea%W%iXBgj9mmBp3`tjNsBf>InA!(dC+ zO{(D(ziHRRfe_SyZO1|Z6M?Ec;{)W*OiK!Fm#uKR?m+3GxTl$Sd0`(%^2?^_D0pJ6 zp`MRqKem6Rz{&FQ>)FW22zN<(o(Gk!xN43h;No^KXf9hM@HZU7{oU2?Rmw=#pC4_f@mAfxPfA0_eWPB{BX(R10#HNJFj}%cw@b`RtK71 zNQbiS3}-ZH)m{;I9qm`4Ns;O*E<1JQ*gq2Kv(UF0TezDli~X~3at@zQK(Xt|ED4G3 zukn}$veQ80YNFu5V*UQV(1Nl}SD_p#D^<_|_=SnZd1LUnCSz=jX z^|$G-fyZ5et6Xx2Zv_gse+q-z7fl~8An=rB?To^)f7A47@@in?O@priz0!Q0%?!WxW7ePfZ!X+os=s`l?y?uGc?%nm)M&Ra_o!15vJXKI?og_6{Qn ztM(I+3|^2B?6JQ=pcEpLOH`}lGhH;QR4fMITyvxG>p%aDld_KMTet!rL zE2(KQqYS6TD?1dc@^I@-7Jk6m_D6e;-fMjJAwf!tIHpm<`E3fv)-|YRbA>{d=jC^# zeK3{8Hig!h80l2}A1cv{`78AUm4{;@*R!^md-*fk~0T=Wo%?Rpz=ls&Yv4JBm^0VxHQ(h)DFRqALox!kXOl{o$N19*E(Mta7* ztAz=-y7_BDh6jr-u4QRCGS}BKslwl|BVI;}y6~q$5OA>!fUv@5@08!V z!vC!WD7P?tIP{RNYOkKI@$eRCCr{BRx7iaO68NXW3|OZ86s0{x>7(4)l7I=&dSFx2 zQJt||rSSfnjo_MJTfIIyes2QP+vb|i3~1f5oV$^0lbRC1pP~lQSM>Mar^@u;)Xkh` zWMb0yEMs!fhu8K(`B@?(^&uuH*s7{UW>A8#k)A^K6ffz`QcNj`%o^a|AW~?92oQmoDwLoMvY1hxi&4^n2r!V)rmjnj7y}|Id-vTuQ zHHdf6by<~(ndbA3Zv8hU>;^xwOFVrGhB-E+4{J@0o}zA8k)_Lwc>qgI_lry;Bctdr z{{)K#W}@PuZIOjyV5jl7Jp*5zUq?0Yac&)&h2;AetW~n0Ze~GLRDQwI^66~$`TVlL zc!I1WV){$$fVm^N?cj^Ro-$%qPNu`LCpP75u=(tixC^2okD&AQZM%G$(U@cJQi0AE zl{bj$s}^5@0{NJB^~l3~k0e|B_wSZFI+PvU@=i_7DFnP-=0prvhSsmA48_2Ly2L2- zL{&3UQj*O;FX?(x4yH`I|MyaFap@Q(9hak)R~=V{ojBR&KOz$nZcI#0`bmx~(_de; zcR?{ee?C52U!DfeW(P-2jfC&t$@Q)!Dtr?mFYqi;(Mll>!$L$^?3fr|2=MPYYlmOy z14NFu%3Ei8df>hNO<@VrkA)43hs z=6YdQYBl?)ad{xt@28Pl(SbTNClcyZD*keI7|g;eCe_J525Tsr)Cg_T(_R}o{mpJX z%jxY7a}Bviqq`7BnJOrfsIrWtR99I(xuE`f;fh?%dSgC_0(B2gY5xtExIm-bF9%>4 z1X0AU`|5z?nLpI$GbN*pqh5DerQH5GB7mdzsjgqYeqUUCa+A(LUq5~P;T}+g?uXd% z^lu_$qqk{1n?p+_uuK_- z)?o=u$jpFnOS2Ln82g79o-JN1Giw~B%M)$?a3CB8B#IWt-x->Kv_VRyKl5x^RL<}B z_O_G^m()L8gI>9jThV8sP$+#c4rEx=scXudwWzKP==M#v^Ba2Y{rZ+^RY|~d5K}}| z=jtH0!137yN;EpdiZyL*Kb=Er6zUdis~{i0=5}(_(=jgYq^IWwZ|Y;!2ovA^1R>%4 zxa;!==K%O|Jm>e43< zp!_`{jlF&O1F0Ni4@dH}2Qa0HaVcv^(UsLHb^AGI&K=gGJ1+Y9dgg3h%exUK`{=M* z=gETxT#8tMLA9-fXjZ$a`>&W84$*pLDcMS=B_3K7&)~#otHk2F)_Kk-f@%?Ja=0^G z)O?iY5`*L1Y$I8qHF@AGH_9$sx%LP8?rTN%}kknb}~kYSJl+QWy^%>KkZ_Ir2c z4dmhz}n8XZQXeL7og3 zOaCB%AV@tuy*#=0Uty349h)060UYrM|x1K#oB5DJ<# zoT>525kk`Xyk`T>H9kJki5SJwE9avXzq?x^4wdut$cvJosFp{wB$E#e=s+T!{)yAp9n;slnifgffA3xP?c;!&SP-jvZMraUt)ehEo9nDTcWjQ_YmGyUu- z5}RMguI{(yB(6BK_wys+2P)#^W#sqyv+(68ZVaEes8hc^s7;d-8%)LX@z&sR-UO3+ z9w@6m?c`~QyJM#0>;WEhLs9cD-RC zYU>&db2lAdxMb;3RNOpYvJ)$#Fcqpko@zt zqO!Q(+w}2?g;TiZc+6B$+N{|wn8d;G?yUa)`M`Q*bRN|Zmf)p1Ir5T`^P8(;%~E`P z?@YVJ1yd8fl-OMCL+iz+9i7I3{UViw3`zA1SgeWWMdM~KL_Nk})3(ivcPjAMdfRPT z+KX5Sb(E4E&zLI4Q247)n$qcQXskz2Ppd|8JI-)E4cr0maX?N_F{0_^i^u|qC%4oL zD(R*$M=C9Ig~Lf51KX|-aG@HDXM0uky^mk*vKgI(()0G zwx5!WqDkc&NM#uV20KiCHORo$#pCfH0X}}HYn~KH4uY0>e@SHyJyrS?_4%i=T)?qU zGVvv7qPTX)CGvq6hx)SG5-fA~=>rho-vlq^y6jV$EPAz*f(>G*{pg z5oBGOMrm(u;SXs*onqch=3#Wo`>9+Bx;MH5bOZGQE(ATj3FxeJb%_qRxU z+Z96_28ye1M99XFn2;RuhqwK=6l6ehCFt0l+|s>sv;8%wOYxB${4-|Tv$6>!Vyr5v zO%A)7r2Ub}nWQi+45`iSM7(;?koJXw)ZL>QT~}7tU*1bJ&GiKiH0plB?;vw`RPDqFKi!e0^*XKzCUqGe5O*z zBK0D0Q)c(*z}g1D>$6ivkvC<{@D2_M7l%?9sfK?e9VI{xHW#0YlT)eso4SS;v&`$) ziv(rO`7SY(xa>K*P1SmDRtscPjfjb=L`Ke`rwXJ{(~`1c<-5B&k6({t_8h{oy5}mF zJ;$gqdBy{&6iHDv4<5`-M)65Z&!l50{7#tbB0Q!e-d%5X$$gGNVJh}mngmO=bd@lU zYu5{p_Pzb8I{fyrHO|Iy80PMgg{2 zU`Xwm7DZF@B|e

#FwwP#A#lGQ`ydQ;pA}KAcFZyz*KOpuP&bXjYJy_vDK7)~nNl zF1aHpVZUu(=44e#ZWNSb*Emjaw|@}7kaQJ|@ciSSzHl%o=~Qh;E>Ozs&U#8pyXW*S z_kZ-966}HXNMq7RPB)q(OzPB;moCMxdpTJ;mYm<&EWbx5U)_C2-sxj#)_YB0JP%lQ zec6oTejqTpOqi)1f;DG|sttgbR>rIBMbk5)kYv+H#zt)`)X`@CBp?zZk>*fdBeDJ6<@igYW|-Lff>?(Rkb zC8fKRh7AfEkVX-a?%H&BNlE_~-sic_c|W~3-{897!&<+!<{ER(F~`?uQWlkWzCuf?bKSSR_yY%HeR?(AEhF8yj-&8HkONxrV z7z7p+{c^eB&Jeqg>4JG9bCXE}tIfK+4}>iO5eNj_w2Q)@7 zk^!U3P93NSzstiRuZs=_O`z3n^=B|?i7T+;&}CPxrn>WLCCy3rBpqE-+uBAevEnIL zd~EE;absj%mMKD13)pAuVTV|tZay?az*AL)u&=Wi87cbeZm)TVig_$SyHmus&iz_l z=;xWUZmnMI(E7HTbr3q0zEw~AN_4dl?}2M&)G^t#$!Z7QUSe6&gaX$X<0;DA#4oQ6*W+&x;6!kvEo2sVKj=2F_u z(xo|>%L(&cr#m`dqn&oUJUaWXsm(+SW~8Y4mU`K{#{l*$MXR=(z7atO}v8Jnz>B(&CQn*UlUX9*}J&g|L$;0&5zHD?~ z8@{4(_}Bs@E?j|Gjy2GBL=Jw~Po-kV9`gS`Ec9Qcc!Cg!(cNrU!3-;V`>|NVD>bq6 z(>~4fWsWY-SzmxGS=xTc0Bk7nW~;p6(RrM*)z_gSOZ9xl5_>}+VXRwB`v@7qdBKiz z#B?`XWE;C04lk^zP?Iz@MW_P0JRnodcoyi58L*_Vm#p5)-v0XWwAGg|N@Nsw^uS7V z7jt}cOrDNzhP^7EWjjY=@Y|c2u|c&CAKy7~du_x)Z=8bmPL4#Q?(-nw^|9U!VK=t( zGG(Hwvn)Bp7p3*kY73~+mnI+ew4YIqsqH1zyAEp;tHwviIWboCo1(QG={aj+SE?zy zjRk#%9yw*{f|{V!+wYl=2V%&Jh8FGSvk_`s)oIYQ74f=yXV_wg3T#{QZhRvn&4o`j zD$Vi8;vEE!TH=^WltGcw%Dzr^+kKYJT`Gj{m)l{X&FN{FZX@(P z(6{Xk4;##NT#QeNnFp9n5a$D$!#Y+!IzgKJDZO~WF|8~fYIwySH%FHMn+ zZ#uWSi{r$tNlEdjr-sGb71c^tw{hB1(Hzk!x2vVPzuvxLy>j28Ix4C%f3e!r7+L+( z1lQBXv?4ybw#mk0?!Fhg9jX&2+nU`BY4M*=MKZ>!)k&k72Xc*E$pwdtQlV*Ad#~YF zF?<>$IL*aBzYKwK8O_Guzq#2SJ{uYu=w*Jg{N4f zDrJG0d~~DKSl2iXG!BcgiY+uLgDaT?mI+cLT;bJN&3 z;6wDJruM?Y^I-hbqh?CazK34V8d6h$SDZ6>w z9!TBEXGe#a6W$nE2|q(rS65SqE@W;wzGnY#9QhYN5#--&H7Kf;yY0@vv_Y$*Gm=8n z{b%i?qK>pap%r-c5A2& z!Z0P@Hi`+6#s94LVXMh*LUH#<36DoRp6{Zy;Sh{(nn;+m40wel6374wnX9X7^cWY= z!BPHj47!zcG82mk{pJ9jPryjU?GlxN(y}f_6cm=Y0u`jzFm0ymGzl4$4(ngl^_?l2 zt)rBZd;XgW0d`F+JLoF9D^CJ$%a^`;xe&h5e^kSmYm4i@UoO+EQL6x1l3L!`U#G zJ?awx(eD47PV9x&x9>#e=hIWMF%8Uj%57WQj?B+AE?k%e`L#f*>$h+0<v;Q>cfQul3#6d&_;NnIo94l7K0p%= zKsatkh$?8KS>$L{&E{n_FHc|c!_}!;wbvh|zwe)IhIw6iE)Ne|m{=8`7338GI#d`> z4re$n1Wuw$&>4gGAQ5;7lw$S!9mZ5_Zg3BvS~xrP?=Q(tYFO9xX=!aNN`%7u%;FBJ zCztd-w@?U2zWbb4NtL}Z$Jse=@KumCJ*z!%YuKvIwI-hdx^x0(d zT?G|wn9$CLX-fOLSs>Uzvw-U4?5wGxLIC$nqk*l<$cGMQvwbsX_bEe00Nr`-?=Rkd zf>q}07yS?>?LPQ6_UuH*Fz>m$*n#hj*B=It%qFkBOsjZ{bl?VPM6aHM*4nAZi!nEE zpq=zbB;VSF@*g$if4TVtIX6fCa+AV-EdfmVR}X90Dk^GDE_FB=It22ey0MB=G`bWy zSy}S{QDVYuMR|Ezaf%#1k)dPtxw&WSp!trBh*wPG{+#oS@MpAkZ}v04Oh#dM_gX!G zkhDED6GRael0q9BOBaZ-rG_gnCOXNDkuE49-!r7j6gxN!rY0YLQdOZ=T=?PlZ_xdr ztK6YCnJk|zn6^;Vh91;nO$cUG@C z)~q{rv8Z79+}?kv+4p?1?p$|P4cLfKQc>B$@+5dbBK8IX+}%g@4$v7$$nq<**BvYb zYo7$Myz*n<%c1p`1{7Wfe(UE05qkuC1vl?#t8tHSiX`V7cs>g3)bpG8oDF2feEdcm z3}_FP%8T_~jPTeC8$E~LmWj5fNW%(&`-3vy;UMTVP;kBQ1l4BWLkmk#-9M2g1fRl? z*i=w`WW>@%Dx@L`&BC~J^uF3XDhuCw#|f4INWRc|oom?i=Vz9>)r|FDR2SQ$=)}Fh z-%H-n(B$DkG}xxOX=xVCZ^K=EiF@{j13zmC*M=E+5*KSx7J4VM?Re2H$+63jv}l^PxrXcSU(D zR2@BDDZTNfIv&&XO*bSd8xL4LN97Y_NkS!VT}8!6j!>5_QD72DlRL{6JMSF}-T*H@ z>XcP&8VvhK1TwZ|w>#Ave^2%FgR5+F1CM8I>iLC#zT+%Yg2un#@FX3G3x>X$s?Fya zP88(a)rMk6^73)(P{{z^VSB?3{C6#1kZjYj`t7E@gvEszHG*=GpT&X#eH9Cb@;Nh$ zCa+yOvtrF?k@_;Vn5Z~$`l4yNlCriA51)KwWb8V+h2UT+=XMm;V2*^EP70rlkmJW1 z7TCn#kZDOtg7GzVTjOaM`JR_pG#Wdl=Gohnu3J;tjbcI3YnWIkkA<>T((A?bb^0EDhbw<(ZCG2ynah zvzJC3yLGr&c6Y{x+==Nv;AN4ouGSLZEl=_tLa!A?FuJRLvB@X=ll?4=NjP`7*vfY~ zjKyVos+KEbv7&n)+{|}m$cE1ywZ3uAD-fnW%AGi1c@2@tf9h!7+OXeqlQn*TJuT$? z<7IB-UDp@#?U8#ckzf#GHB5=s``px^_lKCTu3^E;Z~3W<}LZDX}Nj z&;nUDT|*8{Eia+|)F}7^|E|9Yl~k3| zyd>MK=Fv#kKz7XoreKy=R-ksBL~oHGBDAl9lyb&h5iageGcZWmpu>XUFbcikBD zBznVRt zVMkk3H(+!;ZLW0R{6%6*3P_KYeymvga7c|_&UM*%bIEMF)%!99`hI`ef(lo3n0;#j zeSsQP|U$q|lD|Vhos%PoJ7>CTxKudt<|7wo&>$T5xJoW|@wqWhzjmVtCO7 z#HxM~a88@U$OHv4n$~&wjlQD-b@cYiyTh9k-iHeF8(_jAso$w@Q1@!9VDtHTzXZNc z@%g9ayR@HMfOeHvP!v${Sg)Q)!^?7M+2QT|AQlPdfk!*7utJg|048(BZY| zAN}~KYTBN}w+g z1OTn76t{YI7k=*RiY{*BvqOi0SJa^QMuI#e)kygO-B^zTda$2(o)uYqAKhS2piVX%A5mzOAkLS&PUQM!v5X6>?@+! z!A3jE&RI9|V7H-3%pF2v0REW09_ddciR|i7)$*!~jg2J&D601SQxx+lxN7Rto<9N3$jRrR|b9U(s3riqGrX+(mu{AqDXE;35))#asN^s>91 zZNkQ8UKn=K*YU|rJw;^l zw|cHP=pMKSPEF~h(1a07DJk{t0}@rXtjyCtC9ee~!36vw*Srj&+taM41ZxERPhNpU zWhcB0(?$A2qIWsV?;KABP-gE=s}wmNH-5;695nN=#)RmvUG=|6!TJv{ z>yG`j*|mmIEk!b}7ng%W3CYPa0lWcx@==+X?vu96Nl~+$V+|Hc)49MYZ^Y*Hg_$+ukOi<5SxN#}(-5uI%%fu<9%w7FFC25vn+nC0<{x?y7q8bAH6+tQHordGP!nSm(OQ)?xSkNfp) z5;Ty_wV0zm0?H#m*ohdZ@{q5%SPkyYZzRR!{Q2V{DJiM5lbDSHTTXl%1Wtr2J~uCq z^LD6A-?wRGeo8_!%QIV`uy~wnM z@!%kLMT1@|3yW(PX>*}<+1E$^-IGk7hY0aIL*ItqK2g-xIk4gd#TW&~*tyc9F{WhV zRPnU?ROR1FgRMiG#I-@wxrYpLRLOc6EMbqnvf6*s9sx|@ewM5Fuq0NU=L{zw3?=FR z?NRvqcm0Hr7%+fdtq=vuzpc}DiuVQ7e20cakfEWi1BCgjE=myi>W}tsBES-Qlw%}+ z#caE)Z!EBaix`)xICj2uIrE7`DsNBu!P})?dRARcI@=jm+lfcMzu%keWRYp!VtzGR)+KiRI5LEuP zGd1`qAqkin%^+>}W()?Rgn>t6!qKraEOKNzoOH8`Z-%TwJ=X!1U`=nX#PG5hw2cv` zQKCCWf=HR;`iTzjq8+yWR_7g{$b=Ex&!CmAB)PES;z#jh^CvO2hBu9YDD4BOhg7;b zr@N-%5ny2AUDPy*4$f^L1}eelC~*@sFcYJApC=3tK3aQS_?YN#NRtE1AwjRh!Y~%* z_*I8O8UdZ&V4UT;6>@N?e+%*P$a;E$wWZm2?q8j6#C^z)_~YRV+n=|@Sljb!9t_rf%dAk~V!tAPzMj3rAV(`VrI^p1b z|M>Aa9e_dlhULDo2>T|TUJjpc;5=URf?}&;q|0I9;ZA*p|DT*edAWF~+DDAtdgYo~ zFY8~*F<2l3tfNu;{V@{x{fk!gU}R-QBG#Y3i2yJ?tnhJpY zxFCWW)^z_q@E?k6o&P*lr>UW3GuY|!wLCI{FwiTV#>KTVYCZ9s%8nB!gJvj(ZvQmFq!{i^B}G5`a*K zYSDUJZT5Pa`6l2f5oX)k*l1`fM)K}X7AP|_FEwnk3y^XgZweb#I?IR0XK|d*G;SQ7 zG?$E}@|?{yUzP0q+0bq^3sXQvMinLY0HWnCKzD}fIy62$elf#TsIGhApX57W1WoDA zU@D*A+8T}3QC$(o1uD3LUTR~AC~rs5s5Vb8_3b38y*lwHHmzhDnOAXhflK{pw+6aj z>`F?b!SCPCW3)xwYSje%Z^TVdEr5{Y1TeLZbl`UZ{Em&Zl%nKhvWacCu4yut{}j5R z%{$0|K0i9D1%}u*KG{yftG>Q0JKs&Z(f9iMVQ1JAlDhoXKEwj!3h~16c-PMR9WZM30m$N>~3a?sQES?=5ff5 z={ZBcK6~=y>^U^G2?#9=?C;P0j~V>Gc!CH2&& zV*LGuSZ{CHLypfoAK<6&;3ay@rHP&7dB?{1@r?EHDKyKuata{#!h90Rft5j~K+yE3?414izZugFNZuN6dcc zQCTj#H5Nhkk++BfDdH>yz43g;8)`3zEb=FN>SUThfHD?M$nad`nLnO`VBUt+L|9n- zUZ@zO-Kmqv@7?RNdJ>M~Ro1O=BnSzCMR9zmyF9UHY-L+>5ak!OGfpPsw?wm(&BhZ# z+-MtkB*kkF?2G}`|$)M=QCl;4r6002aFozmLkFBkw zmccM=-1bDnlg(ET+^$Xlr(h8o#b-QD|91BilkG1$p2x39L$Y<@Mn?44i4~1v z1KY<-12iCYmh(k*7p7Z)>*?t<;~cFw`zM5mbancXWis%H&#;k>V%#}t*4~omSPz}O zZrTA4p^VzAGR(JdaqA3?2HE2ANs%F$2kb{#tZk3o`%d}8t58!r<*Mu_x|j_v`|OxX zuhZpSW=NX~|8$E^JBcdYGYMP}Tu)IPESWwOuQmG$_ox`o!jSu*&HI?cut-h>R#2ta zRiAf7;qqpupK60GXnGpbDI0||W$?0aHYv$H`dtrw?R0_27zkEg^bFF*>r#^YN#dOMu4U#JDcVwto|~?^2qa(65svTRkLns@#$M& zH@@lt%7Be@H1kSP0nx$5!P&r#`J%lqODs_`3*;e-O0|R_T*;}v&K;Y#p4*`=UZBpq zuWKTR#bGb9*|KkNwrgZ&1{OU2>7&cl$8yVlVr{ogPXV0(w8ZTXiKTIfy3@dWwn;l# z?7o2*ask@hxg0feCGZ#W8XVVxCholJkLlL^rpv8eZOwr?1F9e~qm}g#DL!TYx%tMD zUC?KGg2_nQ4!g0ekUIk-Oia@rT1vMn#|DV+p*~_47xLZEIO^yIq}=!|H}AcrK8NKn z&<^YEQuhO+HB)vYckVv|Nj0~B)3Q}wHYP9=n#>Efv#}Zk>VWX|7UZfKr*P;^#;tr} z7sIU(Q2j-@@ddmamrB)i->XK7Dt|SctPE&0{p|Q5j-yuj<3YgS>B*-pAzW zBAk#c;Zqjk#vu`X^FEFJfZ8OB?wTt)PQnG|X_mb=JcBGE7viTEr-T0c;_EZPIDM5O z#nSb#&8?KT3Vev&jrw`4U!{;oD&vUal9TPBsQmmsgK~_Z$^rwE(+>~pMA_JAoR=Tn z4yqmIiZ7vB_@AjqhDD7Y;;`?zWV`ZHqFQ+W?p>Ig2lj2%^469R_ygPNVm351tEPE$ z9u7UmqfG`=Q`dE$hu$Bs`g!@fw6yZqz*NKVuHPzF|BUy^^g|&!Y-yS)G(9ED>om3P zoR)6*n7HMdPsa{s_t96m6YONWO5LmTcIMf-Ja1*6kV;d9qd4(v-^3Ep>joPzX(rX)X1Nk^KNC3noR{{P328UmiGg3H zl{&HdGy{-qlTg!A)2ikdqpOa9U4nsgBzbugw6ix69dB#!^!YI;Ydx%YA)>B@oL|w8 zpfYZb=A?6}2<~?N;=x}|vA^2K*Q_>m7BBc9;22AP*?xlJrN}-i8R&gQ@^#Nf`aS)N zb9rh;eZ4QAMOi=0PvFTsha36IAB``S0hTXIaf!01KT=(9reIF#nuRa->$m7Xe;khM z2|T&YV*~1}Yy@|ap(5v{hu2qGKj|M^fXeB{P=T^?z1!&psztp*d!Pv2%@L@e7q177 zaK1ikA2v9e^^Oi!WNT|@*kaL<5i(HQ6>@Y)uyx+=>2E1AKQWnB7v}WRO57A*wcGo_ zTCXpp$M8hkKUHv~6b#HZY*O}ppBG`?YpohArV&voqk8BI;$w7~{kx0{RgvOlD0O_X zeLwD5SrbLPwevtfp~vBx>ZP~pKu0jfL*Yr)mQ^*i!wt{XVCu)jx0CpHPyjWwHaoQc z^lCBt-PYMHtiVtnuu{70e>h^`RkX3vn*hWV9&JYhPd2ypt9csKpoc2e>Vkg^ILj{9 zc`$n7xunr*(93qxT5_73b26HJJ8Lq$Ey`65o7GV`nm>m2_FDGIzB*M}AD|IaX%bSe z3&iLYfEg!KHprD6N?dXlR-QIB-2^%n>$!zd(m%OHvc~Q^aJ?L5Jn~$7Gc#xzJN7>Y zs{gih)!#1Q7R z7Y6tTJKI2tliji38yj)q@QKGmfxPcNDQm=I|BTXXn5O>0{FVE5M^>K@L}i{DYN0SB z+vowOg)-n+x*e+r5{ny&Gb%~R;-yAU~UDjM9(5J5=9-YEc99EcL+(lSTD4 zNevhyskgz?olcew6zPbMzTB1&Qw z(1n(2zI>~__%2dYLN#Wlz7J|2#ChZbr3hd zW{=g?oezq<&HX;pvoPg)$uppL^YCiNKI-6v%>U%%heM_dq4FZTx!d0#Q-;RgG@J4(h{3aB29%%))X=R zD7cuQ=tEFAToqf6fS}3jMWdECj(kEA+*~C$;ZA6W-cUZWlpixjKAob8I9sW;PAmT(u*mB5hD~>XYG8>Tl zg9d~(EX)J~-(_u5gpG_OGPBY1XgX(kCL-B>)^071-qoIop%oPLg3AFXn|y_Ruyjzw(S$M&1&*2q{QzCt&k^FbqbA#zC8nJM zMIYv~;zYkD;lZ__8AbTlDiqXLO$l;>2H{1plaKhUI=VlIj)qrrh1kx-JvW?F1y7-Z z{ZidMi~#AohVFb`ipUyxnhNhQ?LaUxzk@s^$X0aX*RY={>l zx!t!0O#$$&tE=UDdMd8hl`F1)CxOmm>G}|$mhPc1su|JTJlo+G5V+^*DZ+p0U05jo zSPY1YI2`f$ikp8C3MkZA#>mN;_@CR>0{``iA{BnfJfli(hhRlV>eH@NR$KpgBv^u$ z`5LL+;FYO=g_>-;^^>ZMli958F!PSrtyP6W^zzEOhk;J*CW?)V6rc)lG$Yj0&{Sl< z!FLu(XKrJ4en#)dP`$K(TFF>~Zc$%bHsI*k{-%lwdGcyt;9LAE;#O$Yh@D^tc=RB^ z=v0y+UJ=rEW`po@QsPEoS6*t4MBd-Q8vFy@m~|bk8-$ja54zUp2M4ZmYpPV#f*O*m z84Nwi5A|JClX^)jFlwg(S;9bzev-oemtp{~NmA_hR`pkgrzV=DP-nX$fx)I(z+xQS zI81R0l;bO_`Dgix7tVEb*5Sz?*?VI~pa388*`*ik!c?aTAeqlOM zQU6E$_;e!0)8;J6ZZ%F-Chgiz?It=V1=}t@-?7*#RSg0(K`@Dh`>wnFuINWwUi-r1 zw^3D#3yUK{%*@|SlSOZ{)_~@l?45XX{*tAn816nRs*Hi4-QF(d%@HEZZoK$S-NaQO zJ$DCEfNqfnG}^k!aLM@zDk?ESN)J@Sv7@Oqjohm7@W>wnmTBz7BS#Pp!iZ5VXdSmx zD#5aCvRKVac;sDv$k3I8a@OF+i#CSB#-af^I;!%vVYl_(iNsR2*I{xIG32ag;<6C~ z@jS{eZdN_>CHVCJxByJDvc=ksH#=a>dpY&b4m|pNV51FpHa0d5f>X^y5B5KQ{aThD zW_+uc?$L`IluA-pQ3pK-nt{(`--kh=8ay7K;T~UH+K5R?;+-Bz%>hiaYdgvP8K6h$ zXnOI<4&46H(fl_U_!~f^0sHJ&)9Cuj$Bs zBXvV|Y&LqMv?VSdaJ*IX7OS5GfSAHkh4Z+$gsfENF-`3b*X0Coluzp4r_jC<2!v%R zXnBV(cm5_aahJ)n2d<{zI5W@}!*ag;JJSXZ*Qd zCkDNjla*6z++dTvTfpDgyzVGJDy9022r~i6mf(He;-K%xkD`RdJjl93FEVb$q$S9N z%s&7#?+M0j*pin!?&J~yyu!P$%|fq! zwZ-PW(^Tec{y@Fmo!@OtAhrUd_-Zd_M^L{evz?j>)&<~QNzp6=MJzqlXRwrqQ1#I( z#4eMg_!{;Sv-W9c%@S&CLg`4_Rr`Np5+GI#)t`Wl#?Txf%6XQ$fo$ z&@dF$#T=w`%R7g!ec8XNoi6|exT#g{>|rKzJ2^Tog`%+7rw31*r*J7P#U5<&AE zbHqUw^)a}&+rG~M<)V}_Av9kY}|P6 zv1ctDfwadR%!s+Mhse_@NVej&LXG2}IeaBOIU2{;{k|dQe_yb?akVV7Ms4EJ^ct+g zk7uIDGRt`MqJ=)KDaU>dpb%5@21~*~yDoO6&)Ah#4x`1cXqFlGw%uG^3aRYBSG89^ z4yBbLcGS7mQRoF|+KrxQu3TG7({i`T7fkn##2mY6uCB-#Ue~#tE+dz{?Rw~-a1*Ez zqcBi6TKpMt7YswpJ_IdYW}xJlgVk?lzNw-VHC1UY@4WJ21qRrkTw@tJx(3;z-W6`; z6=o^CvZnTIa5Kld(2-!Vv-hH)7hkir1rVO6rJq0SkjGk7Ws0{Z-_C>nm$;s&3WQ$# z9G*G)nhkH5?y?CFbQ(LpUn2z-KWzM&{}hHbl?!_qr!XJ^-OACA6s zrk+&dCpEqM@9Xr`O!MGY3EW1{mwK}9)4no7K3Tf%o5=`hSEaUC@IM!Id5~z5QEk#y zV|srvyfu*j?bF9^KM?%-#`%G6=_PMUO83?EggHG!Wy&3)ZW}jDEYw7Y$B*Z+jUbP| zp)XD*vQ3N{$ye_r*6FI1>{@4)7wf7SM~rOP71f=yi5-vQyMa~ZRQJWG8qcoxvt}pxOZJWML}pt|5$%O;Br^s_T;ii8t;DB zte+Ss7i8qYRlr`cX8-0o6-Gnu?QAF<&XL6TMP& zt56LqQzZ_~O2p}K<(kh*692*Es=DiYfyfe`Rhl`c*XGKpesd9rtd`koC3zyYH8t1R ze>#xoo&-1M5Z%8^?YtN^9c}nQi+lKIW$S6x~M~CjuIxfu0 zE+psIh{3nKFSPfmc|Q;L+dyI#PWWrI&!#v)n=1XM{AAn)h4G6Ekr^#f zv901wlZz+5vXN}nUCS4d`zb9NoHjoQGxX2oc;tKF0`X^liEFYgv~ULg*;Jgh8scP;`p}*hX3^7Id;wEisNi zl4i9q5LK1V&b#+N52xi1`V=E(?jWV=oW9#p`kmP(dA|Ua?mz@hQg7FJdfKDYO#O%6 zjQzc3D4U;_cBnBmepKzWg=4Kl=c4MC&yelw5kacdZZjr53f%EBF7hGU`{^A2{%rqq z4%lY*^u}cBj90y$OJV^Yx)MO3EMo zsXSx`^(5nP*_ld9LS*QE_y`FO{QB6wU-*oX`r_(j-w;fS+NjMznX)|sXG8+>H17|w z>f#J{Gj3)^pjyJHI+JIE&5T$fa@xP@e`ash(hJtBM_*H#8~V}>7{xmIO&{^SUeK9@hRke_WiD&0{ropDKa zb0+?fHE*x7`^=L7f5DUS6VJKURG9s|?&@^4YJ^g-rR3*os_n|UsuV936!QE9c#nk? z8Z(z`(UVOtbEkVrH7qAH{xuc%uCEu`o;bS&KUe#pg=&?jV!JeQ_l{Yci2TtbMXM^x zVjgm1sPzF)s)k|eqWZsyB>xk2elgx0_Ao;P4r;d72Gg9h*muFZAhB|aXM^UBr&&}@ zI22bB-sxvPCNZ7;L6)5{BtnXeh||}%ct93l+KL`wGmiAGvDQ;*F>hNo1_@?m@&dcx z>Vfwiv5Ot|{iE|;MC7y~ zW;UtY{@y$*07kfWb@08+dtFm}|95zw(FG+9x#hMwyWiGx>KJu;3`@yutqdbmBb559 zpvCLsa-5EESHnv|=JJdF($yBu?b4!qVtXS>bN;M*6rJv6kg}{cicW8B@7E@R3f>Mh zjyQDDDkkZ8Lw04Tog9=>+P}Hjd22}bA2o&V8f<-zzdEpAocwy9uWy~)?rXt!_@kFB zS8oYYhhC;Q48CTK!Ws_yiBOn82ve5=v8pL2KQ-O(^LrOGg4Q&g(;7mbszy2d?AqCk z0v|<6*_9CIAbyotl#TRp9j5Q0^4~IYizB1qfC$2ief?*#<)oPd&BA?a9FQHCdAC0Y zYJHn!n-Jsy`|7d^Sox1APdEMwA-=)F7h530dI6o_i)2L+(BlA z;Zz=1REhT-|0&x}i>I)ZOdef*w>xzz428wLfzz=dId}LN2vm&;9{uTaJRZ?j^NzuZ zFmS(&eCath?cBuM3U|&=yL>M;gCblhZqHa#j@EQ{m7?<;*1e8$e1vj-7I29ozWZlu zEGtU7j5QL~swALCbNy=&PVeb6;diV17eS@#|HKU0dN-s%nFzPKyipwc!Jo=CfpRKA zX57lbR@$#k>)0NeHR0po&hMU|6IX^%;9&3lt}tavi?%4pn9yKpqW*oZ?gkWsJ@j*P z+?X}2xs1LjCE4E5yJdv_unYl_U<>(GfR+*8+acteaG(yFn`{M2Ik4sj#z}@zU$!R$ z6IcQ@OIElI5SfRWNU)tR?R#%_eJ~8KJGBShWYhW4xb)|`DGp}0pc?qYy9x?g@PRPS z?HBg17jw_H8aicIwkgA&sEgFpM$G>17c;i#6LJ=C?OoNdX}+U~@8jIN+I;dN#4=9G z^Ge+R8h!6fSX%UkUb;mBLQ2C%#pJorXRX@tTyhWJ0r z&4KoFYz+y2#2q6(qX_L8U+_mgU2$7`LK$vZZh^3NuIXgGhb241CM^LPes)|+nHkmCcoR5 zUF*j4p>bH&iuno#Tw_xI65#zOESuCKp}?`dk;t+&$8qOfz$Py~ojdk&JY156A0HX{ zwBsr0dD8WdGwx2ndocSqt}bVDfRNVx?4JDdzN&nf_(@v8_Thy>^H=1TXY)(?UA9RS zmauK{mbeDTIFZ<1N~}R%$j=~?Xwl}yD&a%pJKLV#2JFx;mrmRwdy(<_;YJ9e{;Lzd zK(XE-icTKf7W~*hA-|td=IlkdA^fsiQz61=xH@1K&ZJ`C*jkOk|Bo;~Sn&vVxEq0#0WoBOZO{XaYlQ#8l3S1I{2WAURqAG+_FBlR@8axU** zL+1bNXs%QMGGh2^ucrpM{R-`b>U1sW2!ReT{1rpU;80pa8insq7FALPAtw(o?fQFi ze}G(VMo=jo;=2oJZCBq^X~HX0b$gOjTj&?i#TSW zmhNNW$U9t+x4R(I@|iD-H!xnAyE8-|b7nY$mZ`K4@WL4KHCr$^r;B6`3VcI5n;7&B zq(Zcf*R_}fQmt?n`5`Md{Do)2(W~l$tGbRXO~LkghvfTrW`fI-Ll8!H+MT_ms7iu) z^K;x#cv~<(EsT1MuD0Up>&ti^Y@k7Hv&zfc8N$PeR)5c6WgL4Mr&{Sw*`@EB{W;$i zo=Na}^9*l<} zrAf3l@Azd%C~=q55+}@}a9R(GD8;M<{;Iw49qB#+_4mj0ae|?GOAE-t0cnoTYVC^0 zugo2_tO_HmhmUhOCX!@I_D79<6$*JDoQ5U)H_t{ZX9>JCSL(l|iNvF0t|>i{>Uz5vYr9Wl2%Y^%NB zT!$1LrX5gJ^l^uW|M!LCNBanQ_JGraj7&69fmlyd(CA=itj)ga(=YFa+gL}o-d1UJ2*+C?JJlXMClufQsvtk2y-N*cS+iO zo-g=gIf$^3+}vvXO4`Pl+2ulVn2vl$0nJLX@c2$I>zWVA*+R)@>>i6u>=E`uk;d~a z9bw+o-0S&Aet2$yH0z1!l)_N$P*?ip(7Dy$5%9Wc0G7AdVpO&RX2p_nJbKSDOP{3V zCPKeR>spr_Vqc#;-F!h_3HHxs|>tJ_C}&*Q`3G6Znbw>mJ}#( zxq8}k{F_HnV$P}l%kG*g<@$Qys(Mz?Dq$89AU}hg8{MLE-Od?ypMB05@~HqxmvoLQ z+Wt!jL>%?Gyf)-4{ZFsr$Uu}|ZOkYlrI_Whxt{v_DH)dUaGbk>nVZbQyewxk9#n7a zcY~}QILnN>!%2e;|2pFpiaCU6U874s*V@DBf zx<}Acu>Q45w_wszQr?!{{uKR{yyjyST{MjqCcCP}wYJ?op@xvLSAle8rwKWC#ulJH zkSuXruGKeAQcuEY`MHRTZKb{S*i+p0xLCt23t=r6*L>52S}aW?v(Y(3Xrk9mA0c9e z#hq|n_kp83XP2wNR?+owQ}KQSIwm{F#De;Niyu8x#LlL-Dtu%I+(WAXOxRBkjH*y%< z{stvkz?hu`=RKu?WCczlV%ma=d#6XZj0TljUW)CJ;N#3x#eHhYL7rQ}bg+YvIYP>Q zQH1GWuy!I_9RzBI2goxAYGV6Iq~HWH(9{g=Y{waT|6JjcJ4>%@@DNm}uOe3|A>whr zOD+=8%Ktu&KfIFc8>XIvtTT6OgyhS&g2T_a6*)uB)u2#|dz8eQTb3+C;$Ky({wK%eH>BBwz;z{2*ihgX2H7oJXyA@CjzrLA zu#?VAG(W(ouOs++Vt~3+hx4l|?!*T1gTqZILj@Q2+4V2lezDWXO(*!*0p-4@U4M&H z0T9baoPJt(gHcC}-rsA9ooH=4u*LIAw^AzRR~+5$4E55ww@t@9 zZ+GhP37Rh~Ie&;4K(h$$K=3d$P*6BUulVou3BTF(JD>d1nbZ_N+O@C*&U81)o)Xe1 zo`3=i!Zo4J^3aJEhB=rTmLMqK8*T&@MZv;)rv<&6JN>|NUD1LwI7=_%fn@;<^@Wga zl)*gV%Hc-{GAd1~<)<9zeieRGDH^k+r9!qFomPJL$F9w`ECzaqmgVPZ?Qbd#I7+|K z272a`5{zuoE#o=%@~qOxD33snb)>f!_VBs3qZ0?b+ns z=t&+)SqyTXPsqBJ(2Q+vJ+a#bWP;GYaO70J(EpIObkOR4cI4vxTn^C(RI=>I^JkdB z&y$Ie5jC?vucGkgcCYZ}F{qJ#aCn+ca(IOy!KT^KEP9kh(1z^&-uV9+t#P;(Ir*{O zNq7S;S>FZ#&)q@6Gtz~P%4RdaD#~0oyW~p&VW%rJviuDHgNV9?yroe1cR zXLxO{nq5Bed1^(sfi-$r85$d?Fp!sK{4hZ;b8?gKlom}L5GF3x4|S~+ijmHPwa7*@ z@M>&2<@A99$q}RN0!!r2^?byyF&;0!wV=Tr!c~b|B@KC)CdvWFS=Tz)Kq%s?s#W&L zx{C@6=P$E=>NnFQI3cY@5o2R0?z6aHo>eXLelP9h%{FaDg&$9d(*$6JqIly`w#;Wz zzim2IeA|4?Bc2xvt|A1v#q3R8^8*2J!qQ0%e_a2WY;N;i@QtJZ-zt#%p2Or44Xla^ zlliNLaux~^UuO?I{*fPx@7z|bl%#L$hDfG8m#-6hS?Ln9?1B_IqjbR#ez-S9qm&hPzy zJzkf7GoSmu_g;IgwfEKz1XWBvl}j@mexe`817wtyFH|UC9U#pLG42VoTv>rqS<>9dJK4Fz=L{d)ZvUOzZSe>T52pK`Y)An8>~y zLqw0qrzCy$lF%*Jl}D2oY|B^qmM?)C`L~vuKvSIXc{|n_+Y#Z}EfjwqeE zL^y?|vu^g^3Z$SNvLBz(P&LB}ha-vx=!?IOx3x^c1i`?ld1Y@RX8Y`+Ovi7vhTNF7 z&T}Q^f_O;-*fUeK#GdXsLsp7^ZZ64MHZmJ}`jUfNO|wf0w{!|)ZhPo|EVRRcqYOAM&?m#w;L2KxpTm3eaFu!1&Llf8>1 z3~wxa(j3Q=A=Q1%0?DT*r!KFJC;sD#Aidj=TN8jo%Wx9ELrL^d6ZP6(4$1qRB;EvR z4+`T{gMeuC*;|T~2+qf!bcEd9|9bGnP}l=z8hy+WSF5HD=b!-5MHyPQcWeI({ANkR zs%Did_1+bS01bGfw8U@5QiZhxCm=!qVW<8|Vp78M?$T5fVqqjFC$|^PeO?I;7F%;; zbsCn&^Isx#j*5GXE1A*W5v<897TDPp78|fbdvkgBb!fAPl8pvKft)JW&I_OmD{#H~ zG%I^l;MAePRM8GSRSIKQt&MY9yzGkr!CxA{|NXk%CbUh9od;}&Wlx5xO*kku^=3{_ z*d(u6xgfx1O<4k{yzNda+aLt z$0($79ukR<2sejjV#vOGypM3f`lk%`Hc1YI1wpi3P}Rnwq1a3H^IE=Qal`>6+K$ge zBeD_DO6Zf)7xuysw%wIOAL2APn{;`w_8KrdW*j2y(rabKNYQpY%+1lJ;Do8IzFPKG z**|Q%7l5~Rv*ntlcFFF7eg_rjUzz8=a`*~&=bq^`<^jHvAPii%)9B(+jn-BBj{FP9 z$lgb2Va5?V6w*!f71aH~hW@^U?yPj`T8OeBIS^2SJ{xAHq=fNxJrTnJX{@o4dkUY zidfyCuHg20pwz8Hd>PN75}jI}eV$!M07R74r&#$7zCr`|QEwPjoZgn?*HOW0q@F${ zDOH@)O$G@eCbBu6()8;MshSIsek4Kw3;vP_cSxwMR9)$DVl>ev1i1EuU7?SjzP{!*9H7$T>DBxA-bxZH1_OGMSa{yf=3 znqF$`+)8rk86o&J*tQF=@bC+HsxLdwXb1QKGv@Q zX9B|@NFnq|TD}wP2;LXslA-aSW<}_qf^JOfUn+Ip2r81kwezgL`~8v=?aJ|S`Zb09D*JZ~YK+9Qej6DLYXxb)Tt1}>-KFbiSW<5Q7zk(l(@b%n8@^#1 z1z=}qHgg_T6kN>51-L@$<(w**POq^@<-wyGzUC}7F9@QZB5g_o4`v5V9Y0k3Bnfz# ze8Tm)6W8oR#YN|UQHT-%o_X6}4g5fcElCsZ9bV>pfXT|EaO_|CNUgs3BA1{+Lti4C zR)vJT{I$vO;eXJ%{~tJ}Opf}C@UHD3z>J+LDcbKnJ<7WAiJfns$d@91_CQRdEr3VX z=v_692k=hx`NeOH9Ym255+fE>=Br=S%$rxqvy1T!>iNr^f2}WS;*mxP6XOaBVSU_C z5*qgK#O%m!iTtI#Nk~xX<3_huh` zO*Y6OpYOG^$${pE&BG5i8~74w{3{0ljlU)c!$V}!5APr?Fe7w=*BJ2an4H_zRG6q(hkLW)gW6{p@TW$0oVmAAS&L`W{!Lo>5(2us zbasS7srH3S7u^4=IpFT2#gN}IM7I8yMv#C53Zb*>sY*9)9#z$txH!xVjU@8%XE>ID zB4pB;Y2UD-&qtnrM{8}QCH_Kb4OAQCA=I1WiIS=kWmU$bqlf+uV^jve$O79vq zpsQvjnc$R}65S(KkQEByD5WZeio9Eo%lZzN^eh-67uUMW8^x4PQT`X|K!JlL?vw_PVCpGts_D`o_Ry4u z{xYL6{Pd4D#qh37cbrk|G;@Wgsc#hEwna4)!Gr+;K^oE4O~rtT0(Iikm+&yi5(o1c z!1SnF)f|Bx1s~eD5&si%4%(r*!#;cdxTt_DT)Gz1vWn8K6|GerZT zY9C_p+Jzh!40f`2BHexEPo7EdfX2fc)E%)xr?QV5VfG~>8BJL^aNe}hxvo_0W_#8+ zyM+NTXc*MpD_QBakn$!^lE|1^^jKM^cW6g2U&JgY{lLG&Ajz+SG&O;bBo8jMl&N62 zg@@Cvf{^c1&xY6T6AA$GT<1b?WV$?Ul?9U6PMP1;Rtt_jW&ylTyI)o(J~eOMGd4pY z1prA2&i)hdpzzPP&Fl#LF^6^>+IAK*g1#{ih!Kk*V~Km?YK1h@nL)31pB z9B|&_0{BF>RlCWH(@(Dd0-`nR z2~SoA;y1HP?ah~`E1T_TR{__Pc(eYJnwl(oDYet~a@L$9NP?X?!h1yMR8(?M*sKJw z&^jiG6K3G|hh-27ZBQufrjEj4o^GU=QEEuMt2WRHS}NLCvl+g^J-Fz97(4`EfJxWO zsA|UvY^z>DD0sf^DEVmQD?`!Tq(IweYcIv6bso7L)|bsCLejfr*4|n{Oh+&OitfzU zK&=r+0#O*#1*!?e`ul{Vly_|uCNulb6`^WEK#BimWbc)mK_)Yqfn*JE*~(4I#zw>b zEp~Y^2SozI=T8BuT-JX>5-(td9`AZ+0qy)e(4z@m`LL641gJuLyU_UBh`2~AfJ;_G zP8h22=kmHTI{MARXr7peMEGJ-Tja=wED3E?;Dez!r4ANSJTzilb2x^dpGzP}XgC}P zkdO^(a3DotO+|Pm3{Mvi(c|JYJ>6LA>q(gTxjPcNyBn?!21aLRrFiw3o&iNAOB(ij zQ}O4#9?>R^3vKAUNI!27-3TUQ>KKT@1#1_gn2x!1;jO3w(1C%;oxX^p9w; z^+H*tV7!ru@yZ~P0cIb5Sq&h#Sz}Yx3m*g?QM*9UYhWM@3$qiPj>=FW=C<0{gW%jNZ{@JzWIfkY$<`2SB=ecUj zDMPbpV4uuuM2TLw2@mI;tS9#gV`T%-D=zP||8(%t5Vr&>8Z29c%}s@jrCOl}Kt>fz zh;FOUKx>}@tg8{gx^DLucGc3;SRbg?I6&EGQwYWY@Qq7p%9yn*S<5i+1_Qpv^=h9= z{2d3LSJ%>^0-V)cl0)Wugi$AkPXZ5zE?}>r&c7TkB2QdG`xh2<`e6*nG|oBpjZ`%NfrOK$xFf%D#Rwk&%(+?N*9m1ECIiWF3-w&o)<>vk>Ru zl3Yl!Z5Q;F6_@R@ZdTEsnNs*us6a0g7!11(in+C&bK;w`wHLg8Dj@Io2Q4OvFnMs~ zOo3};(|KS5*6^+IKCrRkJ21zOs{XCU$Gdzifp^BSrVJ)4I2MnWd;`}2s%Kg+OPgt@82R*rMKQHh=K(Fx?3siSH|ih8gBVjF>v#=TwIx1QdWV4;IA( zp~rf9I_Th5(~1V8AvD;s13u?>ppz#PJ!vMY2EfU7^()3&WH_azWKAdF5YL_DyKnph zg_Eu!E(o+eiT(_)P<&uM%9>q(WAKfks1#FGE$5&iXRZym1oM(q!U=Dw!@|4^rzr7J zP zIf78|rLQv^Q*3si04;q1ib>5$E;Q>~8SRuY_D4Wxx0TD&J_`|V^};fC>c+B-UVJW9 zXgyn%P!tKs1uA|$uvkJ>Si6@X-lzs|sI7EnafS5q1|^`5{g{M|ynXT_3O)+Rytdk< z6ijKD|3ovJKfrzhOc6sGeN1^F>hSD#eF!gHbF$h}?jcL5_qinm7~1m4U81Tk z7b7AfTvJmM4F^JVFuDRCQ(gqj+qOxB>Of;Q2#c#x9bb%t(>XT}Ged-4S=2tzuM5X~ zj3ZLyE|dJ_gq)hHK9{zbG!9g@3ts+&v&eyH~8waYilW$a@o`Wli(gIwg3NO zef$HRCm;V$tdBQ-AN(^9D0UA&W(*}si1OF}3I`C>b>K`^BOUlSQV>ctqM6=kH}osv zd@&9Kz8sA=R+o*vyl1&xhZj+R0naV2Ba50=?QrMh8ac@<0BBg$sr8>W0rI2p(<8*F zCTvs;0XBlQljKKwnn?YNGnK^`>+Z|XItD~o`ybM~O-$zHePco=+agC72$pY(OI^5S zLiRHEl80g1sjB6p!SEabqFb6oLO(T7?xCEWm=l_k%4Zh3Y#4?5@a)4NC$W2%0J~II zyZCjEcv4-o1K8?`7vV9nwRNPKnvTW6v6^T|mMraxv-ulcmq#wdWMBY&l#chL`U&7P zzql-MmK3@??R2vj2yZ5lUl=3aHss{c4aJ)~_YSFd2wR`F)@tz;y#W?1t;{#?zMr=L z(DzoAgy!d$yYP~V|6hGy_vAa_cHkE(xg~PT;kcT#4B*q(xGrnGAQcm239|u2$?wm} zadiKX>YcYImi#a!THT_OGSq;UV~h$yg$%YsT+0>nuf0RLfQxSu0k>)6;5T2w`f%mn zSUiEsbbz@x(>N&H_gHhu;IF&G7ekenF5>?Z&hN9{g>!vVUm}6F3mz~5fz#J)H2=|y z21`Oxe29&yA5{})rrg|jED#k{&J*%%;b$0is!d6tG@?QY$x&#Pxfnx_m!GuL>0G<; zB$rKUx|#@nx+E@u$hvN>xy0P?gf%!tgoK08!RHSEA{{^_wD6g#ihOKN4o)&)h!d7$ zBR1C~tb>F2HUkrZ5;&xvfY|HqTh6Bho*NXq;jQU7_d_+STHG3=#JGO>;Ui-JK z9Co-)TjH7e3CF~--T#CJJL%)p5|#O^hmBqIh+o;+`7vPY>tXx;_=#zD1qrYtgJ5KR zZ!W?%40DKH#QYOPe~ly5nv;V=@NLbKml<=@xGh%OnG%-ljk8=uk|#Sf2#w|B#^0NU zs4Le76k?6?5NAlsB6$RUC^{70UgpKemtbVwjZ0C40K_!~*HxBC7_R126^ULP%0TDo zXNFdiJ*MGad{4}GS>Gr+)`tY8Zp8ZM-%%`FT}eQlA>>9*?YyEkUl7X|8nV#MbniJF&Ltn9RFpb+L2QUA;T zN1Wkfefq+4d`0Z`JO~N6kEv_hF(R}JQxCjro6NmfvwaI$k=y@fVZ5 zvcQr#c^u;E%I-GAe2X{qbT}Jn8+wMFvDK;Yh=(`0528D(Zh`qXDL+(51b(jo&O~27Kw%rI*@6AWy?zS0>M7!M-b|lR!M) z1?fibF{C$R0Yj%Q@6A!3YzNucud?Rp{E2b!rjrRNFXx!YKljIp`s!I1y zSv5{-1}yq88Gyp*go}@6NwdGhCjJ)+LoUeXu4?jdbCcT7ie`+_5I( z=ZXQ9_@9~-nfVe$G&O5MYjXGnNYw1?VrlTFczy=~uEZCf!LG3Y-Fn@QYcabd=c`Yn z5gpz2YXt4GL=Vr*o4qs1xY~&%25&fgqzvyn_|buk7#>i8c6A+;f(Ri(fnLmm1DFJa zLAk8i4F<$R;XQ^`5hQe^y-IX%^n$N7>zRW0&*WF(sEz|o$?|XCKWvfHXk=;Sxqij! zy_b|LS%II^4C;+aw$kxh}(^+khc7Rt`#~$$M)YVq`_|5e+Kz zlJ`AO7NiZ$*p_A57E-ChmALw?h|8t1F$%3d*s__OhLiBFBvJ-ZDYK=%EJ${O!ZNdp z;wX)Y0S)GVMOD=XENmFH!NI|_w6yJG6)o=zP5tk$)Xx(vw4Sm)>NMw}(&f}ZyFAUy z&c|l&{hZTb-?P=DOi4v4M};5Cy>=fs4Q|i(hsoqXAB-RK2Pd&eO)jj`xzAlN7{s%A zX||CfleZj=jy|ZVX|{qMo}CT(e;npLLpUCJ z9lj;PNp%c?-)I-Tlc8lK9tS*I2oFhzwl(T^%RTfud!4+0KS+BScF%CXJo0hq2GoUj zRT=q(N+;{L;I{CAoF#yHOLs2gVrvLL6x=xq>IM>H2hzdgUlh#M9%=%Pj1jvhzO9De zBnThr1cAxQP;x4u2%%i(zoOlMW+G4+zq7?s#t1qD3J725^LGvR>qD?r;b5VZI~lVF z%TAc!GQ}TQ3Ghz^9XAD#U0_{H?ccv+F?lcJU#(X43ht*2v;09+us#A)D!DHI5!AIF z?)dPSOPb*6ks0qcxixg*`xWfkVJUmXX13N z(xujGkF$zakb`rSkoj=Jb?(L|v+qYfLHo|$_28h<(cdOl$KOL{g-XZz)T>{MrmX7k z-_SzSsLUeH*Ef1=hkm99+d83beby0Vki|P3tskY82_=Ei%e&@bs%N9L|*9>R`Lmu%&4hVtsD$gK?f2e_@i+Db3RvuUYuxlVGISwk{h=d zHLbbIKxhkRffakzS?@Qvk(nopnC$9)7;!L4`|dkiikJGUV{YWC8L=F$CJk&Yz93stN0( zq$ua3kiA|0Cl7DXDIQSqiO}9t*ddX=67)Y3xP8C>DuAw|B7kw}z(t&kL%~Xeb6lVm z>lh#%6LB%7kh789YilFF-9|pfz!U(N7~pCVi?RWjjD=I1KVDLm)ApP6jNN@5^63M^ zDu3pE$u6dPS8ZFKr3pTh1MTD*iXesPuO*No+ina>f)3sR>} zajJqS9J@F{dnB>eCsjbE?E&UU$?7_!o*%6toV4oa3x1$)Rp>DE;SNnxbN+&TGef(7ZWS_bFZ zh%{{<2YQ)Npig&pPPG<2zuAU7MJZ)UApVf*S~q3OdXN?bH|MWU^U~ou|F*@Qs37dj z#?{EwUXn9nGPQ$sSu99kIh@gIHdFRkXUebLTsLg%WOWvnw=w1C=W~%yZv5x4Y#uDu z0f%KLNviAgAWsGtXuV0ZAv(8_A9&Hj4ajBb=2BAL7$Wtvs=RQ(xj~Js@5cECu|2?M zf#k_9X1&kmaxawdY%z^sT-gW^YXPd}o+Y3HML`BZ1m(U=*y%YV-hk1kJcCkpZz-`d z(C{xHK-wLSZ-w-(|5K3r{owAHxQ^enU9mHrcMFWnjEBVXRy+fQibk8qT5Z&!GM?B|N;bNlAst&E06Q*ACd6&Cc8)Yl9g5pD9klG+RZZ&&i@ zaQImB*&nnjeGrC3218<$C&eKFPPWV_&X8nt%*+LUc=O3hwI$}+PT}>`2*dk6ynFXb z{;a3bwfL3XQ_)RxDllhz&pRmx?U(-vn2wrOdiUW10r$-sR)~ubwl@Dgo!{)F#K7qo z;R=eE?KIK=kllvRHbMH;PlsI$z}q(W*_uOsadp!TFi9Y+4iX)ciO0e{z@wl6z7_0F zyk0C@B{djfd8FBCD7C@I&SId(DKQBaHni&q9d45g>kWRxG^`6K-lZrqS>9y;B&^{8 z(kAd{@slw>?~VEgj+j{tCWhZaNV!c3X2(X2qc5=ME#$Q??$rxjG^|`2q`!bg9 z-nWRWMC$l-v7me(X^^N$?$-v|l4nTPxHAJmxwL05i4z!rDEEfJPllO;lk>5lM0j0| zwey7ihtou(#oLjvK&6Pl2;s8uz%oc8)g_Q}1nK>v{83J50CXmVc{!5jjHNUyvxU9x z7C2d3@As7t0(k3+QImIKaz`yj8M}TADLzNz8o%? zje(p&c%2v$-MCoc$std=_dlgmuW>T!>^vVGbRK0dImS0{uM;5 zJ8RYe!@d~f*avMHJiB+~qJE4Z#4 zcHvsXhqq)mzc$UP1q2D1TclrwnvQ z0k3Bs*-G!r!MR_)5Z%XTL<-L;X$2~{ogZAwhju^|4TMF%t)C@{TxUT!gvj^p@+|yGC{ywEI^?8 z2m4MU`+z2xm%OIZL4(GH1_>IBfQ>Q{6Rt-1)Dvbr?Tvwgs1Sk+6yR*MePDL!qYZ2z zX09j)ol_?hAe6h{4x%5r!>XOt!rPl5$sWoLbqa-Q{ZkAf|MC)#G44}kLnWOtpirn6 z3`W%EXxBA`(C-QWl37yxk1x5S&i40GO`5ZPcg4r2>Hxud}>3nkkw(XdBKDd^P{r{w1M%-H?QX;LMoaFmf&^^ zvQqQ}eS9^YRdBueYyUKp=QPMRtbR3y3Z>eMgojI*YdFclyBClnJw99&k{ZU18i+#*QL+bq%x$ z5j1KKkfF$DVy|}C^70^1J4H`N0efOx4y7WETJ>;h)w_Qs`u>1BaTq0xF+6!eu z7lBzc3wgOjC)Xlm@hDURvSNSRY@m6RYi|@Zy;+Kv65g7NLAqzOOtUw>HD$hgDLl)u z->3(4lsxu23b^q*-XnwHgbzM}P691_efv z17@VSATR)duBqt{{BpMoRX@ieO_*{b^)NR5Z~yHNTJ$y@;Kf>i_d;Bf@_+r12Un$? z%T^`$=6w-*3N#I3^;wWp&}K%40Np4a;AY9H{doVAg8n;?l);cFIDeu1?QjM2wb*+$ z?IO_CZ~0f%0`0H}5GIHGzq9mHZ8r z+_xxon?2c1H?`vH>hnObo{}Er_=H3S7)UW;IS@I>$w7+O&YNllgjSTty&2SI{j@nz z=;9;(5Bjwm;pUl;j8)~JP*T#iXPgSPrUJSSqT@NFZdOl^=!jl2k-Rh&7+glI1a<6% z$w!DB_*USzd1tc?1SPT z38yXGlII3ZSYeidvh$VZyDwv>tVQ~NUP&M&c#)RCB25{Q$8E7>5R%={-HbMK%Lbw( z%8Z^wII;a4-CY{Kr!4nKMT!^(vjtY3_8iEN2coa=H? z^NYjM29G#w&-vYsl7t78RG7=B7vF{E9LxuaTblKwdYL9IDw^+q6Y$5+LHcao(Rh-Q z&WLKu1{Va6agz-NsKQh_t8@|mm&%p1z{q@j*9S#>MrGVkBnmJu#5+r1-AgPdbRAk4}QG z*DyREC{^@|R0rIhex-1llVAZ=e(zHRcxKt9gVX>iw* zor|AG;b&;-!#HzhqH_ro{z!2KT6+3msQtaX9MTW2u1j3p@^V5(Abqu=#wDc)v{oik z_4rw?${37gnucdyB6KH|IV1bdMZmo4y6LZzf4+xYwXPk?qmDZ_4?8wb*?PB?KKHWu z@p-hWVrQsgx0;fe0B^f64r!Y|XC8Bt0^v8=jDbNuQZH2aQ4?xpN`?h>Dl~ZP1Udqm zr+yjGxW@0V|16?nO3AO(i^{@(-wzfth!#~eau-2>kHy7$9pkU z)AKy2{*1BDwUviK;%i4{9qUzN4YkP!I3Bc(+}4%f<>rWUoP=aWN78ed&8R-NsfliF zZB5mHed9k&F#&0%2Sy#Sd9E3H+<723<#<1=R_VAulhZm$3Xu5YtovfWu#8v$Otptu z7DE}4rIRMNiYQ|N@I*^m9-_H?bfa+U{KO{48fu#t@C!=RmtFz5&OabGnaL{Gl+oGo zYr{2RGkjsTY)eS_{ig~JFUSno=xn2UitE5+C9p_;E{Jw{`#*-a5=)^>z3X3JBq||)1uPL}IHStRFRC4^6uqo@{IsI!28GRx702--n5VL%x zAV?cB6{eyxIyM;=l=HwqS>>^z7WyrfK8xG$e7p*yFei67LuwQbwT=iI@yj4Xf|h!8 z`FG4p-;%zXL)=a;bIAFIS#>1^S>WTg-{&WBkJ|%lyVkzE-zi9ESY6%7V-clM5*PnL z!w2{F{xLA1=-^OJ3AC<2ti=buGK)NZ9ApuJZ4LbOmhjhZ=Pp<>x85Oj(73c5YkG$O zN5wF0I(Ch$55N?V3)yS*i`#eiC!vfT)(*~Zl-_9e<3zBB7b`oSb|}(GU8WQJUTlr% z*D$VFM&WJHD9HYPwsdoCuzk2RFYpds)c+_?o3P5GPUc0MD?`j*d>hZRNS8owqcRhu zDOX&Bb4yJjNLABprvZk8XlK_ki@kYu=QuDmdnh^v3=LRUl`GV` zGaTsR-SH8>l!M{^Zym)d?pZ<bvLf-D27Ryz*Bse?-;DFe`UjM5YWSbMd^d zuLC*sK_O@*C4srQ({l==R?`atp_GrM9_{^ZDc04@KfKzo+l>`5NWe3QpvEB6j;u@F za>Ls`)@dGh2TZ+iC;yM(i#Rv#|9VQ4oOGx9W>*cNwBB_FvPU;(S8 zHkIh1Tv#;=BsIff=|4&zP`-b_@WHe+RHJr$>sWB>cqAeb`CJD!Zdy9_0^JDi^!$M1 z{ceyP8qhAN;pv(83icttj`}ANJ!#X0Z3sR6nB=022*(`BP>0{hP5{k7hDs%e7iE&k z^7qe-4|Lgo_G2oGeI{7PzsC&T!k5V7@MlU& z{=}A+cd`!+5zaHEud2N7`j6E31zSNLkQ%XUG7=w>WUem#*CP3lWN?X+uU!z9>-fq; zqui5WN>*@AWBbUmJQz%cKL+XxLRuDIX4ecV4Mrw}k|o|*ZEa1QEPIyME5lhSyMYl8 z9jW4xojP1GKImp*?|?p|5PQ_J^)z5e87bBs1C(EU_1wmZw+fGCfACuv{qIVa-1=Qa zm~g0n;|8=7ww|#v0d2$g{5BQ;+$P<=|MM%~1tLgS7lCypwAX@(ihGrtTZp?&N3W%? z7kYK|F8RyRi(Lz{ct+;Cwu#1XGU>lj-Ci2RSMKh3LZWO==WBSM7VZ6I%tZz)en4zd zuZPno2@#pnzW~6KE#dO4JpA3B$kT`7hgrkyQsPOj{B@sCuUrvQ#%w>iy92y{Zc-pHqp`WOhw35cc8Ebedz2 zu)gW1)GgcigamfG0*3#%HLK;!T{MXS4K%*h;7u&hN$n9OKkd4<^Mx1SIbEd1!C$b5 ziGQGK0lOFl+Y36~oG#sUbR$*^H7zT;5DQ4_FYcbaUMAIj)@iH4| zmvG4o{DR%&CsW&C{CEk;U!mWpqfy$(H@ZFgR-`w?E-8XUcl94cgFCqmvz93u*P)(% zxa|*y|H*fXP19DoH=+xX?fnUONl62!wAX}KXk>CwXz12jlGX?^9GpcW>?3VkTB-%s zW)(L2nLqagX)3A7(~1>KY-Z8^DCgKK z+vnQ7XyF~jIV0nb?ajdHx9|JxGaX#iEn}WiElB+qSz^@lzRFC2gobhi1*;9zu~efV@_WnV}o-a@z&)Q#qa>i+PG zpNK4k$X|Bx@C8wkwi;}RLwKyD3{(UI{oV^>ATDY(-Fz=k`(Az(D_9U0;|CQVyn`h& zH=lZWMj1B)MA+KFB0R3j2VbsGdISCX0$lrISR|egV=qS&57f+v3G`WQxa3IEexKSx z;LW*FblOc~czaiyG(lOV1du_ToH_H&xLbaEucyC15Yk}!{u$5S7bQ z*wo~Hm+zBv(6AMhaT9R4Gs=I!?UzMUBJl&7YcWOSuB06(HLKg7ak<@fJtCUA!wvw# zkLA^WD0JJQ;xovZh+x{p8U)D@OP--P3I*YhU?j+%3TLm3n*iY8;6wf=^dMMpub2Z1}+&n+9VLA5W+-Kv#cF3;paP4R+OSAX{lkbFo zmO96pp>Zt|A}wJ0<8(RnsvzIvo$yi>t5o4%B zeg*asJbi#PKD!Gz=T=`<~zObU0u2Zycif7i1kSn!{TEj+k#TF<&a4doC$@aI&$x z@w5cI!vbA-eA$*W+piWV2=zAE`+`JG#{Eio{JX#CXzkgHsBdc)^zZ2{z+)OSVE7ul zS5Pw+)9={w-$9Xf4|^|3#~64^OD7(;RhlzWq(t@% zP14iFLu|FTR$o{yc&ivvbUt00&iFu{r^PF`eY;A*Xlghbn?MDxhZn|O{zK`s_>P`(wuRcwB~h z`Oowcmf`Sl1cF=3s8rV-{;MEXgrSb!rnD4xg0P3estZC9SMygX`0>;=@OCVF^(j|( zcxC>C(0HmG%%)g)2(G4f@R0m~J&xc7f%TITjr^TDr2T{hhG_*)tEpbH2zX4jc|y~! zbAP=GVQ!>l;n$WNh+6*jrNG+y7~-IDy1p*tc~+^-{4V>bJ#c)CEv3@AcrLQAN(lDN z%-?}Aj8hh|M3c1@y!Y^EDa;05_kxJ%Bwy%NR?0qPxlyIwL4R`#PB3S>IVye2J*4!R z+qXzR2$8&1ZmMU-lP@bBV7f1q_CFKOxeDZ7Pdj`Swm^Q@eyq>G3!W#C zd`>UUAIjEkl7>)K1a6m&abb133wsrH0b`AkZ5CfcT26%xpXLmAiX2~kH4QBSBCm*| zkmk0F(~-!RCo0Fa+lHUW2V25A*VU93m7Z`@d=>7ELLiO+0*5mXz2^KfAPlXY9!&HPWz9ky0n31iX-xXc_I3 zKNh}OGmx+R90PR|PXc;dy)59vpsN|#;$@ZFvbM8{^l!H}WfvFK5*|{e=1ysT-8fr-WZGBdM>r`v|YjCQbEl~X&6pUn#xAvUL%1Wq@i1d)T#+ObqQ zC@adeGCP3nrEiXogq-F`D~<1=WZL+uk0Q$5WYTYL;VQ!9Z19Z)XheG^mzrkx3tyul zOTrNK2iwU`_|x@;t_GAr`^LV#5MmuZA(F7%7Q1T@jQu|i?a!vfHfGE=F*Y8*x@wU* zKOa73oxUvpKQBPr?e8qNwq~OmV6z~3p$7LGFht$g>IQ11oGIzK+U%?tG%TZYJys|| z_i5AoVQ$Zb4`O1RQfM@_Jr}W=@*HAe(Q9CnZ zSMNn#Q#=NY<~m|44XP8ROTZuXsI3RqLUix-NN0Mt!X`o>E6&}oA1mc)!FpCeF(Pyk zHty~SpMb)bV^GU{^5f%h71nSOQC{j#T!@iuUB6Z-4oU~G&Gt5|t9Bf`V7A_BI(T|H zpvUx}VhOf!C4%edfYe~()dK_l<>fpq+>84~5@~ww9C;=7Aib1G1*YitOwm^| zSy%pTrpYJMpYVr(-0E{t`vnuTpO{#+zz{KBlgdmy&^C-3tsykI$I)l&P!KiAu#S7{ za@yE?-X=OM8kSN~2ONoRs1%nc%~X_sm%Ij%LqWdF?# zJM$sAhZ@xM4XV|v#Z7dzvd@=?*UY9w+Ck=B%>SAO1=00^#YbHQ;{Mk&3tMI~HwKeB z+|oOnBg-jIRoiaARl{JRNo=u|onG^}B&(Ox!<1JCYQjH!YMmS z25eDK2DT84O?KO@iB7E3#j6*IWb~CWr??>&X@%eqOERXw>vLX zp1Nmuc&bpPSldW#T9Y*EKR7=~a+z{@)%9*j46u2p3}b7I~m~TrJ+ODc( zBqWQYaX8$!bU}q0)>L@NBrcV+Y0E7C6T-G#8OQOJHR>Uz=AwMZ05cm$%}kYOJ>e(0 zJz*s7<&B27lO+Dxht|V9zosC<=Pv)fMzUBh*-$&uHa4$ie||f6onVe(?ajXkP75F! zcFRJu0H2!ZOrjv~UOa)->MNtnQMm)b${f$q2**x@8+To*b5Qt??7XF4+9|+A-QM^T zHm>TKZ1DipHP=mVq#8fe(BX}EToneq(Hy$#-+kpvSI)lEZh3Aa;wAcBF%9=a( z>eT#ii_{xT+7al;+3x1^sE{q`&uxhD<=l=v+;Fj2q9sriSal@0%n~O`DAXc|LBP8 zsaVlqqpP+_2BXysjG6o~Ix<=o)XkZ-`Dd$yxB?p@DIqZt{LLYNqNZ(*N-zgZkt>X< zRZ~*~gAGTo`orDZnrgp7o)iOciQL^CjM~wyt?)z&irk&JufM4!#F){Xt}@R_f+wX`hWR z%kX!yWcb``2PEATZ_*~mz4!FD{0}6r`@&uTKe++a1VxFw;^B_^?0vLate-VkhH$Jv zY#Vl448hYiuiBmSeJ@wDQuNl6%u4JWGz#C#w+8Ga-|TdeAUt;rI&cYhcAH}nWPdl0 zpIHSZyl9S{5E`@k^)rEB94U`1Sova8v2m{hs15?bac6s%v+Wx=}4U zDLy}a=Ac9-MvYe%W`o;l!TZ*?{T(frhzX61U3%}TH?q`yC%V;%c@7Ky$I}>HqKie`|bj2L-=oYv>BmLpTu=0|cJjINR z3@pg$B7G5qhDE9^kdGQc8(;AesUJ4r9!RA_Khg*ro|N&IPm0&x{<3vGc609=n}Z#V z=G_50cMnxYMvpVMdWAIsGfD~>;f`O%uBA3E!V4?w0E!>-^K%|`$n(3zA-Eg-L{^0 zJf+Zdu>FFAvuXp4-CGIJLpaKgdPcw6jJ`14+?g)BxO@saESsM153g-`XmSBFlf7&- zBUzcFgGrU;>+JFRFGVMqL=Cv^1u2j)msq`hwpUlTRnc}T-8#8YQT|f{F^TA_p|RL> zIkS2b{daek64`T3lrnhiWwV4yJi8|}w#Ss)D~`h-VXz!yuXxBKR&QhwY9Bkb{y0&?pqRc0#VsRuha}pgf{H_I+l+E?*NSo5RFkO2TXkObm?22Rq-dQ`5j(YQL@_^w`RM(1cjt7rjpcQIrU+_m{d^w^bpGQRe0#AXe zlFQhb>i1luhxXKCL}+}598-s|HxBoPyj_8nT#3`hKSVvVE}tG=8RJcc>c{vn68xr4&+stubfpgObp#Ure}t>$nOWNQ`g&Ou-PGYf`_;sB z&20u9zGgJ;ji68V5Gd^^gDDD*wZ5)B%d z3jGO}gPoff(G_a+8(%(jQmZEb+tSolzKYwqwJFsz8PNpt)-0)0gdB*+9=ITH72t8} z3#5%yO6|5qL^zXo48V--4dee>@>i+{RpX7UBcD3@UBmrv!(=yWfZFW$_mCc7r`MM3 zjf&;P#g1I6jrU+%%7^}GLvLl3waY8l^R^4sCErtBahY-h$BO0kW9y$>-WRoqvt(gd zbWRK-&TQ%b$JloVQo*+W=R{UkRwbi^5K5tJDP(6mHW|k;!?Ee4XrZz<+2h#9UM0yc z+c{?TIQGc?-8@gv_v!h)&)fS?iBsLuy}U`Noza%Sjh4AA(U6eU!?AbPc1FDoiZ%h%U4k&SH3WW&Y1UD~n>{BL-C+s-xRI29%=cBP{=r^?k|bARUT zc^TOaL+yxz@7R%ENuv>uwX0)Z2ja(Zcg25ZXWuc z{nHSC_sU@%`%!d>adJD@E0tq%`)R)-a$aBd{l3MfKNq zqTIcUBy(=Z#hh8}oubud>$%KYBVDHi_=`b&j|T~+cf7{OJ7+SgYWGsBKo}C<_i;G| zu|6HpLrKo9s+;*zQj!*=D&=N88hWo!4B8cA7e7bebFnP2r@5AdaTZ2taHW=)-)?K` zfLk~|=mH(YAm^bAb z3m`>T7n4$l+r~z<{CwF;j&5Hglt!XAZ@o@LO(DCxKV{U9Fl%Se$pw{@Aw>DLbZ2+N zlG!Iinvgt4NKa&i{~Gll{F*(rj+-eVY?`?i7qz=P-D8VjwVn7e>@C=FuoziXtMvF9 z4*T?nlPs}lR7CFU0WvhZDudE(>#FzU>SO5o;@)qZjCNP%R@=0*%@r_*VBXb2+lW8Ay#QfWI8IwF8mlQ61Z>`erI3_V&8cW8a^NdVPaif9tN0bwZ!bX|s|RmgKTQF`X?&J{fToye4)7Y9 z?H$|~NI3P?lcQC?2xrxsXliP5o;?kfD$^Ii&ELtkCn;R~oG|HDBCJrLt7~rwVZRHH zPN07A)a8>Bw=F;HnPqZ8!?~@3IrKUR9=27NPacXN!pm#9ANkr(9PY2Ij<>a%VVtzJCfs-K9wZ#dZS?t|oRmPG z;iNG=+%(e)qqYkF?l{}kLc6n&Wkj95;ZXz4%Veb&a9P)rmxYF+?B6VnJ>M&}%XGBR zLVe2^7V*+yj+4j>0qoP7jgkxcB~{f(Yl$2AAGT1*Nof>nu{dCYnP|3)hgrgRxd3FK zP9YOmwBa$tG2wkIUMvqcFQTS?kN#LZ-WkW~YG0X+K*g0v^W%y&!xo46DzV{p88WDA zD6qvwD(esR=F2AUrMpzHsOsf;l-dM(vn;=?+jpx<%=A4T)TIuzzVDI1^W+`f`@ zHb1oz5y7$8US4e*iNSg^hwjX`ZdJod1=@;Kn6g(l$prSMjCwYHlLWB4dVR>!^Awb z29~^Jh20!PmLOX-pPz0gKX7LX{&KjMkaf_zc&e}HL4u5| z*!j3+c(J?cIFFw^)2#ZOTmpYnabdyJs#3cqS6uWC1TW6kM&s};>zstU8X;($1i{DQ zmd!Iu;;$83xKHiJJY`DHxymqvg^s*P8GcrwytSx>P}eEz@<&8A0RK-8slI~S9rTVvSKmNJldL>=FOSaZp3F}D2LVdpzh zvyKVoinL{p!<;F?+P=zkGhz3ux#3eekc$a5Rodxr3Tpvz=H5?_P@R5DoMLXua|`d% zlcj59gD0wejmV6AQD1Oa51{j{J{Y2xz7vR=6Irma7)xM(Y7 zlAip+HT#quX>hD_8wZ^DhlWW3j`MVC*TF|NlsUV!l6M=P3;7)JGC#vF;?}@bgN1kP zuJY4F_`*Nral2LuP(Uv+c7CntC{8%(oCz0G70Hld{EFPa5a7g`pAIp5@su`0AfQKs z;nnPXMhkXuOSK>0im>+y`s7%?V#a3i_93<7ALQ5X9QixiE8q#Qawz*)mB&I9)JMZdkO)>7rSzt+;I=;<y9kN^0^KM-^{ar*7mI zj&Yga(Oi}Awr2d0$w`ow=A4Vx9GP3}eZeZ*?K$xr8XeQq-=9GOrEeY=Yv4WRd1@Yj z=Mj}y0eBMl08Jl$;-WTD#+bITwl<_(t+*>lZ-Vhop8h04>vpY@Dop^1DfTci8gwzcodd+BOJ8p0#W=0x6pEUCTkpf<;O?G*Ou5UKBqUCh^l68$U3?5^(_8v1 zw51F%r5m=+y#w_!LHDOJl3KqG&|4>@u_{)oEXN|IAx*{3E?%svyI;qA&n-DO1~8FUV(a! z_~e8TfDeySqOH}XzJ?FxwEv6Ke0fE+7Z0Pz&g!J7q@t%(+_yB`V;|t}3^$SLGBD6$ zu-&QN3ccPIA)YX?LH9O36=5(M6AdlJ@WM|GwZm71ex#k47m~8EJit{=#cY-iiP>+t z+z#05i}_lyJ={V7g5{%{sFE3HXuK@NWbHb)yZC-}VP9^`p_c|)DU76~htvB<#yc_D z;!bDPZ)v>daO*HK|H-(R5LXMW;l|)e@725MaJWlWnoKn#qcC7jq{YO9zYd}1=Bx?) zq};c6b7Mzf3ygSRuA@AVSIMC2vT)K;{aMT(B!m_)oir>nfS|kM?YgfnUn>diQx@Uk z;doh`e==glgQUK=@e=ukcW-0a9n^(L0Re%YDW=-8iMQ6&Lt>=Jpj#);_ZK-iUBZuL z2caLd-w5E)X$|4nc7i#t8tpr1c4LN#dR^C`7Lq@>kpG^7+NdYyoGiY515nep#aqnc z-NC+_H}*}eC+qw;_sCEFI`=0q&{(nx2hJo{v|qY~}m zuCIK;fmG%IoB0i0%@ToTY)|IIiyQKcBAgpcVHj*`DjT;bLxsC~l3pnd6QgENf8?<5 zl9>1WM}oN9-WXvB^0DY1OCLEOC7ng zSFL{8FkI?4PXBn91HnVjs7K#&dhUt{N#wn440c%?7Tfo+lI!DOU$3e$EW+XBYuAE0 zy}i}Et2NZ?u_WNH^?TxVNyapNakAGrQ1Q7eR+i`N5?8oEwpvp9rK>;jwM1f0)hZ8f zvyc!6fCCZ&sVBq2gwLLy)46QQC}vV z*$lYDR!;9P^FORtT@zTZwcH@$&gk*knT+E)awWI6v#+y8N1-l{?=n)0Pag!TFk9O& zE^apQi-S!|wiZrBl7jGeOPeNk<+~AEdrC$fVjVEwcnOu^;T((pDlt!)geK38!kZ%5 ztskVD5eNky9<^&%Iwn%Ql9Ne>%96g~uvupr)ZOgb?V`n8r~Q*udf&^=h3TB=i<3FoDH^jVY@2HL8xCXQ)^d^)AuBygqW(!Bd`J z3X?tFIc>Jsn?*5&?n20;dXDl&?&!K3Vnv{Y6^=>wfEJ?_9FuMct5as7)D1Z8{GzC? zR7mp2@YrM-z;oi1QeXPyKGOfXw9=o1F;-<)go}|sqgmN)dFv;}dgQME``KktrNM&~ z^IeZVaU_K4xw||1jdjR-SN(W^Zpx4VhMNP73s4%u)L(U8@g^RwF&TZpHZ8 zA9(o~4i`Ltx$9-GN3Xu0kDHI1kTlLm+Bo=fX))>NI|(ZDiOY~DP*s{Qa16OC-@m_KB&V3iY|QU$86Bu44Ar1?d~01&hCNkgKS+s)&Tmv4#(gBG>Q8#y zLkow*OkFeSzjyBP6b%6F~t~XZ45?8m-6`z;cK_G z@=0t7YneX{fsJhgIW z$w1&;qhZ{fR|kh1c$2lM(s+_z;Wkm?(V*I9$P{)4wzYU`G=kSTm(if}gU8llSRAc^ zu~rcX=DDexL5no|7gCEyO&EEJx)B-4p`R_a@Hg)oUyt))(||ugXHShtmE&|0KTl(c zdU6E-LuT89I2iJ7?8^VWMS~S@r)81c^@oSZUA`$MhI%pG;bQ5gQz|QS^QKU`NJ|Se zBfCq@79~ncyZZI}%%JP7klT0a_I@~ip4XgOHZc!o3X6_T`79$MR~Z&V{1UJuYd;FA zjJz(6j5lU2?@n%QPpr5t)Mab9*+=Ue?Gz0zttA{{@=z%B!A=#r6;4_czvVgKu^NnC zt6kkdPrHdRMV+nrw(KdoS=|R8%43EbmHH%j1~n#=1j~j2`G;ZN9iQ4P>5Dx;Q&f%a z5r*pN^$d1j&eOHe9@Z-t6s14j0X+O+t~d7;inbP5aLp5X2{n13Ti&#^v)5&5{%ma3 zU3{Xh@Gs9yTT4kJReUP=D-f^mZ&?ff15TI0V#Ex|#)ArgDPU0Um){qe($z~7%HH}k=@3nleA z<@NIhzBW&i`3`jt`W^)v9YhnOqx-5CJ5YJGdzSpE6~h~O^i_+K5-q6e690~Q^qsme zpIVnl)qEEXjW70)k9=b7`@_Y}r~IS!=NKl2}Ae#HnMz z=@bLNUrs-MNO;D27hK?HG=T=_6MeoCRJS&HR0O&XyQmfG5?9f@t=x2hUD5M>Q>Hq9 zgfxNaOIjdNRJDcj+By5QxL9ez0o=_95?*hdCpo2j@q^%wG*MY z+B}Mf(T`EvsQtFElkhy)il_E#|f^H(MiqtUTFspI5znN#JJWr`aj}clSBZhfN=NZ}S?c zwfGU9U-odhc~(PR;nm#SJj&&f)WG1l_Trj!2~(x-=44;wNS^OL8GI_>kqOPd!hlzof7oA*_um z#%Z~g3DooPVcFOVq8!P$p=ul>eWrn0)zomXDKNvD=gGkO4%tIrD!!V7RgHG0K zcyISV7)z-iF|+wR|5Fuz@UrA%#4GKtV(aL~qut%178Vvc2&FXvusz14DQcYHo}by3 z@kZd-_wLmGXtNL9ZmBH}TA1x>ju&RL-3V~d(oP-F-3D6FhLQcaowW3ggu^NOb&iqU zcn=Sc?#@n##Lrl*x(Xpx!O39CsVwbNvl_@d1(`ys#4S6To!bF=n2&{jxP0%7&hu$> zSCD)fs<*B51_~s)u9%@J_05u35b5(!`%I7p-{V>QJ`h{&9B54fL7zPDuvw=V01kIN z`NR9K(4mSqzmRJ;g5Re zxp9REn!^tiInveDoo`tY4!z?8RZ{$%4daNlg~K1r!mE4b;=-=VzUzyX9$Rs)&NHJ@ z?j?o8Qyr~0{t&(Z0z#Gu2%4$W47{eEJJvWpk0w774$m#zj%s%Y+Lt(2rN|5-$O~ta z$jxtFRCF%OXQ~4`fn$0K<8!`W!?QQCPd-eSjH|ADF5|4!*Q;mEakF4c`qsp2LwC~i z)_||i$(K$uJB=?dTX(Z7ngw;+F6Wtb!sRomMR)-!9#_v^waO9*L=$pzGl~n0AM*nL z9SDWSoWR38s{Fn{kGw=0DKlktGb=NbbAM{9wr{ES$DO`+_lE%2Qsedj)+LJVw_=VV zt4!-s6XxkCvRnnFZEO1xEo_{~d7@|QmLvPQ?PRAjfV72-jO^YpS<7GleLKzb_JL#M z%{A3}u1$m1q%y2zC6Xq`X)#uDN)cp!?Nz*rn)t|cQUo`y$5BLwL5a@fK>+XA*3>hY zNGfX}Ib&#nywqrBd~N_NZ@!{+sbw1>V+m^ba814T3k!@$TT;bzwY;a+N_B!^E>7Ni zCFLc1AD@pL0>T0x&Mmlm$k4xf&K>W6IYIVxERroE_;~n;%Wpso5E01^U}fE@Jlv>V z=ZoNlP4XSw`6hAbWKMD64Nxt|Shf`m#K7VM8zw*jUvqCwBHPSHF`bpld%l}A3frzJT9mSp$j z(URns6{j!=+0V^=edDtO)OSOlo~i*=a3{0(Pa>gmpfc`CLjRE$xG<)xo~jF(m?s`!|?V#f_CowCNU9C3Gm%gOcsgSd7G{~uCU6iQ;GOObJV=Fk3*R&W(FAF$H3EnapP*fx({qsI z^A1vpCDM%MxDQiQSN!X&E}5WvpvMd%E~Dj8&){^KQtmh12P;5Brg5dXNqg<)|H5Ah za)4mtq%2B`hhHN#+AxuFumNa)js)*C5f>Ma{=uBq(puEQ_8MY7r=!%p^6s6NGLyUe zOPVVxhbiruoN+dGy}Op}GaceTB)w&WxhRRgEN$8QD8;|{3Eax`S>lct0ykG&B!unf zz87>KZE%!7#c~6)DDU%cdU@Fa-g!)n*F19T`Jr4ocoqYo{mi@Q?a*g&@4|QI>CsjK z-BUhfu#BAh6+N~D)`S99Lt7c?Ib!{ykcKnQE%-q(+o~JfJogy)e%nFrsKD(}jmSWt z3IzM0dZl5967@mp#(#p_|EeArBBo4q>FRmNN3`HqH_;s`elS73zZ=F~p{bti`Sy7s za0&eMyf!}357k~a9?@&Vm9Cn;Te%qj0GGln`K35<)CXV^I}`WOC0~_`+%^7MipeYa zH!XxZ+Xr1Y7p18H_IL{O4r`AO`};!V$MzF-fp&?0wYPML8GerF%SSyGo;NLp*SW&F zb*?w$T*C<%=uz~fY1ZJC3Zenr+srCW$>pfOH0q2bTqzs+v!ol`N+|P)`(@o*Nl8!| zpv}cmoI*7QoJ79QX}k2hL><`hB5)YIKqr~%#mxlT5NomB;c>j^c?r@8jW z0-C+1MPekjRtt;sjfFZ6u(h+QH?xqNh-~-G;KP|<=O3d|1Sjz{H8gDgZVjOYl3dn8 zozbi{qxwX_edOPOTu(FGY5F1mG$@p~90-_xyhJ1#8^#-aU%PR^*p^Ejlt3%)mfaB^ zDL-P&JmxM4Uoi`N_n5e2N~k;97)3k~K9713IFE#Osd?VvXbyYg&6*E~IL)pf$=`C7 z9u`$1+8;s7hL7^Q=w3j$+t!V9a-7d{8<_@96o8fgouBm{hbaW{o)c`(X`ol>937?!?z^nSPXm0t>ME z&N3CIPm19t7{a1TpJs2d4<9^c?-(Wuj*j#>-YWOR_rIw@nPt%Z-czu&A+9?^hF#7R zfzz(tDJ_Gj$euv9kqqj?GuuFByZhqdqawa(cYCT^wovQ7ApMLIKZ@xIZ@=HJL?{YG z)WYg@n+wSAM4wEr2L=VrZB~2k>?Z8pWgaO@n(#eblHcz;wB}$oq<=3krt9?j^_Lr> zS4VoXSABOfm3zBq^t`==M@I6T{QTx@?6q%Q2p{R7_)Ir#T|n}uvj&jM>p^rmN84$I z7qrvzKmOD}tlZ{muU2K_KWBnDQ?B~D+zGkDHoH0_BZ5;iorVj$5Ueeoo)%d^U|tz? z7CcwyFwZ?hQ41qCdf)|^c=DBmoPRg??mv7R% z;*`+v3PC)1Dqa9C5AOd9)dA z_L*camZL&)sfx-}SmK*>kbrB7>4S<`9-!i|K?I$U_$|C%lxa( zLiSPMFe$?lQD?aePeJA(DjVI_Y1K&#TKT>lb4K==j9(wmX=oqAFfr=0FB(as z0Sw!e60NbEcHMnJP5?n<2+~09QDWy$S9oI=D1N&Vqu`wXFi{&mA7t$bH!I3&Oo z!w0kJ6|*Zdxg&WK$dmF2m!=TK<`_jT;8GdiHr*FcQOdl1RztxSbxJwD`BgWViUtYub z;t^lwY38C?U{i9}bt0z#?p+g@hN# zr+$k=^8>(f*`kb5zc^}v1bRl$8xa^3ID5Ds;ropOJQ>H+-fj)EQ$CQa6RxPJ>=^{n3>w#*Auyi_-4TYWJZ1$QBK^J`AjKK@ykbK}g;tm&%);(XesEaxiwP zX4=DK*S0b&ff6AR4=52BQH`&tB#k{Gd}^6T%SP7GOPAoc zwg50N-Vp}&`f0+)d2V7WKAkLJBL)cDhuzAWj+#}W_Roqe%_}<3fLaE$?-lITl{cha z(Ys?&mv|TIQY+xcLaCCMhi`5zbA|26J-F9*65Z$A<`MfKZDI>OL{^;HM$%1g{k1|U z5I}E9V_$r=fgHOWboW%Wb=$sTa|3f)K|r_oEIJ9pUh7MdKC1E4>;7e3KN0=UA4s~B zP$u$p%(v(M5+aa1q?fgii>85mcH5Jln~>lRasYG&t1Qze@0wo%%dg0L6YHfp+ED21 zj*9BVw+7W1E#ba`BV41r%1rHQw6KpgfWo+sI*_6pub1z6&XWyN-RorlN%H1X<%N-k zu~xtV5sL;jnm;Ml%0S=_40F5=yB3TC@7#sps(tbdHM{JDI%R^Edd}TexqWn)(zDwPji}CgTr@Zr0^Xk7 zadJH=@C*o;=!H||`iFMSU3a;zr6fHG$FT9>=0$hiSD`&XzC`%&@H^mOclq)|mF=Gb z)&tjA5UJHUyU*NCK&`Rs1sp2K^icvv)8JD-*ZSYS0w*54UoSLH`;QO8AqDQ0Z;!NA zGI1^6f0o1i0KP2j1o}F?ioT$xS1kEwBY1=5wfi7w>Xv&t-5(TUtxJwN2UA=zjG|YP z%cVv^)u6b$-MW_yi|J*0LSn7z2Nc%gR9CQc?0k2O>G2monT8qW_7-F(w6zU;4N~{TC|&S(xt6VpEBlLGX|~)}bF%L=9#^ zMU-a<-Z%j~xlj?%p75ZfY(S1M%CC8(Jz0xW(?*>Pcz9WeSoEvkhCgP$B6s?c`^j|% z-gx4U__kehAS`*<0?LN5tk=TitIuQ!;9*}o$y}YiAH8=FsEUH2$e!i&LdBtpDSX`Z zzbofSz6G2U-MP@oUs5ULBYK^<62IcEdNuY*{lK4vo9sA1n}wBtthckqN6`o$c^6vo z4&=QdGE;xZpazYFx}yCtYm90HRCI(!Jld}}HB ziG!{R<0BO6o?0Gh2>`?|nJjU_3tq>l+P)g8U2D+A`>pf2A_a_x&Fvd_E$Z*PbcFz^ z2#v0`B!p?R$B8-CQvpIJ7kjk!Fp!!6Q*KUlCmz zE>uwj_wD)7`j-+bTD@mc6?sopYU`-5dpn65SPs>ScNv>x{OdX<5>bWA&aCIrAJOHH zaYH&b6dVp)nH5}IIS7!y#K5z}s8Z0_A?>)Kzc`hDSoqIBKBhXNFaBXzfC>!f05zM| zY6FR$AZ1FMdMRDhIXTMUrz4mEYvIypcEjc>!up+9I{+ZZunbyRUW6b$sL?PuEw)MMR2wo?86BY}t+=}!ayw=EbwO3LlZ-z@;@?r%2Z zfP4%~7BImyShf!jvi)0$VvzM?KRiNwhv%>TgSV|yfPB0CN9byZZBeHx(E~Z&{SU&^ z?M)9C0s5KGoo}*x$?~R2K0+2}0d*RT;r#fX-0&k%E56w@jTlmfLrMU*D2>EcR1d4c z&s$pxR0deO_GaE8p~bgWQb1`NT9P&01X?Igqz-#>((x%M?&VD}*t^IW^NzDU1j5t- zKpfIRXG7e`QMr!mcQbihCqzVKW8cwNV-NVLOxWR`?6s2VdnAMFG$$W<3B z;uq57Ama*%H$c-fq*i&Buk$0h!RMz|P9~Td_5kuG9XmR=L_)2^&FEa+Exz@SZCLN| zVXxJur&b+P`y^aCB}_IK@Pvp&UpESY)&)H5+p?C!(gr5Ovih(vpm8}+wc0wgj*p&6lth7!EI=hBg)=}r0fI*4rQB9& zBG!+|KZ%ZLOo`#8*hFi9#tl-?I!}hbCBL{o_XL?RH|r4z;2j8GqzLpr&w946m@@n$ zS|DrSz_jWN9{z=k*AkR#J2l`K_;}Q7)+z3di*sJ$B8m*Ba|4dp{+ZOV%I-X#wckYH zeC8ull8$rwi*){D%WU-iVqDitA_hX}1vlm2nyK0L#m5GPu;lYfMurQWgp9CUqYujs zvM=tc(Lo4l`pyGYmGpTV*Db?=I5UFJ0(PKR*(cEIQ$f*UgE5EmN5INQTQl^O(Wg&d z09Hf@DSiKd48)(#(f7pW(9>Abr zovSE+{h)CzLHOrhC~RqI>$1JL?-f(P7+yo=bq*Bq$L#{~LB&#ZVe%!C!8k(zBhX7j zUfE=F^uj_In26N}=e0@1>TsHX?K4>3Y_y9+jtNI_<$TdbmTPqqsGDHBOXjC1@WBjR zA=FJ1z~W=R%?y)`uHHavYE&J;BE8?2!6lU+pWs;{_;qr~cl2`iK;w?nC;He*#$UM2 zEdbtJmeA&w_b8vI0?8z3hQ2=Y?6K+_Iv`ATXlYSVDn>uy|}7Jp#On5 zH}#FjUNEM_`BqJ*4|fu0gHUQaQ8sb0sF+P8UjG6(whfLCY3WIiThZ=ogB&`UbIY#e zBTz7-lGTL=M~ABmZ#0tTSfg1~;ZW-v&9{6OhtB6qGZK)Y16FrfCD{Zvq7by=P9faT)88neh=E6)Z*Ne3&e18Krx)v zndHZ>b(<(9wDXu?k8UJpYc`qB8!`)t232kEIc_~t!63=oL|46C)Wa zObD!>&Iqjw&0f+vcJWH=~^ULsLbRjd(R; z=yP$o6DRMsZ2_4!bm}}Gr^+v_9D_KALfwjfwz#Fxc9$~HwV(SCe{sI1M>PhX8Q1-=snu{n zYJZjfC)CkjpQ6r#wd0B55k;}2Fbg2q?O~|l{eo5H++@r!!~tkkc35u z$j#MA#vCP)9}t)iRL;E6jInz}BSE-XB<$f9r@Sjsh26occck*DaO* zll!}`O{&n`W{*nte=lKal))brbj>zO->O9S0`eiWLb&FeGEn>C6Ah) zivM8A2l$@_a*rEgO$gw!H`PL26kOhh2$wUZ3yfi&UrMc@osv0$WF)$p-UV*L%P|IL zp?5Ivq5j?&v&b@LP9eL>kXvK-QGUti#zS#T7F)-$&ig+^uRpEKm>W!|^nHWVFDC*I zzxj@_BWUf8^B!Hm`Tt!{&rNYe+dIY$m{Spa4hQ~J7Kgx0-ld{8Y0WylScwzwt zNrg<7^6FY|diVH0U_2|ddzq@|&=7Ezix>5Jpx_E4CXjDmYb%~l!hoyC`oxvWe)twG ztPn`hoz4R8$SPaxEYZRWO)U9uoDm34iO0d|AKNBEBbN)hn%ET?j0VR{D}Oxt$!ERd zFooflumChfsv}B^jIGnA?wkZE0qVYMWihz=&{`z*m4OjpQM6u%um zDm^#i0fVntt0?6DM=UTn^HbZ+U!lOk`LXaIaYzp9rbr?{Vt~!bD|K#y6w%DY}3|bv3;%WYb3FIg^v&2H1Z7v(BGvPX8m${(p;4edLVBxUQZ2 z)fq|NCutol^($5wZ)d8_ZL~|ZO}x-LK%aFwomElKpFWO6oAWsX7eDhwcXHv5>|Hoo;kFf!SBR*3b$R7EE<%#J7R3JWpLBV`uW6a?Tx|q$P z`Viz`K%#JrKGVxDB_uhAlX4a_Wq=y2$0Sc2*)>iG(Lz++zK$ZhoCwV;6rl}s!?-8H zr!)av8SsXYgzml7DjPsVCQ#mu=iK@X&!28iB}z_m+{Lma&|C?7*Bp#%`j1qp&ry4AMR?HXPav8Axh5e@W|mB zZ?`p15{4#+adyj(oE$#y^UDB_#{PekFeL)i*slR;_55h+6=EFzYDIUv>Fhhq7 z+{HMPec_?m&F6x~U9-JMVTj!(-dpt&QjCG1Rl?WwDxY&3#0SY~lXUsGWj&|OdLb!2 ziWsz0OdE<)6JcHp3ok!Qub0-%6qp>g`BfAT;>)+(rko+Dlr!YB-?FnaGBU%McX_#~ zJp}_r-9{m--F}2EZm|FRsPQ28&H!B13Cno)e^UW-lIO@Tct-&1LhohN;Wo^vVd`%- zXXXiV)nQ?Dlxe8-6}UJb5?=c-1lAR17_sfRBS)7~Eeal|dmUb`SG`eIcjxNO`eIIv zU9-LZaYn}6J&N)AGMb3!B+QG*TZ2y)*(DRtKuF>6$}VfbYL4(m>;(ikFF))cCldgK ze&c8GK^0kV-<}Vw`Jj6Dr=9$NU)15@<6BWYo}&Bp6AqL}4hb-3<{{xPLvfYUUuLh$ ziCky+Ch@i08+X@O0s^|qzO5QUd@n6OWQ$SWog8}3y+#Ft+D0)a#1D{l9W)N`yJnT1 zA=;y>ZRjb(#HxwVJF(5ojq+46FA3EbCp1_(vbSIGy6$?0MU@j7hC+!YVQv;|u6&kB zy@2Uia4<4b$Ut!Ddp@c=RJ4jHcOgDD^Z#%7M=QR`0W_u(d`s+qws>`gZpR`hw_n}3+aP$I%ota?VtWoF>_B1Ppw}j88?7NieS^@jB@mxTLw&S&&RQRs zK5^fHr+I4hS=*VNxUsRR6il2d&XbkZw!i7!zb*gK_z$3xk9#?u{$e~t&JS3WlEK*1 zC0q-hYxnQ;YtW^{c^%RYFYw@3Twzhf-t*FnP%w63CGARMv5i*V9Up(Rv9)VA9P_+P zlo7l%J?oxdJGeiWJ53O7nn{)6?Jkeg%2Z$S^?s;+y@x+(Q$Kco`$jMLPvhv_3Jcyo zvyO;}8N=K}A>5sc)*3<`8dnYuz@CsMCtt@b?dG0gDh>a`)%>SDct!Bo{m5DBptKdi;UJXCR=(4bfJ zHkmZ>L&RM^;?ygPO;2buE-090=)t zlo*c0X;fAXx{1|Rc#Lig_H!+No3YZ*=!qV~fR|0rF@3)Ki&yz|M_B0b@G$ykdG7rB znN?~zY8d_WrTC#1`!+<5^LLaD7w$zVwxB|Qc!HZnF(xm)hv<_p--2>_^@?7(R9Yje zctU$FO^%qL+M<|wCcQ6;tV*u_arWEY{b^tD^!|b_?Bd@hKq`>GFz6O zMBkuFh+QlnS95S7s0p+OZc_ZEY*@qDR|OW4n?*lzsB&?nNjc3vEH{-|IFRV$Qws-A z43|9^JxuJ#+)}=Jqrb0|A!~@d8|-H0hY!j&_8?>UH^V_P(NZSjzWJ#O{xUrcSz|Mv z7`YhsE?%)Kh!N_gdy4HcuRCZem3yfAsVLJnbXmThLi!GOK+r~QvU|y+s#QR@V8y54stqnde3q}2Tb;{3}bi$sK_8qVP~eUAJjCCk@rNU63q zEAY@yG0v&r7Py>sYmsN!yQr}-8#SCl5@rnz9h=jj{AFmrcp*twu=17TcG|zr(18VM zxrSAT)k=KDF;>Ey`N32^7N0C6WOOS1HirKcMln5Y2l2hK?B#MCwANHw$Tr3@pVOo$ z^&JXnE*iRM3nQ_Pl~ftk=d~F+)~*{>Fl}|IMl0^F_Ike}Y(I22pD@ zrR=KrzV36uXRzQ{PP;fR)@4sT6KDc4#P-aOEmOg$633xH9X?07hc;KfudX8!5yIcw z#%=GQuOc^zQcl>CbS^%%RmxZv#S8e*bY2lfBR65 z5{oNx*Rl3ohEfuyJhH_**bwR;VQnjrfKHZnr7o(>q z)_u=WK}_J*S$bJnh7Z8m+j@wN`s&kcebtcpx4~2P2OQBy`Bh36oUkhJL(5!x2YaQEKk9?x0)kCrF!7Gmg`-tVca1nkcKq> zdglWl+mc{CE*P@xx8}uN!zq^uKC@P#AY=4#&K|$8PTN8*PR62VX zNxQ^jmRfxXhs?d$NjsIRJipQo$|iaOhci@E>U0nPz|mevakp*%kcWEUcW^)^Xlc80^wyUm~UNGn{>B)kBUvuzJ${}}5>5c}QIBVl1(<6cB!p&XnYY*O`ia&%POlxae79H2PrPJ+}4P4KQ}4jA}Rb zU|N(^;y5I`0CT$Ar+S}j-%yh|ecZX_DP|xN#r3QPSWbT3tF|@}OM$0c@w(AguyHG= zPRI8!Uez{QOGNydLx1X!%D);6%NxJPCv3@|hyMbV0qCUf$Fx2ve&s~f;md(UGcO%eRx*T58PNxC<;Tnf(WQQwNK z17^;u0UYe?wxg){;1e;gEuGg5sb$^#sU>`SYeV(2S*ik`lq@&um>c4J8<+ZPT|7;u&~`TIz~fqX) zXbrt=@E1UgotKtQUC>njw~?PfDucuj0Uh-D^%IGYAu3B20NeOpF?Qq&yNTdB4pRFE zys!ca1s7jVz`CEjljsL&yN2`n)JDiSSVpQ>eLY?&%~rpQ%IqM2;Ui~1zbuk@ywL(2 zgiM3y&n{>$Ri~;w7xcy{W{I7V^~fWprDjn*kF3nj4&+47Vu<^Pbqslxe245FdbpKQ zWhnJE;HHCRWh)KB_x~N;ive(tb&^dp{?&rMiX+kVAQhxZGjPY$c#~H?8j+*}@v|Qu zV9>UYUjeWg*1)$?TXD2+n#!nMR(~K~c^4E$f)ArHWZgc_S*8J~A%2q9MsWYgvF#uR zdCg+-2D=(p99u#$Atodn+~e-7co17Eonef%Kg=i|y8F;9nP*qi_8Zjq&<-Sws3G#+ z__Jp-&Oh_{_wnal1x?1y8pCqG9`G!-VD6AJnv_`p4aO+?#*>}Jepodgv64OuytTuQwmM_EuBCk zARu_proDq`EFe%xRDVC_>waN>6kv3zVk#e{J%J!Nq-9f?skL~b*?F4J~ug@kXs1D1#yjDnKuV|OeqJQawf!JL! zwPbc#BP3b)w>Ce%J=0#nJ0iJV=t6Tb$Hzj)6AzEO{}rVgb+98DL%MVNB83e9MUu9K zs9qF~nBjz<@f1vFYm{V98MZXByJ6Fw2obC=CAFA=3lnz~#gBD5^#+GeW3^vUeqnuCzoL$bS{|wh<+z&$l*v$JwOJy^YJq<Q- z5EF7Zodt^-_#z=`enzcuyp!G|mvN@E&+ad*r>}vq`;Uia1H0PIB(#w-Sqxv?j?o020n=SyZ?QCU!23#)J^Lj1C`G6Uil9Ktl7F%%!fwrJe~}xl3}o^x6I7vUR=-0;+!XW?%X4UbOu3zZesW{xxL@#ar<)$(@)p6p=y8CP9dme zh^FRs6rU8^g4Z9md3Q@H&=`zvbyG3MsX>Fn%S^>j6D zTa8`R%$ZtH$p7)|H=`=Sd-jH;BwzY{cbX{NQi2^f=|vRX_^Vp1mDS-W6+kx6N|}*M zEfGka16!{M$w@E%P2?>7zDW~{_IFVfz)l0{9r-1O4T)iBtoU8qG>5Y``l~O<#yiVfz zO}q-Ls~>Zftpi^FeXOf`82>qkTNSu<5B&3eLdbHtwzaspBz}B#e$Rj5sZ6+li!z2j zvx$UGFFJi@$QfqMz48O}g_geE?Gpj0(<^_jvDlLb5H5qzPB_YA(PBPH-Q#)vw%8AP zQ=<}nfY)l0>|TE=DhdG0ZBfHbJ$Q)VJg!*lw3+YiV-Up;b@q?g;vbxbtYW!q+A+=$M^6;BtDilm#~nU z&y08>Z&Yere^31Pmx?Jy0ICBH z=IhLBFajOZ=8$h&7f@&0ehg-+KvYli1DOm#0tjh3Fa1subC+pZ5wqD5bRpA%nqrvC(hI6-)_*mHQkb^B^j$ML%7bCHI7N$);R+j2rZ+O8fG z{`ua>ap_bhDq+w#EbwSqFi}iOhXEeG1~@!58ydYRzhW3!k^M0Lv9bA5_R4JYfQ zI{K{q{MNkc((DWlN3CnY_P@5lMFXcV&6xFjFAiXVQ~x4Wtr7HQ*6q0W;7)7oYLM|* zLuzPGGk{G-!Zo*CWGealc_G-#l!`3g`O^2K(ZY5*rJJuj)0engxTmjtfA>T)3MBGF z>PZ2zw=|5PCl@}v)|30lvfz91qPrH!Ep={g%w~~oN;7aO^mZYFD9%Nn8@TKiG$8gr ztlnY(&VTvfl`ZSeUsC~B%b71iDp=&!D>iOlP!+rDHq>X?ohFI8N=4cJDa~3Cb)4!u zL}r!VNOdXBJcDMZ8I;g$toGXrL>C|LGJlFgw=iC4-%xYpl_t#vF2u{Q&Av=8IMVx9 z(j49+OX-mQLHJN=q1=*R84p0@*M-O4Boi8NI6#1)y;71BPQPwt|G1j}kt1)yc~gvq z0J!|(l-^ltCH^N=MpU*=X1 zMesE`kJA=Mm?0VN4`Pd$JI*o!xewC8J(PTi6n_r`CR^ z27zf8qH43XUD00v>1i_V@PuIHQTDf55*CzIJj^j4OFT9|T>6X;628POq@ncv;k3zS z4dv5VMi1s@BNV=S$cW8dV6_b(&7FwN&*)X?et)V9B{mcapY-*SDl)Tgd#A5)&Pa(o z{^4U*Rw6_C$_1A~B3~H{O<3no))ELTBW)a(Cp+o)EO`^o5&^RxD=#|=aZ}iaETyuC zM@q*ASZ`bDYk10WuZ*}KoaI4-SM)E>3!a>F*5^+M=@F@WV6YJ3ivn;*+}n$8z)zLOUe zAg3QKjMY%uNwe4O)I7syeq2+J-6KutxSz@E(3bgNIH915G^;h2&wAe<`O?J=sFlX{ z@6ZhuMasn`nQ(9Po6y_GuHli!w6^U4+n$EYP8t6rcf$n(4?yoj9RBow7LOQRA(eC` zU?ryC<9q%(pOOy{xoWSR&V-S!QXD&^4J1wcLEICHPqA2y6!^OopQ^`Sw^A5oS35|l zN=3*tt23ucB+-6;LJ*%(1CS?WrtnG>i(N{BQz0Zl_iTjgYOm=+w-J1t-r!7KU5q9P zpOj?qmN;g&??4}EVGS*O8#Xupu<$(gf93oywo|rnylL)RcQu&s9hsFc0V@$dwXcJY`p!-WV5j)AhFx#hD3kFAH@@%tpM-JV*tMOO4`9((uOQLr9-qBLa65<1 za&(=uIlhE`!ay6>)ZC`BaSzf}(E--6@A%z#>fb=p zz}w7%H07*PAnZ!HW~p&0;c7jZlUEK=*syT>dfgo!0^F*gn+G0oq6jJAD8*sT(`ZQ^ zM*(}hYHB6RykvpXX7|zXRT&&HZ?}L&k_uutBNV=d#v!&4I2be4HupM=&AwsLYGZHS zNj~W->t28K#_6>_=!x5wT z@p82q5pzrXWpABvO52ku!%;6lcBGUQhjWYYc&W6xq%?fU_;{Q%?e2;3kdTA~xQ$U2 zsMx=L7_^|yFuwL{*}p9nP06SMtqPCJPr27!OdJM9Qw?q0W~!K(Ipk}j4JY)+LYLpf2A4=jsHLdkjA&3y%nJv6t<_W2o)I~R z0;y~jo`ipG62Ve+#RO}wMP2l&@?d>LgtE4c`@v2#bF;9ihY!zv+&?|{QkgkDtMhR@ z@vV_yN~fUwx+VX5#$^arE8`{gyVu!_lG&g8jSC1oC42G=2jh8p>fz;D|3#W^;=99EwUxSEc@Tc@*=WC< zQ}*+75PfR2?r?u@D76sqhNN(Fs6c=1iTn?OFNK&mH}eQ&Zz0RemE{Ffa*OsgAM6w! zt3yM53|x=y5A^5i5p>a0QB|q=+!3Q5{bvpw1JoV%8Y%4T@489-s&RIx<{`tMXtSq@ zuyM%p*hr{H!U4@?y$XEJa^)j12wjGS?k`^^6Nw~EQgcRz?s+TYYG{pyTKvqIp>`}H zT|W2c)pI%ShLr8a=Tf9S{NEj<781UCA?brj-X0rX0B=WGck{btrSr6G2Y^kTulG9U z4XRoiX{Q5H{wUld{|Wd_hU8LHWA&)KlMSa&-*dYOY5l8UWyW$`9QF(xqhoM7BBTfeG3MA>rJ1vP zdOH~4W1XQtOl&-f@71djo%M z=a)gXpJ&sLWmr;eb@DnwbdGqXp2zD)F-y;!uET87}) z;r63+4^#3rNq$cRucUbL{zzx*=7 z*jGR_soJw;1+o=?XaWaGn)8U5Ap(`ewS(P9GZ%9rNf(ErcPV@F%9wqPUYIQlHtjqQ zWS@||C5JI(ot&lp{FvZAV+t`ha3YJl}eX=ae3|uY7C}A;i zcX@m-ywj4o#X7|`sBmc+eug(Pk#`JDJsiwEZG*~SgRU+B1ujHR&T67hnvz~L)pbPHn;yy0zpHAyXrA;Aoz943m-rXHa-+^ z+5LH8Y_mdzSH1P^y)BxIXVk>2h;Tps3K+zaJVs??b61?}ICW@x(=OYd< z#0Oep`=yUd^Z>yV8oxJf+j9b!mcG0t9QyP6H4nl1wb)ZGt-l5{x}R(+ChzIaTgCZl zg}nWfOop!XpMi*q9mymq#9>iCDs!cx=jt4=y~(sYG{TjgoNi2+23~i)*wl0Gea94t!cSr$#7CK_o5p0xR2774HM$I-g0mk0yEYtgLB8?;1WWvha{5H+bnp-$r z-Pak?2zPhpI^x66_v4~6_~U!*kM^{zva;|^*oO_ET&+rHH>ksnJw)4k_y%}{C3W87ZR-tmh7n^ZZ1a=#hZvv`YB{$00WUfA3c20_AIQPu0Ym1l^4oo6 zUSw#wHpo1N)28(Kz<1)^ptrYz=6QMgV}o|H@_9EI&DbPRWsYV5R#yp~!%*?KP;|gWf%u?%;=Og1uD+h$$zob07zXli%?@2c||+S1Jl0ZYkD{NOcr`a+7t#Rr~SeemOSutSP9rG^mrM z_9N@=FbP*#OG`0JyZjQ@^xGIZG)Lcp*yNA-h=th<;e=J=XWC!3!~u$6{@q6dND(n`E}|BEg|4%ClezuInLADP>M zR}c5zvrU9-PT0pZ_{PH$)ivZ<*%l}AZ4a;zH%I?%4@vX;!K)=8t|Yt5f5}Pw@*f6MWgE6%Aub*DBg{{HxDa|V z-|4G$BDj|ls`sQoi-R$neOG(}nKkK;sYmOHi5F;+zBnHR)(SpcTuf3={*gHAsdjdB z`a!@J@eJJ#2hhypy&$TYSoFo!H;g!OvAnr(j(9A7Zs?J;Ug1`p){gIta!{G6RcC)0 zK51fg6RC+MIO;QA$GgL^y66mcH8vvIsUxXcUr*8q*6nrq!hRupjkLZ;ddt2|G_m|& zAB~6p$^0gvE_Q3~f3yDG<4h=u#2_&mGO77$e#KOBzE-`0!D-C9W=8yqIq@1=1*j;- zjpsWVaY24EJ<;mWy?(HGL^dC3!819{8IW^46ZB+lB|>I0F#cG-ZRW(Q`$B!euYPd> zhz*gMe+Bj<*{KtbmyNAFp6DqPWl&zR_f=FBdrs1AwlJEV$C5k64g$R5bj~hw#DTtJO%;UM1iV{dG@SSj9L<0|FhPodTBy1>k`V$ zuB)jxG4`lg=m?O2$mi?%cW+yOiPcYD6Y1kZAI zVT>@O*B|?4)JGQJZ2#CZerMfpQ*#MRD&)RKmM}A$rL!2fX?=3AY04NSBT%-BlvCoF zQO9?@^L;{LQ~kI(MqkXiKMn&7)@q=pNDjSgKry8-qH38u=rx9nOl)u3};AHhI-95IrVDu+C0nQmL z>A|?P>xMFPK^vFi4&_aV93z|cgbwT>z?2tr8!rC6(C>&JLtqY zKUDkP)$=|t9i`e^lFU=*Ew7n4eD;hJ#n@Sgo7T`9=21)QyWKRz{O(huS$Ovv?Azy2 z+$3cbgPhu`iiMA@Kz8SNs3z&vGh*QQ_#l+~LGW(OV+_1(97O^<1=r)}X<5<5`ay~#M z0OM4863*^k|J%3~RJa46(Y)@&>h5!H5^iDux?Eiq$tZb<5rv#P?o5BS`mJO<-;)_E99pRi*pPM;)pw(;@yMwk&dW} z5OAOqpfXY?xLFsJ-Rt}+{Uu?`7Q<9Gm%^EfD@glUn}+070IeF^QRxQvwl235^z~N&TT}1!dCm`THzUdV7hl{32@R`Pnp;0O(Rd# zcTrygInoxqRL)A!EpP9vb$SZ&ZZOLfXsccayKU>85=P^{#HQkayXS%7ckGedf|b*_ z&Ypkz9EyN4c80=~vy*e)<7YuI;+S@Y*B!AFsSa}jcZ5P*4+_vZfQ33sSmo-QYlTXh zI!%Li2*wj$Wifx*Hi)PWdg7(2P`O12O7e;+ED~ zyuBVtPnVbT0fcKaiwXAd`x0RfcqH100-_nb-2m(MuURF!)=%NNKERMJEV!RZlB0bL zec@@8Tuv4VIvm9nCJSX=Nr-3!@GZH_NB#W*BPr_Zmk00sB6u9Z@rJSWZEQqJF)|Ox z){9cH!!g5u|5VuB{!o&eM5&_+?#6OkwkhgIK`umG(74DXhn@14tz=J)4%vS`=~63m_9A zs&6?EON?h8`X22^`WwC^@<&$g6Dh9P%dcDxQ;BmNKq#U(Bcu6o8BmGTPNV1esoM+j zVls{{D)8+O>sQ}$1)i#m`vs~EBniedgAE#B;7Y~8y4_P5$DJjCGXGlf8=Ldli5FU? z?-5+WPl0OxooYhyeDRCIuXH~g_WhU*DI97rVkXmYQ^Fb3B=NM+jY%@Ffz>8=*w~DN^G2Tb}5YGo+gu1)FzwZwFX zv+HMnl22qpP(O~vh(+D5_kczWgr{Hm0r7xHbrCc8cUFMZQAOep9`@o*KXye!Kk{hW z+`ZP;#^Y9z>n#RJi>e_vTk+zV+UWZw;{FAJP(Rq8#pi({4M0WG!saMfHbhPa%cq6q z=a%ASqTOUc9I|3rx=+g=G6A-3RRt;pK6B*5u{j}e)AIiJ0Up12QPzYtMekF&C7O@p zWX9Cz7{ZrNmrTsf?6=y&+BL*fzHhOTd@0k`T?{_b$?mZF&Ydo~RK|ZQR5XtP0`xRG z$aBNJ9ANq-s1tCz&fDLZ+!o_ePOh|s0S=vOvrdZuEP6*XU_-z!>-4T^k9Z=^*W>&! zg{La=mU1)alS2khjr&@nP;xaifbzb%Pc$Fy?zh_?n7++24ir-$kbOop>TouAOOM<; zkbnGgGB3mvA3nzy>#3~zT-o-lc^6GF8eygM-Mve#hm3&OuuOCrKcEC^K3?lv8R$cN z(?hG1I>aUvP0#NC@Rs~BvT*W?5=H@-W-60P7N?8*c668tU!|P<#ahyOnRQvNm`eCQ zA-bd;1ehZWrJA#@WszVna1(hFU8D39`O2HaO>H# z5-74+Z14{pu~`F&^J6}&e^5zjy207!$L6kX*c1g*55m?4wZa)1Dx(i>hQA5xK8pgJ zZYFhPmj0#T;8`Eg>42tpSs0Rgi&v)qAuW-QzZ|tAuLZPqOvRqXkM-E1&Sws{4F_oZWA`8G1P&QAgwv9BX!a8!lQ6whiE1UR*;P$glF%g_HIS~*GO|_72QuXmkqs{AzV>pXdXu_ z!qET+lx+x210Camrd=z&s2rMI5Ob67AVGbj%~b9KlVKZ4R9XK!%mH-QIJildENOoG zSN{-}$eKD3AwDmx^mHCO2(axJMD3DMPUlYbJ@fX)B5O>;hl`0d5}lQnS;xkgUucq` z>8LcGyXQ{}_Y(%1`MhHP#^~BY@r$x#+T+b>%<&Ip$@OjElVW-g#ANiZd=Ww=v6Ot3 z7|K|jP-(XwxBZB{np!QY>NR=cs#oV8aJPqRwUBUx)KWq^TDJw8>)!rMZ%QTfZ$Dqt z`(x=AoLohLeh4_v&YsoW{I&;`=_Q|gU%YT~vIFI5U+E=V{2{H+NS|!o>0{18Lcik* zBh`k4o_2u;7m-3{pIFYGathsw2SF8qZ~aT{wCWWC}pr zk>{tzD9b@_ew*rdL85HGV`jAX(-1^MWD9Y|IiIHQ~`-Z!BF8`9s(nMuo^J zNLTEcaj65c8J8*M|dfI*3-?vhp4Kj}e`kk7)?h zCM#6&O(!HW@N;xOio6jbk7!b9K=(^k1*%jO>iRoXN9d^nr&~)V|e<{$kVFgY3Jp#T` zsu}!&AWB0Yf)<1%@0#ZY&RcxG8Hqib`{GjLrxsDJ-$(cPDPexb=SYYDsI^YUxdvHsn16Ty?bm_ZHrvcG8P^aA6s+^M)tk7ekj37Kk`C!uFe z(*%nL@Y7vSe_l1cvb4fPH|*WA?-dUZjnuj8MuPJ`hu4XpkjNC*4Mm{W3c8d0c78ke z7Vg}tHG4G~t}SiyRmhw+QD~xDtFxmq!&-@geN&S?><`dYaoI&{0=V)gg1uX;bqF zUqeGnsw&<+F#wfSFf}=hZUy{;em5Kn?-Z|oGyxW9@8gy+DmE%=tw$T7%=^|N&kM!QFjLcG3 ztDw5onUj_>>^E~&jN62&u62L}ZNxHrldfyd4d}KjBK>UABZ>A(%L%elI)GOB9!wY! z3$S%RiI>ZIu&_KsozV=v0ifC{mbi_0dR<6-q1zMo2j}@`6+4oKQd9lnEH$=M+gCJa zEp0^dD7VEF zF*Wx}SoNdgiGFo*<)&Kt^L_&THfS67s{SDHGNbS&a*DqjX*(M8BHCm}QeBtc5vqxq zLkG8Q1J!j_*UrvlbDFu?S&z#g<=OBMS`I;h$gnYl!EllKVvv^Jld82}?s*Ho^TQ&U z^LY_La@wuO0wCWELEzYkfS>`h4;3e#Jy@QY1#vPRzpB@>3ooxlhdHb8bx&(jyO1jfq+JD(JeY6--4+`b3asaI#OQ9|LD1ws@mj?U&I9cy z2lz|*KyO-q0WAecf#~HzwQ*Atw+UZ{VZ|U-u$_I8+0pN{%@*38`$_f z)PBnAD4MJH`td|5d$nyk7;A=NXQE9e@f9~wev2Wr5h3kq^sdp+@XQHZ(eYmGaEo-4 zjMD1uE{-jSSqHc+REZ6R!hSO0Bil^U<{hLs>Ve@IodZqleg~Cp$YdQfUP{gMAEGtk@8-$>P z_c`*|7Xn9~F+BLJ0ZTf}(ty#4ps-UoY_n-sDdT2c@Q_ zr$)y@|4U^agJtK`xpyy>H9E4DH-;`}L}T>T#FY%@{&xP3l(?o)Xyd^?hF146j}fx0 zS+S2*Af`YG*kTB|+Z)f`PypTRPT5AfO`g*znrS>$ebrk^Q|g{t3Ok$UN8`%7n{Y3- zdvgxdlNpEo;n#iyzJ5tRjc-qu7c2JyaHoI0Dxq#Yz?YAs0$ObOO` zWJG!23>gAN2K9&S-wFCO`*m78Rxf8rhKg~>YHwCy;3vcd4R)fd7W;thle=;eOX{?r z%dTcx*sq3&j#M+TCLj_N{SY|)UGRzc#+6Q-fr+^0CjA>HS7_=2N`)u`A8;}m#0x`D zWk(x_PbI-dAgB5*mjKlkGK}bv&N9il!B0dTrm#=6 zw8Wgo$A&FA1X6S0vNlwPNk|OqyKA!%dyDJ)M`|}2Od6Ye@x?HsS0 zOwot^B?OOf2vQp49uB}?bbhr?H)-14eKP;yYS_;Aa=*qEj<Admo$?;x>^hyaaX5MYzX__Zv!>Beaz82|Y zt?o%%-^YR+BMz0(4Ea94YWY%T+$lwcbp)mfsJ$-Aom-)MX=pKd4#dh3XQ(>tKUVnO zeIO+U9Y%zAJ7#bLAcMA1k`3SJ6oc{xmiE)*}@!D{?!C`r!0b zL6y@8@!->1X!{c<$rO+t}1L8@C3;Sbh{{V<LqzDIYudZe`N4-w!hYhG5bgFrEwWf8n&C=&JxBe9*$oS^i!-vDtnF1juJhR%^b# zf`}c_R7m`SJP3KjUG@=@4L`aA9mU>=A(*+B&>N=dj{9WQYbDpThmQ=X0K~~%iN~9J zKQ=X)@l{WYa&YeMVMqt+XshoJwX+K^w7J&5;W#yjW7uo>!|Q+H5AB|@aA;{El5t^{ zZVM|rDP^f&g1a~>*oLmeMHvKkNa3Y3Zvs`UsnM&e*HMBGpBG4xH4ObShH*ppPsT}- z$85AsqHVjM*8G@Uj7snkG_zGrMf?z3LFb~#XEKA0$UTj%j0vzQj%^=b?CdO>(5*cs zm);3FU(kiUo_1v7|F+?craplX_A$)l#X8Rf;X0cB7iKly5w@*&q{bMgRq&`+_~b74 zo$|-{!Uh%%jc#F*(5qhO#8th9i=B&QWjFwMa7(fv<=u6j&yYeA3$cKXuC7P`x4kn{foXdph@M(ac!>=qK#eLAmx?CK>eD}*{}yDXVk`iEYS zQQ zZS-GWe?eA-*83k$ZV&(%W*SEI%W9)2X|2MM2^&D&Q<_NyxeFov{E@CFn&n56iZu47 zY*Sai1qa4gMId(R*&;I$0G_Q44IN?`*uq3TH@k8!b*^L3f<`AtVZF;odcU-Bv!#Ei zhFkXGLZR)3eXLskElxg)!!hdCJU6Hn>Mm24_`@iem%5lpF@5zAy3_{*IkLjnDd%0K z#%&nl2GqTFC35$W(ZoXN6Np9ThkX@Vu7~{M0z4D2H@_->q=PIR3GIGyfua=N27_d+y2G}4lNbAXj2j692r^v1PH&$ipGYh(KJ@+|1Wl~m7cyaieh zU4X4%>{;MI^%#5K)q!8Q)%TUj$-UQ1w|`fMDQHU9AjjDuZQch(*l6Kb4Vnrajdu$$ z5vuue{`ilmv0HyLod)fC@vz(4U?1<-4@>*1NrC}Z=BtvdN8na-oAv=k~9 zRMDBJsAa=CuOAAK2O*PYsNQmnPF-FnL z@#d4@NWDI&l6!IK;P>@NHM5Ae-A@>)yoSrz^2~;+mF2`3L3ApH!ne~oa5V2}cZMug zpNqn(+IMuke!;2w%>A(y&RQiwZ5xfc2CdnYJ&0kzx1(3L-6wwh2t)H2(^sy#;w32N zJPrW$d5tgGbWZM3Zhg4!;=0!f10pC}=BD5CZ@>#NaV98@$qOfl^~E85-L2hF0zhk` zs>-rET@s}Wxqnuh^>_q^4K0R{Pmq~Pua&;%_S{sXD*VvP3ylo*IJXPAm|7s%i&DU# z4d}m_yw+u~EFXu!1vrtGiH&q@So=@nJY}K&AZQ$c-JNaQ+dMk^sY}mGJp1KX&MqJ* zkt`spnC)iAnrvAeu{kBXnYbQ2`JZSrCGEnN|KeA-*5Oy_FbUAOR=fKs$X=LZNM!rJ zd>}?SVzq7QV;U4Si`vJ}8-+ofrj!m=g5J5qaPRfQ+K;{ZVJ6hU4)uB$YtME{#A7pR zTb#GG6$irT{Yo>luz{|wU_-}n-OhpThZNSf_!5r~$^adCw$RLv<|XI|t#k64j$lRC zIPZMf1K4plcflQu zDZs=Kj%Ni^k$12F&ZVWKOgj)_GcGBGutxGdbb%lZ9lC}#?~Um-+*Z+8ebz`ext zD|^9&AG4H!jIm+7hoDex(x?0X%!h(lz60St18E-AjflKq}5WQgC)E&VQ^#^hGx56ZCA{8MB*jS{=spBfM)=d4;^%$^xT4PLCO?3(KCbmdV2@pv4k>_pVRY`=)iz7JzDaw+~is%x>r@ za%mdXF&3EFnGJ zm@M9{$e0S4^-!xBD>wh@N~7d@e0h!sMvrm|PHl_{T$&i%ERyp-Ry8(1Y=MIrOUK#n zW}nw4>mJh&!@K?1-Yo^{mv_DuWaEhl6|>X2b0BcZ{IR+eyA${>Ds2EqrI0a(pfB}( zmvi`y<4$qjj${k$l1lZ+8rD&EAeSMr60obCovUR1XK%|DLT>8x1_Oe#Z z9H$ItLuc#`VTT`w?f$B!aW+hm9qoqpz0C=PsSGDkP$;)aNI}KUk5?K}Uh7nBM)k3j zl$R07T`rik(I=d_pGlR5W(qhBCK(ZlQrHb^`wJ15qBo=wFdvxF!0Rp8woEZlmAw^nl@vGF?c~~^a(!g3g%a3%f z?-)h^?;>lW)%M9c=K`<(&@YBmaNkT`0U$dKU&+=1f~cjPV3-GSzWnQ{uFC)Dfa=m z^~liOqJycsosUb-$M!9DuHQoeUu(Fst>mpB@LNrw8#MeuY`-Qu zt~8JioHq1Rx*jYFS8(ouBpIdxo5X}g?#X#`eEdEpe7kh`2o!|S895|JZm$FI%5O2g z_AG<>rkjtY6`48QK=9akh^7WM8eQLa--Lt)MN?skuf-1J}AYNvnZJ`v|gc9_8*m#1V238`J;{?$=2v?ovVo&J1)QkhFx z`#rbCi9CyP%V(ZB!5>$j2?Yh4)r56#<>q!fm9wiN4s}Q@ScOu?MLGTet%}<{yG6MH zRkwmDyZi&jm)r;5H!yG=z4B%;x}hQewG=0XHy1%9i-z_p6_qBT6qA&8P*otF7_Ic& zIQ>ire9;fu_Pk*ee+BQ8gdG=gDms#An5pQJL;jne z|HN!T?QHq-<-b4r&u=$TScq*-TC}+{_u&Ngy0WNInu9cnUx(ywy8y4(m%2os*b+73#YkmvEKyt&5I+>LPV$y3Zl>y>vxt1aLP5bd=#G2wk&uqUpUmb#1JOSEQ|PKH`=aGUqQ+Y^6S<~7&?)^X*noje(5 zmt%By?xi}`z4)}PsB-ULJA#6{+|1uf!Gk#Kf6mB^jxi2{L5p!@Qnxds{Fo^c8{$OU zxZ@A1N+q(ll$~xVdw!E2vw5Dv%`!zkfXIDg(WrA%D7B<<0MYkz3flJGoe#1H=M&dH z)e2*A@7bVc8eCz3t}g3mLl2ku%O|hVXX5qJBL<4Yhqp*PKks%N9^<;p@OMD(j++hT zX+F8p*pUBgTo7%lbi7_-gb4Pd6N&oxA-!E~$#a|j*24E{%-u#YItmd)1ao#$X>xI) zcm;3~6ofHuyd?Hnp8qknLPhn{+VIUpM{y?}ofzNBmb{5VngRYVVK*{8!*91gx0~w! zoOQ$IfT}=jRKnHB&^s^U$)BlAE1{{Ibkkv37aUM>=03X zC2$?ZNEu0Z!_(Pmy`uwzjW}+hwyh%mM&#I7;U0gT6w=F0MuZXnU0Q@Qxa$%@cmvxV zo%S!pgqs;T0x#}+6|aJ|Eu;>|IWew1bSIQzNNt`L*0rRl#_G1j4!@leMk(@cC$GsT zfp;qk4xLrHBF*~;>tUt0@Yj>S_bhw;RsGy57bC?trHfN;U4bL@|{W(RE-KT zv3s6;=W}tjO zWq}CmS2VWe-Gb$t(+n{xQa@h{D>L|CeM&e?M;y=6V-Zp#YH+Z@-+f=)u1m$6_bWpL zy+YhtXe|c5`j{DEXMud2UV6t^yun;Ht~*>=Iw=w67x{L;On+7bhGQqFo%g19lu6z+C#NW2%a8rv zTAr1M7qVZ~Hp@WZoUwf<%bm}5Bo+LZ5wX0yP`TsHzp|45*pPocyb({;x-EaQD&+5Q zb(Fhjktm+pGVSxWj89ZS;2iNFmi4G52VAYy33%>;uTjew93`X3ZrkVZNc?43eP@P4 zMo0VelO;)a+%Sw8LW|cTM&dAW6h)R9@)1ON3C7PtR>_qTHE)rqjy=5FxAiqTkB598 zgW5Qsh=?MQEK!s4T8n9Gw!7Z>Zca`w)s-;=iTjNSMf#SO`|mkUtPAR}Qh!Rg6WU8+ z|09-crjlUb>rL2d9X{Drq~UBVsv1Sy(sE?mQ&NNF6yM;@O)m=Vxtv%aKFXoI!cZAh zoiu6c8984xq>LnN?e3qCEIPA8@LRACJmd=6o?Fq>I3hRWRi_8j5(?X*=~MAHt(Tt) zC)x;#uUQMGgzA1&6MT7aWxrnDT*=$L+49t%OXw4x-WSR8N!43@cUV#~ZpGsK#(g+4 zTlkATx%}|_|9b2}lsbF0uNNjQVm_WGxk*Z@XCd)jS*6on?(I=nzt85I)_ui8F^qBk zoap@u8EBgw{(^xkE&eyv-wK`D)j|D6M^5}4h0?Aj>hhDD!_jl+V&&u9Xy!azyh}*l zhtyqDwR(3pJ;w&^rCIYfabbj_U@GHCH`A-7^!a_JhNt;Cx4VRd=P;y`=sBkn3ceoO zxQ&+(NyPF$MI|Kt$KL+)PybI8D#cq47~{?d5GQR^r10F>SJ}i#UN5E1R3*ZYzAx*& zyN6<&zD~d~Kv)-572s6b>1(ARpCT=oAgLO){hNJOd{~|U>@o$l&5^KAvwT;tw9F|3 zQf$ECz(e?~mP46!_0N9Bu`vcd(MRM*ZG170wrLwm@M!}3Nqkp2-bpf==FJ=Jjq&ce zzW-+8bhL38BpSbB%5VA0KEXI)-3)lwU5W39D4f(FENVRxlRc2w@b)TPgE|rlsUZ}$ zP;_x-Zg0=-hL6f^sNQAseImMb z&+(UMPvU)ASsuOY@Cbh^vu0QR4ix(p1US3kT`#Zb>Q-U*Uu*8-Jwo@kld}s(``g)} zLmWSET(1&1-K(cIZt~~5f6Sa4*~x{qmUSHRPc9Gs6b=8QfcocccpQY=xNP<=ihLV+ zR2Hu1T;qyp`6MR;6_2?znq{SL!IS(q?_nL=4faIk!Q;5Mo*g1auGrtjZdNHbtUo?P z+e$q>zyHe5XGmlAp3 zsCzX+KNEwEE-T$1ZI#50JuS=i%qYu#dy{_$hfSo|&G`e?u8(_!sXPwAKJ@LRgJ2(c z!W?|#D=GaXA@MznVkoM zk+{DwD2zJxg!BH5x5JB+iTQstGUSg>suK*5EV!|7Nek;PC%WTKc=F+xWYR6faRq?m zGK-s`1w)!g=^nIjy~~&77Yp}PSUJ%P<1MbT+!QJ3?$n~EK@es&Oc>469jxl?7pP}I>Y1G3+5GOP< z6BbXbQGn;4!muG3;j)8-epgi52h7IXA#a=Z5vraF9!gR#US>7%7@j-phIN7^zE2-X zx~5Iw$uu{4prN|r#XTQ}3b8YQa7&~rPg*5KFNytryzd*8S%yOz5PHx?7BXE@I%zUD z&*LVqT_T=Q%oo&*y1rLA^}(;&s*NJ-v8wAyyjE$^bIV&Utg*MN4P9K+B4G6gECe`j zojogiTux(SxPVb=TMBUNFD&0?S`Di6@b=l##aem{c7%NJSy)(5GM8ESX{9$W8df_D$lCRlF-f^i5c1B~-??}1`s&JZ!qu;z8ogE|qlG-! zFTDEiDFF3is}+yM-^Ud;yw5e)uJD-9+Gi74WEWnf)PKx0OF4=t-@9^Q3dL)YXJ8?+ zTg19;f5l84n=7k*cQ$)n7<q6I*mXB*> z5iLB)K=qsV3+kgu-FgtdthZe#o>_3@fP4lrJoE8k^@+j&>nnFdxEV#O3if&4SA2lnwRD7~=P=5j`V$IB{)aVe=lNjs;ndoJ2+iZwvET-G><$BaIa7qvWv${pbnwJl#I~dJ7N6siKskS%cr0q`*nf58{pZ#MtG+T( z#ZcCOni_>n({jDV+<|_dc~cXoTBgSC(f}k+i9ez-aezXaiE?z-t9_q^ZoE zo7>(2Y!uw`7PDiWMe|F;Lqj5#HI&~zw{9sdEd{%&59cgC@$TwKw8v!W$by;Q1ryf2 z2mW;x7+S-m1)S>Inii={4RKYQQzbziZkT7mEv1Jsi* zSK9{wgQ&+r{I8?B$OSz2n5JuAl`OR#4hmE8+ox|A9Wp24Wd&Rb?li+6(+RouO^n!7 zv{AUM4N6N&N;(P;O^AYlVZ!7I*eySAhWh{AL}jN;Ib+AJ==bcx;sk*Ge|Zl9(tHql@Ck>N(X`RgK?G zOMN3vX=#N#oe+sLBwvUGe3t0Lm0M(-3>dXZ^VKEmUcBgwj3fSVRrC3_qh@waPWN#p zGU=fzmvJ|isi`T1A?FSwEuU>*sCfVqp$U7aTW|X|I2a==={suVZ!du5tn{k?pNDV{ z5{RxtT-nI}&zk;$tH2}4ImSx(IMeoGS)g_gHumo{u=nzw*wNwVzPWm{_8RN?=Ubm; z;=WazecxM7RFbqW9udSlxV*a9Z9Mw*(rKX+9Y!sFb!u{n+zs$(4w&qD(~m}-Pnh_2 znd`0!Qz>*;UuOJzlE0&Db#q=YHm-^cND!CS%mH&68zQv21&ipSx09Z=mzVh-%2N|R58 zbnwQeCF{mJ97xH@-_p^!P~GV3;c{q0X#7ayCr)Hh`bMTC612X)E_9EboxNvV(=g_1 z6eX2Bi*L4kOYIjsJwHD1*pXo35~*dX zG1Ah~W(wTmV+*soXWK0}6HghDiqPG`ZwRx}q`-j5N&4^5&_Tk@-N&tXg6>~M6Yk=z ztzX{BMj-YDVof+Ez^C@=JH(ahORu4ymS7u|OV#jqd)6DjAuKExq)aw^eokebxy6Yc z{IIgAS@N2d)-9~hE@n&BzgbeRR8;|*b@4U{C8dVRvQf9H(Z%uh`dnMffdOi)NHrlb zQFYhnWVZt)_AQQa7meHJ*mlMpX1DmZ=hdHcER*atae|lm^M3-Z>01H@r5br0{ZPfM zbj1BnZ*&qg#B!Fd+xVa#I^I{Yi>(^Z)5UN*-2TKhP)PN^eEBjaIKmik38^t(bbu9pu0#GFn!CpO+S(HG^7Z5f__FdL$v;ZV$Nh`opk{- zNLh~&upnxM$&O`s#(G|`uObZ+w7RJp!F994KXEm2l)$?U{e9l24MrysG6Bn{LTV*- zVK&+&6Fj}=$M)o8A?+_-)JN7$4AhMXWjN3*XtNH>f;PxW{Qa+LA}HpOg{y=ku97d(e zA+;*W6OPY%#Dti5UlRUeZWwnIpWzHYQkYwwHnQfMSa=H>)S-pipn)--39ukcyAV$$zrW}l zAoMYZ{RJL8?~o9|KU16QW>4r8X%M$j(kwd3zN~#_cvPoewEf0lk((WHzyv zD3^c(>F#!iY23QU3qG1JqzuMTCE~S&b5mPAM!)XDv&2yNd1|-_m_K_Rx;hRSxk!hMza7F2&jam>meuwHcGG78l4SPar#9%i9jr|U!QSQOLO z_v+ewPICM%jtP&|%Q>3-H!sA|4Rrl8tTX@EoJ?P?8*mk#iO2tZ1D!Y3GL^3>tNH^^ zBiMUdOT)7Rvfv40`bL{lewpP(z00<>|gB zysUu)o~sh9M`@AaMxjxvWef}Wk;;8~4zHjk7}iizW9s^<@ERuseSd#HhLL25gbT11 zn9sLgNgeo|@AVKbeX!Ux>|pd>zXSeN&*wvDi)}ndq`QgY!OJnOYuaAf#%U>4c{a~V zgo_mulnJVIJk$KpP1(x{hw?c8&*L+1?-~2e1alCnTfbD!Y4Wi1{$|Rn3pRZG3c>oeQ{bu^pG-(cF1DhZV?|`nE-oXb+B^kq zmzyOOT<%+1;T6dJUPgiK+EE(1@f_(W#}R4D@s^=V}sV4=f-t0S%-QWCKK+tai z{)Fj=Eg%X1C?$V9-oQmKdJfn)lM4(Unx>%Rx{7?GtKa9C8vN1zBp!z6wNl|9%?pjE z-@8Sn;N&mael{V! zD$H7j@8M8%f>CP=F*9W56EnFG^eJ3MUlJwp?M8na3#_fTEf{(ov&qGC6~9a=^Eoiw z>G$`r?$rAw(~`?^s5eNSyW%|@H@0` zRuTzmh18PfC(pCo9nmZx{(k7_NATUsO{h>-kMW*`yP(R=QzZy!3Go_5S|w0+MjtkI zB-AK0Ly-MWmqytHP4V_^$~Ce#{fR96r&lDHwPMB-V=tC1kQP~f`67C|KX`^hTX83A zEQY-2Te8Ibgc!V*Z^5XZ@bG|XhbV=(*)&i?b#!p>4-9Il2XI1+5=jf-q5k;sACHzw zkbq}pvbxpeTr`(Z@e4G&j&dodr8D9?Y;4mL*}nQ$zTOos8SZ!aiiBj-u>+=lNDXD2|zb)5q$;r;{JkC=RN8Z-dbCM3RliNE66|~IdbF5lM z8^B}9CfY$0OID*>;AP-=SZ`sHIN!@vqpd=JExzSt8r7pZuIwIGjBl6 zJuy-@R&bj>D1M$UzZ5R#IUy#`zBqkjrcvzqM6S&Fc_XEdo$<8Zvg8$Azb@m^E4ERc z5a0<&w!eS}!A(s4Je~oRpCg!a>sRl z_UkE>+J^WDNZDy&wGqb)=Tsx3hPw;*%>0(O0CUt%R*9x4Rfik%e4dwd(c&FRS)E+j zrGeP=w{H_AuNkvfd@64F?+Z}-tE(rgWN5Gr>NG$N1Lzy({e@i_!s^O;U#`Fkviv`y z>loPoxk{B}MuG2BF#lQ1f12;V>IdULa#5l5GupPZClH(MXtf->4|y8-$v5j}Bws=@ zSy7WFaf?L-nbmHW0DgR(Xy}4?Gr#6*KWV?aY7!yt|v|| zG1gi6Ou{m}fW2*kzku4&5GDeKAx{ZP;6hv~t>qnSFfAgl~Uym5`zgPYEV z0s2#RsJCR6qxXHU{CcMx(gW49=*4^m{831cm1o@C+*-Akw+2N|^eRe*2E3@U?Pgl{ zEdQx{L3_7B7ZO=Z{``LtSpT(TPnjHBmCNLGtADl(o(h9~r2e`Xj04@ZBTjROWSKL= z?CNS#GG_VCRv zzuN&xIhd8g;6I%8{yczxbm{CsbF64@z;pVlB{j{LL9i{$M1M&a-O<4t<=b!1F1o;6 z&a}txtJ?!(hRN1sRlUia@1eqs^LLIIZ<@CBXmp*1f;+F>O;hXlRez#ATO#aPA<*l< ze3~dMhmQBF{1KW4CB}1?KpG-Ro)=Y}**`WRcFe<{v`K^({Sv`OX~1u|*CggG_L(&E zXBpxpaoZZp&BS{;Ie8rN>|N8D>(syQEuB;S8eJP5bn!cS$f5*f(^J`ni0hfWtXz$K z+?t((g0YU|TR{O_I)v&bIC^1;19$%C(VHg!w@Bwc+Y7<9-1bSD(Ex#iW3;;~ zV)UO!BFw(O=M{>d9{%CJGeZq{Ru9p$x?`;lf6>P+TTg7~+x5>PLoFNt#rRx2#$fO( zT3PSttyj2Q^6*(#9<;@bv<4X`Bn|-%=I^DYwg&_iOY-KuT-(RL_Gk>ZM_jE9$nxpa z@xJhvtHg9vHHw|e|F{H>;12~9~uVv%FQdQ`;k~J({*mm2nTGz$XHeOU-dsQ z-l<6SOu!6QS6A<{u=K)uW`%a9Z7RO{?6$4Fl05-zWaH(*_bT5r=R86$(l(I{F*de= zGCuw7FKA`#cl>ABu5~&n1}4dl?%8Xl@_7QtQ%`zwdQJAx^5SwupVnWLDH(i2ca%h_ zlU|V(ZYSh7`8)d&Y$bsz-->YJ;SQrp0aKU8rwN+UnCG=&-s_X(fXdFG zDUVBN5W_jXX<~Cb!Zs+UxEQdsgx-G3IZy9G-~=3^eD#WX(_(MmCcxpQ%PT7@>$5HV z?z`?w5A$Q4W}-f~uFgTlLCUUIfAtCKXem-9ei5ieFg z{c(DYugz7HiX6D$DExiQ|BnTYglxEHo3cBW4p;T++!&rdVa?0XNvJo2DkmUHv%nzM z8BNV2BHY*0hD$(|9ct)i{~nP{Yi-}M&G#cq+|X(RwDGU;ccgqNGLv1NK;Vn_ojs(1 zIWCM73x^5gBBmRWhJGWiys;w^_)erd&oLS3X`F={6mW3NFr=o7veH1dbMKNk1D z9s|v>kMgY5K`H#mhF%6LqvL->ROy=ZJM-L${kbAt2KJr_W!c$iA3l6=`)0=AmP#U2p5TtRcV;8)SXy?ep~fzPEoa{jZmg8pAhIS>FLov-V0 ztT;T)2XFr{6u}gn4KqG&`+kc)udLu3|86OcRhruk^huJblOV1ebl6oX|EPDmRDD7cXllIzuTH4cSnQs=9)yhV>7Y1BfFNte(22NRB2@iUf} zE9%l05~{UyS+YDZARHwEKS;}@i#GrW1M)zMX}TXMgFaKTMrV)xZF^s3V1t!U~xY9ZDm99XO$Fp_=m< ze(kkMyG_1wHt87(!w|pR!+hL+`Z`^}2?I>3cdvF)R~3UkXCQE^B(jescD{ZO5U#ju znLg#PwTAfwfbS+fN&W%5kko5@w@UV7@qad%PwY(m!*k+JHw`?!aGaZo!Q4kOs2m=O~ zloR*S__6N_%6~@-O{084wet-j9L=omPzsh&|C76eHWlGuzjCz-u(@_-%k!$yuAJH2 z^ayMeYyNyY^8&1Cj2DN*TMlLRWa|c_mzJ(GN^M)gkAVkkG-0RU{V5tnM^{+qTOiML z-mi)Ru#XvwPXiZ-k0oklUnS5c_;B=ur1+mn~E>bfRUH9*p891z;B*p-B>~b z{c-d9-R0HQ-%D}g-;y;AHjX4xae!Vi4QL4ESFeHuIFZ!Zgh5fk`hN&AHyQy+ht6UV z@?Qt`zvhS;vPxnq0#O$#F)ug4So^r3_OZ65kUC9k3MNJcp5XD2VSA5%lOn?a8_PD< zff|A!T94tM>)dXbkNv=7@%s0dw+4jif4#x@aEt_sd^5<89{l_A?rZ1t%w*d0T<(lz zL}L`djT3a!sjmK`dS^(t)aZKGJ&n5&>`J%O24xLdul9m9d72bb8o z7p|)^+n7#3f0kdJliyLYsbxku+{E%HrO&l%NogT)#1elLScgeV$Hyq{qU%_g+r2gc zevoSiwD`rE)60(^d9&P}7Z2p;<$Y>xrOWa^e|RlcrlwLAtfdUwy1Vnqy?psfPfu^x zzg(#IuVx5({@=Kdi4^$tV!mjvrT$NbEuN%s7iZc88}dR-xmh39BP$0QGO&oTX~6u( z<#zcT=AsSSyg!-r#%fg>q2mzJj2S_98kdNEeB{NyX7J0~j&&-+y3no-4TZNb5=ipR z&~k23%0@5@AcUW>lylD-sH2r$!$WjkV*XY6Y4Li$NS$O2peyR z%jfGhBMX^I#BG0>F=dl=cz$$ktC8qBMAd`e2Ul=lt$cmc&7o1uTY<6~7qsuGB9mV5 zxnl79KF5|C>s%gp%abb=~gG)Ta7y>5|s zUf^;ij{?%yZ{8+!{LbHBqqx0~EGxo*9~`V=pA5z#O}<;5|3ySx!AJxk*JI?LakV%t zU{zL=XmJ2vZs6xIqvLNVJK{d&zl_BOnQe_r=j*7A5fywr#=57pR~u1y%%CJn=$t+3 zAh-d(_YQsFy`>fYs9bhEi+3~O5MsoxxNc5$JhBrS5jQ2mguKtK%9UvupYfEEp3u=U$LL7lB-X;quz zh5f6xS9Mj|Nr{>TPIw&l@%&N#LgT=3UgSxk!~3UB{?}nkoq9G~5^r`sdUT7#;6Ch;4gs;Tve&Mr^* zP@U&lhDTD`+g5No5j%J$aSJdcx7`(!<(glwOznAhyu-n|dN;Uht|V(@jO!rZs|4Ky?mv$>}y@-awl zPL$Ff;GlhGU*K4_ z=)d&#er_-Du^AaiqqQWI8UM>0jeN_Nl(gL&i=-XNvva7GSCmq7C3u}<0;eyZvJD=w z4fTD@HWh=+^T`e&%9uWWR${&p@%F7v{D8M@auvqK%afd~XL!w~N0KVOs?TJ4nS|J$ z3yS^6HZbDp2TUeQy>Ux>i#-Fq3HM}%Kg$s378I~2gS$UWc!f`%45=0mip^4Db41>NOZkI2o%0(7$^5Mz?-k>qHr=RXm!ZHH*(*?lc(g;Y?I zD6;mf?>~>CejbIFm+xH4F(1YAuH`N_8^wMz)k@t*^ZL0m>*CSO_pb_c=UUtA#POgq z?d@)BI%{xUk0gwSA#+>zLKWRel`KAcZXG7Zd=;_*==*zT(WcKHJeQ!X2zmcrhT0W_ zG>OZO$l3POwB<8)20g~vjz_2G2^HW^okn1VCyB(EIN?*w6nRTX%a;vau;oY&HYq7- zYkA*BQO|pwWNYXKVp3CkW5a3;NlTVprxjStX4Fdrku0DWLOTeoFJwi0ZvSbDu`G4o z>cHr@9MNpCHV7%v*c7Ch&ei|?O0>Q9_GBG?-vEYAt@6dI0h|^Lo=)VAJSy;GV$44eWH5c0X)z zy{FUo$oKIlm+qs8kqr#@!(0}Vdg9^CkMAQb!ic5yR7j@@Xo4p~a2{sCVW!CUw6g}@ zMdrxC!ND-!3KZNBrD9K0H*ZRqfQ#FTy1F<8%2$=ycZ!ue7{{xo zKat#|2AdJ5b~V=7*;#y=T3K4@C!kO8mA9W;A8o^+@VfkC&nADV531$!nZ6cp`rFSQ z1Y%ifQWjS*cwwG1#G;^)GQ}>Nm(Lw@S$H;Oq6;fu0V>iK+LpL#VY8lsf3#C z?S;EMq^yj1Lpmj+$8|?vQ&ii(xbS55Tx(f?C}@~3SUB%PjLh1+hktHSnTZ1?_pm@j z+Z`_l$vJ4s$;k@3P<8(WDJBkq@*FHB+;o6>*P`#@;$W{5A|h}YKLX-u<8YheiA{tf z5bj}UWmrZjoVa3_Bw8H?8KhoHg_@iT1MERvAuHlybOmyf6~Z1EQIwb^nk5|-e6`!B z4IStnGw7}xD*U1B$sT5?A#vPx)Eu`jJB#H!!#a#oV2#dbIJmgN!&9?yN<3+K9!<4~@IgMwS1-{pjz9Ho;)cK<&=LRP z&c0y-TyZ_#-hu-EK`;MJ7(5FLoOyHz@b~M%bU`_iyiW@D44y|LGRXzdp;T@uJla{$ zrI`2vZ=3CWd0=fhHwPnQ`Ub53$2pZ&x|#1~)Y7Pzam8)%z#raNSIHrR+s?k~;~ zp7Xwt?MlA4^JSY-JScV3x;pvW%^%vQ0u*JwxZ!aW{GPtH@^m}xM-QWE1&b6T*xQQ$ zG0Qgk?LiB0%HXgS&76aC-#ACzsjjL2#$(=3)8&p%Q_*UI41<;0jlH)lnS1A+a}fB% zN>9e+{e_KlzmsImg@%fb?(e(p;pD;|i!+M!PMWCph*7N-JPY(`OMQhmed}MI6&UMi z!W%-hJ1!4ix^5Mg&sTT&q5{C@l^dT5t4~V0eQgdKxS9xm-uJV}`LO7+mG!Z`C-VKx zdeZKUr$syG+Z!ug2(a+*h5}8c)NMm6XM)k4QoN3|N9LEFzU-@XSJe2ims5Li*wNv> zeqF(#+(KbfMSMXcq9Iw?8z2(f<3hC5htV4zHYUb}Ty)J9|44+y z5j`H7jJub`C@~#lWhq`FnnN0V86PyAQHLh28mTPunMyy*t!rk*#YyLfm8^tZ2xu`) zV$H~(IDzobEIKnO;2b0cicoC=I3R&)U=kV+U&mDcJjNVqFsd{T@awr8Q;U7 zL7UZO^ms!;_~UYu6ZKwX*~v_xR$~y0DD$J)i0)^2U@Y~Pj2q>>-l{U`{LYE_@;w?k zIic=TtDG>$yn&*+kEKUvqe?*z?dbKkPIiLcPr2OKl<6(q{UDe=vXY}cY z`{2K|-a)zK!Y5Fp`}K0=bmC6GpVhvT1EdSch2Zt}{6{rG!|v7rK9|Z&10vwm{RcGt z@wmvzbSK?vG~f9AXoDyuISng}n6Z2&H7hMGYAq{(!O(aAP4y69C*q`|D2#zUw%%lQ zD62y4;rOprg+LAa%nZONnGdGFHUIf>5tPtQ!L{^|sTvFRAY=G(Lp$Zt6ih5cEi>b6 zqwRF7KzkqsC-ce8Sr|fE@#K?08`SI6u7}hY0oS{1Hm=&9)cDD>cm5@BJ$+6UZ(h+0 zPIFnQQJ1{bVxAtUDoorR$Z${D)05JFP&eZ2WoA7+BPCf}1H&n~sBoqRXM@`3A`nK45IM`!VkP${iFJ#mkOF!A{R#H85zFBbevhV!8uKm7{?PdjB zYPFd=O-*OdeTlGkZeYLh+s#vJWTuEU*40Fgwn@v<=#oCR78ZD6v_CPifgxlv#<;ZU@Gm!EY&2)_Ld0eck-Z)ng|No8oL zAkb2eC{Fg_vg?AUwmT&BKo}Lp8G90IxJs?~m*4O99OAb3Qp!xQUChiM>pf!Ajr$1# zR+pEt{J+C$M|t0v1!1d3ws%MW{z~=UiS7N6Coy+{2U>GOX+zddd;7|HVHp>b;k@;x zE@!TgYV>Q_c)o^nDDdVY=2grjMr!YFW$kFyX#`jI_au(EYN;lzySK$vc6Tf^uaqwvUwW|Pj0TZrZycsu63a55OzazV0=_&>znY8)6`pTLw1GWvL{=hPM3&V0ULa6O1b@{ zNQ_M!vuqdfeO}*nMEVq{z)_RaVRqESa6FnNF0N8-84Gp7}t&rBYIO4 zZ?7EW5CIJu%oulRKO!~q6RT;!o&hd*E%Gh-I!eClW)>dV^wJDp0jRLC%XZk4M+3W(~?3nX^LfOe+1xb zcLXf+CS1->0!Qc5L%&6&boaeKiHBiN(4S}>`gs1Ht^d0_fuBl{#?#sw`0h)ugwb3m zux-RJiZdL4x{YW3LSP-7UH55SJn9#fDlgOc(RGTxuy?Uc-4{3?mLh)GkrKG4z&~qB zYXH}<+e7N6?RO@6EWmgf*#pGSrl%TB*Eu4})r(3SO^KP?g>Zx;`KDt#d?)QvPfsZK z)?4@M_qIee+ao&S8u7VDs)(YWtCE-dSfkZb7V=jO@IAVa1kEo>$Zq^t$?`e@5x4G% zC{d|W3GN~uPYj0Mo(S0M8z(N=tswHXf!@tWPonKs&#v4^!A zbZ`p$-5@I0j=?O^kPKKi8a5Wi8`cp{^H}F%INhLJiBsKa#YFidcnjbjfSpLfh0Hkh z(x0B1xFO&3D*K0NvwznaYO)w&0K`5HE&oL6JTRT5Rfi1>y@3DBKd3n>Z`mn!k;=H- zqT@0O?+J zf?Gn>h5pAN;1BcLcVS}DJ#tCMLj&Ub`%#SdPK;X?a03;0T_rb9)h0RO;HRqIY$d{mA#eJ92E8qGx+<|HmbM~t>kO6MCj_3Q)fNea% zASWju2;tsljAyk-grWj2VDog>z%8Qxf*MqDm+1w-=oPl|-zC2KHO)-iQX9Kp@Q&1$ zFO9xj5ccGoQfvH$3`6vLm?8HaS= zTac)IS5P241)RXbd2CrV3T#PW@Rm`9Wa3ypNImMi7son|k%s|qc7qSMdbya%le#y{ z+ecKvs;jHxv$Ep++i-s;znEtlS)Tc6%e|D)1YKwm7jqK03jZL({ra8vl@fz)g<58r zL)zu4K=_hwe(krMf@7w~6F+IS-5}QQX>w=XEZbDnPdbAzv!OS9E(HyS^iv>k9m!D(UXgQmRR`7$Y&WlaYj?W zq=6cQoysii>U5$^S1Pz^P9y>{{rh~oW!I;CzP)B_-~){wqnkpYI=0*!U=qpI+c@^< z98uvBGegcTfpo$+wdHtE{|hydh=xvQ5LsE6x&m;0ZWfvob>3e+!k3ggeODs-};f(@g94#4NpK{ zMD+*%mWh0I>B{}l%`!|IZoc?q)glK|=qV`w<#E#=k0B>vaFgt>Qw-Rw%2^P zeV^?*q83j5X0@Uxy7SCIz%*X)`Wnr(^eG&C{rdHzk7Qc``t-qpbGqAvwpNXKjB`)? zjDYFv6);n=n^d&*6AF{wmX(+PQsvjVSk{@45$p3p+~D$v!MAqnK|!s{4)PYVCX8Re zjYqriN#ypf|M><>9-G9r0>;~OF(2!v!ceN6C=&go0J%D}I6GZByY@|35ZK`=6^#p5fzpAEzM z-r{PRr^nJN4srnk?zo$In%z z+=L;zvv6mZ2ZPgsWHtltzjyF^msT3g(aXl=WOrJx;Ze~Bv6e-n7*4bh6Je7M;jmm!+wiAaqQcc4f^{w4J72r!4jgwUW7sa!>f?yNY6r zt1~5|9vru!q}z4PWi^f^N60snf!O$TLqbk>nNTv|%kp553l5XlNgyjJS61h2mma?6 z#QVj_F9UtrsJ}-4j{%wk$ap0yQ^xau%pm{$Sb!ldE#0^fjGuI~WWw%O?hDW3DT`ZV zqmHr=w&V$-xlEs(COK?z&E94ndX*73Xu1CIhHLyGpZVca2)jh#t$WW|6|N4xa|#^( z;IaFu>+rE~HVZ`G7W32WoloHdWY+QZ_ZbUCh-Ag{I|A6-FU{;T7NhCUiRGK@W1q~0 z)mt4pba&6M32!}tXPQw>n&iqnBUksH;Xbr2h3%&~>!lEBYqeNos!V^I5L8lECl_+x zDh&O+&41GW7fN*BG$ip6{G_a5F0#o5UOtaH?G@*; zh=n6`{h$BH+HLgb)U7ADC*xi34@Y>X`yEf6Zu0|J!`2LvN08FQG~p)ymXo&c2$*Pr z@>Izy_)@Ef(>4dc00Ckq$>1~}HXAV_?e)y4I`x4|etDD-eU5LlkhgMBeKS;?VLtNK z87Eu7d0sD4fTxMpQSPHk#_^)~{MXUlRt*c^L4)~;xwr7oGAYu1+dmN8%lV~UL_W=8 zG{zvYN9o&$Hg9;*)^nyhs36hc&@4eY8lf3btvnEJ@zS=3Y{@wA_%yCJLHw?vphcXa zH`CbIE=n~L1oxQ2C#M)3%a?E`Ks~U`$mhB+1fQ>KKIBi9ooqIewMY& zKS(JY*Vm5;7`eN!-%B6IC_v)5%?s_Fu&*nWE#tG9^*%zI^BFqxx)1SLeB)NKCUz*V zfY9S#?H+&ZmmX?8N_+D`i;!`A`yiTK{KC{9&?7Ma`qHJNqe_=QM(zK4gxH}sy?w?u z*~ZLoHfgsbX6FAbnmRsBW2+&Y!MkvfY_}~TC9(jxx>FBsUmEv>Nnn)4G;MrKL@Nu8 zS?)&y>v1hkh?}d(atXFaOTE_G?qp&*n`fgWpg~93W;L&sLo)ySH~k3;LNU58z-$p zoNadUk(mvAU)go85(KvDkSjn0E>~N1qnJD}AM9DA0?34@hKk1I#_>6a&EjHDc$MR# zlZb zBqR|%Og|{_^O5y8OCsqVVp}V1EM`VHX{%nmu;j74p+iiQ>s#K|KZK)=TDh3!JY)EpG1kT$Z<$_JPP3LWsRszw8Fv;2oMahQKiFJ~B(l)XuT-h&VzML{WTz!E( z%@&0hN8uM!aKhOYk;I@ihIo8m`fE{z1BZF^EH{4Cz=4RrA3H7p^>20wb}s;r>LXl6 zzY&M1>XD)!wtmiD5w6o-Plt`t3|#JbaBpdz+90c7Fo*%ml0%*1wx~`hQfXIaAmX;G z{uueI7uFx4ud9uEC+Wd#y*m7?1g~uPD*4!wVwM28;oyj}uQ8Q#cKGj(fOQL_NG9G6n_= z*IG5N&BVfTf8sz0l}rpxo=BtW9H$eaQ#K`|Y_2O2Z9B!#|1GdwsR=rF1!Fg=6t`$N z%==%Iz1H+eyBc6$=l2&mIPzXG(f1PMqb6``VIeo%ZTxJH4ZA{)qm>FvjPTE)&H0Y* z&#Yw;%cre+1p)&(+6AhhzYh&W85}8c-nYL@h8d294?WZ!%Iws25UkLG?<_Y~89ukQ z&5)}rU}kQ1GTn1G4&?JZw*BxAe+6j)BD1xJ{Uo?Ih07Q+8S7NlttE))%@=i+UdttN8N^KtQhi?nWi~>TULKE*h-Y)#>Y?1_GZ&e~;^wx-)g>m5dOS3MDi^En=C z5|88fKg2X1B|N&FyyZN3Qjjt*e4qR4%KoviFRB+qj;hR-;#lg>5m?!W?2hL}K?zc6gUE|O1Fh}P+x{@tX4t4lEQh0e8KfrRFb}91W z#Xf*nwBi-b15U{In@^swI5}A}4L0{9x)Csh2Q$4Pc2N2 zUh97Dx#zxQtE&<9z|UmG{?~3Jsl(O+=B5VL_?6x^@E3s~+yAAqY=~`fPFEKM0EnQH zWzCiUctKR@%iP7*s1ByL;!Gl_oI73Wt1hqJ#Dhr?P0a z9j%>D8oT1^CWBl=&h1zmlZ^Hc=u5`;h&o)T@*GkmJGA4D`ZxMg8FJC=-eBv7+kNfl zWf|F=&{*ec3DFUv3*67XMO)3+sb*eHc(2_?#M@zuP~Ug9xaF;E?N=+8_z;8Sw&4~F zhjxEgx1g|fC~)(vf2o4qzCniWJb1^f(g-LYxz){`{ z1vFb2`8dKZu!W)0Hz+DoxLXa|D(Tv4mxEmdS-%{TcV7IYnWyOovIWP?MN zl)C=Kq1MH{-5Ovz>`+ALhkVV!vf7ra^D;AIr4^=NEmzO;AEbjw*6!G<761)Jc*kqj ztrLaJO4@Te=JK}0QpIMd@_sqqDz zEn~_L)U0GAa}Gk!#Fx$STDJ3247ySM3N(-Ts7usZ*^|;9ZSi>>_(@6zm-NtHo`VrI zd7$DteD2?MV>lBa966W@HuT)*tOhHL6KH|qSB4;8oyzZ!smssY|5J!w$kkEcDrXV; z`au0KX}Gwg?3Y#$&yMTScKRF{qu9HsNh)YBEGuA#U+MKRG;YGG+OWZxYI+TWV4WLd zmZ#fVQgxy02X8P2~jc+Nqr6i@qTH${#- z(7DDO@a@UOf(FHJULtmYUe0dl@G&(4H;lNa)3h$Kfj^A}eVVO?nz-y#-DSN8MaL*Y6;N z_To(R<}B57*^LjhQ5{0@Pp>AKbH6?9I(z8Hl|NO)%Ck|W(LpSp1@0X`|Cm;y+na9$ zEgGdI&q1(4Y|6W*V1~iD-3&IuI2Hv*wF>8yGA>S2vD&c}4yxfs1_iVvc7_i<;<2oN zm$e{w>e%D>94LeQ;`_B;1W=jsxVsDe9jFGA7SclfsJekQr22)ikae(_5^<4$Zl-Q5 znRo`oOyXwN!DDdM5i0{0rfI}U zsZ|zU6aCl;Zz(NQ25SGQ8W-BD{NdqoBF5swJ0;=yp z5B#ns;reEF!iL4!&6C#Q7P<}gF{sNm@c~T!mA3Ht0MvE#rbQ)LgKuMWrpbjC>0jM~ zuCoy$a{I7{SX_<4oVg?Aq{b}qr2csZz>Qk7!k~@rIA(i> zTAk5<-2kDD*EZ*_JA1QU#ZLpHEYsGxJOGKW)l|LnO69E8t_LCOy_sGTno+i6k4t2=cyK%Uf*lB@V6C0bI*9p`w*U6VO|lD&PzlFEvlRbNc8-6 zH~o;=_m1`zv6xQgS=?0Ko7k39%-TiQ_rm2#a`4N5o<{po6AS9Vs@^cG-LYMKEiPHOp(B@_5^Sb2&8GG?vp}y z6NvnWp1v&P6BL{(^MAgnsMnD(Bm$K=nUL{9HUsbqa5P2RFX1I*5K2<<(-MB3+c}0_ zjZL{!#Bu%@&%SqWNkX=&!}75!XuIrdd^$h4w0}gzIhWq|30Mr+zr5O|`xsD%9B-^a zXd^s|+{lb%g^iS%#U7s1FWEO`!ao;~QQf_8@moG;#fUjOLD3V>2Wcw_haK6J;P61$ z{i>)qDpMatM8-L<>ntMQOrkFR!#iwH);_iEHFdi4U3pnauc3|lL>EM!-e}*%1q_PR z*wwAma;)0ce#2!NQbX#=fLr>n`&wHee&ZG^i+Tr;nxiAvl;;QW99{zEuU;kewC{-M zDG*f#7)s6sXf@bpaAaGHeroLyvmRqD)vA&_W5+8T@LAtcYbbL-+rhD1@$`!SfMvCE zCw^kD^b!ejn2qh~clsz6XKZ{&04Ar-rxy#y$G>OCYYWjZ^B|Irj{LgBJxnu|iwTz`J1fqxwT} zpbFkEd+Y&XsOZwmtl99Bj)1O3d}0G6Te-;hHna+4kPq?l(m8dAqom<#F?;~ZN$bwO z(|$?)^o6WM(&L+d-<;S$6c>@cja@RxM$mz#w(!)4MgDU{_$ zi$7ZlPelyN6wPN>XWVcfGl(owF)l2gQ$fW}_JWPbJzm&LbGK^s!3W&@?E}aFu>T z$%MIF;Wb2)S*~X+z?;SR>Nwe8_LBLpU$2(5kUjy0;V-t>*p8fXxp~gw<~T*R(bI;V zWxN`cM|3gW(eCC(S{_#(8hqha9;e4Boz0E9N`Zd3HkeP>+m-k(6a18bCD?IqcU$qz z7~xuG{Hz8sJelRCFGDPJ?K6i%nX;R^-$rvELAu(o1-NQfd8^V3FMjRFQmd=30CVT` z^(|X=Z{OD+1BTB7=`t<^mC=;E1UK|9aH5BRn=-RzYpoKc$Wrv2-yS$B;YBx3Yg8D- zbg5*F*(ZjVfK+O!B1!#m(=v)8HyF;@ahc=05yjcA%)q>Cn;7occd-gIXH~J6fcDwF z*R)xJgaQF;!eb8HWk3NOt?sAQBCKj6+adJ`dd^*+S;rnixrj;s#G9?CcXE}A^@QWb z*B4yM6}lr(SK+_jlF^?e1;T+!$sJ29;{4sBpL8KXW@cJ_>cy%-@wT~{RrPu41?H=h zE&UP|kU!)pVJGtOE}y;taTzU%>$}nZ9+yaBuWh@hxw`tao* z7*z5XK`y}PahIEW#7cAd#X-OjUh&%Bn&D{WbSL|7*6s;DrWkqqRxY9*ku9OvQ+wdD6wNajsK!$@zbtWUYRaH= zo*CpPQv>5!Q z=-XGgDw|1Cl+pr+Jg)39cS+}OHi9j&4ZmW4y_HPEU`HUnPnNL8#YIY<peY6U=B~hXDCJTSPhgE>ZqTfuKpXwBf5>H~_ zqtu|0ncLTsf-pm=5oP_5d?>trmL3Re65TDSjx{#TDVvy3-nd!P!mIoVNaJ5i?kkM! zgXZ}_>Z2_OQP}+>AqM8VbEdT#R{zV%j947Wn)3z05)=!hXnhG-9D@K*I%X@9(Y9y zBwA0M0Q6CxW<0-f3mQ5%2O}bJJ7wkQ#kDlGDCq`lVwQGb$ssad1ZrOim__ckv{(~} zwdf9 zB=)o?ID!zn6PWvJ9j80}%uQfA{HZMmdio06MIO=zPjn}1c%IOnCblhRyxNqVy-+IK zMWm8V_i#C--5~N>^rTurSC|S|38o*~OZxlf{Upc>rfNDIr9T)?Pi=R;dKBN)Ladfp zx~DTdTPm>_t?eX(3T=auUWcIkIvH!DqtBkcuzJPB!8ys2mllg9Rm*SqLUczogiDl5 z^m6T_ttCLcivw`-D(^M2mGLIDZ%ccrih+)FG+b^Je>^VI7XS zDVqT|F@7qB`~-_MTm}&lrU6^p4}&R=4h%RgM%&oXoY%ABR>h-8k$U$$Hm?`bN3ERI z_b#pS%qN_GBq_31-#GfK9pxcIO3~{EcqsEPU^lI0u6HHzkwvTduGl&o<*f?c=zpHk z#e!FE#V{h$*+-uOV$sH3B4v5zW3SAL)k~F6>1o%D75T&+3u^hMwQmiUC*UGnc%z{V zURw(1uC~_AzwtQ?KbZFdv?CFMDgDZtxgc(3Qn&tAS&Zyk%y7l)f1QW`)ay3^$l7gi z(>3rr{kN}HYU=OwjuCNsBm0AA`-?QC<3eb2i&tntmUpu9bUJ?Hx_rE?W zC@2u~^J}e2l(9$F)*2H85j{kdj{40Pn<+~)D*6f1uW5OzS>gAAJcQk1VM!mg$3Ko@ z)pj65F(Zs@q}gEdXdi8U4i*sU?}fFp-Vzorc)}gNvGdq{t=wGH#5Jo{l%X(R>un0p zRFnM4OSG)cH@afQov*R7q67r}2ayK{+1qsSK4}ergtV;Yj5#|>nlQXzT#6#hm#p2B zXwgukg@vGJ9=@IQKEGsjdfAH!E;Je@IzpZar4z6fZ zm~sbVWxW|%=@3pzOQMo~&vGD#0DSLf>pt)86>JD;%IanOg%ZJKfSQrt15&Ftm#L(S@#z3vEQ|ffV(C(~w<(c6Aby5) z99kGM=?6~5lBm6C=q6!d^5Katl}lSgQ(i;SZSE7DydvNhw;K>!A-Vj%fo5X8i$Ox( zmELxsbUJNq$Nr_wU#Lgsi<+)guMrFS_ZwmIMH!Eq0?SKo@N=g=hQxsj*XONRS3=dr z`rYlhsM=reSR!L2|;?8So*F6UM-TE8Q>u zAvbcgn%8w5PJW39Gb<|3i4@VE&n#=XSe&2RrY>4CtA3qdTX}PZ5QfIHqVU*^aZ~oy zOGi;mHzGwtb0mt?@8&cylx*F0w>e3Y>$nZQ$I;jAZ}6<$S!56Lx(mt#_kPb=u8nlk`TMPup4h6E z%zx#1NyhQ50f%mz*#XIROfjnrBQyA#RRIPP*ffr-`B?OUDlkz*kF_eAZ*pSdotBp6 z24lk^5d348)O=@KtVePmO%K;-y&hmjD#i3V)JYGHyE-dw^tt`G#`#SrG>=1saqhFm zOd$#7GLIjN0>#+M{t;aJsywdv*Q9>!JxN$^B!3Ua#iGSWmiJ2)hA4j5N3sA@0o9Ma zXSH+Wq;4pMW#_kBCw3hQ?!^6}6>$N_QbTt$zu2}mpoT3jD>db;xn>p6A!Mt>CF6Np z+usg^U=OeX)POde`M4DJuWGI|ie* zGwl-<;%Mmw?oKXk@j8~a9JlNIsj&F84n&;ATR}d{b5fETTbh~iD-cE79J2U0fR!ZC8v3A`9*rBw$X zxnC$q4YEFamAwKs*{&c&lqq|G0f)9Pj#&fY7%ke45ITN!4P0DyheVLUBA@h1!g(#W=Sa+9N#^WZ;Wt@yMWw%z&X~`5Bio-t>&fIk|eIXHAoMjO`)(#1`xK?W)YRL_4x8OpeC&{yXa zIyl49#lG9t6Dn_|QTrwKtq+gApixe36Pn8~m*7O6)e9e&L8(Zh`T+IFYJ36CpU?aU zjpXr+A)YbMDARG0)Qh+;To$ELvx6A4s(8p2;(Au=_ho1Gn?YDeJ(Ub z!7@IjUp)>H^}WC;GDR}9{`rI~%zcE9i1X`LyTz!ryIQB0ez0O?VlIeS~)$2Dby&$$4-pFkU~=sTQs zqLeht4JCbh;j$d$1sRnWUS(Gp11XEJ1mzq8C815nE@{3^_p9n}<5M4s-C94N5Bh5u ztl+kh@PB5hdp>=e_vXP8A4#yzLXV3{&!ctW%fR_uHuFDNdiz{l z#mu*Q&))a71ji_f%wJYP45j$sws;!ah?C=3SjwZ8^C#VC&)bA5I**>l+meSin~s~; z-iq5$Z`9R-&A!PmOd-4{5zYyLIIl#Ix1AKFG58y>22iw`@jc)_K&zL(N~v(%mZ>4P ztL#bjFrodtQHvG7K=xL{r8d-3T2(OH6t$e{8VZwj8SP@-Sh9HYN~!o+9NMa7i$Re4UZ&pqGb3S zV}W3rC8wBfPS7(*d}UF$WMyPzoNIDtkB*+g&H%$upcIg6fM}D~Zow*%Q_8Jqs?>Cg5>nEVvJ47 zmspigP;21S-ly4z@3b|{ZRr?!(Csta?!(hCA^W|*HqO!#GuqToe|L9QISv=#4LB=d zVTD4@&Uc>d6%=;k$&v>;k2nskRJ}R_QZ0?;w*0qA+07(jDJ9JA(Lopw;o$ubt{>EV z)8=GlhTb@xs+#Kc2S2}hUgh|`9ST$3=3f<3m(2RBT z^#Be0I)WCR!VFd=7EP_;T<;GPWupjx-d_Ic4iYumOn0B2trJ%4rc2sN&X9X?FNW)= z(2-7k_MjV2<@pOyD?vFQ?XZjSd_I(AO~e^T-?K(4^%W(1OZIEj`!MDtrRTMoT6O=6XwF|TfsilmZAf8!eRiZZNa519Wc5(WlBZvCkQ<5(@G}OaL1#6syV3{GGp$||Rppzkg<6-l zmzymHZq(W2@4L}4s2k8`xQh&*FZ8SOrIyOni7=>v66njdt1aV^wnwV?|R&!7yuxJ z49SSUCdB{iGLT3QU@5D=z1#&c_Vxumm%uHkp(V6d1_>ITt2D0kbY3)?0MbH$d9N@L zMs+g)#22e8PMx^d2l#v-j#b!oQ{JGpp~f~aNw@+&P<1??9VId5%8VcgU zF)5O8RzetU!Z5#?IL0s^#Y`ojDZvkz$!)`KM$VKKQ+-T1j~ORNx?a@zd`^yr64kik zyiD{8(=JI#pTIs`Y9d~W))n+=Y4~H{aj@pE*(7Rvypia=VGW7cnLF5FL>ZD;SZ__{ z*lEQl8Qbv-{U9JFym5FYHUMuKWNRAQDPcGu%kVvWY|?qpUd|g?d+|&+#FE5rDKKHC zOvTlI{+D6B(Kl}lc76+MPc%FIs<*D!<4G+JhwCA@DTH&8N?mmiSw|%gT5pOHZe6cc zzbGhHi#$KwysaX?c!uG4y{+VNIIS_}tej$OFE1b7DKP}nE)4eVL8>FQK!K>)Xzgv>SVi7M2n#E(`(S@&;Fg(uII_ zUrpDIHT2Kf_kH%Yus5!Lw~pIsd_0A=;$A_OkIn7;kya>{Kfbtn+irfB7zye34Zv!N zBTk}vDX$jH#3|~AX^>A10Fhp+~f>Ej3rK?J*2*V1nm58A*Y?<=P$o8!c|I8))- zb54X+6UN&8Y#S!8X*G?)BFL{l2;-`Eq(Rx>deftMj}d5}GxXec{pE%J20V;iy~uX1 z0*OvGqK1<8q{3pH)-*mZM;n$dYp5n3 z6fpBRvH*gapS|z^C*|l9kpXV}Uv-(90Sh3Tv6DTSe`7oUadN4fF(H!idxZA8x=g4h zs~LPnjm#k0$4T=G9h(Q7%>wU3e0;poT!kSbb({8!FKA;@*{Jcd;`oL`F<+(Du_%;y z5sVGMb+j<)ur+MLSXA*6I9a7V29c>2X(QUsvUSaE)zsCQkQuesjTvPrJ)a&QAFEE= zN;lF*M5k>PKfIT#6A&$$%xQhg|Ht%316NN-_{8}w#hNxlrO~9(_5M6he!wD|2XaEX zN0Z!^Hmfd+D?EBwLfcd7xrfuY)*UCL($-D7sqAr;TWCdGBJte#+&{Gd>oh4;kUoQD z1Hj;aYZmgm_GrF2TO7C&mklLGDz&}(U)0B>`^~lL+~zH-E0w?|!`too&Ex~7*7Li$ z&{DEE8!jS20sz zZROKRJg(OsFup@PpVK(wTab=48W&EWOLXq~pF?1Gi&m4m<3x@Y!JLHVxwx^DZ(-0F7b)M~vs zvZkM%*ZOI!CjZVEE+;b@6RIQ`(K=&j)jrLU^dE|}%NKJ-+mszHaM4mKzu+80UI5O@ zqT@ZgJ!q)q$=67UIf$uzdxYq|*hTP05kEz<1xK`^{0#T#73F*|+@H93$4ofw6J=dP z+pSHZO~=BQT8@`VCB4rnlOTqkJJwb@U+vmvFKKR)U95dos<9SF=OYHnr)YHxIkr#4 zU-7H7Gz^n|>EQdKB2{~Ae*xcM;v_7mN>da($;lJNP^SeGFelPHOqpjLZ#>`jYq)8R z&47xk>Nos>H)QYvCfeb-IZf*rI1@8&fh@Trsvp=L(H*E>#%x!=if*dHCU+zwCTKc9 z*w-Vm?1R1o2~h9h1Kl$b?^U?Co_qqPhJC{ZaWeoQi>v_X(F^*?rI8vNKSt*|;NMqU za^0ONgh%_Cps3FOayee_kCNxM-I8f#enhhPUEtBt!(_?jd!6^6`TAnT)KREA8P zVb6_%|2U|BmtN{`n0*r7jw*58S5WEVfHM%H-K*!mlq+xslB_yF`n>tBGthmM!NnN< zF%p9ii-Y!eQdJ;J8Ex7B&iDFi<*vtdR?oaNhZn##8m0-p^C2rxRggcXXD}-iwRN~#L#w-0>lVtby?|bf-wg~U%$h9y4Zw2qyCaXaQbke zX(_8skqQ_0$|iZ{wAnTm+oI)J z?^?~HF}Yi47t_USaTp7Hj(=RS?d+jRZ$VSLQJVnozbuNvllw4Z_P&S23JIHeiP&= zoGRYVI8pA_;-1v$o6G3vdJRVIOY5nt=dp;9^lCA}M{a;#8v(y8pj&ASn)=yTAsvSX z!X(~H(^N>Zq7tm`Wa6B^x6iq}2(28Y<{!ARqi3b3Q&_qrZ!K3AWGSQIBr(S4(u>HS zH|bh5ZKyY!-7WHR|ILS`Xrc!uD%M-_hX+^pTa1(|+`7n3q}(f8+1Q|TyvvdMI6LI5 zU^H$K$W5i}y51IyPaBWcKQT7Pw%FgwChb-i-`~lb{$n&oVgXw$DB^({v1CW*z!Y){ zyFZrZ+euHK?^xI2S<6xze%ZZd`aWA#H(0TotXJgc1sg}vQmkn}9ti7p4y!!u@O`AA zWhp3-v%jFOYr`7>gM8k%o!yE@m$jw%RNrCMt92!wMESz-bPsB+sV^#!;kGGT=Z{+g zc!M7p$WH7sJYLrb*rrrNO-+k8-(|YA<*HyR&il6$Rd3aJJPezJR|gMBngM0P11GH0 zZ0Ke64f8I^^`Off9vSKB2`58g%k%}jk^`W_3xD;wKRIrWm+$!q$d&%#VYS+<4azq1 zA2!CymWs>fwsNmuhrsch{qOwx5Wc83gZcUq<&SBY7W;$sj%%?{mXuhiJLTNUbFbTr zts^j;4{ywC+j0vaI$s^*YQt121$STWpTeORFHx~6W-9pQ(NXURmg5M&o zL`a7JtyZmf^NT-lCThXCFwi7J2v&g)-^{nDu~A#Aovy5vRtEfxgt$-g@lJn!8Ri?U z{FF_N^qg%8O58pp8ROxZT|2ulr**H^y5}=9J_|n>B&Mcsl>f02DT*f9IR90>tL7`` z?RLkxEvT@ENmbG>k%ZUn<)osE^A$77Sl}_zaf@{+XqWJ1fLnnLFj>cqwrs~{B7(G; zuJLUc`T48!2nuBw-gyScKiWyk@G0~1w5YT5a9U86l9g#BkEkCR88ryAcT4`{6o1?v z+n+dBoPTKvWZ*9uX&Jnt-B>!qEbhc4uqrJm0x;QFSC*gg@_ufcS5+}}F9 zy!7hMnyCs5YCdGstZ3i&j^sTd-0S7=$GCcc>@^U%KVGu}ks)Rq%wt&Id>wggtfZEb z$Wx9fI1tKdaU)#xuJ_61`;7{JT7mDbelbB(%}?62_p7)$9q;*3dObIy)3tv$W?|Jc zBz(BK66~jRdN=)}ZM9~dN4CJqSUAtl6WQA89Nzew(WBvT15y>T?;uAJJqz0mxVpBJ z{gEcR6kMNki4wyVxW^qVFci6Px0ys$TRmYdFT5$+f@NX5H8OviV_1UJsg5ft<&xr& z+j2pCw6o)Jip~^5K*0HXD+>Z~^=&R3|0w+8{Kr_^!@^{$>*@DTGeG=BLgfO4Ri!S| zO`dh4Tuyc+;fj{FsB}NRlT|aOxre69Zp&Tr&i#^(tL#R|zJ%9kF=?>``A3cQB!_Q@ z3pt+m$LU-s22Akh&go%Cf+MHsWi#_$EiK0EYBrQ;D4YlMp?nTM0yI*}Ja+;1 zY7#WSyX+zP=~Zh^J)kRIu9g=UJO4?S+!glwi3q;$0x>JOJG(&t(gXh860ZYLta^ad zEp`ilM7cKKO>`EnB4j>70W=ypc*wl&9r|K~uhT1IyNdw8`sQ~_pXjLr;BT9t)44Nn z?WTOC7OapNsEZE!J>-S6o^%S5e5WEJC0l=zb0pWns6ZfD_!q_hksQPxO4_~Qr~d0; z|C`!Dyof1}3@2nL3k24*YTRGI%&g+}!oHkuF>6V=4kVrx78VYaR}owR5nQG7mV(gl zG07-t>NCOm!GoWGzd^>O6oP;qOp;v%P-#GX>d5NJrSifYf~o{t_74vCD`UD}gTOM4 z79YU-zyZDM!kozQBs`JFHn~&bchz<;6tUR}fik6Q*E?iYkq$rs$;E&jCskw3_&m*l zYZLbS0Z7r$S#`MDy1a{T3Fuw6Ui`G2aZo*y4S{fBTW%Qkjh(MN1;ebjp9D?g$jHjs zgKl3b%IK|U1|h}u`$p|RZb5Pk2|3b7JNzm(#MXXxd`?#f`x4Yv-W3QVDiGA1I4Gob&v4W{PPoI6f+xd zTv3f$-#q??T}+|LE!qc>b^W<5(E%Yz?cZ3cGkN&+@yO>ISvY};0NtP1#vj#dDDn(h z8_&D%2E~BLz(7>rw{yDwIG4GS$EXyp+Jr>5fK%({%E}X|(d6vjRx4PQKBOF?o5u4V z^?n{v=Fan4?|qM$OTX{8o>xlT`L8UE#=e8DS5SI7wXz3d`vRJ^vjuf)OotKqrvD83 zv$`|fvbVV^3bh0r>t$wSc^+HA!s@BiF@i12yjxtv(&3QXg{~i76bisl(N($1nhLzf7YF zBW6{$wP3`sZ0Tip?Up|SxVGx)v%_aqSbD%w8n?CK9fKfYXdxmuzbB98%`^CY{NL&7 zei<5it0w4wF=+4$gitq_UV`D5DaBPgbm#^I+vNNd#FdY_M{Z^JxqdP<(=83tM(1wD z=-l`7%$Y!o{`315Y2m`G0#En>7HYgt8q~3)yX!?(tdQS#@9$n&;tPPQX?U{8asPeR z|8?m9=bMjANO=4=TcUS?5HVI$SiR#P(8rOxktH;airxv?H4X0_JY~y=(!TX%d-OCZD!ksHdTEczVGyl8Z z0638OED@D^YzCFsd^KnVHJop_lfQWUJn=qSn6+*Ck>UA!I?=hi7!tad`s}fuR}zKg z(PB z>HJ4XoE1i;zk&#UuUR1plYlYZ&0wY6Sq;`B^xUUwmBx|c$|YLwnsb}UA6~}?Pc#ao zCJ2+xMpFKy9@>8OLl56h7k*^D#>F-&`|PP^cgcXvSO)afLOf%NmF@WNSu0_{*j&tdVj7FNTd@A0RMGCfB zN`GV@&(^Efq^~i3_5Mc&ke_4OMZWz0vDm#OqVA1Gjo!+WOQZg%#c|e!_pPm^OP@}l z>|#pBXlAE;Sdr%GTi}1lRr_P)d*mqPNuHJAz>h(YxSm}LkCv-MvTo2A<$$8R7dJ9aESVJ2z5-&En z+vnbFTZ|sEdoyRUva{FO-Lneu1+2gyuzcaAFI)A^o~gGP;+*&LEoQ3nkjg76Y9tf3 z(pC{6Rde8voRLMo5yqnm)ARy4Go<`ZPt!f%Sf(f=d?X{^oDi*cf&XXviHT=um}Onj$cUBn1#&3;FpCDA0)_l1wB-3`!S5`W_~?39+6zp6DV zHmKG?rg@~#|Lduay7%PC6T$>Bt#w02&~)Tf{rLW#LyY)SiB26ZVx|X6F!KODMX#l4 zh&QMmL6DyafP;j7-IC`jW*G*OR8-p|MB zrw%RXu+U-0nAF|<@0y*^O!-tt(=2&lsEs?=9gx?o^dN|5*9p%!Az5u&5v}>`x_ac_ zy-yOa(z4Pp9cl^jqc45kfTD()hqzz+g0f}S`J=DeHd{XN|huPKhE($FUj06p* zkF=h8+?>ufxh}cQ1lJ*R+8@`ICPMSp?=8dXA0OUjxxMl^|Dy8s$>Bo7AXfx?-C@`D zb?uDd>6*_HGvx`NSNBtEfh2vQKXhgXp0nES?{v{;!kZs*Lb_y$iXBhV&y^N*!zW{8*Ve@S z#dSZPbe}en4LS_Wm{;W9-t+2m=`MXd$thAvB}4yPX4IlOEM~n|{{k_7a?t1l!3Q_Jru~IdIkL8W8P&!EONkiTJiVo=C*>o) zM8%Z)xdM(ogpuNJ%g?%Rpm7gdJsx?RLG^mOaY8%$TD`!q12U1RP_O|L_mhHq`_7LH-Vx=|=CVVlNQ16~c-r$T>6)bYcyvcDU+}4M z1OyDz`2lMR`y0K6QD20w*Z=-guQy zhGARfcB}7I$@%n>Jfd+U$|}}P&Y;;>-TYuay6LVgm&s^8#Y)ur%` z+44hM8*agAZK+yU*EwB-!(BUp8T}|si!>ZAW}cZnRcpE;iman_v);@ji@&=1z<1BV zxLz>I(JT93$8{Q+Oc3cm?|BUx@tO#hmoJHE$5>ccKC;}aBy<#u>n5+FYXEqF50JzJ zB5;Yge3PRQkP~3y`l@y+<`X^b4?^<=;89S<^ATY7!UrQZ5ABN=1VCn3^_l5Aht~V( zsHh)jU!p1@Yl$rMRfJkov}M43zd*c=UHABfnV7CQt8}WbX`QDddkmM^5GjHg3q7&- zmL^u{M^<#Cgr?~fvI{QB=~ijV>Q30mY0pyDUw;#HIQp&QLX%!gW#B|rO=rtXkqC1@ zDqR%CQvZb)D7Iy<*cpFLJg?gUg-rH?G*ThkH}hlS#2y1i3Xb9iKu3@#9Zxa5f-zg( z>6xGxVK7r(*8{7wCJ_?6;d^S~;$Xq^gcG#znkr6X3!fntyU9B5#v7>}#GEv)S7Q6O z?Kqm)1em{5+utDx)p_B(*`311YU=6EvQK!rS0eP~iQpD4-mE@{5vg4>{Jsf=Zw>t2 zAUyTniTifyV*sWBvV^Cs9)2I~7YM%$K40-)=^z@=xkT!Ztd+Ml(#D%Q5dLDOf;|Ge zMQ$zRHn@^|oIZx_*?AzN{0$ne-X-kTGqY9kZRepi8Oj>hJL8hxz&xgn2F}kcKAaZx zmpysVuvg@!ZDqQVWNvLizVbvxUO&fQlTxk_?Cyjr&1bt!6IJe0EGd3x70xT}ZjhV| ze2wV--y7Mt_kVD;-(uE`H1>NiljQtGNAY4jDL|cP)rlVe$P67hnko%-bMM4|;TQLV zQL>1}Zvyg?c;|DaFQD00A^aq7LdZxl04pVrF~ny3nG^lNrO_j!s~+e|9$vw9BYu

j;!BW9rK3uRX6KTF_gd0hU?FP+Yn_k@g1D}!7e zrQCF8!*U-3YTOQ|yW!S8nWU#8sJ*7uO34Mpg&)|E8-xM1yW#oZt3A@?Xr>-)MLM>i3iYmfJt0 z{{^qN6R#l(G$GWO_y--Akhvz;plDrdU$JR7e>IMFT z(mf}3g}Qh&zKQhxh?C`CXT{Ta8en&luNdW- zg!Uq5NYo|3ExKG2hNaMDGJUKGzYJ^3Eb+U-8xtukyOVg-Q+VdL0s-PS`n5`&1Qj{1 zttAPy-xCnx(48@0snc@Is$F*~-QQvKUlDP=uW;}cX-mXlL{?Q-Ej(X+!?-g`Ir#qb z^TV*PU>s>PWN#dn%6NY{pYjCL=%n;;mpS;f85d?C)9y(jyMu74_UA$CUlMIXG zVy=1tBsWBylH~gt}eLI2R38Vm#L!Bn~BC2 z>};Oy_n{{NeObfXszzwzh42uyj3+cm<5Lh zk;&$3^>xkn!&v6Z3kupn$YzE0ESqVs7eIet4GJXbecw|-)2t(1NzuVzq~u8Z`opw>2$4R;OLLs9#ZVlOuxfv+9|;W# zsK@GyIEL@+7LrQ36(*cX&C#4ZKQYkPkEp5PHl6jx^M;UW6RT?xzj&+@P=)+sj5srI zxV=5b5>s=@E-0YJMhs?&qE#Qj6IC;x@CZ}t78(`bD&=wn^ubIQy2lFMVHD34U;9ri!WCQQ) zN~E<_X}PkS-oMus=y`HUO;3CODb;^}*)wCy5pg(a*~d+}->Lv%QGM z(2r02k?xm#(8imN7xUG#EaA#FQbJ39$eq*h?Q!LeG2Y}0bUnqNp%9DFu2Q(wqVjY$ z#FEVYWwxO`%9jlpsa$Cq0Xl8R`j=l`Qq$5Sr)3$3%W(G?rVixt5VOHtU60NCuM1*A z-jjllVAR!tlf64w#XgWzRi)fe4i=&Wfe`Hc^E0#**qRn-OhDBlx88WN8ZF1B#A9hQ znx-nU*q4_a&*gvXlTYTnpfCthXTlZ%SaTT*amWDTj7Xk@8uGnTpv%|=o|9hu{T}3h zY5_Ex+*qrss~tgxvII<1m=UCWy=%qBvvV@gm#SZettDuhRKL3zVmP5+Y3mc_p0B6| zxdiDSzxhznWiWR0Yi>FsHaX}Hob$wAT_5{?PQ`|vUkL9=^~Mb*rwnH=Gz!GkL;FpR z^`;B~0fJtlqZ&(FG|Wk=T2|{=O15-~%cTS0^?w-$FnN#($IutQaO(g2wSWEPKfl31 zuG*FeeST07Z>&r49NRNO^wt9`o@1xTqqIOOMP)IL4dxYGTcl*y6*k;`5Z^UE&a=08 z>atvXh6F?v6CZFD^9{%#hh}cy;$&mJgVJ$(zXPSIOdq;{So>s~v7B9%%TK2AKH32U zQKn^6Z#hZ-Hktc1-bX!$4m1V2_-^kJ9)m}-PC*?%#u)@@ADy`0vaQsN({YwIcY4vg zJ46mtJ*}YISAL7l;ol@W`=Q~p=t<5Cwkn$NdJa$saTCCD066Bl%?St#(tVpQq~+-6 z^=CC$Sf-@uy1wm6A1f+C-7w%aY|PcM{?)rQ{&TMU#!1NN3w!HB*)w!{)1)O!SrZE^ zMuuGuQS^-(OI(4mi*fwKbhMh=RzDkiCpW`{H}7;H63%KZ`eIfhgU!W>LFCf!tnp^( zY5JQ!UwaUqFUkzr-Dt$l{f>KuOG%9>vAaV%FoPpvf zqVIyw&SjLh&cId>E-d44+a2}HczR%oK<3tBGUoR5oqG$!%G$cJtabUix(xS9hqwHg zua$#%4BBg@>LcWYPoS2)u*|ty*%8~j_3+_8pCg#e9z6r&2SkA-So*(?A5VXfArl9) zx|fC+TPrIs!uvqXBoppSC|qrxb17y*DKPN4?P?x>8Kb zn5n!(k?=rl3*XR~@ShMdJv|BqkboT*_6HCtzqWHCnQ)2Eaw{qx`Cb;VWxs)0%A&(Xu6b;)yZ_)ESCjE*>3fZQj{hub4k9yiO9cl5prgq}AT+jY@i>ha+`} ztS#KmBvVOSFf7}8?EKtqho(d!%n(&ZlLAnyDWOveVcip)C&u}TNGRa_+D1hNSAry1 zgH$SvNT=}tGmzf$E=T~t1-tCcg=JDTgk803$zga%w$FbUB?!>IgH4$L;Ha#&wsual z+;9?r#4m@9$`eU3@)yRjvQ8Q_2~ZK*k^g-dfgH5pNs!9(1i$(JJPA=`+RX4U>uPLa z0Gb^EUdm(tmg(z`{`()IsYuorzx1o4pgywgjlYX>x(>`ZZ5Q5Aa}5;JF9<`xGZ>61 z{TbZO3sO+QRL6&^YG6-%%b41-uv)A^_^=*G+IO%Pr7Wb^-wFGh$CULTKIV5X2;^&Xc%g zDg8D@0~MlU%aAZGJoI59q$Tjk7CGoWIoF9X$4K(6abCd82|tr~$UqkK9$GptzJ%<9 zjz`6rpp$CK@otyxy(V>7--|+hC5C~ToRZ=QdX-i1E30Pn|NItH0lb-{576_+`^||R z3w(ioJ#LmAgoq%NRFw8*W|pbQ+7zj%G=vgC{p-|4M2@!7a&n6djG3oiJ;q?v2X0Js zltxbv`?=kF9@Kv!cL6KFb-T-3W0Uw_JC9e?shALI<_WLGufNM9S=)P(JYAsns)>=5aBlgXh;{TvHW;BC`Ifj0}1&!Q* zdLUC0`S|gA+ucoh)#IpGkSemb($=;#JfW?v9g8!+-eM4HL+t`2g`O=+^k_8#LW~j| z-}Z5E9?_HvEqnh!vhn=+>^+R{eFrkNfB>p2`5X<-m$1&nkEpwnQnf+0JX1I}+No1RX@4^! zUm>Ngq7npFxFRf~QPS`cscNox$za?pa8(6Aq*DJJpO^>%`^vg{dc1_DqWUAlS#6CL zV6^WwKJ~JE*a_$;G;?3**V@b&|JsO~aiKIjNl??FB({51SS-zY{Iwi^I{DG}6oPv3 zIkJ{g+*;ZK3P_+x@W}PH^EVstd8dAbNk~K_&eIHHi}LZ00F?9X`k>@hTBUI>Q-(kK z1JVF+1rdQIO~+o}z`GP4f#LP~2ZE>u?u^hJuu3W@!}qiN@UZ&q0=Ru1k?6!n5WI>A zb$T=%+Q&nqypoY1DB=YDOB2%Z8lj_3<&}~D?|08wKdQ-58zv45t{yfCTNj{5Ey9by zjzCa2si;MzyPkC?tz{J(e*Ds&8M8I82;k%4h#FAtH@)n2j_w>eKdaN&@;u7e^Yqsh z+vR^ji6?}r?|pcAOP5VDKM;<4%@ex5vbsO*z7Q^XM_2XL1p6HmCKRF)~@sk}u zK?JE6luE=VZc|@%*}K5~H25}g?fvb{tPiRVx6{5C@Sb@QxdCSZ!r~oSZkt>EZa8vI z1q%|T?wHStY?ab%L`H}a;xVKCmKm;{MzkrLCjaWuXS$42TVCQQ*t1#Zs*cdyzS`wf zerG~n0nffIzlP7he>=D3wnPm_QV#jkJyA1Sc&Ulv$)+oZ&IS5W$HHM5w_qg>Q8!W= zGH{b)DkIC}-~ovn8v;BsMFr$sjnm<>pGsz49z9|iAi}n|(*j~u5E8N$w~RO*psAaP zp@(!rF)cRI*Q1}wk@H}{7!(kOHYHm}6-@unIKOlwAdwpU)1d`CgJC#*$mBdtbpI|K zQ3wRFPmvSj)qj6@KOQ3E;Nb9qdy|kx9jw=#Dbw4nA;Tl>GaiU#^g#4J_dj7<2!G$0 z9e}^mQNO3Ue`3u`VJDPJ6~#mN>SuWiBU|S5Na)L;$N0UdGFrdTgi+~ewJ*#ai%P}AgIPZ+ zoSHmk2E)VTz^D@G#?g;NDq)!(6u`_%Kms7fV9eD=a8LsUQgcjgy}iB6ZL_npYk;Bd zv8`LmyB6_2vk?L&cwD%o;#W`_7&&JS8IatOwaxbr?XA8yHVRZ1K-F}cTFc6EvVQ$h zM;10RB2==C=*V;`4X390XMqO~EHD6=a(Vt|hX0E|`j0zJi~;WvQmLt9c)Vl3L=wn1 zwk)(N?L@1gT)qElBN@M%c|S|^UJNI-p4W5;-*}!GaJK=ek=iPB?wn>j6=A{)W`dk^%OQXLEwlalOP3lg!fS z4}&+}0PNfQWh$^0ymd6f7f;H620PCAzV+TVB@q``eW1>9it+ zqu1L6UksP}fD}CpVdpePhacC1K#BVn!u0t!0pW86PKB(p4QD};C3#5b#gYh218Mef zcqo#_4c~ze%v_WN7B)6rU@-v%xT^K|-GEzQ8`PKMc{5;I3uP{iMMV3SHy?-2jvPY+ z!9{w+eH4I;|4T+}w`7n$rcfTh>t(Fgb_ef23h82k$(E03I!{)X;L+c8oeELcF$!#= z|0*;83D>=%{*6^rQ}cdfAP(Wlek1gr`w0c{pdHBm%+1Z^JL)13Mka_yMv269)!&Gx z2Q4n&^8dgY{QT;789IYY!`yHs!V4P!8fWxJjze6mj4h}}IZPR%} zEq%Rj7wUSh_YGQYmPAn#srKvDd7+Jy#7J-j9hW)LAEy&Lzg*rc$Iqv!Q~EItMfxER zn%%q!xESa4a5u^aqZ?{91CwqT#Dev%$B^9b`cgI(HK(lZX_=Z!k7C zmTANEG^M2fssct84c~>mLSj{fiV^&(3z(VrDEcCUp;U@#V;$Zj_E7Zcm0ai-mq*i^ zqz_(w`SPIu$m!j`0WWYr6OLU5F)cp**S-G#_=f7y4`gjBu?O!7hF#5MwLQ62(JPD} zHibgC!z@6rJ%^In-YywXqJaDalfz$7B0EvNGi1$>Xw&{-U}Ym4CWmNa(&v3sGn&%+ z$xR}pVVdT-xktvt<3P}&Oh3juZ@$HFk~8|QD(fEpd%xcgZScm*DleWRFFLUG8$37u z`BRPv^=jul%UpNVp{Jt~L4k{jArfjH4efP(7Bk1RSWNjp?R{rhRN1n&v`vzz2#82f zBnT2rfW%e=RH7m|Dw(DM$r&0H3R(0z4n0}m@v;4XvDAM+Bkby-d|jAZ^O;5%ox~MsY0XCNy!Z2^$WGN{i0}>=3nTw0o z1j?|{@vBW*nlJ!sM04l96> zQ*;M;pa%&)HKOFzNUz`W!9Wf})5c({cc7H~66A#*Tk0nS(14B_#J<}N&X9!k-|eS1 z)p{(4aI&YePniwIPaAAU%kjp6qrzbF@&OjjwiGttqmgW(ilN87_|{y#K_^cd$yDjfYZBGz zcMKSx0$RZrPbM{5Ng?4?Be@v{)p*3%q(Up7e z@V%G=@h*+T_WjU3m4oF|1GlVU^62j0HW&Y04ev1#Xu^2NEOkhYz$d)|@f(I_`=Ddq z?~9}F7y3UI;dJGNU`F&ZWL<%7HFCNkzeVLard3c`S$BM^4gB-A9F=$USl-IDBAWV%y{3#Ycu*pwH~w1Oek) z;7>BKvsZG)INF?(jeR|`k96?iv(^*PLzdmER9vzx*SjX zvlvZXj^Fe#R5tPUZ))>*E%J%;KAjXUO?~hqYCPrb%#9m2gjc#%eBDz%(0b}J*qA-m zlpi<*8_WL`!Le0*_u#V=@f8e(M`G_Tzh!t3^ymi1Nx_3xTZlUSA$N7_;6cJ#ho-m) zKFtRmf^wxH4Ewsf?}1Oy6;(tPmz4qHq8TP1aM7#aiFX32faHd`C*tMh#SV`}_Ku$u z2VPJ@^%A{zoVKkJ*V(h3=CjGJH5ms|4lr2V?VQnH#8M(q-U%Xj){`UCSbXSzVo2+ygfvhQDl+wIR1(8yDQq$P)Zz&d?$Q&BV*bP(?VTk=S=l|w=rG}MHap_C;UlNUY z1%NTF2?RK$pHutk)_$az)Ho>Ei3svRLT?iIiq_snxv2}+8vyZ0{SK@&#YF!^A5gNb z%SpLq05y7&9hFk`%R3aF_nVs>$G#c1trBcROocL4a?f5M^;nVEyLjOwF{bLB^QGXYp#5Y78^EgtHl!|Xjt}MpYYB;&8P3o&e$ZY%1rzURP@+irU|D&>l{TIj=V8A)}W~i>SBzK`|>Ahkw1FPrhHKtj8=A5Udbc4^ewlf7uQ&7@52s% zRD^F*-$1lQMNuDN@c$|DX1wKo>NlMI#d`d>3kEqZH)@mIA5v@?TkUUlRS29a5G5E2 zXI&Q83QKT;tNYA#F5dnD$7mD7zskw0`x zJw15zGV7ye{E0@`w`*&EpUG+bOd_K1#Qpo3+`g9d;w#pK#6<-iJw7C5m)jE1+?WB`gAaA`Vu1_cUb-kRKv(f!yc1 zMQY)6Tm5Ztf6qQy1F$y%gw3a}lERsfiS6l!w5$OR*i9%>Az^?CiLmM((sgd9yBt%B_ zn2|jYL9&wf9ZY+oVGy8-P{DxeHgf>%26}eYP*%iDWGKloT|ut>k}^3GO#2wg)1)ix z8N9Gd!sHc0XH3`_=_0k(`Xl<3HpBc;J3svsiWj-~)!v1B1!Lr`f{h7Rp>M*`dbfCL z9zW(K+grGOq-J0;Ids>ve^~!t%;K-ACc>^<-UEV6ZnU{~&TaP9Goqc2j2Yjp-I*F# zyV$4b=OAlBZiLYs?Z`$n3}qzk8v0Np-CLdffnIXIS(xA z${u*5KPrn-j3+(wod-#=vZA4_opq>p4sOv2FTF(H`*zJaTm}5-oS~tw)iLrP zleAI#iwOrbT!^qtI${eZ;ZH+l}Z zlMQlqMxdJ{>X1NQi!<1u#deM}`HTV=$)ftWGXj&x6wH)_Wo027C)yv#geR%RS;SIT zp9q+n3OY8fp=(hPl9NYjc>c#*Pa4R=poNbz&@ws|$+X@5~EN$61pjv^I=N7Y9y?cwaPp_|*julaKtu3Qm*U;$#M6dCFD zR7t@fwVVIYj{q#X2kVh2;6a!pm135(*}e>cWOwnwqa|&jZv_ak6RWD=WSMUR1v`$osl?RS)DDFCItX}^+d>n^1b{cG zAvu;wXiL^YS+vMSaX0eKU2){YXp=M8DCV7K?;P=XiDCzykqZR6D%eZ+)=Y@_%-)=! z16}B4-S6y9|9n05X(+e0767jk`8h)1G%u3!paS@vI0e`YHjx{Q3MAtmZ^lkCW4o4Ko4!$^Y@E_v)JlMzHH5yJmYOG1PHvJ z{DZ57%^-MMDdG6=UN6A65nPftQ1Phx+Akxmpm0g-gvWgeF$ukc=tpun(zgaUBN$&! z!6WdT%~zu+1ZSXVB{2OQ{jaCw2R)hvY9pPHq?gxg_MI@qtJ&47UEjT<7~VT3EVbSM z*0=T$rofi}jQTB)U`00_Gwy3ltx*oRk~f8mVfXR*qsT+p@dK(p7~Q^}Yavt52SSdJ zJ_e1yX{^#L$iMDJU3h{*rg3B!fU##d>gvY(=j6M(LCa-jMM1x+4kN?COJ+aDEdutf z=CpF$`|xYK{{aB7B+>_rIS+uRP-{z-vo3fd=78jOXEG140n|kgocq1oJ8zEy~sCdE%-#CK*L!E#R zRoYx8Gk*O1Cy4wtX+j}kx@92hvL|cT$5WhX0Hl+0_(Q~=eqUNdE8AMutyx?&e{*W`2K+6P9D*K%cPjaLYynpsH2czjC7IUM~sgvlh=*IMtz(0^`~BI4K(Jjt+6r^*0FyJN06iV z&VYqhCN?mHpA7@QxUM-!EsJ>tNwP>BDPOo&cWT=kSj%;<#Pf|Z__?Dd@m~JoO~J2O z1MDvC6Oi||@Ioks?g`Q!?9duC_fPf5XXSQs@)LKoncP|M-~{N8%3ggHdtDj^LnQLi^{2drp$G-J9sEua9j{*+p$1zU^eMezBXf zmRfSDB;u=1^B(-^JQ{26<9rW2&z~#}n>xAVqD6?bSUM6UKMw z1YL0Z9|A~Z5_@~6(N_S*9`~SP`_55!I>mvw{wixF-r|Rs+B)zS9|CjH1#U(9xbn@h z##a0G41N)nY1YQ5pMbst z07!ne(??AmQ$btJIpnbJWtYNZjKJur4{8MCi)-xMzFe*&elZWOWZ_A^#o)b>;RhGu z-C^{)e8cs@6Gz=Fm7Fd8H^rx!I9WS2A3s5>-5OxyNE-_*ApEXSBxk^y`1Reh#TPUF z-5+W$$am^?${7p4lA?Kq=MLr#GxAxT=T}=11p%0AW1#HUKEfzOk^ViW}5e7O&1LjUik zf=9d0P;RH#`-QX>%i^6W3E%onE*DRl9LF0N6TmRF#;`iP=fCXhO=2c}HB0OO!NER1 zi-!*_?b74p2+3#ZGTA0d!3{o7P?WRE(4zIXjau2#XCC?59Iht42s!v&(d?e=znf$H z^|4!}8bviy5HkXm^| zAu!f98Trk|v{kx4&@IJKhnP{n`}X4aMEbdzb7eZjV_S= zu6DnJWfC%o@c_sj>!dfBt$I&`%@?0pJsO*)@KZ)z1}K(5h8GO=J_vCp$ma2x*1MVg z?dF`0XR3t+P65(L^z3t*{kMDZca2^h-A4%;M6_RC$UbAtraf^pmf#aMU*h#sq3_tuv*!wo>s5ZV2*he)kFsSKm#Z^Y(U6$hEIm*FU;Hy z2kQwf7mYY@3eIM1%+?U1uTWCt_$Bsi&^6i4!@*(M(1!fR+ChczJOA8vj)?yc(}7YD zgms)w;pN$vNi`)p`<=!6u_O^7EEZ$IuMR5=q`~`Kr16YVQYkl#$?2vL+gZ$@Ij8c| zo@)gttKGyZQRJ(c+@QBMhM&}~;GN%meJ6=jj+Io~Mt&gsxDmtKC-Pl& z?WUL%DUtN)G;zDj6=BRt`}do7l4{%AhzeNVjbWc9B4Z3t?|)lN2S3%XWs%nzr=D6r zp}^f!u{xx_;v(Xp*AGsc+T51hotc5ZsGe8yMx7&>ZQD5|+Ku)pvRg0WfTztWS4hlE zp7k%IVTF0`BY@ax7|bl#Sg{<7JCs>vXkbA3xZCM-7G@yvaAs9TK|!^2fDHaN=x0_| zm^SehDe7-OgOdF7qKhVj&3$ecl-MKz9>1qxl8z| zq)^_^f}T$v5s7&?FDlw4ZasXr%>h3Z5^ApNFz;e6&9Otjn@l6^5yk}aPPAhh)0F7k z2MY0|)wmQ~k8xLyU#{;*D2cp2EXr}iq!s)gb&V__fL(G>kRc=IzWMx!Tc^~8`iG3= zVOmdc?=FPZVkjl42M*7qU4z)k8=N+LfxWIx*2%oylelv+&Bn4^d^)->8TU4i%(gbJ zNZ>AhbohrJM7BstsW@ge>W}{4s^q^9jyE@>c&yI1yaM1C^4u%xdr6CY`j(O#5;7v4y_sn%^@Iui9M>ZPX z#%N{WMz1zeJk`i8n$UUdq}EHWW8Z3WP{-qcry^K zh;@}XXI{<5BwJS~>r;dGj$EBWGn`Kp0|6wJ^!(xu8%!H>mgmZMW&W2Hlvf|^(3dANXBjvLc1iPhcZwhNR5oh?I5ebDv&^|X-gy3u7DoA0?{68+GBrx)Ev4&MCor{ zqDW-nwAyBs`Cd`9QVRQdytB(>RVUHHvCf~RR8-8St*TyV%;a#XV$<Q&Pn7o}ObSl4FuzE>|O3Y-GRF z_Cny5q$5cG#r7*njw*r*m7o;<_*D1F=Xy^crvZ~XDHoHn6kVjLy{l~ppKFfq59RF- z*PU(~CpPH5T>rj6Y^FeBa&k*2goh)b^4oGC%XkEAr`pFUi+p`$oxq_zS_48N>zi(R z=V;8V&0XFpBdoOtnu!vmO<9hyv=J9uw^4{XnHX#>%*!>~cv{a*H`PdB3rXGh0qTgw z!+PceaKIA)M>n4+c?Qmc5Uk&f6L8uYm;#l()>buwewxI?as#q z8xu95xehbw4!ORh)EQB*-M23V5C|uXKTb8fR;0vk?$!9ao~CgB{YAVE%ryZY=4Rxq zDtXoytD36KC2SJUO1ez+H}y=io4Snh8J2ak3aB8N`p+2qV>WF^uemlQq4$OFGPL(vrc@`m)oRWuk8fBf@xGego>O( zVOGuUq>lFH&TwrlIEB_W-O*K6mQS;fl25USO7jdTSSzR5u zM`GUFYN{El(hj&cBv`;VI^54Q7QE!E(hq|#234|&f4M~JKycxkUy3q@Y&J9m-M1hn z;;3Ock};5*To3@qbWO(y%}-es$zCohGQd7Vqs@bR$T_!$BY4-}%nhxW7p1aaw4XZF zSZ>?#%-wQ(0~{KM+0bCTk2+1A@p)U;+mTL3C+$02|1%naetLyk)97?+GkSs>T^59# ziqF|>PN9S4U=_6+;Jr*uQX_JdfxRVKa`0EU^`=F#8PVJh5^6JMg4>vl+#X;3b=$d} zan7?6S|dvL%n3ebGXwef`?6tJQ#uxwv?^02!_8CW8|CaOK$v}c_VqL@ zyLL_|h1~fWUM%f*a)U3*X~qC7r6{%{r2bEq$IyZ@1v8{nCC-dY~y=I)#_w^RQHmgmWvh48pZ>((0ifr1)XM0Zb zPd<}eqdy1l?uU}xQa5Ns8j5y#?tU;DQFd_4ku`184A&_$v30_bMf4iJ31b`^@i@1> z>BCa0?`E~g$y};rg^ZI<(t`Lh#J!TjDlLWuq*b#d+{|H+v=d7I)cqU;FZsCaIMrxe zUfYVpfCFxtLv*GvS31yxh7>DR$(q@<D37#6QlvA?kAKt*K{q27Y|EL>FLQ)!i}%Jkn)BV0Fg;7T_4&&uA26yY0K%hf|lSAo}DR= zRP?QYeMllQF~Rd?q6l7jZ8xuR17Ak&(k*G8p!?=|8k+Jiojl4a7iL2kx-S=ceLz-3 z5nkX%ekK`A82A?NW_IZ`#oMRC-%%Dtj)%S$zq|_qmQq*&J~raKRFP`{&u$U2yT0l0jViVj#KWwis6g;@0 zHNXj+hKB=AG4FMRHG9Q;%<#n(5!Zf~rVaWY`1vtvR)GN!DW>O6F|n*GGw&n{2^mHA zf-PEhA4GTaj~CIh!;&D7)!B=5Y1CNtG^Sf%cD!$C6 zc_RESiNtf!{Lc=OoDW9nmcg$lIXXECDJ?n7*?WFcf?9yAK-L!o)mhr%Gj<+=CWb=| zv8}M)@fe-RnKZjchNRyW>D(b<0YSloDe)vd%$|83`kR}2=jb)gTMvUEGm=jyDi@8B zC|>c>tud4xu5g&?Mlw<-hk;U1o19rGC6@x2FOwnWW!1G*gS}M(WexkCbo0o351O4ow)Bg!D_4jQ#Aa-66k}r0&o5!vYB8;G zgNph>6KR!_^Lf_3UB|E$+$25;E#iF8kI9#;PwMTX|j*u)3 z3J2LpmuacWOdAoA?Uyz$y+ooJ;dlPMIqyXy`SZpe_?>_ySwLDGfyw1yXj52z6NA8j zpGQ^!Sf2yIHq+^x*+Q}+ez9XI;+&fK<4x(kj=fc51x?PrlE*3?^lU#ch6dGlB|M`c zp^kbEvE!8&Ep>C+nbzOA-Qe%fSpG4Gi3t=~ca`Z*YopsG4s*hi?m(y{B0vlx=`6hd z0iEKNa)$!_GG5CWSC$nvnG@|UnKc@^NsEN|nGqVOC|kmO(AVhmLgx9R<2A#fO( zM(Zp;q~0J0dFM~gtL*Vogh7bNLAF$!NuC8ZWV-EO(cLZB6i&o}q-qQ76T0wLmt!e;Z< zi1_4sIjbf)EYu%m-K)7pp^&pHdO%jizv zQm7;jrJEiuM2^&C&u0_mfE2~PGXGdrY>3tIjE}XmbK#RL2gebKt=AdmwypF>1%?}x zbM%e_=lD?X{H5=h;>>~6I&b$*vB+PlNK{s~w&&XD)hDa?O`-vA{SIpR;S`f3Ty{PPT}1&4aHjto%)Q>k(q4$+m|xb3*Ju*uL@Rq#+G5%amSwKdzh zb;P$XYU$_mO~)kaER}6g=mm!eR!dy;FhA=YN;Sw?8m4e_A?O0>3VV5E}n~H!D?CjL%>hRLD<~p-!9~`n5>1&n_A|()D`9+5Da;JeB|jhpNcN7 zB5K0&^t5wEVRm{i$~go|pb_M}Ew7Nn%ed7vw+tsoCC}PQqx?IG*-H_R!<-}~U5bh4 z`aQlxGXX4{6*cCPEVFFv$Q$5yNvS4`u`HakH?_v8WzLMev!2j(QBR0B6{^gO$lNwj z*?+~vw>Fu<^GJiGK-6?0h^}PGh!!+>7pc#V=qOmdT#l9Nu zZC|*pje+XMrn*uk*zYIYaC3k^M4lx~__(uFM!{%{a9Zu)gPOh9 zp)UHhNrSu74)@hK*s5d1SJm>iF^R-21`6T?hI_pLQZbh~y3x@(8)^iY%Qh6(4T8wd z+eH=oBsx6_N|jsc4Bigkhds8t`fi!D`BoC5lDBIA`&X7Wny#CXsdj~SX;Nx4Tg4GZ zg?A*k`Uj%jS8^bQJ>@s;rIMzhL?W_jPz(46%u5&AiV@ljOmr)`Q4;Dv7mKU3+PK{M zO?F6O*ZeTUo}ZwhKXOzjWCz*9a6}^vi7cX-mnzuaU#=L}7=ph=Knf|evOKN=_Ws%* zCcrTGh{XTSVxvSM&-Z@~^!=D)MVBO^qZ5{5#uNAxnxk6*)rWdW3g(D=W1`V|qiwxw zbuvQIL;qs^t>Z8QMUvCZnsLL(2~G4!>~O8I`9-6~%*%8;{Q6;A)x>j`E%6dM(EYj~ zcqF+P=fP_ZydIDN6UfJvkIKWrR8fovSc>Xv{dr^x^ z_NVRseS*z=$YhTu5CDohan=!=_70kyjZK{ilPzgBf=+@=Zgd=)$($x$rb+9Beq<^s zBk10$p9H&#V}q^2a# z&b;nckGnyZj=p?HRu7U@@5&gz4`~QdaNJ#=H;oG!nVpWF()UK+2NdpaJZVN4Y{Vn% z62?P&=KSbgzZZ)^eoK)jrGmr9k`Ca>Ud1Ht+ZZ$s7Z4n9%Ql%VM=RcU;Q9uYIy>Qc zX>WjX<-~5Cq5=$Qx+1q~hYab8*|(nuo^;*7%tW5l7PC>eyK66PFh^o3VK@I2hQ)<% z#@<=foqo4-tDyIstqk+q{R$s4u6_6Muy814U`eW%jRMg|ulzkcOgA>rsl8~~SY3Pr z)86Je5&~wS#H;*evn?@KE8MHXb^@GPP{?=ZcR_+TES``EPo63HnK$~)h^>wJ!J{LO z9p$mwiVhIVd)`;pmLdceQ9y|BC<7qu;caVX7xot-;>pg5D7OrieEJk_frfs{g*9q4 zUWsz-M=dUs<4kI&d>Rbx3)$;vDcboyU!|m5lVl9+?Ij?9C~)N)4?U+rVg~r!j6QDH zI`oil@W1sTH^~ou{kTAw*fuG&%KXvyrDzX;NJ+itkSg+pcS+{Ee%wq>o@f!K6~|YN zQ0Jk;W$rE#l~zM<7y$Bk+W{x^-C+NDVITtWZ{YMT^jJMf%pBbs9farCktYb>QFRrc ze1T=ut5*+q%X$`>05o52^l37CSVb2lU#zqB+pKpbZ@E{|PwHkin!8A^8D?&flulsB_}2kmJn!+cG3d@?6ZR5xDQw% zmLjGwQltfbCaf>fCE0eVYt}+aXnTU4ED4O#?Tr`$Lvxso^>vs^(<*xT& zbLO&c!+^B2Pyh}=wZ(0dJ@~LhkNU2c>11r)aKiqJ%Fa1qr}Bj#^9&3$H8)<|1AG(u zBMcWO%rc5=yjD8qV?FdXKn#zvq<5ZNoLFBdccAGi+>f=?M=XKb)vsZLn=1dUXi#v$>1{8W;^=9pPTfR za|`AjPVJh2!a-K$Ye+UwNV;5?DPf@Fchy?+r4e66MoDh$n|5hHHoI103WlCZ%|rT4t(a^!pb!n|gr& zwmZAB1_lc2f?T$fCD*KCVaeP(cFmJojYT~YE z1H*btLINo*0p=M$<=FSq^)DbN4QS>YActUt%SISqrQi$fLb;*JtCa|Ia=nkqS&1q` z!`F?J0pqF3B@q8j!&}egDy+T=EL-jJ(!Lg0FtQx6rvUBt5IO(yu7R)d%QW+>MDmW4 z(_Cw?QU!Yr?w#Z{2_2y9lFo__ZlcGHi2>~Zye&Q!IF*d?NGFe9fblr;y^GXaiE!VN zU0MurAHUbevxIW`6c0c`p7=+c2}){~mOCGYEP56FEU1Vr8ynMik@~XoB3fE!b$Z&f zVe^({_AS1!B~q~uJ9Yzv^y8tetq)y5Jz>Q5bJVYG0OaKRA-=(&YFaTlXJjbnJn)cfqt;p z0>AxjMrJpWwY6Owj+yZ!-ITfUYo5+)ZzR@c0@jz7Q0))Bp2&wCGLHqfa`Lthpd*IB z2~o@L1emZid%y<$LNV~Bmvjs%zN$!MzG^KeSSdC=Y?D2wBpFW5!j&FOlhgT9xNNPZ zDOl3=nW=CPcyJ5UmY= zH$BY#zz>W`?J1lTpyr&_M3Jcz?M4&xxjT+Hr`fi=?V-S?JTLBky_dvu;g7@kD=*^n zpjWxHcobqrZnl1o1$1^$SI|)1Zrko=;>1c~g}{1;=wfCiw`f7ZO&aYG+Vz{&PfaKL zza_Tcsj~?X96P20p!~oD@0BOAB zwpdr!#TVeS7nvZg#NAJ3{;jM=PZDl8ags$Uh`S8%HsKUFFB)7*sCT!}LRCnIqi zXn<$l(lJPx4_3|`K6&YD5huh*}heKn%mIA+z+w2}} zCKsRWTOTAVX$Egy+D)T9+28&p1V{uvDEbqi$ zNTdy|olCSS^f!&tCs6Uasd8T{ZWMX|d;92&AXY-r#5|u^ym)HDohEc4h4m^~d)@?) z4rpM&$vY0~);xOABYl-+T6P)Y=_SQ!XLqSod6__7tek>U8T67Uxh<88l_<_C*@p-r zGXQRL58wZB0jq^bZH6U!l#ib1I=1snh<&Ld%_X!B5TF9@35gu%noD*TR(USGr}voR z?<%_^o$A_&@9p5`%tv@FVjhXx>~6<~sxp`IIOUi<0BPtUXD+IV&pNs<60Dm8HDimy zKfgdXC&xAW^WL&Ldd})WU31?32pWoaZO%oH7*P%aOEXEOJ*S+EdVS!@db@%4)~8oT zhMr}Hdnjo7ZAiStUiG&g--`w8J|s4-fjxiuTk#qQIO!=vgp)T=lqw_E2`pV2Ge zjd2m;g&P__2e>QGG3llnkZr8PWqg5$x{q2ZlK{2ELsfcVa9iEntSkI6Kg!S<)hH** zV{ggkt1DgwR(thiZhd(d9*$K4Tt{3b?A$Qm%#}Q=;;-%b#=T|z`2Y|hDuZK$IG+0k zBGM6;Y&#f1PYUCJ|7S48j7-#9Ify!0~{N z1RMo>-lpZEnJ-IeB;QquUBB_eRD%k3SThi)UME{l<6f^npbnE2O`f^Ho zvIm#q-jLdLAiY+@ae=`ST4ibKg(Z{p^tw-5(dc(8X~#jI728*K5wnq9apO1o1cXmP zJ5?d%GCD(nIBr^be)?j?OYscw0%RtcCR1sP#XZBu)?B`r4Z;7=V1BXDl-0`Pm=jBaRa5i>x^RyXu(H!Wwp`~yi_=oIo zl^{m9c>D_gZLr_n0A6t`Q2TeImJzv|`AQcJ+M=5n_<7PJxWV5{p@VM? z`)cT#$Md}`PxFH>zYJnVM%vd0-CHlZXsWAAxhco(L)sF?OyI#{&LR2eZw3jB=P=U0 zCQ@v%>yBK!>)ltM*6Yy%BKUDspoS8+vbH`x_R^m^ujJJNx0@UAOm9C*gb)7XXx5ZQ zN_hI zr#|AOKX>E^m*YpJf-LO!8t&s9ggscEQ|;t{$j4mQ6Zw%q{uJpRVl?X{%@2=%nCE13 z*eO`VwHmc7g(ei34nIGLmkVn@PHChW4Bnc-bGD=0*8a3+jNJ%sKyyWoKX;~-2%n`O z>md5oLS-K|uj$9Ll)8xkB9z}HmDs8mFQ}u(ZT8CjNx2jBrgw+qohCDNRD17I{LD*} zIPx8gPFjOc7rRfQy2KhK6xJL#Tpw#|FGYi*^k;TCld}PKq||1%$jlLdfU#SUE{Q!k z{ENzrMnfC?!muSA!Gn4%=_>r!)bv7{XENHHW$?{=$ZN=sogK^Jwf?P-WGnrFxMh7W zL~G?I3UlpJ>NEI<9zJDbAiUm}(=>vfMsD&(p0utxp*f4Jcx!wPl+B<)ob8d-?&n!@ z2CNE;bWKM>oKiT&8+ovaKcn`j5Y#-PKU8UUSp4~!poGEB&~Bd+r7u7FJO=wU6Scr- zlBNkWUGa6|4Y~K%R9&U>ZExS*!BRgsvCDw`PCNlNh=6CefTyVV|9?kYH(HuLbuWZ!0!+kCS>nu*} z`epnsHZfF#GZ82Agn8CMm4y}txAuNpvuaJykna=pR z&cUy*{&uoRb28BGhO?I2aANn}3=Q#ZTKga=X^l|A(6f^%UZdkvDpz9%QCr15P?iJs zMhV%R8;PqH^^Cx5)*=SZ7MAcE?%z+t)&}|!x8@Q~YZY;)TMC~Or`J3G1<#1%tD2>D zPK#rRrud3b;#KwvN{(&NB}iY)`JSGAM)6v!eu5ZW)fO&^UARlfuwYnbpKQojbk# z<<3X%p)3K@jc@ZQ)-(UKmlphd!fzq`Zzhb2qwNzCj0m0|j#ru=iq)oMjw`M!4+^TR zt`Mym8i*w$G)>1&LLqjVN!)lWD08Qc5&e~t{dP(Ia&v*+XmxV3yT?fNVCP7pC=qdi zu^E?JL&I5NiG<>ah|}>x{BX>Got~*_?$m7a(JVU0hc`Bypq5zTK^^p9x%h~~E;^B>Xt5e?qc{$F`0qJYx-d%XaEyw&fb zjz5t62Y3G9&i^Iu{K1+(So4ph>$ec|BYXG*!@rf$AJO~~%^wf-$3y+V%3odlUnLEH zocAB+{l|I#A7ii)L#VJ8&k{S70Bs_Tz5wr%tjs>RE%x4TAjkn?0#FTW!Gi<^3)V{7?Ss zkFxwqeE$n&X$x=rux}s9^0h0MZv7j9|52P@$@ve;{L)eUQI0Ux&K(le&N{SxNSyO57zJ{c}zzU7V_7|?wzLm-^3%tAeNz$ z*!tK@Sa|;x#s5#ZI9lWFjrNE-Kw_3&srUO$RKHT0e@Mffn!3H5?!Sx^e+bM|d9+;V z+I_DD8~3xnT#+Al{!bSuI|2f%-8rTIM!tWUh5Jiy@Qqul#`NEwo%ffU|INF^=-2iK Y_+IHqA#r)I5BzgYTJcKmWdoo82UJe%4FCWD diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/lane_change-intersection_turn_lane_1.png b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/lane_change-intersection_turn_lane_1.png new file mode 100644 index 0000000000000000000000000000000000000000..d22ddc815c4e7e94cebda6298c11aad8f1bc4062 GIT binary patch literal 8152 zcmeHs^;=X?7w!-$BMnLn4Fe)MG!lZ+Ftl`z&^6(auJ-UazyKH{Mrmvr7twO}Be6HC0E}cfvZxc6GY0w8Y3(B*+>?k_ zElLG|38&Sc_{oMxv`Qh6MD_s?4iqdYO;o_A=wUMlGcn^4QCmWFIid(z;}pKDO3C0- zZ$%X-|1W_5Rp9?#0c(Ef6W0RQ6NIwToca^p2fO5;s87(apGD+uPguRaF8z`}-17+yfNbLb375QMO57}IN0?zL^jQ*U5uc4XwTgXkoih;;@@j+#WM@T&|j-tmm z#9HJ-OysNk=NA=CsaO4NBs75X1;5~lkZ_23=*5UiqkO|LT{0}g^eOV3yW!pL6mf5u zyhxa-m6cW9rSL6n(Dm6~kC~23q+NFPzcs5NvrMDjuYgcx3vie&rp^fkkEmrz%Qz8M zYh$4SjIqC8+En`_4uR+_)!Ge2GZ+7a(QDs6*y8^384V69Fz9fo3e-VQ6=L5KHil5@>GxtRR^gt@X@I0(NA7Zu3TJ{?O4hc5!> zu|~7L$u<>x!g-e86Sb-l*;OX>PK1Z?Zx_|3tJ)GG9T;C6qdnP9_d@($D|&AT4f#YP zKkSN5I&b+;N>Xus!Q1)8kV%|c_tdMpw_$X9$^WBU`!)@TnVBnXZ8?g$fPh>ox^pt@B^6pj=UA5Kc9aXp z->gOsGz3R6_lO-gOdOO7xcx77B{qgXbkTo5?mhWg!e95g`(dWAoqC}F*D=Z-u(QHt zI5L)bKO_&=amo&2gAIvq1Ut1aH>+30Z!>AoC!?wqX%SJjeD@K?kN&}#LoSxLc<-{i zmxnRDRiE0Y=Ej!$+A`W-Mm?r97}T5z^2`vMTF;TI{{tH7p*GL@KfHNLLQ=E8Fpw$_nsjF>>8nZDr-F zj8ll$4*c_IGlSdDR(I&6nrsU_G5%!gi_aU05H9wa`LCxd#DXI$O2}x=%ZVbjlY#vF z((^yL5rL05wY|ccrehN5ncbp0U)Nak{rVv8^64Hit#X@A8hJn#-$}WT8<@n%(Nh`VJ+QwkGe#Vrz;q{a15 zShcu2@s< zhhIfPHa)fvbFT_JVywmZsr&zEF|(0qhxnw&`_KZ&vSc#E7XsaF?m>qPR*q0Qc4~f; zmHsgKA@`80&f}M*dnc z2dDh|zM4=<`=^OW@JU7F5Gndn9U=4Kb8b*lZotk{siU79@RcI9Liq{B z?aP*1>*-b{-ALN;qP}F22Tz~BT7AG=E93WG-oBEZ+L5TRrH--MZno{j>7r`@^98M4 zaMnRUKJqx-LOD*MEHP~Li{QIGE;6n5yHmS~^7S6M^x7Qj zf6Tk}=RJ8z6AL_G+C7(yg4Q0w^p%FKy-oMw=RoXOL z$TtfcCQ5fD`ASS{?LEIYHosX{&y@0Ua-*EGuo&c50Kei6+qe)9*Ck!rU=rHf5OHt4 zmC6xuHne$atkzk3@U<*eRHD*MMO)^OFem7!&-<*B+zrq1Jcj&o!jnfZEpk)R>4){O z?0L~GZ*>t4X~mpbSAj&yv8pF{TH!GE|9EUWr3v=B4GOru++;u;PO8&N*xr^p^EP;| z%0gvG#mrapKV6mP<#_hckLsQLYuR_p`f_&4yG!CxV1(})A!PB?xk_!;CV?4&^)zj; z1?C(@2r9lSZGy_=Ttq@G^x(8Fl5JzHD46INixkM7DN3|Z_U1>`V7NAl8Za}JDPq$y zdsl;17A;#w=L;%E0#=LPJ?O32H<(pO$6xIyE2l>|iq)-pB}Y2*Xo?Lt`woFJ15QTa zCh=FY;X=w>JA|8?=!dFTV=lG>2;S}jd;IdMvyts zCp&VvnKSL1?BJc{-T&*o;b|14gkNFmundE8!9XjT%S89v&Y4}AK?N1n&E+*ulNr7x zDKGR_9!=8MZo3?^u@bjk39mK&80YHd22sy5F zt@~ha(vX#iV~k+$<>!aVz3L{+V;-P+1^(~YH#>}SAzfHy*In)8l1sxau==;npp0A3 zThV~s86ZDf12qxGu~GKFQA~Hq3BvtYhToGvSJj~5FOZXV=F0J!`W=7sdM_={C-SvS z`(^(r@3w>lVv-xR^Lu!n_=}aCDnVPiqAcZI>w;H)yzq}7#jGEBNYaIe{h_T>C0>~q zP5bC;ftxquTvt;&lN?n`2Varh%a^3p<%eq)H^*kn;zc>+Hrm2gf1SVT8oyw7elUHud`r#?B}uSKEb3y(kbdqRgjPj*`b3M{VwmQf=Z_1W+bB~%@Ot4_@0 z>Y%yn4gW0CrTZg|E+(Swm%Ep=@Ccvv+5M45@_^*qK>LO{RK0NLixna|;?+0I;<(TIr;clvBq|z*V!+1S>Ho7M;_LZq|j7|(x6R} zdZp!;#8dy?)}amb^}oU}2KTtM%*%jZlpaltuChkm>glgJ z)1sgIwq2IcvY?~GEW!)fY_lz~pZZMXb4Xj3gwE}612KMf!>?fqn3t-lQqF?l^TrYqsK;BmzuL2ZkqjzB%%V;i0bEaHcP#TUt@<) zZbg!@o-Vh9!obdM&-%b;&IV2AbG3HFK0ZE5?o5!3B~)u|p~bU-5ILwNduB=DEyY%s zB>&z8OP1kwaq(!C%+RJi4Hp_*LGbCPP3@rjQK`}Ih^N9dY#VkmU}PjQ3);tc^PW2T zQ(4seV+y^uA<4bZ#fesVSGw1nIiVR*c51`~*sJH9TC+O*1DdXC$(YxeX!BThYkras zm;UIEWEUVyayqMB;(gh;@F{C6WoH70^wJxcB#OB8`Di*`bCzBP@V{Uno5Pzk@>}^}B$O^FQQ8o2_-0{r0we*LTziQ9X z!F1i+XSO&pSW~Yp4cD+Mr(M?!ANfABbGCQOO|2L-(Ru0O9?l=kjs; zOv=hpX(Oiuk^mMPuQuAW&JNvbgSHrmGdI-8s57EfK?r`IQ9Pv(H{cpOG&LZj$fJ~L z9velFcL40VV@>ee`>r-wF*Q*7SS&;Ua1L>T0c7LUDiYtixXD5v2V@u~bqV^tCgae? zPo~=BiJRCH-V5DUrIKU8phV^TdpCHX+--4XUAI5c55mf98Btc|$|?U-}=wV&lvY{hv`PyT)(wF1IGuRI=2|#SMH8G_p6f zV162Q_fY>o)b}Q*7p=1n{B`PVD(^Cdl zvmfe5=9}amQ|C}9&@riBvK-UW4u1X+?9$#9ZsosjVA}eJD)XZ6Fhj(bCvG@DBPq3g zLriWopA_cJy^a`sjJ$@Q8r;MHt1lO&G9l>qWY4!cblX|3RczoZgu#i~#QG;Ad?D1v zi3O#q@+hp`h?lF%jBv;PMl!+k?b!;x{wzKvCdV+)i-v6Ob0O^7#?>a zAx^*YL2Yg^lZG@)$0@$+5s>E5!SnB4o0jscJxm`_TNQVgAbtx!V6bpQ5O!lfL?vCo zSQ*jyuSL{;kZup-N2$z@UnEuZvn%9T%oNWVoZELj8+ z?9J9!*kP!pq~T|kBK0C?JWx|@4j9oC6eJtxJ2!CJ;p>Hx5jhfo>S=SpiSEOWToTUU z2I{EqqCuZIa0r3Ft)`t; zsspK6-W?`+V#PpXMPU$=EcC)yxbJT+uIC@y)V;wEb+b-r< zciOgpaZVmZRp%6?#BEN;V3HJ&RU1nHV{DkB0$Y?qOl)Jm#V$e8&TW!vdk8VMoW}o- ziK)2+O;#i)4H35{CcY2_)EkM5%3@wcI@;Q zA#3sawdu`;6DY5OS>Nm=LYv42^vtAJnzn?a(-R2H--8DBivnL+$ zaD*pvhQi@F!13R|O)^s}ir5&4hgJ?cB`3(Xzbj(fhF0*xg|>?=#Pq6F!a5e0@e-Bu&L-WUIkNc=4Tw!4=up<#Ztiae|GcC$FCH(< zZ~YVBv{@~Fbl$Kma9`I3)?eEsGJM7M1{dTaBGrN^>pBM%G*B1GPdPb0Uibp~S{3+O(jYs*{NgSC1NiZ~ z9V}MoJ1G$a{fY7N<&d#J+Vo-CpOMTC8sLvSaceiPo#@SXDn!BJr6U9LhIGuwbLg8H z3CVh@9tB9Bg4z;e;+-n)F0;I-ggK7SdS4zu^Yh(Cu0&WGZntj<_YM==59MfcAvAqh zXh|us*Gz2KSt~}Ay^t%f0R#V2CA(=L5VgM}q>5Nxrjw(4IhL^YvEko^I}P^>Ui=u0 z>fHVJkA*}J3W&fDIkrb%7*q0=m$9;NLDcEs645Xv64EAB{KD`=@4b7+Y3x}Kk3f^1 zsx4EnHP=UC(4hO6^drF!o3PEo)xk-5^0!05ik@`j_%jR;I zQ;QCIGO$$oQUInv_w<++dZOT#uwHGZKnEP?8#6rYX9-CeNs$M~r93!Mo2#_}kuX|? z;P@{pF05XW0OF@Eh7ZT-f(Na>$6>Ez)T-|dQqg6bY5ix!hM-;*Wva*^w}B;YNIzQI z1oKg-I+Qi%4Rt9g3CYAj$TzyQq=AL#@>k8K?(Xh6R`ixrf#;t2wdzAPSf4LG-rf@f zSZg;RG1WS`h&qZk3`BWz%em%XoarSsW1AtO19s44r79V8f5dzJE?mq%n>z^*PDwBR zXqFbopd)3D9;*Q`(IgBH_mBWwOEX`_;zT6HNYaQiB>?7v{X>uvPGn;5jC^^G6VQSZ zRnY7>5h@X;kROZ_nb1EutP*it{m-xYBWN70Z?%?Kt%^^fY&)alXoY((c=Xc_Iw0b%GGL_oTwhwknU>FzGS zd7kV0_5J>U?|RQK>zs3)y;q#I@4e2tPblo2{1YGz5C8x?QB-)Pik7_q07eWh4*KlJ zkYNy7U^uJF%K(Z8>9zp?CV=8AsQMSf{WQEv2D!MdUA$msBvZLPJ9B^raWs}X6LL?C zFnrILo|@T*2@4Y|0MN#gSQ=sDTY9(*yk$Reg{lYj6_?keD1Is4OOjmfyd=EtJFX`;nbvm8*c^ z#}X42S_PJdRgS;dC+C!gy*hbb2ExV-i%-r;V?j#=N%qMf0O*M7Sf$!e0F`Yw#oCNB12F`;vAu4o@B-!*mQT&H!xiWm!oKFcSL8AsPy&VXA~Sgn)i#x#&^ivX>Pp+PhcUMrhta zp;ft1e!1kmv~d?#^0h{Mj?XROWC{$cogbBGd>7He(~`;#;eny;`lk>-gv!{VxC~&TDFS+sZ4*$`eJX! z{CYj1nhb-xq@g^}WV+P276~Apk2;{^{fUm}_1@u!o6&@R<6!#NQ$;!$exulkru%*S z4YV1R2DFt}TMr^IyV`Zo>CJ9QN+=n}EZxPDxA*S+7K5=XfkD1ShUa7?^YWJSkVN&% zjYPPO)^^(G#pm8PV;TH<2wMAwkyNK%PS@xtO*lF;em}a^`rtWnxBOVDbp3jMQ__OB zZi{8EXjT2w`8Y9x5H>Fg#M#2VphWTcjG-i`3A8sbZH?7~%MDDWYfud-Yvs z%r2bQd^Ok5VXRyzrWP$%pbSP?ixY>x7B`m{;vHVub(INL(EEfQ_l!#`a#AGE2@_S;8i)?p3K;7Ei&Y*4& zQm7#jU{fEAkm?0jz1x0?i|H(7wBO~V2y)mkSM!Ktn(M69Zw=|`kb2_Nz-SMV7j-Jr zH{tjI6*qMHbi8F!72ja4z~=3~lFy-GfrBNEVQoswDl;$@rbRM85k9n?b`M&f!&{403_%%^iCj&{d8V-4XX=Zi{uUv#6v2c)Mr{I)6 zyxsuUr#(=*uh7!i=17M8`099d|K9Tai$*R0+Jk}py~#ln;0wZB#r;&phtoopO#n_5 zmlnofWf8gF&dspncohACl>Ads`Hw&np3sA-Wb0xp;pqLk-Qo#1Jm(EB@+)a4zNOks zU03wgzC`}<*C8^}HtSX%=BO@2DM|<-d0AB&D(pD#hOB#H` zw0WODA}F9GT|4$pEGaj`t8Rni)R7cj{=8}=wTdm$3SE0U8jXpSZT<&OX~6HXI~^2{ zm9=8q78_T|e(G5fKDsjc-y7q;E6&|QtxCmB5AGGW2lc|5w<3IWz6l~XxWTGSq5!p) zhUE9s^kBDOn=BgQ#_+5_{r)(Wi2%azCA<248|q1e&jz$l0AC!r2ujS!VUNSC-xKr4 zxGG#sp)Ld~cJd2mWvfWC!|h$^41l>EeosL(Wzr#JyJBrCjyaSvTaKT&np+MPg1L7c z_Bk@Xjt1p3^)tFX<=F_LwJY5WgrIlW3jz}xurmbsBgJt=a_~xK3;(2J#jIMkDaEm9 z(LG-mM%OnI>DwK&?F(-WQjnA5{KqM%jH0jZgLP(zS6W!Z&R=Mxy)hLdi8#O%{I6iD(k&qU0Mu%rgeA46o~@u5 zZ%ewn4PNKq>piVQEbLXBx5UdS^acVp*K$)&JZ8pP*Bzgobecb-tNbQ$wY6d#;dkU_ zLnCWw7vXf=L8<3cYQbQCAtOStIN%5ApSJ7-Ws9ofDgnV%RI4d80$S5iE9Q-S%Hak9 zRPC!8#A!$X3mva7wO}Q&h&JY*>zeY`_2=P%I?pP3MLyA17+TT;KP7vfd`Dc zO?X{Ir3&-$Yx{M~wL?`h97!+QL?vhqPr3WT3DaO8U!-g8%5Bbqux05v>Lv_53mbo|$QO@oG?o2kx&NwV9b(vCjOUi!=yGrjeZ z#Rw3BJ+(BXpO8EN2@fhBcybxlQ{-&#d5*4wU3GdwRy;>MJPZzaWcC7b;Q^uT)E#nECfWOOAHBsT=hVM3GN zhtPu@^vejh48nt*FylqLxI|pou8Si5*-^I(hq^`iHt&yU>})t)4}II69n&dGZYZb# z*ipsxdTQn=^7bUDyFpTB2x0p!Zjqr%~8o%T&nd_?TS#PmaUKL3;a6%1Ru(&7Q6o@7N}IXP}1OJ zoEpfvDyp@Qr*xZ&dK-G1?s+luP#M^%J*B>!sMC@H=n4EWB}fg0_0|~Nj+*+BwvAgS zr@F0jRHIa7w0qv851qKQO@tW(Sb41WC^0@`_XqP@_D&-$mYi5m$Fng zHyErRq1GW+7ogE5150-O^UtH(5&g=NqVdaZrb%BrIn#t#eTizpim)BW@th13Xpgh_ zk|Wfh^Cz~#hQ!?dwnOH1rV%sPt@pBX(-7IL{+U#1qC!Ekd;=ox+SdkA3Q8t<3YHX{ zeDL4_OIGNSZWhYqu&g2mH-qV_i4j~Mg;C-VFv=h)QFHgSF5FF(quwNj)6_2}_mlls zLtI3nZX9ft-6B?Ou4ZdG5P61!>!zs<3j++Fz0UgyjXBVoEYu#E3`DNgYTJLcgZgr! zC>X|AepcSb3As9sb)%ZEb~bi-Gfz)Fc@KAs(JNmLmA0@*lreG4#ohebMx&D8pbxNp zV%{Yq=DKwkHamDbMnQ!IM9F#Pdc&!v+cFJOb+`QMzY9yZ*Wo`LR&LX^1^fd*BgbuE zK7i7Q-CG`mQc)k}!DtKx>D6X}{b@9;t+Mx<0TBEPiR_p8_4(Xt2jvs#lf6b++FP=9 zvKv~HnmM$E|CnNqiqUydcK_SCGe0!TXu(b?V(QEJZ_KL|Qh&_QovnvY1z{{?B$)*- zK521&^2*$wh|eg9!hof=CAi5ejjf__=tEj0>1>(oX6`_l>>MpQIeBrH?fz`;wh^pk>)bn3iGAL1gT~1!k_}Q~stUgJ_H>{TDjTY)q29 zIbqabX4&a*b!|1V=l{+UX4&nrsm?@!fO+2M7#+`Oka87qY<_6o4sGo_?R+1JHwXW04N^%dd@k(Z z%q~vFyj{QS!Mv5>$h7{$22Qp9etCxH0v3Z2t?&dxcPqU}dek|@`G`6A)%%=${1FPo z@G64cD9<{-h6{Ev3n${HrE@wH-9=nHZr(WIOzZi}kt*TwJL$d^AEbZxw{lD+!JOLj zrWmQd;G$?3kiVnh6>3-1xC>*>`UM&2vf}<&36PQ9lkU6m9)m05I$L{&YaC z!koI2=_wUHjzz1Z11j!HB< z8jZ=By^lHzu-LXk6fI>$%nheF51kRdNLC?}2~XDqYmBc%$WzB;uE!THzALMUDDk_} zICz@N)Ic0t$u8pZB~(#Ce-rq5Q+lZivlu^7@ARcGQwF+Wu;{ukV_4?nw1aLKg?2Gk z=MWiz*?SW@BD_Srr;w9KMris<4{7t{Qi8P zzl))QKhn^{R$w(VxIda%wyy36c|gM%WSOZt#1J_y@lKJuN(@DTG@{YrA1+z(L_GJw zTo8Kb6z*?X?bN{=N)ex#|J(ei_FeSm*65Hk{;(fygLEF;eL}uq4Kw@G9;thQ6Aw~c z)Hx?f+^sy$dA`Qc9MN@F_Ky-t7us71L*$Ev`<+R8Zv3}fyxImxqX8M3!I*KfT~=JV z9-wT`Eu9+)BH)Kci7ev!wc}u9hFRw`W{Z}5EH=EybW=qEw?RKmt-`5`;E|Gb++QTe zMzFGF|KylAoiMeUwnb125NMt|0=>TP1TU%M7(cADdcnpYU#xN}aL*zSfyb zo>SgREW*jDROO?8s`DX8IQp^*w#2;fNGvq5!PWC$Pm#y|&Po8)GcHnzz2)Oj+}G8_ zEpd{UAc*tZOG-?10ak^E+GQ2Y*eSMHJ9hjhK;7C$gd)wZQGlRN07fS%V5RFS?OoH< z(_mw`F>D7{hv-^4W-rDCb;t3fxcoaH6Y6N@FDt5TGV>>-yw*;yq?)yu0q8#(bf86J zsc3ZMHo2HkzEGMkjdz{h($LEdqe2L|G?n{of8~H%&?VjSOXIK6lD&rYiW$?Y#$#rO z5l6GP@6cUwbUl}=<|IR~e=J2=#AC9>N5{kXT_WN0?gS^FOG>-va^AvZCSIprBQUXZ zDs5qhPo;dI)db-QSE0p}$QBj4ky+ame(3T0n#M~64x8zfe8h>1jQ@mJvww!wt^gKW zr!Ik3&L|RzdllcYF1GwcYtP+TNoIBNVGfS~npgd9$152ZVQ8;WH;|m^fn!O>m$@YH zq5A2O+X4l#?~gnU#n=%!^;LX-twV0UEs0aPfr-id8fyN%din4boI9KMVeaqh4=Ag_ zG`ev-A~E=JbXk>s$KmlpxM15S*4ymyM07o8SlPdJt9BolkY`E-s^o-zqr4Ug2q7x4 zEkl8bG~b{DJo3k8NSWOC8sj@Fe_u>B**)??wQ~NHhVou{*iK>XO$G%yIpvSYIBP7b zPWRd?2x90nrD-|@i%lid)tiBwT!F-zl4qu|mBrXF8b0!o4J=1tJ$2s#4K2ct$7*kR zzlH!U?XZGTN>!&QCF#&ie2~-KAGIp14*Be(%RP@}X7jQRkmA5qc7ow^vQ9?h*St-s zS1oZqqo$Po(6EfmPDV*CGIGYa)+Oh&0I~sZWzpw?s}(~MOA*?3i8`)HDoZA*4Ipg? z3<0MADd{+0)z6eXwb%LYq*Jf3*u=3UUvBvFn|3#tkH}HdBPP`TiuIuf*38%@cwf2& zH0G+pc6R)XLHO28RQ}`!e~&b|HedUZD)pFLulbgDnA4_cXc{^)ja^DzHSaYpc_&*X z7+5~orn@yTYI1@#KDWdy6!KdTc@(TUK7}3==lSV{`JqvNw_l07*yweXZUM}S>v4xm zOL5H#kZkANRrzzpC^re?cBD%DFcz^{QcwbnK zB`2M9ekQQdYi-BJp(6gjrh7m;h`se8+sn*n-{lg53|ygfZfYziTi*O8dT` znuot#!P(acXrV0eGvS;*=gQIgRj=U_v-i<>NBCMa^mmI4Os3YW?5jHiqEL|HQgoM{ z#V1^2WVs#>-QYQ~@}NO91j<*Z)hL$|BTfc+72SHbEmBrH8JT-pxo!6=4Bet@R5>0o zmQ7Q6Xhk5uTP>A_hCm1)aN9i}Ji_-u!qy?KXDOwwtV59rf|2~6Fj>oEK z7E4+Y_+;C)Rt-~MS!=nw<`tWBB@AnmqynGMmqB9KR}M+@r8TE*hQ$nn$eLr z0`G5U1U0=3 z_K^S{xh}JQPgA`n=h|tKRw^)LQGh7cgf?NE*_pzAKR;{!YtUO?l-IKANtm0y>gdmL z)1GaM2)Kzi_6LQzq^VpW0w??1YRr$g16M;#gtk9__-y-aA14fmFr-QN*%KeZ84kg% z&=(YlQ}B|AyoqZj)K3Z0tIYLY# zlNSOcoXbzb!~#*h3i{vK(nA-njp+(KfSq%Nn1)DJ6(^etJ6mx`(}4S>>P(}w;~_UE znE`FMb}5FInunRmi0?W$SDF`WYp~Q_jaM%vxmS%k(~Fi|X?@Qrl0z3?a^1 zu;EtHJIr=Oo4C856M7!xW%#%Al+ zF=sSTX|7d6q>Um2ey$s;3bh&|5l{WIBbX2|mi|)OYOa%K(4k{nyHPVAeKj_V*TvSj z5qUf-fQ$HDly)XlYTi)X62pf6T2e}xd?!NjR=!xx7mBPj+i!oe>~YMRD9W8NbfRSh zKnNA3IRFknv@{4rU=}?Je00S}F{B^HiT-@j>*SzorYta8q<`&;0h{H6%>UM@<L$axysih9h86Fik zY#y*JRYs-Rx7@E9d}jSXZJ0?E$WC^OZ$rs^W(|0zoF-Z&b)l@AN*b^A!a16ASlD%M z+NrxyGkX^-ZQ?w>PiF9d}K@oBW^n`k13sMKzXnq8KDHAQhOtHH# zALQ0A3tdiiA0#fesS`b#SfM|E%N>Z8nLcleWzob;R=QO-3{BIMNB6j(Y5Gs&0!8F# zqAdWEzm^c)pN@3TiIYJ~m^AxTCYq*yKUAsu3r*7lyVw4!{J&xUZ^He@rG~}=;i@L7 t8AwU2C literal 0 HcmV?d00001 diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/lane_change-lon_accel_sampling.png b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/lane_change-lon_accel_sampling.png new file mode 100644 index 0000000000000000000000000000000000000000..3f4c08b6a244c1183094234627724e8629745b0c GIT binary patch literal 249998 zcma&Oc{rAB_dVVq-APD7k|{~Z973iLGAC1}3=u*iLWE>a$UKE4At9MbrX(RriV%uS zA({EDyZ7@x&-?xF=WskvhjQK5b)NfNd+)W@zJfK?&+H*%AltHK%N}JVdF?G*cFJto zvbBk@4L>n|O6iIJZNDa`tV19Wz6@y$ZrQ@JMOj`}$31zn`iA@Y(ds{&lQ&WYr*Es0 z5DpMncbT!heyC3)FWZ>TR`Pzh<2_SBSL!v7%k85Ru9KH@bv?V&?*^UTPWD=pUyw_% zISQjz@6cf)zIU1k6K1N>R<82cdg|NAqetb4c4 z{y)D+ay3To|M$fjVuBSjJ8gbXq&1rt7HqO8Q+vl+8AP#fa1#RSmu{y~M>Ja*eBY@Q zbzh17+iV$U$kGWKvLS9SKg#7JQSB=1)KTm$MPam2d?`xo=7sbWTh@$ZsiG)XuSMVU z${(SaFX%WWOSM$m5_p6MZVM9ZvAk5G`?y^KRm!O!b z#T8S;!%aix^)7&^NuP(derrqqF24so6RZj8Rwahv7VOHeD5;8t8TRn9D^uUy63i`LGfF=+60fW-e8pUN%dj)WP)RcjVc8YcASU z8E{&8g@p<5irbYKN+sBqFuW;gG`|?8z!r%QC6F|QA9OR2=G!j!L_NE{yEmTvXsaLx zm3f9rmUeEpSAuzAyj=R=m2Wh^xAuIi9?gtp-&OQTCF{M7a8*uZqXQ}rrjkS`0069lPN=d;=K+JTlbCA?@c31Mj#7NMk>jtYuc0;W@#TFC*4E3eIR_u z>64AH`3Zb%+82EuEV`uuEs1QF_K|_zEjQ~&yyn^dJ#Rh(k5j!@#vLmuNv@XEpWuj5 z$Z%KfvN~oE+ex@fr?5BW_Vef7>nj7B8;hq;pEfWsAocfcRcuN5u^#yL zc59(PC8q^B*&*?Wy;t|#wKJ&-#JXm84b9sKhmf9N2v^B^b%dpU$S6gfE?EBhbl>uy zFOIc~Up@Ei*)!Y}E|k=!`6i>2)6ItCtYQ2<5e~1+vs^K6W)@Em))$PCKUAzCu~*GF z&lMAYEsr6uV2RO0>#^h5$w!p`jFR5yi2<7h{xtt-VPMvC(-dy{bf8jjWd3AM)itKLN#3WlB8dE_c!!fvD~aN>g+6UJ|kzKiVais<)TZ=GO1liz-{zx}hLF>L%g0!a+JM}XQ3l4#krUO&|Aa6rS)8>nt5iCy+vG6%3 zkZy}r%p77;R?1zXeYLNL#Nz)t1S|k)#xwrhMrC>r?PedAF{*huPPI%vw zU~V~%rrD0LPx0KE1wEO^l%sxo+;nuDi8J+1NJ?s@?;3XrmY1U{+8{{`EBG2YgBp1ha?BO&CKPS?HW2BWoK6K7Cqxf0i#r@`m7%BUbN{ zPtuD$P2v%~_8?0x#{cD;3%F9t*HX{+Pc zdbM)9GjhEs2XoKH@g5+*)7NJd6w`N`JB000YMQG;>19Ea0=lmkRr7Rn1MUPdIS=N4 zXFJTn-doz5pTir+O+^^_{yn2kpXXyo2USEf9j{S*Vq&6wWK9NJaKMsB;Ni$1{Gxno zTpJSFD|Ts!Z} zufyLgdL*@BL~KVYmziL~uVBuQHJ8{C`q3x*NDfoPRXjK<*ETfAR#W}J)j%+!A zpQN~#{6L~>8qM(kE2%%e^TgzwBva^SHRU`1$kS!ADc$PkFwmA5xkoPosTE;xuqXk))bu+1SIy!r2WTkl5L8adj(zi>2)}1B2NAJGwuwk3}qK9nK3?M${qhY3oPsejW+hWw{l}hOq$-SN!XeaI@jjD=XuE^El;yLh# z-t@#nai=rI?8=%`g~ri=5tT6!DbgOktryZYeD@dtge zEtV>}$7esE=#jZNI=rJOqw{gwB@2s+<6mRcV|Oo?i;+6Bl5jkh?)c2IgY81Jn_?7u zbPLH)lwDch$B=h{^+TGR!h(W+oc@-FqK_Qd9(|~;%5iN=komogZ?j_BYUxZSk2cLo zSu{B&TzGOwdad|YEBmKqSg67kuQ@w&adS6^AKclZk=gm+>T5qL@f&u1-mR+Z{3NEU!o|LJnMN$^>A?w%Gs`R{p(nT5UfL0ew*+H1}NCDhc^IBDd*9k;xx zN?~dAmXtBB(?*y&_;&rp=$40_Hf5^8>{}m_{CaF2u6Q^kqjgl=X;4N@ZO_WftSK{o z!twZ-+}4H;=`)-(f(fclNo?cW-gp-EMh_6Y-q&oLBz0f;eOXL<$Q|{I(~WCGOmo7E zPY%D0JDcpadsdTTC|nq z$H@M{*B&0!xeYPC+c-nauU(rjzxKmL-1y?fiw+JBii(PCkv0wv(_>>}Gc)aNZPm-) zlhVg!@?`Cgkcf?m73#kob-vPHaX!226tdLz?c2{pFe&WGot&IR#-gF2dFekszx?y( z&ph3Us3T{2Xz}fD{^iS;O4kY0G%LUADG!p9#&y zYioUdeHj@Ud3ij%L$aP%92}%>t~_rYMbUNR#*Oao?(*_-_Xv|LZRF}JU#rR=KD2yw zd)L&|RDOQ`i4!Nf9;uzS-*&&xU2=NCBVU*Mci+>ePh(?aace7HHJ7^{SzWrM9?xGl zt_<03iO?uOYu`f^nH z{kO)@woCI!pU9$Dv$PHH^v1?hPGW=90g2z8%MA?;D=I43m5aViAs2K{EGQkgQzt|n zoM&3=?c(Cn7_uLa9VVb0C6}&w=1eoLGdjO4C?xcwEy-Fi0f3`;=8UU&O8t<`-7Atz zGn13{wzfaV$9*RyESkc0?c-oMB|;l|b7?3rTRlbm+V`;L;aQLB`5*0RC$D{P2;Ns> zm|tf`&&b$UbF-2&L?ug*o7-+~q-DpB9epM@6|n8R#ud*kTcWUqSjC!}8tl>i`}ddU zf6&p;uyky1IT%)$o}P{imcDp#-PN^s>JL)Un>Q+gsRHWRb%US?(wu(XrC#lA9T_}Iq3UsWUrEXd#c6uFBF3OZwTH#Rn| z{dkw4`Uo-k?b|mXGpbSLs5S4}P8%AMx~c1>rKO@LPL%ggV94mzVdBItORih$LCJCC0?Wj9#y7Pm$>9@1I)m5E2qPd-m-7{QPY4quN@Z zAMa8~{V#s4y5Yw%s7OU}apm`TLPEm6qw4a~Y8+io) zKrX$is;VXWXv9I$cb0;)*|J(vr$)XmaC33M$23cOKP~O_*Xl}aR%PXvAM^Y7@9)34*xwq* z$H&c$GAUhito%nRo;m4+ovy8|EjzWWKWgZLnw2L#6UH@O<@G~Aip{0ri1yS|+yprk zS+m2ZOp`uar2A|m9VL^bJBmv){-D0@9lL4!T)NakX^+n> zdx<3BJWnAJ8w0)7)Y=}YB_$>$`E1OmX{3n92yle3$zMs`)zQyo?_CFWFlhZXzT@t+Vww(00cwhSc)I^751PoWd+b-L0KkrXB%OZEBl=RXK| zKoNp!%%uW|cgpk6+r$&CHo}Q*-(^^Ck$2@^C}ooN_Im$N8O3&3Ar1h3LR?QQN}XAU zL+OCWL_QY%(4j-Y@~>tVn}@H4HVO&~&Jh>mQ{iwZU(ML~xK@siZf*$>?Zp>|N}zu0 zn>Xf#pLQ~PIgNF&8pN_b#6G=x^(r};v38)=uIDLY@6Vq{ne?CA?Bz@U(@1A(-&Z!< z%2)e)bzLeAnOikga#>}u^qu-r$}DmH?Zg5H zbubVK8=Q4E?kmc0VAu6ZTa)T zYFc|^{(E<>9`i|O%buskZEbDdwbI<&6RYSelTThlf&g$br=Gla$;s&%G7WySw9onM z<;yw!4m0E9y=7M|#2BY%W|$8g=qJ|qEk}#NSE|XOifH2 zWMJ^C7iWsVT3N6DnZo&%1Qu)OsNxhNV<1P+9XGrm9bHd9?=FeVR(XBubE%`LscBmC zaB!n}^ihqcIXTOLK1+evt?aIZWP&P%(SLceAUoQ>0K!QVBEw=qTa_(oSN z<}~>7pkq~McXw9LMDCL(x&&0K5jaUpv0s(W+?L*-=(1=HGh zmiBjPNE;g&tpNkLW8TQH{CX!bvo=KO^SZq~P2>uLg=(x-)f^vT+rdzh(Sm4{v{hmS z+Bv^Hs@s2fF7~^jAwelY`6xS^_`K^Y3xF3yYq0z`T&HUIu7qFRprg;~7qui2eCI!S zuqFRw$~)uA>*EV6L=^DZT*q(VD(<*gWo6~m^-AP7=G2>idV5Sf^Yij1f$ZZrvR+aH z<6YSUK)2Xf+U%}iiql26^N}3qiT(U^#RPw#B-O3j?KL>N_{BD~X>J2I5lLJzKXC+C z7iWC_^je={YEL|2cj;~XEOAYMdCXqFWWBvNBD{ZR5;2`wTIwV%t=5yU!j+X3I#aJm zf$O-fxcm3rtG{BI9R_OFfzX>P1)GKj2II5tUvW0~929vQFEE^wovNatK^a(&4bRKX zJ(t@}Y%kPA`)McwySlngr)yeU|5#a=I7HFh?>4aBahkGmc$Ut@eF!oC=Jo4%L8}mx zf;jfeNJ@@1%a_#E-|_h@w*oQD_&3y(I60lf7?q4pc`g0A)_$s|vvYPVGlG_mE;QrQ$B!@EX1)^F z$BbVrMLntQ&q%a}146yO!WBSIDZS=&{rYuTSznWag52EI-ga+YO-&~>J+Uz{xZTsh z_){Lg$2v3HrB){q`87}1XElv$2Q~pl05sGPX=@`#0nQgn9r{b`^gKN!7z-3LXMYXV zYe=uVuv6#c=ckCf+FrhVOyq5DK@9_eq^P*~IBo0U2uZe9XJk+VgWgk%edn~bwKX+6 zdV4PmGw|VLA_j7vJ#(7<)|jiC4`vkzc5}W>)XLyaJ6!^$4m!k3`_$;>Ua_;w#j~QgjZqo3 zh&c7PB~|KNpDb=iJxj}HLTvi}{Qh0Fxv@I&F<-)Gql$%qD60n0S5{P9pZQvi6a4)7 za}UG)y&2E{-f7o=vEu1@rI$y7xGf6xf%bQqr8hE}*KJUl zA5~8dYBWcUXjtw%ig31mmz<-?`Swz=V&;JZ2Tr<8_Z=_odu3c|5&A=457O2J#G*I1mP~LRhi1*hH zobfIo`&_pA!tdW=Dess!eg$6p{uW&s+7ITNzqJ6QZf>GK#SmU7E|u8lULTI&x$q(n zs~M^E{Kbnqa_K0N4oO_M|M?*YnH;Q2UxllkuI|U5-MKSm!xYgi>;yRtjR?+=G%%3Z z-IES|Wxs#BRGZ8!u4ZZA z7mM4a=2zEI$Y3$8OiWT0Gf#T_w(;@VB*MudiP-39Au+K}_Kk0b%H7{HUEz@S-HsMlnG}V3EOe3@gEOUWr?Z(>jJdy5^yfODKMWWQc*Sxrw z$$iilsn0N9SBnODMqENddUaBW@H?!~U6P5MG_&(@zeCT&!j&smB(6_7RrYrT3^`2y z{5j`Q4XBuY`SRA6DaAGJwGU`NZvLv~KiA zxDxU4h+XGv*A7_Vh?$l;7^CR`JLuhf$nD|7hx|<(YKafEbAC=t;8u#~=H|k}!bYYV zeC{@yd)E%kEK0A8WuhEJrtY+P{^-$ny4t121R-n0YqMxz=);?k z+w=1BvQs^5fp4Y#*S}yDP|Q3+v?4>Mrkb2Pch1nzR+wRRWrdWK6tv3scPW+5qi+m~ zF99qHdJa+qZvG0CcERQ?EDZT>rG*f{!ucX6XB;h%ZmugZgj+X{UeqC(T^W?Q8Go|a zRde(vIJ3kL&dx@MQBkoHd4{R(&ATMg_HmbupL(^nj*ikk8*9%mcl~0in^<5VzjHoU z_qhJEm*$1!l$4c5Pr)d+Un&N&-^8B^y2d9bCQyI-tPL{{W#Ook`m@r8?xCc-z!U2^ zQ;iTV2ZB2}X{KwUf+~c5feLtKq9D*RLfjjS>+v*%dF8>_UJ zy*x@OwZtMJ;fYHOIV}NLv9e3M4=YFY+Na`4P~<}`36Sfw(aG!t?V)3_nznl3%s(oa z(P+o!KI(?FQGhs3Aeu0w-~Rr7l`LZWHL&`1@t68detH^`tqX~or*>J-_FY)Jm8Y+7 zgOh|F2QeHmr*ggWl(cl3!1dX03K7lqhfkDiww^z0GQ68slAxHuiCoeB;RDM=F^;f= zL}h;d@l&S`2^54CuB~~YCB%)Rfi6XB@r70VAo(3s0Wzu4>^XUP_AOCI&<{!6Tyb%8 zbHfRTF2iS3_6w!SfOG3{2p<8BWV?40&k?d1%89lFp`#~GblV7jwtu0-9+i|7O0W4_ zvYa=8r)WU(_PWcSsOR6me-BXculognMmD$~7ngaIBG3YL zJCG2S9O_>h1^>ERO*mAdo`2B4+J87utj_})1IbXK;DhbL>%U(pQmx;{M@B}b>u`lD z4x{!oV^eI`THSqsfnLGRZUX%_>nD^@7muA)QE{jke*}7>OU4&@l;U824*7U*%-pVkF=mHP3bZ9Sl{_Sx} zR?8o76pZPo=JfoR}8wjvNCsc zUG#}iyry1!kpcjqKOGvn`1L@5oNuva;T{bJNhV6kd`M_$Z>|DJ`d#B1&Fij360^hn z_cm@Wu2-{QtA?CFe#^M1C2#gls0<9^XCJ~Rg{$t3e6kQw4uuz=;}Im;X-cD z#1I1nI-Dg`=4f$?d+pu6-mpg9FP9FT7h4Ra0IP*|$kE5ARy&80p1#9ISSpQ=hKzN4 zqJXZJmH?K^Ni46^W>EahpyON`&3`j6;hUj9kz?If#IxH^Q(u4Stx&t=rAs2h!pV|1 zvp_jCjOS$1kkxvd_B-L_B&{a9q;g%VUnlCEIwHOtI)sUoq8G2Sa=izGa8 zL~*yDj;>xWls^zrT-h%rF8*_V8Du*Wr!H@OX8V7=0J-2cj~_n{MDnPXg1WqIYech! zND?S6Et0pxv#*OJFTZ~XMEdC>t{Nnlj+GdTVprz0=-?_y^- zTKUeRFkU-{=h(3X0gI;e(}6GSd%roCPgl*qL(dpA7bK?`Sq(r05O;N<+BzV47!@%( z3p@p`JG#WLn%SwZt4n%R@V296@Lnc*a+L+ z(g_Z`#Mee%6fU;n#n}W20iCO+#-BHTyRs1ud6yBjhD4 z6ChALg_oZEv%N@)`py8mzOt*!%gfNyGpMCg!h0PLSb!2FJq;>s!DBX6!s4yH$YG}~ zJFj&{m)1wI8!Jaa))hYEmD@GW78%rQf5*c{m;tQ6#=C%$b2JKLFR+)Hoh1IUS~MU8 zJ4Kf)S;aC=a2kXOq_r;+Nr3=56DkGpDoy4B&}goF7;=I{_4~k2dU=y3difT4wymre za&%rPjX9TZ^W8#bGAnZdI-p1rD_dv=A)NBNt}4ri^V3Yo#n`#*E>=rW=yGSeY=lLU zjx$A^Huu*ybO%NU7=A)L%_i`{V-QJXhTw{WYkOK|fv z3d&J9vplpA%>bU}g)%;8-sHDk!nxOH_)WV~ppx~iKS(hXA@_|%WP6QYUoa)HV|c?| zz$ocX)z~q4y|V4nK83>E+*V6L6za3?{M*R_UJcK_%z`b1WZU7xhYyO_yQAS@xnsVn z9Cf>y)aykp#ly{z5HeLhkBm+msvUz19+66(s7}G5TMg9Qgzo_yIh#E@_4wo@4>vae zlp&lnf|j4HCg7PCi~zVPyAUa%CNrZ(sfNQL0En+obhwxVpWR&j0|-2I^r$r$6qKaZ zXye~^bzL0z<5A65{rf%Af4_s9me$@Lr+$ahM)OYF5=miQDiZpqSGxq7NO$fW`qZfU z%_wL_f7VGXIWdueEP&nud{B-K(8*pQk45niMPT6#)VK9R&wA~dBAO=_UOa!!V_L&_ zlIxy%AtzaYIW)!ETImxfTu0x;fb*}Z*=RYM<|4*8+#FFm+jJ1MhN+Iu{j@a7z0B47 zNwzN1{p)JkL$neZZ4J5=CQ#7BP1yEz-Lp-%3(hLS*e(zhC z`Nnc6-$^-2UP~uOXUK`3SiHe2U*f#`h3eI=8zcV7spjlEx>p{Md;>qtN^8 z%DLU<43YJ_x27D~uOR{M0JO?Yz}Jk|4+*=EdB>1|S2s6iHaAfJm_O|}O}Go}n!0ZB z^+CtDi?~uD4(1&@|GEddx%ET*&n2t++fzE@_XSOkk&~D+ZQYtrm2q744XhPr{48Y4 z^_0>)TwKJ820U{5cJP>onIaB`D+bnYUF6heKpvz!J-h$CD-vMg0P;e&?TMr|tk>a{ ziuG85JNLIdj{Q{eDdchE&gde}5F*)7el1%&r|L(lC%SCXgC$?4HfAGy`Z_xJB_+f5 zY@Zcoq_Ftlba(#f0r!_%^7mahbgsE6WMP((n*8FM`^QiPiw<}Rk#&JV^#WB5nj=x% zmDuIfxX*q=@e*g^F`nY~_1LjvH_*S^+Sv`MNqMg=flG2qyHkJB3%dY613UHX>UvoZ z#Lj7ggeVqW9x2ufi`NsCfiAtb4xonDIY` zFuFpja6ZA`Vj}%l3Gr?rr$tbc&vU;_bR=Y4{d1UkQ2)a z#HO5X+k9OKLBVa^!P)y{N}a`1ex(7Ya=TYPSwui3FcwMLLt*r~fT(o)Lgo{>WPkg; ztw>V3eTJHYcSG*9Vg5%mexnMPW3-`l>OnVtc~nzfnJvI^)#veJ0p9X%oxeOXPpZ{D ziYIvb;e$?N;93n33Q^y^c%I-_=n-qVFpR%iCiFrR8V zy_a?GHeN#|PpYl1;)kj#!U}zTea-k$f^Su$%_ToY7xJ*hQk#3Uv*|w5hNYx z>ORP`X_=TvUHvBSUk7@w9EGtc`m5^2uVHMQYimnOr-c^~T?+~zSlNAkewiWs5@^{ZC`a`4wLE+~Y4>tO_^}A14=)V! zfePX&Pr)HV2G9NE$095&T=nbKZgjGc%WTjjHwFX*q-(ymEqPPq1?l|VJN1a>?b`+0 zt#2vN_`cHTlcjn!#Q))xe;o*YcI7#DNz`Z@1AomF?|Xa47gsy4Y0(TxD^zX2T_wZ9 zFD_2Tca#I}O_%G}Nw;k^h;6%cO-1Dm;>?&=&&0&Uz~I1$debNHM3B*LN-;~;I$eZ3 zHA24RCH3$dq+vA7V0n?J>V-m&k1Tlb8CTrS8mb>LYeae5X(I`Sb71C&^Ai>Vm|Uqe zN2qo{r4DAam}p*8)Q@Heu`7$C$9?^pFgXHlf<{4$=0?!gx1Fe=QC0iPsviDG$gb}Q zxxamEVNIlSVgW}HC0$MqY-F>u*|Zo=emT>^E=T#3llEs{$QL z54Hvx5gu9(&fd|@O%b_bXlu(Q@AG>7^|~fk3}P%u;Zm4!m3v`%`7)FzkLs^OPLNU1 z*Y9Lz0NyRkNq~`B_5Db#-->m4j8X{G4JV zBWLGY`9LNH?>qYa`*+f9zV(5W)|W0l%F3!c))HQN&-g)HogtxIggW@wn+37}Hrh}K z+6bf@b0eTTQ2~|rJFp)V1|;-X((Ntm5N17y>`>XyOV~Cd7a+GcSbp%xNI^z%p_9hz z2Dr{>$aeVGrKYArLAhG!?BwJG5;%kN`{-y^cD7x~=QB(<*dc16YX^ZO|Ku_!4Fpzz z*k+v1avTt2Y2Ev=GrBW+a)$7xk7n+u{R*=H6=DvAXsoDs zr`tAMo{h*bQXKhRq%g!~iJr&R)fEnfw2j|Kb*7`NZa@Gh9{#D49#|9v(!vT~ym*nG z&Z=*U(E8nLoksNBF-06szJK)KgCfRl2R_9&_nH^Jbj|IyMT)<6?HaL4?bb6zlKFHQ zDiG+MaCyD4K~Q1l9%78KR^>2bfW))2zwys zjWCt3Zu;9y}}j!v&P59milMB7hyONK5-(T z{^H0%)C>)K%_f~xSG{WL>STrYlLas^Fu)G*v8N|cX{V~#+J~yJgOauUwG#^~GAvt; z3NGfi7A42VLJ*I-az;^+;UMvAR;OuZky+CH7uY%YWx(KCMdz!UXXhijT92Ip>bFC z7xAomNo~}W56lFT+e^YVLm!ccm)CoQs4Ca@^tm0N$P-Y=@%G8)pIw~{yB z8zO$zaJZ;RnNvCnMg%H)NN+c{MPy}sE*BRUc!#O$o>o?)h+FBU!R;|Ba1`Xh6 zS#K$LUQdsbf`UonI*+vUCaB;z_FWrlONx;^Tidj#NXYrA2q5Tq4T?q<{?bN008I!Q z{H$W6u3uTy(4;=R__}D)MI2;U*ZcQ#v(3z+qN38jJ5Gbsva_|7oAU>*4$i>U!GGoR za|q_O8!Hp&v^}bcH;do_I2}EDCP#-!%t;1r0zEw>=dpzqpxVINcTu1>SbT^hpq~fN zqC1O*(g)`S-?3w8k3pC&|L)T0wp{?pUOP19$r-~DJq~5L+I`mi#*K2$5M)C;d;2_) z!F+t^d*R|nP_9CK#O1ad#KLdWnR#aC&Yh64!2Wr7c-&HS&+{HMXe2fg;Ze0cBrQ&1}3n5*T zAj&cgw?}Bo;PuLjydp_$AUB~9Ksd_DfxJgSPM&w6^qp-9uTdESFyl`OtO8S03IX*f zlt61ky+VKA`eWW0JRf2Qyc#qKSiwubdT=v!i!t7X2Lo0MMlmNdR0-^A2lz`GpYVO zv*@!jo?W}rUGUuSiigJv#IIN$17c-~f*JNFh|!QpP&&c*oRH9>a2nKLi6Ok3@>-MQ zEkC*E6Ah$-QrZW9zY-(|g*M{fGzPHF-5Ag;s+$7+ktE*k;scwFA=7M6J+E z8kOCP>t7YW#|LvZxu#FX24hB^Q7 zW4QehmAQHayquiw=z`IVf`TC`TyVIQ!x0FJ33U0Xu`zvUsXAIZzvV;(QhmVxW`O1hK`EgOfK>kuMe8MNYiOWE7Zp5_5ZB?SXb?Dy zKzweaMf6h|_v6`M>Fu^fmw&zTri~3JLpUZBIMeS%r59VAP|!jfh&AoFA9>`^Uu!Y? zb%?=mhQaWKL*HU)Sm84M3zy~p+QKjN6(+*}<vPVJAdH40&Rq z+rBjLYHYbJen}+hh%&q#dlew>dq^^6ceT(%0mELPJUdW;`ntN>IJ-+Np5M2WrPW!I zshRtakq0n4j@Ouho}NEJRq0&Y+qbYsP&Ho>IXJhKL{`QuplcjQ&!H6V#^8*{y1A%M zfEwcB;ykpw8567S>tgoC(GkrW7NzQ7q!LJf(0t$4Z)RyH#KrZzf6qpcgKYrZw45C$ zO(HB!b9XV`#AXobz#5XFn0Zw^#aHI#)OCpzb-4e%Zv97_8 zTWc$vQ)oBf$(vY!-RZ~ZXu5ek3jw*QgDvvRq>~t$?{Uc#4T~?K4*lS#-oBVFu`pl-o>(&SB}_w6rL*QzN85JqOyq7Q3SaLktK)I1L65 ze_xl+^Q|)z^Zb*?LI5RH@s@>rE1icG3zdv^;J^$>Lr9JVJ#n$IbNpLnsf>8zdM0An zl|k(D#Db)-H-3Akekh**BD@hA2n7X&9X=0z1>Jy!5IgX3RkA!4koEX4`oRNp<%)5k zImA7$@vOMH`FT{mLm^Ot(DqRT9%cwZqy&;^m%Fz zd=MW#|GDh)-l^?`IQM?0mR+ycMyIYBNYaKLX`YhstsL(2C zMX}#*;z-*uAv~~UiLoS~N+ML!RCPD4POMdp)&UD2b$uV0J5Ak(0({n*eTddx$SYU( z!-{tRb;Km$^5u-iL;GLHn*aDX$@x*c-o}?$DhrZ%S{s|L{L} zC`~Eqc7gyyxTb5bzSIegZY3rP-JO+(La7NPI3MrrK_clgnpe~h4GINESxHJVOoe8M zNlJRbrqEKf#=JSpj818U>0%!bL8VE?iM3{WOw#c5?W@ki_IZBH9La&M&k8^7yDjaXLT4-M}iG`-?}K0$a#f?v5}V_yA**sowErCD6ig&p*ZU2K#2}+=mX4 zpeh;tTd-~KD_!S{!t@7cw|^&l!xQ#2OyF^8$12Od`ZdB1qZ}P`mMHd%ERtbzr%0a$ zTA$Tzywjd?a_g-> z%MEjDBuiaGmOsAS3hzJcblQRkM90DRX8dCd9(lW;U-rHn>yl(D@F;e(^X1q2V#Yik zGWu`6dqj49u6v~5yp6dv?SlOOoIs|(C(tRBGcMPie;du|eBGqU>VVzUY`aw-EMXp1 z<~1hRI)eYsGm8oIN)vi@3VKfaHo9J=Hype&r>g&S=d8mZ56KdT#Od@4bzM6bRH$z2 z^IR&_fACS(IN*Kr?mXFd{$0^NereDFl4FdbM?ZJ%A7T@XJ0ozgs@{t$>IaE;6V&pa ziRgpPKiPYP{rlcFJvUo}ZRLovUu0}}uLUMfNdw*;1(t7DZnJu)z@Jsp5;e)hhsyjHyHZz2onVQV3zqJ$M zUR*Wid>z-nTP&1~=ARP(saj3W7?rG1@h=wjCVD|KdJCr?brQSiSPy#I9ZZjXJlaU_ zUrnKQwM~JF#H(>2vbpZwr4F9k3hwk**?a;Sep0t9%IM@mYh4|`N3*;?UE}J_=%ixXtE{W8~gNv&I zxnhkNs37R1PTfj7olZr{8Il20$i8jDcNuRv>eE%5m}+X`7_k;-SQPPG$k$cXVxf8& z$rKS7$j;w%?|Ex>(AhLEX6L#T&*~dbPCJusyX$MeCp|elA%)cqf}q2mCfWcG3@{ar zf$1MWX_xGP$wd~D3!$F&H^>Q32y^*KRa9c+qI3mjAQ*y^=$;NaiM^c~a(BP=h(FM4 zJW}RWGhv8+eMm#aY$(v?Zc1?QsM|h{1J@LO9{+E>*KlID74ba;YYQ@QmYY5kyxvNG zmQf2aRd_5sbDhvtj)Hd|B@_&b-aZaNjKFDfyS z@_!dKI{o)O2D5t337N6m_t5e69PLr8{0tN4W1(2aLuc8C7gvuEr-}xypZO<-g6!yU z)csgCRDOM4?OBiKJa)%%uRdP7AZJ(`)%Hf^= zzG-2$^ftUJEJ3wVBNf^NA*-E6=M1)IE&-``>VC3UWlhe9wiGOErZF8aLjKM3Qu zbWn!)hJ}XBV~^#V>4z0^VQ}DSMY)=0nsSURSe~ui<{-<~MM0&)f21px8so832KcDW z!}o4`CQv6Tu_JkHo{t^X2cF7 zo5xvZt_a3iF`9NhQ~hVrsW!X*v+6z3JcBAxG#JIH8*Il^3TRtYZeVT`+P*Wd4erDw z+R2kA^^%JBpKo=y;qxlfv;JIPN{EdwFqUMh{roZVpRBpGdgnhYdW&6|EMS|usw@?} zdbSs2pT}4o$a+a4`?!E;yN2sGn_amo&j2m>A-BFl+wLbA&jZ{i2YrN={nvCe>z*t? zYDHC2%;^^M&-Gadihq~hClI-|`vg-2>Q;>Nhc@C3rWZudV+i@?@6J>yFZa5s1(BzK(8 z(w-&LgA@3ms6!vDw(#ihkR2Q-Dx|jNjRW-&e)ld$#g49`}6SfYm<#pV9@+A1(bBQ{!Pu;?cl zDKKb@A$<)g=!lr8+5}~Fh@M_Ew;R?I8Zv<{eRt*3Z(WWP0O_H1;R2EBAnNYw*+Ll0X4|V&KT`egX(9OieIZJN z>EJ{HDLPY041Qn+r|;v(?~AKYaM+cJ(Q${`I!u5lKf?xxN;u|bX` zNTWHlH3vI8@bM7JFf!)fb_qluY+Dz@(uEH&gf*JOU}7(#cmDjTwO{q{$CjEDoG}n; zisxyyZ2aGcnl#4BZ7LMmhy1wkS`lmm#jtY+MSM;Z?ivJ3v8x8w3mb_{(GJ=U*cS(qHHD1eeV9s{a z@q!6cV#lz<)vL4k{p5s%-tO-G;fi3Ozf55vC#I(M6QjA!ybyho)6*0r+Z;+g-QC?mpn@Cka;Fz#Y-wi#TC{EHRwzbV2~YvOt=pEZXAS} z#hw0jP)!a9U4pe0tpc(Nc+S7pG%)(`^#5hH+TOegA-*&Q?_+^wmbqpshwa~6|K>>Y z_w7fUyW}V}D^+uJ!1-V@r+WR*7l1H~$K(NWVTDmqQA9T_Z^mRIHI zdK1G9gO^E)dUmIcI?fkv9D{($Q5cI7aGN$tYI~%e1BwL}NF00?Du}0GC?FHywx2(D zf%5>*jmW~J9rmAwY!3wmc*4)4&Um>6EFN$X>XT|a{xgL__?GDRH|uR~`+5P{C|I6? zNwN%NVMT>FY)XljfFCB+9t+^(kO(jnRDszMCo!JZIV>6mL^^RRHo{MIb72dBE@+b0 z-b@cuY?6eV16;kFG_bS40T13ME9(dq0agqp_KdD^oW_i9+yBh_9-=s-rx({ej28u% z6qFVg!ft;IY0ugk^r1oQ@T?f5ErhGjWWSq>&SHY}MtlCbtb|C#>fOpLx7iPesRes@~lE;6QAnB5z_YEWABIszQnN0Vs ztPTfHzcUZqLTi@r!_`YHv-53=#NoDuPS4cU4VK$fas*bFnU`DWSZ{C8J?B)4dJcLP zRtlmTnfORKs$qT&2iWJAKeKA0aPV*$pri&IFuXui`BKXx(T5eo%nUx77i!X+KX zL(Zw}H@R?OH3^~;{OM8bd*z^;z^yVmfbS0feJofe9KlKbG6|LzuwD z=+Q2}dueHoB1!OoPfe6ihGdMHzH+cjB-PmWe@{mxS4t_L2=a+}|(`~fG1uLq;mG`u@Jxd=Z`Lv*V`mw^ko+-UNUAWSjfX2 zlEFf_RGe@ThV>}uq3{x5)E?FX;=l(h>(GA&xv|h%_gPQh`90Ay1NqGq&fmL-B!t!A z2*tTsU!U>ufn5Wmi&r}y$O;Gugk)ecsIs3Tg11%h_sGwSg&CauQeKND_W#*dD!H+P z6dThb4B@w_)VhS#CVIQ9XAE!cF3;x-xi>T?=`;BW)Q-8i`SeF#*4xv2pFDYGt+2Ah zrPf7W4|(e;YzWZt5S31?$ZmjLN=!pq3L?McKEc3Ft@pY|T&seXj**cOwh8YDa2^SI z@&rz5Gk(M!AON2B1&;%F#()0&41+z46OHDqx1AU<%U}?DB0-fR(EsNPv`y#F6J<=1 zq+P5yzYe99*lUaCyL$rbA#h{pzUw(~4p3WCT1v?*<<$_hx22_ps`J$*6Gr%n{(*#H zvBXELyYDi!D*QL1H6#3cfpg%>X%vVb+2j8u+pKy)LW8DpES(=Y0A_v62FX#~t}K!! zqiNFQ3E5g8rr$d_AMx-U+|GHDLaiE_oxTHdKULvU=FAq@*da0|9PSR1{)Ev`rLa z;vL_QO+RaFz3>-_z3TfS!&9P{!jPw#uouv6un(l?ux zZVs`0PESZeV4ow@erF+#lLmnhHp5%xItTl_w4IkCe~a(6loUl6 zIAHz5aClGBpdH~rpS_nrMG`(-1A~=@AEhkreuNv#_4MhIdV6EaQ+uj+h<2ndRNr^90=i?@bxH+4lAcGMcDUo^P- zzruAH;yB$M6t;Tt(wh(YDt7mj(eX-9ERw>WYqrZmkXvxf+PbIrgD6V4cKdx8^uWow zc9$2HmnV^NIMVhEaqZpp6DC>5qer=D_CN1EdGZ7dH+q?*EIMRgACVaesp$G`vTRQL*y(gkYf%b`@DGO#=?}{c z@Y#k+HnBIP;hrOAcW{8#QoIe+sO--}Ljgm|{ocUeKMf8FT@71z+A@iQU-7Q{ppMwR z=nEIFBB=o$Ip_)}H{sCw2V%Sda>jX~ZVEgS`rg*vkY?jCi`$1ggtM>BcKLw86rT=r z2pIigOb3DVjA?te+}~IibR}CXH8(y!9-i9|wE@e75#IX2Kae1CU?ejh#yyDIg(eFu z&pNqdlm_a2JmJ^buKC|jyU`+tIhBhflr7dKyJ(bBw_-l(#6&_-h72rz=|i~cQNUx7 z2q1qAMsrUU>TrGB$L?)>?2kW86%=ry==?gj%j@BWnw9SI;nJku5?ztUle@G{=2`3t z3QqG^9C{j6yEI+Q!XXeE#$|54LCJF%#H^zCKS$8#cS;eTsjLwcunUme;6vqhzPUlo z|2LEd;!$lJsy@5v`P&7vJ7uGDU7!Zqnm7`nTs^XWwPR>3t}^Jte!%n@2K9lWE2#R_ z5ra9&wy?Y#Q&z~Y=njnrlSXKezk znj}I9zb(s-bwXQ&;HF#`cXxNBdHk;D@TWos3k80GgkkUF%pwG;0DM4|LlZA+v{g#V z_O5+B_`iv#mt#EfexbsHRhyzcJ>E}T(YVK2_ucD46F1_Ca1Lh=bs1Gl>RMpO24HqdQqtbBy6hG0tHs&-(Ssm`p!?Iz-dOi~?Xl z+XPo329%nb^ubEBzZaioUlwSWMJ(UP_u^5fuiN}RDxoc1TE$n*xS2HC@1qcM(w3&} zmZwqdn^k74Aw)#Iadj=q7K2a+cN$UKxwRj3EBkU4y)YI`ojdemyO+4&lsT1sQ`8|` zh``ivkHC7ZZ6Xp1FSF{ecZX3;wGg2o*%XxxW94%Np&!U;`cUEsad>p&V3tc2LM^f) z1n>n2hN??{PgdnOYM*x-TlLH5c&fa8UEt9SKiHM?v$KP9M>g$_fy78^=T7gsKzi!x z6Eaurzwv%`b4m4j*b6grN1h2fd|(`Ce+vIZ0U*N@4Ri+LGf+GUX$Z7#nsckaCFZ&m z6#UBG!A%Sv#Hq;gwJe@vOm}>b!+fH<{CijJ(isTf7RGDQDC0$Oh{nMaxm#_%6=GS; z1L)wSQzb(dQTYk(gXs!eqkGq`urV!dQdWQn|LRi7CigV4D3p-ja4KNF>wN#7_3#74 zXY@lZhM<(2kX*MdN`*x3Ad{e(a8rDQCJsebeXpy7!vLJs%ucXwaWaoiOE0^G zuiQLlMpgdlbHOaeXd#OPYaRO;m54%#p}+QS?&LFOCR@&Mq#! zzNS!ouhTbu3m9ItV}9Q0@4Z5vR~nO} zFUoa+Y*f1THzqDjivpK-Cw+leJ5tqXb9~bmz+_W%=Sw8}zhAFroxizF(yRad`#C_d zYoni`+U?E=GrFrrpLLC8JRbt%^Uzun@=Gn@&GF)@s{Uxj5st7<$uqC>SSO2#oDtlc zY;NLFoZ9aA{-GNTn({&_8`oyT=PzDt=VMRJwFy{pcX-{{`h4S-t!L$onvg?-oQ~!p zNcIrn)`jZbg}fa!7k~t5k&;c4O>p4Ezj)%#|D=+?@m??R0%+jkfpFmv;&q($^7?0& zory^+=3aAiIoM0_=Aibd-oW=?6J_U7y}2$&>=<4(eCImVFQ_an9cx3eb<4K-B2t&UOrk}=* z0oGPlD>r_>nTrSmr877QAz<5vPtFD?mo3kr4#<@9sJ@Ad&*L@PRd86j%IDckVzU4Y`gubLHRjU|igC z?M(){9|yi%$mCH%VD*=lhBpHt%}8Z47W2fZz1+Ct{Hz;|bY!cs73)#M2KEisnxs~i zGZ<&IghR=GBRllsJ_f7481s5KKtpjB0+y@pNh7f`hfEX#yH$%4(TmCsr3v}%bCdQP zoG8w9i4(~$kkE^JddS2)aj+72L`Am>`c1U2jhKtIPO)YA@;tg6D3CRJid?CaLmhNmVSGm>t4-A{Wv$25%A-|5T+khG$IBo^y8THwlIP%egjYQ22`O;lnrT?O{pAU=Zt*^7<>Z zp@>Wg4rb8Zu4Muh6n-b>w&|89zTCJ4&XE%heLWaZ?92M2JKxz+G`w%x<%66oQ2bZi^tZ8|Y-8}Gk8X*y)qS1WYg`vom zm;VLDCHk3cF<4_DSzZ5fEmF}^;^P@}s$j>7k#Ak#kfuD+pZK)t@4Fjbeb^r%b^YJ{ zDut+aIwq(torE=ymsjEF8-Dnby&gvE9JaFRz6_D%c);=kzI;w5`ZwaL7>j_7<%_+{ zGr56t3HzcF?tPT(x1F6EkWYr&1C}BDB%!f*Swsqmhax}pZHR+W^!kPja3q+#!w>K0U;R%8e`yP%ZoGXqo1KYg4nPuJ6jmAnyTs& zo;yHkoUtCvBm{3VHincLQ;1jL@IrgF)t^ae_g^i*fg*(R7$$u|z$07m-GJpK9D*Xd z+CHaJSo=3`-i)|h5fKq%ifEI}5yLJ!1=cKIbU?B1X!}l19SkUu+`$gU5qI4LzKZX# zds5h5lt4%eoVElX55gRCa&u|VSDwA#x-+l|86wHawa8mSq}~C_(?j==E9c#st&P9; zgiW}E;Ew7y*M1`Y2VUjj(a}SEx#%Qd*oBj_D`4{Rn+AK;MtAlGMgG-Ej*#Yp2|&6B zzO7srbhg0T`7W?19=ZdROGn^gZFail~+}OmwdTUhM+qYh*=x`Lrzd+DO zBlVJG)4XoU(tMr#sUySxyEZEHqzxFkwFea6xK>z6@|3>k=jBaCB&K^0>OKs~N_Y`S zI}bTwRepky1s*grn}S^kE<$jPwM9igKsSa>B#=)7Wg{%a!2rlGa{(qmnk$vBr|dYd zQ9CfT@S^ZFn{*Hrg@4BPjjXzNLzAMLHW}9(mdfLsWK+;vx*!Bq8<&7~bw2EE~lz(N}fmwq#SB z$kS)f2y;f_0b9$v_8RbEjR>Si$82)6d~0BKUbP=p2Khg$U7V2df=6&YDT%q?k&ijp z3w&x~oYnc!9(~DUJu1C}eLJlAsFU`yhBn#`c-9lRn=(8by1@(eq`;=Vb zd-eu(m6azDnt-6BnP{Ns)13!c*!k+H?B}6KwoyZn+0tVFa&>O*GiO=-xSJbk_*Bob z#(f#QvFaFg3F8z<~<1Zm(V$-tHtg3DmkraIL}oYEQ*I z0d5EpK$zcQ@Bq}NZ2}k@dhxu1V_K zMb>i}%X1m{(lLABHo#Do0UEjhV&JVicV5kPi5c|&dC?BlnM_0QLFchmObn1P0tYR8 zyY)a(rF9W>_?Vpds3M_Mc18n<`o}XV1KGZoo>%YWx)?jxl}IMgStE$-#%0wH2-`)hGebjmA&_w)_3Bjz z>_bkop7VUCqHBYIbKHsGL*Kml(N)|Ji21d`-|rTPA%U9VI+q2qttUAXK2Gh~6Rs z=+K%GDP6iEG5{4#Zs_C}q^6{#q^11^r|}D(1AL1$KGVm*{=z+X%UI0J((*k4ueKrf z6as!=A0QTiN`Z}ooObsmK6iixC~lYGhuO3#gxuEALAjuXem-r_(L;xXiQei&ZZlF`bZnRDWd1~ za1n8fh#3J-4a=HSsW;{}ydU7o7>9|qE6^&#Ni_KB)46m=!)=Qd#KkX=IoX-HI62WU zTAQ0shiv>^cdU$)hV0g+l5Z%C=H?)c(C&j>0Lv{-#HvFh#&;6&Zn%kq1^IWLzFAp0 zi}=&X%a zJ%XI3#`|lLnpRdugjRk31+*L7%-VQ_=E7y%+;HL5{Dp2(Z_~$WI`J)9d8xT)yu6U= z^$CjdcJxPCwt_o$lp>rIStys)md>H$7bH=%>qV4>nEEiRDxpmZ7Fl#0LVBFv_Ih48iPMJ!DsbxPb2G(WVj6+` z8*K|7#MGw8VZ-%Si>F06(b$m((dwF-f@H+kLA*3fZOCp5sYim{0zSikFvYIqksR)? z4M5IItMg5lg8_y1TTV^w4*PG=7HB)Zv@YVKy7W;ZOp#^Py3dnyAWr(nIhYuzjW6A; z1#pW7Ol}ycI{^w1~v-#kR%Yhr)d~Oo*>BYWLA*e3F|jMpJ%*$4lf`x3s{E z=4jamyaf0%W?hSN z9VwV@>;aJpTvg?R79H(WwisfWZnf)?cH(LPc%?&n@%%YN5~m=05u>0kcs%UwpMP5+ zcs+;(mk~w+q{iS=#R;yo-93gFs>6q2VMhldNG65RV*9{DneE>X^o*Am;r1|T;l~74 zi?5j^1W*o8B7rI;Zash*7+pK!%;?PXWtU{t_A}kB|1WL(1bM8K6pO43>e1iUA&9o^7OGI#qy+k8- z9udk>*=FV&wjX-3Z?6hB7uOBx&(lv;9_`r%YVYnZ!OsN~)P2DJcmF@DqbS@mLEAe4r7+gl$4$Bm%b(T;K~~9b#z_ zH`3eDF@+$=lw232RI-JEK?|6d zN8~SuU;wdUinzZX=x-eiwu&UTi n38Lmff~i4M zn9(l*B>{stXcmms;N6bM;6V};D}{nv$wT2Lhc znLWtO)iI%%njfb`{&&N4CYU zop8;-5H{jTa}N^HgK@23J<>UZm`ZH;E<4S$mC=gWk**SszdQCTxzF z!88MjBEjKqkwqKRylaw}x(fG$Xly&sKfk;Fwto+aIRtVJf~6z&52*_ZMtwrex^9FR{4HA| ze)oIzTAeff+n$lD#H;-okhWSUqkLC(*G+j@BZU6EduMU+DZ{DEEnpv^$PrQBT4D{y35wOX`CO2lIcKfEg zxofpeV8D87{K;EjR8ojDIA7tNN3~YmpyKdw$KJ5FvPK(49)(R-t{Kgl@-|H=>h!SC zASZ#x0jLB>;bE^UEwW*N4uc{VnH8+BY)WDkJWho z-i%Ymy1!>R)YZ6{!%fa8BzA?)FWs5hZFlUMx!FR=7PoEo@@Hzon211H01Xu;lod|I z#N;1LeZu7vRj^yc&2)$15`($9gWg76f9RiP6Sc}ta?IHlTUSBVnUBLw(So z;-9T`U@+n2JYtD!4?H9Ril{ya7@SHb?V;dFfO5hz8=P{Gn^sm*%iLu^k0I!>rmY!P@A~$jp8Y$=x6y_L-R>^?ksGG5TKY zHrt`s4Baz6)nk}mYy5l_`7tg6a{}7;qq{;{NGrfsr*``(>#3mO+kuOroVMqbh;1`T z(1_eY`cj*fUYz`?K5H{GSx~G zwN0qHP1H+*q*x906B<>?2EmSvA8mc)MMw;kLywsuiEyxLQ;}FXq^KE=r>AYwQoVBL zYD({8)v>WSjeCqDPu+w|Rrj$URnV-w(=V{4w?&14!P=-@_{wwiU22el69EXE7g`8@ z7LoWfg{S<+0Nppgd4ndkrN2N7+~S04l$7mkHiQaP!^4LMi7S7GGiV}~9PhYB-nyKHh3uK2eQJL2G6>s5Vp2$8;5 zSPnXW{K&=2d%)T{4Ljwim%6_rb&$Uin`MYd4zyv8?{TRrcOCf^=*L^4I>prQ!{kaB;qRmGk-k|(XrO>agh%yXzPl&lvA&dA&x@f_JAdJxY(cyKj$1R@y` zQPDLtL9;OVlhykcl%`ni76+#2R5oqGGNgASo?sN;zhApL!qF0P_R~n%2F8eXP)|>& zH$p@4h_)I((^%_Cssi+Kf2p-LKQ4wITa9KfIPk%QqHD1~NRC=3_#sf9S%q4)Iq@9zm%hO#&w-XPDhEe z7dU7G)%aSbv@>%w*{jH=wh+w<`FxpdfP0SEW zfIwUUNMoR6Nj2QOILZE;t=4lemQSZbcWV?r4@4p$yuA^Okmi{>&>XgK`QUFi-4W_b zx>^)Cr`D^p z%6S?B#d7(8L8ctHPwnq7(vZ(k^U~wvCqG@3R>dR&=^&MMJ0m4v(Vp^>DU(cBK0fV( z$qqsA`X&@`p`f*p;$Zs+ukaZq!V5`mS&S8pjMl>wj(p%No{e~x-@lKh6WT1q)KAV~ z4+R2a1g|++^01ve^-C!Gp=9QVV8{1R!vU_v*2W}9$olZOKr2Kv01_xFF6M}6KrfB9 z)a_d^tMy{mfS^v%`pW+iL>H-b)tZ7VL8X_zdo3Ux12ih+Z#K5J$j=2kgKJHwD#r!s zE7tqcGmma0`Nh{sKPV`G4!IZ!ghK%x*7zHNPdt2d3JGc2zD^#M>Y5M0B}T<25h zFDClAyf`DvM-uHFSB=WX2Bs;XP1eYd!H8i|bBQjVhH>Z<)p`jLbOUWdpzu^BD zSSE;2%&209&d5#$tZ;4@A_7E3SGu9KXVB5jZhDz-|h+>Y@<7n zdl#(R=pXOLcLzk>%p5kFVq`9-r?gvba-Wl#ie_rE1v4abl_Ug>KEPoj6$AiHk84G) z3mRbP;E{o!e9Q3aCr_o~wSA%Lzvj7sko>c2FA3bSLkjpwOspsSYi!6&+9u&Bqlizz zWcthAXXRd^=|u`pYA*I>{hDPeQoY1cy_GuUgGn0-%nMo=01&1lA%X3Gw#D%O_kFlw zy+du~WpK#ZVt_hu#e<&Bbg4pQ(|0e;S$|Bqm^ZH(<|4L3_p^i6x(|F)s-M!&t@>Xf zSb;)7GV6J~wkIkZx)(sXP}@QuoIZqYG*}3Wth2&`W2UB@&6BZuBL>Y4I@DS9{#^wH zw7L&1EqCz+U<89$3!?M%A>C*lEfWfp#;N^b0^tGo-T7+6 znCU9ItFd$mAuC{J#G>$^(BY56S}Nr8vrYh!a_ESmiYX`<{hnvsvarhj>0Ojp5O~Q= z=5}_{ByjeyOMtro`Ei7g*|zUm4o5TX7u$4w%ZoaK3q#Bw!lm#F@&31OZ{=U@TWzat zf|`O`X3gcs_$ycH-T6fZeLPoQQ7NzgUrktzny{Pl6sB5t{-zS_M4+%CEux?R_|XcD z7TLlF54@L`7Qt_~G_h`#)^5Jz5O}f1Td?D}tE+9vkr!5{s?BX|HUNJqIEJbS=4cUD zBtX5j?9Ayy4mOfBQd0>~RK58Ysm06ks|^_NN3V|XP6y9`f#(H|ku3Bl-jH=*#A0X9 z`*kkxAr{^N#w5Az>V=%ejTc8`AgO^cp`)v-!TaT1Dd5YfGe|3Xh02c< z-1ZS%QLVRGg*w*P@8%694;zH>lf#d}S%);MQ&_SDF9I?lPxJF$(2BZvkud!bq7}^j zA`&*$xvJcK#$Db$XrbKsd$7-|5c2%jsdAt$O%fo9A!IfXnZW^7-XF3%(Vkif!6B#` z6G|eMm^i)S%M1H{B^p;9<1FU~R$SzYF}K0roIIK6_yGIC?5XU0)H-`=-AA<^+ht4Z zE$^cHI;C@q=Fh_KKvls>0s949SK#sxKry#WR~MI^2%2pAQi27(x3~l-zj#*rP~Y7? z_5Cf6)qld*nx8(Whrg9$I)7Fp=pLB;4(Ji&TLGR6$`3=9nIP@h56GLV@<5R_{%mn+ zX_VwYqvmy1bTzQ*;#WxtAu&KMBeD7m|Z62#&Tn5<$3KY9q#z-$G!u`aUw>~!Z( zhC`+7Afm{j2B<>Qo|}u!21r(VkD`k_H*CcrlA-WJViiD!R`?ZLMe1nu_W$~8&8mNXKiH|lGnT?rXXwmX=M&(yb=}4Lg8r`-pu!iB8xgk$>Ql?)l9sUi zHNvlV4gDifbHqDMDcgDsP)1~Unm>tWSC1${N;YeU||z#b=pP`+{Ga_(ml?me2^F!u&(SI76r0>sYG#rD)cO%@!zrdNXeLYb7~qoA}5#gsm(n==(vZFh4+eItW>%rzb2a za1jz>53Gy)ck3&#kzhf-Xq`pT?=ZGKK|99a3t}01et>k?_j(4Mk!uA)*syh?1dkTF zZJ446p$QBgX$gXaw#-<%y|nm0LG@I0>v0C_;k|)@f}1yo6E*>Ri*eWS537Q_6*S1; zlEo;d=4GX&leJ4@wS3`ML@tmSj+d>3hnPV~WbV<6xF?9t6keC3Pwt_Cl&rc;yD+6LaJbWbPQMkD^vf1j7dum9?R`-3|^z6wKEYl>! z1t7cG8}3Rf1f_=sU9qG+qsnNxCDwwUI-QvH2d7_0?JG(*Ez7^JRUyGCqf1TKct zhwV`iwFZEzz%P(xYuVjCkL2^LIOjDn2_c@8lq*z!AWCqOK)>%gGnxRMOp&#VvvZ~A z2-Gm0ut!|EejTIgxpY*Qiu^|me}|iSr(wAO`Q5^6hWEDA!mlGFM4#(kJ3PkYNxM%! zcnS(g>??%Q8e6759kj?;m2QC82hg6#pi56qK44+Nw{as!7I$t%-c0a-{__z4>34A- zfhUwzP~f78MOA?&!}eDNI3|Yogbd%|DS8kVV^-OO3Q95Z;H$gVZ*g1m{}F{O z=}w#&72d!jyW>Q(OL&A2C)N@xqUyj~?s-NixuUbcIEkeT6V!Ps6@*kPj&U_|veUm>ckwU2RQK(ds=i z7RZi6Lk3ZiES@TqaVY!$aQnafud*mu73--9*|s*%!HfU7YURWJt6WK^pz$Uf%$-+_ zXlO-K2f-HtpXL%?99f4QJK*vJK>4FAf(4gYHR?Xi&by_B@7wg5Qu4K@69cEtV$((IsT4c4LxC9S_6$12USS;wpi5$uh|@iLhy4A_U2r z>(aV{!Dp2#hrgibYbB?%Un7}zJS`|d06PNQ;N3&`$N>odL+W8@cfzRgC!AZos$i%~ zC3sNLV#}&>_Oa~{x|mQ9_=xSkUr+u((=f-TIkKFY<1cEf>Cs2M5iqlmFt4(5&aDG#z76wc`M$Q(hHl(f8YsO0zd@>pOjSz2EMb zL3{Td=|iiS8}K$^@`Tp(9xVTWl4;Lz`6KW(1db{~eS(m4aH)uLR??YSSd=wtIMpgQ z_{`WaC_?LRhd9IVbx3V_uD373R~vc$l82#Z$B|ndMk7`O^v%>LfQrK;cf`>VqFm`c z8-zO^-j!V0a4VJ(Rub5?2$wy+A7TTVTZ%&p008Kh79hvc)72$1@f-Y}1{n`O%@t$g zR5zjEAU(pE0iQo2)A0!*n;JMBc0=jKc|HtL(;x#p!#Wrv(u+55{6Vc@R35Jj6*uH* zC>>Np{ORN4rk0lCdYmHVn1-R1h{|^3=UogQi>_8#_*AFaBKvysJm7NFJ^-MidQcz( zG;o%MdJV_(QFXP-pK%;}17IMwtfS|W`7+EsFePZ1Wf8X z5XOs~`CdfP-)NnEDmQN*`pan}@8$sF(!VF!-O@4v5en9Q_KwfoE|^DjC&7RIQEux~ zo~ECCwAgn2{apu5td18F*|CF5HR}N*z0}P#pL^2UCXh_4s@9+(L<$Ax1vKO@ORQ1q zxwsgmd4;rUFXp2O}%_Uq=+9h zs34(KnOhjGs}mX8t^Pid84A1GI9V~#qW%6KptA_wDnxQSl$F<;+ElK($=TX@l{Bq1 z(cMHfL<5SIXT&BxSYG}_#siPQ9GMP%AU;>9B3TLYDm1)x%Tl~mfqGD@i7vHaU;-05 zfkaJ@np-BJM#9MT07*0xyEw)Ydw*0|h;Rnc9caG~nj@vIx;KA&AS1lJ*e0}SU}@|pdaunApN{mQMHg13w7IiB~P(N_j#Im7n55-f&b5! z>*=|E#Il1P$9C?CmMlPLkz`W~3t0a?W2SxgkK9V3zRj&e3%7fJ)D6;3(x&9x>|eZk zh30ZiS5?b&MQ9mlG2b zPM`w9y8wU%+oQ0^w7R+)S`wsC{3}ckdN{mR>cr4$Gt>Wo13Q*kmWd6Bz<7URbLby1 z*doah2HB~_k0vgC&%{$mVj(0XFlo*h0fndTHsE02A^rr&u znhO^%!T<&*240OL?pi@|9!Px`7h?0{@bEcEFiy%_K>|6F{vllX&=rQieUvag?aEJMq$ODH% z3`%XZ@pK^-yP8=T=x=wjjTB~!#ZJ;@&mE_iYIJYu!?qA_^awB_Y>h%2GY)w-uGcMF zwrEa|Zn)@rV~g9kg^vL+JZ{w`bSn+{qqH4@aYcR-%{Fw7ZrLT2Fi}fiq_yS(Ip4SW z1#kLeUc2e#YMo75;ZJPL#f>(v(>Bw!j?^KwQuO05@CYUJ_<6i?8()!{TmNDIgs6z0 zPn!gZ;Zhk6^DjdGj~S+GEUYaMm2TD-J3S$7i%Uy;<(?)`QO_h5$YA~ML-frGs_yM^ zK7ayoz*|K)-=putkOdO}s}RJ0%l}9(BOpXA&(xd}h5(GF?*e_8^znJ+-@Y9$A}%WG z2x}L0*vD#Pg6Ec-^QR+4MnyYiw*gwm^7SvLA+pkryNR0#P{wQ6-=L=mW00lx{NUZ) ze{cA?z@Z+X>c~JYecyw0eXoaE9=Tvv;Cal>Lmv$CbyKyQo!^|??7hdoYTs=N`rAlO zAFEKP`@Wi+Rg<)`v}E3#B9x#HyhZ}wgT$-zr~_-F$Wg*t3k$!+a@Ndxq-B$|^Oh$! zYPYTvB1=xs)&}$&(VU}=JE9kTcXW4=u9ykyhu&b-bdkMa94f|cWqV+GdGY5B4*72u zKPwt;jjihq&M0-0FMXl4JwecPT_IIc`yAZV#^J-xNkS6Z9X~Fzx8~)Yms2{CGqqf_ zc2x%{%lvWOX7ea=Y8y$LG~)jq->CN4Q=#>AGXiuD$UODQ5KnXEu#{*jfsg>oyz_wg zA?U{zIWu!3tcVA0LHH#xVhQm3gl#aUz+h(7F1Rn8jNk#tenFj%K@cq2ghdRv^5Klw zi3a50S)p$a8R%`qe3O$-cg(f0JaIloGM*6j;t>^F~t@;u{~sIU(Lh4On+zK zQ4PG19P`H#q5DX;IoC0ta-lhAw-gw<$OP^4GEWr_&C?Rqx)J$n#_WnPWmQ1ZvdUNv zH?1jP`SKdpO(vK0TP00gjIv}CHy^vae0zDfY@)Ej)VPr<+p6SO_i49c%3S6O*iQQ6{L(ml&dVUe`WBr-{l zq^C=}u~skM*3p=V%I8V4=iO>Y_jg_O7+0xy*!*DMnT*M)$+t;Ib2vsr zLPG`H!e5s0Z@rv+q$PY0;4Kj_ zj7+|ZV^ws)f+@u_HZJ!WD{kD-RCdF5>u0wI>lXPvMT*9%a3*q0M=&4_4i3^HQP81G z^+)4WG$wU!UOuP8Jq>IDW?--h7D1CQtTZ4TVpVjLK__WI}Bs}D<(7;+MLHtrmvk*>?H%tRU>eC=+J9Ay z8D9Vp;s-^3&E)lQ!UUziHhjR5BDLvg&REsKTkY4^&B?>v`2q!^Qa&r^xmj_!5#EC&Y%;<>lPzaY#NXkQ>~ zwL=T`^pJjjSeyFvDn@Zfgh(RU3o2OLyE9l-z^~$y;9)C~XzMrK3GRuo@q_d0fwTkx zbvB)4A3VQ}2T%3 ztUYm3qVV7b*>awj$IoeA)HPcj!@DQ_VVIN#^P+@ITW;ZWQ7p)~#JjAFC?@Y~&ZQxE$!S)qUqRst4;vWjMtz9V|b5 z38@2%fK38G7IIw(9aQYHIosR6yx0$t#<_L>ftPLLod)C5zR9ZL;|oxHoIiT>*7ySc zr4K>3tLs(m1(o}H~sIE^TyhYx){Jt02L7Dr+^5RPO-5la&(|Ucfxxd&WVy6hB;55?? z8Qx~RY#1>N+|S5>5j{ zhGTQ3fCl-xbpH%eUg5Qbiw22sf8?zIGqGX&@?|6)?%lJ8lZI_*W#12GSgN#zZGiLj ze=i~V%GRwP+44BG=<>H!P(m5yNe2=Po{2ifnQDt?g&NZ{84J)jG;~8n7|b{&NL=;| zWM_j&oYO+rWp)u=3@8HX*07cGGtXDjxnv+Aim?b^O|w z9~YNH``CE$t?`$)2VyQyCzkB+uSxN08vC?ehs>E3$!W~=lA%mpNc?k}{GKxBJwptq zk5&v-cziv|#yU$8dTPzIos!3J;3HF9-IfV45%bKbHw85vq)I!7$JCB&3$ul-$xYK! zQ^Z0*0+R3Zo9Q*pXCk(m5gT|f`%m2f(f+XLw%q;=cI5D^LB-?>gZV%cp)x?ROaCO- zB4zWYqa~6^Fyqe+a0H|nZXVjL;4J68q+TR;h4H}3O2U4Rd=p2>ufKRRS&F`#qeY(V zhM)tR2e4BO0g;n)FdQHm7Z9MCL|NeK{pb*cIp3EJWBe<_szY2LVmZvr%>TkaPNisn zF!JKVxM~R1`0x(jGqOJa_wp!OcVK^=xiOom#u{TbeGNsvE9`Mv;RkJenzl@6oHynm z$FiMpO;i=KXR0cgy;G3qR9$q1*DU!<)$eUz1wvmXjm_IxS+_A78_$hgYEX<^A$0wS z%*Q=LA1CSzi^RIu{tokPw|0eszsoZHcpx zA!!Y3CeSxum@EQd#e=^_XLk&?J`w?%NRoJ0)@5rza<}O!|1NfHf76|06Y`~)Z{CO{ z$2um2hdcp^bP`+5y`dQVySEK%-x}SgZjF78$XkCv<9f&H9!M~nCt( z!q0CJsxy2YE5isd`SvbcQ*L<*?gF zX-Ke=o%HHf8b7BPthgM?mKiLZIk9%Sa*B__&BK7pCPD13<%VSA6*jkYN!+6c)e{0a zwG)d1bvhfZggbBjsJ+Q!vR!zEwrU%#;PQ8&3@d%3{Jq`>*W`;07<0|-nl!)kkbX!% z|C;=%xrylmjU_w64i$NIe|`2f*PU{jB+^kJS5I^it@V=g=?`SFVIhKz8gpz`kjFqzM4_*Bgak?w6u?%Ef zv>wqnT3N%?P0mk45W#`sdExiPtqL=T7s`b9OY&Uap!|#Q@Ik0JK0eN(PO?P40|CWj zX%5!IR9Z+PfpsxS_s;Joi4^UpcNB+OKLjj_w%s5F*PXG+={R0oT@F@-%C6E3J;M_6 zgNQtEAuWl-sLc-klyOA%>6EwVHpRqbG!LPeO_}k9E6LF=2YVD5+#VS`m%dxPOmeHw z!#5`uZ{E2xxpk?e&!4?l<<)E3`}aWT5VIbHk;q@UnUIdbKy7(a4Q82x`}gOn+2~tJ zBu?SFcypia+d@sBxA%^)O#|m@NVlbhno1OhfRGh~3V^5&lIJ;StVY|s;VWH!fyhQ^ z)76${2Z@YT=$rj-B%H2U-!V96PUN| z8@ah5cTn*3x}4a|JGpH(ZKvxWPAu#j->4K&F6p8~ zrgV%}NF4~Ed$o6(n>OsyI?46o256*2eR?f%lGb zuE8l6m8pNcrY|1u{sqXJ*ai#D08S|~C9tpT_e{X@jM`$m+O~uDb(_mo3lY$JXuFDA zv}$n8Q4cv~>jMYQHmp*>a#4Uh1nmTC1a>Q3(E5aw2vlqYws`+eIJs%$uNL5EBk1`Z zzFa@KXcOlj%$44pY!;qhc6ws>zhgnQHj=s(xL#Z`g-e;wfkYp^HfV-9+*Zl&Q%hKk zQ1iYr)@~ybjb4J4DKS{xSlz_ngP93yL7rJ)CRs~@!H)GYUumVOL_*M#Bpc^ont!U( zxd#bP3^W2ySPWQ zCrWg&((gyZn>QC;9FfX!t5is(SEraW1-ofP?iJtkBr(oFk95PBu9HD3jGd8HIR8+n z1cOdqaCV&d+ETOpSg9~>PDj(tc?J2pZ#&JvJZ0qHVa zZr``zqVuMboyVv5KMX(f;f{aMuK`nis1o`Hz0;-cGS`)V538EgAmLtqfU5v2Bj*6F`VyNBbj7>^L?;S7NS_=VpNN6OJ- z$Jo^6ufYIx6uAl;AxR~uYB@Q2F`kQQ9w)uuUS)5kpT2)B!1DiAg*cC$0lwJ0?qgNF zftgKBSC|^VvZwPgG3UH|+ft=g3pN94@8DEyNF|_vG8#JFFR^B{S{$48>MdnE`DsuVLjz3nFYgK zYG$vTc=np=nDbd!TS(r&9(%fTBR`|nn0@|a;`zBlPD)aX zv+SHVzFCZqloc9OY_lmX@p9L!VwR_SPM2_AYisQzms{br%qI^$wKf-fGdHBHa>n?M zs-MQhki{inVk$E|9>g$@TZLKhiZ0mKey{G6!0Kl3?XR#$rp8snW9?&K^qXT%(ON-s z2|F^Xq~t-8SA)>8HPo^;9!1KWV`Rsz!HVj`7aj;#hMz_4<_mB<_A9 z3=Qf9o{Pwl*oc^AS18k;R~B|o&dm&cUG_dxGi@SY^hR!v2q(cbdU#Ai+zMx@FF<_L z{0`)YKOIJj%L2U8*ac@UTcH%eGRgMdX7tOkr3Vn}{jCiS8kK1bMN8ZHb23f!RWh3! zmwx?HOW$?6AmL|MQDm{rP8*vYx~vYXDP7aW6sPM&S~5J;Yzti>RuPjpeRXl+Fp^jf z550NR%BMM=q`@93T~XG>u@yagPi|5buRZqupTi5wyMFH_)$llGP|mMNw3iVPA*&l2 zhsB!GB8{^W;*`r9?x>5Y#gZ>E#AzzJn#_CW2YaTPnZ>D73^ew$HI;~55i*HWR~OI8 z%hqSTW|Dm~&Nx=WjIFer=Sx*rXkgy^HDqRblhvH#>tFB(1QhrwedR7l`LbiX?7N-2 zw!iaO`t-UnJsJdh~RuX36qekn31`Wb^%>DYiAM0~WgiqABJZEZyGw3NUG887qPV20=&UA5Fei zU^Lbrxd-9z0O|~qenR~hfz%U01fELYz0-M2haxhTrnS7VhQ7P}`imoQy~BWm(%lXn z=q8_>1P8v+NUOp=iJbHO9Kq@=gQF?-+r$yQhlQjk5PJ&M5Vk8kw6>`>yMK|0{6*lw zFr?9lu@TQ977$>g037hp&E(hiPF7c3ktl3%D@*dpQO+;EH=JgwzoF4YA6H6IPL3nk zS|Yf~7H&>jR^3jdTl^;69k8YCg3Jx|u;|X64tKVB+1JIf;oc+9{yQ#cG|umQZ~`ah zWHF=g^ks+s8J7RY)mukJx%O@U!$=Gv42@DlNw**+jnXY8or-iwcSwh%(lK;McZVV+ zNQkruC@J0WJLi4Zb3ga{yZ+c~ujN)@bIo~v<2XJC&MmE4eb>~Svq+BnY_+0M-J>K$ zWfqn_D3z&t;!?3BL{10;BISltWt^=Baf;SLmZ&!-yk#wvQ%k+p1i9N$l0nczhDtJL ziIzKl13EPMK>rG+_r6>He%JB4%n6D_aBR8t=P%VHi4;h)mZ5Y^nu>Xnj0`J{^akjM z>F>=Dp^TaH*fjTc5VFP!5(BH6jKq8!$|3A8c|{$9geI& zaZetp2?AzYz-$VIR|4W6PMxho^Ym!q4#OLQJ}2NeQ)l_@(gF~JD6R?cMgY82D15jU zVCuoa;tKrzV1ca&qMlDsNNcb@_slL{u5zW}DqthOuwfw7qP<2z1A%rN>>S#G;Q%xk zZX(oHI{(ICE|IJ^)GU4&b4JaUlTqpqj|_txY7+0R3n48qoDGI)A1H z(jwrSoU=OxqqCRop3a~#WJ@^|i{}+wo&xQZbS6kvOd0}ymSbCyh=PTXFLxP=NWk4M z0)Hjg$clr*6fB_5{JQiw_5gqY#8HF7909XtBaj^# zR6rTiGX<*Hq|wn>7_o9;B=zt} zIOLsED1zUMS9n*=dR;ll`tS?ci&7T3?Cy8@27<9a<>haJcWpXv`Oyufe-!V%gCJ7G zH`;Z=6$x3vD`cS9FP+2kmzPLS>{B!1z2bmedM$?r$5+YVdAWbeh(gE?I?)Tg#u0;# z153p|m*lhv{aDgx8G~p1$k?*e?)OUGczyo9n}R(>@rZOD1iFH}PXC$h zhF9g}xA(qS@_|&}N&a!MI-rw5z+iM>!wK>{`oJi`17tb_dZJC;oHiR$t(ENLxa@Rz zIsiEZ5+%X9AP`iTX(s+&VA_E4`Mc@$<51(xMV<&9CRD=w_ZE5YHPe#z^LQ(?#VY6o!D?FIbYZv`iSLA)m;M}l1T%uGVR*hdbCr~b?>-Xq} zW4mgL+{l<(@{(Y2{Ge-X{#;HgKD@lp&y_^Qa`{jUd~*%+Fhxby(iAOQwv6YGu$aTk zo=w50nuMlS<5W1$1EElik`}Fk#BYt38S+d_8rrP#a*XI`>6%jnEQR#4yku}iR;DOE zo(u*Ff&0UbuN_L6p2VvE%XY;d=d`b{{eF+%Sc>U;-pj@9`%jO0RtZ{ty1IO>G?QP< zHwyC0^c3ZyC(ywpn<40uXmOB)K!KMxBTh^cP_7MIwUe_mFve!dQVodvMi!n24h8%8 zm>ASBE0Q_e6TE-!<{;np1OTRPL9-2DUmXBqhSvvP#4vpet9JD9~wu7qXtSzNY2?jLLy|3|zR8vcd5D0johhlHz}}1q{?~ z93gQeE16(CECv{^fCl;$kU3UXR#1r);0pp59RP2Rg5;P)Ic-I-a{E3%Pl?_G%5(5v z0vG56hzrr6Xet&G93VtDu75QFbcf*n zE%=~%ub;BTT{W`FMd)+?8Oifmqve*bG3^Rou=oBRs1l^gLlwffb1 zO;P@~cRzlLT+0BOe2Ey5CUUp}jhlq5iIq4Z^~?O4)`bLh%zeB<9AftsPQFyl1!r>| zHaahC#&b)>$~g4%-t~U2i<6w6Z22(ez(PgxR}3WYS-$47L})6GT^=$*)O*nk4hxgL zq|uvFh?%Ft8KuA2)ja-taT7Lay279nCTIW3PFm&Z7Nxo_=XdNL8-aNVc8OMUMYyyu z^CUr^CYP!r7ek?}i&r(ewEZK+3sc)N145;!1jX@Ra>F`P$Vp@r-z=+^_`0#U8Zo0$ zlVu2wqW^M+K*cA&2Ii0t1R|9O|=}sN7tkxlMFUJ zE#%qL@PuG#vOv)i(7ED^tk0=J;UJ?(vGj;|2~_1a*QM@P!;(&akB4cgv7 zAOpBz*MN*5=CMbGoH}X;VtBtb%4JVL{%Dwr5I#}lmYb#ZV9Jb4o&*^Dj`Fy*_QS92 zzasOdnlP-v1!gZoUJb?AQz&ZvTv;h3m z*3}gN-tUZ2&@q67Vo#uZd$Q=J1@c3KB?*25l_U@cQP9w!BCvtWr;1fqL!$=lw}1u4 zcM#neqss=4o=8m^2=*n0t}1!z&A=eKw~6`;fDu!`Ra1Z~)$?%(@-a<3_^4g~BJcVG zR6_RlS=re$&!eGaZjH|@<2wv}XF^B1p6W<^2Hhk0KY%JFK*$Xb9x%Tx&d>XRv>((e z=Z(pg0Z=?0a~YLzZf#woQvgd478c-K)q?LD07^PcHZ2SXo&T#}==pbXy-tXOM}&Yr zo_darM%RLbnsPj;JNuKE7xgu<)xcP{N9$nH(*Hc<``Tw!Q}bTMp99%kHoJTtua&%x ze!U;H4*o`-$?^`mwCZk=&vaV)Z0UCyK|RWyG3EUg|G% zbU1H<8rl7;%u`L1yV6QTLd*!6WKtAMUMQocRFEbVuK2+m5z0c3hQn$;B*b#xZgx{g zm0s&#G48-$%~BgX4&~yI@bHhV-d&w>Q-TR)A}>;{8%UXoq)Rj@6!Te33H3r1m+R2* zzp2+ElI6H11X6Nn#@%v;&*kLtpPY1rEpzHSP~>PJ6Gl~_4bK$ZpA4LG{E9D?y7(5`W^vwy$UF?uuXOqJ!ceRT`e zT>v4t+yNxVpi;W zs5{e!0X09vq4hO5)`9s>WLSW&!`xV4fc@tXa_5eEG-dc_ufeF>$2-xx4$IObQK)wq~>@-CrijM#s*K7qg z|65sN_Ptmm3W#{G&#H=r>69;xm)U}y!Qf9)dF z<>7hK3W~-;f?5yRRPSFbc~V%We4T&X;ZIsx_K8g3XEd3@q&PO>I` zF?KH}lR}N`VGG+en z^a-LWY0p9#gds=AsE2I}rN{ltKq_~;99#kYZ0*EV=OBGP#X5G2lv`)BXm{py|fCBsg?0bws zPY#MmmJ~(Mo&h}0xWKGo9SE7Ij0cYdP!$6bmKg=0N={5nnAZrI;LcFuvaI}UTm+U( z;1mGIE}#xefJzpKE5D_UfZfkj%pt!y~tFhHU`GRGz;viH~0U;^>pg19d&26;7fbZt_E&GCIhEqNTlQuan zE>c?^`rbeXcCL6H^shIU;?kHRR5~`+=J360xzoqI^oY75Ob-ni6?>~z{6;?jea_MX;|Rrr8sa=+N(qL4eSmAHj76V>8y&Qgd!MT2>x+5s zrK?@q@msb8;^ofHQ_3ftwl$ATgilvlrNg7caE&(>wREUIkCyAyHs5Da$N4G)NenD! zAqiuJy1h_We65n8iNb|~AE%w5sF0A53Hub8?x3D{P5{^kqFi&Jtq@Kd2J?Fxu=hso zkAS+oaLt5Q_sbi9m);Z^^2$TME^RisU_0=8fK0?KUz+d30>Ekl0m$~&R=$UkpOuOt z5F7-6)j}6&azPQ8q`4*iG7c<>$Q70#$1L^zc&6aAMcv_`Zho=%@AJ0@pIc#c7Rr<# zgf}w;?Jt3pNJ2#95`gxhqTOjL1PJvep#7cOkla5(bA$?~1fARLz$oAWpy3e^bRADB0gMw^8g+qr0}!j!6Og-_;83&Y-BE$H z0TmV1!-pbZgAC#o0Fv%H2ID_n5_mhSplL-OFw+?=R@P+5J?1Y>*msZ&&_u@yTR4p#Fp6?w0IOy!j8!8?7qUU|{@enyY zy!GZ?d$5f@jv)(42t<{(&Y!tFc{1M*Lzc{s_$?Tgeiwcm`)9bsdEsKoD5WpZv}M;MLahWRYPGC4 z&Dz~cREaJ$G}qN>RSll>R1f~d+5hT`_7`c0va}-0P>FVk?k=6U`|CYp)3Myz=rAhiF#Tg`C|h~llgn^|H`V*b&p4+{udSXi$)dy_uZKhu z4VUg-*i@NVOt=qef=i==G4KH3a<{Ksbtb#Gxg7)DGGK$#hlZNLx}7tDNfs4P1l*!( z0Cd{mJwG+&22vtXft}#y1SStDxNLr<4r6t&(PO+mJHc|%(sCrY)Df`y%hF`F6h$z+ z;qE*)2h|){UjT7C_$OEvTIox{UujIbFS2v~-C6^(wRKSP{RHf=&!0cLV{P2sO$;A} z!ObWJ*A74oj)sOa7&|`}6nvJ_Q}v2j0*g8_x2a)W-%(2ukZQ!AXgktIi_3RT*aret|nh5yTsUVTh)Z(l8JZyYF^l zJOI?7|J?Dnf-RQrG9#_5XbN=5fs!f&CVmQT9rE8?(=xU}#v-!vV5`+m_lc-)ZEZod zw7HCz+lgE>l*I*|rn-tr0#mok?79EzkY zHl*(ENhF&`AH>HQ%KDSho6y%Z38U2yUu*74V>c_a8pvj2k;Rn2|A=T5^A7S|{ zBp^_WG|HKdje@hFzNLy+F7XlLGlgJ6O4x@ir`^b%sg;3fVwD;_zn>~I%ERBVB3}rJ zhY+y*K#yXVN~!976sa8~$&wz-F3h-T3ddp4(yMo&R=X}aQ@Q&Pw`rlen&-ZEd4Jt3 z=8MzD`IjHB#1B-9v^8{$boF(N^a;!r)S>F~m}uB63|@v$>mRWoeZfTuNF-w8_jo`S z>EdFC{k&kMo$dW?Fcky{XaAYm*J5fAEuxW7~Gnxf8ty1y#15d+u(qM?_2F_jJ7&ZoEjg-Bz{VPx@{sgNo z01Ocq7q1dfuXJ-AbEj~wmj@>w6jfV-;S~{bnJYICSCW-fU$KCg6A8G?V7QKjqFe)B z3qYEI*AfLRDJxTCJpmf?zd^vTGQNq0g#{LF`A_%;$!2`Y+X%xP|GbI-d`U(&#b`>%9ZlNjgk^C4hB26@P z^`Q5`#PINhyzY`hLrr#)1ZV<;K#KG|M;{9ydN^JO45~GCdLKx(hy;AD{Xosh+KP?* zK5*te=p*KF7X~aB;a6{Wogih=WkFC9MJWY%!K(2KaJPZoE9v-AVRGCWxa8DSR4zJc z(WOeYQRrvX&H{u!bTl>1I#Uhm0qq$|ItoVZTPcT~`=W98x{ulsFwmu^K5UTpmh&;@ zAZsY9*se5lkZa$+3Wc)*`KabsFk+|Pfp<(eX9BQ0c!1y#AX|(kRBe+rtG25^lni)T zfyx#<6Ix~zwu{2vOo5=l1%FW!5-IoQj|nDs@m_k>o8qg2d2lnMFc9DX1~QP$^mITD z28&yh(8VnZHB9@TEh!lfDk)yFck3mohp=MlE(; zLHcqKB6zMeZ(cJInO4lbfr6i%q}N z_F!soVBMy+{tX+$&Smz(m*HYHfkuuNf9C?+A9Yw}f#`$?sA+dEyN-!hFv2tjg;NJ* zR+uyz1nK7O-C9?d1kc|s2kvGsVAR453%1gij-YgCUIi(JdrvwKVlOYfJI;;BMZQxS z3{6{4makBZuDgJDti_NkDsdWPG+DDouR@&#Y<#-v8ts8*Op%qYu(9zJ%pbcz*YOry z$di*UNcPIt$0NXI01U_L0LcrY)4vU>?RHFySSRO8vVzur7u=r>(q+RvoE0W1u2rJ^ z%fjU;R>&!k0044YvcXgc0MAFQQDPZVS5{Cl{G8)Nj%*$obWe-C{+(gW;+E~0j9ys{ zH!7$oE&U71Rgk4+@PAn@fE)<4gg!n#0Rea5_(n-xfEslhjA$=^frN5UYF+{&_Bogs zqYSR7FA>;qERuv6UFvQy4^H+3MQ^DVdv5y*$M?3Ms=MCYi4u3lHv90K=k~BGHb(c!49X2t$_?q9o6~UmO(#4IO)=0uLmDLr9W) zYhUnYj$M3bC{R)5prTYFQebV68ZLREq@{XgH|nr*##N!eIcwnIZ1 zuxYNFP#@=!^Ky2&qav?nPD+UQUpmuMg*B?jaH+_eejC;7)oRIi{zTICaUjb8Y=wZz zR}_3&$xq&>{Q|ZUaAAuI2%sztWx#(h3=~s4KpW5uBvFnn>#4x_^TqT^q1c|p(Yqz0 z7DK!dj4+kCC$WIS`|zTDCXN+p@ObKHW+TxXwLQ=Tf!iOvRvthMqftx@5aRKb5nV)o zB9=VG{D(Q4sK99k=A0jtpMh5VL1dxL(^T5)6)Z59&E5o(;BqpB17TS*5Eb-MQv^Vz zTOGgx6ATr6K(zogmGZ>W(?UbTMS=s$1`}(8J0m?a?@r%pq?J-sKI8x}dE?{b`-AB&ict;z+?N^}iNotIEt&Wc>WZTyBVu>g zN1y>S09#Iq@T%>ta*gM5CRvo2|1+isjnO&f?@4q+947&_?r9cm47JDt@^OM6=&|k# zE;!Ui?$mznVY!b;o2b~Zp-eK^imWi0mLg9e3lc$!oD6osc7Bmw%PFAW$|Jy9%#VQn zWsJB#NatGuha(^sxm3NuP=utkq-ZdC`~5(A_}B+!R){jzM8HMj|e~utL@-3NdM`FV}(crOEW#ZF(Q_Ljzg(&h)i|6b}>Y^-Hf^ zlqy}#=|#WKP7jlv8CYSHDMe}$`eQQ%eIUA~8pLE)h=4fRsvF16xNxwkr4Deulfsae z(!fx_;Be?GeV1e?!TGM(+B^HNcZd!NId|_MQ%z#&P;?TxZ|CoCLuXa59qbJ|zif~( zvaBKCq1f|zMd5Q+On5T(nK8$Fi{9BDfR7CF15h%_X@%U-1i;z4>a0%d17{Zm90`Ce zdWTwL0~Rz06Gr>?V)(eNDtPWRi7$uD7C50mMD51<5Dr~EUkPWGw**}wsLsGR@e)|- zQ27?$zJVz(O6j+=Rnp{L1z}7Y0(#C<6tuDZAbjS;ZhmG%#a`c?Y7?m84O`t_v!#3t z2vy4pEtheN0zwbl!}D`bu)zfS+W(`g0m=uE3;?3a-*tx6~q?z5Dfar zrQB4!GR`~^(P&~Vv|uD}XKg#ji|hn=u+yVN7&bW?6FtH|(u*zyJ&FZKIv2qbmXAYX zs;*7Q1|toHNn_-_hr*C}NpTI$90FQj2+mHd=EoC?zUn1WyROxiNpr1UxJ`0f!z~kY zo(bX_^jl*0g_!cCL2Z-X`hC#SAyk`bjcop;-I$z3gds}TD==Jn98yhtjBA5MTR3MW zP_u2Ip1Ji=dCL8yK1XQ2v&efQzgcx648alz6}%aCNxPrZ!@Qf6`27@ov_%2G%DAw4 zU3I>(t*s5!)C#^~ODU_W>I7G0Cm=Id8h410MVoQ8YSX@znqsNM17P^rxVSCnzfVQ( zdEC-KhAdrBqsODp;(`L} zG$jysdn~%of-I4OB;-{~pxj6=52#RMWB)Hr!4HVS0Z!b`ZU-p#I`@6D$;0zhWiVH+ z{HI=Ujqd!rl$pf=sxbJ)$ZjtMgpdiwMR6a$WntqlPF-Q|! z(j;aQZvPKyawmAO|zg{{LFPPJN`Y_`S*)(!8HR4Kq)tGI-;K`v_ zTxZv;@a^proitq?MlCn(L8~78apRpoMjfvwezBG4k5|6k19()ELk z$T*s(B2S-IzG!4=st4#=ZMN6@yMUtJc~a>Jt`lD)mzPU6CeR(hzV7 z%(`RK89bN@!Uk81gzzR1+%)gCZaaWm7DzQgpeh@(US+b;e$jq6t3CfFe&acN9xy$j z%u!&g145bNg!eyfxBh%L4;oD{L1XC@{&$(pPnLiKmk zjb%|~XNjAyY>gh6^G#dyFMO*yl129o9*jq33RXdi z*iy~rf*kLDI7{t{A)aE>NtLSqV?s+-Vt>cL&aVUdDEliA>s(Nn(} zzCTC%^CJXOTm6SAo$V+6Z>Dj=?Ddr79A>6o7z0_JGOH10EQ_iX>HP>!7D>_|^r;FR zTsZ^`oiK_;sxb2gh7=kle@e+{l>G|t`;FEIUtPy`_fnHVnOUww3g-t*WW`k^sW2lZ z&gX;XVFszitHR%9|k;H2j#Z;5(FXl8=-@I4#`mmNdpu3U-@?Ggs#h;6wamO9o+m%LX1qP0#bX~pQ61khr7trb8F`PXyj{!wTJE*k4;uj(b z!|nqqQp;xz0dUBsFQ8$fv^l8Q5`ded7J{P(RVgE27Bj+(RaBiI^I6 zs4x!ljvk@_bzqeP8deB^wdm?vGG*UY{W*m7Ik~uK zKL53qHIZq!o9N4%|I4NIU5#E0FVM&~aRL)MkQ#yJ=3*s;0NjM)IXRh`Q;)V^5kW|B z!a)3&1t47jJsT+8-t>q-J?WkUlG6ViP2tsC0YQQ6QuSCQQIb9?xc)!BKQW!FO5!4x z;+dYH<|h3vP!-`LRg#>K-k+cQ9zml1RTEuNfu2lK*LTF4O=+!TM!vwu}k%K&XNGYl{`X zqO=0^Nsk{rQr(n_2pumR60{*WZ6*x;Cf{bM%Wev9S8JX%s z$;UA@CB|eB#nKrpG(#}ELfOuM7`Yw{tH2qu8*rVTq&w`Y%N+P(do9zoQUGj;QCA8o zH3y_=KzIi0|Fi>U=}U(eWPZN%nWEA=TpB_kQB4|Rq+?7`Gy-fV@Dl}P`Yvkt2Lh?i zPEJ&mmH+(m6iNAI@$vQ=mHY&R?$UW+@u9OsZvNOL`9jb&cIFZ+Bfx?V1qTMYHlQpx zIX$(tIJwr{`mzQzJG#bRR^ZpbD;2rbXfz7Ax&JwIRvn|1;?yCD-+nP*KssvcS$g-D zI%PQsord4{)6%epSg!ki<)o`GDU1t6!U#wbdmpLe1-+-sy17xyOV-qsMw2rkvym1i z#%%e<8Z6YG`ibfs8YTG^4r2ndhdc^N5|W6}e3K}$Z&E#wje$ojvQRGZTlO5{SseR= zySg)LwN$Fv51Sri&hgDkOCuH3CD5`@3Fv5WM!E!gIl^Fr{1T0f#~)u)j`oSgj<&~) z{!`d(i%uCWJB~uu^k0Y_qh94O!7`mp@6pUw!2LMBm&C#J8r;KWIU5^N;9UtWGr6 z85$z(cfu^TSFvZe-MxJ%)2dc&o-l9vKNj}WrV;94?$krBNwl2X#*eF2cX$T`P<qlF8+y$@PERq4hJZ&I1 z@vSLUZ8T4jcKSC42oQ!{{(gKPK)jgcNuUpx+Fe}*<7?~e@l9DbAS*+0??9yw2rFv` z=YZ%l8u`gv5tirmH5x2j(gH5hm_Zz#-{s>#Aph}kCjmpC|9$SZyt<%VPcl}p6Ob92 zL1Ej-EKb@}t(`FSuN4nl(!wY>`VsmRfg+Ee;NT{ftV8(TLR1TPoSrn%r^;!lYaB<_ znj{m`z0kvmg7l=rWM$E9zlJotJQ|Xq+U?XGK5M}3)%>foP+OcHXlPTO@`jVD&$tU_ zkU{FqX+xIQ4TnR_*h=IXW53VzC{c3Vo7vcf{z5n!yum?^Za)^{E7|tuEq``Tn9%!O zlY=ssQCitUhH?b1p%i)oq*o4G(oBoLpy<`Z?l*{j-d% zZCCJ%wAbm$AR|tHCsW9cJLvWgvQzbuA1&n8l#eFhOmx}nW_tGa z=t<|rPTe>P$KZE;@EN5}YHWN&-|KQUzeu{%?JTl_s4Vju6EH=8qLTRUcX7_;@@@Rx zO^d|&6B`<@<`tewn;@Zn`UoMsP`$^x{DPi!VG>TqrziWW8v+n4e)bhf98G;T;nT~T zyVWkhsl4+TcQk6wG>rUr%%9_T8LdWM5c~!0-nw-HHTEkVpTZ7r-%q8a=)uAf-c|&G zRswymnolom{I3$<(fD8Tcb$wn-WG!y@CCR9?M1TM-UwQ`2=kbaiU%$poSwS9d9rK& z74xH#n?u}?!~IT&B3|0eW&4MCfzz{Jx2T$NEBlOMLv>A<5Z&#|`?Jwo>uDyptOf(9{}F*?H=rw67K56 zg!oA|c15i3ljR2M|U7nX$ZT$k2ToM_bJBndr>T z=ggDk3YX0SA=LJv4=q}n>w(h~hPPO5A221If`aNEsUIb!Xp)@;zhZr5g&8rV7m=(( z-`zowc->%T9i-&MoKfWU0-vK|T+@`je*MKY?3n4jPEYo7;^&Emb{D4A_bDy z^%`=!CDB*1!mnr&L```do~NPlyfW#tpZZjES8<|pFOUe&K!)Dq5w1` zFw;G9?aEoS4CMp)Z|bs87gr3lk0FNM zDqUa8wm^w`d<5;VvHxq z)dvd=kC-tR6a5dG%S(cVzp0YwuP=qmYeRzJ6YSh~hx=V89^lVxlek=suFes~eUd2Y zP!4zf&LN2&%9_FdZ;;#MhQQ>i9E;ZH`W8!d2_1(Fie5Ba&4?!LDtjf;7<7N}r4kJ?A zdPC;!hdv*LSxqsYJfi;utz3%k9qRtQzh``TKLpP*bSF6_;lT%by7$q|XdB7eE0#{y zjw%6xH&I&gH9NLOw)!75&>nuU4gQE5Me!_7D(mf_sGhRDJwC$8Qs2M}Ew{2Bb7vdo zP$jE~2u_nE%)K!TTRTXKj*ac8+-~+dx||W*(8?6+@ZVz05>3k@6V*~?>nBu*)X6Z< zZ(EPJ)}06@xNJ^~Tc7#-9E+`oP%>TZ?bUX{sy8iuxjHJ3+@@H;sQ9{mfE$Okn z(N5SSGAbc^0-6WATr|!WI1Y$Lx1?<>?puH7LKf$q*1$fb~LEHz}c9u2^ zm#AZPM!Sztys|6a2qcl^p^(Oo`mTR7H}1FU+I7;xeK(et<9n@jmL)dVEIV}8_Ghu> z>8oJMyW7QAL8qaFy@B{JSA2r&IqrZ1T#1_yUB}G3ESrG+($CoovH>C)N4eDyI2Dr9 zuXMN6quZs;*WTjK*TkEk#>xJNEKu_8fdVyg?_aAHYPWl!3_Ilq&`>kjDJm1^4Fv$*^|AhRA+nPb9+QO)mQ=V56HrCwWi4cdXrEroi}S zo!j_&%p?0|!7*o!Vm(F@M-U$LaX?8hm)=7^@`$QC*qQ+vvh4bx)~~l`Zs~RN|CVFa z)U+@5(nY>cMUxZK8(=rfPO-L}k@4BU2$e^(yleiPe0|@tw1k}`T7 z^@puI@q~~%3v!|81F25s+oh91viJ+V2O zNQ?zU@GQU{1NE#8$TkE&aUcWxcnT)eR{G)h(lBmpm~QTHer9c;2U2rY4hbE5-*DgU zxdxnLt)rwhSNo#KjR)!F`1uh_Y_D&Wnlr8r&>)zb(}Jt0ou(3ZsMf ze=~f59w_rUFXmR%t|Y*&TiRX}L}&*RJ3V&U?!jEK;cc5y+Nb(KjEiy~A6;&YTv9LUVW}6M`uM~yiaN)?E=x~@^yVo~;okGycjo>V zmvh8V$X3MjPG$-F5%tM*t*4DMHC?1R5U9Z7KrH)ry9*!3(f9c0cD%GFmw_Gbx0PxB zhZe3M$I1Jocr&IUm?0D;&m)-QCCeBK?M}pK>dwck^rWEc%NAe*u987 zJFPIr9p*G%ZVTZINH=|E%@!(eX7TCPvFnoATJYx&1f1VWGT&12TsQUMlG6BPe7{xP z|7ZaqZd}iO(BpL8IG&CZ6Y*4T^8>Pk4RhSn>y>+?jGwwG8Y?Wm4D0^0;uexbghNJB z)rH~k47V_XA3<&DW+R4)km5GI9cu%Q2@$@)ldAA}~Q!n3oTVqYT3zuB;h6{#e1xR}S1{{WI;JML^} zf4s9PepmWjLWg7kIK{x26ohrMpfrC(UV4y z{ro@A8p9AZu~TG3#DdWavq4_Cd%&9|A9|?%TMv5kcON3Z3_3+DDx}XO6Q%6!ZQwJv zziDTIND};Mgh-;pd$tGfKOBgOnGkgm8|W@L`5RV#R4zKt`g)E;#x?&M z)^{}iPZN_(uun~VkI-sppKw@+mv>z}3Aj2`^A~2B-Q=p%ALs|iGjZ3|!1Be9&*C*L z&gVT^#k3bc3Yf<;ope^=(QqMXm37&N2>BQ~={#(h6XH#j=7P$^L+mjGCcVtZNlokE zPr_7afm&I%pbzi> zqxj5~b^T5&7L~H+erV(niqQUVkN65kA9Q2=#P_*({q?H$-AQwz*cH9R!9NDIYwmd8 zb)~K&+OFFt%YL`}#@>IgqRsui{MW6QL`dS%U}1gHr@l|RHFyjY9H=`|Y`m;)I_8%t zRnmjdg}s&|8)`i_zN^K~%sM(a#(!P|yFc(OE-ud5rD{&@yqE#Zw7VS}37-@4YQs)X zRwNE~O9SbVEOqYC-q@_kWpRPp(+Qugr01&Cq^3U#%;sclL;uE9^etIP#gQ4uky$HUgwRDx_3vEa6}nSD|1lIVUGo3L`k8WHcJ@^ppD?+%k}J9 z?7g4mhifX17|I7e7)c;`vFKn*i{GQobI+lu{NKv}-Jp1bzi(OX_i>v&_W23}iK*&c zQlf(1sNaW4W7;C1;oq1cL{QU}spKM83c?U5;tH2Cwj$QTYd{`YiP)W ze+XDd?WolGkI(Tp@c_*kaIx&Sad$g>x0wc@auV8E+eYmK(=e;h;}XWD(1WiAs^QWf zIqdE!ul6Dy3FQup#kP618^72aqeGxW-dN4~x>Aeyo_|~I1G3I=(S^KLJr3*AGK{q$ zyLNZi+K##(86(U`2X5l!WlyRN#XWYvN?acolP~$+`^cr{aBb3ceQ>H~?D<8!j+g4G z*iTQ!LqCiew6AFH;ZW-^o-cd}J^CN}8j7M!>MpyRxP=!!dd9Z3)BooOj{27av-LRa zW);(5khBmesG7I7^os)_;Nj?JU$(^4p{BR=9(vF+9Ly;nDp?QSc4ruGRtK6dh5u8#-q(BV8J>G!nyMh?Etrx!2crU|N2_0`BU z@3RQ4_6U$*js>zSqjfU~ERI}tTGC_r5E}&g6wJL&VSL7wA&b?W`WKE(_jqhSv!-NC zJDf&ssLStqeDciGIo;SKU{l0_s&B&#?>UA2Gkj-QlFlH;3gTS?>y)XA7#Fb;kF5^j z-lM5_dym%O2rLZ9@1G+==rEaSWnm{r*UIO84~5)*f0A&@nW9M^<{RY*VNQ@U;k zeK%44;Pf`RiQjJ4?D(E>i$N^&$Fk)5owL4N38C7HKg4R87du))z7(t$_E~z5Z4#mQ zj3J*m`Oc(|YNavxOhlajk}>U!t*N3*VOqyw{M$Ggh^`(RGm3jDFz8zT{jG219+o(t z$nC+qf4^D9ykO7KrAWnO%$+b~)$#0wxgog;a6bAKDCrD=c&z@VQ{jz|ftRqNtd+bW zHxG@)75$PwsbhNzS9W!^s(4-Vim1&QS8RQN>%%Yi%L1F&iRk~ybI~g6NoIhkq6lSEEQkyOCw6w8M8}Lq1Kn&Z`n40`J?n0Yz8u4r z!$Sk-6Jnb|OY@w-c{$dqxS2{-iJV>PYG#5RBY&62-g`mcbK)sK3suz7iH^uVmSXpu zVBD~lti+DP;!mHbDr#U3urP7pBA)#JRrm^f>484DOCO!uC>DIiY$13&F5NMP3*pbK zvWyxoQXpN%r-f*-qEiaVFG=b7lQ}<>C82ew!|P)M>{L3#tNfY-5e2d3uPiGEBU$_N z+&B2_;wssjyzsl%HGM}^PB%7nLO10X!^Wb!@INPh}e2Q3d zmqpVc;<3LaM!JvLTmb&*%cY=w5RGF(t!8yl!+%jAo3< zN4!1V_;l#dZ-q*}LWn<*r{RRnV;fRr-DFNP2WO7iH-Gm|hwJ{vMtC_U$RdLEHo`() zJ^ZUuvz^*BI6rN*G?#goadL$&_8U4)(gDYQD%1x%I1O^-uRg0@jQzCyrFnQK8ITbE z_lYO-(Cc=;`}FEQHP&l$nXHer#Ak%*WUmt&Sf6elZ^N30MYcxo5BL6t=v$A+7`Q&l znP$O-(Zh6fwZk2v+R35JOhN(^m8un{SP!6RIzf1v7W+6=*;zZrIT*X-FK8bsvZ>_m zrH+!k&bEF@>@i~q)sw)7^}UE7NtJl@gc;2NpZ>|cFH>P(6e#A7D_u8DE?3JXZvXC` zY=_bJ>Svh-w@y;|V3^l5wefd)3y*EaE)Y+V)P*3*Wmz^L{_eAnYgzdw7Ex@A&-7>6DJSW^rNc-|w6Q zsE%LLxMGxRU`Hs+_uxN&(~sW0BvM51D0iux3_{g=^q_I<*9q+gc|h&?-*qQ1!A$tV zsuWI&xuTijzJuB3vj%>JXoUc7GiOX2dg(|$mV}QCg@_LkSrkh%wywVj#!rH>(gQ2L z4Ay+OuM3X+u%rdq*}zCWXo-65Fc<7eOcv}Heu@=eEW z0)&%yoXCq2Qpe070Z*Q&68%>8+3)T%Oz%;`e|j#|zxdWSAK@>ggwOY{yp7uH2-Br! zZ%Lx8NkS7u=iV67q<3kiG(byRDqbEZ5bJx1{E?zjGk(vdtH~ao3kyQy3h`UX=m`k< z2|I4Si6`PqNZT_+la~FsvhiZUlYP7zSxZwf5Nl@&#m*#*sEvMzH`T|oZ??l&bhfgzH3JFiIp z;5ogV*;{IoG}pGU>xi5+{%~`iGQgg;HX!Fn*h5-`(Tt9(S1_B%{-_U3Gf8@*Ft0aZx zyXflUiknULyr^1=6PqBDaRVtx|N4f>C0rg!J0=Ky8Vo0?1b(JuV#z>vOuUy*KKZym z+;k3=Qny41l)^9_?Ggfo(&RoAc?srJMVh(7ToDWpU!hgsvKLQP%dD{)aeUjRvnlKs zcI-MBd?|6K?|x#dO`B>Zl{uNYAcMz?d8Cefyi6&omGl2m^_Ed>gHJ+S(w3JQkT zFrDdInLlT6YKC!;oT98E`U~~VG&^+H@vkv>(U=f}u~LHPdZUvDkE644V;H_*!^{uc z?Oz+tyVSy!;+CD|S#WRy3zc!OdxK_kNCEV45M;5ZX3OC3LaP7MHkTfePUffI<=Wl| zp+_-5ya)%<@(>gQawa21mQ70}uTzjgRt>gKFC|J?5JrHqjet9#FOp4dDf;%vihtFU zxvRn1Oi*XM0;oz*cM~oa_xQW%EJ7~!%i3xRJAgHAd?<#*kl)`bZp|T?s z_6eRLibM?cfiyo)$}R_s%-z(_jqMr}xq?GhC;X@{^TdBe{9*p_U2B0zt6$?( zPem%kV&+Q?GF-W~rYX_~mFcqR*uKwv{S2%qkQ4KPdsUzF* z@beOQZ`k2qv@LMq-#8MERQQn&i1a9e3@QKwH-12`bEYQMrm!{BKT&_9&HkU_sXS@n zS8~%f&Hw3*^h7k%;X!*9l1%7DPumWQWr0D35ivf7dOl7FU}>=$>s zJm@bC^Q;W4X_AuUe8HXWq|0fkgUI6w58SvdRs@;?8ISuRUGWQZ1H8oNw^FhdD4B^M zh9hMcN=qIjB&c!`OPt|vv$~t*<|C?2m3*&U3M!fsq$BDx+F`G$Qycix`JDCaX#tcc=p$;mHP&Z z^((4+qoV|1lAa%EX6Ac$pv0iG)!qHAqb)txb&_%V3}i{ES&y+qn1PLs5ieicqUSI(ZvDO?1OYxI1SziG zVn#irLWDsks$DDt?WjHD;BlRZ-?HUxo8}UY!%qH7MIa7NEi7W(9Lt$5yDq6AdFzIY z-QtI$dId|UK0^`fQ!D9d5+=aK3hqI^(9AB%xN59vEfE63+4`J*qg`p!{&MYWIkk|O zB=rT=$G3`+V?$9lm|t{QuXMHox#ibQlQ_H+T8U-xrCB zDzdpde&zs$qK2U$L4bcwC(aMRh~~8enYLJ{(y|MZOI{@?Ib!kRZe40fcQp{oip<_X z_K0AP(Br^|Ik_ z)(wuc_&z3wZjC6rjU>#hc$k!Y%L|@W&iC))v&aCi8^@ioE|eSfr9G>IrA`=W{7Cc= zM@G*`Os2m+weolQ1Ml*sQi~-= zjda(%3qo(-xWyvR6p+A2=yMFx2eY}3E#z5I(#PwYrw*YnXa`|mQ~1=lQmADDQQ2C> z(a^QI%8*1dBtGkUtzn~cTk<<uEm^W)_zSCf`)rX|QLofosv~CB2Hd1z2_Y+q`~i z2RM;J(x>%-?7h2SiNJr*Pk+BZ(K$5a?;OSc!zE@R07&_G^x#+i{^8m6Z%at-X6!so zTA3eXqxlB^E${Ka>O}IC?~P^6f?`gUu%}RC4iQw^kgImqtmyDgJ4Bkas^wn~AYpQr z_f2kYa$j?d0Bz(|{b9LbHvyr7C@0@s%bbfK~IpztKO*I)tEN(FHRH~4gwMn`_-tLLh! zSZmYr7XqtKHH3;$u~6#BW%U-YF*B~PfY4c`KnhY)sP(;<`W@?)6Yi%g{MHGGz~J^> zGZ=hbV#ppN77Cu#I{aa(LXgss z3)3c3IwO4bl+6l>8jdl0hIj-ofzA}{9eJ#j?Fgd#{M9|p%CXlag@X$@s@l@{TBJ9s z#kARhRE5dvOzn2Mnx1padWee$JOG)DjXi`PnVs8o3>^{a?KkT^s+Jk0lg&OuZd}o^ zLBWJms02|OPNDTJDrbL4M52JK%!an9fUr0`Ooco-ze!2&AO_n z=z__Ma4*5A^f9%)aK0jUw%?>WG(7Z$dIfnBZJUo4urlZ*DA*JVXuA8MVI@boNOA~1 zgV#T^3@GH4TQTj*t)AxZ$NM#xMoWsm>dcVuaZjHm2g!di4Y zJ}D#Vz@?=P zH8?BK$v3>S2`{hRu=kxkfZ&Z+t&J0xk%@(qUhWqcIgccV|FJ_zPDluwA>JR_$IVI6 zS4EXQ*up}_B2^mtVK6l=mo#|@8=2_2-)qyEh=WI!xWh)dA~}VeVioJ;qzxPom8bbD zuBqlo(l;(zbh;GakLE1Zk72!E)XG%La@%SFDS=7afJ}HPm7G_j95jmr~7BqvCW;&-;%3z7azehgVI3~mq z4NGeu0KpKlHe|He$wb}{-z4QU@u>lh5@UWh^kj@=h#<336rK$7;Dg$jL3DRGc5yH< z(@G4NRjc!0Ka@p6bS!0Sva#BRo6dQ+84P7gl?>)t?W^F+O}NDMQu(9*m}RB^RApq2 z8Cj|%nv>_rYkeKnnNmA9-^+&&7TUev2qgJVuk6-MY?BQ3%-tw1Kl${pTG|6CU0T8E50{exVn+TlQe6(t^D%i7ZUf{ zQszjqw6IDR3COvGzMj)X;uwPNBG)RV!HIP6?tB+56|u)?Njw)?KkyTD#dGqYjM zh}%ynA??$}4i*;M5y6V+GmPH}_um%Wps*i|y!8zOqEZU&@PWgfpIA6fzGr^`qGRiq9sUl96GQ~ju~63xy&r8^W;F#IO;0g@7Nv3bOoC)U5G<4_T_^x3 zo@S08p1)7VIJFk8In01c5(KIKuqB8%9i*yTI3-Xr?BafXcZoVM<-Vr#$vVY@yDO`R znXbcGv(hgsHDW86_bT|AtFS6{EX#PkXCrlVEOnO!*Cr_;JKm}wqJLF60|+u|Oe*xz zgO3NSs%8(U7P>mQ#<#rJs=fX6jwX*DTR#G!P1~W}F{c}aF{26howx|;PwEQ|R(Z-5 z3U$O9TQDU7tlG&_%jpP+wkB>mWY;A2V;Hv*1i3WI*ZpUKMgi&g#F0iQnu{7lFpa|9 z%y^)p&x6FC7lP~Hl#$I@eUw_)Zf<=~EoIklZekJiZr4c+-99~Gfbp{#J8MEP+IVJF z>Lq6@=L9)cEee#@CT6~BItxMK!2Tj!&s?(&Z$R{XRYNepq^<-IuLykb(X#N{6UAJK zHepYbej0ds3=wA~5vxP53gHd{Li+lNKbJ=`*PJ$|s9+E}+W$+s^b36DRVW#CF9r$_z&0mh*=`eDF)_&jqoc`|O?I=8HjRf>!dv9P0b7u*=N@-M zAAl!Fyv`~~%b)}&EL(czLb$6%Ia?u;4n*TYF`qM*8sX9m_H=1&2!+7)R-6EvRu%*_ z7Ghl%N&hHY=1zZ`LD!hMP%P-hRF$w;8rLng$$p;ALmGUiM%xO)9(RCdiVCt!?#cH{ z6#vd~oo+)-Bt}gTPb=9UETjAaC*Y|P2#>7%p#l~Cd;jX_;IvaOdvRE?aS*w4Yg@$1 zJozt2x%|qr!5d;5c183IsXMwbuHrP!36_cYpqKM2CdAKyb-dWDw5$Cm@(%Kf0Lj2N z8z?q~x`wD8`WDuk3R}+`RcxUxLyR4X#zrALwyxKS8W%%N`1rLWom2YyKf3@Ka8(ki zp{Uj50E*xcjj1M+@x;n?nrc+zh!89o1fPs8n&lgmQMrRUzwLowadZ_m{DIA7%{b=U zy*x{BU4n#^Q^_Q%M{P&1L<6rfK361E6@DrSw5pypUGnlumh8t|#BKQX&4~#1pEJR#fL%wIj?&;P7{xlRm5$Ootq#8zLaP zKVu)_rWLoP=W6}yueIcNh4j%Zk%4E0Vok8FcurNJh7x8EWAz539sD)XlXwd=b2YV6+jCQQUz9cC8M%V4Z*Q+OJ{eN>l?bq5CUq;-ipy^*iGPQYe0iX=9n~V~Ls~MKr_*&(eEJY5kdI%0nFq{*_=Q529-A0^6@~bZP8q}m&{4W25R4|T6 zui?sYkr)gFxhu)lQb;&UaUqE$K=gSmD;YmwY=79ASW{mxVWT~aP@fF5rH)R{wyx(( zRFQyEO(tgddoSwFweixM)Cf;Bp`;cOtb~(0CBO2iO<7zl9?-I|%K+q;2;V0H>$x7Z zke$EFYba`YJP-eAHCG0)PLe51J7IhF9!$(DuN9P>zBD=gs}pGF&6CTRc3`e8qr59y z!H?{lWU{PG4p9blCdFu7JBN^hhwT}2$ZI3L6jXLgZK)B3nKgI&k_SJ_N7F_Wkx+alDBj8kr47-B@dJ!8%|d0Sr%tT~G3T zEN7T#U#amJ)@yj+i9^g(6+0~Z!U;x+qB5?|ik#!?D1Sh;lRwv0S;(xs_E%LKCG!mT zf-$$zeTxAjm=sFxbrn$XQuNs#Fof)pAT;6(PIbvXZq2;j9xB2C`UY_E*TkNfWgV4hpHA(a*eH^T!XN`h znoFv7@zW_?ev~MFh;62OytKLPTNz6T6(m(=s00Iawp}KxACM$@;c|ara7l!j2NdlP z6%qtVy;U5h55l*87H;gsr4l&2ed=shoaBR4Bc(u2Vww|scpI7HT5TU zrWd&{jZ3#CZ2`y2jv4>gG`*w)F(=^h%Ms0;@vm(~mWZ^*m-ghzBFs5nNKzfC}VVeMfzR4^|o^8_4k* zM0}ZwogSaCKyWk4Hv2Tz^yi#DS-7}7BcePWM?yqG&TggpX9_1-ZfPW8^(G&MD}9PN@6R8AKr1@?d;eFK1- zmKju%0)yhg@9DZOv4XxGD|SMy(wZJ>zN#2>5nrFfCCJ!6P_S)Yy5C*9#=oDCj-1H- z1jIk7<+e#B+Q$P+zmH(D=t=WO28d3zQGwi(0Bj@*K*RGE$4f`X6no`2nmW6wDX@-8 z0gRd0iBVgE#>7!_{o{$WtJRnDb|HM_uEl7RnHxz4RX>?YaFqWB&f>7Z@O@$yH#nyN%!dP7MAAC3pPm`Z_{O!;r z%@7I2h8mIl3@-d#ZZ1ekm!0)FHkFoO#HeO66pR^|gra8yR%lX+x09ATdO3bPLJIKQ z8!vmx=jh?)Y8r#KXyzNuctx#rI2n5E*hnBI@YPYI@OEKOW82Tz5ZDwl}CN>qO34Gdn z=9#f9nxjyn3GP(8wQ)jo5Me4i?>EF0TnzG`8sB1wVjV|0NWf7puo05f+wwQ)E;=6w zQDt1M%apP&;ytE7ptiXDFz;uVJZI(R{rBqM>v02ykQ7_T<6~ODgGbNynO3%od&`a> z$1SraKXRcA6?^`mltxhkmV^%KSF+QrpLP8j>|E*=6NYTOu<{(YYM(<{T3k zBVzF=T*Hf_=F% z4fCj?F{kR!)+hp+Wtc5B6wgOFhJ2g-;((i_(YDiM zkGv(l#Wkg9Dq}#@mdFK>rhsHZ<<%9Q^xq*wWT3$X@o?Q7eANNPtbz}w47Hw8nCv&) zIzGvw3}={w9(Mmw(Pl;D)BK`%`!|^cn*sIdOQHt*falJ8qOn*dhFyXlAIww(4`q+0 zS-GJoP0UG1ens5r8g&U5H{L+0|5e^jePDE-`%{OU(Tm@op5|G) z;y6m#vrq%}62;vY^gq=bj@_f>ic9MTO{;^KnA3s9Uns3YGAPlp54a)mM@`fC%>!=<3FISnSm{>G zlMka^pa6Zwpdlc?0+2i3U>N23JR?n;Yzhxsm%59aJ1QEOF6vJvNcZ4V%>C5E0LF-^s~d zLXT1+7~5km@==1?{>GZ~wYTSOhsKawE!nJI0=d%u3jdJJMM(1MJyo^3#a|1{ldO}@Z(8Fsq|ybUL0gBkuN(;!!3ty|C}~>dMpvB zbMuf*oYHBg3jlN!5O>3o3Gthehd%*K^`vkJ1<?BV(6SjbX1qvZt%l^)@|?`dhJPyO8r_Bpp06TT+E$H?nYBDv4zFpA!X zw>ak5n50F^*Sl%P(C*JcA24jY6YN;?^Wt7mW%w}j<8}fO&f-+7cj?wh2CzXd-rM^o zB94|q)fZP!(`ND0`c0?Y;gOuJpVv5Se_{pTtSEZ}lOr+bLPd~I;jQpGYeDt=zdrZ{VF)&4p z4SogP%;|^1d;NfY=LxemjipzFM~%bS^DX8xFGBQ18*duSBC2a0PvR#zIH{ zkZ|@{Y|oG#yZZ8tT!>dy9PAli{dQ`$ThG_ux9I8YsL|3}p}^Nl_!L`?Tt!BWB3F_} zcN4c-D2ZO$#HsLGUI$L^a^Q4;;USA=nu+Gu+Gn@sf=YIMgC7(lU^+4oi$1>Jp7CV7 zGYTfe1gjTS1q+&s{Z7d3CL{SNdqAn%!CkPQ+}6ecl|n|o)mmLQkJFNL1LM{Ax-=kg zX2zLKJZ}h7?5;$cD*2tRZy>%cgVvZsb_!CJ*4WMa3$61bnMp`!OjF_s*FHzWNm@~iU=b>S`w6aM+SVbiUMT(Ed(=vDaWK3`AJU(%78SY z#qA-(?dz&A9~uwU))n>N{7INfw%fb8q3V*kR#WU2hUNokMdrTQ{B-^v`8ee0Ha9_tTI-$*E6e{WaHksnPQ_;k*8j5A z3;0&8#3zGhfeIImDGg6OZ7%yxY^Ujje?bz*C6q1n>DpdoP&YcUu>8Jy9Te~J2Ho5SAxwvdm5LME3?Hjz)AQ(gyGZV*)y93g+%y;+f_wjpV;B znDO=SWD9pNDB@}52gF^08+be6aVjEIDtn7q`K<4JEVZtsABN0s?~ME&mR=@~)eK11 zZQhT&Cp+=qtQ}fk*|7e*d_#sQI;{rrHu-@YQQ`i+$wLT*4R;_YAV`1JYlnn zZH%_aj%$cwh}19e1`gj+``~vV00|GSx-;jE9DeN1=hA;B;7CKX;5#aOI~@( z{?7G*xMG$LS&ysmj3YZBqx%v2rGfN;RA{6DbH35piuB1GnApHb>p}kvvX13~F=n*z zq;zjjdSWzpf4{ukSVGz8s9lHk*xdP~P;)cS31E^*5d*NXknkkLI5^0yPE<{8CGn}Mj=I|QI;R%Dx$B0SjPGaWD|zwNU48Nv>iZnDMj#or$ba0sn4Kpp3P(tZzsv5F zn73Lv^Y8j`%V?*w!|{}BUo|O>z(yyjML}|dt%)V_Lc{-hXFC61OEf+yVIIQ$#jM3G z7Wq~dzI&xECRpU{`(}7wu3YzvCzMsAJ>`|~3U8774i`V{ibL;?^|$MtcoB}Qu8f){ zQ(Le6j|glYB?_wfGAK~R7%m!d#l{ZkV$HFLr=c;bonwj=-(oyc+bCqVWQ@bgmX$4^ zdXzZr_b5OlJRx=baPP|@M7p33LCs45EOxX<0#&aiSfoHEfx4H*o`~>jJ4_d>$YOE! zQ;+VIuYYEnbQbS={##Dp4);ovJqn@y$wC(J|GFV6>6xo&;il+PfQnVQtTw85KTmZi zyBn?*5#JfqWOvhO0(;?fpr=w*igij=P7!!0$9w@xEKL5`5-83v5!{FZMgEglwBOSF zdQm1}$=K6>B|UO=zUii|BVx$0=f|^+-9J<7pidj47AZ0tCuErtL;yl&_DVBy`Ur7u ziZ_iLVmdSo-i-XjcV3&%REFv?gOiK|!Pei%cwC(~&Pc`?=G@o^QRIRVaT&f z9@yd?>(-nUl$5i{G3cjy&#?-|gsp8KehP+pH;F@~Fnra!T<@LNgd>pp4OegKm5)6n- z=DkM!!E?8ZmnRZs8N8r%qjfW9sdZRWoi5z5{Eg$Ar}d8+i<@-(1tp`s0c>9mDH29| zjO7wJ^l4Gbm`4=fUn6|L9C36;i&iEf5-0LofVMkhoPps+|g!Hi){jp2yrit|IkQ`eHkC=c)0@yzCs^!;x&-@kBL zBuTyQ!+PLdAOOx3?2BjyNMLaZ{{&BA5;CjYFxfm|*EM{xe4)9z%{3A3-DcwvegdIO z`}I1#y*w5)x*Hn-R>52v62!3^OcX7tSl1?F+u)NH#ndL0W&AMiE3q#YoqS+6-LUZI zECru^l9m8>l$K7B^+N&;EJI`i`I&b=*vZT5R=z<}Cct~Oi?i#U2N~`U>$ddvX~@jT zTIIvo@y*ab5BFQsc=ld*TlU3ZTr8YrcVshg2=QtNd&2u$ePXmKM60Y}4ne@bkux{6 zvpnv~cKx(lKOI5!CBB~>1IF+7+ao&&K7G$#1vQMvtP;KJsYxKmjK5&BFBwK;=Zs|y ztU}v9w&F~B&!{P?RdNYYEr7`~9UPL=Co;ClJo8K_4F&|T>4Ft*=Bfyk`Y6c|RENPb z$kuR3v{!U%@MV-4A`+X_XC#!)O@a>2E3t{*FCN$V}yKae^FZ8{zmpBjFW)UhmoQ`?}1fFJAI?*q|h18Wn zKam4_lY}_a^UAOX_MaS1!vJtyjx-|x)G7m8GUHz-_dzOQc2N(Z-;FD233riY;ima9 z5vU?IFCBzvR2h~M<;f%_&x`{Di4}$6Y*O^rzDJ#pFIT=ebXDBx!lVw0C%V+d8VTf6 zqwH`Jb%;0`?V)LvFBeRDaT7Bo4xv||q&r~RW`{#2!Eo+b#mKd9T5%whY7gU$Q`qBu zyHBcBsnNDkX(L2}8;wxHet;ZdY%?d*u4uaxW6;cujyJ1F>Ot^rR1vlpav2a2e){)z zBb&QMi<>*UBYbP1e#@cKkDj%eJfVWtV=&S+QhbSvLNTKcM_$~ktWx}w+uc!9zWlJT zV0K@EE zsWex(qEKZ@g3f*s@09AekbE&@0idF4r_9v=_L?7!kI&yn^c7p*+iHJT(hKg5sqQrm zT@p4UG8SpmrpZ;-5Mop?iUkXBdIZe*PD+8`vdK@|(ZAWy!sz~?wN*dH&~SDQ^l{pm zt^Wa}rl?AV$`iHtBtEUSF9Ye$SiRVS8KEe$Z=7A!7`-B%wi`0qG8c@T zmW<$zOCLV)r?K4@MUr@SVx1{ZyuMi68a*>nqtAM3+1)Sy-0F1gn#!e;O{RhC*zBr5 zg?1Gu%1xUU+}EtNQXE^8+;HryM7$JM66S`+RuoHx)lREx70(c?A6X{rk|n#ZoaTv?ZKkLQ(ob z`nWWI(()s_KX4Mb;_i61sCVJ*>y9}<7VYN}IOp6o6!-oHBoVLnlHw!^7TGNxOJ*3s z(w6cA8{7Y#ZCrVJ5!a~Mcxz)!6>c_8mDs~I{B3K*fypV0o6%tp*4>by(8NlCu7M!7 zuQH&p#9*(HW;3qnVmuRD6$3QXMSSPc+v4e1y4&MGK7?5!rS8vh`}=^a&`P zBJDT^AKm1e5B(9sWzmxQQ0&?|ynlr-(9E2!4u?r00zxE^!I~uoUuK)T7tKE)Pzt6|Nwc~An*@arrig}#3_@60 zFvSySM=dk*7kt?bYs$9k{$d?Q4tPOu48xfb2cEcPZ>5zq*m%9%*kjX3p$Jr=x# zvP}hoNa5-4SEEK#aBxJWiJh=qiEaB%IHzW_erEILNjXgir)HftAG`the3MS5A!HN-> zw(PoCMoTRq2goFd#KCEnny|%~e3*wrrn~h^p_2p+2R&7((EdhNg~t^U|LhTWOkUh`dZG_F}t}m zmA=x^(`K#4P(8i*Ko#JerJuWJ5;lbME)DKSP;sT*3?;d7J_QkZPd~zK1(By(`YtFb z5IHqdGAe~-6p1YGmTrf)OnZXxDFbb0%O#8f^^IH1{3T`=N2N|#Ky8rW!-QK;$r4d# z*P9`(aXdX|t6I5rP$NZGr#MD2uMOh?_eHZp10h6zY&C+ZvaI1bmYq(rR~a{$5R#U? zZZl`tNR*s;)7RL0K8KAVM5)Cn)n>qk=@b){lAon%lY4kF1?*0wkY!aPp&N@gyeyZx zn?Q9*o}f^}7mGL;0A0?&4es^{%^;9tt&TqvXfbH;Cm2vp5nF)=Z*{UsPYGU0;tYO^?XM_B;_aB@iRF)2l~d z<_m#TW9*nJ@5ol}3~A>bb&38R(*=#Dm~tm-x1%^Yvo=@4r`s#a7AE~wm@cpiI@5lb z9@uXojepYc*$SScj|jvhMPNfnDL_Xx;k581W22;oFX3^C=o2hmc>;}t3I8|SR>6LW>TsI_QNo~Utt)FFH8h4yMsh4eAP zZGFTz>@L@IHfX&XjDNc-igE$3g~-%evn~9vT$Tn0k@1J-DC`OV)I3OV>sDq5^NL$+ zC+A+dXf5epPcKwk=zt(%ap+(zNK`Z|G~s}*(lCVK}Df_&+v#miu*8eqr&BWXJ;rYkO+xKt{ zCLY0aIM&-4;! zuD#&a@!wsRtAcuV0io`Z`MzJCx;l)~?oK_LDm|Od^(sFcM`9ujJB{}{lk|IjG_qEa`SP*kp%4&Z5 zh7W9O*tQs%_?S*S9qsikZ?tZ$dysNb|4o!TT!sX59!(Lz*d}MU9o^6fmYNhk@G9h)A0NA@z>-YVVXS>Wh#M>yQpizK$l$%m5L^n9JND3s z3o86TRi)E$>!cAQ*3V_?Sfb_ZJC!;ILLOnL^FtX8R4?Q}N*s}NRi`Dtf!drC-$sP$ zkH>ne}dAp2QATB<36e=4QE$n(eUn0pA=EyxL zI#*V~>A&eV-+rQd%VpEaZRk>*_@DYK%qMdnQrM=lMUseB;j zZct1jz;IX8EO4Cr?^y5uD8S*>p15@c{AK4yHpcTmagEIG#3+bZ*(smGLMMS^Za5Sy zKU=*u<=JT(2cpnWC14!|DrjhUR=y|&@OnS7@X{;lxd5%upp+=Yz0drZTEF=p=pshu zOuWym5qVB>8UgAMprjp;#i#bPBj0`h-Md9L8O&L3unP+u_+%7tZPC?MlTB$czEzOX z2S%m(4VS;?a!`r&bZhqn3wK{QYb>uqLu13BWGizy8_&hX;Z3YVSZJolux~2o{-C?X zYqa~LVi&bqBq>PXKzlonMtTp|N{_nN2ctI_F7WOT-ImlFP$Xrx&7L&Z3zUGU9f%ML zHX+;Vo`L!x&N8THB2eVrb&(_Q-Or2q+C>xx6vvxI?M8_ttHv`XR0k=P%4=b;3KJeEN0!-Y)2)YIw?Xr( zx4~!OabC~l=ui5&yCG^hr92bPti!9fh_4cX+uJDdX@$}{^`CZNW$>UgGN7IGd6&{X zOW`rpTa@jJ3=hc#7NW9r@)t5kS2GnI6+hORsW308xWE`k z!zFlkJmc&YxxgBQ;}zx=#qouYfS#BaA`aUnGlK>5B)BmM71E%S$am4-wu;BOZuBnN zd;QzcCBh`f`!lmxVxLv==2Ig=<0?y8GzStk35MteO!#ERbMJi=G;{4jq20 z=^M@Trd48_U_a=|cd+duWC@2=JKb*fOIcv1j!XnGk+fLlmb6&}>!kXJC8>=p>rzbC zuMPyMv!cZ27XM}*4S*B+Y!eL&0>V?#3mn;R#%7Ix4X7lFO-9Z0tDWhU=->~={}vvk z1O6RickYA4j5%&{>psl5J#B-tGp!@ZH9$f=vJR=Tb?AkVJ}Em18tB`|xL!zBJv|*@ zT)FNp=<`U=Okz*8!XHl}>S*E^-Xx4OT$0=o6gkAwU1m_?TrFWA{m)3fg-5}1rGSNV zC%y{T5r3(<4ER|9e-TUGiIu!iUmcY&g@^UKt&Pr0S;PV@f}cEcBRvRQ#_Vs<0MvQS z^J|08PtA{O!lP47MESh%x&@d#d|AVBkAuJOr=;QHisq1WMrz`~O`18kHZ{OP$)k1- zmD2$S*-?O|n>1ujP4ab>;*VAweTyb`;}cj4qLF z(6H|Ja=6hF@Psk;@OHa77QUxy>R>VDBu}EC7 z(cXV9llX!uBTCahNZc3OBxe{oB>sE_qlTS02@N5cR`(&@PQX`twhG7izY`yDO&bSOMzBD$aK*4+C{jDO6d z15@vn{)?vFE7Jcv(DE}-&677Ku&>^MvxFaBc+RPa6;qhk15?8|(i5euJQI^WL@oat zGdw^o!#$D{#F9zb3m0)l(7gf2q=Gic!C$=Q&-F1#)7h%Oxypg_RiUkm`|R{udC8pU zuf31edWAi2A&ixdo)t3)w5!{CJOBMv)D$Fw2-oSj4glvUC-IU4Du8uf5uzpu?N=T4 z%xunVxWW`Mv6hkiQ&Bf_2XBs%+WN@s>mNbdUsvkXO5JgNR3pe9gEF^z6rX3FKCCP- zBufuH8-EohjeY2)g!AE{ufsiBq)itJ!WAcLkK?JzYXDiA? zcW)J05u8fOX*6uA)B0ELFhCy_z#Tid+(D=FgTDh zziA^FCGhfM==mh~lLYu#HlymTxox(|;cj1?{P1ym``426;Q>`Eh$T8!uD?o!=qLvk zMQ9b6216yMD&!pb!a_7lj35Mu1?xa8r6Z7awcJ?QbA07`etyT0PMRC9$n2V$HZ|~W zosj;$@Jg@nyMTQk@2~Y9MY7#mOC1n6S<)hQ+3lVfpya$@GVo+u?(uHVsN=MB1YdXw z6AXdC;I8OYsd$H78^6WJ_Pokf8f?~ZA2RFy&O^BzWG(x(W8IN`TwhNY<~#v@uJV<)Yo3g5rDPd`CM2=0U!?ej2#Ymi%9%rjjIFw;V{2M_f2ZauplA3O z!3}EqJAL`zeb8zPo+;KKoKYy@6MVO8XA;k@^D{(#DJC*>RHX$};GI)}iUqF|y62ZM zxNjrfllEDE@+X%*a?Zgd^h-<>!nBYGPr+IdJ*M2*#X%)J*M?b(O&Z3b%^EXz`^JKh zS)q%@A;XQy0cGQbPZYJ-*NRjGxCU2b>X?K$WmEUcj*j70Y9!gy;({|VJZxr*F}J>C z1Uy>poPE16oiLRs4$+Ga^pIh2pmo@Ea=Xa9%C7yAg%-@riC+F;B02{+UU;(BLIYqFrYojDtO8LdGmn?x-bR{rVqKMav%mR0x@$t;Likbybm@=I@HLi z@=04Tn}9+^o$Y)w6tR@CLTWC8za{Hyz=-J$i_kU?oYJJQnG+dTEmTar1aXai`DA^p zb4-eCC3TbJj@Fi_5A>@^JVX*OyQl=Ix2T4UJ*!KBYk_FQ*_S(#X5wXHw>FQ}qA*aHvv-`;Bb1MV~+n6xl!=DH=+6Y<&Gt6-dgK)FMDS!5 zv}s^``KRpD$32I;TYSfB4kJdqnd!G)Yb<`cmhipWJ)BO|;$7Y!=95182xRNheqdmx zWD&DrV40H2XTHBm%`aE#kA`;v@-yef1p?C9rre@lVFsMrXCoN4j1%`5j_2L$+aED1 zW0%Oe^FL+P6^Zz1O5Y(BQD~#8=mvt~`Y03zs|U9VWmRa5LcLCyEq!_2XDrs1=mq)v zOeS69amZLOC17B3uH}AY0bZAa3js^fYzUk$tqw|2a>WA?(P#ac+ETU)HEHvFK8jE( z+)v1qFgV*nv_{bftYfslxD^Kf4^>|k6<4$^+jv8e#v6Bcf(3VXf(L8d-CcuwaEAcF zC3tXmcMA|8(6|JL$GGF2`_9`RYpk#Jx2ILjs)lW9=y!Xq=C#XL=nFKiCVk&W!$E;D z6k~uRIogyGa&Q(_IYaxof^mQnOQ`X@F;xBvcf;bXd4|inAtVNNFKPncg@5qmlc6F< z9;CSkBAv28H{~mqt|#`A4pX5TlEs(cm1?f}tzFR=E_T9aQhooWSp@y=N$otr@=U7R z@EE%9CTM6_m2GQA4A!7#0Z}yFeV=Z@-W+U&_1=0s0^etRc zE1?_?DSph)D?RFanr54FHHOC#9qLRTcY>D@4GjW!svQW1{<@2VK{bIm`JHdkIKMhi z4_a{youQmzo&Eb()a~IpD23daAH~O5adlHQ+PP0We34q_uzd#(#TjBp0GFPd&g2WK z1}f+o|L&Rqr+IGG4_Pu{!x`@FmFxl1A_VT%oaOE@`e z22Qi;&>Ne8cvgou^=RTcs>f-$^664OvBQRmWu~KYB;O1v zgnue3=2@TYozlBUQ`&2tn0Nnrm0Onn>fSDs-!>M;ER)sGl{uaAKBXt~d%m>HZ(5&x z$$uU_czisq4RF7{O~1=Vvz|!d%8i8(4fG&#CK4LgS2x)cVnJsLt-Lb*s!;bcZ-EQ(FkwkOBE=T&53` zxIOa*y9J}ddJS<6dPnm~T%*Q~y^|B%g*w{qY8@+U&$B%-_9r8jJJfKND}I6^@i7jm zP0UCq#vpjb)}JMVh*L$y%vT2%?VnVZdwmJbSM4ICf<^qI=84N(bClRkshyO+P!2^J z$cH#6aw|QN9LkaygAgeFV$|OG-a(~e z9mSjR9!SJ##ZPEF3LD#t<4T=dr=I5JJij_8)7{tTb!!VkP?Myh&~RYDT z;vT@!G@ce(n;%YTV_b!^f)9f_GITC3Q!yWzr`YogG9Urbhg8%x*v1`FU(W=Iwkj{i zh>2rCqV?GiX0W&sp}@QWT_R&foCIP2h{r&agT0qMlv=i5p zQXQft^OdFjuEnnvddrKPc3QU%^I^G7Pp#V;vDR8Bnz3unOt5ShupZ?QOX%6Y0(b!s zUMvc<_!C54rPa$A1ASqonF)@HUCG%~JH8%BNHfAw{E(lAJGf}(k*T7xGadZFc-EXZ z5*jV_OB^)_>cI>%6+es(!<-QE1G@3*mfG53?8)COf3mP~PrdeV`Frn`cXQ%oN%wM~ zKF0K*-*=w15F_|#Z~Wm0yP^u~#eXGaIFjwv;B{oWIqx7GgNG(lx$6=e3@rVS22Uk@ zPD{!Aw-w(;GTmgR$#a3>3BM>IPO6XRTE0nA4cR%gzRhQ(XbbZgJ|HeMUF#(||CPCHC1|vZ;fq=P;er>GhB7Y_=>c`E_vEufHL7_-nYV^ zmd3l+b5`9MGFs*U@i~NOn4|WY4Gc6`$&zHm8ym`L;zUHbBCQfkEXCN^YD#$Ueos&X zAozPnH@u!7JMXL7lg8~?Qg8v}8!@v?{E$>(Hl)+!qoB~YUUDZW$Ti(AXI}7KO^fM&OrIda=J)*2oGpeF-M>Cu#y^Z%hc0?ZsKp`{*U2x{VS-X6 zQR@+CBrAaCr{gZ3uF$C6g16lijJ(%HV?RLw@8`9CUPBR|Q*Pq?p6~1tBOq{vcnLgb zq(O)ZKlGpQryjtah;VDL%*YF@Z4iPuGdxYXiNjtn0XZJ_htX9P#12oyWr3XS-Bq-j zmUri=Z%X_4;dZv@ny}|9KkB6t=_e!?y!W(LqobGM&Ax%*qZARUWD*=j0*=dc-@FzC z1P)|myxc+>k!d9vs@l>GxHgARX>&SQte}fWT}eu!GBSrN?a!Xz)q{NL*@GE(qvI)b zExyw)zu5;yifh!64Qo}u(MP+rC~GrSX?N_?Y(58x{Mwh=A0N{;WZW;%>gC9yr=^b) zrTokQw4Sud^@`NSjS~wgqD|GByWSQ2_VcUXNM}6>s#5Lwm7LH^(;t0op?BO)T==Ih zii`1lYaAN%+nRc0ga8G3Fqe#w=l=6)xaw?3@OL83LV<}sCg%X3hwg(JEOOw2M5ZX7 zT_$!22$sB=I}MKFrs^CG4#d92u!PH_rd8PWBYGU-tBEVp?o-d9lT!12LmEf3N-m^9 zE~2PZX`g3vI?GnoAQ(6y58t1JsoAN{PwJB>8X_N?Cu@MC|5UgBX)(vjcw@yNw!u(D zDSj}=?syrgUxv<-ZqH731lT5qh#Cy<6lDFnraB)#r@(4G41=^bmQp%PvfW{`ZHvD; zb0pyP@f=^9KTJwsf~5U`RO)qW2j%!x^jLYhIWOoe&GOc~*;?8l*eux^wJ4G|m2wJ9 zCqlb!o(tL!sou(z$P`&mWQA>xGG^`DnSauE)PVBTD5~ok$A)*!JfAA>6zPcurAm~j znfp+x2Vujf(ih)63?6Vm~s-? zr|E3i;kQ6-4jJ^u+oa@oXG*SdDF@IMP9J8K8>o9waS5}B9%gl2@P2CWwgAgK7 zG2s(uRw=3l7D?|}xPJ=N61rACx!`NO5INXFvojGXih@9bAY9ts(M+LF{x{HVub*qF zhtv5&zU}R8&o?jU0}yR{Ud?^`SO#avC$-)8J+h`{dSq%-+I~p+l1&R!bIkZ{V*;DV zeeXMlyN8tEE7Q2V^`g!%EU!GpP8ezry@J=o+bIptjOKxwTR0x=POZb2=h{25LAQl4 zVSA`i!_P*6CDB$O7^FWvKfkv4l;;)n{VDcjXS>)f4dAGqa*WB|_i0Ok$n;XDf=x9{ z-#szOC6S}c?Z8WYTtP^2+>B9$ReiS(m$Rp|zIo^kCssN6u^dyEi=OPGPHV$BBLHcu z8Z;M2j26ukkWB}D(Rhi+`Y?=$^>NFGm^p42J7)Psyle*?avf?9B_u6|M-O`t~NG~G0?>^2V4RwNJQ_15Xc^YZp{5z%;L(U!fu zGCMn>(Y{xb5wR3AaLI^;Ol-Y$k~mo51A1`f6(N#DsPGKn)U%H*PcoZEiO6-irc7x0 zyhVFETc%l_@1`27r|w~>o`LFIOMbkIT~)qmS7JycZZrQmZkUSlyQ6en&+EFsgIp3} zGU>`1-=2;V+&c#7d)e2kxGHAxyq5j8h4P5xBphjQ+qF^b;pIxWoUjrRsVTKmCxp$G z^jhMo%Qs*AQ;e+p*t=I`0QKC2va&Gh>RdytL9E=(+jtaSp=$*V<<*GTR7k4E^q}xh zV49$Bx+~J)e~PFCCpX&MUGg;820q?5vAhDyPi@!+%FD}b$(M=INP&pmN-MCuV(ia5DyGX6Q*PSNSDimO%ZZQPlUeZe{DZ-Ty6Arb?~^m zyLt`9pZ3(|z4g$>|9R)o|>VWELo`3uOpGLi-T?LV` zg!lxqPGSFNFE5ugWjb*D3dnQ+5?wV!8zyYz%-{M{6|@ng`=HhR>zZEFnX5M0 z_DPvDSAjWVHD-H){B1pMcU+}2=u0|_BV4lyP*_S1XQU2-FKr5-1Lqq5>aP)Pa?ftl z--0-^#Nejk-`=8R<2EyOZw(f4_S#*Rh2>!0IEKV?22&Qeh zZQqlz0wU^H(GGqrf?>p^ND6yMA2r7!&2HJ&I7GQ{tbl4&DP#mzO$vS%G~W5+;G6C0OJD}=EHT2IDqD$x4J7DY zl%4qcurBe8uJqPXG5FJeCF_FFSA*qg%ik_{XkBvb9OUfLn5%5LLQZ5|Mh?sTxubkW z!U^uGUJYsAL>WuR<H|emAsm$AuukDpST*sF`Ro+0f|3NmtYBtQR;~Zf3C>EONs= zn0vufQZ%owKi!%8uyOjzl-)2_;uMx;2LLFZP0Y>P~ZLA zi@CRov~FoiE*6Uz)Aq0Mct1=ioZtwHaSrMm`QBSSEPm&CLyuM!c_PoFz(X2yh+(B~c;Xl!f2qDtZ)bB6+ROI0ueQwZWvoTU< zUes>7@5$n9G|`c|VK-ap=@|mzUJBa~$K z{zVw>^}nX>ow!!5J5&-bOHrZrW|UszafKkWmrlOJRBA${?@nk7_!v`cj#EZe)3s^% z`0JHWo3=FrBMl&7aRt0uoUo74aD&KLX!O|_NNSLpmc)#JZgmo4OC~MBNSx3DJ&2rz>9@P5+Z6e^*1UbZQ;k<0Wyr}ah5e% z_UZHG(4tZh%uX-Rh`{8DdfTqP;_{N4RqHke`Z&ma(9w$Rm5me%ktx(gf^gC*H7@Y8 zpL^I^GJgz}ET|~rh76qE3C~Vs1oZWD<)RK-esuMSMuPjreIWt8LKOtzkZ&k_<3w!?IIG##|8~D|Qv?gI4*m-M-Snv)>yJzhNhZ)rwEXw-3afWx-#=RY ziTc*wUA)RRW^I$sYR_yNY#;L|dlK74*(zgtZ;nDyYAo(N&CCTZRRasc8~G?hPqk%n zZDNh$PRZ*Z*~&8_gJu!41hg_>;$o5BS@^QHcP(_dvO39urMZ_)f5+}hv3)|tXM?jP z(Q>qYPwzjp`n5s(Xd|HnKkovfio_($&!jP&MFPy$f7OV6?&&G{O;J}pF05~AhmC|zC5ba3KIt%Ojt9U2o zOp@b`k$M2^?^+3=zQ#y=t*mgYzLn4Wp;lzRT`4BP-+TdtZP{HvX?D68AEM+GE+1SM zVe*{*H&?%B?QY291L_wWeQOFpunEiW;K;(i&=(W7fd=N(@8H(9y7m{xA)fXf6Hi-xB!o5gOJ zn;pvnK~$7q*CLE@q{9$EOyX*=){_&A(rxwK)gh8!*85A{8;oYVN}HTH!V*h}d3#gR z2-C;32~BO1hs)d@;K+{)oo16jQPh+`0U4VjOUDw?PNrjs?o;&_q3~@;qcmm^X=y@& z^7h%Z@`H&An{ey9``5pkx83R^R`mYnQc^1`tDL{&7?I8Hiof{bbv|u)2lTo*2L7n9 z!ih9rcS=S^37B;(;CoiWC{AFN|f5Qe-?Uj zM#_B&TaRd8)2z(qBwM{K;T00+mxR8ZYlLlxic^uJSilE=M}MF4+v~T|f31i#wIlJ{F74(LR8SEYSJnj1Vy82(vCU{|4@gam8(zVXTOT8D{7v5X*z;WL5@7 z+jAzCTXlXnW?wZv99WRlgjSC%ppfYT_0%*a66>vxIz(~Q07<>_O{V4xgy|jkb{+n2 z{7`@OSf$Ie*1Y}V)!9EMKspUYB>Ogj(1}gb?w0Ta>v&Inb%;w=eS0v+1Qm4U3JVHV+B%NjEy_GZ9fn7{jaMn( zwj3(#F>M_s>UQl<8Q^OuWz2~ffYhqg_5rpeXiR*RD9q%sszoa%0oZf+vuHFVw){M+ zd`DzoS392LoCT+ne|-&zXBM;gjT&3LkZA4OdP;yK8U}w)>rlx;qH|W}4kIc6r@hh; z=jqNeNj1#6YA5>iJ~V2TYByDFv>^x6e`oc+RmA~h@J%pRQ0%h*NIGHHf&E~NX-;|! zg}7>*q-i!)#Mo=rn*O@1Pt=LfkuOIUKgooP%t=W*?^h&W*NSqY#*E?s7T6ijWGs4c zRh#MzI}wDe`*fh;WicQk3h}&f5m1j(L*wS%vMfwZNil{bilUscZIV8`Gd-6-xBn6} za8p2?yv9@MCQE)ANboh?5*!j(CwY?3o4$0yz@PlzUiyE!>O)C-E89h#uP7ktT_A;W z!>cx#;4$vvsZZx>P1n_W;NcTlz|G#^@#s-#YL%9G^7n5GF^l|AOI;D8+GXpkXvUDb z223zbad}mqtFsU+AM0F&h~)lHY5Sx?=8yz>>mYPkDa-+})J$p=PyeM)VavLP%w^V2l_3J(*amP&*A zjiFn@K`eDhmY9$<)vqVu{IVVYwF8zq>w(Au*$ebJ#`yQ` z-RnPIWLxC4O%SYCghGK|EB?!_HCZ3|20%ptR7wf*euDR`N<`$Vb~wJHWNmAg;m8_=>7T0+o)vQ)oV= z5Hsxu^tuG4C|!@dqQYh#@zio;i_RYopm?WL`_z6b(lEN)6kEe_;ZNd;LjMQY&}Hb=t^Lf6~= zgsaOxRy^6cLK#9{e0~>zGCJ^0FQ8>q9@77BKh@CGidXZ@&k=tJabUFzhg@EDL}*%8 z3{}E668>Cc1=UOxHWp2stS|u*v6y0KXfduX($-_In>$^3E%l4RN?$ivvzP*g2n<)J zMlO91OwJ3^GyxC6GJYGev9FZ~X#9*FvjO25B~zTAXHbsF_;+yzl|}eOWv`!)%t17u z+Mrg4;Cd2Sgt^trZmgeG5zHtVJi_V|HWf`50>hywL45kpm6tHbBPPPC4Mz*Rlv+Xs zgm6m`Pjw6+Q)RFXp0w;NQ?P4!IVG-y`gm(j)Mr8>FoIrYA=p2Q8ISnaa)h%LeyZVP zADVHQim*5sBsfo->etT=*mb<*Kq{$5FOam)6 zP_e*JL{Igyr;^3q4o%s9hEgpJk`J0g(Bn<%YIq>fcU_-k& z1z!FRE?z8m7gBK~Oy#{??2Q)@LyS976m~a^*;SYL;gt;%M~qD~!qGkz4}}Px(e}MRUYzPQ_7uycu?BNuk(RkY2wFvk)Y!Pk~vxx|0iAJ%RQE_$)6GMsj zx|+$&@k#**HTSFQEFHe~2Xb`W|8o>>dpWkXyk0lZlrqu_@jl<#``T#&i?#II7@qpY z*L(uWUrbVDl?o-F$Z?YhWv)n@z&?;hbS>Vj6Sb3}!rigaC3|rRztx9_ZYqjI1I2|J z6pm6+(TfkZMWj6TG|`Qosx&k)NZ@Iy;gzmUsM`M7<8pzSrWXN(Nh}xBj53&4NsP?O zv34B;Uw;}l*{jR&MLaV|#?9Y*9W@H$OPL$Rbpb3jV9ceeBs3c1SVcr58`QM+_WHI-|iN) zvQ*cHVNef&g&U$CW|o>Q^Hi>@YJj?XbPnF4r?>16+PAVqhx3|WETU8J7f$fYYk1pLX55AISbx|4*2E1dUPKd;~-XfTS zkV2fcPRlM;vzJL<$cXikYs4>Ykb2%uHk3+$F#9s}#4L6eRYoQQb@tqOY67_mj({%+ zbp)UW3B$r{gmcgSb%&3Oei#3$okqFdAJLIo{xc9|Blj&%`^noM?gxnqob%>~h3~o# zXDs9Z)X5dsE-gQE9vv9{!G@{>O>bzWd6hP`w!5>Y-865uIsG{3m|QBhD^2Z97J<|d zVU2ZARRE!vzAbB|!JO6fM zM-(bizh}qZ|C_VF-yRp2rt^DF0ijC$*cjB*k$lRH-7iZWZ`T;F6Q>nsT!fu>XO{0E zaq;AV$y$B}wIqydvY9zOv|ZWP8wgXRrWa`u7R@Qe-~ZPn^X*~GJpc6ONyXoTqzJ}! zno}%nln75=?1wBPVKD5Yg4u69i^ya~1|6{=P0HQBq2=X~un^|Vp|v>u?uwe)^l4TO zqnB3CO(Im46gRGsvb_|NL8Y6)DTT->r!>n?0$0a9ijtCqp#wvBT6@fq8Mull-%6`v zdOjDXW3VZ_UEccT((dtYk1CTrnPq&y9lt%eB3yQ@V#2|FPa`|b8HsTm$}{8hJ3VMm zbK?~gaZ{uK4^kAW9GYL9x(YF6%e_E(+ORek^Dx6n8)EJ9Y^N z1ZBYL!6fZqr6li2nEj2RZo~hyN%u+LO(q7GVq*~hs3uB_%Dy9C3?UVOK9Y!@sJvm! z3k)B9?6e78Y*=wPEaZt$hx*`cfTJrSNhwR5$VDfPAu-fdSS3QFsGEQ3$&?rf0GYi8 zr=DTb67Uw9-_sS6-|TPJpVm79W$?A^y8m4(v0ZunBoA~)m|hu0#D$0`gAjA0FUJpSLYp)8JGJSzeg@|i z?NuqNZR*wT01A%Z3+y2S>cy3V)**y)EagG=`%1b8I7rqHZfbX4ACK;o=~j=p^5ZxJ z`l=GJzjo2=amo`3#thI?8`CAuJVrAzCjw``V8Ob(1MJEXdaznpw$|bk0a*tzan4Ex z8XdGgtKxnoFQ05g(c$5EMYAYjDI;Nx3d>b-%kh4-?+&&Ze2I8>$-!$dkZUVkZ+csB z{az6yiAQVC*L0$IXdhi6jmG##Z46W1@DsRl$x9xxCbKoaF?E_D-FWhcPbhEBE6gO~ z-G`3%(kg_){U;1u@u?w=ruzOrzEzo%^Xz7?hf#kgK$dBYSfSF@RxVF9)kYQ4hS3KO zQ8Jf=72-Q(A3Kmj0iHM-xfmH3kdQqXDOi2=6Opk1{-EfvW3h4Zc

i(f0Nl;&}=s ztJS6<5|#ZnD&1^TRi`k=T!Ea#B@YZKm;qqIHa7fhh5Ueo!Stk>D})4tVHAFXv?KSf z62_Hak97&#|IkBo|IO(pE1|_jSw;zs`)ce8Ct}e>971<6;C*PH3?51g_M(N-P$5^y>uU{(an0{8-*TD?T#9sD<752s||S`*pw(!iL{ zO#I@Cn}#;R2fiNd@)q!)ZEd5^`%W!HxCnskGTrWFXxtoXm71RpQmvTgA~0h_9Id{7 zN)KNgBw2vK#QCnKpJ~Wh-jiRICQ<`Ej^n-Z+=`wrR?iKt*4Dni`RM0?PBu$s!X*_L z)C=@Zh*)jS-tai~ejhTb~tLmN=tK}rDIk&rb*OP0OVw&`SlJ=jgniCPag(P2d@VoVorCPaU7*I!V%VoY&F$2 z!`71Fh!O`10y@7qF5%8jKDhD{-^7;|uiE)|cwGINJ-Ni5h)=pRiA>FYu7(Z5EOJQr z^=GPSsF@QJ72X&w2@j|DK$zLxk&YAgv#d@g2vrvxEZ_0fCkzHIOvdzSYQ+JTRenRO z82YJ3d&i=!qtzgH`|)8-ivriBEKhTf}fl&!_v zCPFum{~#q#n1I%D?`DU<0{aFPb%mYRL|2pG3if> z0h3rNwdMb{0iizB!W7n8**BoZ2 z&L2G4Hu^RspwOtKa4dKfc}g6yqN*Vf$mVm9GzgQzB>Ja%y1aaRu9@zGoSudM*Rg8-+PKr*EG4@0$2L3(snsQBQr%(wo2_zWl5(iOnQ@G|H|KH(qC*0 zMr>*36`wyz==tk214CX{|FjSY4>Yrzhr2MZ8~+ca_dg-xrn0QL>fVvr+JO|#j;K4l zL|rt<`0d!@rt|I3UFROg+hX_DtH|4d{`hJ4-QQcWywB_Q+XSKX?&j5+ z;z81;^pm0P9iW5kO-;4#zyQ~zGN>Hcd1uTjPSMEI1+MsDJr;`?imi#d6AEMig)rc9 z>GbtgzQkR5jcB7Yy~H?z!#=fg(w{-R$2f8ytI}S?%FzHv#VA85Gc~!9Ak!^tRd=^E z;%mu3olL*18GMxuO+ye3AuesX^kR91JS;7kr$9KFj759faO3soX?LbsPrVC7>{6;`>JSBXagg|m$-twY-v07-e&D&0rpnvy z=o#DVcwmoFV25sL@kG;GM|x%l2cnoVcp&0)I8t7l5s{z0VB3 zN}G&Lh1dlS-KyFUFSZ~zTI`{&|O+&<)2bN{**$P z2ppi2=GF>>1yHEnnuU|pW2c+4D<`P<6cfyx7qu>=^}wlWVp_|#ir_{t-C4DWq-2iQ z*LMnIoJ<4(38QH~Vi%f_^nCCOZ=ajA@OEwE3#`vH3cPqZx2{LaW*O^?^pr%m`%E7# z9W`k^iD1f*Q%F$<8R}T+ z80-_X2kgp>dG`7&cDSTu`0~FQ8y(SJg|^a3?&=zj?%v&sJfraS?A8pZjZ!vu?T5x{ zEBscRz0AR2FtMuI@{mS$3xqA&5n)^OlHD4 zWE?FXlHMn-)OZiF!&+OEvi~YW0PvJP6?S|bxa9bny48H|W-3&0pf~e9`=M>*4q0e*KT= zgRNhpDdpRVZeT#}vMmuxZEq-?uDH0Q^fMa?%OIQ+5(x_=fWZIJkR5O*tkpv^_ zwZ}FDLlfq9_y`ndh+zGDHmkv0q^y`PCk_@OuF{3HJ`5|<`7CNTi;kL|cX$YL=OzKX$u}R#f}bv!)ZAEUY_4BaWQClTLWdhKJ`V}xivAW;aT=1 zAyHXLlRbYB#DZ(8dfBUB7>cyXEj%WB^~24TR?z4Dc*e+x=bgzMg?qS$kH8wCcH4KT zp1|}c;ain8u89oHAzbzwy(!Qp?1IHffIE`}UG?{>UVJZmN^ z=+affui1xPK>GX82>1Hwl)J!v1L17zD;&uSR(F z)ZsVOu!}$M((!ro;-A3P?_e_Y7Gc!X1fCA4$Yb&3+e5eIz5}tx4-^K8s1QvjJIB8P z3?a?|}O6asE;MbdO7tHWp!jgE}=rr!10z-&rx&v~oU3F6hFN7g3uL z5wXL<8bAbwpXbGOZQoCL>xWgqf_6!t9T0f@G~Xa`Ax z`jLL|83_i~^L2kQ{K8!8aJ*>m{gflYLP>3tN;9A{tm=EHZW`;3tP979NvKI(gpxGR zMSz-oROiW`-SztC{&pG3l5W%r(h%z_lnA3E5tQ73xo1Y!XD_nc$wE``lA6n6glGY$ zum=7MPeJJ<`I8;ZJs1EVPOq~FPXU-P#)`;V3bSS8Tk5G8y2U$OzQ)JD-KRAO^J-#A zv(+CIBuCEj;+B7}7D>eb$ccdc1sYvib8_+qcu8(OqFZEbxe_%C%h1=9z1I{1QblL} z-giAS;4mYN>B{9MZH2T=1?3rRsTF3+u^}3y+wb10B~TNy?FG}G^CrO1^X=p3R6_h* zcwmL1VkFu}-Xd1D)4I07Q><*Fs#^B$=otNOz3|hBbOl$uIi2y6k+0EMO`Z|_4ykrwwi<`2-vb? z86~gw8`-QJ5ycqEu0TIZ>IPwBcsVr^rAJ*6x%i+K zwA{MUq*V_dOe9mo%K?m<)Bo-VUgVDto90^Ea2?MyvY#Re&5YHXl`psY8}Fp&&qaKt z$34B-2|FJ$x*xZ$MP3Y>nCMK$B+IMRd90JG#x~`Tek_Qr*b8ITVpt?}UEX>Iobu)+ zkd2MnDbN@7QH?69#I+fe>3bKKB4sH?VU44pA*$i>yxY_sJ-?-dNuo(f;$oH4$0Xhn z7BO$XiDq=}gm8f+ymx*4Z-#wtX7YqZrw<$jt43nD70B>vTrlE4f0L-YbXLb3waBeG zJaQ4psI}@^HQWmD@uwPhZ(u-_7y4VZ4dsZNH_KSrNYwZa)=GQje^iMm?p;5R-|}jl zm}^J3hU^HG7c_<)(0wpp!%uuJ$2#l_JLV;Sa{;WlMLm!ON?o;Nz1c zd6j42gV@UtH?3vxbke1>s?iRf zf(B)ba;B7yKuj>BG3VocfqQ4yO^1HMPp}Y2C&v-rDMki!xwXt<_{N##s#A9$0eAlM zmUK5K&{NkGLA;~zGzJlLnB3vHHU85lZj3xp9Cr-R*l1UXVtKJ!e%0z0bN z9p`DH#PVDCT{-qcDhSh@k|&jOP##vJjd9n#$)`QzP^8p(N#s+OV9t))h>>pw2GBbq zFWgpRXkkeF_Kbb&d@o&M|CHUWlx5SELQX82gu-ogKg?LE<*vi(JEx43sZk1K=2iJa zeF091|6ZA(Ph=x(m#9urEB9cZUD`@@onQB3OcQfuD-%S`R!sw!9=>Kk>V2gY{;~oS z)s`ixrcN|PkSEQxIV(gwtY)klc}mjK!&<&m@aQ|Mz*WB^jgb)gp4i-Z@wN<`Od4fV z9WvI}upc{zYaWSNaOHBv=PJS4E^SZml+(o8BDpok9bXA0drP4Z_fuF2f#H+w?X^sK zM5~kwJ?n4Dw)`Vv3qhy^;6G!LD3s>WqVQ79!PQ8wQ~jf`I?IjkT;VTI$Ey|(zrGlq z%vFC!t3wGmg(_VLYgO2Yf;1`ZKP^VAhVV%y7c@x*MMkZ{Mp6p{V}l#nJ)Yhg?n;%C z&6YE_e5X2>H%${pzBg2KR1$6e9g0U3bCFG={8~(qY4-*5W9F#hHQc>9 zb+q(qB4JYhjuRdhS2A1(d5|=(Z*9c}1jFd8^YCwI$8fS{xEN;8>WbSh1H4><_b=e3 zUFP0(`#KLyzN1Hj+v}Glt0*ThVQ`43yQY+)@l8AWc+uhf5`)WS|+=*E7{k{7^i z{39xCRoYFkHpe`0_3sgxz2!|p*XFu_N-j*kuq)5U-)CfNr~8LpS@vd=u5K3{)AE&{ zj?0VV`Ty@R9bw2N4x^NPHbO3$hJ{stnA(TOB;GDd|x!#b)3xG=oZG8ufpd4s@(L*8lL?g5XRCwj2;>~-sBfWqE?-7caWDT zaaEBx1bDdT!o@tV zs3h$KEC5J4a~KP`cNIyImbp&gap{lRksh|}-)hpOZT|jxtP)3nNx$t^@{AvfeXY>_ zJjUDYFs1C8KENF8UgW;bYa-hjtaMx1P%bX`O@Yk+cTIa&*@TxjgZ}i}?pvwj+rj$3 zm$yrz_lfA<&m7^`DGa>sYkWTvL!*N|=ew=iz?ajvf7$`Jr$`uaoYb4^1h7~c)wjnY zc)tS{RA{}Ap+X5;JGjCDv5Ko5g_-)iB{E%0t9H$qwy$CRYx~*qp(gSy-`#Pn%87^x zb>Mi&7s2Bw*=9g_8ffboIe{{NC&x*hJ*uOPSCyKk+&faaZJ*FL7ynIg4;M?+d*0rv zVjUgJ`Eb`7L6ex1Y0E=hW}#-Q6Z_6~h2)FQ2JmWFIQkvLlfp(bJza zk`7g4v7Pz!w)=9M=;TdPUkcl?u?cC=~U3}xziqWtG~i$Pp!j1VH4`?DS3IkzcR7l=EkR(LmI5&@EbtbDfh-y%*;D+hZ;w08w#p(yIVL;%%7)P5Lsm`Q z#)`XgcF6S@9z-e*@I`LWj_9x>*(Ueju})^T28S&`6frfD$aLl#^T#7{g1n2-Pg5$+ zJVUJsufP;!<@Uekf2mQT0fk%$@7+?5G|A`=dNs=-VtwwzI?QUbk^rB~&ug0xel3tq zqVN5ecHMXJoEArlcg%9 zM*1$i%8(AkI)%6u-79{r%62oe$ii}Bd;5chBim-&+29s~!#RTW2d8tLbx$eM4$a{9 z$iw@Go&Sy{<%Zzju(yZSFjS(js=;V{2&%oDUA~&HY;Vskfq}14Z~JUF-4_<=GU?j^ zhmYH@x>s9BMjF?X*Nt2_=R%Jc*fkc1{SSwvLoLF!j(%#ahS9ld;gZN|Fj5dz%^k)5 z(DjFu?I-`2<-pgiy1AiAk2mPS@##F3s?7*JJIHtE%=-QWtmMn z%x{tqo+gIIhdo%eev4tJ763lLmz>LB!makJ#>?rpd(Cp0xq87>Ib*7MlOc;^t%Hd7 z&3*Bm_OkZ=jb4mk6&}a*r~CMwh1G@9Z1X|(G$<|uE^J2FC^m{HmgU#bv(a~Tyyu(U z@4cg)*Vub72`*N15Jz)D4S{mIV|j-VQ_(M#<`zmGaQ)G#u-oBJC}B%#vI+8KP4(~Iw)cMC=lODe zKR>KvY2SY<5hLr7^(5Z{5X6ldX2ug1%8e-m?|wnel7!kSq~09}KFJco^?=>EZ~kd$ z+IO<~17njYW&N~~Q!W@khfc1e9}L?R8mtS!3|bX}b&Y7apbQcVGwf@ln$m}^DYFq$ z$K~nJo%ZV7qhA~8tfm$<&P?BX?Zl`IbSa38uER1hVn{Q@$U~Y)sV?n&+z!ShWkqsP z7hBlLHnU(DmaIQRg^tM9Tn7|X zl8@k0S|h&8KS`vyfQd!`($a;Bg#NsHo@b-@&1m|C_g#g(Spjvf7&hM)hJ2n#Bt1MX z{j<*@(~f)p{r@#aVeG4d7BjSCYpU7;?!plF2bsK$Xz3`D{~HX+M{U6M=Rcp!?N5o` z9^PJ-tgx%E8*%#%NL%mEMUg{nG6T1Z^Vcuory4!KdR{xsONr^Q{!&yx8iVzr{ZQ}L z%$d?y4!C!S6nve}Exf<5|1`=dQXcu0N(**xJHwGYBPg$whknC;wfx#}R{n;EXzjup z@K*dObO1zqb5oEq0aheKAS%^(TmURq7DN*r zw7PXitcqy6&~m}@&jfIyKB4`HA9#NMnEm~4Pe{7d{C11C9tvKUwm1Gg6bcjT!`)r7 ze1E?^cla3Dew*=sk#UHNcLOBlSOYs5$4jUy(@<(}zUnqFbTl=yqij9_aN-rxTw~VX z=2%=46`C*fIKiqA!k}a%EkF@##YmZ9XkY`)m#A-bA@3ldb z!8bm<;TP&mm`S;B8N7iyr7;oB5}pNufmbMQFr`vz2FC^B>#5;_U_iN#v-`)+$5=Nz zaonGCGMT<;)ObqL5&bhUSVuQ*7O^3{y2hx}jSrj4WC)sDqHl+K+eCHE7WVVb-wdhK zj@#1rtpm@+{2Mhlr>*pF59#StrDqD{V<6ZOF=>Bpsxu{sgJ+RhtggB>!(plwkPc+H zuAF8ePx0)(nPj=$%;7#s@LU-s70k?XRj=_Q1E<;LA{4X zB$WWd|5$&G`U8oaS5xgogcsk6k0qimH^3y8V3{yd^mVK)I?SELc`zOiiS@_un2o1Z zv~c8PAATD(qeeSaDR>E24tS*9COkW+51)*j+%dw=sm5|1UluVs#@*wj=@$;5Y--c~ z#N~Z*a*AFwJLKDK6O2E}4mzaLEaBBUFx9(v;m+QNVBJldSyN4OnCEG6Ayvc7iC|Do zOZH2bJOI?>aa#E8a9V1tfE%4G&87cfj)uKBYPa z34;Sl!=f){c;ld3I(S)s61L^~)wgCo3P@SmM2>)^h6>LgxyDT|(~Z1ItX!r5O>2>M zl_ZGV7XH7F-_rd6p!Fjyx5>}5shq^T5D|se@J2rL^J}x(xcwz;o!a&_yP2wuA@1SQ zRy)7y>3o^E+U&VwYB2rxn0gXbd+?;-bS2Aj&!Vj~Gl*9OcZS;J3{C7s?XQb@-upUz z>+$K>w9Vh|%)Sk)1Sm>pm)_>PBk!Ddk!hd!1uTY1Wzu2y6AX_%9gR;FR z5p*`WDtRp`4Rls~MqNhND6rY-esMLQVyMrw$EMjo*xTCa_v7b#!eLe$MB`2W@~QTA zixBDt8Fq7fU5ZNnq`hq$fAGEtI@+qO)U^T1L~DLpBRCd!Q_ZMa(x@zl0%}Y+N&K$u z?t%rMV;YBx62CNQTkLEr%t}IyyVE@$wVoZ1S}Su=WIO%gM6}fU%DXNn-w$jj5*~MFl_Iaw1e^ zxM9-q>;-+`LCpEj^2*l3*gRTMBk(j`Ov^@HAsFJZ7?|)5Hua$p8)c+6dI{)+$%WEu zq7by_x}gGT(TgI24H3*2><&eK;hL0%fK9OOH~eIieyF0c;Lk!yeB19IPXB(jcL>(- zs0K|64>CL<1*x7(Uvr^oJ>o8@tamb-*#ay0zsY2Xs2Xn)wwr~(QV4-Kd&Db=H0?H^7FRMGMk>o*2? zYKYp36shdDQ*FF;0-8ws%7TAfmn z)BA?7gk%myd(-uU5%t0UAVVMLwFT1zli3k>N>6R9$a-^D!fc!}S3g`fY8Jj1z$SYo zCB_#*TQbw4QiUV0cfwvmLkuZ{EdmCzL?~HJyMkGPiw*%|sk-F_Iu7oy_oRK5e_t6%p4V#9c z)(3UhvxOfeyo*r?JF!`G?(TObLaT57#hUniK9KxR?0>xi7II&ufC+-*JT+hQN0NcT zH&$sVL#O>FU@J53-G5`JMh>O_{hLXzPaXCZs?jNDdnD4O)Dh{$$ z%-&f1!8!f(;c|5q&Z!M`+AqF`aW7T-O2eC-Dhy%;0a~a6(-c-xKyf{vO@{5qrb<$B_*%G8x!3MjYArl zDYK48B$d+MjxJwD%P!4WbfbL!Jy`#=xatmgF$j3i899T<^=or)y@5PwN3zs^AIyDw z>%Ctz@O-N@Ajm7c7M~^a=p)J?^Ayj&R+4ysR#uAE2bM~Lcsj4o;f_Vm`D?+F@GM{^SSKbIGH+;c1#_D z>>{1@bpil7jeX6Fy&2e(1-mPZ-DmN>3=E{S*w6^B~iW|4o;)x{(c(KHN zwkUya4$a#C*XQc7y0Gb8xQm?$rbs*&%ENj?U9cr0ezS(~QXD`VNSLOU=HSRVc=&L3 zbMboH(xElZb{umBJ&(4oRAPyWrH_UcZ$y|CXoRaYm%v$vsojr{tNe2$?J_SjW`sxX z+8PDL+tV@d4(=7(YT}n@JQvs)erOw#?xy|Kl8}#u!_~Z9a8OYPyQ`r!xz|$|nh%G~ zM9{i+8my>wLpX&hDir#T3QWveBhT17v@i%nK1p`h z=nh`)?aUv25QcTtZ~2QH-rS}>zY&H(d4JX}reeHO^4*;O=5KZq+r1@0G{I@ET!g)6 zo&TZia(?fsa=o^-v^d=bKS*I5S<0#ug2DvCh$?wAEPrre$GP$Ute=cJEoqzLZfwv7 zRl!DqyrN~qhC`Zy7y32Jpcq7jg*NS#ux1BgaKi>*85Tr2;UmX^m4cCqF4s$U)IGiJs~DY?qtNF=_Bo zqN#0mf1B^tkxH}XTKs`%imATZfRKk|iC@X)T?PX#8_E0u-t&+1E~eI1znj*loEwsg zHW&m;n2%;EgsqgXpC4LpXaWhs&wm)+?N7#Bd{c}c;fbd=z*alnvN9e(>E(aZ=zY1K zCF$W`$>Nh;J~HuY+euwkOBs2Nxw|K*{qZlx;RB~uzl(Pi8Yl`!BoC_?5jJ%ra$eTk zn1Q;|UD)tg#qJOR{u6e+Mj3w9&_8(Cu3cC4Tukji30|Is+$p-G5_J}NMO0a={2&HF z%e<5S`1R&*GRLXqoLgDu^`*!nWea*5u>>2q%b+KcdC}GCTH3?*!f&;U*NK{axe7^{zXpH2bZZEF4ySJUHo9C1G+-|Ei!j{7{qxpS2#_+agKbI?aoYnS&Y%;8=E@g zm?DJr4oxGnu7^)?_7wUkXD3MM8s5^XBVQo?&tBx3xOeTaiFhS_pSW++<3apHKe>}$ z6tzt`$EQl>8GI4?1+kJ~(p*z-{}KAG(vdHwvG~AdiaUSQEgrGUvA>xg`xo_Vp45s_ zn)h_`zf~(obqw{yfuaN?OO~Tu#aEo8Exg>V{V10#1r~h6mEXStd7JXZ>zf6aIW$|4 z_51qO3E;ApyANPR<-B^Ww0AFP;2pv}3F12fC};a=LKypErtYf@;xc$&+sxaPJZ8$L z$cVI}_g5alRMhMm(AvVvL_6U>aqE?;8;1(H_ZOanAj`X``f6Cxb^&A+-r>8!!kxhA% z1Zw|X`LN5L$N0_A=QGusj{}Mg6-?sffKYf0jof6dU zPR;1$AeTzjI&Vq?pds-3q9f7%aIAA-rw?}kzT*ZfsxviXOREX@ux)iVG)?H1BDAN6 zlOHEh2tw@G7b0HT54Zp>U0@`0_yuO5dPEhJw96`3OJe0#wzT3>)kCeL8AM3QspUe^ z$+S}FXr_y2)2Q~O3%-c(Kn-H*Tpz0MByX`%EZ|s{7i8q5^q`DsoBA!mjk@4>>*3OT zIJ)RO6T@$=GP5WF*9RycR?qX>EstZ%+rF^)fT!wrW%^Qkm7clffPWLrpBlZl2oOFg zjuQC-;wG{eP?7jZcz^WGBJlyW1TX->UR(O}DAYHgUr=l<`u8Zg1a0ck~>B@?Uu9<{u;O86!_ z!V=lwLB)W;QB?{KAg>2n1Zjm5Ozk<&aq#rN@4ukxz?hcXvi9F4b_XYJZzdH|8)|H8e&QEE1_|x8Xa|8Zpk0TmXVvoI zV|lsSABsoDLHAYJh`diUu50Ihhi3@3%9%9aa$9AbQKeVmS zFc{yb>5fZrC#H-H0nvu7uxWOS)&*(i!7q-W*kGn}U2zpC*&Se7l}sPHj}EH1u##fG{$Vowh&P__mmm)jxlR+p!sVT6=?n#G8}0FcjiZz}|jvyT8r z#4FtB zknvJiGw@@^A?2>J!k64>jJ7a|RTZCt78e|kQ#?YgS%6YC0t+BBFIA_%gjzR%iYE*k zVrXm%r@o^~6bL(#KvlGaXv@oHZ=1ln-t*^JUY^7irj~MSb?ZB`6$J$%XJ#|^amXd{ zCAcQY=kob{OM=as9G_hCiI31;tBW{iwPnVoY3F}M@B`iw0>s9vHa!$7l-nSjI?FBF zOhYWt7!)Cu-$yNN{c-XZ@TTw;%kLgh=l3|hTKQ~N93 zJlh>$Qtu=Jo;&XZ|Mk}WJNaw$xmOG$^_lFvwVSy+F?L!Tu#50{eZ2iVcW$2+DU5=J zDIEbJjGwr1iGOad_Hc7{UWTKJv<8yYDI_Cp_Na_eFcJk{&8DjrtruU}dBnhsYST_p zqhg4qivioqho2}bC#AzgL*-N}Z#@uMlj;n^rHEJwZY#pwxOOAB=5ah1VY2cgqk@Zk%UJk(30qR80B;8sU_Qxqp} zNd4{nsI(XifBO5K1O_`gwMp!)Ka8 zHSi7Gjs`0&(@2>XBR!aGiEAzpf3QOW6CO=Ki0gNLJ&U~FSvFnuH@W3|iPh)mX<~I0 z`4iU#BKb*EkP%KdrdAN8m8ZS2QS>Dq`wJjtJT~@{%gFQA6#qwZ*sLw8X zBK&5Gv!o_hc%2a1-oM;@biLG$_>ZQVn3yOg%ZSs3UQOm{pvgH-?U+B5>V-uG63e%n zHU=gn1+}9u{=2hRcgD zOdtVyY-zZjd+XGDg%DgtCatYP4YaR^oAu}Osz>(!ZLVdRH-;E4>AiG-GTL{EEh_9< zbx=EaAyi|%-cK-}U*@ETS`z*oeO<(!+m`lEM>CAJSQ_&oOA%9&cI8JPXTA;P7kDW2 zoQnd|p@^*vF(edIog+pP0^kWT!wj%CIB7Y}{a{dhQ)!11Eo?2{RHb6@J~hPPUgQ-# zMNtYJqEwRG{VBDxP%c#fs^HznRJxT@SLHYUMkdNE8;FKj5LAe7hJiI6uX%cU0_{jt z_yrI6vJXLkYfH4(ou2F~90xpBpS@opC8TAU_oprLb_w`CSEBSh+SCRdUZhT6iFZ@F9U^!lIys2C+;{ zf?)LYY9H69j)1=xP&rfl_2Ee^d)R0qVDY>Im`ZtI8r(OpXJZm1y8f@H_pf8t^_t8$ ztTS>s9v~GH#`=f~CCwx(VJO*w11X4d8mtmaS>CQxq%X{*1rBq!@6GME)nJ&k=-Kn2 zizV{%p>a7XUTu>mTLO|rXlsyF6f|Oy)o)s0MsS)2xa8XQ`kH%rXikM4kCmP2B3E)L z>*q*|Z4v4LSm@3^UJdrS0@K}ZZrARD)sd-hTOqNU(1F#z)FBn{W9qFtpc{h$TvPDCmpl(d}Tv&0Fc9^K;p`!gvv@&U9(w{ZA z5Xr9?&wCYR1dUX1RF+K*B4fiLzi%Q+)XNq2#RkxUp_bz?qOO$~DGvw^Ou>5v`bI2P zZ|HvAbUs|v#UapV^lC0rv*${F*eh@}1$I+~I>SGejz^cG|jpGxoD zSxwffD?cEx>a6rSWOkPJJ4S0OjZ1cCtyv!y-RiXDDv%OP!gpLQT3Cs&_u2*Z4 z-LtouVWHW4mqcXMw&@l{qqNc%XB1ta!bRCQ5KW+rB!zwkFVg!ewOVp@Zx`**D>&*2 z=;*%{2cpZ8ev^bi+Yy$-yWNVV4jqxSdoL%ekYS;?8PF)@;!m%64=0)b>;6OX^%x?t z{YxTL9Uh!m`z0nhKiGQDX-3vwUl`bess<}--^T;s%rHCgpOumP)bV#ttH-T#IZYpF zYBLK5gB6N(j(Gr|(9)Hw^rcWv5FMOF$LoZ06^gF-VqO)HCWM|l&xy?muW<)su;Wsk z7D$bnsj6Ac^TMa=P~TH{FkZoeYArpDpkJ4{Z$=B{n^*HEpb-iF6Fvm*6kti%DI6Sj4U;ksnee z)0w?BHa7Mil^B)U@O8`iVJ3fj*f2yMxabP6X7O8P_fFn@UGdu)Ku50SHOOD#db(NJk*`o z;Z{>qOQyx6PIaZitHpTExP&PS0<$qh8iby`T0!^`Ey_g7GS7`|LsR}fDY(t>q=RtVpFXM5! zYJc+xV%K43)7B1$jnQN(X(SNTIV2HaayZh66Uf%rJGyIE4=wLP%f)X{l(D9*7@-w_ zBneqTP9g+R)N8k7+w%eFpJ6qc1x&j|9@3-r$hPo$R%(Nm9__hNJCc6n~J+lF`pxdc$Mi0~qtfaE%zCD3% zt^8-Lug~nJKUxx9tgw7CC0jt3C1!1i`-^mzf`y%w;mcXme3Kc!7nXwC=E@>T&F{l| za7T72$8x#TPxlHZj`wQ!{v86EU=1t#D(W(+Z27H*NoiXETtO?@Be>*(7iQLla6`wA z20d7+Jx3@I6_x%OzDKmZ&p7aqa30T`eKN(UnLhPfhTtp;m$_0Tb1|(F6mowBejsc8 zqh#>;q%IVl2sjxq!`;9(NRCRbI5CuA-d@4yCm%88U_R0PAHn`>1W&&Z|20zv%8h&e zM#L6JNO99q`&&^A@FbxUsng;9NO_l}zhE2gK2PELnQH}KJ1!LHKlZ-~JhnHBUVg4; z7uyxx3UD~Mr#CI#UijkBQsBZ~IiIhumB3Hgy)(yY+Es{MbK^S%=VHI8r5g<2^1hy* zl;Wof!xxYeCW`@@p~Ycm(W|WJk-Nf!qUEw8k}b?9#MQ{i$to%a8nJ?Ku`sBx#wEi| zUv2r6-fXF*+~>yRdB5DN4|5DAS@*ijX-u?WX8~FSUB5WM{y07?NdVRuvgv>s{}2>O zCJ>=DTODK%f8aqyMv$QfEeXJV%fWmMm+Ra{e>S9)FuKgtMh`<&l>vykS}Gtm>c z+M2$8NBPS~;>+1#;Pc?(5dC|Pn>C_1d7L&aTM@k-BSvXfGz1*2o(qubftv~fr6Ykr zi0liGjS=wWVtcZ`9cTWmq#KEhK%2tP!NxkG*~Wk0Y{Y2}O!n}Eynv|rQsTfhLA6ck zu4O7;(B+x8@wJre!$P{R6v(0^m8GmOu=XY&a?EIKX%qyi+FHZ70jQUu!l=~r# zYfBpB8<8KvRvlN)@29R02YYxC)55eCwVFk{zP)Zg8ooL$@-k&c0)tH~J7JrSN6h$l zocJaog(xV+$?d$663D?D3Fn7zZ^!P>ZvNg{yFYk3y_m9hhB8+Ti4IwE;OFTVg8DLQ zIO*^R#Kuv-Ma-@kG8S9$;y=nOK$n&V&(Gfszr4J|T)GA&-stN)$St3{TYyuM8>gA~ z!j_9WxnDsxtjFm9C#D*k+*ay0m!ON_kYV!uJ4vCyL_j+kw%UsO7S(S#)!^7vH7RX+ zd*%_9r+Z_n_RddM@tERj&C^1bSbmN}$hHfLgMY0*i^7#~Bazk2n~q&qZv2)5JjwPM zz7yiAFZ zyso>mDZlw5Zu92Zc*BZH3f;pJ_qZP&(Q=K-U?NOz4R15B=$SNDaZOmaBWEIUQB|Z_ zvaqJ1YLS;G&`T;Nx2Zt}v9bW#O{)M668`$j4}9WO+f^-1Diw=PpX$!H|CA z#<5(Q{1For%OH1=L{j$DxijZc)jCD9eq#)dNw9iLWpv)gwauK{st}${kG7L17PYN*n7BJbDf2jB~5%rwS`7r)Ko`4aNZcfZK z&$$m5Z?;#NZMa!!*tsmNjJTwG=O6tqxoM$5qPG)}01~p977UDlR80tS$Z!<^mUlFc z2?CD+p$$2zlTT@!C!?6^VVM%B7&ft<9mt#O8E6{?VrT|N{e@&;89)@0f{o7$8EyVd z2`Gtvu!tn0kZSrh_cZ$5p-B0{wO6qF#UkJ?d)xcCmL&WB{n+4Zk{PvoZ%Tw^s-VmJ z?||Z^ALV+h)Ii?*^F6iaF|Oy|p+*Nt?fyDB-cSlQLX&1h4BB)s(~<%(|ENO)g%$zZ zEa~Ahkw9f!6f#({FRdtKC`rNu1z`@6@lCo9+^^qr8Pa#gs7XQL8dF!$c%#rCeX-HT zW3=_|)REYJR}!K?6jG$i4z)H0tWnpH|F<`q`UIPShFZC_&$ z43Xt3FPq#MRxv!U3_eLr_Y2dPIxmr1Q?i^&5}-O=I#GGTXmT3CRjc-~#v#UlM zg)D^D&?Zqe(NymsgU3CB$AUMz-_+Ot>SO2rV9Tb~J&eM`KXMjVmgV7Df()Cb(WqsG z*C9XN?Mq2q1##hJm5$8vuf@yeISOQyn$Hso|VCT?9!n^X^>3v_R zCUURw$a>XAJ*7Ny6p=K;um}WSdRxDF`zO9{wFEh>>zhynV ze=}6dZ_tFbukh5uTpl)8$C}u|sS=#DP`MFPQzxS*14g1wkaC@i8dKSC)Q$wfj+Yth zxE2HAxiIFm2I=XAIhSlGp+#Yl=bSd0rBXeG?6ZoV_<|cL`CL|EkA_N0t$3waY>k)@ zcoFCQVK>AOB{;S*0-LQ6LAe*!@Bdr)^)69^1KBnQ*x3060p22nVpnP>&T)-eF4qQg zlmJ^&k}$`D_!~9P*19pGDLD-Kyoz2&Lv3@dz};FiF#f2~hZ0$woRw5Q&6ULQUy_4W zZStzZyE>0(VTC|7q6CDTh1rA8_S^aPzo+e2eQquPOS8`-n~yzzE53F%7@zp#{i}b; z{!g`+5?|BdJ?2mD?dRJGY-*GUZyxmEK2+37PUC11I4BK~dScnXdOJF47K<0Wg*&iw zSh7%RqA++s*p|nS4WM)wRL8F#>vi7)MW3y{($AqUjYc-rnjw5+097xE#%2=DPiuJc zI-OXVhj;iq{^Nx%Qi+~E-xBt+k(v-}@NNyn=wf!FJL_@(cp~UGxxIT6#KBCoj1$tN;iXy$+{Zl(s(G ze%Y-fd$!2K+4-tJI1vWr^=XNM-0Gg01u;kOmmd zI;5VSFgiw0zJMkOiH;fwCH@V*Sop9>I)8HrxxscNRe0@vgWrXX<=BFU!07KEoAb$5 z$<+K`fZcacu!StpVgmz+PDZLc_}rqmuf6QKsac&)ju<;`7P1iE3?$=JbO9{1CZ#Ka z6ZccV7X>jZR@G}7w-4Q-D;%XMIC)_)I}BW~O=>h$lyML}loh!*pkvBGOu!!%!rzeTZaY)H_%w3#2QWpCE&CN(elb_yP)pF+A{i31!xe_&WJoe=1Bc~V>?@~f%tHRX1d_IUp4tBa=sbTr8l<~#(14_U|;%d|6SV9os89|s?E#roGJC9>8K;! zRuRF(D|IC=I-w5S+%Ci(xhgPj;I(AZqH?jK!a3edO|N#jv5O(id04y{5?qA?dPotX zND+dZ%`_T}vP@{;QdNb~Snwm(4g;HGk%4sF+5}V(v7i!Cr8T zH#)pfJ~z|c(yH^?Ae@myGBsyBkLUjwy(&KB0jb4JU0~!qU|}nFfjmQ8D#72YT>q;D zm~J9&d$rE^BEw3B7#y5`=5~9$I1#PS{p)Fdq^3Ko2Dy+=f9Jjv*lb;^sbPb+T(|5K zC$Q{;n0c3YzPgz-8GP)+P(VaMT!Dg!vG0T8z^}O!(f9(J*WN{@ZlRBLFWnj@Vq&4C zb33S+Q)LaK!0^IH6bwztN&mZW2(U?00DQUr{i44ny{4My2pYWYGI?d`GW+HcBPcM% zSKtdDq^;0&j;3iEb!Iz%nH?@a!UJw*K975!mxoC{gd<9bV(t>A+-DgBWvj3EO7KLLeE_4S~Y4NYI!#KIg}!iujBL_I4e|y z5Nni|aKp4AHZ(~j$)M%)iPe2r?BeQvzfx2{JZ9FdryL543~Seyhqr~aL&vFOU>b!$ z1}?PST8;kx(LHLe@gpM$W(P8BF-cl3CVI#J3h>)rSd7=_-(UZj@0h9!tXv~BkSh$- z;A(CxHKlbwr80E2%`~Ul)JP*Yi7VZlJbHaUZ;qmvw*o#6kB*2Qp9rPd?}q4TsI`eI z71alK)6#{jAeCSdWp`Ag^|)lk3thR0ySsFKUlUUW-%d{sqfB{+9YMAL^1dkecoPvl z+(xLX5DX8WgNa4_@kQwV6wvUJWlWJQQV%qcp0<(3T`%>}O5FE+`m%$LY9y9k9cqhz zXM(_YqblI7zZyXYyQ$jOs2r8fu*Oxse|kY|un0g8>~nF&gbqnixIUn75aROE@lJ80I%+X;$>1y; z>mtgLwi?|aLgR)^(TsSYz+A)_M8&NY!$yoxXh?Z9=SZBBOhlsqu%8#@d28Y2>mlA$CYZm`+#FQuyr}h#q<}ti z)XB@PnDbAlk?&-SeJ}HJpE5CDDzeRW#y#7!f54T{O*@B=RoiEdb5I4W1GC4~UGc^< z_iuXW1q~QA$UXA4rJCUyROo_iqmc)_tTqUfS-V8Zu+q+NB5+60uV|5cM~o}1D=>p# z(k2J1=Z6+TVDypXj!DgDM$@bWdG=r17=I{#tgeA>FA#k5x?3E@~H$6nnzYPQx45r$%y>+z=`gl?d1oy@NTM_c0S&#Sl2&ku#qxX*{$&&`wE zcZ?U9-i;|7?oRT`hEOE#&yUT=+|Q^0>dwz2g^z2&PleB$#ZkWctcBm{Va?0Y02ntG zWpd5zeJ|_5NA0F&aQE79NiqT+de$F(Fr;?wp_r15mW|NgcsOe1av<7{u?tE)tH1ss zz5}ql*!mb9UL#D5_VQFUD z_02kC)>Ewx8!xNHwTbp}E zUYa$rCCCf8*2nm~|LvTwbD} zQINRG@jtWJ>ecvfz%Iur_6qjJe5%Cgv}c#R-8*-99c*l(J4K$I?uF}lAjK`+S=w3T zcI(}t#2J5@w^F$x(YiwC(vh}RUJJgj=DvG;9)G5M-~^!i-&ADC*U-rv0m zPTqb#=6)o8UR!^>E~>$oX^*RZUd92q^=aL!#AhyhB&IxT0BQYFjlt6;P9qW>K9O%x z;ramc`-2+i(!H0G7Sh2Y ze}uz|0EaVlO&zUOi+@g2bF@pA;NUXuh;!Phv)|^A4RBV{)VHq0aH0zNg7b?(RJGqM z3bgB&{&Bj!+5frJc602{zWHZ*@FrBdSHs6yy?-iv|9z^ncFX^HFRIhy%H!#2*ge!_ zw`e?%j+TtFfr+ecxH|BvqlXC0$|byeP`Z zKA%wd8)VuGC`mEW1f+W=uK8WKe#4!f|U4IB^)q^dfpNJ6xgAz?J6 z#QBV5Ct9rh%l6EJsAuxC+Acb5KD%{^6V0 zos3+qyGMh&?{d#=B@f+v|3tOTSo@t&SAS3(QOC^E+^R!;(hxC7XBPpZrM zHW_#2Vo$SxK?;6W`P}zay_xyc9S*A!{}TOM9VFOh*KR#Ek3U`Che(B>2!Rb1>UrDJ zFNT^V?oaC%o9+RP>kLu*+NvlUQN6f2I0C+0mNx>4+atW>pl=B?DgbGZ@QQUX}oRf%N+7c%n)DHR6M6>c1Tu_6A z6^$)_+V&?y%IyfN2SK|+r|fAd3XDrR5PMpD&38nb`0ITB!R}8iJNczx$PhuKfW^Z#VY|D?-TwDTv(w(cI4H3BF*Q?)Sfrn_#L4Te=<5Ondeo&a_3j-J@+V=F@>ac zTG?qEyxq^=FzJQ+ooy`@k`&Lw!v~#)M#xSxD`t%rL`xG0lOboxp-_VJLz|Q+P@G8L zl0_0yvP2p)+x6iWh~99Z2eKk|^EoM2xi$m%vhg^% zzvQP@>9S`o_idR$HiI>^VZb~*9Ej4_Nwnp+(%Z|oWoO#BEGG<;{t5ld2EwiuZN5>DMb|@oapvvF=&T(3az_p?SqJCS4v@X}KwXRRI8ZX1njzP}DCLxO&RFTYj6AWigPTnuM z@rTy!NNW^I@J~PPetk^M<|5(O0M6~uplfFsJPMAQB3juLZZ0k5eCOO0$?lmDEQETO z4wpwfFKc$a)bHp?IklA^s!jDOwT!9M=k=^NMl=M}w)kcAqr&j&5nSEVtv4xg9A2uCiV5IE4t#8JdhvEA@Q>{7xx-qQC-HGJMpkM1(g>X}4wZ@iK%SH|{eV#JD)80~KIpHt}2sPh8(x-P+zDz3+q5 z=b@cj<8%vHCWX4h-wIV8{tN0@(%$LQX7i7(eM4o|AthHPiGPc3N{wCyjjRoYb5hHrl@M3UF#z?zx8&pP*%z|cYcWlo& zV>=Tr!1Au@6(%y3NN9nOS{{#a?^h~Z#9wDzl3~#Jz1YpLY~TFFqvXNVhE9kS32i7! zaDkVn#{pmnkp&s%;h9I615_7-1{eYrIQoU15lepLJl||6l&rcQiL*}{>?g8P|BQBy zc1FZ7r9-cIZ=HIyGC3s1Q;)=Gl1Iw=nRY3F%7m<5w~={O&#@Y2%5IkTL&;a9o{I04m3eR z9qs6WRSG#efeJWT-`qt@h|!fo@qa-4#iRr?GprBcF$o#8?!z@(Wtb?j;(8d1-h{pP zX6qae*BHE6=v3u|QTU+;Ffsh|oqfT?0-6&Q4{b4!2O5=A?D(tEaDHHki;oC~$@n4x zxP8^`o1DMXQanwE@(aCY!QuDOs}AH6 zSTqk_I5KBo5~0E<9M>oh#8nLoFk!`!sK}qEWk1;euJ8`5(X~DEwRvl30wbK|8Vjn` z>-F}H+WkJ=y?h!wI(^!@+dE(C^aLEW;#Faj*&jsdRK}Ua55rKC`k0jduu3YzP5$P< z)7S6n>d@}$%Fyk}>S@c;Gbp`7U|`xM93{I<8cC<+{0MOqDoFD-w*R@%+4x3MZsYd% zc}-p=?ZQ^-T;S`3?QeQ8NLJKxk84Al3JHE%0ei>RVI1zZ?Y%*1`_?8#SA&qveq^## zLTNX`Z%X{hI+SH>?4@wN@Mv^06wVOZ>Nfaqu3RNAu&ETE)+t>*Ls4ioC21(EB!&y= zyEC+Mpxs^C4#4pLW9l8l;|$-Y;oaD_8YfL-tFar~wv9#`+qN1zY1B9yv$1WfvEKat zdY@0b`}N-IIPbY;=A1c+SV5m>>Cu*C0l*xnwD#ZnmY=@t$}gVDPt~UJ9cG2cXmOM+ z0pX*SguexYD#Y+@@}Z>yc0gd9O4LW=h?jY%#_DE1K6|h|{({YVFxh<#_jBP5ojf)c zDN3qZY6JzjS<^E^FDb0EjDAK)wxW!{zN=|b9%Y`a9j}aqOYUS{x{*MyEod8U7kER| zCV8?=#0{a*0DucWom2p{PJFTazC5jUOvVF|6Fd35AcPQ0CVu~W?E7(UjEhPh*kyAc zG*M&_G=~z+-YTfLUMqUIiOvl;rBFA1V5F~JJ3~cnp8)%H)5m62tbs{JcS)MVuz&5e z8q+#~*aVrGRkt%eB1T{eAXtV)17t`?N$bi{L3NoLa^fnD0pysS!xFdbSv1STZP{zC z=>`)_8%Vc#$*gL>tazntTn&U!B9&g2NLN2aIx80Yi~ z^s7jmqwu&;#x>7F!$b}3ffq&GF_N&vg5OI>I?s4OFO-OF|IdX)=6lbZa51nT@as|# zPnmKeydpkEpS>RCnFJ)0+P(@ZYbBkTWNZYjwt4ocfBnPBonHC1@`A-cy5KO!rijZm z{a?stLRCKcO_DvKAzv-*$gL&iu;3nXvhi`GoBHRZicf`NBaraVHTRdPq-&@md>D#f z__Vc5%PBGxWZ`{8>G3U~!4n0%f%S~Wg#y6l7cfUY2B|iiwQ02{oSaofhN+AUqSRVX+1$Ct%62zxF4(BiqdrZk7T^I?)Cq!bv@O{9ME z{N38x>X*dCXyA8qZ0MKK-7&ZWq06SrQTdtV_qo!@0Zg~NpJ&r5p7HwAIs58;@>zCp zO|(^bf5Qp0HE68OovfHn6(}1KZ8O>go$9@2>)6tF4&#Bk8t38OuFyr_Kr9PoEsJsn zfQ4KVZaUB+FGlb_gq1Fabu%|FRtpdYQ?{qy@RvS?*OrXXq_ygA8HYc?sTeAXDyv}? zgeP&rl+&O!P4}47popnjxVnZS{c*)mSQ+9PKk|xRWnahdnIDQ_f|0RC^*Y;wLH-ND z_o-9u~GH8#EFMg@vW_c{_iMk;+JBWS9o-Z|+(GG->! zV&=S;Ac_5vrk(gQJsfx7*R?gq!&sW$*;{HNYo0z;pKi$8KMdvr$wTWH83sYKg|HM~ zCwwYvTh?PvEtpL)|L{8K(0UGsoY}=BK{gZ9)e}3LPNtC@5JF;5RHydHL8s*Q!emg^ zql+A1ol<|k0czFL23?yaaM#LOt!NW{9O{6R9?t4bD^n$h?e|<;Av7RRAmG6bMy41L zkgZaO5tUG1XKjoSvHutE1j+P7cq1ISY7|D2e>icP)PUR1Zhp-&@vzb7Hy(;b(DoV? z#Z})l9v(!Hd}NJHm=8OO2WZ$>3%qm&Bi_gafGZQBw%}RO&T`K}NF+`l+tPH7<3nCK zM$>a(%5>p%LrJ|iJ4BRd!bkf*EY#`Oe*(NftsvM!=m^@)DKCod`6?7rfW-~Vsu>cz zjRl47EU;iy!_*QU9^Uoj`$@drG5jhCfU{`4W+*Y#mQy`qU&h6*po%3tTUes^7^+T& zMWjL_(t%(`rw{>>o2a;Blf?reaA(#eZcTY_gYXa1uJFrp;l9u?hLK)nFMbKq233Nr zeCPcSx?j53(D-1$&oSA;kZ8%6q4=`GP%5e^Rb2D-O|Oqn*W26M2fN@Q)R(Mw@J)ek zty@dpFD>iTHcFS=Im+ZoD!=$DS6r!}%z3KA7^`(vNZT-|r z=l0n*rC4um>}B5(?-1H~N?l+`GA;hNA&i!&$al?@d@&jMHNY}j5zC+`zQH4|N(O`D zQ(tF?tp51=K2#D>5WMqZ-MJJyd~EOBnp1)b7X#@O?vrW_AF?9ukTL)QMe3Kkq@;=a zKQ}sS`f!xafrnf#Kq#SW3fg*vXrVngSuBdA(>OD^J(2lz7t|hAMUfo zq1}?tNi{I@FUk-#($0xn)vR1QomfnUBds{V(2!ixQLO*0=XYh~A66>#Pxnta96h;W z2<_7RISuycOd=@uIbSy~IEU0qzK zKy(tcmgN!Owow4RH2J_KXj01@j$>r`xOqmr!KV%#3sE(1&}!wPN3kMy?q69d$s}{j zd^o1zWI$|kBKcIMA>SF-XV<8nTDuzhJ;)PLzMsB7-Nx8F-i5@NrA{R|%GB^FT#vCa zihsn7TR}pl)rdv|C}&Q4BK-mb$*w-Y!o2nSsp@s@?%kuzGXJ-yIfiGb2XWMCkpl+w zFMy0K*8uqK;NAXZ+x>3)lc9NedjntG4{G#QmYivFB!@t=(H#Fp#3}^zb|@K(L45HE z6uyv1GUX)H)9>=UJ$Rl~C}GlX9YF&FZ^*(=LY1wg(eCvKjo2*pH{@|yagf^ zErB&6dRd%?=7pv(*v27I+ZoL900fKSM6WoZ8g`dO1}J1 z5MxH;1wUjZ4&JvFqSZ_mj=mr_^$>AfIJO*b|kRwM{TAyEE5$tnG1osny8k1H8Q`W74m?Aa=U&m+FVH3yD6vE z!`;dyc=K^+rhg(-IGsYq`1fCO$$t|;6|k*>Rao)l$vd5-q2*c-hwMlQA-BxpTBHwG z+Jz8_Q25b1rc1f2_a}G6KYmkVE5M<%>23_=c85X2C&J1V#R^^=3W zrb?NG(=RAba_2#3kO?;`6>UL-%(10zkA|OAkrk^>bO~3TQAi-8&`T*am*BCttSL5@&o~k2l2Q~XHA9&tYo3N1^mKMJp@6%%xS00}m6j%j z3ECp!P9@zLw$M3JYl#DLe}9)Uu%SK|qg_h++zV<6&$Y4CO@Nk!vDiYuaPnXS^R5_4 zLuv}4+uI?3QGedoyK{%}}?rWKjW^o?}uxp0WA>jLqtgi}y`0?V6%sGa3gttlt!5#aE z`9CXFW9PiKEe)H;@+##WPzcy*frj*FIYnX+y?F8=sz@pQdE3sJ3J1%ku}=_5U#TgO%<+(!hZD@Cq%h!GTwjq^ls#Oq)(TfS3#lMqZ_Q5*8JHePxp^0|M+cxoDc7peFyVd+#Y@sVxdnQ z;V!RdxV|oDX=Fc}dhSlxb@1q^-WAsH|3ez>y8v`3ssHr?d{RBCgz!sEAp_3lHFx9* zfgC+h2#)k+H<11p`kj7Nk+>_RU++tcZuuSK@$8~$@nQ=T=;nrQ4$=9U@XPk<(bFXBIL>sIRtb_F6h) zx8E+eNBV)geOFy)A#&~7O606_DxSq0Z1=JX>p(4+W}Sb0U-nn01pPne5650!cIrwi zGFe|pt0b)Ds|NF6+OMPbc^xIeGiN zwz+{O^cyh@fBQi@LB~dPr_G(;e;Zj4&qc7f*hc5e;b+8(3ayYAolPsEs0)N$q$%65 zudYEa-!~Yp2ZnYnxWYVIhT4%i=jRmkK=|l$ge(9u6}Nsg4mOCBGC*B|rE!W1nd(>5 z^ye`p=kMTsT3_E|gNdugZ@N@?01{|Jp~%M=(P@D-P`~1C#m}D|9Ko^i4QPbXyj}ux z|9U0;7s&8lmNC6UV-F_^7;O-(pE4C`c)qTI9V>3x1~4XG9E$q3jRArss4AQ=rb93k7y7 zbS>T``Nd4e1^>PB2OJi!PF}iEPIM#CX05_*0c^2XO_qpav%v3~>OW=#+x=gZBG=zF zLuJAz+Jw4TN#*)^_9>aMROeX^B(k;7Dou%|0x(o5rL!Rel7$r^GrnTL|E#&Ya%F2^u)HqvrKjys{V^TS+5=~widV%{>4GA3lE0N=ojmtg zW$NIcZIwAad60PvdT#y?hktVSpz?WLCBv@0T18}kFrBgAb)WJ4v9+CUxR<;H9Nih+PLjRO!@#$#z1`sL-bEu>S(OnA_D2i`WF^#B;sD}=phN^& z>5z_RCuWB;pVWifr`MDHfxE0;&MT0+W)YAH4)BB{I5`!kIxE9!_|4&J5{> z6c^E_3G=BOGKV*y#dFfrgEJ)CP&KLiVr%Uy1qTMVdVmbEw=7FWFT7cT$vJizx5zlFu znTPK`bGtH27jJv-sA_Op0ot1_85rYQL>2k&B`x@Ld~*3TtcQQeWY#w^;{c3OqUT=( zPUTBCZd+eGMHU!^^oSNRUCu{zSfiVSmW;Z4&7;p z^^}QPF_KT_IymvT;C@-jMXKw}D(O!~G;c{9qA!JDZLp-(LQ* z0TrZPTD^VnL~XUFn=?(_G#E+rm-t@jK^VHZr@MSlf9$+|i6rXo+OvIi&7Ko=D9AJ@ zXjHvV{uk6Z&kc$In_yY=ge*LYsjPWP1)bXW9+fX)0AK|X9d4tQ>XNIFeKMuVjV?CD zPRJC_vSF_IF8hQYtJ3RGZEZvAVp?{6T&;k@1ZEx{8siHUecR~yVxanzI zb5odWlu7g6EyQrLGmLWr*aQXSmQRh!z zg@#F%rTSrD-OB0EIdnG!j8d|Cdv*90Q1WV;OZ#>dR0sYUao3rA+VH1ZQ7Et?Fdjr4 z4d5(-Gg7lDRqK;)tQftVEuX+`Joe$vB_#v~4Z*ib00PL_`5zGc7bzdC;OW>eho1M) zT|Lcp{+<1c-^RlIx#W=MG4S^DEsF_->od1!gVDiZ^gLB01IkI;%1agwp27*HOdAbe zIAU#yRw)Rrl7ee^_BuK2Da+uERc9Qx)Bq+Uw5i|Ykyy+vEBFk?W+r6 z0mgH`)6|g76tAt{thKWJcXMuRAS5JbsPr;xMZBfCWfoO3svkr!lM0fJr-(n@LNq8| zt%DKcma%rpoGTL8L`Cug*fb+#gu76_gW}--AZak2-a%atq}3#51VywYgOG837w z_IrYaLzO}UBqban_aOIv5gX!1&}%UBYQ?p$et4idw(p`IWxHQJ#)`9DA2+S}A}BzV zqYtssv)j+(HTO6%?~ZG&cQBJ6m?agr122B8ow>Kn8{v-@t9lGS4Ly`UMDG>(kO*Z ziU33-BbtBLgf(IH5J9uoVWg#b?4W@P$46Y5lCaIjISc&czq+F-(5MBYtQ~| zcCPeO?Vi21WzM7uB5PpT+Kqm&pf=lWkCNlo0INlxz=3WDZFEYsGONKhBq`>J2pBTt zKQJ{2>4UZ{TiXo$KIMG19*f>)h9aRl(JC0Ivnqw=XS~{xiZLE!dn4(e+ki;_5I@>Zb^(-8k$fuW^82@9 zL2i+CEXj(WS^@-mSw2!chPY7Mz&2uso>5b;Ieu!Eb7zIRj@D%z!=qxW$$*(-FNP8) z1vU|)9-RhAG}{xEnmZ73iQ<;iP+B+T=WPUGG)L#(k!1(GyMBBmDN-FT$U2B4&+UEErnr$G z82$HaP}sq^$EbcCFA`Y^DSN>x)FZEL0RUkOWeJkdkZK?7_ffZ5`_K;CI8{-nOcc3W zPZvd+B2%tj?wAR~N`}JB9FWZt;ZnGOLl(@T1g4f^3olGOBBfCr-OF$293w{d;l1(8 zreqV;G!4Rksl0X_^-Dm;IW|mvf;al?ioj>)E_jq5ZkzAY1Js`w%^K6^9Bn_AcfoJ% zc%T2j#G&DTRMb?rHR_zP%%h%|!iA`r_p8hK%EbpVZxm*rrzs;}eMf$Hjm9~BKM``9 zwrJS%W6VG6sB?_5us3%%ep``xE{5gVcy^;(+wlY~+GN>8a>W9IDQ&>2VdaFQpD@TPwPp$&;Q@LH=+jvN|Y9z&bDO?)j`nbei8M{X0?Mu zpS!Q8X6QN0{50fO9@HP@piUwXk3r;c= zEJpSrZlQ_51@dg>xTW-22^26dv!A(K-`k~bw8EoqgSRAYjtr~ZwL;Lwn=bVB8%Zn? zEDg&j6#GC-nWcrRuBDz!CMv;G0$bapmtXo`Qr7HUJBMlQF9b@a>=EwYWnq?fSVsbBJdJNHsPmLKZiB~d=MXN+N-pk?>7`#nPL^$hZ zqiy2u%X$0EH&=x7{zq^(2Pt1!0X$iTZu%yCjduW(4}ziPpq&lKN>A_)W8ZkT7dnWqf$~bg!wMEh^i8#w=t76;W&ttE1Bu0uavz zkj}R8t^wuitt=T(XhCTG*}Y!_RfyrFGPjWLB6V2+)RS>r=F+^N z_;GV_jeGJ7q3j7kP`WMJb^KAcC@1`?oXY#LK!lF|y`f#Oh-B;jf0>at&;OtgZ3SwQ z7WZGzwF~oR-~Xd`dM`ApbbQ%|(Hwf4j>8j+6Z{V#-rGHP-zS-n zmGOeGZ~${pC|3p#%8iygs!)}k_1FEl2s+iH=RaLs+Pk~ky*2%!MQlg8d2v!La%({1DHoB7ItN{ym4Cd>LB+vqv2j!}eNKTMJ>Mb?|Z z1!QTS92}j>Z#l#*-^bt`C<;F;In?PJxy7w|ule<~>-gyI*xOaQX}EB5Fp z$sE-R%Sd4`HP5H2qK>GbEF7oRF9Q|6rTq~2e0~xtvL)&CYiE5^79*~cjp!0Q5+>u{ z8=xjB@+a^?-!mQr&xt+ACtDt=y`1}{xsYh$SQ0G9xKhD?7rw6e}*1>4(~)2lh?$BcdX zKiyz8+!q6pwvJG+DS$ExGETG|7Rea1g{7~C)V6rs%=t61fkN{UKWD`lSZ*u6#`EM+ z9VfrKIU-J$fPDn;4Uob<8`&DhCiLUp@bK~^8C!4RHLg7)ee(tK9sr-F{r{HnPcJh* z32gAU%yV9C<*0jo}xg>_Hc~( zv1=}+O1R4HN%kp*j+)tfY^d+bBUE-?_}Q!9`46=%I4M}kY?ypi(n9kC_%prrvR??Q z${7(BGU=zfQc6`^`xECE2ktH|Ep2UD>ucDR?P0Zk-~v@Og=}XCj%xN~wM0`fv9m4i z$vDnHC5&X<|8w?d``;Yg%qoO3F~WYbc`Co~J7D?YD$vmLT4zHA-YWPJ6+!5ce>9aQ zW=#!ce4joaNC#6RxW%~48$la=%cEGZI-lc*3=ji z{OG%Qc*#mxtC^K!;U2CNApp23Mj7x0RJoQ7YcdO?#Kgd8Dk4HxK-x%!mqNDS{aLnr zbUrZ9`-DBw*QfY{p_IL(;%gBlq(LrmK*qm+HD59>>r%&^Z(DM+OD%JuJTCI0j6*o6 z9EnD`forqxtYRko`1!>o(c!~9l$Iz*0Q6vrQDk+#vxlXc`ikb0E*}V|y{C(ZpIbLm_a{v){)C;6&=abTi_kk6)-X<|9@T(Y@El`_ zy&jSym&0Q6khwUgOjWTG+Rx9 z(MFKilH>hIc(Q5*2XDK#gKTUt|IcOdXzp`dYr@!-s8@orqNZ>>T@U01Zjk@uPHbPe z1hj_Vuhs%vv1TER8A?_t$|{f~$C)974I!9`0+vC5ZvhClOH5AwK@+}Bn>dFa>B7^+gT}5{XG>~D5qWwjl8wE4YJpJF5HeG>ho>rG&75KYKzp|qq^}Ni zeid<(BWW!5Dk!u(XMkB#D>XHdm8bPj1)8j!l*kSyQ~*NYwqyUB^V7EZhhyW(xZ%2hvWQk*1vGL^wh-Z;IBrcGE(%84Yf|Fcee+`S@T|RP(Owh26xAz zM)s-XN*ufHi?w$hf7Qaqox`9ZAqp3;Ug0P(SB|0 zrNf>eQ77h`^3{#@P$emG5)%(5e_a32qbwSO*4H&;8Kf|b#9nPgA5LfR2UA< z`^^5zF>D9s;RiqcojZ1F)>R#RWoI?le1nY4t+6zzBtrRby6Tz!9W(f$i53@DbWQq&(+F|8?vf97IjQGZ-OfgEW!>WC@JxJ) zU~ek-oRdvZ@9Yff;Waw7ruyYKCrpwX?8B!QUX-m!!w7@?TrWv$pLZs7A0@o(>zPAW4vgF7uaIgj z;kGVur)2aMk)q5hDH=Gsp$d&E*?Ss!($-;wrdEW+8v)3=%Ru|uSMos}9w*<;st@tm zp;wgRUQ|EDDlq?pr$6G)&k5T_#I}oy5P?#QIDhthxE`D8etg_dL;WIf@r4BC6n6Ps zGQy=`kCY@elO=;q4LJMh-1x;z)=at0p299Y2sZss63T>rw{}NYu0gk~zCIZtI26!i zIYQ1W7$;E{Q)pes?F11@jYaO~8smQi@6WzIXuUNbSlyhF`$$yXMCCp(bryS3DI(g9 za{p2PP@+&nsFixywn&WFn^WH*K3ZH|X(J$e_wnH$9TRgWtKg<)F8z~<^MaD|!TTi$ zk`(Vcxm+Vfxk88gK01;VpY+HPv~x)!h}#aq0sZcY@D_=btq}g+65zgNoyT(%p(VsY7$i> z4k-5LYs&88QqvZws|6}U9_05yD2p(&HUOH~$N>GnVFmwk2Q|OU?o*x^7Ifi9n)kFP zMi)N4gq{@+45g_n14to$UoU8b?c#CE_;n+0(Ze8{b(Tq7AD$k;vCVwlJV)DNrGZhI zx>oXctrgoVqS*HupAM<1n2l^w9R5UF3{0}-jb8)`*Xf77_l#u;NebGX((d3O)S`v{k8#O!N&pDPRH&G5> zq+q#E_ojp1ld?LWhFztxPPRVE&{P-iMy)gE*|X6w(r^QdGH)OYk^C3*gsrh=StH)^ zpX$_bL7D|k6wpER;P@EwB(Z6zfAVgF>HWv9$&548tUoR#c8fWF7@|~xu%tk($Wv+% zqy?r_+3l_PJe9NzGYJQBUU@K0sAd*c!PWo?UUfpm0wp+|Dj04o@qS z@zYTF&~mvcmwLJJQTl;dgm12r9@^%mfn6g%v?2c=d-Ed3GyKo`Ee1aobQS z)B!Gn^;vk}JLK`VH&f$+cT*1%)OPAVkw^KFsK z{dEfzMd>^e)n#;wP@G2S-Dq^mWH9javG@c@anfv}jZl?yQ$@#@4#(?Q-8$P~qDCku zL!Ri!0CPuv(Q)WPr9&#D*&+BjGBU@YX6!v6G`tXT&$)^2@7BX1fIZ$bB9w(LSID!? zZUg~2NC>M-M2l2#JDoysrw(i$G(o^L^=G+lqK22G&a2nN3_(pzy)FRQm_S|J+pz^a7lw>GFA&MC0w_=U~Tze?mv#z-pV8fWPa&t4D?;atV<`_BRQ zVz&dF9{eT5=8YUxloQmNwf(1}xetcT+5$7JLvc68sKS~bO!DYd85B1%GH9H(NR4FV z8X6V)@D&JV#m%h)YlY4*BJ>>MCz4*d!kA!mC4^BtHcqw@hmu=0qIIfcyJW_y9GVgS z!ml9xWkx(VV0>D?qxU>kt$ao_3l#NIXvAkDw4_{n#{v+!$f#HI=lOme4;xLXN889}9QS5y$j48!|uQ_3w;qo*TSbYzsgLs-%&-!dy)A zeh+Wm?=GM1V1m9Y0)CA5-UcaEeZSP%$(#F;$dxV!7ALz(A z`MruZ|LK0YdcOekRi)y^8Lhfoh#@FbK^u%WpJy#@psw7fwvUR!O&MBc@i4(9jf;CtXO=xePD8?jb(bV_71nnbjki{^5ct@C7J~= z5NfQT@5qWEr#cK5yYwW+OdgKqbSYgNqdTkg^1w$BypB}KgM)t|5uT-JsZcguU9eau z)Md9e$61%iSR^J4B2(04np!9Q2tl`o{b#*!@6TeuCs^F{%qcuL*}GU~lS~!KHVK=J z!hPnrwCmWv9rn68IUM!u>U@~=O$Li2Ev1@cK65PaheZbk%@xA0x+IfqD_im+S(M2L zT9&yULQms7F)2xNerfYrQ%;GWaU&SJ*y`Wb80s>OSO#5#r6ZSqCn-RaAbc~tfBUB! zQf!0Rcn_y#Qb6BZbFE>$x{nIb^bXtN{U`cdG%rY?v39@MR#@gxy~yd+AvakKD*Wys z^3nvB)~g;W)J-c*dwtc-UF_l&TIgDl>U7^1_O)Nunu#|WD-brOU2v2V2}leF$eIEy zxx1mz96F=m#>XqFj7KE%)6vSm5Rynv_pe06loU<-WHapSF-9B?(ighIH$s&3AmIV) zo6|0sz15&dOy`2y&cl}|s(UR?vz(#-pdjPS8GIA6Ti=IJZja3Yls#1)GxfH{8(Sl4 zYbd7nrb%9;;avT%7oZ(t30Ke^=I4JM=g;%~jBNei=lq|?H1yWb+P{P7l5>pVse>@o z7JINn%}Wlq>m{@bA{aU{^paSHX+k*~YOz&`f&DgLb)6`w(UV5kU(EQokNZqjNUgeM zxhijb8`<xbtadF%J43fPz5)^lbvcQBl)DPd$l0T7{M z^&`j$2wr5^p=iQd#7`?yW&>2VCC7X2JnaT2=jk8EahfIRa?DZjoM%Ijb;y($o)~7z zKgMOsP7pPW0}BjQZNv64c!ekO#-NcqwTwST`z3q-J*e#-*PvT)7t*6l_RgchY82IM z)2Uh{^Vv=TkJa1d+BVeMb8M%4HjX*DO4s&67_zI0`I-pIV_LE;tJDp*mlqvTPKG6& zD*CUgWX_QJ8yl{FN6xa$;7_IA-+#W!cENl;jeT;V$52T~Nrq!oLR)Gh%BY=Rhq*Me znAmh73W-X(WEw)Cr9`QJT(+GH@#&6=ZZ|PrW05I63^^|F)%QB$%0Pnq2;J_RN>{XP%q` zxx96TB!AW#76P@>`|8rI|&$FcYiq78 z0M1(9f_8U;=*exR1@;qs{AWl9`Qal2JpS|Lo$;rMiWm8$DKyvNUR-?cs z-e?xG^)Dw$^3Tn@pswU-FE1wl%E#cEw%1Ax%i)sd$Nc)V1w&|bRYjboi|Px5lt*2T5hoMY5ncyUG$IU zTbloKZMK|ObB}2xtyQ4|K8KePvR8{yTi5a3d?Df^;JL)Y$7r7C=mrL?ZDJkB^w}FA ztS2sJSh@E5;wSVGV>@O378`v4MIE1!_uy{HbJ|qtWv*9VmgvAswgO{K3gn<#C?0bV zTxjyv@FHDq$8Wswa6IGB_$0TAyP=4UU$-9Lo*lzbxmvS~QjA2TvT9^U%YdcwYRI(4 zC8s2gtw@GhxJ(QcB`~lpTd7XRD~oyIxRPy8bVzfO*>44V8%j1r7dvDeKCRVCxlRIG zbwlr=J_-t?9*aY?DV=vNKnx zSy?yGgv846V~VbQ*z=}+V&^d``PMdf))72ZJ{`tiW$F5Gi?~E7p}4{S5>cLa`3E|>cERLub0c|mMe;zT@JJL z!Hp|nrXaObac$=}FA5i(A8yGL&5`C5+Z&wD>iJh^qqkp+-+qu#1HY#bk5O?Sd>+Dh zHE_4?{a>f~zcF?B|6yu})muPoA8l9YF(?lLB@wK~ZKp_7zd1Lgr<60#N6tZ?%5h<0 zgb*sed;2Pt(2}5_JXvyWn>%qpozt@haleuPU3)dhx%-Ec!5!*wo}|0CHRt7@L!Q6) z9l0Ln%N0r{lo~KQ%!=)+>ehF8iwV>z!PmIk&x0H`l{FOh>ZL~<>&)w-HXxD^4m2)V zVhvKAPY}#n!R!d-6qk?_<5VHs{Me2=c5d?dIDZ9)jhw$(vJAO~F7+WC?I5{t@1|rH zpVWp<{w}Yn{gU7EkJA?Qpc23+f&m*q@ON(-UytboCBZ2Zfdi5j1nIo>b!Zmn6mvn6 zzv^vwvKIAj`z($s=QLt$7!!^e$)tC$?KrQWv{Fn4O@sjrsK#WaWoF&To*T21<@M|* ze2JrJ{&;|Li^XLk%M-r_N+#-b-}@@IZIWK%p^Ha4f667g-a2vzY3ZAvcIX?Ty;B3V zJ!XB~MWf+eKLuq3*DFfo6H+0Ov71ie-**ci_WfSx%)MbF<;BHqB@^t@ynb7dI$EiM zqsVRPs4Se4B0WNf-+*2>nqRUCG~C-hZ1`cu6R`1m$HlOevwE8_gkkT)t0T?||1T zWhrRMzjc*z+f-=le$$YhhL|+@sY;mq92%6HFQt|}7xLGKBKLn?)V@UBQco>DS*hT_ zUdF};d9?o#sH_}T{UzT7mF24ZO%-0uR5L@nrefl>k6B47nMHng4L`&JeU5}=kD`c$ z0)vY}U)vjVfQwUW$rGK1ZD(_{YH({#A|qxnw6upv3V_%j2$%Nt%XphyzqG-+qGH~* z`!4od6HB)g0Cv&j#n=DM?S1fnZiAM89n>Iui2pN~yNjTz!T&FPVWY!A(};3OVWNeQ|#SgjnOOEcnJ01^lM)81#f8qshtn&OF z8cuW-6@UaXkOnXoPtdRH}Gr ze9|?H{GBYD20EzES|H{l=LtlPENZ)wn_NSEae73>!VzBq2=CsS!5VkT$FNzW-3m9g z3q3EKY(2NCikwHu0pO09xLRAef-tnwTH#)^E@?qiZcLAD{x3A96F@y$D{o*+VZtps zyEy@V7VAaH?%ZE)8EPjV%u=qRYq>;vyAI}QsC0l)xx|_})z16f$@#SHiTX@TWYG0n zp^O8(NLKMTMHr42k{RCx#ob*LL6?`sZtZu$|DDkPepvo5j8=toti1(7aGIg23(a9t z{@#H2Tg8?}?WjDtbXjMx>q?877l&49oF5t=e*@j9D5{P%8PA0iZj*y`9b9@lVvDap zy~TpoggCZZC1!_jwZ!%|vv|OHJi|HF!vyVE{J_wy$5y-Y*i>^A5#%ABsaY1L!5zk* zmUj4d80ORH_deU5!^PA-G_-3@VP=I_A7lJO`4CN^a0g2SW^g53R+ZO)Z84P2Tzbcq zGi$R-Vr=02@}0Z0tD$HIp6vFpPL+vfwx6k{-BTuTeZOeX>cZ`q4jE zW^)z^a`WSbiox*&hI2hfT(O6PbYp2F=wpKGdoxDjGI(LZle{;YUQ zro^3W`KXp@kbxqQk-p+LP>Zo5*0X}6*FFDaRgYVz#?Ty7vMm$MQhnN5?CWLFOQlpO z;V}>idzlk8B{l5N7frCWubM*OjYAR^=)F?hS3X<<3p3&k*2OLklOdhMZA!mCG(ZC! ze)=NZCEn7VM+8nXjDiBonkuZh_@VAdA&nlJziC@WsDFy7uxB~h9eg+g7p{Kp`ww(X zI|@%vx+x(pZ4Ye^A>rCO=<{MC1(}9`5LSL5Ood_yH-Nbx>23p!+&D0??B}+kOFS!i zeg9V{^YOL8DDI5LHaQy167lS+8QX+kNt7h`qgdS(l-qL6rLo5!j`f8<(&(pojy4(D zJd0}V=e?O<7k;~RR3Sb+Kac(2^!`9009^d%*W3DC2$C?g*OETDh~~y>u)2s{i;%{T zR*bH`ZQ#>1am&E5X4?uLC3xD;Pni;{GS3%yU`I^5`~?S8Ac7MgYQ$= z!tkV$(N~@PTL>W6&R7cty*MbJ)DZ7M(QT>ivFn3XqJoL%RIgXfJ6$&$&CwZhm-rW653k5q3wQ~ z@h$%PAp(~YRM`>2?Ai=w*Bk6Ji4_fbgFnU8M;Sn6`oz+whe15tN#5S~_36pR@gb;o zzu|1ZZZTQ0q;0RIG^tr^lc)BtjL_zo@iyHHG~QDF^a%6d(lo^zNY9{dW((9*jmA(G z<~Ph|Q$(UIOC>M_hYF<~&D;NBN0UnUy9m(LDEfD0xrN>$87ZP{VbL?^Ug!O7lIiP= z0XIKzhi!7nOO-=6);Mk#=QCZ{o5-)HG{!#f^iKaC8k=gg@6ck;?Id}i4`PQDMV=I) zsg8sMLAlwKVF1S#T^dO7$??@u$gr|ykd9HlrFZ5THuM>X%wvqLGHREsi(7rnX1Bw1 zeZy`NMelJtx>|VE(-^mgv~Mknf3r>c)2+9;fD2cIuWOcvvc@$B*kZ z$sI{DkW;{sKtr3g0^}sO$Sfe_2=FP$w6oQZieKr(9Hz>X*y=xr+f#^sEH8w_GVHG{!lyJLx zK*&K8wemL*r2L7WdgGWbI*r_BJ>@2 zv=#tZbS{aC^~e}qTzp$6diAXcaqvwXM((AXz1#UCSHn6xjf_qMYR3ppJa)HWQ-$@FK3S7YpG-d|OoQ4Cn@}UsGbx?6*(#9%XUyYa z40Y3VZ2wL09kKzb5n9${&2=)(ZNRC20WD*)`e?iJF`Xg=FMy1d7!9}0G5%vIT=<$` z3u2dt7Jro}&;4%p{qfD^scxWLo}Zj0AybS- z&Xf+aqGCsts5}B$2R!Im=2CMn-_Nri z;OAjZ?Jgw*+D;_JlGKjsZkar5w4@(9*wx(pM|=9p6J8Qe$p>h2ibbBeA%-mvKh+RU z0?em21}bRg-C2E@p-Bc5j_vn?pWL;@!wFX3YlT)O@846RHuz!FAit2uGATiv_agD9 z8N8(c>8*S2h}y|4i@Cl-jB1qiu~^SOx{Mk6z&1B+K0j}}E+w6vJQt4}+}xIM6G!dP zcKsfK?<&*XFD4hq0!!3I#9%5>KyZhscnZN?F+<#wfz$HEpzb7k6d^fCi$u^wvzIJK zHPzIjEtd8Yig6!VErHY5Lsy6#TrZJdt#{!FlS9{|zI!cU5@JxNpo zGb%@JN!rE{zuP)w6t(_`KDKKV`2X?rjp3DTU9&s3ZQHip9d^{QZ9CbqZL?$B9ox2@ zjym?uIq!Gw&$XWQbF49IR*g}Gm2cXUcD=~WoU^1uNlqA3$+bk5U~MU--0^d;fnv{r ziBKJ6y{#1dOn7bm09T~>I_3ywX;4WJmDVJpfJ8p12fhv>6hEK zFJE_8+w)Q8VW`_r#&{EbFvv7qzp8Sor5!u#(1e+Uktr6--+e4=QOMQ&U7MmGuEs&0 zz;IE!>RR(GMnn;9rVLx2lpt9hAR}8XsAKFTP9~e6-HnH`&laY_`kRMc%i<)bXmvTQ zY#4(fU5NO-N)qG(I3si=Dh^m-xran@pk-giAUoc#tD^_s;`y{Krkml|r`EnN2l?ns zq9i&P`m#qtm@z?ZOHi73RgjHwXFo6Vm&@6Qt{26{0L4t3IZZdM@|DRHTk6(M z$kvOhACV3<2DWT<;2{RP&}M@$)G$2ukgj`=65TX^`=1-p9^ri)2XAklw6omyVvD5q z@GHynpp8Mmq5*hgqJsETu&cBM(5rBkHbIJ!imK{p!s0AR6&KLbQPKWM)MPnQHw)r! z`_{7jY&Wz7Rg?`KGR=S#Vd%LFM0>X(cdWmf`k+OsL8+`ZV@L<%QY6N#PY-=2Q2*0i z{voQPE&dN-N1jRnE`xEky<1@;tD)W~pj9<>7vc++`hP)gX>*PQ+F?ggWjBvbnpQ@SuIJs?VWJP4*QZ855B?gx zvHqz;DLO%=XlXK3N+cy!QgY%7eI%DW+#i8fq;d(yyxAMorfzN(ZdX^o-&$^I2K|#bfPb{7!W|>9LNaAuyFX9Vb@pO#KMA0`m%fJ9|ARLWQ9sW)FG4jzrvK+ zGFDD$HL6aIAi3Bkws+sb6LF44A@=K)^%B7rdH}}yHp`w$na|Xv$z5@%Ny3n$HB_Rz zXHR<^jXqxMke#~KGpWwY9~N`l#LL7`d5pv5DlB+87~S*=)#>1-f{nGNHnh*niTnvk3~W+yP&SK_6*jsMdz`((+lL?t7-A`U7m zeAI$M6K&bSdZ@u!Ft-?uUZ^qBNbb|CDfCx!Hp+e4Dbw{uJD$QbD5f6+BAk;Sy}C%z zDJ7OPJk1U`A#!MY-)^nf)9%f*->1nDw%dMbjHy?CkHfRxgqxfCf_9#UD7|n|D0}uQKhtGb@@v3b z-Q^0aK`s|-PBMT#4$d#^XZ3Ra$#9cMC!DfEejZBT!9o8w)ZdEnohb z`S9jJ71B}&2s}nH{!Z?jp}0_7F=K{2RUO_^O>^T;RkIO14hw!A`TY*9jp^%QybaS< z9Rm!bg&|AL9;j^+elhXnAnLp1S5M$NQ}11@^yiGT(V|9oM_~^^L_$gq9l#&ER_P1^ z*bF7m+1jj{(oCU+P!_*jN?_^F+lnTyRk?g=a=vWk>2aN#^M3q=u-A^bF%D$gzm{F6 z`e|V5j*CxI*z^mny9^Zmqzmx;;A&3xET=BFp)ACiR_ja~zZ2}%(RVOYcRMl-Uj)|( z0M|$Q;F;PG;m&&7QENdw{6B;l5`tzUHYsA+Gx79H%Je?Fi6^LyjtBCH^xZw4) z=6SoeiUVnX;_~98=m9ep5%Ym)862GIDon7P?;0Vxvqj^Jlm0frHiv{U!wkEF$+4<8 zidi|4x6Rx{1B>Ad0IDqym!fZy>Afr?r3DOhI6x9uRMhDrps4C1+W;~iwF=n?xyS)4>H;}z}DQtsnPq<&#nc4(}y>XP!R^Tt2I)o$`zb|N3A7>k=25L zj_*QP=78`ugo?=AQyYH|XC>o> z=9v3PS@sX_g+C{h)z6C$GLi+*}nDDEfqL`f^MxjZyEirJ2gC6GCh1;QgYS3 z?)|y>Y@(Ap^A-e(8C<2*I5%-pXi3wz#&EDcrI zYzq+OMM1&tC>mw&--Ho0KluihB)-m*Atno@xacO*rjM+QI39e1ItCFR0tI@Kk{bPe zGv6N}M}g-nv%*jnpy=DCfA;0?_#M4fW6#$=2|f-(iMii=Hq(4$_3&vW)$n`ZgUP;2 zz5m{%04so=(J3Jx+}}LX7RNHv%+1%)LM;|e1OcB9sRZcH!VHRH?!On-kJ5p~FR;Ih zl1p^`+~&E~c8iixk@6$O)0MibjHA4FOIe~QB`v%XHAuRVlbgkoI(u zXp^M2*`(oH^Jdwjach=-_I~4lMd(%VeQ=8)@+T)UaZFB76#7Ow6zTom_j~ErT~a{x zbSqr;6^dDWWIwOA!3n5Slbd632|Ge}b-v&47}T7rOmuArdq99{mH~Xvq(r{KGw7oJ zJ5>I$&V}m|8h$?jp}!bXjCX}69srq zl2YNMEC7C1A1S!73I@3*rkp6J6Z8TFDaBJcpiW6nW!Mta__DxxaCTU!x!{TMo1Jxi z?F}ixVz7+#l1puUTBe|QLIV-D%?0UwDJkiBrl)`hXzkuh#2SR)~r+aAj(W7@S$AI4%kVg!K zBq1T(imon`#;a)+zimjdy0Dn`;7M5VQLRWK_RC)0YCqp<{k#PQg@|-H?+qH>@0cVl z0r0GSXFfW-dW$mrhNjqJA<0p~*XMurEmY61<0sj$vSmWro6Rua3dQ3;bpaRnqc59;aGzZK1n7IR;JV=CQyho z^ME1OL9~b8Sql*bQd)PO10ISh6?#lY_;{b2GrcX;Q4&Z*`n73CZ$(z z7QK47ea2EMl=pdH;VnZ54~?}JeHdi*l&C75;CScBxXN$BiWAZDx3RFz$3#T^WH zi1_8aR)!r7&w_@>?5_cxBP}dSK9ILEV39?h#aR0!cK>y9IBn0D zIWQW{&N)7RJvgJ)ki!b6!zhB~4`peAsah>m0ilkan1;*O4xYcK3#AUWS0k0j9^Wb* z>`=P6wDlg8!10NEkTq1f7Sb< z{GUwji}U^ps0IZ$nHk(Iy)Z51xT7gkr+}U8042NyCn>f3S!E4uW%HB)(d)BO{8P8C zHY}!e=%Q0rGs=gSnY60;6L3aS0HE;*r?Z2NYrz~{nMyg`qm(nl-fX(8u?^doWb?YcG!rxE{I+~z8oq0gYFdBpp)li$`bySK?Qluz#Us+kX&4c#7p8+CX-KJB zOfWo4WXRU{5NvT;`zapvL6~?Endu@CKA(BV))> z7rqAd; zut@7c{MX3=AWmqfw4!bmOb&EV24Sr%2d!C{@CrVlCcJ4J-VN%$_M&3?rJKB>M*>hwky@wi1oSpDC z>FYEN(@Dme3CN;RLX)p((VaFHfBC+3`k|f8KKAT=r+Qrv-NLmvy;m-Rvj4){n5}wJ zIE`%w-d`3TUJx60Fe{Z>=Co)h1vNFWw3~Q~&Bn;22r44xTEv`nwMF_$x8+r-px_n^ zZ|~sAGt5ljOz2+=L?BwTU1!Dg%P!B}Q+j{r^XX$%U1%%1b`l?X>ab8i!wk~k>3YMd zId+lc;sapNt0}?R&C?gGbb8f?YE3v4@0*-3(Dqgs!#~;ff=edWGm}#SV+D4$$2PqX4Lp%B`Y98iQ&SCA~SV!rQ zS&$^Wsu+?JRC?zNO2*=ANQnaj@TJ1g>S0pc_MIa}QD-|fDyo5xweO`Hu3an~+X<@4 z#AD1mbk;A4;zAU650fX}JiEzEGY4lBFK*ITm$f1moE1PUcciPcVTI%S+x_Fv)X?eI z<5cf1o~xxxcSCiGN}5dRMedS4;+!C88j>HB6bqsp6}4q)!(0{Sf?7Ur_K(BcOxwSw zQ=B@|3_5|PlgLeV7&@Vh0Q9&n+LntraB&?DVTnb&qlX;zD>Xo2RpG_>*UqJFo|Hm0 zL+EC0_v+N*(_>hhUCR%!;9;I+WqGgO&wF5Mr|;^Y9NnqR!W^q}YFGMW+CujU7`lEm zOMj@5jsdUzswPSq;!Ev=WEE7L@X->rlDhQR#P!v?O@^-D!<*o4IJU!S4~AbX7-*qo z61{&TL=xzYq@g+UT3@_p-0w~y*xqbT_Ld*O-RM@ho{O-J;2RhADksIc`^Jy+w^F^v zyya_Yui>JQg=@sU9ohwozhE&^_|x2_|n z39rw{BCOnzY7nZ~;G2n)zhdGYxoe8t}T?Vz;+=0dv~1ZBkW22daFDUWM~H?WHs|^chs52t{=ju zV~EeG5_*w+pDD0iQ!l?GpgjyYN1WWa4?^D^Zae+lHHF^d?3P}qx4-*7lmwy&-`E;+ zM;8uImWYXbtIR`&980NEGWwpZ-4#o(FjTnc?cn!%nQ4dRMx;jc;XemKX=Ge{!-q%R zcsI2Y;={3DMOr{gY#MTE63xk7c}#mqs1{MG;N5K;V_OoYF? zY#Mv4bJNO@8@rPFJkK~5tgwa7=#ZrdE{}|}!s`aHyhU9HO{Y&*1XKP4=a+OzLTFB8L@&_kerI^XTfw%UZ4uh06{Bg0cG2 zE;Q7LF#2$RDkgG5z=D{7HpKBSd?(p!@IrtH!ydQ;Et%jdPRe)PNeh<5!G)>gQE!o3 zq}FUhUP(?-OtR)M(w`wDCSu^iixuVdsA0g!4jcqG6_C^WZ=SZ{?qM;P(`L3F8nIgs zk`Tq;t4^Pvx1a3&ICPdj_S=gC*Y?{$8FtYJm6vYyPP41#pfMfKl7_9`B#&BJ;9R^-333U)u zAp2OUv+*X$ni3n2?fbk|{byr)dYOVX`?o!rjF|OWtMz6PxJpi9j}TT731U%Lv5Am8 zc<4?jkx`&bSRXX_r&p~sl=bI}=M(JCN7{L_M7ux@*9^$U$E{xczg7G1pdibX9e#Hk){`>C0f-U$0HVZy^fr#RuVdThapl}1nHUU^5t^v>`Ookn9Zx|Ar+5l z@ZF5G#`QwmRP%HWB(TEmHP|;F`wD%Y%qD|W^Qwh=>G9rH3ubVuC3W)Ym5#Ux9C!`= zM03de20UZu^Ea+;H|qp3JQ-W*xu@gRo6BuZ(MoR!yF(cW&s4I4a0C2t9Vv%K z4AEcN6W9;wBdLt=rWxdDG=$7p8YgH z&QNW1!nh)by8;2&)auBKg~Rj0`NN7%*M*0>uMn0C?cI0Kzz6O2e7ZFm2UG!?W|O9} zh*ae|p4=}GQhDB4uD9~Oy2R(`a*^$h@xwMIz0P6YF7azaf|S(6HLS;&7=0}%JQVjw z>l!r<#y$nAxNLY`c&~MmI5`>GWWkdud-tTI+l{%!9~BSVry)r;{k4$BVc|K?O|kgF zMDtpYmhd5T!aF&p-Vw>o!3I3q*kVTH1s{4BGS_tZ3!7;lBGkH?++pZ{FO=!J?A!GL_K`ETQ;{HRYB@ z57)Z1u>n=$WNf%poQaEE7VJwm3x7+WVb__pL6JT6V8qsSg?klWLSj2d1x|bx-(P#s zuLMw7e*3!UwUmJ_6#Td^r8}Uqb}I>0I3EtZ-`^kK?|*r|XAX1Lx<;P3%fzvfis=qD002yu;X>HvmNKWwH7 z8^Wzv1Egsl^h=5nXN!BkVfO}YnA>~MqfuzY$7>mTqpdKVeL{M?>3Duy|B8(; z5RGPA%8S9B&hi%@ORX1W_DTQ;UTHz)S|p-XL(39vx_-_C?B>SLLZ9K5>(8^RSUqeU z-{ZuWE5){lIF(v0U=)GUE|?ui{b^aL8c$9AYf-XZ^(VG*d;D^O%FHraf|MDW0zMwl zH`O4GRwfGznPxBumLn7W%Xq-rJ0}ij-1*xr#%4F$mF*{$mtFILbV`=RN4ckUFXA>S zDO<&ggzIFjgr>2r`{;K;5WOV3Uaquw90MdPX;(E<`tF{(RaX@k#uyy@OB9Vt%kYVj z@nJ__Ll@4JrXt zp5GNF_vUno0YN~L67FB9e$L$3Jpw%x-!+Ebmv#N>09arF?5#*kM(1E|BqwYdr~rZ9 z4McMwZYeOZ(6X*#&(*I}?Do^pFZ4l?;L)YQ>dXc&mW5D7fQh#tg#uLs{L7{kw$la< z6|ulNJCjrnKNNZ*53*&UD{3<;4i+w8HOO7E6SXa_)>%8~kLZCaOBW4QYNBB}R-_@T zS$ke1^=%PJLziB{=njZ@jDd+2c8P&nTR%+SbnC_GP~6YYMr1KSKlFr8)@-f*5qyZC zosC;T*YUP*J-p#UsZyb2H12)mBDB3!G%m+kYT1FZm>t30^@LM0wMyV+*u@anW9)F3 z8XhHs90-^PGBn?QCGoa_{22UHT7)E3?DHHJ*7%{PpcZj1*qqS@I_GKFB`p{}im}ju z)YLpb)F-N6nWHHi*!5hH*H}T5N}ZSd3F*cxXDOZaW2_s|R+m?YU+a79S3c9i%M3oE zCWlCu{ekf1K=G0UE1D^(x+)bh5>&pLFlhqDp?6bjr|#y)!T9~M-#b_0c*UQ4JXtJc zP|ptOIo+^Y1>9I> z=rP=$t2%V0aHYCC1*)TI0}^`&V1Ri?*?3S6!YBl`wfVtlW6E8hwTnda*uL`KzOpzo z_tzshj6R+)0EG%Fl%kkY#b8|M5wxku6U_xJYa;u{uwk!_FYgyMA%6D9bz7$yp9`Jn zsj+(hGPii%aSRPVP78bIxE>#Syac5q16#NlP!~2d#oj{|QzuP&^QNN;_1#IjmowaD zI&J#etU_&KbSfsYG-1m#OA=!-+KW?ab|Cs{T*%tG-6=aNHy^nD(2QPEUG6KX*MJ9M z=(`!BlTf{DcUUqYPBaULp2m=rAO-+^6n3g9GL1<#$8Sa868UZ2XI;?s!e+hGF7r{x z>G;JibQobg@H}vRiKAF8UececcLnBKm_0NJw8QmEFTqh>Ty00WC`V8qg1ynaK1=J- zjI0Z)xoBFLY>;WX>|blmBjqEm+fm->8p_)W=HEe;{uD0@!Klzo^5H?%=U#|=jbEu7 zab`+vJu?^A3x6)HXJ@C&@#EHPDdD4}!xVlem~zg~uO5aTAOEj-zlydTWhVxg!*YR1 z`RD{dR@)X2r}RnkemHyssT25f|KZWxZRH|nSm%Oa#VMYYxB(g^2))nJK9o;ojdR<5 z)j0j2!LT`PiivWZBLbobUlbz;AUyyR#(&!ZVm5P7$f=KzZ!4RFAU^= z&OkU25OfTrMU<*>&3yc<`@G)Wy!zesetB{8P`!ECS>9%$ZW3PXuSt@?f)W)*4HxSg zb}+jmAJXGNGnf=PdhplM_x5a2?>%+g&X=R38>WH-(+OGZIw?h;`Sy6?*?NBV3h~u> z)%~;h8Vz(q+7j63(L?D7nmuGz8g39%Jh*gihj6L6vDIX^O=SC3#mGc-n@bv28j<{- z23cN^hTQ&5V_lNyVp9n`N>Q@l@$FWId7O$`u#;ndEt^_3UMIyr*6Fm-TholX2BLEI zL|DanoBF@`#Lxo+Z_4=BX=dlmoSw>xK8MX(5!sx9_fpZ{g`$oz^#KROV0=9@D#wV4 z*t1P1yzCrju%Tdxe1BZsH+F7ji3nrYqc5*!E)~^pem-~aH^a$Itc|!_NFm7^23`>& zB2bT+=Hv?>Nm?$X^YKIm&yBOnV>vWMVPUnlj_K;iRoB$MG-*#MVN!ob$N46L90tTm zAb|&=v{2v{hVDJph`4yRf1`5qWt~gfG0cg%T!~?}Zcy0M8NzHYjf|&V}ek zlt3E3lk}S7cN4W% zRF}aGE9&nH6AuKSpFVw*?(L7_eScVhoIa(=dw!$#Yflj%(h-G=P(YA;WsgN0@_D%a zzgqn&UO*JU?Vk?pTXsg^fynhe7a=%occbIbI_#bwW8PNrpD4l471dB|tCox=ioeLj zqV}OurF{rPaTXN|X;Ks=6OkH%=~%0>Ti#>|WU_G>VqgWzek7gtT@+@@p6?%t*Vhi| z-RM2i7&~a6s3p3S6835o+ZALHM&haY>ECol|-(`oH&{u0Afe_chyZi#3=vcFruR&-6(q zYl4wSmBl>xb58)HbnXA~m@JGHzyGvY{TPAGJm89Bwt2L|3ybewK`p|YC` z(eSYe6hUG+2$5RX@w+=VySjuryY|Hfn&ZpI`Dn8P9hkwXu1I-;(Oq%K7JA?jr7zmB z3EEJ5RE{N=Mb8aCUdrDV@!noAy1NG!;o*Ax@kes^azb_Z)3n--_eVoB$@|kDE$~i^ z!u-f-Dn<8wL|T}+iSMfW-CbvHz60%wAvsv6unoo8(?l_f!(i5 z%?@9{Y06EDpYTL6)QG_buYE-4WzcuC^giGgIW0ureV??y*Xt_wE+=65KrA+K_yHij1%V{HuskVjF~i| z?jjSWy@L)VTybiF;E_k!9@e()g+9ndsk**)ECT0-myWS`{(SJSW%Ex!jlYWt*MJER z`Cd_u>1h>dj+y)&0RaOa&!s;)PduSBWCoV);KT zLBn?&wFd=z7|OSqKi46vwcv%{;@-J@v3Ya7;_-bCf-IC3hlQG=zPSp84_opGT`r1E z$`ork()!yi2c}gL8!-U<5#7!6;l)f(VFO&q2huyU{HoJgQGUTKs|@1j@!uA9QDPww^S!I3df; zE&J-W#HX#r4)q6d#jeilD*>4B^3QH{N7v)9SC`PWLu@~aDxD3vDyx}Eh!_HI#_`4#$@ye^|E(6-7zmyzjMm;(&`|qR?VSd%%R@=wk-2MzD33%7XGAxS@hBU z{5X)9JkbOyxCzn?%G83*S9>M-tzY{puQLYf4qNYgoQJtuQA{TxTS#wk0R#?hcB z@9#8uyD&eri%inrovlBoiYd6kFoY3hK|ny`dRrCRTzCeNcP;wh84o`84&Q4Zkm5h| z$vgRzb7+-vBu@&5qyE7V|McVVmjuA$&5c8o<{-A%OA_<{-u_r!T~-*I{wQ3D7fu5S zTrx*AM-0Q@BwBmXAJ$nW)MOoP9jPa!dVpLKL68Rmf1DM&AG=WV=gv86&@;Nb_>ZDe zhmv{#z*o|9>#kn1!!!+Bg`|LyY+~ndt22uq7EY~pE z>gsg2r<^bQw2L~K8~l^N>eT^*geciiXfAz0hZu@)L~a zGilsmSsOuykmF@EwNHyy-Ra4CdgGZKwnsmw9awttM_vbE?&@+BDzo$e+D<(vBc~?p zq3J#wj8}dlu>y;Ko&qyckAn$UP9h3Z$WezK|Aas;V?t9 z7yj06Kjy2KHRq=3@@0j)b=Bs$fzYbTuD)ruOU%MuG>*2Hgg6LJAkF~|a<5EQa6qY| z@g;fW-~<+%Rwtt#6Z7w+@ru2(jGC06lPsA=EQ5v-;r#L1ZrJHih@<$cNEN-Ri}bRr zQbfP6?>H5dubB{ceD{by@{z#1MAij;M*RL-@0{Ko3+)hHHsNE!g2%n zb^x6<<$*&w%YqAwrf%N+myfFNfX#_WFT3;h7{~+wqAB4b4V}mz^2?$#Vj#GWXE5|;Eq{3W!xnH{## zWs$+ED&|Y+BLiG-w#hj@B_NC)K6QTi)olFl?JpZpD71N5S0vCM+eh;x9FKfq5O@@J zHXGYfyw+kv(4^Y<%wGL9n~X>tz^f_Y9GcdUK%J^9+wUB&P!dP8v<$5*?Ga*IW%oIW zljcRIe5}*%c$oD$0T@%>0n3Rd&fUHh_5P;$r!B4z-X`#!)0U_u^R)x1gW2r zn?59jJs>YDYd=hQzZCZmqWhm~CcF)T`~J<{4<)xIB0OHn1x-@$K=f})ncw(Ai24${#@h;(m2w!S^MebL~v?{aP~$A5C^k?IWzQ>pYhY`q2;??Dl3g*5;g1r2r4qG zv~b)lv@#TS{NgIKXqi(oQWt(d91t(G^jr_nbFZ)|_?d0iVk6CbOvJtZtHk3aUZ5iv zL$Ma|S&+st9}G9|Oc~2?vC(DTdf>C>Xg84Kb$@qeK(fl#W&5;l9{Mzl%ps`NI1XS? zSQ!Zk-ip-Ln1M+{4aXcx$Br7u0)b-8&F)4`9VQzUIhC?wMN>`w+gYPc+rc+Gb$Rfh zK5g>0V8UE5nA!2mn7|k8gHV z!;xgkVuv65rcix;b?rBs1s9!^!?fdno3>E$$s5@7{AjBD45nFJ2;g3jjqBcNng#-i zSK0s}LmfV@NXMqoL@oIlzk9VW*p$sN!}m)_RmDD4A8yYSZJ3e6t8jq z;?lrrS@4hR@7Lz8ZEIU0{;f^Uj;*(x>@cT;^TPRwcYOu6xU z-rQ-X?iW+fHr?O8U7g*%p3$rDi3Lp7m+|Pm=oLb?A4MMW9}8v|e@tE;=eMQz z6tCqvn~))_eM~xg!?NLMev*7MBypo5XX4HsT&y{5`TjfOutDM{eVw*`U7x4Fg#Rdb zA`B%?KqI|{Gg$cyHoI`?RrHW^NO^XgBY&3RHz;IiAAFUU<3iu2ox;E;sI~4{wl&Ya z*#7cBFiFHXB;U<>nwi&zr?Q>>pwDSCvz?REHvdqtY_w~BJ8(=8b$lGRASmaK>MhR6 z>d4II4!d=^Mz_%S!nNZ0Y|TUSjq_3{Hzux%8aZ?P`OxtuK1V=O8dp znf!Yww!ug^?2HO|np_wq>d~Mv3(fJNvCKnemimlE4#VG3#~;g-a? zalJ4@_JnFz*C=#UT!Ozgut7+&H-+Y~+PA)#x_^HG!Ti{o@zFRE(p>Mi+_yKqlyo)K zCV@jMCiS`PqqsIwa>%?lXM@UFEQ`Uu(4{ zaONh01bF{zw#)>9vGuL#2bJA8b!KaZqU-4F}^8cEB)$QWh4hPjWDR`1aS)!>6gez1!QT z!S@{!i;fskgJ?HXRZ0S(e%{=joAK0|U9OiHTY^L)kd*myX3l$4Qh}f$JYy}1BGn3% zlRe;lnKC?JUU9Z=?%mkDZ=!@25?NL8D!Y*x8r{Pr6)KOJ%p%U}BaS1(vn(Ri@}jY{ zh9&-OrS=g_JPj&=)0{Bz=*4o<>!#^$A2|FbJnGhNqog6l8zg1$ELx!xW*U<@2UVM6< zVlO{i2%!MP>*!O&yHZ!8j*jBh#tY7~=4v9uVYzkR(#(`Vx`~M|UUULs%A=T+@sCEa zXf_!ooV%burBVCCJuzU16kL4~@luwNG(D)zjcd~Of_L<=U@&5e*{GvWi8vH<8SvU-E>6KvCQGdiz-EEh&8`&Y_;a@7+-MH%!HLGgj zB(1O&Otc#tgQ4*7jG&(_q^rbHi;|?C((6?oSB!t98#(&CM8P3XFx+FBeY72xtZS@Y z`1$fQ2&(`671F81&F%xo+;-nnUZzNJU%S1vE!6GfwzBd5`uUXFy1kqU#ixdEBnf>D zNWk<@Cub9dYAmkO04FidF-d};iLho(uTkgXs-a4)SX|zo(9@aL-PRWbd*o@Wa@9~< z=_%Jm-}wyl9FuWBx^EzX-NBdU?GcW_-Vq!9ye$FkPvp3!=g<35OPnPN55(o>CEYcM zy&}54)D^PMT%Y`Sh`&5PC9D6|6nROQ23AsR6vG)X_e7pq)=OYb4P7aT3AReU|CR2? z=&Wj7qwd}`P-A=jl~iJyM&{z~$c4oH-W%FLA3U9Rd*k_+dHwoAiXWe*-qW2wcV5dW zExQTSiC8SI`sA5M;B)xBo9}`f3_X5VOqLp5C%U*Vzi(IT(^V={%e!^(b^Ym*(RXD~ z$3&@57NP2kzQ%a$%i1&`$Y_)ScjC@Iimm_#n5CO}(3fy#&w5+Vr%x^K{w?m*oj-)X zg-H2MztsBEP$>^RjJOC~*TKNdBM18$3(Q_7(Umj?|*#Q*%LhmRL{vGXe$%huB_9N@AjoERdxktmw_|zSI`BX(1*GUYr=! zIbFStV{gPC<|e2w%Kehv#gjv;Q=^hGqW*w+y8h7GH#=Dm#AF+up=$q5pX=F4ewDJH zxI{Od&cK0H_OP*9q=N3=Mr~wTW48=J}~^m6wJ5H8Z=x(Vi~h zf`Aj1Jd#Zs8JhLCEC^J+M*WbTekoXXy0ZLEEcsBcwdighVq}_dmP(@i@g~H~0}dYO zg&VeTwz;`0%PcQ1!_lK3(R@>0U+(!y^x3dwefis~A zEUQVCG4uw8A}?3P!)qW&057RWIq0(U*fk{>6fFEH4o1GjazUBB`#?XzR@d;Wm$!S* zCdfsHrMi?r8IKrBI;%8{g!|N1?=Q{STOTG;V^p18`)TJbNg3#!HA&JLfb-CWrPyhXDiJVva!AQof%d z0=23g7iW()_l(U%l^*1se18Zt&MtpmoJ*2r0nEZ#MdWFL{^76C=F09WF0Qr69=I&Q zd~Hxp>gsT&z4T5@QI6_DOSkk|(jybnJ~_u&75C?-cQwTg>GSMNM;^W!@=JrpDDJR5 z$oPHGK}lNqgdlN#p1qDyirD|dBEEv81xa*@%PuJpYh-8vGmWkQJHU?@J~+%1+xY38PQ(&InPSf zfznfKI6|=GBGs4D57}7LB+$6F=;mRb02aaqJcq9*!r0+W|2w)1^*3pum)*T z&N}>nmoIA+1~%Fj_UeZW>ub@-WFbw#eIYJ4+`wktB!z4nwX|qZlTJ}aadoOq@H?j< zVV%Q*wp+f^89SA~MhW5W&NnI}c^y?2dP(b1BlOd(hg&Hpf0iHzS&0yVG>(Zx4ft+YSp1G89JI9&tZG0oB<)-%F&ifyyHcz>-$5qg~j)d-P`D zRBXH@Ei_2}*)MqRqC?<$vr}!K;>5&;RHTjr*x@6iKe)^QKC^`P(d;X)UZ@Hfr|PKl z`}6t65ta0$9!Ax*a}Hp+tg1T|&22RmNFDuRIz)U{Dq2lLd%cU(YcM%qTa{pv@1)xG zyPiRfKWJI_poj7RSOGmH9%>$LSRBpK6|nguw=$I4M3mz5aaDgu7mYmyvUM;HMf(Pe zM!vjLBrUpNjLYq3N-}X`{-^1D-AYcQ_`Q_)y)XMkv-pFj?(^;0k&& zMQZm+Wx|q($KaX1(DV=Q_90vr{h9A~#PGja`QJ=V&Z(?Td|hRJQ7Kx1y?dNZOd%>7 zM|>HHULp&)2LYqg1XkPer^FBbAmAbiC^ARFGgEWddBBY6C~{qVU?U}SWqY*D>#%;$ zVP(|LRsn-z#fk$4VFN298%8QgB^9|9C=;Kf#`>@iz4M)M1z17x@L1yE?f7qS0q%lj zIcT}cr4$pVXg+5Oe=?PW?21oUM@WVakg4jr*E4?xv}L_DXJ50}9}w;o^Wn%Nx{#5Y zv9eOA{XmW;B8Hj)~lhJv0L^n-?YxJ(O=Ekic09jY_p4FCcq6YK$t%+;AcZj>_4J zlB92a3K;^Pz|KuI^I&Ky_#K(@{D9tR^?ASm4ffdgljYZ@c-6PV4TRU=+^}cB{0;aW z%HY`sSzy>oJSoB)0MgJcl&9|Tc5?HbhFI)J89xk9*uWerM8ka}`lYVP@P%{3FPkcx zM#comIW;Y=lBi91UhD=KQA3a%8qr+q+0XAWJBaI`f;95^O&CXn%SF@V^5Z-;}e=5b6GzP zDi=(ijtb=<^@kv|VJi&pkHg%`%vZXf&5xAK8zQ;Rzj}UbDLV-X_`U2NzG>WnLq8pn_m zG=#kA*Riq-lUpp5SBqE^hg5E-2(prJoU)yZ5dvy~IO5O{r2w;QmDIg{1Rw$Ks{;&( z_z9_D;6@&UtN}QweOicOfMY{cDKV@l$ps3R8#$0Ksttu0G9cJF#Mua{qwIi<{XF8dy~peAT$(u5;D9ue9UDIAo=Gh@N5 zu%DHc(B;7{;Pd;o-eUSjS-RSoX6cSSJNKj^v0d{rO9Ye0!*+|$&nXbN`s1Z)s99{& zTy+$84?=gpCBNBiZ-5X#HVob~^hI?Jdw*DYFyU;%==yF-h+I}~>- z?(XjHQrz7s4#nM_0>!1c6!&76z0W=8-ZAno`H?ZQ@_y@`>sfQ=L;&ksg%FkG_(L2d zwtf=0qnOj^rN8}*19?;6vE*kM0ZQ!%sjv9 zU9*3~C$tNILzx`ym3keXthUUotR%{uGV6kDo;4J?R8;a`#lkbvB?LJ%RC3+N53XF{ zg%7wten;u&`P6OIlj(lb3++sTPGjw&G1CBKa$;qXgyk9>D{#dZa~jJTO|ne>kX;HL z*yl;RmLgY*kD?4BWwo@KSe>ZxyD7=b0v!huXrmJoy)XRuack!3;*h=T;x8#DE+N&P z@=OdPXCYps|K4BOgH~>$;r*{$kQI5U@d9=O(&tU7%=vV%fOm`d=CxBnhpe&FZg>GI zd^%1eut6v+iqdwgQ@B)nP{H0L7$wTMLt*-OR3VLMgsUyiYzHaBtCL2s?qcGoeGu6V z?SujhPoZeae5dPSVAAjlQV0SeD5F-QX5LB>5G~v4bN*Kph#))75<{{?&&1Cn9HyDA zDP|d-X4>VEm15Qfwx~RgED?cS3fK@r1Z>~o`cl%lFgbcVj!0192F3QQ%mTDeRKC>| z5Bx+ZbO4(SLh&-DP)0D=*%)Z@d`&9jmthPaeVI$a`0RF`@dvi1K$gT~d`XI4Atw2l z%`fObQxAP@G1b(4T568rM^9FmkE_;M`=<#OfM+hG!NJFZlfNt}s=igy2k-XLfgUE^ zZJa$nPTt~j0Sw>)>!?MGYTjG~NZ~T{_CNYo4RYGhNkPzLs8Tk(H%C@xiG&O&hUnL_ z*IMY-xxrL-=lygspIb(m^J5Etq+(;08VzH@av4z z`$=9lpGR55e0c!2V3n5@wJMf0S1Y;O)cK{yv)|3@npNXUm$!Mi@sBOv#W^6KG5SbYQ6GK^5zc*u-ut zCygR93Pg}n`+jP4t4w8Q;t(1f5h5-n*1il5(?UOu{9exvG=+^=U$JzE*-?%56ceP?c@&v zV@b(Q<_gZINl3Ar%&l}6i!8V1^wKl9QAR8dA=6oegx#Ee=5%Hg8BK&Zx00lw zK7WmY&f0tKBLiSkqb7qWu>}#x&>m>Mx&7^7v|)!!@@&xz*^enj|Lpwv4ktJor7?gI z-j&lGnJ7JiED|JZyLMkopRI=%kZ$soiV6o*om8e9q{1d#*c8Ak49@uWIEHlL zYXS4Hz(lA|oezUOf(%?&8dzREwn?($Ns?fQ?uh<;%mv@Iy?-uA*OKqw`DH;vzGCR~gUv z4wwHyHmnwAgw@o1Z>BgW_R)ku5CN5yCx<)P`hOHS)#L!28(4`w@6SDXQ)c>B-v9X< znWrG$w^V%FblH09{nK1N%C8dXNlxg9@%bWr}1TC*@Q#+2L^M(vK=;{o~kHvD*D=47A< zlJ<`pATY7W(`R{Oqd9&JdCONr(1vKUd!y6e-)CKGt-&*(=Oi-*MGS~gw*IrcLOKP4 zLRMIc%VdQiS>>+chv%=aHT{cKU)pqynI(x5>a0#qkOCrexqs&ewC8E8@!e48Rc=5y zXhRx+#T$+@!rey&k0S&dWA5CSpUl=S?-ZM}B>gSg{k?ldn?EQezvaR39R6QUF$Gt+ zB6b8Z&}6@0O=$`YS*XH7`!tVhV9rLRL)}6Rw2zD=toJlV4_h;L3wy2NR%VBDf5%|F zM2S(M+so$+E4TGHzcZr$oIajw&Dj)N)o1Bkn%5B&BolBm9FO+`Wsi^m%BBPeH(=O> zP#2p{+X>GE_AV|Qe|-OuWp%S``=e!RQfB&DsNf1E-o2%{7{m??5 zJLqTvCwEg-?4&-8sIPBEK9@S_t+7C`$JRVJINmJ`IUe`Vcfo6hN2hqa9Y>vj^!W#6wGiz6HeYWec5sCJ>`qLG9cB}}1+ z-`6}q*3+V?o;|wX&SjT382V+W$UHIPJj-vGP**Sw(L6G+Pc7SWq40@gU89*fv8!$ksWpfYWRmy(LmN zE`s(AKX-5c_xrPrj(=h`Y>9|=+;}VK?ReAs`2v7n49r?N7*Rt}L_kW-wmRgRi6cYc z=pm=B_Et~Vr-QrwQ_hK{T8p;96W}C&aT!MWDx|60%J;HdO(C`^&7VgT6`;Q_r_v@; zV{NZOH*nIw`SNx~@Mp^yk1ucvrN7T$Nxd!J27~?(JR_|^o)cfa)%!loc6$%*)<4%J z$yhFVESe=cVUY$x1=A#Yj8mfYCKdvhAudMo-4Ga($g&h%F*9qaU%a|sPB1rhjo1eo zdKm_i69w}skOl{par$4S5bM?RD=)$ z%`9TLHzFThi`rLDzHeI`ix-^8TZA0QHQx1vb$r3x)UZHWFA*aXSh4yFX`8WUM zJ?)t*Iq2uJKlghJVi975@jl*f+3jpDu46P;34EFR_nT+{3oKaf507n%8r5hSTB+`* z1|Ql+b~$yL()<_jhkv%-mh$n5Vh|iYpeE0^e2+T&dFPb+_M^Td-_qSHoKjUrJUDR- zqCOS!oDA%KD9RmcYxlqHo;&>S&h9TCJ=Tdktyy=1L`f#2l-H))u>i7DvSQVf=WW)I ziBh8zV@6&70{<9Q(VXx5oI`)fdOSmi@I-_Fq*mBN$-R?MRHNvXcyBpeJU^-3z2&iv zd;|rq=KE-1iLRCXt0DN0p?l@#3!`o12Ms(~N+Fo?A@6$+B03;j)Lzp3%j5{{AI@H} z)`qLFY?HBAwercuLUr^>Op(~3aIM0=htdwDx370(Jje7mfumV^G?QyTU!H!9P=>vN z#N%AU3J)J_=`8Koj17;C%V!R`A$-Fd7u+h`p#ot%u#mZk_8 z%_)?`Fj@#lYn5I_TtWHBUgZ>$?<3)tWxqmx z&Ld__nCGtF)aK1{W&N|IVzrQ_G0#SAVQt1d%rLQ@^K_$I_R;MR^*YR-wbx8E+#Z^y z{Cmuw%&5EFV}1slSEz6@4bnc&8d;Pp+TL@W&l1-A&T6Xo&K{Ki3Z$J7a|$EkM?c|j zsfff9Pmz}?jl^`OO*8DKOT|vF_2N9&Qo(nQo)(*A!@2n5X^(k)W?!a|^Lh4cV&Zb< zpmflCZ+c`<){E4dZG;3^saery6y63Og)ro7HwsD&f6=-Z+9KfS- zvtU%k8JHvN3_yWBF7p#2p4Tb9*eio>>SIv=(+xB3A3F8*{ZE%=(x288 zN{@4Bp`Y%^@%vqATHh+$C#-Br58vODh(5ATQi|zJyD7AsCN>e#frx*^2IND~cKxi@)1YGas za)^^izQzQ#hLD)x3FE{eqvBxhDQY*C`XWn$R}OE%g1HDP(U{?MF!MO`WCHIVt`kBF zDpiw7mGoEjFY!HZ6>m|>s(uwQ0xH&Ny-zKjUI?K*fF&q9jf&L_*{BeT^fEMnL4HUt zCymrOiNu7GvCH~cWrFvF1-(7w0+ErU68k2ietW7Fm<|+>kEf*%Q zhETcbmOXi*K_NSh2?`Q2Xc}X~(fY#QU~HbQrumX!nYq@+Zd}UjVz@yzV+T9*l{pjR z349KTEGd&A?0Afl8G64Z6#>OgBGhDAvBCM=7BBBRVm+cWH~rVyncqG85KdVnbLZI* z`W#>G2epIu?a^G($PBdk{94l`I=tF@DwG{r8M>u69}#S@@XY4@KW}d#OhcU`C*^+L z6g+_tk`ooDQ3O)D&0JFd;e4xORPZJ~i2(hY{MEMGk4J)-0xets#SGkCl$bVRZb zB_kyhfxBP6aA{lR6SU3C{go$JDLBEOM&qzf^dhe==uLRHNez4O{I5IzS~Uj zDJ}Zr1D7Nf;K`hZ+3Zls^a^?0)ps%nC9@Byfet_Xo#SE#Wz-feag(JUlowHv$R)lXj^B{F<$@ez)FTn|}py}Xl(;B4050E=!!MfKMa zQL{4C>?BYNyf*Iv7aYq(bz3K9S~b7!tk7G$SO2c(IdIL6IiK0a48ulM^5g?$Pzx!7 z98v-JT);+_AlJEi9QtW#x4aEx53YtHI0bvAo*|>aHT+4l^mwKW1HS$`#WmebJ$jSc z81mw-4~iWD<#Wb;CSpz@4|P7Tv(1ZZURn>ni`GRGfrvGcoYZe9dm?eU+yR_5XBQ6- z=+461Wi?H2zNIpAe;=?P?b{aeX-ZhhU&b*AFQMh7#XbZ?bLOdmV!s3s6GLwOHK4N6ZfCFdxrVoP+I;t1n|uo%_*FJM8Qa^@oodm5e9y*ZB}@emh8s zkwRI2k9gsyap26Fvf+4!V{N$m_Y-;OdvZXHV)9>KIxETx#~YR@c9dXPB5Wt2G0OuX zKQbva_RSjk&*SbAqq)ks6ia9*5<^FsmVwd}U+A<^mpID!ew2bZxAuZ7vZf=#a=>y2 zXuj2;pWx7Wta-hc=5=&)XAzf+b90UW8<30mxbxgAlXCr7Z;|1sRYUX#Rm7DL8P2xc-r+RzAZpra)p9r;=m($mg9wYw5{iW%tLy?~8< z(~f%-IvpUPY2}OAo_r3mOh@$a_@;7qHF11Xscn0DNba^zV>TUKwFuK}1qj2#iTE7_ z)#t1#X~01O{32K1qHXHpf(Bz_PnGlxy%B#k#nzFBv?;i47vpFhI5t&A8k$+m zHe|{FN<+!zjVUFm_!}VtG@zUwrAtVXxRltgMTP z3-t!=@O^oAY87Y|$vAdNd%1jygnQKHUV4#+E)t4xW%F%N*fx%Ywe_Gjd)u-IET@^1 zF&1ZfxBG>?#eKjBwl(d@+CST`#RWN1XHjy?m^p^jrJY1zF#W35-dMV1mA3Cg2LrN6 z%+hOmgglzwQ+jw`%2dPx1&XQm8pzb9E-)qzOAYIxCLUtpe6lgMtmj-tY3WTGSE=q+ z9T_=kx?ZdlsJVZ3CCsxX2=zfB4%SdJHq6nc7gJJs>ky;I#~BbQMJp<%NMuJ#<_9ED zAF_EtDQxN}N&ZQP7boSRP~qYoYxHDpA8X8*C==_++M2HZ%H@qP833#c5H_Cu*=+c` zN&wg8g92xzcVz#5N!|q=EUkaX_Zg|Es^+e0E&snY4WTDxha5g&!S)w!=KTl7|2?m_ z*!^hUt`L6-kp`ioJY~Z{gI#0sG_=*Uq5XT!nz?OuPmB}jkcEfvMTV0b`vIE+DCvfv z!pKOP5Ghc0R7WmJ$k_Te!2zq|>vityq(uCC z8?b%C2o7Zi{=kHol$mnwddrvY$J)q6_wxsXqwV+CY2B`JKuICIA|krKu(}SYi~~(C zdr&CDST7?VJDtuas&2tNM%}pf+!1cy?fY;hh;gy`+br%QG^k{f-$32WGKbQ(%86f} zaTP%T-;ZM$x{?$s%U2Hhm6*iAamsKNlzd~jC z>?;;dD4`%?r4N%RP#CQ-7tDy1-e4VMIwplxNTY>QedykYXX~YfND*ADxto)*J&}WZ zII{8j6cgw7t51PAhc5nd$kKoxI?^`RVa#(KD8>!e4#KhQ^=oRP{T;(~3)Aq4xTK@&fb~kg~%Fk_*ob+R*}uzPFBD z8v=If3eT^VpB~T@pz_SUBfTRxS)vH00RfVF?Fp7BMZZt|I@;Z_@86^s@ zG*)z}P|AjKl`%EgsOR4vscjikRAG|8He!b_F6?^hJpd9yzpmR_T(unn)JW*cYQLCC zgK?q=lb}OIk|Wq)jLuuMX?iIN2UGD*p#$lfTy?FWkNE@F{yDe#{cMlm)`|GNZjY`~ zF7?SB$P3w&HrC@ZD(?LEqIa0d2#N#^f9#zEY_xnh8~%m5ODz&_!qrmOgrOu}OlDgX z%asl_UJybWFy!dTTi-NH_~Y0ZhnE;s8Q$PEVY8~}1Q8h(A!e-Na42q>a(;7&{pDI2 z!Z)tYPgpQNC2%+lGbQ3%b}+ygvt{ko>GkD!V&whtVSgn4<5gNYv@{$YcpxS} zS{|awnv5fZrWPumLDo@ph!++!6&Aem`ue=}cCc~rX6fY4`FOw|1uTNQ2CrW#36p76 z3AN6W9R_v)#|y!lm*SEyOB5(;7e0yOhv1@sG^#9I@(m3ewc*xQtfoq(Vbs|L9Q0Uk zKwMDKwqUn`%FYdypB@o0XW4$~DuD;F`99N4_D*BQinet%v=SE)Z3JnUqhfvyAedm( z+TO_0D916~lTrNP^B$5K4Dy9~>&>%j6(=r5@LkW(O z%0=$hp4(Mk{#*IrF@FRFRJDyhxM@VJYng7?z?+1k$pQp~MKpjg=v3Lq(aOlkNfKiXlYt<4{x+*8w8tEh9OsAdMT(RC zFlprOiMDK^xG~prghX#cZ(HsjI2j*bfj~TtEYca#2F84iz#`I_!^k!(;@rs|oDilN zj0r9oZqOtFXH^sVo$&nS4QxSss%d!Jq29FUhG;SbTAGH-%R0mSOej5~xRXH`BmA)@ z0Fj>jrEzUuj6^IOglUZYCr}QT!?hXdPJTD=_CX;}V<*qIE9GxKSH#wm>(`-*93j~N zc*l9QTtLxnr*#3(@B4&W{xX zc{gpac~PHHx}38t9J#@2CS$8JhImYX*MP_%NqGWYaC$4_n7ZkvECOxBwk%X0!n@41 zzub22S8OlfkAF(u>t&UM^>R{8~IQvcgO}agV+r z|KEYcAoo7}NKiAmrm|?}b*;pea4XK1geh?en3-wPKvDL90x_4PV`TBK=W*`K?Uu|B@W?=48YXS}XkaW;w38}qSUpPqeFQw3B2;KG zTWxkS_Y%1Zmf7PO;ped6aPcd-8U)fy3S6H? zDnsp01E2-7Dy=s;6LaTKIOd3_jjM1 z<4ZMh{mP|V_-mlNDc^!NdKG0ILG~=FFv_ zQJOi=WH&NPo~fg63S+({Y#0&)%hSk-ad{9MW9M$LKN>cK$KShCggpNuS?gIlK|Txp zgs5QYEXiTxG}rVYmJykAlgTpAg=$T0Z@0bu+mlTuROS2&k^@j+>5l4`f@@c0{OM|K z)$YBAZrEk0g@P)KeyAeCQ}S|rwnl6}9hk{^*aWw_SXlH6Z+(0?ZB{6(}Cl zi84Ocf=|1`O|B|lgh zKskF|9(9B&lYP%+=b*Xh_qj|CdZwNNez=m=gdmZHqihx97q@y?d~+I_>OjcT1_g2E z)g)q>8CM{FOJpt&_7XhRJ^^1>AX$=KumiD0b^0QrY%44+#v;(qQ{= z0Ex%n&cEj~3V8yyM8pqOWdk=2>ovc>Ak96FTQn((GJyjgI>t@KQ<0M^uo#OTwtHoR zg_(2Y&+Vz*-EW@5hn~Ybkclk>Bo7iy>#)Fz_}$3x%uG5|YfNP3{kyfteKKjTx4-lO zkzWN^S-j+?Tr{s6TNNc?O!scTT#4U@xoWkqNf2@V-*9_dFxRq=X z-f1exO%qXBAz3E_l60vYc!D5KGj;Fq zO=6VXFr{P#C7WOsp(XI&3vSc_#JRaug`tQzp2qN_gkfZyUxpjYCtn6 zX$p<5nW7p9f*2Gb+kv|y3TJmy(DWOgXZ@A8cN5pLR>wX3wPZy5%N$CDIyz7df>{v* zJ(OJpa|iXCbd4pS)M)SCiHQm#+vmx;**=sa=3$jw1=nlC+bLE112=&W|KwfLVNo!P z2~tKVw*px4M_2pIB8~`7bSI_Ft)fS13EHSpD_3 zU80)2t$d5o1Ou%|fj}Z;s{|5bi(G(P=yv}c8_tjnh@(@iC8{pg7J>;PWeSQDI}AII z+VNx3#26ZE(>kCU_&tdejMy{NEnK zT1a90A6Y{(zBYuI+Ckr@d37J#q3aT88IiS)_05F3pIGTkDX&id*PU>DNBd^w8xYjhf z0SvMC=v?T{8~hboDofwme&t`jL=uIekc%Md@7C%2{k?tqXrg_eT7A7@!bRKkh6WNv z9YSKpP}4fP>IY3iNeUCwm;2kldWs!zO>lp1xbpDwZuIcrZ2QRaaDQjSkDv018iVrO z#6kV=pQkzncMS6tOh~^j(&Z13zi>rX<+#b)XA6Jg6WhqF#|VM4m78B;JE1;h?%F2=9r zz=^P6r}J_D%&@h-TQ`nQosTtemzYTF1($sqzdiu_OhbF+Ga$p;_+ zsiNq);vr7E@`FB9Rn*aMXb}S|mONab=;K{R!R3O3`PpxQZI{7=0N2=Em{ZKucn|H9 zn{j&%zsALZ)f8|3$0L3#P17$XP>PX>5!DT-5(Zd`6!u0qUJ7&N?0wqyH;Q0Wu881B zc}bp(D;JwmR?aMw`AGbDCa+%6xb;4hQO4yy94;8GW{DV7gfowXTc~q?nAbq;V~~d@4xyw2k#Hz()>)O- zSQ<;`SD1v95LM_}b9>MJbM}h-e`jwkYO4nQCjz_cEk5+m8Z63kKY5^)vN-5Otg?}o z86DR@VobRRMLjQ-4Xy0BOQqyWlA%TcU}7r=3}ueKeKRh)F!Us3=I(G@g9NnZ>^9<* zVP1&p9w8uhZ`C(@HG@QSe~>Ov6~ZIXT6E@f3mTv)3_d~_9`jMViCuR6=s8kT1;(*ai8^v@VkB7@M1A!jz2PXdq zI}i7XXl^QW49~2QFbIiR5c|E4uRr4prC<)8b-27`�H17PJ(ZLq!f<{`4e7-avh= zc8_If5T(QAa7lh#7{OJho}Ii7|hcJGv)~+JF97|PTosPG zp;<&2wl}61vxvTrS^F@$>@W@@GeZIT(dSS6N#RQv^Ted0ZK;M}I+r-9XTS0+V?i33r49xdXJMHaXIh##% zU+v6C|JT{V&!M;ebD5jlt=eIaefE+wYHu|(No3%~AD1vzWDyHXc!Z_03ZhjjKvPS> zm2Kfp0z$k6T!&l-ydtf+;f|lHe=wbf9W{XeaOA6nt z^0vUU=cek;NLc_xllmK)s+9YPaN@-bm_@@P38LbalR#9BnnH!`ntG?(nTSwklH4ZK|}1M#Kp-u@JV`>=6K)m&E7w^ zi*g@}a}5bffOyil3rv;oCetNby~|v(Q!hPa)2$kZ8(%^KYv7Z+67A8~d)|bKC@R;% zOIPYyMsS-koBPRQj^m*~3y?`H5Os?+i?{W;#oqCJ($M_u`h-EOp;@zIWsgM7pHm*g zAeSQ&xEzMt+shKs2SY;nbKw~!k|ohp!-BcGjGQq3%;Kc<$HBj`Gt}vwBjFGqgA->k zAv~lc2?*xp=A_n7&tqzJR|K!ymaFJUlfLsLUJojbt?bwhG(}1ZRYzJ_TtBp5Kpk2P zo7;3HTrjxSvh?e>ZHa^li6?zt=+aMZD{6#|qEXsGmcPO2g7)${bGBdYjhmz1#?tgF z2YzZ$Pe@9@T^~P@^x_1Nge9vrGe4`t2t_eWs7kA;{FR0@;uyc|R`y68B|WGlA5bx; z4h!!cot4Yo0$+PFr-QGR4$R2jzwNtEihg2Au=GwF=HT2wg7}{_VfsI5LhY&)=?Cwu zt-GQv+^;o6Yu}^!^A0Fao@QW~iW2~y4fjn!9|78I- z=DgXNeqj|-ppr3tuZdJ9U=X!s*uehuVvrtRHe@4^`RR|tYE)2pTk5ACOUI$DuGk-% zi^Pn1pWdt~_WdQc3xDez%Mx&i0l)=tqoxpK#rXGGQ5}^Eo@P842}~pr7=v2jG$>)n zT&aJXeBK^CdtREJAH!e&-h9O28Fq|RK?M-PP~ubeSn7tZC-x_hQJn%ucQKI4}J6PHJqeypMj7ZMtkI_LfX zeIS~yaO-BoZJUx93@Ff&Qh*UNNpbwpsQ?J{g^0R{n;BIa0xJ60F`D^t;v|{Zk4>T4Rn}64#$$YKR{7!7Kc_sjF8Q;~? z=PTD#!v2Rh#ASZ z( z&F&hnKH+0wxc^4hSB+m<#+yFar&X_OjT9;L-FCyBH~4$iTM|Fm+LvykuKedRI^TXA zyMB)Q*v(VUOPKy{AXHp`3K0lC;?pXxtZ1VXZXSy)1F)8Tft}08 z(}koT5_SZ0F}0w^-(7X={*D&pAF)E<3%AnBRabKby8;4ZQ439wRR>JW!|Uou!*H4heOkwVLd^wO5&$;vv-pc(zA&I z^Xh-5j=M_{|7~pieP14X-@-ew9~b*iMW=sup7sRIv&P|9t2=hAs`CZatc*t4A$V<7 z?*RWBXNZ9Ig@BIcrg^{s*!=4w2SxG znY^Con}e(4R&BL4S1zKmj9pC~;@BuT`FK3FhzhB&Ath8eBSvm))^I-J^-p&1zt@HY zeHtGRHg4Z?%~ZhDmjSK@^9|vVLtF?n=%;xRDkN?a%eGC8G-88PqG5w})Rn3q=8Esn z8NId{E3ARuQ+q8$7=m1O_BG_FYKXDV?R>R8r$eLfvVgCG*sE4&Y>~xT8Q^LWgWyHIGEd8pylIiZ5roaP23~dRqHCLvZM2L`gg>BEVvaYLrw> zVx{vsedCUAiw(MVRU3_-Z$JJZui2m*W57vKR2iBn4@O9#rOcIPqM`=chhH~K2@pk3u{)wCyr8zTEVWBZdla1;jdTZp) zP0M`lao`f)(Ax=*7+Si0h}WN(_>y{)_vQJ*MbX|du6|z4BOl5tAL>_B*XZ!l%>LDr z$7*u;S1nsjKmGGxJMpGxMKrjkrz!M-j4%)cWAONt^wKg!V+;Ezsy1L76QvP67M? zN#J0qMHau*sKtC+DY>ec)FR$hcc+p=YesNGA`4eELwU|7ReP2@o2*b*G5d|ruoZWP+)v^w_(Lb^3u z<6jrEUg7tzT?;BJ>Btzy1;{+IW&HX6q{h!|`Mz8q3fdC)RQJ3i?^;)WISmfx3JOF+ zv1V!%mRS;|y;7%$3$q%St4F#v66krpe;wc?riy-ket+{Xz%k?tVMYw3ug7BdBqhO2 z=-*~whf)?Hu}fb!DN6k2-E5MldxVH(Dn^4h13XdPK(0c4FNOSb3;FqVzdRx)NfOtg zvi`jV)uMYV6OdEfp;~zMj3kn<{L;S#*iSLGzv#e3>88Q6&aPvi3*Ku!3+uA z9S5qNHfqSmL(utx+M}oUV;BU3!^&U)1tLL3lLwAdFxu|jjS&YyK&dI?r0+q-s6S;x zU3mPKag@LpsUeJBa{Dr2`1**vS*xQ}fT(vkJQfI0gaQ_Z3l{S2xC|PG@4}5>a=fFz zxA#>JT3*DDSovR%$jHo)<}GVaXjcgdbJ2)OlNlvT6^F@M=Ye7H*~=3v=!+ft_UACO zvH8*`_K2qhHw>7ks9Arc8#0gh#Av~o|7IZI+|iAYiBTFg51T#eTQi6d+s;&PtA!UU zF@gRPwy`KWmykk;_n=JtlP`SST)weUj^|wu$*#6|L?P&Q6BSrh8SpLY7rIcn4)zA5 z15jp;aMwSF{7O31 zLMcB~ioCe3Y!JIeqILe+2OPFp9ElxLVwL|7NW@_Te-iwAD;S z4KuqwuX@ZX;%lNdryxVF|AplwrK(g){+Yt|3A3_3vSK#%ryLWOZRb$N!2U!uvs zt9EQJX3SZ~f!>l1Yif)cI{W$mTq>@t#r~__=tJE8b?*0z-e4Wi5v=|~%dLv{h0IXh z+yG)hc$A5AA(uvsCL#7u5dNHlog}9nlXEa_11gubc#b)@IS)P z1CE)_Ce>34@v8VlR{#&m9G#P3>-8Y-W@Tz;<8|jP5StSxb{6FtPy*5qNUxc=Vo2xd zm{_ejx?49$C=8j=?x$~N37|&~&x36jyv!^=zIh3R1=c}wV5agiAV0R=>Z|YHe2jf6 zeUI-ATNBqg1+v1XLK`?rn+Xd@>f!ZNV;fzo7lN{d?f!7hT$rD45JW@x-2`|BKEv6C zVhQ|^SYrJ8bF^&chl}10wswCil27#EqDHuW1x*jp^eqzg z=ddui9g5Ldh`s^u#{d-4?~xCd@$>LARVSYNY4lnbp3ekC?q(e&XJbTk8j*0Q%$_)` zU`jm9pL^CJcsK~ghA}9T9Q~;bDxdoH*)msGCMU66{Np=d`PPkEdN&9faj8Txu%-hT zW2BXj=n)R$>V;Iy3nNg;P#~=rO6uO7xqldKvQpE3Z^wd3?in?HBF`!6o-KKJe2@M$ zs=jJs9gD}aQlBk|dP!(k4}%osJIFEG@Tn)c>~Q;IrUU+6A;7=5C=jOH9OU&=hP{$a zMAHoCiN zBrbqup%{ZLAn0@3={w7d@@P~Xrz5Q8B%U%#TR#)U(tPMxm#rw;C$3?Dy?*~D3 z)^e(t`{MYezLZA7KnUqigchoZfms8%w7i@m1c$za3vcbp#m~9J!=v^2AnVy)P*%_< z_!uJ?BHKEoS!`@uB;UZDNXi`;odqp$h&WK?uw+IpJl?)Z;3iJ~hB!uvDjmA@JqQE$ zdnLglT2hPG?Ch}oMZgr?46mw@ zilRg-jy zkxJpWY#G+>5jga2gMA8M?iNKKi~_&4UsG4*>vN+W=V7$Q_BiNllc9t)!O!2;_X3#U z6+lAJs=XinBwq|5t1(YkKTqtQIA{{b>*&|K{3hwXEmLqwOi z3#WH*dLkHtB;!8+hAmq`BH(%dh2lTRl_2T=R38}JZ#$o)hV~#(kU;RpC?EvLJla;r>kGB7Vv#Pe!gg#7+E|NTzuYe z?6?X?_tx*-ljX({NT8u8Zn_XF4iUOHu(1W#vuDr`Cykv=-QJVtDZD@VzaX;`WvqaA zQKR@mYv?U06^-F2Z0~EFYg(d9F9}{(T{-{2BkMzVwIq&mQTxBs@5%umLS3fm2%0%l zq=Fisdr_AO>nkn~`H3E`Cg#sQ2|2=B`G;*IeYr)<6gFYTRgenGNun7Pzk?T{}XGw|*Sa{5F=Mg~yceS&d~d4_4MN4eIdc7ygoh_eCd+Og1KIkyJV zOdhWeb==fXN`BHFYzRvVn&E1F8h)MHK{0Slt5~iNWca%W39?0qI0BF$1}5hG8pRyN z9EbItx&go7DYR2W4*KerJ3nG~ofRTSuF!^3x^$EV&8*c%jllqt%OH>#1XN!yCJxUO zVtVpQBWjYRo)jr;#_9@RR_q@eo3LG*_TE1*(GQPILoNaRq!S4`T;Y@b+Fb5_Lerc> zBkMCGM9bUk#=b^01miAEqA9NQgCXQTO>RDrdo{i2> z)tP_eY!e_RcZ1a$xz4Ckb1Mwa;#PRkg%9$>A$Rd`_w;ja*Wo0mM zAqqT?o~~UQzd2=Qr!D~G6jbEqN9qLyfe@uDMIwfx98fOZ;WZuVM&%$4s2bg3+Z70I$EX1oBrPP? zY<^xnANPvHc?^9a_`h|{{J*-!b1wuyFKmE zU39zK%>FL(-2_^i_guqPDkr(DSt9j7p*gW{bXv=tFt#U1Wh1goq&OB z?+u6FO11$1#JnCSbqAxRMu)ad$sT!O&~=znQ86%* zL?^t%$In099f83t9hrHG8LA;n4lV>wS(I!cFw9_$qj(u=o0C)Ikl@y9h}6v%t0wjR zWHxn^C3Zz+zfcwYAuaj~R%c5+s; zdG5${`V*C z@6KpH{s<0~K$kU7{|MPING6}zW>{`=g%lz*YG9NOtszuEbFt%NWHO)>sbRHq9bNyl z_1!k*0qR^KBn`@rrnokd{8j(;;*M zcEv##Z05!lif_OKA4?dyMPnP3P{Sd+Me*q21jnj!53Ir0UCVGe%AR+<)Q(4=-UA#C z$)1&wB6s%EA;L~Fsbm~gGSLhSk^uwb3>7Of)I=0(bhm?171ngQs4VI3^y^oQivvxt zBkwTVz@(vtVF?FF9T68{M?RC}7^M}a4kdVkgUR5|M}On;K;3-f*R;NP(6cf8dgJJo z4=aEsKt`9XI%W`=Hd;tnEbdd334x;E?hTp(uMOw2z3UI8Q`4^X!KvZeI4>RpeHB`X z!d__3=^FqQvxkY@$q4K+gsW+W{!V~O6ahgj+5?@TYRl}cu!|>oS;s2M+g1Ih1hO) zdaSjToRE{PP{2J@0E>}LyO0%VM5sK=^XJ~z5OfD90f-J7eBvbmf|EMNiABR7AA7$? z4`}h-l}6=(QA+fDRbvRq@U)AXCymJ@F{_%cCMdW;Aa#yOFjXiNRIR`&P4!L$BD6#b zKA4qr47QOkZ^g&z57Z0tO&0E2M&pMs7z??v#2~8y1~U|azSn5gf{D=D-Txu#Ex6hW zyRGdIEI@E~cZ$2a6^9@N3Ir*|rMNp3cc)l!r?`8uQYh|Pio4sF=X~cm?;iOBdyG5x zo@=hTu9frFs5<(wx%uU{*FQh(lLnljc?7c9L^(qN4)K4Cod45QT8RFyZP5y|fa0`^sAN^)v!n2=X2pF&gd)W|;Db{zqLu<^qoriF)QN z`nX>@Iig-VcX^=xrfI(rv3L1nZMY#+UMpcZCK15^D>a{viiRE+uP?)N)G%oRzwzSu zwkBgu^!cG4_GJUbFrMn#>2-#(ZK4H z1ldp#4C*~Q3P(w$KH)W3eS9~p&n|-S>kRU<9K|6zM;aEd-*)Pwtjg6Zp0oI zxEcR1ecAIN?yjPQ)79I-^LSgE1<7l)fE97T5H zy{w!~jVkV{ z3`R~>b*qR}c0!L*Ny=goic9;+lqhK)!%RtnO>8b3Dho#h1r(F~q+KZED|Cv?RIDKi zM(s1sQ;*4Qvx8-C^Cpo(hAiCAE*-=Ea>~gg3P=I%L%MlSZ|@MQ+}le-ODK~{BFkA9 z5F=Tg05~S=hqg;bOm5wWyshfn3;(&Id$j(qr_U#O-9JQsUKxg_$PqHGvDG@{Q2pcv zA>XUJ!2<^e5y7WlHdgivg$5Eqn3z}%=_{pgJk!vv9GW>{*J#mTgmL_BLIzKPtVIQX zh*%-J*~R-$tnDrXlpDzQ)^6sXsDM!**vKqwibhv`ic&&6;I-A?f7xEQV{)GIP9QEe z9xqHbmlKXGHPn>IVlaU*b}*uQRZnH#1M|+~OoEMK9i5V*uC>n-+-w@Gj4-Re zNat@iW8M{MF_a3a`G6&hyGZivo8MYSid(arFk|pXg^_MNOqPasdw!AS-|zOr(_n|& zr<1gW)Q3MLChjZo@pD(h6#e;yK?;APRsn93Sc4$tLQw*Un$T|$95qfMWKz(IB`leG zNonhE(H2x16RopnHtGaJTuVRa&$ep0F!DQ`uQ^WoBBea_<;!Jfq&Dx;OZdF{FGL!j zQ}YLAtDpzlqO?J1SLvpNlPBp z@KIAc`9BuTy`FF}8|jE%4UpJ&#>8K9Tz(5E(T!=RW9_>aiMR_x3YOmq1(8uWVR3}D z=2biX@rb7mj~0QmvALJOjRAZR=3k9y^2`wBlo;uz`uF(O8eea#p!W2j`7FAo5Iezd z9C;FkozE7n`l3%u>Re<{VPt`@$xcj5WAtI#Afz(>rBzjyYAP(#R512Yl&{T9gai)R zpW6*rrTE1ag2~L)2Q;QmWXcn2gzYU`I?Mc6Xxqpds^h}e$+Dl@*++?gE~Vov_{z*& zO2F)XCvb`NcLXG7S|x2*u39BkGg_F}g!zwxP+lQCY+3t*)@pRATUN(DW0L6_X zQeIx<`Y&sBbP#oD&}i9FX63tRsDJGXef5jXE^WLo_Yd;7f;KYjIyfz{mR|V6oM0OI>Y-kuhGL6QTs5ui$${heJ;wAcXiluvsBhd5UL#5g z{4R4t@x_EHn-=`Q*zD)*ziJ1g#_-0=l`R_g{L_<@5?eo4zUB;<0_&()HF3w@F)y7T z!GU76)nx8jm=KX{E`G|BQU0^!U3It?t@uFF0&tf^ufo>7G1HqfJiCQ-iQ%!Dytuga z27YtsOMhqTt1H(6s%2<1yvOTNU$hPMGMi>3&>y~S>=5*Rl7e39>yLUkhNBn?BNwD(#( zkE)x6lA23S3blJ9q)_f{vghFcn+4cWzWo2|%s1-)YuLaK(GH(uPej>&_QHV^t$?q1 z$N&B~t!6Q8uE6Dc?}Y~8u`1rQd~OVG=%#8vh1y(SloCDV+4DbzUk%BBV zq+64k4UF~hPwHA#y2y}K#?~|sP$W=cJ>UVl_b$7SFUjKPu z`iPmdiPwS;_p>H_0yvKw0zsst zw@io*>@hMv;W;29HMl=Gr!MYh6d=?ng4L0)Uh+Jk79A2e@8TJtENPEJ6a_9tv+Rf7 zvwCB*wpkC4*T3^U#@nyWuQrYgKFb8KDHUXQQ^-6~HdR9KvYZm!_p)-N!ny?fa5i(g zIo@fdUrU1+grXh&$2eC)!xF>e%;ByoRz&e!il(?k(nzD~@T@HN~+>})R=ZkQjTf;9=_;APpA|q*m z*sN>?#6t;VgztbTAc`$ww~ zE~`d6K|~~LoZyZpQ{Yed3e|_AGq@lhyR%=X*I-5isNh|^;0(e#8eF*K#5--QO`GEu zeetUG^-iCczpp1NHyuwdO{fte9H^{GUl|Z8Ww9c^g0O>>`lQdP)DL^(ej18os4*_2 zH-4I8H|gwr-QC+(kmw&m1S#TR1(B*zD`JK5#nK`bynFh?^hJUuSV<&yNlqj$lq4D? zo?GUUG>%=Q>Mp?|(V6hZF}c0sOXY8GamZ}(E~)i+kTJYtJgLT(Z7Qo z>nY0Z(gd0&x`0hHp#-Uzn!> z4DgH<%$cF8YL`2eqq8%f3F-}fyu?Q63R9}?h{e5FMDSkk54cSc*>c(cB^}^EmDJ3r z3w39~Xe*#l_HQY9ipKlu;0qkChlG^Lvs?;Lnm1H)T9Q#)Kp;m3{3P1u?2-r1XQxq`qv) zu`G7p#!mx|!7EaMV9e<_nn*e}9_%2UP54HlEk?)7l+?U|Q6p6eTwS2`=W z=ogn3Aly_oG&SmBaNXYm;q(vjIUnKA+-Ao~1)@NYIH_==LB_+x59|uq`T4_BnZ<77 zYw#;L9)=#SJ#B5J9bIpG_U#uA0SOJw7*SdzDl`*Rpp<-5OD!i;N$C>hivF@q^3SL(grG#bLA;J~bm&m^hcX0a% zr_L7L9+B>Y&AHGI%R)+1Bb|NWBzMQ=UA6AQU*Yn(D5jZXtl}|f6y6A8Ygkd^zRwk^ z>E>4``~DyS1OjFQ;aN7*t{YD<&>>c&MXMQIk=^D|(98G~qydddk zH7LBfS%%~XJ&j%s+=rqvOFiE2%UK*YK(_4A!B%c_3kxmNDyu~Fk6^~BhAp?GDO2|3 zW0r9aZW6|yL1aYv<+DV8RH>+<3}|!Tbanzz>204bHvUsPN=W`+?P#|7f>6WD?!WBk zo8m4%L>9755F0s-S)52VZ&|WO1svd|3NI3JIPI7#7Eh>T+b7l54VQ*?SF5b+DSm7K(J*zVw zHw$DIsN!hEIL; z6*gk4`Hw#KwJ{6h|PJk6bU>adv zxwDCMYobx7V!lDRiWD3}sz1%^z9@FARkqKMNOwLSEyAnS&lL%7QL3X6rebo{q|C%> z8JRzc5L4rNIT2vXSwm5~Lo0D_h{MdjD%t$q*}Cz)Jx0Ak$(!OLhVl<1Fk03KrDExP zwJRB((MK9RYZ+Njhda;vL^@PB>r}s2KIh>|iUQ2|;p!r@BHa6J{QhB-Q5Fp`L$NYi zvY2bv68A}K>3&|KMb;_{+wQFtuD0TxjF1eY{OlE^j7^BBviMUwL z;l@Em6mIqo+($yB#R{P^^R(g$x3kf*JrM*;eBVdQQoFnWH!_z@^LT__fQrbx!Y5!y zmwv?O?dRVG5AyiP<DfF;M6JHX*$$17q}3EW#NMk%tAiN8pDU8=Q{Wz|L*NKzr4#TFzETI!&n7AU3cb zxj?C$x~{^EYx+Sle@2wpI9XbS+>}!zjVd7t-KKLYIL4GA)NB*w%2GH7vmtuRGY>ud zGe1B)H=eO%%T?PHARF?1x7AvVd+7DP8~Pu=u4p6x@c%@E(_{Nl$ybj9=`gJ;!V`B~ zYY%IHrXlxB)u6#uucR$mGZR0Pu2$9IfN*OUMv}9W6Q8dJ&9-%AB~j_`Kw$*JF;g;2 zYGTc#oux`4Oup=lFQImzagTo&Xjz5^u^WDK_y`$AqR4L^cUe$-`)Z27&t810$K2D*}c1136Dob@6I5Q zjI;rN#r-gI+CZF-M7KW5s>~AtMf3{ds;f>uzMx%Jd2Nh~6CUdt86db5Sv|Y4DspUT z<@hS_zR|6{wh7FTfF0bxVvsGJ5}eSyEeO;%BmPiXi&lLU>S?N)2f?-Vzf|EEDXR4H z78-$udc{SP(T2z-VBu&*1F$8r0Fw!?>nN*t-0{Y)fu})^*_;hTm19{dFQH*~2Fa`A3Od{*X{JzghLyY`==O_=F1SUrLa(sQWMp zC8g{Bw+brzMNM4uOqU$wv(enobcaA$WA|4I9M%N`0U?jMZ~EU1EQ5zL;q&G%zyAdb2k#a z|L>m7e`vRL%VKO|=rQr6Q{7?!)cBhGU+aII4_Pqx^w*U z9-*5^0VDv>C1XR)z@}7mdA3scF-3!)%qci7NB68ncSMmHsgNx9J4t`J*D3^Y{!)K< zy!Es(K8N$I4muPVTzFpfoYDr`tVuQT(dYoPanZbfMGEoq

iJ&gwjPp zxWLDo)7RTAfp6se<9jbM_3O$fY)t01QA{8sENqOkRU-bT(T2{dJD7Xn`#qU-|8CBD?4V5x-c4Uon9~tv&!J z^^92e9E~iq!~V6_ec35kofjCK9&hU^!OC)QAd6c@bJ5tGK-sfCU;7y29VyM0gg`Yi z$;cHfg<=HR-A&n+i#L1$m^-KX5?m5k94f4P^T>uxE+USIR^G~G4 zi8#BR7EXItl;6%j1jViW-W4AZ9lpNVhQoaWdYZKG=DOV_f9fXgrhbuhA!zMy!|C`` z4~uQnRc3|x?`HFM0GODhoI^LZzn<<2e&#QdR z@t!f5+-q0CM~z9e3Euzfh|qG6*t&Y8@21SuAM2H53E2uo!|%$Z-QpnMK##fXmZ!b7 zlkDuL?3V0~Cuo~!6~(H*#JCnllUoqIK2v1^626uaN)$IUbuYqun<^fL%$Nwh^z?6? zAD;is9WOOb53RCW5&g=C#}ZKLM{p{7wmH+shZgW>WwOwIS=0)vNGedPReGNfO6kKX zn^xYo8}Yx6ejYZyQYB*b_RWXyn~uLBeJj)v-cvB-^|tlwg+IbsK|K;nGpxFeSc#bH z=y1~eT|2)sRxBMwLQ3v!OQrZ{lm!-|=7b}Wgp%Iy>NE4XTX-cMEG`qe8pWR5#HFJd z#n=DjQcaLX8O#5tMZW)wnd0}X!B>hNFzP0NfJj{U7mJ{-n~3tBNR>yC?s0>uf-uE9 z@?j0Cd}0vueMs)TW3`+~1TFTwn$4@mUDHLut&_|tf~OqFiDG?#yslOQQig_SXt&_d zB693-a+yBrxPI~ST36}!j-l6@YQOAqxDxUmYZE?LMpXlTED=shR_SMd3DjQEP7#;b zf|`8HX|O0NSG{qGiG1?QHI807?>95?K_;0znn|u7iaMr=SQ7{C`ci_Dh@AC+wBROf zu}b^MMUVQqDG;03Tcvv3Rq|efnkpkX2KHpq`$XqgB=TFzP|U=c_;05(zV2D)SwE}mhf0k=_%3s;AI`43D zWNF|i?bpbGF^IS;c??EtB&i(Ml`>;XjEZZ5RUH#f1;$1oyFM@kmHMg)A6e77E)Wu1 z)0%9-X~6^KQBE4A>L60*VEA)1`|s-5&f=cKTkE33_Nu;q7 zrSg)1c!82tO43VITSgqO8Iwd0pqy{+@29)9m`l>6`zWyBSd(h`CjFG-vM|NpiidH2 zyM$9>!(E_L)6hsufr<90?L3C8x(wH=9UamIOvrV|J-)q+wUW&B2|M!9A?Q+DqJuRi zRv2lxQ4EWQDS|!1=~OKezBgX%jqguMJWO97J|50Zagvw|%iBl=21$|)Mo7-ljF7K=1(1YjqyA_QXjalByzDc zW_qTL12bD!@ttK4R&!)>TXN7|aB{k;FzoHYpI#ukq{p(Gf6oJ$67GcjV4?*eATh2h#0j4OvV+(Bvv4UKx%gOL9v2 zZzj0`&7Vevq(&(xzZ_qp-3|~9RGz!+udxov5Ew}E@P%q9u>O?Y`aTlw;BY@Y1Oy`pTxQ4B_Jqa36CjS;4 zJ zJxHMtH$yHb;FsO9BGs-R80jF%;yG+2Yf}pmF`?z z&#B83>ZMP8oBU>cVG#@i*x*fYg$M>Bs0^;fNhx4^ez9&g4zf?D5&h2Tk))z7bn~2e zW=?5o51+W_Flzky4HXM76{>A+xaIHK+Q#9iJJ(^^x{|3%k13}cE)_O0;DRbUfQ=Es zjm65!R=H*EU73bzBJ8QaBA+Y;n?^0YBA#@4y})O8F;a8p8yN!O4%Zb(7Irlt)JkQ{ zlAtkQLO6AlQt{qJP>jah`Y)4SNlv$qb0_==C|@Zso1Kqv;Atzet9;Xh><33*c<}dl<@JFq zB>Hh6y%PX+sATw3=AC0upktk2i zRRtde0tQw^$>|sX5vjxA=&Q8sUEj-O?+(XAmNK*{{$XBG-@oFTo@L<4{+0A4$&$wu zRV7HOW4ODNBFpphYDEDR+yc2=BOGy5IZ}U4PO$o?iwajWKDV+(UD()0juF@5v;WKO zgIhsYIOYf8=WLGC|I`R){|ENDz9-248R zXV}Uy<>TaK@j`K~l>;&0H55IOXv{ZJitht|H zgt79=4}lEn;h`vGcr+C@)t0t>yL7WSouSKh7!gap?#_OE9i3Sp#SBFQ{2xYH*=jh+ z_|k|iutz}OjHnO`0TT5*;wU;7aJrEQvygYr>7O5oMhnefT_Q$fNw^|iBE3d(lZ>zv zMGS;H4G;A&TUX9tsLvbfReQH40XfCa4`#tZT{Ga}NkxmA&VgDG*vIM0p?kvC5Uh(}aK%V2v)^+ulrT$GXfn;&5_H zATA$##uXGDK7bAaqC`&9Ldt@1epBViQ};s3?qDTXO?}(I3p|B`(_MaL>~XVy2kRYa z&s^f{Zt!ETlnNFt1$8fCC;+0k+w$*6BswT6Om(otEi1y8Ejdc1ggf`oHBDD58Ei`h zY;v>D^Xn*@(O)7Wefv>bL|a@BTzE?aGHdR@(eSxma6-0%`3?5y zO(b_CrQX|ZEk0?TGmf#OT%T|dHt^cXEy{cfF2!QdhS?Xllgj1G75#SNd zh?TkY$v@FS?S=wd(ND;z0W#*+720%Z8hznc8(0dHkJ@)J|J&f9{jXI6JI23t1f%2O z3gZT#=KLe7B&M_Hg7@U}taiFX?%Mc1dMA9dL{>ay)b(_stw&Kpu_0I*wocOP#VN7J zo>`VMSI@ZSS{Y=D@rC*u`d{)As}->K7qD7ipBJ^iHoxEW7swy^>KY#puNg>c`ujjg zk565PKJ6%?#bmAX!RE^8X|MJ*LPyRRPisDkO1oIHqPT{i3P%%rF2BM;km!T*_YgWI zlaj45}OY#Y%kTwLkq<=g|0A#X29DM@M#jVMZ&hC|- zu9c12in%=0^bS$6g_z6MG&j==l zKt=%PD4a6hn%We=a0^rf!}P)l-zbVD5H-ct&SUXR^R(VDeZ|M?p3S$LZzY6-rJA*- z6Lv@Im0-+!wUV&+BHsfvnP^9y%@X*K27?4OP?IAIP~nT=Nx-UUSEklTUi?|1OX`zv zqC<8t^27jhIBpDgF+q4A(r_!Ck2w6f}@5xLn0F*<+RcDNJIGg=R z_{bdrhEMSTalNMvXWZ6OE^(s>)G+_&9V7SP?kCKI@fBzBvwpkH!4ZcZ=E~;T(LhBF zjJ;Mlo?F?R@5V1$hhASnNz9q7njthx?GI*F%+#T#tH|Ol4A2Tt|@Z_-DiWareP4Ve*}NWDN+{6bT#zRx}T6X;dt)7&c8sqH<|bAT%1p ziiC#{d2%*M@PP*bNH&G44!mAT{3fAH`bX^#Nb2cQqETMY9lzCUVBjiW_5boIibl@B zV)nO&5as*~rVWQ9ohVb1QZ=P4@CC_M;2P3Vgm+WbSgr?sxquT`HTHuQG)#U&5ET&Y z9Tb6Y8>Ay|o~?dz%$@zQ7bEEU=M}^>utQp07eaHTctU9QOXVQzO5*%pBz~kq{c|n= z5d@UUcb_s4Ile7e{pN%1`rj--&BlwBtB23kT>$}@!@>i<@NASbb9Tu-W1XmF#~QffxIM1TOj})m1gFz z)~_FmfSBNZAwtiTFmWr#9pgS4t zl;;@XraZqA3gA}%Xk0S2@5?n5nE+%6Y}4G;1au~8L4n(;{J&-+n;LnASdQa{Cfh^K zxdJY*ZwSs|%Iw(S^BNLZQb8c>p5#wL=k&h7GA)P-M1P3S|7|B4d9}9Qc+|zvQP;mI zd6MEuxSG{4%}BV0+&2(8#grIcO9n5*{3AAAf1qYv!c8dPNT`60?{iJEP~N_9F2hdc z7jIR)g$$EzXv{R;AG{DeV%q2=SwsUWnH{9%!1fj|-Jk=%7}26!hgFEa?LH!9W`DcF zAnkZA!OXHYk516M^V5A(St&F?fg^SCByTH_gei#J$vTFx!VOY0K2XBe904uAj~zfV z(w*yO$NWVuT_#74O+QbI;UHrdr6{R1tx^Z)cuXg~_kDGgAMG_2IG ze^3nh5L#T%4xysLV`?r#TlIB2r*D%sMn_FcF+gWN^s|gLGly+HR93En_7|*L$dF9V zjEWLZ&0M4)2_>`~68=eJ6mjrZGyDbmEL3uZBXSn-EEWX(j!ZN$(!aWo^ApRpuT2&2 z<~QnILA%$}`R&@{Qf7=zyJ z$%y2YTs`bQJ{~H3>%71IGdhPaPaN+84yPJy;2#5<_uVSq7M$?GFS>5P{SZDo{d_{f zPlD)Mh2TJ!YlyMX$0LZdG;7g1z|{#Z%7&UjZoPL<%>gG{e*#6u?2zm;w>t+gfTc7RzK$3^(rU6&~i=Sh<282lC=8mzWR-F5`Uu2`!!)_WyRyll{gxoq&||N!kG;f z?z0XQl}n-~rfOnDjaIkiTOZ*v@Fc)o_#CcqJ0Hp;9CPs0TH}vNm8<2da7G^H8EU@N z=Z?)_(`}?KYZ0p1D>u6lW3?8Ry6^iWXV^lD@+M zHghUH*mWMAyyM2DtT4N!CfT7il=vS?#ESHP{X&Wjpbp7_YKQB2AdBp#p|%|Fo(OMf ze&(clrzBpFckfo6T-(qsT=q=?yR`9x1{xVUCzLL>;oWIQ>(-~P`CxdJ+}(^{mqSCI zf-Rkyl)9AzR`_E$B;a~W`f{Z({Nf4DDmGcv8sqa}&vCv+i_hZO zlk6OqL(fZ;FQeCohldY56IP0BF>+aaeiJeL@9%!z(Vu*$*vpCkt;vt_0r6-ADE5h6 zgdG*=^`(4rQaQPZQgNt(fAnDzW!Bkc7El2|#OUQWHQsa&;W&HQ_qdrHTXRq?_;Ox? zLz@=0SwJ(NH9W`{IxMh6L`2}+k5D2B`q~TpOQZL^-_|iKKsm!u1P{vCLsjx1^?l>8C{leB^U;nPL<2p?rm+Msf&bF~`(_ZIqf)Xl{$_v6Q`A>beCOKSP4a~dgvOkH>y z{gsS&=Ssn>?=o!z!4#*R?~1ROkTglKG7^1_v>Qeu3a}QC%mILyVRfnG`J=xvxeLEj zM(pr9oC_MMLi4F`OC^NU&}K_;@p@S{o6}Y*K7>C?4Hz4Dvo?D`nlKzFrSYXv*1XQ7 zXev|%ds&>5m89ik(Uqwqhi$2Xy zS;$VL;0Q8xMqt(vSQKdod+QALeb6AV(tB{qQz0aZHS{t1zHtXIx|s?P2v(Sy|6QS{>T}_e z_d%IlXn$IUpaN#rkgljgWFk9hpdusPrhgsnb-uWcI*+MKq!|qyIEkv}<4n>?4_wjw z*kyu4IreW+N@3VhVqzU=zKGSxKR*ww_v{#%gje3YTA8agiFoQ_PQh?n)b(}}QbFY( z#wvU#^P5VQn|EZGkx5Dv#Gd$6&(YB9mGw)06q;nBs!+>*;Qh6dxCCCsb=P`#h3va6 zeibhrM%)XLjEGGT0(h$g9~$2xc1umU?+85Ws$fvUp^R3{DgorU4riE0_=m)M&I-M2 z|DcnT)|Zt{m?PIDT&4CT4-8D%GCTu^lL+R&W7hWy#fk7)?P7LFfLcVn{dg*!sx69*?AFd=`{z!Cncgv5jyPFt7ARy{-Zitvxg1XbZNv^+{m+!6}twW)T zR$&@buTKiH-NK%Gqk-7!#`@ZNrx=^woZeY$)pIu(GTK)<25+lf(k=`DYSClkKp8?z z|B!?zqp#4BqDNdkJTKi0RZ^6v=gh zJrz)GGwdpF=lMIOvBEI1oF}MoN#8tjLa0N{N5r;~X%(D~wXq-0Kl!~2ie?-J?ho2m z-F)%Y`knd~EeEw(0b#47;iYVCiuDIPJ@@#%-U^IE4O%ak#w(-M**$}@4pXZr4kOU* zyM;Rq4rkaV#%kRK5i03dYnBuD5;HkvHG%822)J!kF;+i zu3cHhMW6YzF2BSr0i$6h8VvHdOJt#lLxr{e#^rF`Vnw{?T@a~r zj9b^;5>{{|*}_ab*4^D*&*NO}dbgip+MWgX!>GFd<)3e_yzFZxJPfq;Pn6Ck%MbC( zWijFuyCWm0&Xecj;>2x}KX>!6TaAmdiMCU;{(X+^h6OlF(Td_6x8rrwu$3a z7V1MBIQ&lzrT3_`$^`2eZ}O=W?OBv5c9p~$OaECz^R1C8fi6E#vERoPP#6v|-aQ~Q4&={!TOUKgpz^fWxsc}w0!w}9Z&W%CXJ2^SI(&G4bLHWj|l*Bgv zdOY=dyf>a+G_459b>+gjnhi6MmE9fav4EwCE(ZRe8tf6FfB-~<|K#Sv@gm6E>ai#| zhG_RC6fJFQChP#>*F}3g-S51tS>hiqQYQW{C8>b)`!Hq1i>C;GD}^}pr>e)=k2q%*R#7Pza%=x zjc&+X&wX^y{dmvw_|ef3mh`NB0VH!s&+pv{{*|F&&f4*xk2?y)Z;Z~Bz-6nDO36;U zX3X&p@3ys(}JicZ_KK6J+ zXu^GN@;Ywv^6>V!-#9e8E5iv7rtHMc#wZ}Su|TWxFl(FMqxP*&dMa!+PV-=0CYuSd zKvwOt+0y2>!_mjJG^3HkD!~&E1kl12XzafWgVRIeRfFMcO;oPNQB2sJyn-t60z?O6 zxW@VrXwjvVw4y))Z6m9KnM^@!ke~7obIL2q1HRgV06V2!@g5|AD7(>E#T3y{?AdUfy0MI$TP1U!OSM6g1u%->w_q zj^6GiB)o34@-bUY%w8-#U)p_*;}1D1Yft-K95E3IZCh>`s0#WCo6z%3u?@T|%la!T z=yCJm4&gA-IZ=y=ES|pnyNXH5L87IYJl>sQFX8Rp9RlwVTe+$*673U#6Re10>+?;s z-Gy!9Z+zFuS3)T-T2$4yTCyw^zVeLiMwKz4+P>o%5r08C+M)!nKfxZ@>Yjl6q8@g@BjFZ!gD}mzPB5PQQjo5%Mdz7zcz1rSCPehFXwLW~+-BS#69` zgk{;_uXh=PfYwP!6g@3b4?G|ZhvIf;Uk&XdP2qH`cv-_F5~jeWe+?|@HLKRGV#fj` zy4@e=_DXII^-e2YIJBHUC^FgVl~>f;Xm8PBIdfw*fUFCRMxbV&0T087ES}b+tZcU9 zDcJPNQ9lDuI7h>g^oV28<^MA(@X5eE5d$_f@M|e-h$sVy%bQYz7(;_pOBZ;PLRu`Y z0acUgC@K=sCJ!btgrssYyyphec>=oKz4ByqWEY7dCGnk^pMHW?TO2oDCpVsBE7sT7 zD_~&Io5~^R#nrdB=PB5)^v}TsvbyntW-{r!40GRpAx0X?)QL`5w>yC8x-aKH3L55e ztn`~h%!>I_B#qGo>?;IYVhoFfqi(Wv$O{!C;4C=@aDc-cTpvw6Q&pP{>d`yg+6)O# z0ilChR(4i+;RQf!>t1V4tl(N1i>7t%KDPPsk)v}Eo@{x|6Ucgrh4e6B`1JOC zDdBb2bG_<1N9Xsjm;QFJr}rBFcEmBB^?Ir2UtVJcRk#1aO;RVd$Q*{t(OFTitF1L4 zd2LS7_1T;AJi@PIW9shlLCwR3_x2@qq(PElo{tjeDB_VYorwV&0JjfqrrErg>lgiUTo!h6*LXLF^V+inQt zG*_FB7d|Z5G!4}TaXo)t>Jrfw@y8Zv7t8p|!32j!b*|A;9S0{z<_nIy+selOvf+B5 zHj=zx^0XBp(SAMQsxEQ<^Fgst@1x&?;oGHjNBZmQ+oOcYCw|D5Zt~yHO?>6z>oNf( zpD1_!!eJ;7plCw?o?>+A$m|$MkB4= zFGhoNomy9^6~%59&0i|X`LZ;-!mRLb2!u%mwY6hG*v#iDEF9YfzIDCg!{=+M9j!cA z60H5REuIvL4;sO-K0kcE@m0bBXk7NjQqKb3o+hoXU^0{vBZ8y*e!H@^JIiv3^0|+) zs;Y|VyL50Lk!vRvtm9(aTF8{vz=b<-@GJU)4>M__|DSwlB1OtIO!#>GPAi#-u~N?Lfs(FdtZh+I;V7fXcT>#{&sSIF6;Tj?0%rgu#5Il3fQ@scUQS!F+E!nYteC>VowhRMO zM4A-KMLyggSjA46tc??Q7~XR)g5?QHo^D0PCZCwlGdX+_067tNji}=fBjOAZnJ-_} zQwPuop_>dfMs1hefE7&BjU7xQ*>Jwr$(Cji#~P z@Wi%l+cp~Op1$9A$9*&MV~>oHjGVpKp6i(p<{}^Eva+!NhJc4dGNy({DbP=eiF{sf zM=~y0cFb8;0hiV;?l0z&RL3f+@@HUu21#Qx!xn`|em!P~^o@S%397Sink1Ap=rT0+ zq&nWbDbcI{;od;E<2P^@z;zzlgTdkV-U+d@&EdP}{=D<^dWsio*7!Wu2Z1ra&%-=g z9J!BMB`tH@>Of+gxz<<(uEhM=#6&W^UM*ZC@YCQwy%BiUF?AR-g)Cw}8@%?BMSb1; zI~081N!k_`-YvdUB0(^bxU9{9+$1~+1;J#Afr{`4V-7#wXVWFV7}y^`v+w1*e7l&Z z&7xrA=BSBG!dr!-5r!V5Do{XWdYWw!kAGyov4)+S5>tTU($Bj@99QemMKK(#{>+Ko zPH5ZO=p#-Ly1QWu-$qXbKVYl^K+OR9%BOo`050C3v5+N**rat%G>F^B$HxOWdT-aa zVtVb@=Qu<@-X=vlm@A*pFP|T~R(_B3Da4nVR=D4xxxi@Y8B4=|D=j}Nu?M`xcuDy_jwtK z%qp5aB5H5E-{W_BGr9_1r_*fqnS3!3JD#~}Jb4M8d0)IikpUvh&oAbhu+;pd9{SVr zVMnA_=%Mx+$r8T_nm7mF442c(>^|}e# zA_pk5-N|I;>|y6lSbnuQ5QKe2@_JHJa?U|DKP>L(?ufp)X)lJ?+OWYt;~vKrYQ4ry zJA*Z<&RBA#5lEU|{9B=-vdhl)`z$ftG! zo%e&zi&j?KAd@Xr1B~uh!KDH#kg5nbT&6Il<$^(<5OWU$i1YktgXiOEPvUp*Py0!k;<;ZDoO~CbV%kSibT$3-;K`7e z=>M+JrQTj0GEsRtO=3fuU1X7O39Ywxw@f}V58)HNBDaw8Ar&Bi4fAHlmukg7xw%F~ zJ1iJS6fEV?1QW~|FvXVv*T|b1YOO&9n@LN2>%7f7zkqf?pOdjE-uLl>B?vCfmnQMyoaUDaB=LSQ>Cg6j6QSlI&Krd=aLN^d<EiMBePd^6$yu>urCnW1V}+}wqqT$3rlMd&xCp$+bQ}Oj3)R#9 zZM;hm7fSPCFb2P>{dN@8N{Sd;S)G*@XTQ81@e_+EOy4lx6_0MhUy3`fA5GN_9t;%> z4zS?IP;6}KU+Me3uBW|7w$&`AN#A9~xk0ye0G+H5S<_^@UQxDMA7%~&t3F%qQ25{X zm5%ryIr~S~X1$6V9zq4q;llIEavSr2vIo{M7*TzQVqe#Bw+~5e?=N)iJQ=7&za+SZ zD5)C$ruv(%M&r&JTt^6pABw|qq=L+Ax->y}5jXx(Vz?{&UB|9mR>X#-Ms;XJ#hOJy ztPqVl)Nr_>Z6~nr-K~*nPV>m);~!+^f9gR2Z+qNNkmI|bSGxBkbRs>HGqtZyC6cepkj-V;G77=`%W}Wgb{I6?U^_E zRkL5h>pP!zylpRBb-j#QEw*ZQd~`pDW&2#NOe`jgaNa0k-C&|@bvJzFB4DA|7~Gyl zc^JF&byyyQ1|RWOl>}3t7)OQGx?aaf#MQ4hy5gk&(!xe3?Mi}tE}>;aRVI1SH?qLR zN^4SNYKf#|<5V29fUQ}sF7-<|97!6ofNC}!GgXj0C-u9;a0SDi*Hy<@mT789_A1)f}2ZCX5)f;N8Ez+cveewXIn;5c&L_xjUNb0^w6ov(>l5;B4~( z+W-E&ZB|Q_jCU(_X7t+4_8)K01G0QJP?hTmt=zuvlUp3~uC-XMMG2m`4i=!j z#W%n_@7r^on9S*B%Vg5-Qcaa&+QG@6YpmpAxgxXFovX_CV_v#%V@i{NN$l8=Dxy+A z(r0(<3z0vOR? z_=d-`*m(B4p$R)ypMOuas=8)u8!H;RoOgPk?~b(YDZ)t%qlC~BKFH5R_|U?KcXoCz zFE3$;y{E4pn;IL5yv}P(>pbobCqM{?Zj2@g-e0%sag?^I{p00K5~Mp#9A$f5)(jE# zy}^Hu$L{`vHT>vO;BNl_4hZG&p}j$}U90OM%a=Gj`jgFgKdL!EZyQhkf~O~N{E0w< zLh6o{9?du`pi;9+hB&@I{Wq>`t}`Q6n~~b)61_l#1pKH2He5Jdgd?N5Nzd=I9_N|UBQ zunVp}goA2)_x=0_-n!l&W@Z%B$8&f*YBhl$<2o5v-#1Z6*lD|S>?mOYTAHR4lHbRp z;Fu@hn>$gt1X%;^D(q}3;wa5rA77eWp}D=nnm`TM!=DZaJ!ArSD^l`Z;IcNsd}4hh z=5_>G;9cz7VvQ{mn;) z8KC`|7}EY?wIKzx27^%e%o{X8|0yUbfM8}|bwT-KtH4V%O3S;<%h|^Fhq_V}pCdRR z$8UFp|MQMN?zgd#O+udaj`a>(c~(rGuf4VoAp^~-ocCw--i z^97M}{jvbVTYF#GFOw}#nBpvWteF)%@iNi@J<3-^h_;tWUJxJdC9N8KnZ_DlO!Ap< zG$MlY;CxL@NQKC*$?VOKHFK#2V6bL3TBSJMx?vaS+P>NEi9q|^*|2`w z5K>Bs4Bp^{Q*$La$!}S%Y0YOZhQ0H3<4RPazOm8uvbaz+_7=Hw7tKJWov3U*n)nB<7}34FFe0*i`zI3(-?Cl9^p=I!*UYvMGv4Qw0vJrk(2OZto;K3!T~1=R zSm@!eH{zEr5~QIKfUyo}f_f_1#qSXFX(XOxQHp2YEBOR_gCZhF)VFNg7ES!f>EZ$p(uEwhIZ85YmNh zBZd74LBtTb-fWxoIBOrvlFsBMYdyCipL1W2%M{*R3}2!=H7aqeEhg+i{pLa1ju>sAS8?ws#rmSt5M(EC1$=+8aO%K(ds=% zE_!--wJDaODy09}scgMYhhZQ?oAYr4SJ|91bvIYD&+EOjppFbNc7B4#2QRS= zL!R%FQj_@Av#Tk|6=C7nOa?YIlU}6N#4&X<)lFVbN23SF@1{0BtS9wyJkER;tXgMh zNv`-7BGkNAtewZGA_!A6sN%Jo7OB(fmJM}{@3fSl&9J(4mDA}Eu@}pnGu9CHHb2@B z;>n2V{0sBBX^oaOik*vE&Y$OpS8dwI&Qn}3Zof_vNV75Lo)M+ukNvpMadJ^HQGahH z-sLqp^&E4cb)`+9k#Xb7>DwxZ)pXK(dTS%r_P&4p9FGS}fJjY(&nc*v_k1voLM?A0 z;R9F9g|aSke^M^y2_dz=0dPaKwehc9t@atXvSdb&m0%`$Tm%zPr_UTxVDjJ)#cqd$ ze;tT7b$3veVagzM@lr#M!YzxRXIE2eVy{`~g>X?@DpM8V70Dk#Wn{b=XT7tn!@i0= z`HW-SI|rRIq)5h;b%=PsToA{9x33h(^EN%W=$Y7$Jqck^Bm}O`kALp{s(jbG>+0)x zxTC%tN0;t8L3D*wHQvE@1nY_`*mTB=8*W$EG}LPs{jst2PCRFky=a8$`uJ$Ou{=U~ zu$ZQ#ML9`cX3AT3|F`RN)y~!~n;PNO?Q?3&*4i4azDXZwB*`Nz_$`){3MkA~d1?tW zQOA*W;-L5V=ujQh;Y0AifUD0#1#QGnb6eq@c0bt@L7`wckW59WZH^DeA-9?TtNZsC ztK6@`G)&rxO&nbHVJfA1=O4|o6SDIfQf#WT3ly3v%9bTL1Es;z$I4je8s-nUKQc%h z_tz$|+%yuV)VWbipuqQ>a^fi!y${D*l-4LapT?Ee*0jnqw0vd5${8$PJtB82OV8DN zEztf995|~{U2Qx$eU05K&hdQ#RjyNKF2J9;6A+kqz3S@f=;&x|ZM~M`@cVeXdYimr zxC2o}FFRqxKi)9F171sCTgNZmhU{O7cEALlVgX>bmjD@m?my+cm#a=;C+#`-yOUdX z58{9tjH}_-wZ<98rDcq6&#R6&p)VijL^1%(;cCSpJCQqTR`SrSK&T3XwTd=VUI>bA z%w@E5q6ZYwz5v?SN}l0b+qB2b40rxpwjfM@D2;F|9kM`EY;1>3FM3tsaPr4&p~)cD zvv6?&{V$ts(hk+FOR8Uv^1U(T-ZI3(BHUDVL)k7YZHjd5maJ$cU1~={BTgNp70xp* z!m>RsA3x9Kme|=(7c^%rP5j-$F=+>??OW6s#|XpDk4)E7ec}U;P*pXwXAE3Tt_h7u zowbbx_GI<;yne*D(Z?9wOHRI2eKu8n&W0S#N$$225D<93-3*0=h0$7-17*2oF<|I_ zB~2_;eLPn2euPZ8%E3RkzP~Hr(!f z4`q^(MEJkaI7bceg&E^z6Ifmx*a4*Gx!@bZK2V3jt{UqdvEJb`!!Hg*rv+H4JX&h~ zG+cEqm%?Yxz}0!K^veTUTFRjygHLmo)h(u4dPb)dv+yix&y#cq)Ry;9>aWMv|r7n_Ne_UKb5+TRx8< zkoJ6=(nXN`-t+wtv@9MrxsRe51;_7|gpZ0LgT{4q2I4Nv1XDIPOC&a07BgH*1K5~_ za=?%>dFvbx$0M5)mMWuTAKdKLSG!!C+}&9&?gxW5^|@4Z4P)Rf0;}B&rO=BrnO5De z>L1Y}9*eeekmFoqF^StBT~{rd*yZZk*w^qgfcGwQ8X`cjbeG;Vjo;`z!$P>$yX5wF zh7$0cE{?BhLpc=iUAe^vRSKq9-eDS54T=81&Yxoz!mN>N$#V>2yEi>Se9|J;M3(Q=Sro*vkZ$OlS9F20DTDl_M7ctIpE*OhZB&*!H71w zXGS@?Ijz+3v7Tp}eh<#Y@j5)bLC7!C(Cmc3DT)qc;*iCOYYBxa3Vze)n2{Eo)_GY= zX@RBA7udZM%HcR#g;+yf?ZpUy)g=H7!291#A|x0dXFCN)kV{Hdj2zi7h z^u@nd;7bdKV!&AGqbn0=5?W{WdLU$w5*sn~8q>|$Iy>INGJy3_Pn8@3DR|nam(~gywEG-&BCOLf?zfOdf z)yv!DY5q(klhkJ!CYcovz(t<|<^P^&&V3E++d^faUmYzcI`4!*P^* zGa4QEobpy=WT1JuhZ+E?i6ZlM;EH~p=ol-fwk$-8gf>6BXS1Ix`hS-q)5LXyPIAK? zGay>jkmE#Fh_gbIXc6R0V)Cvd>IQISQar^LmUGY)dcj{FT zyyLNzDSK09k8rP0?w8(w614gDe=%1EnV%FOr_51+L0# z>5pC*$R+sY2XC-GEN1LzGHD1rg@W-8Z$)6t_6~2mfQ36!F#ruH35^C>eT}^-ggbjZ zZkzpfEkNb4`)e}b-Y_dliFcv{Rk|Ngiw>ZHPG33t{RfVG9qeg$00p!c`yQ0*`5a13 z9ackY`bSJP$>rDrE2$K4w%%%J^1^rY>$4BQVh3)XaH6O3Pu)TN?3433W<2oA6==)jDsJ%(6WwBJ+8s8WwYmEw0}m`#&`at{&;{Y#x7nd}*Ew z6sqTR>g)h1ik|xATlg+0&|Wa_?^zXFAW8Dqi7^w=sPSlJG!`XA=Q-`n?&0@{1YwmEGbtrZRhiw5otN(Es4rU0HG0Nqqk7v3(05kQ@O&oO%E z&6GB;ir;-xc?6J8_P>d=^>daPmj-mJoEva8{n=Cpym|Y?+hcfOD$UcjOia^Y1$N7+ZAQx zoXgCXsy7AZa&<(Q4^s_bp#jX#!;p)EFteH6@Z<0y>LRPO4*>k{(k2?F8qiQw52*Oo zx)Hg!*wx5%LV`6mrp8$TplHXR=*1T>8aN5Ge^qvp&o=@+(+GljZjDy!3tTL5?w;? zvp)o1aP<)$ir(H)|H{P$4gM+e9+&@4CH@8%I-4YXxn7ZDv!OoMLpss}SIg zG^6DTVAA-sUvpuWnnaq$Uk99j$)G@~MLGgTZygg4_Q=LYnQ~+iNN~t(+8L2MhneKS zRk5F9j<3s&ov!s6Q zyAr3(X*q?AQ5o$eswE79#42x|chBVF>`90hJM#ij+v01k6hvO10O%Nv0V{ zk%prPKvb~zS3P!nWw+ZrzxP~>T1;1mDah#60IyTs;o^7LHFmLr0*LKz&_!;&4_*0O z6{!)ut{;6~qkLYUr!hlfH?OCprv_MN0%7QzAy4i1RXS6}^qcOv0jt z#(1*E8okS?HkY58+~oSW^?ox@u2wZU{^d#|3b$aE#fAlM!c<8(nvu*A#FadPKzn4q z-sipE=Yrn*LPJBt^=>zqw3Vo$WBOmWiTpl6-8z86Ea7|e67pZ(d({&BUNRdG{S z0*aVNyxFAVj=Z`|1tKFRNeKN0OWoI$!ib4GrYXuWv5qtDu!U3KI)l@R!NpR^;=0zB z1r5C-Q-}qc-@=T=k))HH^rPx2IEv!Z60}fWX5S-rLP|*jSTn=(^&gK1(2N(ec$vnD zHoXe4x+gWkj(tOYc5YQoA1JLZ9Kd0_CnqOCO_AUG%e}xv7%h)BWk6rd-qZd_f@Eok z6i6cB<=}WaWbbNeYkLLB%kLna9VNZ9mJVl+N}bY=sfR3lcg14{@@Gk*x`aWVtSbX1 zA71*uAo%jxi0{(lpMngXtSEX(YC0|RINViKqj^d|HYthW0KDXYFr!GSCV%7eWnuGb z-PPq^{F?H#)f3PNy={!|70NTE`ATA6{|FBeb*}?@xVxharljjU4b;2E0>i0Qv{e)j z<;#SB$9#q>cFgb+{9g%xmzE)Nxo|5uZQ(M)gP)qJcOcs1tnV|pTqYsEaz>$po1gt zcAS~M7mhn8s}!e=LY{BKlAsF0l2P$ifCcsa60|UZ)fp6ZNR&s{%35s}iNUICEK^lo zki^eoQ`IzI0%2c8!7Ra8CqNAwT4JDT>=(ocBXd%)VX$)%slwdwuQ>>mqTNN^2&pTA zwA6Wkvs^^nq9FU@T&PiimZBv~j~5JuY4{^Kk*=wsCj&qP6)u`1tlJ7EjSp<46@9lSsQFEuSR!O+yvbd%#3!`xuqh7^Q|NTzqmp(V?V zxJB-yv8j2#(6pyPqZm;cri8cy9DN49kcV`!t$)rmL@ib6HHjD`nxb+}flo-*k)o-s zngWTAG$wg_E; zIjxFcb;pUAGVEJMTR-}z$$vpGX2`2|hlfS4uG}W<$l}+BC=`Sf0oQS1RzzX(GjT0t zLbc)os+{HzbN({H-?O*I%J%t6<>ItO?V&;LQ`tsYmPPM{9H&Tg=?aV#K1ydp79y0a zWeWi>7pF4R^4%ge;OY~qxVqaGos#J2unCG$Dq_lvR%aO~hbA4Hh%mJbVmc)3sW2DSi=jZL9WgOJAeKSPt_po9%R_pzG(Il76^F8F2XY-84J8KrLe86lHqV)I#jVy6(&u&W~klwy8|cIm-ry;zNi>Jmd>mL`LzAoTIO&V;Y8EUZ2$x;Vcf zHmL}+P!pUoTsaaZQgncV0)8wb-Ss9bV(p27-TH;xD@Gc2YkiGLK|jahq(e3RHBnKB zJ1ztnMUrGDSGQ+0eDR+>TCrJ4ZOZ$svWmr7jPiyHm3kWS0L^GkLdIO&bBSCs*;FZ# z1nGpy$n_U=Jeo!2h#*p^AQky->TnK8Lk2qeUfSvaLwfy*Q{*7o1`_u;jr<>{XMO9a ziZXc)iw-HXs^u<+<7wm)wR8x#rwk{Aluilc8d_TAs^vY3f2bm_d>`BF+HVFy#maN1 zH-tr|O1A^AmODw(L~!rJniTO5e8pjo2DWP|wDygQxJn{NGkB$NS{{KBm*O1QAnzq{ zn(flV>oW=c9p7VB+u2tl4ZUQ(rbKS_Y6wnJ3Jw?rR0CKo1T=SlDP!z`={mAHy;!@$ zpvWzmsQR85tcKayduaA_g@QbMYV^?l@HO+rnG!M?Wpq--9zAl@i^YQ?r%8`Msza7^ zLJ|^4B-rg`DnLB67g$0l4Ba-5AtAXRz~h0BL6jMaH%!PGCjF*ZSh`T?^qVkSbj9{B zfIf&^2l*$x!>@J+>#yZt%ho{JgeGusyyy50B#D8HiH@M58J8_blb|JW;VM=z)8cd# z_zv#>tL|+jzrBA7W~ar0-{7zvjI0O@o1w=Xwhw%wh2Dc8;OjmX^9?Z1>Ygw(5N*W& z4QTNBlFME#QW+mb5Ch$oFe1x$FHwO>(C+~-_Oa+7m)Pz9DI6X$tYrQ+dVQVEOjSkJ z&zN{F+FHI%d$TM>Pyd(WXMk|t<&0xJDGX8pr$OIrX)z@?trdmDpISWD)96+q(BWrf zOb&?M;CSZ3^8Q-V*2p9f%V}3g01AG7)(hFY^Om^_Q=Lq;@$>#Q#k$C(*m_cWHu`AB zwX-Zut~+wlL6BYH?}VMN67_p|*F!@Xv2Xp>8OTroGno}Ks}EtoG1MFDUFuzG4Tl=x z|8^mK>hrU4A7tFx?SlV5zlC=wL&7vTATVG%AJQdH5iwKz$*M@PC$I?$e2ukWIkg+F zcUqiQ{A@7A)T~QWPX&12T$8*y>xC&V*<7ENA`}H1fXT=is&sD1{oB!SEC8SQP*X`W zf;-F738IA5a+1p_4-%e49+2KnpH)WzZ=6jj5Dry}!$CP-h?#z&S$@yC?exeA1+M>x z9WDOES+i96mdEdL!wvM6<8|2rszTnN;tD#dVR4~cZSBIfcy6TjoWG&1y@4UUYb8}Z$8#5Qz@uhagL#$_5*t0PKcZMiM3>n6VGXoQ3 z->ATV?ywh!TJoeU2rIR26l^YxaY>xC)fh< zxE*wJmjTt-$ntoL*pa~!%BXT7Ar@fNbSf+W4iq$Dc!4x5ie`26UJ>rN?9@(GQVf^jh&$s`acW-x77&9oo*FpJIG)beUr!@Yx zbTN#A{qG|obSz#F_EeB*+o~Qn#2r8vJ%15@Ow7^VCaX?6wUMQX-0B{6VpS zCPyfjMcs~uMNLrv$o4!ESdF~N6V2(?Y$-8dmaf>qmzCy^@>p%&;bxtaoSmRqrCwaB zUKJ>hG>!ffn!#E2TWNZHkxR?igl&SEL>kpFccHx?iENNs*6$LvY9w-*s zYZ^j;$XqrohLK;mn&UZ;=&2f}R2X;G8P#(k<9QFce%OPDQ$hF8Fmz)(JsK8m_ntG$ zt#Kd#1$})D*WaR{IKLCi{R)0n*mh!PX9rmhu*;sWmvZX|w8grvJJ8~@va*OjpN2Hg zj&l4yKs)OesLj2bU~gCiHG2w}SR(P{5l%nW&y%0#(dY;R57XnkGJ@dHHaI82V28nj zY4ZB2p+f}W_H(J{71lY+SeXKsc&JB%E@xt9wp*Vf6zAH{@8 z2$<8t8_@f*F*6y+AjGIh;1^{GJ${B;Qu)B$Y(`*QW$qsguf~0os*i-p*1;AjYwRlj z+844Gxn`xzsb*offNzms;gHM;1_UGQhEM?ntYN_ls&}KBLZQH*(u#wZ2Ba@cj)bL? z33)0+pxW9nVf>8>dX$HkC!Z#IeGMb-`1Ji2>v#W;oJunb?c3phzkXG~w8`Nl6r-w$ zLd03jury3+I_HIvGC)Ix9XcO6;@C9O|JSuu1$+wtfu#SK!E!_(MU7?#Lc+m2T)ZbL z8gvth!UnE0AAV0;B2tCp%APC03XE6Eq?Q1?k_AX04nQ06WNiqg`u>V&|ba-sNd3+kq&(T#(VRTJS|>#Isn z_8rEi#iXSeZADZ+P}_VNGOaQHeC+~#KWB6~OtNN7Y;5QNsyZGtsj3Fo4R>*H0*%C~B9wEyU<@ z>{Ni1=np$6OoqH09_x`!LDB^arezicbsX5CLvRSbM0)RyMq7+>&9-el`1IdCJ*qGl8DKNf)B>I966Wpy+Ys2Mfx7ri$ zKfy?#Y5b+OF^sJg=%bKBm#^~p3H4eI+7fp4IgaBvX;&g#dwcyA8BlL!<&zV&T(PlB z7PdPmmQd#@*zje}C&{DYn^+f|*DKOwe*zb3HU~v9fS6i@$|JZCaWN$`Oe&O0jYLI8 z;)Y}}DE0=-<*Z*4`rva>IWYl{OioJjLXkUA=Q}|W%o8CiZo%%A%h>~vD`mL6aZw$%%WAR%;fcA6Lv-0$|>y2 zdSqymBY=`8L2-wjSTDT_Mp?upU=*{?T!tSY!b)oyc?mp++-oSA`{`F!48eQ+VmpNl z?aQz`Bk0QT=SKJs=TTAZW;b(q<_}2`;YbaOz?**A9`v$SvSCn0#`aXFr+UBLReA0r z-AX%Nb*&2cJmJz%lfRTPUs7%w*&Oi)IsvSVGar!#zXd(Jtit8kj6Fnc8ZA@c3$!GM zR7L;qUlD-mC>_;9}cVCpS@?-%}qk-}8P#4>PGY&(6SO%oTbL9i%-f z>cqJdwi7{YT21Sh0B(GZ$snk4)L9}f79L1EP;wld5U*f`#r0$nQj0x+k>Pro`;<6Z z)W|Mu@?mV3AqUxdg?_AtJ}Q40!A=Ao4TBXi0Uez_4K~%t=8psU9vqdT?oj_E=N=kd zV&ttb*0qA|4g>Y5ubnc5Cbg55=kj=L<=Q)I0?jv%)3Ju;#Y&rjlk@`{t&0+J8HKO) zaHWCJjP*fr0&tAoI|yHJh$_Hj>O#|&3!yu?bc0O7Lud$u|BIiL&seuIZnV>%(df$E&CA z|5uk!{-5fXp49LkhgnP96ep?c&e>}FV!K(12aZa;UD zh{{Q3I7^S_`NixE@bdB?&dUqJ>izW8vUp)6s&?zjY%ZTp>PQ=?xV5fXrFyzI0y=VL zvYH2PTUGlAOFm2s9aE?)y0 zaYS&!sU+q`2uXVU4MNQRWVQ%L*L??sfmDkW{}JJl`Qmf+RFPXRz%4Qm5x&RqA)>c- zRP>8%;7*nrQ8zPr`mYpN?=)UgWc(s%aF%fb26s~>s6j6x?r7uBHbx#*DvUvA+GWX= zU=a@H^$3h=r!0ZpZFg&VEUN1p*%7RA+gn^{Kju=E?%$_uK>|dc9>UL)nM#r#CqAl0H`;BlW+W zq2Jq(AIo6-`@`De>W%xlIm^GKq;=1i@9rIP6_8p2zMIct+dBji7-)g2rh?~O;lCJ2 z&}2rnDHSB8S#y*0xqIA^Fw}f5oj3>#AEz&fVjew%`YvZ?y6-7s;MCfsCE)dB-|B_o zD2kNNnO%R=D8oc%}QSW@oM4CjGa*5{aO00EXlErMrF?T7?Vqd#mL%a++OqK zwPM-@rw<=oUVxeS@?5vmH^i{c*Rri~6}tH{7zB=gB|% z$i8$9N1W&Pn8z+H#-D!(JwTCnFJO0m<_ z8f2qLaXT(*nH6KO6F$~av*eRSCDKY;i!XIxZtNIOPv~e!&^DOP{USms_HfIk*t6gq zX*i0J_43)U2iebmT)FTQ$wWEsqBEMUUL@e-@G34MB`MRe&Q$=(N2sT?u&wNI|BCf} z<^8_&ZRNP4sfoP+vheU(%77yr3;q&))t{%mJFGDd9L(zP-3+ar&!?U4TO0e9_ucLg zvCr#5%8QteJEza>KJyfhAUUL*ezzE;-hOf&VG; z-}F>)$S*cj^~F^XPkjY)_cuGA%uY_q0#&_sBPc|+_s29w1x0k#<5%JUm zd}pc&06U*XS28(!t+#YFPFFrwmk3NXR|s&I8RC+drNA=sg-&U)N9TI0)^mroi|VhQ ze9w0F90ZIX`f+9i7ip*2m#b|LiV{WnHPE!g;y-nAv`!E=Pl5Z+a zmivumG;$=}%0Ey_U%ehpHl3!f2znuB3WHjMxR~?Orpfaafs6eyBTbiE8Fnn^K`u%GvnWb%y*f=S-S|%Y>HZ~V9Vkpk_F3FNfD=RBWG0%7_yW^MV=R6*_`*|}#BhFGR zmca%3q)%*)E7m7jHIJ1#UG4E2U!@IL?4O1s?vAnvzI>Tcj;VS4X26dqx#OX&fVt$N zrmBi-6oyQAtD=*A1O*N@`P>r(v$neG%m3TP`5r9dg1yL54`oR3gw2oqo9k|}vi*sN z`i~{s9~GOKspFLukSfWs!gm>3V38zBLg_@xm`Ug~qXXmrGQdOONzHYS*z>DD zkKW$fblT+|Bg(04UT!Wf9^co&EN-_YX8acISOf=9<`hAW*JFPeEre%SE=AkD@xuO! zlKOet39Tm-SM2f#_kniVvfnkY5C3#PtEWeL_$>Z34TR zW@ct~V2Ht%@e}TAu&m`U7>lA6O8~IimuQVy22k>%-c3r#Dm5fLu#yq^XgWp0F!_i- zesTo_K-LKtT8cOhoQfu!Mc#fSx2b5XE~jdw>5W#X5lAsZ2r^G6iUH|oM2cTY2VbM#*-x4teU?y2}9ZLA16gI3u#`=bxMz_ILWxf z$JfI<5HNb)J5IuqsPID6U}302fl+RiI{02kFZ1)5Ms(OwApIr_v~>QS%>A*rgfAgB zSbn_q3&9$YMAzz+ zHvSSqm2kxj?X@e0uAWE}*VBW6l^03k;t`<)h@>{dxwEZ9S8$z%g;T}PCaVrx4S>@p zUpP)wCYk&&oARpPq~g{>SV=l5+6{$3F8g^|E+JEbhHc6E(}omVfqaiB_>5CKUbvwd zQ`D z)s>}4IGW0-QY}xM?d;?mtNpilueR*c4_yyQjmpY=&lO)N_)s0=j+38hw1iTHzyudM zL@@oYd3Nkm%HYGUJGjWHLP&z;hwmHiS4Ps@wmjTEJ_zFLo65b6jSCwJjErdc8Mv4j zm~fTi4ebFqB@nvg>Vnn5?ocIg8g&q)QX(N^SJBVUyvP68oyMOoI`+oLZKM)~9goEcZ zLo)!t;ftbae)+H8kA-Me9WE}xw6?8jX_h6y8(CL34b^4IQ?YPxnB(FdX~U{1V3sjL z=fj$V<57;s36WnvCJ^=7-S*q$M^O0M&5+w?n1im;&37>%`L_qyF$xoPyL{g>w%!h( zo}TWe_&?X3rht`|x*)CVa-*$C@kH)pUk-HJy$OGi7Alqo_Zduj096sh$j~GGFX6R{ z%ODAMs1nh{*BYYzSGTcH8Yi6r$!bsc2RW(-szdgFflZYgpZ8Det7tOJ&0ooY0h>Or zwp*>tY#*j8tEc8?RM?}TXvfDkkLu?g8B4`ix<3vo08!l7W2KgKM6ncqvP4B;xn;A%wHBA#7w|#rKs)?s~tHp)(ML@_s$oWNQMyV$8LWEqf9< z2v~AeRw-8n=5+jx`j=gXK_=vJK9;9R@&vJ^U7*mbdHUka3`juzoY`3&gS>xu_{i|P zv$I}vB`|B!$Y5OD*yzZJJ;)I!b^`yMGcD@MB5%0%L(s&T{g>@)C}#99uUsNQKZQJI z8I?bHi2&*~)hyUw&{#%f7IN&n3_D#Pr^6UGW(>lgL6TG!)TjIJEu-&V=?4vcZ>tzN z5s*T%dF#pI>}*Ym`h_#qK|Lf8H*{)u$_fuWapj~NKUgF02ASpoP;C+qV$9q#O5zqYWqQ}emUbYdf@>i0?DF1wI@4XnmN58k62;tsh4R$uR z!NI}NgIiGCv{Ky3j+3a-&!c2iM@L8Rb#+PC`$lBQ!CMUK6MlMj7Cl1P`<@ptm}-&U zqJ8;QSsom+jl6cfl%_GM(fi6d(I0StA}QtS%}gbroR4e0W*vZ*q^J^L0TOBFgEE9G zh;;}mC#<>k)uJ7<7AelxIBD-jlhkbAyc@q65J@1D8{HfTxH|XC(0l1!DL!rd z2A7%-3l3HaGwx1C8UZNEl+;>Pl%&{Zt6*4g0Zp~V4T1!_rzI(Z3?~1;a#|}4^AV^1 zSDCl?S>V<|<@sNYeu5NKQJHM1(rop-KmBJ9q5uA!_og4?->Q9ieN9P8Asq5}zh7cb zi{6quElzv(83o`P1qkG-)2(Ha|27CYHEa`9hoB0B={`U%3haYk&`Fu1motl`g^?wQ z9zb`)v1@;hQnTdw44Lw|d21LpX;r?^0_~F*zyXMYu!p$lY#xthziRrFsRM+N zq=6Wqb*Z9jJG7G}k=yA?j1b+I)-Ims)3KC`$hY~fr**TgCyOk=A2!A?vbZ4%U@te{%G;K<`_OsL#tF@fSUp*KnabH#|siuVjNZ zOYI-zdC`}DtzJe=#%i`&9WVGlhU{!BDs#9$$Cp5V`|9jex7Ckdt?uLE^QDWNY$vvW zGPdgp9IHKXOH(&fPcQWmKFzx0Q2BdIb?_H`qTKFzhy%$GwEO^h2_!+p6#PaU`)0+m z30-2XNz7z6_JA`TLynNda<7bk&Q_6Xn2gMUX zOv(QK{_gH>Z*QQ@+9xKs8+~hATa%b|To1T^hxgVchVR*_H((gKBY>B%qVs{!eH#+N zUmW@vm3tGc6Hgbm8v?eV|8YW}yD%IXw|`XCua@Z{wqyBYJ#WhUqWorY5j3Y|l@`bE zA*X9d0S?9sm|IaM+l@(NqmEbHO1F}|#|E19{)1IcKF?gfT9*y6Xdw5GyrphTr7F|e z3Kn)Ib+|D3ZfR=!Usr|_0xr&U`ozr@_oD{Cr{|Q;+oCDomuIJ=$0zJ=bZ`zRTne@9Li^p@!m|cg{drL$_!BE^8cLo)_3BJ`?)%)p^m6a9F z5ACNq{?|Htj<*evKn+TUrAeDwfdT=*i?2vdG)dsqOFCfwsJ*onaip`Ba?acy`^b6@ zZAz-(@~Ft?Z1k_^7qJ=>n>c~6RQ^Jks3JlKilo8f?nK()C$q+cuF`hzhxmR?x3`NV zSFZ(idW3`oY^?VW9a>wNuZOc)OsC@f@w0?=+LrD_2y>~Xma%&rNJH^NETp6a^V5^{bP;zJxq`N~prID2G?rx-{ zyE~-2mF{kk?r!*P@0~mIzVIguGwieXcR#V#XI(!Ojq%_0v0BCc99&lBuvuxkA2?Fp z#`<^MB7vy_-=XSv&3L$YU*?gL3b-Brb4>xSrM|wtk&%&hk2@1n(|e$sP}Qrxnvgq42e|#F<|v5L2TpTx?3Ba zWGxCZXep&_qs117&>6{$wQeiCJ9&~2fp0zPYj-&LSjfJvn^DFf*9bwIjrx%jqVlt$d$@&lq3=;^7?*dOi9J>_!F<9}X3ZVoI6c8u_6EZi#2Pi{9MWT}ku-TuA zXF#S?@#mC*zPXaWKOzN`qSr3tf*yROY-sJ$%(mXc%0f5(tAc@Jmj7$D6%RVXU;E~N zmQ~=kq?XTo-WGV>rjUpR;eYrbSD=)+*S~$y(b1vLy#IvqSXWr3PKz7S>G?3Pv)U^W zof#_H7<0hUB`t(NmbpihdWeXJ{!>*)Hv_9r%IPR( z`iRPv8jedXXoYZE91$P^fjRIX!Am~0CV$JlEaicXD?3-cU>si^*`HZP{aikx=Qpjv z8M-p09-oq$j?7!+LSdQ`;xLf(4Xti&=GR@%21X5k%X!`o>m8CDCi!B94JrguDRtk@ z_5JC%KM(COQ*!NI`%qC}e0VafIy{shGqXbiW}zrYH*aNhBuPLTBQW@)a42~wIl3G6 zWB2EfT!*ANs&08gY5nt%{iIz85BCy9Y;rC*>yB7HpiEM|z;j*j%wcal>U5oH1Eag( z+_FqAtXy^IHE!LGSa$YU)5_V|`rFp&w!8pAlsJ^pudlR#J6V;C+Cuoxk{2l z>)zMXlNcx%`|$_Jc`@^Z>FaH9<9GXzfb|;X8v;x+UTGXqoYeeIYAL9A>4sFcgCZ5;s`2DnQVMw=V7_jQ47Khqt|GOg$EtSHZvEBeOh3`E2C8ksJNCC%o>aymoUH z>~=OG`mlQt_9ndUE5tuzCl5Ks9JtHuyP z2S2i8BLS1z^MYXn|<}1q?#@(V#_rv#u?+Eg0ot{pP$|7XOdG8z{*roGF51wl= zNzcW{yw1fB66U}0msQOdgh+}1rv*66XqJUN6?p#~f8&)8zS+r)oLJ4EZT86d#fc3E zy}-!g*fdt*V*PyXAz-O;7?a_8yn?kS;`f6=%+yBD)P@v=FIJjzT1pU5sTi`zYJJsC z&dPEj8LwHHo11%m?N)%~S`bnu2TFl_9aPdan{;=r4J8dKLR)AJ`@*$2G!aKIyQbY>;>6v_MIK(K3 z<_fc6A;J6Pk0Q`!JE71mIgk#K^Vz36OKP%`Y8Of!5N1&yD4>!8FCW8Dxp9A4s<%jD)R|&C38T*Bbiamx z#;-0PJnJ=4VW24}DB#hE&y(s~KL%v(*^L1@##KOD?J?eYp4jo4V@BEIrHBFrYQTak zDE)%)9=)T_>FqT(C-ybMrp?>sP|d^TGH9I7<9WnDgo8IiqNy7NZC0)!{v9(uf1+WpQ+;(@%+ z<8;V4@ho&I)p2%?GVF&7|G|kAJf`%{a{>+M=Aje1`O|U6B$Og@!iUk7)o0B*w~^E9Bng@8@2P3CJu5Fh z!r7;6Z2Mw0N%-B({CZ}af;#(qu_Pi#V|7jaPm8mIDBD8pe4-WFHHT3ER0A-B zOOVF`bC}A?%71|0lY@f`)K-Bdg){V~)@82O;HdSl<6L)l_RohtC^xGHMmry1$#44* z<4CpwPx!w=W9xqi1!TD`R&d)`3^0MTzUbMN@FmQG*48F^kDFy2Ys6>YPh1~oe!a_h zX&WOjWRSKfo5Tt?E4mYSJ?_A3Ll`Qq3XK{J<0&|(7`Z$g+Op4HxAb8*W+s8^pCtNV z2^A7REvshA<`AS!`XrMx(~ro`A6Ju9M5@7#8Nwi9=e(xGUk76yosO zhb3>8>byUZv+CRJv*r4Pv$ATu$j~U@>zlo(WgIdqZiKz+rYI#qOP_n zAPTi^lV!r;pkCF%cRR)-A)ncDe&0OiNCXN&F4I`k&_pEk>(2Dc=@0^e07F59va))m zHiLTE>gsBcu-)NnJI}PsIGVa&x^$6iW^5} zuJAs3>}wA*??JAvLSwr`Gg^P|~C5R^b9-J2C?parT` zgx$$R#8jC1Q7I`h*Avb0-=CK^+B}RrGfXm^u(Dmmcm4l z+~MT2Cl@X{#n|cZw540TSgx-C;;+lU9(n5yzmpU>^MBnk9~7DBblsPa4glDX$K~{R zz0+sC!^=CQC`15l~Q3Lh>+V)%W)B=n{tjmX5?Ns?;Et3$_SWpVlya;!%+D?~rI> zfeDU@#p312K_xD|3M)U&Ne#hy08ezhKUE_tjfp-Xoa1PGyh_?} zeW@<+wm5A%-uDzdfTwPH8AMTX-8GqKU7@(JP>e03%V>eMyI)%HNy0!_QAIq|s7B!j z%m}w~xw%;Ur@|7F%}{j+WAu7%%Vz20PzItRz2gVssFuoKZKXl}^w?8Js4jG*#zQ%N zIU3+T5LuA%S0PqGl_)IDUll1t4h=`wz}MX!DS$BrOd+qDFL~e8zqdw67$tikX0MCq zJdmNIw^FD3=$;a%ZuynR_pB#%QS^MtDl78M4unQup$aqu#pdeLu90}SeE&vk7BM+j zxu(F|1^qET zuVibXqb2p<>ikLPx+0Mix=|H1dpZP)MU03W3A~yHYg7MEj;5Py3w=(MuI=@yGFDNG zXLY3)xK#Fy_NKLL7=%bLaL~BFv|Z8aKvX@}GiFpPn9TkI{SkQT>gvEcke8Fw^>C&H zAj%JHU&L_F#Eh)3Mm+1zdE2;eN-&vVbuxT-X!8R9DR}RFCOz?v5J;u#Vgof6QCGEJ zIhUv$N)|;&p3YN(b6AY|^-^2CMH*ct*j6(R{eal8-X|l<-}}DiC8@ycL`_My?=fN@^ux zHjN57BG@1dRr12>>QXTjic&(B!hTi00z#?W1_izX2m^|NKY|bl>}x{%S+ycXoKIiP zrBol02_$Bm4gR5oAVh{xa6QTW87SpC_slSx{!`S+vRw@NCwu||R_N(xj&4+F6Xl9< z#4v>STTWX}x3<0kWnD;bxBkQ#>kXf+s%pjjk;~~yN^0s>k8uM0yGT%^<**GDnHL7Q zKp0^_g{(MtVslfGHG8$`b4Np)34YGIr}qtwPUflNAez3Zsh+>>Qecb5L6CCX7LpQ{;u38?#9N6SRIc1d;$H7)+y9#d;u>lh1h7ZDqhFiCNQOg|G+G%wi zrH?Q3>#wX4v zGV+8%;SOReuy3Pq@h8A?4|cgD&YPMcaRX)}y)1kP5|p4;z|H0D;pSZV>z9M0K4&gG z83F`LjZcpr+dOeIATMXl83q9op8DC^N_Q!l`}WzeD682v+gt5g+~jSSr?I>~K+&Qp zFYza@0pbjCSLI+Zd^bKKB$fW_NMvKOT}g-oVGskfLas1R<_Bplq+zROO}k!(QF?hx zdM4EC=s=ksk1KXWg7RMlDoo|_W7JXmh7$6(&Nut1v`|SNrP(S5PZARRSBvA8s$~wy zR~*(WfHi+W%clKihso#RNbk*^JodhL`#8xdsd;&J_37J*j`^C;%=-Q#({Jn0>Absd z%L>mq9)HJ>Lu+491{?GkKtd3zA93ipSR`QfBXPEm?DeJ@s4 z9=<9MalN|Em}^7?v`Gucy7zGDKUXZ&>@Nn~NtfS@o~3ZnOm6Jec0b(~Qk9--n|PSN zE4R+g=_)`f!hnhTu|FnRNw+Nvl<^5R8u(q7U!u*zEwi5Q_@8y=z0gVk+x(bG%U zN|TEHA?Y6Tid2Md*Nov4Pt~Iwp@2Gy2Px`y7snc zonu{nLtz}qA&1+y_bPt6VDTYShi(V*_NL-?sczx0Z3FHR?mFl3b;MB~4?y`Z!IrM2m|tHhJpgQdiMUe_+MPtPj*jG>LIC zg9X>1&Te6U{Z;EOy9D=95VZdQf`#HWjH+^Ys@gk-@DH(U!ih};p{a#A`hyOa*v3Js zp#D3XNgN*!X(;@hNJ;XSG2e{w#E-GdqF6ro|KA~po~r=)YtJ>!_VoC;w7iVkTTL%B zUAMEdQ&3OG-yRaRH&PDb5AJXI{T9M-0Z?V<3s z@JP*-L6b}lh6@uPUDaN`v=kMVLP}J`!JNWMwCBniPHS14T{9p|9r|H5k5w`w@AD~s zl)=flK9kdp6BBjju;53Iv>ZXsO>l;_l)%%qL;H&r(L+J=&cSlynNdVg+B|jZ61=#? zo!eZnIc@l0T%s$aI~l3pHy5gP&DJQ5*G=?C(4At-nNQCdQNxb+h+d~AYO8j+rLjZ3 zJzoY26}gZkT35~S@ng8@YzexKl~s+xpYIFOf;O^+;_$(l-iM2svF|>iua-05!eYcC z$P``Q)|n@tRFvGh7trYyC&?HO7R{@DSw(0pY~RAg@t28VE-;uacmIq#5#sK?VxA}& zizM+mNges9PHCDX1bf(`@l0h8H}1rWExYsPw6(u~ry)m3v5J*()7_t@TVY`{SF`E{ z1@-yp?X{D~{(AqqeXzg3zt!c8k%>uOPVPU7V*T?*nZl(VFaGnK6TjzsrQ;V}^#+;E zA-<8PvF5>B`XVZ*B6J?cCXX--p+KaMp0P!gpr$=5YwKO4Agq|IlMjSS&``{~nq!*m zzmmr*eqL3Gyo-%i3y~%howULx@u+Aq4xu87l=z&-BT(9rHpXD%_Ou=5_aZ*0)@Xif zK1Qoflv!Qe8zfVp02?6Tlndu%m8V#eWKOFAlRBb$ot=pto&$Foh16h9+m=9BxuTV} zjLr6q@MJJ7>fwpwqijxKl!AxMQUjL(v#c`Gn%NAFjtAhg$L4ElYpDfrGJ-G!g2$?&Xh_RTif&%IioEUA&-p zY~4zSAn1<-jksz!kuCBr$Pl?kn=y*%{p}t9nvW&tnh@oVwhB?=!J@~*)?6%w#O-?& zmU)MxS$#0RQTO#k7`GEHYf$oodkpur>wZmBY;m3@_yMO`(|ER2iD}w=je&{aA@yr< znRs8$N-2g2Trpb6{4XkvY?h`Ve;uaK(1L@6gSOM1?i{KKGZ)h+90p4IZ%ma8!2Xi^ zZ~+B()!MzndwRwnZgQF)GspzmDx|gJUPAAbbfK}jy1Jo(ot@noKoS7DEx_C@NqHH2 ztB-HkD)v0e^o;7z78ZjSCwLrrZT)4P!gYgD*qPBn6afM8tF_8p?a_|=LzmyX)qr+J z-k@52-t^&}GlsEUi-OqG=$9fn9_-mty6(MsR)^uEr{Lh$R=7|Jgl^m4f~K79T)$K_ z7tGd4S@Fr2f5}ouPwwukrv1*x0INW!!f@IXEoyCJvEhd{G~S$$I`fWcS01M7EVTg3 zx?x7N#`h?NT3CVz6TUl9_6NJ|wuwHc7xC+yS6@D_X4b?i2u&qd;r)y_(h{L4>iE#< zb8kY?TK|c)v8E~fX6G#EVeE5AQ@%onIRMB-E)Gpw5l+|vWZ3sN?%Zd z(mCATPi(4FYkL_Hk&E;nr775@34~Oef?!PM__*_)M@zCIoL_fCpQ9!lvP+=hz*O^8 zlQb-X2xRCy#20VsJc&T{)<=!@|1KT$BR>;H3Fl;&ngfWyb(dp@CK(x-2TyOHWd$4z zLBa-r<_6fkr+g_bZK++1!Fwn?pwV4Y<(==XE&9l4`+#OvNdwz=l{ zDwbd5<*UleVMn_*x)j(5T}b3-6WrT78ai|<)Z-6~*7fBfl``+aw!~k?Rv2bwe#`SY zA0G>q1vYyi#|j1sRV7*|D=UYGulZ#vQ_Hvh{j;=WukL>SILlK|;oeRkAU;&dJ)4V% zVsRtPGMPH@juKl44E-6ztRN`qim3uc)zKm08%hE9}mjxnSx;G; zGP1H_=_7yEHL(F0IHR-p%KCFtt;v&JY?<}niYIjCaGFpO$Q@Fa6v2_+Vn!UC3bXkLH()~@jB*%wx7QyNzxGOuB z?Yu1P0}RwSD09EGlJwleikCL_&EC4-VKsjA28MkH(POc(u{O^S^BnUW4Gj$)HyJiQ zM_TJG9IU`#PvV`Qghmbg{SSCgSkgt=UAT~ZOyUGgBt#+nzjC^FBJ`ary9Qy;6>?!G z6q6yRiyqD=1>d32c&FCR;=R&k61&G)mgRbLXY7e7u;m&X()@hkOVEc9f6j53?4G*Z zI^Ln6s+2EH-G>)`zi@rNZe|q^EqH1*s7}>l>M_Uf39I?z7u|40tpFRYW=j>Yg4-!j z6don*>@ZzjhJ>nB&)ryzNvk4Fx1$QLTUt=SgMBuYH?rkCs!3~UERBOIt;d<@jO|dS zTdJbYK3}y)qLq>Mp0yz8XxL_L1jl~R=<VU#&jXkX(;rI{K;3+FY{$FsQ1D<{Y`Wxm3k@y+0 zHiCkj5R_ClKVZgw_uP2bp&*3V?63gOk7U1m9vDXwbraCo^82fZdmN<0@U|TjO||oXeE7~Z(Q~)<>~|EJIam2=7Lruals4-K zak?Ja9#230o=}E7{pY#Xx08iNDiIx70X%q0s4R&f?2UCL9U4g4`t_%h{TR-c zM=6pdl&~OGj*=o-7&Y+yLlph^Ui+PA>*@8T-&^+glaQI0;D^@D^?6Lo$)K)@x0QhrAhDo39{i@71i0#US19-bA2aD1^5xawU#tZan%4- zNKT2&aGCe7*mFul2#z_SvSTUz*eD*yuK~Y2Td3$0dM1e_r{A^2Y`mir3`tmteqgN; z08PBAS&;)7(tq>KVOBNxk-V?hkqxIetMXfPZwqqtdcw zGM&+`p<7v-#wjG49keji)bKdHo@7erR~#}ir9Rc^d>pIN>!b~hFICNJNc`^lvlPR} zCQK2^79q(&3L*$|CHq2!hpFU?+{BKs`I;C`^MR}ZThv}EMVgXAR8o#prB!@YJlCNA zYOzGPAucRG=@cvU*0D@Hj9gSbmr7I$#T=Vi2nVU(g=9^peHW{bCe3D?xF8O$e2w*)qZJwaUhZb=zQZJ}_|OVgDy9H2 z7k6(glaELaj>NW9QH)9%*=0UFB~IPv_<;4KwqS;nz64L)3qwtZrecPxjhF4df`SE&i74elF6KZ4`j0X$iT6Kjzn~6;5{Np24_@=U+5kpPWf8(*-8q`#N;G9=Yr49;m*MU%}KL7l~S0IY3pL~ zdJ`AF^LG2e!9h-DX3G8wUR1zwfjU(yL-kF@- z>*JWw*zP->3isUpDOBi&ohB#7qs%>ML{(*NYJ>w}ca&KrZwCjF9A^BVMTG-QdOMk% z-iI|SHHK9kUO=$d%X`A3s*2qSU)MOT;tW%F*D|wv*pT zkqqAD*Bv*L?O4ax`>q%)@QO6#dX=p&x;b0g>3}WkL#@#)uqGuBC*~}b^7H0Ig*y=Z9 zdt4m%zU`M6aM@frkX*QKqD%(_`b1?!A-AN5T+F@+;hYmCx$5xlN){EB+QlPb3xkFu zQEnDE7A9O;I%%WhRyoq6pn1`BNV$ofcv7)fgo^byx@gBT6h~q8VN{;NIrE2to1ITc z@K{f?iz7=bM^}w!*Urv2UJcHTZ5NFK_wvIdE$97s<9t_+?eO}B^EL_LK@BQI z%Y(d_Qxt*WC+5iVNEyjL&YRF-0#9x*);Fl+B2`+>0!v*k83>d2?IjvCG_uv@1O5aAb&h5k&-dWK(UCfYJWLPK8PTV1?Bd z8mM~Awux${x~!r+an{VKCY%Z!uEP7ZHhlg}$D#=>ieHyzZ|&hAE#)H7%wnrdCrD7j zQNK73qi*E8BlqS{q2x)VYFG?kHZmMZS6_)2h9-E!Gj+8^<#70820=mm99yblAF3qq zN>;OeWj2q%hS72cK5=z77caE53+>KZwbeVa%Z;thQMReo&O81s^Y{IA!`t!i`RTlw zHsv{LxBtBQxvpz42OWZN{F74=(ctE$7pK>jFpvUu=5MsEXHV`1tRZE-FK!e zwzs!`qmd4oHljo=IE&4KDRaX%9)q#JSpT&D>6jzJnSO`@f;kMQ519$h6;T!nt7I8= z4jp!gdR|zbp9NUdEXk#?X=S^b$QHu|goA4=1;AU%&w&Zs2mV`K5?AI^WN@4!> zrMc%=m;7YsldZ=^$`*ZhQvO#tbukA%?n@YE>O`a?WC4j1 z%CN|2Sr&xMHZ}b}EdU5d-`n>@cig)6#gFoCMh)cek%?WJ8yE6o_`HgN#|Q-^95`1F zEE89Hy21^fxPS)(0?uabhEIlf0|cr-grJLw%*B9pkRYj||MdG7SB}X(QiN0(>;Inm zvY!4MckvB%b$#Dzf`Wpi3xsKIusk~6Ud{k7*<=GSLOvA)1I>{*4G95(LF8(in}dl- zAuy~nGc&WZQ)t`!Sh)PXKHN`SAKvk0Ll!g(@$k1$Pv$ z15}j15m@m< zsj(8nQwNjGov3jma3TQSK4VN&6b@1lpnS4#ZmUl;jtt5JG*=*@cHJt~;pV6t^BVLp z(YOmyddyk2(e2D!2pC;7CxKhV4tv%_T1PQTqx>_vWzh&~(8#>*d{2(3heT=P_%uq7 zcHxzKyQU*CtYm$mVNK|^Mxf+;ec4Soe4vQ*!VKyr&hB21cri1diy>9n3KbzE3plJaGdVuxrjv1x$0jr*UzZ zZ@6SiO0`;7F-$NA6qwwkg@Tku%Q>3TwI`cp<_B}mz09%tk=<|%2 zC0a06XsryXuSoOx>wDxE=tNkxyKpq=zP~U(omwr~8H_scum+FS-mdCJ-niVsOwn{` zgw9PY^E(!MaAJpA&nrp`@i9vy#AZjLLqQ3b)Q*P}nAQ%Fd`sx`fs;`{ zB&SJCkYrYP@O64AQXN`HUFvw~CO&;CeGrmZdm4kltHQ)5_{#_hg_TljO<&Amo0gxt zfgy>~fS(N5Cx6w}E}uUFjJLJrqm~~rBL zKt)|;Ys$VRZuL(t)KXN3S36x$f83vxlI*$QsKub52QKU%oRsq?{k|lXM)P<@CTpXS zTo>jgzu57#%WOFW^9)ia&_b+8U0BI2ht8LfctOR50 z+L+GU+W34T?2Y!j1RQpnAJZ(Q08>A!u+{RMQ@bKlRV9Np&L{Zydiw;&fN7zF_14*i zd}<#!6MPzgtaslSi-#?EVAmnqae^nhIB8Ns@BeG zR_YG($OVB-zfzt1>#NdO#&BkuI&9j@8-OvV;=$MnET!l}g2mK=5G+xs*dKvdNMuC* zDdHe;gz%0b<58@iL)j&PKL#z?g=ZD32M4v!59$~)%Hd;JvPjD9xAk=kGfR$>2{qaXyL&pWlYw0!V+ zzWDMnet73}z4N`kv-9n&x?Y6}ZA&E+6I18K0MYdH^wZs$JSFC$2CY^lrwKoB2d zmK#o(4(Jl4A=uE_rH9tp)7ILN@*9snl`6D=Vg(l3574Rr!)FhSxuctkii(t!6ct*h zzkgzX{=|JFanDq@Q6b2yI4Kb(<6u{V{H%StLoJwML3ea4dQZAMzsk~db}mT&jedkt zb|t05ZcqG8U(3cvijb+#J{-!Te6Ue7s&uZH9h)icAfZE~ zTgzRhgR>7OMy#UPSNU41hy+723>*R{!#|w8?H(uf^Kck}u(0y1$#(4ABQ)Yyt_+gR z+Bx|sB>pOb*uE=mn5)a3EaM{1Rh`&+=0_>SEsZ~HxCZW@`?l}go<3axaMpT@`G1jm zD{XF9+c5&bh58qQ_0Ml~?cNT+Hh`oOAT%&<`NSG<`g1$chLisTi~#iWO0}|o@q%}q zZ!ZA!r*m~-;l2k*v{B|W2>XM94yjZHLz0(!y%iYvZm*|1uV$+h3_@0|Jxup@Pgmt{ z?>>ReXRj29_SlYkcCg}ky11sf7C2sn6tIaZrcw)~8g)j0IcQoDdfd&bck+w@BKxtm zR|z2f>c07xp2y*mW;>j6m&@!&{;82kjQ4ln8OFcRh=b1+VIW_&pbr7AIQoIk4&P z-BhsfI$hx^n6c#q_|{T!x}A4ZGE66DXPxIg$bhUHn31pxc1*`4MfHTTZf$YOv8Oe; zA{ll|=JN2I+`Sr5I~I+R^1Q8V6J@ZirTvxr7?ROF%EK~X+KXkHrx`~l$PpP8!fuZ( z65|nnM7m0R;?g*+S=Nk`T+KU|RKwM`(@N8qlh$y1OhQZE+-9>%s?v zzs*fXhPn)JQN!fH*dmp0{Hd{rnNlEZ*5`*p>GgkpG-VD5%i>}}KQ(aq* z5DOZy&xgBOznMBIlK896+VR@qz=+Zdj6eV;5h<;i)AtSl=7u$T5Mdrv+QX#GbK?;^N1NmnS?{3f?^gSwD*y@ zdfp@L$l~o}rhZSJ-(`4((70W<$mj01wJEBOn7`phU+X>mP?XLjL$J(N}^vN2c+PouqOj6+%z-jcW_TAs0J`@Oz_g7JA_WQe2W8J-giV z^NKdvDq=KZ47pB0NPh3eBe+9)y15{qwN{5{fZOi(a6iyfQDih+WHzEqQEFZwInzRwR_TF;MyqISd{dWFm=q(HC~ zz?eBcJ?#LH3?rVduJ-|?&l}VN4`Kh(U$kg$E{B=U&dvm`Cq#Kd6onBlr(ZHsw%1Cq(!3p`J7x!fKv0uPp9<}4>5ssL~w&HxI{Z8rs| z$)L`u`zWRS!RJ-Bcc-g9UfTeQX!Y%cXr0&YaAs|640v3D@HbNT{T$BdyW88xmsfdR zuN@$*a1t=V0q%c?$C(lkCtUeE+@+s{UrSh^p2sEHrPgs*?baA-g?`=@O$+f`$#~=E z29S?CY}+3#NN)-TIUoqT;=w>`2(gq)ns7NV6N;D7q}PxiC-^&r%IL%@8YGU2n2Oj9 zQbrIc`cNCIB5iA?vc=aCP>(Xx{L+kwqdn3@pYg>cBZrB^FGl(kUnQq+8fA@$ve#9Y z{IFn!nq_`MHl9m9D9j~jjbz&4a4-XHY*FB#PFhaz?fnX*x05AUb za<>l9kv45zpYJb#yXrF`>K*`B0ZKXGmw_)JI`H2uBk*SEqpt?+3A*qQ=agcY!}1BJhYuk!^?{q&7glU|22k7c@@*(XS86u zuFqjfk+ZY&zY)WKD3~1&g$|Y4i~>MT=d8Jtjm;U5HwqNAz~}WZrJ}NGZrLCmC7CM| zh4nBH&rzuJ^q3(xBaqzY&U`F4sO!DImEz6(I(ah`^`V}&xXA3MA{vH&cB21OweJN> z>z|QN+Z})XHBgm&VTqHwk&H-Ub5oq)5GI6Cm=SxS{uV(Yu%(gSogoM`vYd9}d4IuU ztK3TiPU|}$e?7$K?at>7IEU`s`FuuzOfO)I0nmwGPb(VN2+=~Q<$;IAHoekSoC^ESstkM+ONiV0EW!B zs`;xljdtBTC%Cz#ZheIcU^68wI>i>1yKm}Jc_pLI`+>+1(2hC+O4FMgrxDiayvaXY zE|-4?|KXUpT~5<|!W|f+w*mFDz~vtbczAdq!}oREz~_8~bsR_w(*r4%%|1TP11C+; zXP=jOADyasoAq{&?YU9uf`38GFU@+f5tVQHr)A~gJiA4_9!h=T2L1QpZ<`2T}qzfeL(;mKFt? z2$B#RleMC+iJESE#~)yNh#p9G<#2X+2=v$eCq$&4XN(~ur| zs5MTSJp=bKBkMmyGJgW}kHP~$9MT9x)=3xGzdpOk9}pV)gI(`8L*D)Z90MRjg5Aw- z)6YS@k{9?ffeEPJP+l8u$L8e-zLf{Q$KLMg@4>Wb+D-k*+@NK8OvqREhBz(@_=aR? zZYi0u>^}yq=&^GK_<;%qrv?I~i@7``Mb0XS!#JvyWM41HL#wJ0!0Lag^w6^{^yaQa#zd(U8$OAAmyWvUcRRD6S z9yz8z6i-1S5+m>R#M_0yD;PBwzDidN(=UPF?s=vrYMq8Eaa-%JcG=>HI}n2U-ot9B zkm&JmfyRwTJ0^S-n7`4Px4tjWuFJDfh0(_PjkOH zn)}gp5ORf~R!h2VdobWgf!Rr{x9ronoC05@eyPvzvHK;@|BIp^Xe)Ym?YD#G`g*Ke z6`j9LrW|h?-rM4R$(MBM``3r8H#bvL>TvQbZGc<+FS6VFd7G5T5J2``0nbQ+G!@8> zIO5L{P<#UtyDToJM<4}(6X1$hXf;9?G&VMhiLyj|&UZo&G9Z?{icFvdE7OwWBx}0f zq^z4~aJ}{yWpdSfVGwLZ5@w3*UxQ8=W6Y2 zxMHP!uA?nZQe?`3!}0&N9;xuvc}_Fbn4F~eD{2KO=!am$ye%zrolesSbcCM^m_#PM zGWM3liCbezoOf#rFr8r zz*Yk6$bVBP7FkIL^@O~10Id;!Xj+x_9=a}>BA2x!Upffw<6Rj=!Bdv8vM zIe^HN?ugJge!3?YQ0uqr)R@s>V^ht5iNhL?OB*dHABUvV_Hbbl4t5btDsGS$$8HCs9Ia ztj=AyRxVjUoLHt^mZvMx9&G|!FDZd2ZJdt*T}y~d8v>ml`Au#P;`i}~A5FGZAA2B7 zZT^rcY;HfJZD&uaC%X*|g{@Jc=eUBG`?)8{9n-kW4hP-7jDZxJ|h0p`i<(M>CZKm1VNWc0DVOC*>{+pQ<5u@s%7K71r- zazwv#GdC{5VeLaS`kldO>pgfT0wpHS65}&iP4BHOnz}7J^?Rl$9KY6o#WYY+XORI| z2lsX~uv8pyA)bd4>42*6d+K9xFBeb-1IkA;wxzYT+sR?T7SVZ`SOv(DH*NRZ?cf8t z0gMDuRB(|iGqt%_0RzbAH`m@aFbTK;Fx9^x;iIFnAO{ca_L`cD3LCGo^)n7aRPswt zC|^i805}W+2-XVabm~(Oq?AqVUDVx5{+k7g7(D{C!s^g%wrFzZAH68dA6hI`u9xG- zUMHGL=DwT2${|9VR6yDPKw*~%qicXrHs;l2I1luyQ0;&vC$!(^V%woYpuX5bCF_T^ zapbxP-JlOB-k~)*BK!L21gi$( z0fgL?E$4MZ0O()Xd*@?WXYCx2hxvLi7*8!zfXV9dJ&wgh2$gBgx|@v)L~FZoGHu#% z(fO7Mtx8ugk_=H$fFa57ypBDbGs$+u7MphFSzhH@Y4y0X?c_REizZ!fc8VW(a8K^T zJ}d{*L2;2BD5%d7QeoK&(B&$n2#tl+-G!X=dYZb}UO5|A#LgVm8xqYLrWMqS&zNOv z2BQhjC94~8cZC}I3yzYu{r)J=5E9MG!6!hVVK%S^E#Y+2`3+}xyvM&w$2ARI5kD9x z`R+5;A4txM6|luhRFtHF2STUa-HDT!J#7>c-lo(637^;d7wmBaOmdn{Gur{^8-Nvk z0){%7oEvKTZ;KjTcZylGkc=azys6cEy7KpTEjzusG4FJ(X+ zE)r_uVb8q2h4lLVbu3Fzqw8LnLswxq?vbF9!$WsKP;JI$8I9(xu9& z1{JBPfs2YOJW5ibPiU$d;pmfnQ7Dmt_!OqhA<{t!VJOFe+Dvd~doId|^-&awA6s-0 z%~i`)6$GMBXw8p`ITWkP?7vcRPk`aEQHrt&q%ofCEm;ug>5AG$Yc`7I3#P94CGOCQ zsC{{#ToTS77ByF%OnbxW9`!^l_&&t63lsZ>T3T5FHLllzjNavRlUiAjfkxFlP*z2< z07IOG8bj|VfR(6HuL*><=0bx438(E)3^hu?ObnA`sF@(8YN(qDxKEbg>Chs=>wrB zTSG$%hNQ3*L1?=H&QVL$FkgI8uxy|&CrH~QW!CF6iK=kC0lrul*A~qd{{;IH-%+rw z7Y$lr-pfUGyzK7={Is@>EfdfC2F@=72adwzSQcS7FcU&XVPW9D9{TWZUqf32atu1# z=0xJ3{ogfcu)C{kRPZHpBzhqT-wNY~%M29crCE+d72a=GNL$e{%xWYBS(IA{X~0S& zX^yHM|2j3v2l*?NW4ECOsjs^Sz`}1DzgzLBrMdbtJ#_+Ie(E*wl78leeCwbtQ{RKs z$y<)F@}EK%N9`V^TjCPbHm7RQ-q7%oJhNX*^sGY7B1g&%$j|^@G+%vunDGJSeD7}t zpxCQps%0O*2B_asnR}WRO!+tU56CqYdr&VCu5t4MR8nzlvUtIEAIP_mmd(q*kNRS* zFZrv+sLHO;++jr~qjB)}E7%i}1}!_YeAjWvQ`_qH@E z;E(5~_VFUAg_R;Uza(R#v{W2@VYegq=Ka{ys}@rb@aBx>Wj zH_!MLtLa!ea0?Zw6^-RDqWdD-g)7*UKgnHcO88cl!1NS1)T3geCz{Vr4aScO`TT01 zKXv8~f#>0{MsvQ4TZy(l^Q~hQQ^U3;|Kf*~Y@DZygQ1N5k;4yl8}ffly=7FJT^lSM zAVBco?i6kzOlF?K&&-#t`Br`L5{H}32io`}<6V()qr|WqiLS3|`k(;=Te*YQ; z00&8;PT)d;A94nQ0lY0buT63RGJ8Kf4WCFu@|&7JvwP*RE8tupqU34(_{fa^k5$|o z*7foaHfp%TkRt4F?|VJW0K56FY-&0VzUlTrGO$x+08XYQo;mo4q&ioIX^vDI<@|pW z(u8p7^>Bzd3d`yC6T?T~kd?5-Tx<&$2RS)5#g=}xS9#6mpIaA-%2LB{W@oyiy_P-1rR7?A^*Ahcp_j#jN)cz7?ZUSaFx&hE%BFXnTU1ky`s z6=9g!QFLERIeBLt<7rFMb}*k&@o46Z-Ww^SLk>%Lx%nG-`DdK_;W8PwG=f}2S1J{) z$nRXO$)tTS_L-9vLAWwp2@d8f#BkX1HWHB-+4FAvwK5z1xXTHVn3HRE9ag}A*#GAR z5N^Jy@Aeu@m3S^qd}uHvw5{z`6}Apm?RBns`>nb^;COn1K)}Fc^9}EP&hQtJ6WDZx zC34yIAD)Yp`rfettKTCV{0}^~1UwPjAL}G)lxtUbwy~e%|4JP-+eDF&383N}Fv=;2 zDX@eE*EDA&!RPgIa=>2p*JRbg<=Yy;i4vNGK7}Ibt~QAq?9!tw$e{#0`S=fff5@hw zHeewFp2`@~g`?Mn68)LSAMMC73q7&P(ay=H#B*Wt#*g^{*>Oc)Q74o1Q&#g$`00Y%R0#)Lo}H_v3u_7Kqf61w%sn zt5~^fQ2BeJoh`*Ez=Aqt}%ov?Y`PvL)#FQ~JVd^SBekCtSI(f9n zmv1-PBd-sCg#?7-GZ>FxQ&UP~>r$JX0T;UQce2EO@o2?=OJ)4w@T0ti0W-#tRnj^4iUT ztqAu7qfNBwx7a<&DxA5!z>*SRF#j)%Kle#~K?7q88q?Fefsrb8O_j)GHVOe?8vg*? zOw}7m44hPlR#i)R|E*Fy7CU9L{YG=g`9wRV354u|@^%&Z)D{nMVEM{pXd@c{1UFMsw=kBn8ZLR~@w^9|oOY$QCAgcqhv89MY_MM2e0a6B30Qp{`2p8~? zSYH4)5lgj-F-S>QkvblULf#0M=p&Zu$97t>7>5>3ug8G3jf+jO+CZ-8Y*MokwW1#A zyb)&@L}|oKAm^Y^fhY(>tBfhZh}o7nw!EEmk5;&*M)(n^! zHKAP8)P1#mJS#c*Kp+va_$?B^X!(;{N|xE~79QM=#D^~1M3F_s){ty^vyMA(KxAE)gKQQ-S$H;$N|L0cd zJ5n=4o$fIsw@M|Mly0Q=F}1v#$iZPI7^%`gp%$qaW_0uqAX2q3IC7~%J*mR3)|hK6 zGRk9T@^#9dTVuPz2JzOy-ZuxQDRQimws0+q>#qqG{4RWY&WvPH{@7fsF$(_kAN5g_ zOwAOChb4(kNlY5Wf0BOCt#eGCp-;__Y$EC7W6D)$uqjJcQ&DFx)GLTs@Spv9J5-JW zxjD#0jj`}~_NZ>kt`i$AJhb5;$Rx-9cY5_jJUcxtgWtk!NMdm#?4D-+dOZ~$p&Gv(dEKIiulQ^{zZGMkltrZ zt_DL(N$}(NtbjDaR!0%RcY}-Ti;n!PI)9DtIc3^dy9scVNYU2$Xf{Sx+C*?I(|o1Q`6^v|FGy*E6A+e?ZdOG=gIzb#-3AXp znb9+6t)vbHiPw=Pmj%v2(v)=5(ikuAZx{AB-$4$aaY2qF)CLmos7-ElpI;r4gG9>)`|6aj~Bq&Khrs4*lFO_#9b? zsulaA2ot}DK)yhOi;EpOD17UM7#m%3Eo#{r`q<@^{`QEEe!zi@MvvJ=BXrk^Gkx8K zCphQ^ZY|2ub1mm1-c;t_!_OsX5W@9mri`}AyB}jAIZ`WUS zzp;5U%e3N4j4=AA6uE?Vg4s$C>8rzBs7ThQYc-fjTh~6JHlogd4Z}4ywtw=?3S$syYL}Qy|JX)Ix;hiI%ck^2MW84zEuF||( zmwn~HtDWCW^NAmYH?$Zi#fd24fSEIEybxjhNf6bkRm#>~ZS6Gkt7dXFGJ z=!Ev;7_cM#b0HYNkjm-0+uwlkB{1=+7fYNqV#mhtB}3zQp-SJ8ELX&H2J75K=@wmD)OZ7UI#G>Ayc##P74uROS;Ne zmGcRDt-Eo!a($R!pxwkZ!td2=(#HfA#<*$< zz{I=n?L@h?v!%ycfEQBbrfCtt%C7fLkURT5QAa#_2vghx zn9v{z;y`7_3q0=Q=S2O2!ovQB{tlf45V-v6)T~+jZwP`pqhNsP5dh0Bhs}5+UhvP+iK^}m-+$-I$@_FAV2j`&h*}ZIA62GL&z}j{6Cu^FJ^i?ly`8<@`yl?8 zQ<=GH;ragRF0quw#^z7>uDs?)Yw)44&Zm>UPZ2au1R%gi#drQugT0DXzuMhf7$YE2 zctb=LQiyO-l6ih-WapFNW^Na-^YXs~pTqF?Y5$!;!|)ia4$;&UVdD#-!%mtmNFC3$ zeLYs}sdc)XL7@kon;n{wTo`%NUyBM7@v=D_QHG$Err{%G#HP3u)EV@;Ar>m%qLE=1 zc2Ecr+flThm-#LIar@58&jrzvtVAF}eh)?B3EL)%;tHOnVo#zO1g=kx8B+^uhI>96 zduc?sYN^}6Trbg!q}Cnb+66IImW(!84SEg6r8kxNI}__2x__J!;BmARps$c5dTQ;#HsC6pdxrT+Id2F@ATrF z{2r6J$r`E#?ICn$silF6XujX_0x=?jSbHy{z&cQ*kJtc`F#KiRHs;f$&zOY{wv~ej zd}LFtk?P1D2xM+k9l{-=F0aPZr0H*S(PU00`ZD}s@1)PEBqpff@pyRl-DD!z&Y#*8^vIa zo!2R#$PFr4u8wqnWKM+P=*q>Z)?9^gBZpH~Jm zOU@~YTOWqDetI4{BoEGRT39jBQ))1_Ka}k^(~s8+bez(=4(q{?C^m*u!p0y?hU0%( zi2lMw*S3Cgds8W%<1)B=&P$5-WTY1*!(Gfk9NmY)WEspULnQHj2v|U!!-NkO)E!&_ zQ%%7E2V z;2|+tVgsebULp2M5>#WNvF6h9eY~rQwXGg_661rCi3P$zjRE2B^8W?bGfa{cg|(V&eo}Z>NY$0kI;gBhc<)xe;jF*kPNQm zS}^rUwCBU?1D0@hF03W@zrcK$X(&{ZZZ}E_!yjHQt$&ro`Cc2~h;G59)1D9*(30r} z2SL&z;+MkiPT>*>sq40X5Z27r3eE-wDGqq*VJZYG75tDALM@ElVP}xC|7Ks#DjisamGXB_|eGYv|4`|Z1>0o7y+Ke)(eXVAw;2?OjSnDFwc!Q=7o6+=4E@j;Ckc4UEyi?!r;T&^PN1~v+etY?F7|` zV4`ER+^xd;wKdTtWbwXUuae%8YlI=t+r^@FwtX39MY4O@?OiI`HF0qA_LnVI%v#X; zB5iNd0SB`u7%a(40i?O`{D&pmo|r7U>#dsifH~5)eoVWiDL#HkdrzI7x&+7Y@(Fve zLmpt9>U4TBMuWy={yTAUYG0`l$z%sLd!O30ZRIfdE z|BHT+f9QPj8`R~f8ubk6pVJ%*zWF*Ww$B1woH85(%`nJ zQh)9+1T2>4VnSV7?TJ8d4^?EU>Xl&m@KH&&cbXB|&3*$kx;P zi5cIrcm{6(r?8}H;>Khu7Ai;S`PIfpnnQsQ?y~c&?s2)Vpkm%Bo&zAh!{gK^z|P`C z9`rk2CxH%@9SrkGo2%ow+pQmyHxCPOGNS(iq0vysm)^YU85EEP#gc&t&n&VKEoxIF z;1K<1sI=gs2F%d}RA*oXtHb4gS|c!n4w+* z=WYTq`-Rk=6}aQIm<#@?8Sdje?0_ILK!Bzkdm=0JM)XLOR61Z5^>Vz9)wV~yAI=A_xaGdwN1ytSoh&o)*{Fzn#!FRx^5l>JbQkf8~qCD1g+jIt*JXqwFnji0$1}&1 z5i}H@u9;>VW#x`(xA|)x-rkN}e0dGj@Bf)9My(4ZFP#>Ip9kWaB&hdbxnyK5a6nap zVsiq{@v3c-$uDDijd0MghCT0U5*B#(;D080$p_y5*M@~J)_DnBD@8*R zS3Vy*#rB7ho`Q$hB07ryts_sPoQXfHrSNfr}%R@4I2Vi z-eFJ@(oxRTmH6|aAAj6on}B@Bh2!SB*{AHrGNZe!8XXHtGBWf~X&UC#1idP4=H$P| zIXk=qmZGBsYwk}+*-VXNEJ_xY;H<#Hbf*1E;a?ynE-ws=`28c7)fV@AyLFP5RrhMY zy%J3xiuONARg8{GMSboIBWI2z{x^nq{Gj3eq;o6QzMIXpykoZON zaCv#TwM8`tN6K5#WL~ABUi;XqtbN1?`Hq<3n1iXZ1xT;!Y2XtXod!{d?tx*(Re~^R z!~_r}rqwv|E?3m??pA&u2rQd0;=(bE2dLq-43(_m3a{`G)E*?$U zvJld(j6O1*Mup=1cpk12Gb0~4wrH7V{wCrCN2p2*Hv*Nl!$#^V17J5=P`{U#;o{=3 zKCWXdHaz{(sZER6sl!s7lD?)|W0PBri=7)WT7L@LRiKNr`n_N~zeoc5xC9wnpxL;D-I zO_daOMpWsEy3My4Ys4z;VgoE2{G{@-1@)@@&$1d)2{h=~Ks8pS6acs0c%+m$lEmJN z0nVh&p2a`WmjW?{mtK2-_k!p4UFYAhrUfD%GEA8JCt1TPgZpM-fgpt}j-a#w_TBv? zh5B$yMjcvnZwx>0Fj8H&=Y!=_RxLAn*o8_3X$z;z7EjDxednpE=34mGYI;6(Ny;_o zZOpZAO|M&j> zUs+jf@Ujkrty}!JEkcXZGixi<3>^t!bKv+eL?2c4fUM42F^B1c*2w7Myo(05UraITVVZ6$Pup##V%(zu6vO)C#$AfxX);(5y#r7hyIg(;0 zQAVA(r0(BX8nw6GhrjDO6&_tgb~Ek#GEN@Qr|X;GpA+2)l0_!HvV>%MPKCT(y7?ph<7Y`TS z)!%WyN7$ZAfW^c4$=Lb3nYZ7r3;K-Uc>HNaj@WQY?tSFZFna+_5CF()@dZVV6Uft! z#@8aiSzfy=>H%3EE?pRxMy@xX-hJlaaAV+g?e}2* z1ZSFzeb%Ki)SCX72$E4lzyB31Nko%NKqtvY?#z{>R5d?SCHt#Gwkm-w*t#&HNk|c; zykWtD$A=JMhYTf6B-9JbzrCx*O3_=WVlVZuzT*x)O+RnX)AwTp^-Z%pI&AkOVP*p( z<(vh;fb2w-P8doWmg$F0H-(rK=q6`{IcOs3%MF>Nt{Zz7yhUrTc3px7FoKf3kFkxa zj5S8iMsUG&oRa=`aC@K@jdX-wBoJ?`lKvj9eqSP-XCQrz1R2`|-}3#66mJ1Me+#`@ zJ}zFcG6bVk{j>lel*0I41FPJ|xT5<`Nawh$y3pYLyZ0GXQDAPG;JzCvG$uO#EjlB< z59(Vv5#PM4o5Lp2278r7TcP#-Pit-5-aaw1p^1faWFpU(9JE1d7c z%M=jz^*}+DV{2my-6%3)@@Zhej+(A6!r{=*A$56`eR_JuaMOYyEs}wGUaO-^5AZ_x z2P-|*1U(!bJPj(u5eXEKw>|IV@f%($?pEn|F>In%{vRT4Q-T$lA8=0lt*Qwvf28vy zVG*t$$FZeMbf1>w;r9uep_Dw}F--6s5s$M`I|l(bKSMG8Rg@iPt@IL;EcsVcrSI?g zak44xmyZiY3H}kG5s^s6hMa5-{)jzCEqU+_=zFuI zKZdv{_WT9dH9(|_&L-E7Mi06PhochsM0CuU^{2j+ezE8in>jYe(39s~U8ee_oyz{K zttE|YD09-=JZ0!JPuVef6vROu z<{oL8tM|>$lcE9=)(Ca1Da5vlMM+`h&MMKe;{7W|l+5V3OiJA3_&SMKcj%MVTmp}y zDCS6oa5F_Hd~}r|lD8;0t&d?ztju6II)#~e_7mZ>L5to+f95*=c)XnVRo1&yz47e= zD}*G%i0}#WD+1%-X@M+!h0`OH+G!WTwRfna_yTD&4RwxTyJ6k}>WfrTmaykWAO-lNjIl5^a z;3ER2^LWpiAf93$@TuQ4ZRV{$MBXRb$A*ZRoE&SOP3 zY%L3AMLhRvw?H#vu=G{kPSOJUL1vMk+^aC%VV!~cvch%-0)VJjuh{`j| ztmuoxjf;3yaS{caB}FDHG6&sAI2<%@wKoSc9Abs&0YyQDJfic53lfPR$iD2yfKh6@-RVm zEbk)-36DYz2Fv4*Y;Y>U%ht$~L?z@)bSDDk^R}qFIrXI!g@W*+9JQ6M|C*?M-s>M* z;kwb%R*G(upTW+Ai-SiT12KMd5*-$KN!@tnnRxVepm&&r>_+iSKz4a#wX_yid?&UF z!)-TBy9EhTrM0wN@wy6&PB$?+5&R?NM$;(#S4Y)i{y<6cP|LvB(n+mPYqPEAq&DB^FI%C{ieSlwGf`D2AdjA_#CpgzQgrWUlV&#yhBnA!*eM@yZ zt7&{8VG6C!eGi!bdN*q3QmOypo=zgq3sSaeQ*I0wih4iB<&-QTM4MUf-R|Z-Ta{Dd zQL)HSF(1#D(nmAT>-{o&>9)53Ns<^eyZ@yIt%fLx9MH4;5{!4i1s?ae(ba+dL0N-# zI-BbozdhUA{a}ll(W{l(Sfj7s$rT4_WV=vN6B3NgLx42}6a}a}jOH&ZI^7>qXhuCm z$P71?a>O%5{Cw|@=le$qlMdx^_TCqIaIcX&d!NZqzU_kLvs<#^Y$*hT^T^6Btzv)+1#bBwX{@1KPD|HR5BWlt67kx2 zam&MZ`$9FnlX9(0?A0|1CrtFTQOHDxLqDcluVzWTGr*U7m;?WAXNogN*EZzd*su`A zu7^Z6AYo+!Sy1_pVXAvx<>itEr+URcA6w&RtN~5#%v2D0mt>``lG67vR%@t0T^Ulv zJLO3^05MqZP#1faHC{eIPQ{MFy>K(~Gd?sQu zmacu#+T}6nKP-J;M(Hmj)pOE6LKPn{@d>|z-i>%(NO8(B zQj<&}d6FuhN}j0LWczO;*gG)|ReNodFp-Hc<1B`F(qKPBz6&lhq9M zKKan|r<=~vn^~#vOpmW(C5O=4c+7v&29=LP4mbMZuZ;ixVc8O^FS=&6h`eeN<{irx z%c)1`=JF8Ooo$5U<{VwVO+ExZuPa~+WmpSPinKxhdO)`hP&|Pb{VRh$?>7cp%h)EJCb6xC49inSO z4+BfW7uxNw$F-Xa`vYy+HEz_W0S~spOM&noCBH)Gmf6)ZPjOtk^RLXf2+HFCH1yFo zqVk*$tU2#$6*1A5W0uhKOu27Z+u1{I3exC@Ifn<{i&@-o*U`T3;kStN_(;vz`b);2X zr%u&F%6~Wh21ikp$m{*g->nO`b+Q|m1*z@OjN;JKZA|#~(jd#-Oed9zxL+(hxW9yk_Bw65y#(;8kAKvK5A9-3310@MHea=W_T{~MXwa5y=jlPZ$UJ3%r|9DzeCd8Ab&DXp#e>l=y5%ANX`d2)LT{h8{* z6`KO(bTM#}4Au76AN|?SHSUO_ccgQF%9W_$zlDEP?7EFV-2U^$t54CLf^ht&j)TbD zxp2Gbeq!n6qfV9qYXZY)n&#bdVXS2#SQfF;hP6fawC=~%D>;GLlX;z2d)$|AS!!(G z%LX&(O{nH9h487+%q6;!ka|AWe-F{6m4!Id(+abmy2O2szVZ%9C2S?zn#V_qiVrt) zN$Q6KFgPi~-JWEtFS=#Aw(}yk24x)k;F+q-m15lL?uPx8+1kJt+$a1w|GSStF1#1z zI3}Apj$Ps(HswXN}>9D!K;6G`@=y!I>e&^4@I$$+(~_ zyBvI&0YRJnaM{Zv=2F~$4l+-rppM4 zxK_PaieMp(t4B61Nw=F*`*dysl>&WsIxK`|jNQ>QIumUSnJAi*!c?To0onuXf&-3k zZ4ujc&7F(}B7CZS5BU)vg05~}&9L$|Rlm_e84U1OyQ{JUFzR-($w{xQfIqAbx)A;* z6gxXN@~eexWb9hH{*_r3Di%<}Hu^W!J8BVJx@*W&=|{JD#N zEAWXOH3$I6g5?h!2&;imIi?^E*en$xW6bdZGJ$14oF>J}1mb3za4K4gC6~0~zycy^ z!|3|-e0BAx#IGiapAy!=lTbKLAd&>hq#QKQC^So?i2Um=3T{$H7aRGk)Q)AEoc^{O z2vVOn)1Eo^SBp4w0XKb>-tJkXUfy0Yk1C+)ZI6Q7o{K`16}61ljJELEpK$;IzSX8i zK|lc=>L5JUsGRll%iW5H_+Phy*ib;92O=E0m{kKMwL`MXA*th$y%b!fOJkX}>^+aa z*Z+Opi7mXpd(=P19x3a~sA*|vC8rEu3nZ^*yf(AD8(8;dkdEuBlN+Hd@a{(fR6&ZM zuTf3(sdS6BN`*|Z>~Sj4X~zW?Q2zEl$rBcz$QL6GUi?*I*=SOyifl3gv;*^$13xTy z*q+z$eAoxaZx1iX3=ZOmFrpK61H7via%SFX@Qv`H;^BgF&OdmfE5SC-93h5XpGZMCUA% zpy^MPMZE$CkPyLd5mP`w*8Q(=!m;h58&wW1-LKX!c8;xv$GzQ1%J2+|KZvx^ z%%EyQ4v7RD&{ExMif;;^jBBQIZ zJ_@yFcx&wC@RIOz>gF?3haq&0p_|ap=1}{qWdaqXJ~8vpdk0MecYi4Pi9JT5lsJ!Z zIPeYb6YZj>!y$-Sk77iHuk1`EG|ly0SW|VO^#xoXk&rw5s=PX0rM1UF5UhgMBe-W4 z4tCzRi8S`He~+chApgLV5yw9#0>t}c)VS%i_IcGX_WkLe(pJtDQ8@^2ys{3VIiTq{ z{W?>SH?}q)*O=WgURVY?O2(I`VhLb!RAQxqvfSx9&#FP2OV!2q^e#TbO#W*pNH@o;xS{yuj zk^{Of5khk;-5BKla2w@I4CGKFj(^SSqJa0GVxr%icN~TL+>F8<*+of1my>4)F% z5lKjD_ENeK>yV{bSS>Y;fpBtIEVE-u!Frf=H9!xSR*S##pfGKjE6l&z@DDDxhqwcs zEf{qd$?rt|=khEK_si%Kr2z=HVk}_kvYo82XbIoF3%5WGF~(@>PvDdAR--AB?61(& zTxLb5cY~SfLkySjR7$ z1BkC@j91Q5EZ#|vU-9OpP#PF^fOx-|e82hoRKYPYY0pVPJ89I$HYugfBlA@$^K6Bo ze@Y)chpyD-qV$Cb4i9bY_QLbSR?g-3_)afoYXZO-#Yc&?N?fr`S6zl-+xd}fy2=j> z8*rJ>P_~VA@^gxwb$*f41@}?wx`ByzD)kxMu{~dZa96;Aq^9BO57Y=xqidnC+c~~G znEpRgB-=r72L%Ji!E(a~k@mh{T{qZBrEdUB?LXu;$W(6VNYFlAtbTV%OP7CNDe79T zum~`|eTP}&*>^rV6Ta8VR(u@}@j<+x{o{gsOxHU;cqD)PdWF4MR9=pePD635E(}3# z>2-@dqiDz1Mq6XMearuBzwUN%FTAq0+#a|b2{gmju0{P}!9a)Oe3D6d2SPb5`#t2d zfoF+RP1sTCt^4Lr0E-!`78V#{dK17ASIu)9k57cKXh6HKc9xQFtwK=!b`v zKK`A`P{=XFL~iId;${r_BU|vrQp1 z@$H?^)1PQ_E(07N3Nc&f>pEFE$~1IK4uvqGXH|gImT9$K%PxD4oFn6(cK%$_msn&( zsaeuN80Gb4YlCxrokS3$a==02LbLRbk9wQ$|39NfsbW#mJM6pkkbjt!Ui~W&THEUu zJdTrT=DGxQq>JhMft1%2Xv(D)2%)6+zxtX@kI9cm%R`iT)$bs3XtG2gE?dzgLa}7} z0r(BSiBg#I_?^iNZqL2+Xds0zp-q4|iuY3dr;nn15jqjX!SGiOnAJV6ug5PJ8?edI z;l7m}0)M6o$HDAq#qj+2 z-{po#4#Vvo5(QLK38b&n#@aqkz3AVpII^ot&VJ}W8>N0}7kkZ+ zWB>UVdv<;jIevI2uYg3SVoXsvGGRj%;}q|NB=XzSf!)jb+okWP&6=Kd?Zp=+Cw(hD z#1keh?hzUE0SXfIPmCUQ0fJ^+!Ex(W??NeZ935c~l0O)rhC@O%K73@q@eDPWiX-v2kQ8 ze(pkQBm_Jr?$xl4W$3s9JTG#sJ>N6Bv|Q{r8U9bCPu@{zc(Q4+cF2@6slC*Iz(kn2 zzNKvEHfLanCV%?P{b`*cODue+Oh^W|RN_|lH7F;P=dD$(E0neu&lw$L^a!8^OB^iu z%y;1|A$aw#Z0BFQ@4wyG>OX#md)PX82wm?v6EIN3ks}%MQ0}M)vT%#+ak)>eI)~WC1?!)?zXN4-_4ppMjGOk%{_h7XYi<~ z5F#Mcv%8Nc1&G@AjCNAZ$8cb#J6W>`pdIA+oxT{~c>n?l!_^WxTbyg>?IDKCb{$oeLf3$uUExPI+(jN=k-jOfi&Xv;5+1s#v6GAxymm)~ zIPRjRBpr!K;Q9ZV$Y75vrh?p&d*JI+ML=WfH5p->@F{=UeXEb=0`jTA1i8#S=aPfD zQ4x?Q3XYVqo8?zccFKsWh7n|VVAh1Qu8=DNzJz1w8_g~}(7&&Kf-Tu=Om=sc)}DT% zW6|$;EtAhxIK5@C;T+f7&*`YVTGW>^dhH`(iN1o{hC_EDbKP>~#xI}OS9h!ydwah} zEyjm=H%iRpD=~bO53 zsq0j!d8NwWm#_(%BQom4>0(r}{AyeEeyR3tDc@xG(EMW(sr>CE4oM}5o9ndIjAW`P z51wkS+T3PorDQ7C13zhC)|L6D(S!ekp~3b%zQKee&j4%h6xE3X8Gs&*LYSVZ^C;&y)YXh$7tKxqQN5wvIh?@471say=zoL!n8@wY*YSj zk03{XR=JQkDo*rYSA0?~UB&cxlJvgr7b1nWv4xwVSsQ^^PEYGK@Nv*${PjD9CwX!% z_YDv^B~+8v6rS;WoBZn0PDoO=+Kk2DbXr*wp#>Z{(}$AMnEI|q2EY^^Y$Nrjun|V3 zKdLU^;^geiu49cdW!_gOS$|(3*%m>oy80ckL;@VZpwTPYA4s=gMb~J>MPS=KJvt(d zheK4W2n=_1$d@W8x9;2DK}Lz4@lIQEO!!RjG;ZmVZZ;XwoyKVlOF4xXhIh(?wRlhO zLNluM-w$1@a}mE#YsGb`+1FZ^ghw!fjmTghVrlv3tPvZz@Xxo)#bMyjC+W&1^QOg? z!L-k-xuaL#wkZzLs7ToFPQKwZa{Ya(+6mQXgA z;|55LZjYpQiT+S(|-8-!d-|8y{1C^yEkLr)?`|n+aD?7E_*8b}wl=s~_8anWU zOcCtgm3gu>fW>NBlUo&Zpb5 zkE4A!tiXc`kGo9|7cS)gfKydp!IS!u`H2ZuH|~fZw?&%uTlB?#y}J4QyMH|qc(C6f zKPNEO(a_RA3|%1M0Bw}f+oA`C!4Ib>+QYr$&_nAkS~jwd*nT`VcX0H)I%Y`a=p-@} zZ>0`3aNUdJAhVzUTT@VHcmo6Zwm{!08?^P1aWV9NSSDA7-g(+Xji z@v#rA9)Dj1oicx7{wY@xeyS(ofwf$>N*sN9W+K?^TuLehb?c}&#-o#+y z0FU^q5n}@FVsxy1tTjIQiPKYzkHeysjDVwh%)2WUcPvD1VHRMeDWsIa=d;IS64Sv; zib`^b@6vMiao@FkUUc515CZF#r%O zZ~8FJb9-74IS#5E$1C<+gyw|=ss1If?tdX zVqV`7+4B8It1`G!nmRBELp6cgOe0%?`7Lq-R}mMwQu&DTt<(^bngrNG?zdvT>8PnG zd!)C_cdNt-kLQk%Vdg9Z`#4AQBnR}rUo=j~-t2{8(T4Q$_WV5A9 z((k7QO=;;jjs>()QIhjrKPi^Z*hFMBx(L$~J2|kbay$zH9T?YZc+io`j_>8@Koz(% zxf<{Xx3@4R)kKhcx@7U3-K7SpKJ5TW0K2IK-OT&D?afzCsYC# z8oOEI>!}lO$N7FDL_It>`W%-|_R&6QSc|bl8$kkuS1vuU#co3LC)HTCs0(P+=$kp$ z3|icT!;91Vr2}-$j$PEJ1~^giGr?0c zdIN~~B~$X{jacS?I=P;)Am;~JrCG+~3EX@YYvefa;P3ATHc*$)D&e9-$>d2$1jz8? zao)G0)79l#s^ov^Bgb#*Fv!38C5-cL2Ae)W<<5`h>`#s`JVRaCm)s5?=IsOX?pW36 zuCwBJ{!Tc#cj?V@zPZz>02U*l2eMALR+#{VwQkL%v*#FY)J&ISbbjGX=kF!`i=9P^ z>m`jOTiI~$r9bH(%{{)I*e*^~M4%*JSMPVlfMFkg)dSq@F)LrIgVcK`I}4sM*)&Wp z3Zpb?RbyP(3H08?h_w6QQ%R!Rq!{RE9K}p!_NASY&2!0?b)G9!lmhiI@-9gmZCfJJ|7XerD{T-UX1D^}EkxT2IP)U?144`Ae0 z)Fr?P>In&!0ma&Ovly$?(@E%RRd+hBT9RKWa)*;JgC z@kIdY;m%Y!U0;tZuJppu{Tn-?lQe>KA|1KeA5MkPK11_a>`cda)yQt%Nd|gS1Vm1$ z+1WusqlM8gYVzU(c#bQ7noAhs7#sJr#U(l-WdTVquavDnPQpuXLVa26UT*O66scy8 z(N!u|L zh|mBvaTi&{vU_Gqb5mwcu)q2%CvGw(v~ zmWto-<=I|U4KGjWpZQ#2vj;B;)uSw0S~!VcM9vv$l~9l)6cq^WwmaPH)c5|^dw+g^ zzPdS=IsUetzfxUX4w6EZ?m3nZmZ6pzL6S|E3|Z2aKw*L#p4s;HeL6Mw@N|4SW(Zt9 z-FY4vGiP*K0uBV2=D3&&Et9)_=xN3TsG_WC!eI*4*Z*)2(hL`H@8^mM_&xd8Do#6A zhQUTzQmIZS?;gaZISS2i@m%`nfLPU*f0+fBozegzCkcm64$~DD_q3j za`3y%<1OfOFs=uZ&?^bwbrFCw@!MB-Y**FWzG$kI-sCc}q5$Wzd&p_+>UQnm8(gH} zE+s+h=F@uqN~)fgMv9(RnG{X{#zs(=SRAT%VjU_erHHj3QJ>NON7Y%lMHzPMer6b8 z=%ELYM!E%55E#0@y546!ao_h^ zKlh|tx|`1w7yd7T&j-aJSN)Cx4yzB847<3J$QQ2$0D+*-5v(E^G_~Z>}D`suTQ?0Me{wE9IXMRe?2dJ#NzZIaw=lwT@lZ6e71^ZgR*N-8UF`+{GrvCH8 z?iBfiop@}wb-A`wCOK40b{z749zY|afrS|rj*Oa-&9=`k{td^TqC10nzT^{&F=_=u z&lsa3z(_r`{n4S;pxXVu@kTH4R2;|Ri<28$-k>L6FAT@i5+^~M%zr19=1+T!R{H zK&J#T){HaLL}ntHr;C~(hrRey?9~^-nO3<4iL9iwh6_3xNJ=K({&+Hss$~A>JeXTn z^KW0&{=g;P0Jxut5qUt@3QUa!DcDeD8M9XH)B)O`Q06gKXGJ5~6bj%Y<3pq2GP&p) z(7+gQm32knlU0z~eGN`E55HFp8`s(7z;mWC7r*hp_ zz#=n(6d5%bht(zwD-0i_2<}vXy^~9ER7qmcJvumN#qrW~d{I7THT79&$Sz_VY77ez z%ymXm{P`w2ji=-`u0SQLGAC`j6h0Lxf&@c%>t!i_ttVGwrxy{bp=WuF|aeZk8WrFpMvadcqhLD(-fU!~0QBy_(B3RRjJ}6#{iTLt1OjZB+4N4Uo4~b@d z3rt{d)c}bDC15=;z!pG>)82L;+CgoDo`0x9sh2?9(?b!g%k?=G3IcG+j7LYiwJD2W zseZi1Wn~1CsGOFV@JBf9#s2cY7hx3N;bi1p=sHMHpVXpu%X#l@Ip%rTxC12v~xglF3Gr(dYd4gOBWs zcIT&lfO=vVL(|LNRiX^ku||KtO*Dh6p~Q*|G5(GCcZt#dHJ}PZ7;ul*{-rU_Nnmm# zDfFg%&$NAG@rwS|&4~={^4j~9MD?&L#<`Tf3iHEeC_Y@`qbl#hed=RRbU&0#xl?M^Of`Inx<_K>JA|xa4Q#G&RI^a>Z9tWV}aCqb$1=(WgK9 z*PRkRcA|wPl{!XU9YWdtJU`8QyUuow*#3IBy(Rx-BZVxgZ-!E`Q!`|#QKeNLdf$F? z=CIkly2;_O*{S%on7>DWmKwJX5!}`W4uZ+%RoG$bq4QP7r}mlK@iT_}z5BiY?`T15 zE;IAb*e@6+XF9b)8@H$;5(x`bklA5Hcg5M1QVh9rxDT$Zi4rv5pwxbukdsdkPk<>4 zD0wPn?N%guJ=;Y)wBWNwBb&U#!sMEFZ^JNonDM!InOm9crH^lT&W%R);|~zZd>{{< z%&`DT%L3cm8@6^$%THTfMzc0dks8|epBm@ZMPxY~_+JHW*}7%x*9fISb8>UXcy;&E zjM<8r_DEFMrP*8e=x{SXY8rDE{edJ}^;@aE`8MYhaR?0r1yW0zVGa)Cjb!Yq6DH?~ zpbgTYuf>DAW%}_g;MJT|235H~j}FEV5To-JOj(bGfbCaM<*qll5^^G5?mmMA!OOpq zQ3H{;v9-PJj=ieul52>X@t!Ak9P&-@`y`JlQ=?gK8d*B&+@V2PePRQoyqal2IwOE_ zQ3xD*K?RqIBY7Ror-?FJK$K8oV_=aNPD3~nhQdcqd^cZEEzd_Qz>YF!!o^be(NZ!h zz)6G=(V?&?o7V>i>@B*oe7~dSH$yuDPuNcpLmH9uzG@oN!GVW|POF_d5gr9)bmZ-F3&uc&~MO;_N8b6Ky84avTeI8P}Z2FhG$uz7gT>*jHFaFzqhdM~UA^$Y%X8xV;GtC#c(p(-?qQ(O#=hK<6zWVsi zxVi6W<4kkA#-(asxliD=g;>f6o(hC2fEh%E7evmGCzJIv1MBk#8HT?;oVmSF^#(NC zlbI4ANzjITOtLhIEW=?HcCMsTbXS~N=XSx+p3|F9v0c>rUx^p=m3bG3Oo`bJ#P%!{ zT}al9uNoQp zLM;yTOy!icJeWMk?4hTZ>zkI2v~EwX*4CX7a3HX*Lq@A0&7+K9-6efB>0ozzC^#LL z8b~8W@L^Pp(Syb`YWokEUL*m59|x=r5H}wGHQs#r7fS%@wDaIi@QDPl@_CRP%j#aR zC%(siBO%0RS~H3=i+Bk;lH6gbMelgs>&DmFbGhg^?m?Mhb?YdH1}*cub_8oXesx}% zF^#1eCMJGxje&p1o08}j5mR=_!+ItI?1W6T36y=ym~u3Fv8Xo$YZd$UWT`ocEeU)p zyCJ`*z$!9~)II1?j)d#An95kMu+J$spnHy)EJf!h3`sid06ZNmfCmT~+JT z<6=@eh2fy<@rcv2ccQU2laDC;VO#i2GJ~u=oZsP z6Px>_^2wR#N$}xo?{1^la`$qoy#U}JF%Q{0g7>r0ZIpU@ zKi`se^*KbkAs}J#g|Gr?jOAA{Kt-Oww~)$Tl^@mGr{2-#3Cra&`2C|AeoG>CFhEY$ zc_=f^D>Nu6AaLqiZeL=yn_?L8A+%~z;*+FZVVs`=ni zaZ?c5#-7EYfmDKm3QboJ4!7Xi|z$~l0kkebPg-b=ZSkot}^Bsa0U}1)Z ztYtAs@R3_)RwqNTG97O)&&X)JSX|A_YEeGX{OdBBJP@;C`=hrOCS0!|wSj9hhTPEj z6^s-Wv6Z;R1fWVz!VBpEe)y#M7iO)O-khR1I+n^HpgAE(}sa-1q^b-FJda;@S%@)7V zexl=0mu{gJRgDqV(WKx}JW`7=zJ_=$_neH1Wu5{O!v0Smmp0`3IVzNd^)s zofnje%BC}tWoGdF$qB4x5#dDnER;4u|5hvU_;_S*;o-;C%arSuul*Ffu2d*oIm|f) zwUhX`)?1AIe?Wh<**zS6JzF~0D^m7MLaEFrJh{n?4D~x75~{1>aY)AuB>OFWi#)}< zK%GC=80Gh;6Iy4@N$W)XG84%^fvQdoq=ZUBx!;g2@5e*FaPt_enY0d?1{dCRdk%SA zo%-t7W2@hNw^e0njl(G}0euZ*E^+Qdc+e~9g*R7k+sFyg8aZXXiLLu-`qdz+?vAdt z>-%3heFdk)w1v>?`bdtmo$xXPUmw5VB$oCUHKt*%9O_ z!>xV1Ii@=51Oj9mB)XYhDT1#LLtVeDeCiH{)MD7j4H&*nNU`QJ24*p>B? z6JBQtr9vr(0q$|rHfs1(9&qKF@RJWKZv}!?)ckTbHa_KX|VmUy>EB2eEhaskUsbYR~s)oH4fyY(sOjJ7x z^LpmyOtDsvCwOpr0zDuvIkODqD#Dn}U%UVX*^GB;t~W;-<@yNuwHO`k_xVF@eNieI zo>x&ZEr<09T-P7_mcZhTX-IQyh3tv+rhJYVRHWE=E=@!K1X$_*ET(qX9 zby+v6a1+-y5pY>!Y6V17?c5@F>Izeo7fM@lvC`=6lxx7+v*i-TF#wb%-e zCn=OkWs6@p$p+VZyIcQOr(W!fY_jf6M4a9Po8eslp49U`* zZg(Dg(DGevervjciEr>7vZZiuBv*(UCMu(9gR0K4M^RZ0nml?YO|E8>fwPX9hN)lZ z{n>e@!2uYOl*XR>?l4+6^6#{2&pciXshobcX4n^5 zXlf5|8R%_HR#SE)VZfn(1$|iUzwTY~sM2k*IXtes5zsnQ_u&fr^S%c7Cd!`+yjUly zTyCCZ5AYU2(6UJpVOnFp>BnQ8hbwE4*pAwvk+@pElRJT4N16(mzL|{pVeF}cSyhn^ zG&4r|6g3QK0dwgZuP$L`+a>D{*_pRP(_1R zT+B@MY=2ak4dwanYQpd4VXRwrd_aZ5X)rc;kbD>Rj_!I3=^QZM(29EY!4PpRX#d)KmF+L^19YyqVG|TTTtnz`rkS*>okKC<;1ei zAK-{`k^;av#qXg7G@H;l)cEBa_c=V;EAk2tC(@wtYA>+o$CgI2t{4iv1pwtcW?Tt6 zpdX6CZpT-f$P#5a%us{mv`7oh8$CswfNmUdj_+-}jmSo{@excl%%87BH|V%K6gj#X zEvMoq;K-m4IYn9-4^v24v`3CV5V3q1Wms0TRp2YMtW_5lQBgVo%{@J$PfNSH-}nBh z{mlL5Ci2YB)AMitOPkJ(cjc=imk-hfRWDirC=R(Nkh4m~ysv zkWO*18+~!UyO8kx5_tD2U#5TC{f3KT%jRW>-}Upo(NpnNCMA*M=BUHB5_&*6K-tV= zrx3RG@Y~AokI~cWw}<0yz9~a0Ig@cK`K=u!yLDPO`)4f&a-$hq+;b7bob~PaqTgrb z_xz&JGZJ&{9?Sxer!kHlh{*fl9C3E$+%E8Nfm-ioVi3|9h!av_GRC>kWlBRE)_6wx z7YRB)pnjXn+xT1g%V1}*N*kN3J{&D{9g|bh5Ao7bI<$5o=>l{u~Z6%OPTUq z2T7!Y<~(J)39~K zcw2~`oOvKm)~^JfVHXrAUqMvh6-=I{++^P)Fw=g0^wl7ky4VhG zq~%!pcy0Qji+z^K1YsRI*D%6v{87)yK$WqEfz`ho>FIGjv-|Ez>-m??Et6MG8KlC+nXY=&Vp2~B_wc+?t)hx^1>Be^`!H)GGHjrriI;#}{C%!yVC_wa;0KY+WERrXi>)_{25-Ynl7{=k-tF$;APEdUrU1LyMF@!@;OCT zkh^m(Zl8a&*E`6>{8aqy_r@bOZ0%Il`vrVXs_-drtLBFocIdBzFg#wbxk$rHsxRW5 z$4Jsv6m)+ut$2Q0CQcZ_dC*Hl**qp*)2vO%uWi@zkUMb9Iv zDV~bIQ9Sv5)56iZw|{et?-GC_4U<@v&~7r=WLq705Ya#35GoPt34M!OQrfcVyJSys zOy7u=*|9Iz2O*to)AOABYQOah2@U|yn64QvWN+dgq>}-9{6XpnhydAHo{}(5p90!fejyxBcbCM%9NiE6K7!vS*s3sxz>FCb8j{$WZH41nfA<@X82t2I z+oF%*VaL7`!=A-B45td{Ax@g3uB(QOTSA`@*;8>}OdOBZ);SxnZ<#&caR=vG3i7qz z?Z5rdGcK=z1~ExQwJSm)<3CIfGZwEC`tb&YHa}ix38NY4$p!NEoYIe{;Qq5&(VWYD zH-Y}y;r5qjM?uT9%X~G3`10{U_t^G zOAD4io~p-S$NrNd%7{Dlc_$yrg@N#>d;bDYKF#VoM*FnXJXMboSay<*+Pria0{ix5 z4YI`yK!2aPE2JSU06QCUiDHNyl0q#mpJQ+Cyf)7;wV8+X(JNEae@F12I|#C%yg$TN zOuekJcXx7W%ziOzy%TxNWT%l8DPO{o?r!q>lKu?zU*AN4`Z0-sTsdWB5=M&I6;L;B z+amm+kb0*Fu_~3@hw^AwpcmO-9vNp;#KwnUXh@tw>+Os9|Bi+;RN+brzmPiREqU=w zWBHk%SL4*?{lA&SO&{NjtHA#I=e7@CJ}y3AwZ^K(z-aM!Y9oT_b=U*RB0zI``iYVe znz4Hv?9&J5A=oHLTyXh_VlpxQQkYiqqDXjeUFkWmG(TmAnc&+m;jy;s1&eW_MJGmrns| z_No&2&GvbKZ4Mp<_u(6hwZ}+xByxMocTg*99(r;O^|E6&t8o0*8L<@E7%8{fvEXzY z4ORv~bj513d7}ZMVgTav$tRzShys$%k zRO9v266ajB<^h+Ga;QTi}zD1|W*_-&iC`nfv zlbBe>G+2NcKI)~WY6)ckoB43f7aJiSfp$U6aaBb0_W-WAUd+g26Aly@ttLQ>w8p^_ z%Qjrd=S;VoiSG$oet&oQWcsJ2L5dD_R`^I$>dV{aCc=}62r3VMXgH{cU^xxI_d1^1 z|J^JnNm&AxR6L+y*lhr;rXy>ZB%dHwhr0N9;VBU+s#?~wtK#~4&~HU>nRncD#kZT; z@PD!ZmB%a#w>EaytqxFkQu8hFE%6pZaj39>*9AgurQJW9+Oic+&}WASvcRy`leZB! zJbKU?iY&kU8SCz7lr>R>bd|Yb_k_TD-SH`l32@ni_YU|pcKC2c;d51gcX*g=u(~QX zd7!6G8+8q5Ng}f3L=H!JPknez->v&ez(}}5pxw)xFB6a+2Qw7y{jZJXEG5-QuWJ^5 zVKwPHX{2^OM@66SKB2h`>ok5n zZ`j?~-7Y|;p*`+=shv`+tDDkCUA5^afE^2b{T(cFXc1GeboP7wF;41@xrp?%$LH@4 zWZ$O*6TcWfE&of1$@U#-Q@t2S#bgP<{_357xai~=6so&LkIY$gOMe+bw zGGA`ZrvkRIh(OzuxJr)X)6XW{w_ow9t7y$r$+_0Q+RJG+!NtMx!G=_N8Xc|v)kS3O@m zKs-|zTYVt_O5sO|-*@FttdKC`FJHb~=WqrcB`wYs)z|Lhh35ig4=_?l#)vTbyFUzy zH2Zw=ytpk9&IZU5>v+})wU+*;Q_(gs&>MRsTz%6OPkoYp5;jga+VKjxqDQd zZ2zOMe6!XX>38@0g^Skk_8OexNdT{Y(2N!@5%W#v%5!X ziJFDV?1RWRYPiWVJ-iNkYsIzeiA5v7vv6_pTwR#wHqJ2PAaDQ(lT+95RwGCbPGE`NRDcgosr;vs`@ zo}Vk~*=w*E1VXZxFyLf#vvlev-0_^zg=w!CH~DV~aYA|Wqx*_4(7Rp9(eUbP{&?%m ze!mWmnXCKXJf8EDjobO1%f1OWfQR=dfz6X{9qw;Nlk~5~1FXX`zsrnnVV?FXaSBU5 zgCp~2$$veS=w-8}g#PIIsy5X~ih!7Lg=mE2;1Tvh!}F-|U}54#vz43nYU`1hhy(}8 z=yW_}Lo2@2K~@oZBKOiZJgKG3Ltnw{@BD);u8*?BFaN#c2FK{(xc|DLyhUB17>g(R zO-4XlO}smBOt$?+>Z6f5Kd`Rt9{2llv)ldHDHZ^< zmdTf*^=|I)x2?2d$Gi>3aYQ9WRqnG6;zXO6oP2UiB8;J^x|nTK8;NY15Tt!A2mFel zQVs@EFHSQL4vM~STe=Rl*U)&a*Q`7-ju$fX*9s^O`mtYN7!DC(8B2(DzI;tYxI!Ul zk?-QG%i*{wiP30vh7%H3O(lQS`Gc^{P=S&o_S>hwNcKt%0wRVb^pY48{y_>+?>su0 zB(xO>aEBYhF7qNcAKJ*H6}uiDMyma~>g&5dd?dc1{Bgv?+dz)omYw;Lye{fhkL5u- zRo?7PEXAbXpT7&KM#AsjpWKhj(~yEfq4!<1JH+4-c8yQ_2BKvBo`xEg{2AHGU-dGz z-Z$|xQwI;K@}UVHy<$O&HzU9vR0bWnrEAWaG#BTUIt9e2R_gq#N}7vekQ(FIcfM@Y z)NuVfb98QgnUi_FFb?Ze_D2&P2Bs4NSn7eJcCb`}`QJ-JCBDH%zHV#Z*yW6t&g#x7%&Ezisg1yYN=Y~q;HLk zccoqLl6~gS|6|SVH7(dRg`>Dbqh?iuE*+*p0mQ9Eazikw&s+r|vC~MlIR=BD*C^(d=TBxM-NhHXsR*Ks+>Nes=PMZ^%^hU93R+vDeLd$;jpVj+2YbN?P zl!KXLy|)dE%J*&?Y;WHM^-#<2OR4_pefXIZrmg@nG4KgfhrRES9--==PR#4!>|ojV z`eeOLxiWXX(b=soG_d6mb)hh8RBO!fak`4pc+)8B0lTcvKm^|$Tc*r53{0bG zN_gyCXk*{ZQ+W2F#2TG5~zp&Pl3 z=Mtnbj%!J;Q&`XHzf*ErPtaeG&8h8e5;v@qzN>(8%Kw3YmN;2;RC&eGgRkA~=27$D zSV}2nj1LU*v|e@B(U`#KQ$2^BzIAu=N0JVN_+urja_3Q#C=zgr^XbM~Snk#j`_O3* zw)9mT=4JmJU~VQz3uQGx`e6y?;mWb|B+Fghj7`ZgAHOaG8gbX)y>!)KWtg3+c0cr9_-@=kO&EaBNGy`2lfn@2Lf98AL%uA67&$G4=Lj>7YuRM$XV!i8;Op zYX-`W_a$Vi+DzcbJ2T-Yrzgv>N2jz&^F)^=uYie~2){)cH&xyTx?bgks35i4 z5ad~tCQ+cs#Q&hu`4NVHvxv>GVh1MMH?TywPBI~*>&y2Ja)n86-h^io$8vmfBuqJ8gUv#$AjzE^Qs2}#B&(j=DV!LAI2>CrBe z_N$Bf64-RoNp;fU zebBmf??alxo0rXZN!9qEDm*a+fiCLU!D6|%u?ecPP&Q=940x z&4I)0?BB!N6$0cOzpl!vQz2|>F$V!xBK4$u@9g9GYXTqyxryVAA*$-2#&BLv03HwW z45Xk>RTQ^QRLn>OU>Y62!kMf~p#8#_`UY=2;2-rv;~$TL4_5#6`7$+c`A*E|H6MjWK9t@x}4Fby*zl#Q~`Lb&{?OiL?-|=adCp^u*F&nEakK?IM|=* zH4E|yp27-2BFQBFTd8U&6>=dQorV^rB+n6-ed<-pnUI7kmOEe7WRKY8CZ;hdeRacj z@hi-jIEXczm{p3!oKrlPPG2fta&%$g@cChe^0C_QvKPmn{L_EmaORt6>2A5cf=mlj;RGKcfMdoW5{43IHDwk;1 zzq}hU{eyAx?WcRX9J{XRiyhr7`(7m+tQbX)LX?=$>(9su%bY%GvaT+xB}b15xTE@wpwtW5d+C zVMH)76n4`R+mCrcVNf=8yu@HSE*tP$C>+xUrkRBs6)$;Q?x2cg?oV+1Ntb&=QI@Y^ zbS;C^^|diIqm)yDNfWh7NX0!$h`x%U67V_;RhGm4zKu1n>aE2G!aO=v;&Sg*8AjGe zQT|0Cc%Dp+p3FhL#pb6-=k%$co=P#*NrB}jiR;T7859b{#k+eh4Z0fTLJjHM7$=vz z20Idg>?wHY$^>=rT7KOM?js7jEjX95Y66~C@B#pt1k?kJXNAIOL<@r~V%g0!rqS?1 z!>J8Ix*v-Qmp=Pa_2f9(-);EzFB&_Vzu)FvS~~8khGV@3fa$3ap|tkW{vtL7;9yc7 z1ZJ7;GQ1!tTRYsfr<5A+^-Rg2r8;JjIZAEORJ+8GW{Gq|f~-SBl)6*`*)Rb=uDv|V z96FIkluVL3go*$JKR!a|dpPF|k=Z1O%2|NuF1m#w!8_9Hu^3Sbu9|tMIB5cHlrNcS z9HT&_i-r43h3^PZG`|~?V)Yv5nWC7=aMtIUf}u$;(m|g^jIj|BKc9*dmj$c9MRB^$Xeo7u z5;#8wH5FKydJIq#Jq+kCH6lzT6*mF*$I*Z+C2{);hfD9o?EDjQ`z@ecDz6b4g!uTT z5!Af;`5D%%s=qdVI(4M&pE`Sc&9f;M8eA4G%*q~$cC18ZT)Xj-@}e2ATcoRYjvvbe zd1l&w>~UhV1Tk@z*o1`B;JO*4x)O^r7jjsn$+v5=m3ca&A>XXHOp3X``TK*~1b`!39XQ|u(2lxlN$7^vd&b<3*ZJNyULStp(g+j+c9}$FgV02E2>NpDd zl4aFtxCEwzO~JN{Z**=@pYj_PF(tJik^(pu9ppO-?HkbeatN9)MBK6SRqyK(%X=(6 zRiwkeUBuKM?iJF(tjAC^#I|xS5CtZoZC+&(ERMtkR2MD5s9sUlbnAv)jp=wa*h{HQuMbEJ$ZFV_X1& zD$N8?m=iDu%L={+$CDr{OJpr|d#7%lbw82qxETgFclbDV%g8}qRw3w%_n9rH2v-RR zNZJEJ_V3m4QUe+H$DySKEVt~y#exV1N&uBTkWp$ZHDl5^V-zH5m1s$U2+8OMI;P}( zmH67^kB4Mz_)KOa(Ld>46Uf+oo&Ch9Qzg!wG)&%CcfwQxlA?k~B#VywL+Y}dfFV~z z4q&9Vs5sSo8aW2^|1vWV~TBCJI=ocY5IRjEa=rnj^b zoRJacVFMv(pLiu%qCl9BZ4^Cj|9K$27aH3{faJyDD5zhR{4n5P<{r+>XiM_z7$?u5 zIoix`vI36x*wm)Kj;vM9e4{=anMN_y*f8eVAscgtAlE_S{KG;?tfD|^XuVMcvXZz| zebAY!Yx_p|DV$w)ev&-T@yxnHPJ{>$g$CVU43bOF$3-^bKBTKS>axM6ct0T1{!W)2 zTTb}QUgH9^xRC!*kb>jypRz=K%y^PuOmkz*N{}+Aj6WJ~pt>wJwL-Cgj9Yf2ITo0J zW?vf;5Ha@`$>x*{7eX*DFMHe;0X8`)PzwO|uMnq|qQQZK$LV8r_AX!LO(bh_l2{kY zl8e-Nbjl*YFKD2&y`9kyZ0vJhO20Q41# zMOqYb5H+UWm9m@`nlb|3V7RDf^JnsjmYXL3m+j=9GAH0` z+QfK;)wr1ks9ttKcFs*J_Fmwoot<~AOi!L6GM)9>u662j>b;C-omN-J0=YhZ$l$!L zZebF&>tdUu_dX*K7eqxZrMUq51pg7lBoYS9XplAKEu`b+fw^wS%`_GW*7pGh3azK+ zv>Z0CFFL=Rq`+U+;&sN@=gJ!mZGg#~>(p@@9~C$HxJjCQRPE#m7G@lyNy)fv5egL^ zd|EZ_cLnIIZP63w6*G*0t#)9v%xybZKTpYbH@80?*Gvy5+51#I3+QVPKqk*1Y87xIQkjDvN1B5x^+Iwr=xyF)Z7oJLWneJ^Zq)tc^`ACx1lxdxW%=AT1&) z&6rcJbfY};(aR_;vyJ6W%baTF59)(?U7yHP^N z#gU6%Eid;FWZ2Yo>$%zxuA5RLkTIwU_PdHIhPQ`3*@7gaV?u@u7JgUCcz( z7{7BFr9{ZJyT*o9OoyXi5UVPR5-l@$$!T3yT_nj6r*n$abh;uo^m&AHgp=7nwH+x`O!_rS^;;=y% z02~3uL!#r-5zH%Uf~eN(({WUuWtQoem8D5`Kfc$?Jh``L+x(*TFT`?`Ul_16(ak~f z4(HL?e9J9$tmYLI7wgIu0;0_Wn9dou9j=4|#erL_plPpNZhD%0YSX2eX^B4ZGAjQo zbO7)xR#vbv6QDOqzOg#<>%D#hL6RM_-Rqjyhk-VDQL+`@5%v&4;$2zugGr#sTS#)4M7;OC`E6S|R%N4Te6TIo~28Aa>!a}4ao3LNgEr%)O+aSc((|3+|*O2!T6GNF&cBOCz z(V86$j+KR;FE$v}XS~J+#%V&up=_Gyh{MU#-jP~FnM^0^Y)Z$QOvC#v_N6&rN6Mig z>LA#zQzxkz!DkgL{Tr0h?14KYYcg8Z8dYUZvU+N?dev!I626AH{9xG!%t>T`1?kBR zYUINf-7EL@Fj_iuQ9S^NM4|{f9`x1tX)n~R z1l%VX=jPK}GcxD3%T~j_e7jC8d?(3L`#nZ8!;yq3S)|?GG}x$h412;Pj1hQ_4wzyXvONjPd_UUyU!lxEp*v1w zgR&-ngZdf*EC4pfHP~Og#bGwI=luO1S@g!V<%4;&8e%5+P2+Lss%)u@CbI*70yUoR zIwll$ijGz(0IF)#D%ErlYRI(BVSSEefV+X-&12MoZpQBc9&+AZ_JyY>Y+9spWQiK; zkpK)=vd{4ck?wz_?=>ha@hzf&QFcjPPaqO6?xA{sQRfa%QBJ1;d zzyC-)TJ_k{b{yB2rk;+jgTf!;-%c@LT3v{I>dw;!vhA2CDQJ0NGZn&0doat6w>8DL z!g`E%Fi*zTRNt;t-Z+@@^!ifh1zoJ7HGAH#>Tdkp{c2C#VEEV{{THWdsFZA&^ZR4~ zHGm2_YTrfJQlWSnrPfo@rm$Xp`uK0_$?+Qhow6~vs0tF(5ETF0c&u22^9N=w)_X;~ zvyE2gUx`Yy-ju(;v9B~ma}C1em@HFNF94^_h~GZ9QlYvL5xMTnO%^Pe$2)}R6rfLH z){X+iBxIy>jv5(86Wu&BLV3dLW`eU z7v+Up!@K`coc=aUys^qSc8=Bv0e~0-Ly#t#jE=7U5*f|t>76%=hkm(F{-y-07cwaM zd6ublq+yEjGQ zQG8{%qm1TKJ@&B^CkXqC$R;gWOP#gk!LF~{ZvXy^r5R}Od#nmMh!l8m?v;q>JV`P7 zb+@^d*u8ks`S``*PX}p!lf&nCc*FaO$OsVY=k;x_->o8C^9I__#K&erNb=K&Y$|tl zYC~9}vg?+4XFitbX)= ze8QM@$LuFr-v3yDpd!GmA3~=s$~r#$l-;%_*B&rYfdFiDd`DoWF*C5W5g5kY>?W^H zT+(y)(K)bVt$FPDz(cdwnVXKud;aA)L4MDkmz`iR1<=R}bbUqw#<>)>yWKzCGpzS7 zn8t@80p)um;!uJa-Ne6YhZ7Y}F`aI6#uSi!|CZHGx~>vNY?Jg=5Yt%A*u!-hDmn#42FBz1gXc%xP>6c^ zA!`{v?k)e0W&+uf+{6c{a>VJQgBii-U=&e*G-;R3==Qw@m~f~2m1E{VG2_8Qf#L!9&;EKwJrxjS!?~GWhT=+E3TYlPmY^Qv_ z-Q4&$C)~dwBzh2TT7fmVCHk5QvzhRpJVp_9#qF9@=a){R9%aha$;!)<+8)05t(oKc zV9^$*h8}+F`-hdR%(t!W9*GKe)rxtAfqGzM2&^d0h7P{?N zr7w7x5*v#xlsVNt7?y}^eHfe+rmesmiKnhiF#X5oifgF5&Ff_I_sJ0w#z24)Nl|J$y{qM6Jv#I_#yoM?)SOr>$->NDP z0AO#(h>NJF50p0-X>G_k`+1@wi|~>ToOSU3q_o692Qt(W3~$TZVX7O z$@(Q8!t!0Ek~5@~WU5HZ@4TOqrZKX^^YZp~CNa@H9+NAmhl+b|S_`Pr=y7}F^wYn2 zlcUl{L>$vT+({*-naWEEw|ZPS8SZ`lKkZ#WPGAda@+@8nUHq zAtP%d*~v0vDI%p(%FsxJvG4mj4M~QwCBu*yOvXrz4CbXr*ZVy0m-p-Y;XNPDIoJQX zw{u_Tocn*S-~Ze{?-MZNIDblRbx!5H!WFc`&*iSoZc{=7(>{()FcY(!cApeZN$WYX zjLY))J*>Sa(ad(;-rI;(u2iI7`m(QpM=OtR;Oz7MMQZB3Rgpl{+(`jr@?3EV8RL{c zaIjy>FsJM;^@ffazh^v6vyFSUdxLK-lpv2z_2#eVL#C#_`e>N0KHmJ9vNe+|&XC#u zs@v2WYvf{e+;8i-WqHq#_IiUTs8sm=M&yF$%~s)knYX=z)>&<+4OivyQhLH`Pmlt& zg0&vwXMj`pv;i*wg^}S%Cf8Ar`0azIJm*l*XrJ+!(gT7ZHIo!TN&x$e?LHJ4 zq_rqt>X(oJvR&6YR!o1*(Ag$yGbgwL2EEORL&GY3%Ys<`meo=WZ1+HN&f^a1(w-K(_}-dAkSO&Dpi_Le z|I~s@2pP6x^&Je%*bh`jS>>@@5D|m6HZdl5c_VSq7ZE|Ns_NArD`H&o7e1^nJZVVl`rJ^U5oRcN@A7HZLw}wU~IC z)meS)2e#>~mc^wbX|mbVAO~7zm=`fGz#hWQw&<*f zmu(S)oc=LSxDW%JKt^*Ij*R1kEDXrX`%x~{pElyMl|?^fECcKHlhRH^I`o0~_SGSc zgLdu@dH#rdVUm2LJ5}XHM#M7=gMxjqJ-fx-+7~GL33P(_8*ku~t*ELZ(LwksEdTY+ zB-Q?FY4pWOCnO`3vBDrtKw7Wabm{e6omNo#a^KLTJ20(7ewLQJy;V(S^o}=b3gv=% zIPU^kkMYcZl`v>+Z>fMzj zreH3{D_u&dsxn@I=|QwtUC|PSxtFn$7fBQBV(bhYPZ%`H>p{uJ|l%r*u>~)y6s~3gB@% z&Fz+V6s}maTsGcTB4x+RcZypyiz~z;RzBHd) zJ%nc!B=R=$L57KCxSIRzve^OGcE~;TqSk6drK~*x^wupkk1%uM%QCK<7*BSP$-B2m zp_rHNq&-P<*0z~nCaVzZ`SgvRg{eP_vR*#*;-~rMqC%Fp5Mlug zTKVxn$U@MOIp2_<6x!#2qzt%f&O4w80x3Tw#Wmwqsybbt5Z`hdc-ehbnP%CTH9Ps8vaz|HPP5gA$ zJv|tACeNv=A|lDNXekF!I=_TxOuyTi;cbm7125RVBdM;ZKN<_ZmsmI<0%%^`9DfzB zsS@#H^!tx|!?6pqb%qXxosxv)SK?NWHMKXzC&HHo1QmfdJcdYX`r9YJ;Y><3bKM;# zo|Hg34*;*Pm``9Ylg#D?m~SEdtYtzX@mw(2dmE*k4-bVZva9Mv^Bm72d?s7;gO_>9 zn_i)36XSaatw_pZNxEieZzVZz8-LKDETpTJGmDI^e7P-f2gAf}8oSIVDN%N+Vb#Mz zY@f5!dWJc1rRl-9C>yn+kg=lcjb%NWY?-ZwM1$*n)*L=7uF8E&Mx4fzFxL=wIJgJ^ z0zjs6rzC(6{Zf<7Bl!UvLkg6g>2jKbw ze-8HrKMyMYNiy)4OvFhc8 ziBd@;ifE|3FI2IUJYW9ecIeR@&E|3jxQzRofD~2-{IowjjUwEELa;cZr;7VlhGQMg z1Pc@5+n~{CarLMsZ*%iTjn{5hlRg!YmrR4B2!jYF2e#Kt*K;eCOwX}Ke1vumz1e#u zv<~&?^7Oe+mMkIG6v*Gyeirn6PdgAye}CqlSum zJ09Fd$E6(tuGko6RT2znj-%cHgt@MDM$sca!6s}!bIqaG52xff3Q_TXl;iDMaYdz) z=*sez9O(u5u)Ixc%yE$~1Gd_X zwc6?*ok2}zAy32DZmH!x4rS5HVmcu)MM%X!)urlvCsni&MTl3oEs$Ju%Gy6E4$qVU zumCeBZ1mC_w&6?;Y{%Xg;jdClBB*}TUv740vI-fUbHCc;%(^u^^cD1L@yRZ%wF@dV z=0rrq{W{y*MV`k?54IRTt=fBr{t^q14+Gy08L7!&0%l1gdTYEKyUM@yXqkdXs-PTo z^qlIy4~H0qfm#18MVfHFqBA9`SXAdDtP@HZXo`#ZZD3c((Q*&+{cYl;4EN;Ozo`?B z&HQKV|G3(WfV9+q1RX$m^c^Vqr;j}>WpA+l{JXt7Y0v3S$bU_N{~yHvekLdkU($ph zUwjOZsDXNLDnY$0_P!lwIJ{5}nUM09{a$-8o1sa3uY!8XLp)eC_1(PHJcuV1xgXfs z{(t;0c^IUEXb~EDsb+Z>jSH@&zZ?PWrfpr=XROADKJna+NL$KWH+38tU!u(iZfsT% zmk`t3zht6}97lR){Hrg|{6xEql2f%hTdquR_roD|q?IrYG%XVCHagvNqgFOCo7|wi_A9th ztFamyeQSF96$Ufo|J-tc-f}ISu?@a`E~RDsMkLWZZ$P<)gSl Zsy9!7pWy1MCZ_EAHqtlKE75_+{0p}JgetNumLaneToPreferredLane(lane, get_opposite_direction)); -} - lane_change::TargetObjects NormalLaneChange::get_target_objects( const FilteredLanesObjects & filtered_objects, [[maybe_unused]] const lanelet::ConstLanelets & current_lanes) const From aa70067ab69e4c1ae8f9f5f017c535e792b89bd3 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Wed, 22 Jan 2025 16:25:25 +0900 Subject: [PATCH 281/334] feat(autoware_vehicle_cmd_gate)!: tier4-debug_msgs changed to autoware_internal_debug_msgs in autoware_vehicle_cmd_gate (#9856) Signed-off-by: vish0012 --- control/autoware_vehicle_cmd_gate/package.xml | 2 +- .../autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp | 6 +++--- .../autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp | 9 +++++---- 3 files changed, 9 insertions(+), 8 deletions(-) diff --git a/control/autoware_vehicle_cmd_gate/package.xml b/control/autoware_vehicle_cmd_gate/package.xml index 6eddf68595c5e..2fcc7d77e7ec2 100644 --- a/control/autoware_vehicle_cmd_gate/package.xml +++ b/control/autoware_vehicle_cmd_gate/package.xml @@ -19,6 +19,7 @@ autoware_component_interface_specs_universe autoware_component_interface_utils autoware_control_msgs + autoware_internal_debug_msgs autoware_motion_utils autoware_universe_utils autoware_vehicle_info_utils @@ -30,7 +31,6 @@ std_srvs tier4_api_utils tier4_control_msgs - tier4_debug_msgs tier4_external_api_msgs tier4_system_msgs tier4_vehicle_msgs diff --git a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp index b67b213b426dd..a4838ddcdc1f5 100644 --- a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp +++ b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp @@ -77,8 +77,8 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options) engage_pub_ = create_publisher("output/engage", durable_qos); pub_external_emergency_ = create_publisher("output/external_emergency", durable_qos); operation_mode_pub_ = create_publisher("output/operation_mode", durable_qos); - processing_time_pub_ = - this->create_publisher("~/debug/processing_time_ms", 1); + processing_time_pub_ = this->create_publisher( + "~/debug/processing_time_ms", 1); is_filter_activated_pub_ = create_publisher("~/is_filter_activated", durable_qos); @@ -520,7 +520,7 @@ void VehicleCmdGate::onTimer() } // ProcessingTime - tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg; processing_time_msg.stamp = get_clock()->now(); processing_time_msg.data = stop_watch.toc(); processing_time_pub_->publish(processing_time_msg); diff --git a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp index c44e96631998f..094f114abb0a5 100644 --- a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp +++ b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp @@ -32,6 +32,8 @@ #include #include #include +#include +#include #include #include #include @@ -41,8 +43,6 @@ #include #include #include -#include -#include #include #include #include @@ -62,6 +62,7 @@ using autoware_adapi_v1_msgs::msg::MrmState; using autoware_adapi_v1_msgs::msg::OperationModeState; using autoware_control_msgs::msg::Control; using autoware_control_msgs::msg::Longitudinal; +using autoware_internal_debug_msgs::msg::BoolStamped; using autoware_vehicle_cmd_gate::msg::IsFilterActivated; using autoware_vehicle_msgs::msg::GearCommand; using autoware_vehicle_msgs::msg::HazardLightsCommand; @@ -70,7 +71,6 @@ using autoware_vehicle_msgs::msg::TurnIndicatorsCommand; using geometry_msgs::msg::AccelWithCovarianceStamped; using std_srvs::srv::Trigger; using tier4_control_msgs::msg::GateMode; -using tier4_debug_msgs::msg::BoolStamped; using tier4_external_api_msgs::msg::Emergency; using tier4_external_api_msgs::msg::Heartbeat; using tier4_external_api_msgs::srv::SetEmergency; @@ -116,7 +116,8 @@ class VehicleCmdGate : public rclcpp::Node rclcpp::Publisher::SharedPtr filter_activated_marker_pub_; rclcpp::Publisher::SharedPtr filter_activated_marker_raw_pub_; rclcpp::Publisher::SharedPtr filter_activated_flag_pub_; - rclcpp::Publisher::SharedPtr processing_time_pub_; + rclcpp::Publisher::SharedPtr + processing_time_pub_; // Parameter callback OnSetParametersCallbackHandle::SharedPtr set_param_res_; rcl_interfaces::msg::SetParametersResult onParameter( From 4f3aad22903967813784a91f0ce54a7b9f38fc2d Mon Sep 17 00:00:00 2001 From: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Date: Wed, 22 Jan 2025 16:26:29 +0900 Subject: [PATCH 282/334] revert: revert "feat(autoware_ekf_localizer)!: porting from universe to core (#9978)" (#10004) This reverts commit 037c315fbee69bb5923ec10bb8e8e70f890725ea. Signed-off-by: Ryohsuke Mitsudome --- codecov.yaml | 1 + .../autoware_ekf_localizer/CHANGELOG.rst | 63 +++ .../autoware_ekf_localizer/CMakeLists.txt | 82 ++++ localization/autoware_ekf_localizer/README.md | 211 ++++++++ .../config/ekf_localizer.param.yaml | 50 ++ .../ekf_localizer/aged_object_queue.hpp | 71 +++ .../autoware/ekf_localizer/covariance.hpp | 28 ++ .../autoware/ekf_localizer/diagnostics.hpp | 49 ++ .../autoware/ekf_localizer/ekf_localizer.hpp | 199 ++++++++ .../autoware/ekf_localizer/ekf_module.hpp | 156 ++++++ .../ekf_localizer/hyper_parameters.hpp | 108 ++++ .../autoware/ekf_localizer/mahalanobis.hpp | 31 ++ .../autoware/ekf_localizer/matrix_types.hpp | 28 ++ .../autoware/ekf_localizer/measurement.hpp | 32 ++ .../autoware/ekf_localizer/numeric.hpp | 37 ++ .../autoware/ekf_localizer/state_index.hpp | 32 ++ .../ekf_localizer/state_transition.hpp | 31 ++ .../include/autoware/ekf_localizer/string.hpp | 34 ++ .../autoware/ekf_localizer/warning.hpp | 48 ++ .../ekf_localizer/warning_message.hpp | 33 ++ .../launch/ekf_localizer.launch.xml | 40 ++ .../media/calculation_delta_from_pitch.png | Bin 0 -> 56991 bytes .../media/delay_model_eq.png | Bin 0 -> 4906 bytes .../media/ekf_autoware_res.png | Bin 0 -> 69064 bytes .../media/ekf_delay_comp.png | Bin 0 -> 147442 bytes .../media/ekf_diagnostics.png | Bin 0 -> 145097 bytes .../media/ekf_diagnostics_callback_pose.png | Bin 0 -> 17825 bytes .../media/ekf_diagnostics_callback_twist.png | Bin 0 -> 17945 bytes .../media/ekf_dynamics.png | Bin 0 -> 5346 bytes .../media/ekf_flowchart.png | Bin 0 -> 146302 bytes .../media/ekf_smooth_update.png | Bin 0 -> 146470 bytes .../autoware_ekf_localizer/package.xml | 47 ++ .../schema/ekf_localizer.schema.json | 52 ++ .../schema/sub/diagnostics.sub_schema.json | 63 +++ .../schema/sub/misc.sub_schema.json | 23 + .../schema/sub/node.sub_schema.json | 44 ++ .../sub/pose_measurement.sub_schema.json | 38 ++ .../schema/sub/process_noise.sub_schema.json | 28 ++ ...imple_1d_filter_parameters.sub_schema.json | 28 ++ .../sub/twist_measurement.sub_schema.json | 28 ++ .../autoware_ekf_localizer/src/covariance.cpp | 56 +++ .../src/diagnostics.cpp | 226 +++++++++ .../src/ekf_localizer.cpp | 463 ++++++++++++++++++ .../autoware_ekf_localizer/src/ekf_module.cpp | 459 +++++++++++++++++ .../src/mahalanobis.cpp | 32 ++ .../src/measurement.cpp | 61 +++ .../src/state_transition.cpp | 102 ++++ .../src/warning_message.cpp | 60 +++ .../test/test_aged_object_queue.cpp | 108 ++++ .../test/test_covariance.cpp | 84 ++++ .../test/test_diagnostics.cpp | 213 ++++++++ .../test/test_ekf_localizer_launch.py | 170 +++++++ .../test/test_ekf_localizer_mahalanobis.py | 229 +++++++++ .../test/test_mahalanobis.cpp | 66 +++ .../test/test_measurement.cpp | 86 ++++ .../test/test_numeric.cpp | 54 ++ .../test/test_state_transition.cpp | 101 ++++ .../test/test_string.cpp | 31 ++ .../test/test_warning_message.cpp | 67 +++ .../README.md | 4 +- 60 files changed, 4385 insertions(+), 2 deletions(-) create mode 100644 localization/autoware_ekf_localizer/CHANGELOG.rst create mode 100644 localization/autoware_ekf_localizer/CMakeLists.txt create mode 100644 localization/autoware_ekf_localizer/README.md create mode 100644 localization/autoware_ekf_localizer/config/ekf_localizer.param.yaml create mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/aged_object_queue.hpp create mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/covariance.hpp create mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/diagnostics.hpp create mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_localizer.hpp create mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_module.hpp create mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/hyper_parameters.hpp create mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/mahalanobis.hpp create mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/matrix_types.hpp create mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/measurement.hpp create mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/numeric.hpp create mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/state_index.hpp create mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/state_transition.hpp create mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/string.hpp create mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/warning.hpp create mode 100644 localization/autoware_ekf_localizer/include/autoware/ekf_localizer/warning_message.hpp create mode 100644 localization/autoware_ekf_localizer/launch/ekf_localizer.launch.xml create mode 100644 localization/autoware_ekf_localizer/media/calculation_delta_from_pitch.png create mode 100644 localization/autoware_ekf_localizer/media/delay_model_eq.png create mode 100644 localization/autoware_ekf_localizer/media/ekf_autoware_res.png create mode 100644 localization/autoware_ekf_localizer/media/ekf_delay_comp.png create mode 100644 localization/autoware_ekf_localizer/media/ekf_diagnostics.png create mode 100644 localization/autoware_ekf_localizer/media/ekf_diagnostics_callback_pose.png create mode 100644 localization/autoware_ekf_localizer/media/ekf_diagnostics_callback_twist.png create mode 100644 localization/autoware_ekf_localizer/media/ekf_dynamics.png create mode 100644 localization/autoware_ekf_localizer/media/ekf_flowchart.png create mode 100644 localization/autoware_ekf_localizer/media/ekf_smooth_update.png create mode 100644 localization/autoware_ekf_localizer/package.xml create mode 100644 localization/autoware_ekf_localizer/schema/ekf_localizer.schema.json create mode 100644 localization/autoware_ekf_localizer/schema/sub/diagnostics.sub_schema.json create mode 100644 localization/autoware_ekf_localizer/schema/sub/misc.sub_schema.json create mode 100644 localization/autoware_ekf_localizer/schema/sub/node.sub_schema.json create mode 100644 localization/autoware_ekf_localizer/schema/sub/pose_measurement.sub_schema.json create mode 100644 localization/autoware_ekf_localizer/schema/sub/process_noise.sub_schema.json create mode 100644 localization/autoware_ekf_localizer/schema/sub/simple_1d_filter_parameters.sub_schema.json create mode 100644 localization/autoware_ekf_localizer/schema/sub/twist_measurement.sub_schema.json create mode 100644 localization/autoware_ekf_localizer/src/covariance.cpp create mode 100644 localization/autoware_ekf_localizer/src/diagnostics.cpp create mode 100644 localization/autoware_ekf_localizer/src/ekf_localizer.cpp create mode 100644 localization/autoware_ekf_localizer/src/ekf_module.cpp create mode 100644 localization/autoware_ekf_localizer/src/mahalanobis.cpp create mode 100644 localization/autoware_ekf_localizer/src/measurement.cpp create mode 100644 localization/autoware_ekf_localizer/src/state_transition.cpp create mode 100644 localization/autoware_ekf_localizer/src/warning_message.cpp create mode 100644 localization/autoware_ekf_localizer/test/test_aged_object_queue.cpp create mode 100644 localization/autoware_ekf_localizer/test/test_covariance.cpp create mode 100644 localization/autoware_ekf_localizer/test/test_diagnostics.cpp create mode 100644 localization/autoware_ekf_localizer/test/test_ekf_localizer_launch.py create mode 100644 localization/autoware_ekf_localizer/test/test_ekf_localizer_mahalanobis.py create mode 100644 localization/autoware_ekf_localizer/test/test_mahalanobis.cpp create mode 100644 localization/autoware_ekf_localizer/test/test_measurement.cpp create mode 100644 localization/autoware_ekf_localizer/test/test_numeric.cpp create mode 100644 localization/autoware_ekf_localizer/test/test_state_transition.cpp create mode 100644 localization/autoware_ekf_localizer/test/test_string.cpp create mode 100644 localization/autoware_ekf_localizer/test/test_warning_message.cpp diff --git a/codecov.yaml b/codecov.yaml index 46d6dd3b5f6b0..0a033171d0250 100644 --- a/codecov.yaml +++ b/codecov.yaml @@ -122,6 +122,7 @@ component_management: - component_id: localization-tier-iv-maintained-packages name: Localization TIER IV Maintained Packages paths: + - localization/autoware_ekf_localizer/** - localization/autoware_gyro_odometer/** - localization/autoware_localization_error_monitor/** - localization/autoware_localization_util/** diff --git a/localization/autoware_ekf_localizer/CHANGELOG.rst b/localization/autoware_ekf_localizer/CHANGELOG.rst new file mode 100644 index 0000000000000..b8e74c530e059 --- /dev/null +++ b/localization/autoware_ekf_localizer/CHANGELOG.rst @@ -0,0 +1,63 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_ekf_localizer +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - localization (`#9567 `_) +* fix(autoware_ekf_localizer): publish `processing_time_ms` (`#9443 `_) + Fixed to publish processing_time_ms +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_ekf_localizer): remove `timer_tf\_` (`#9244 `_) + Removed timer_tf\_ +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, SakodaShintaro, Yutaka Kondo + +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_ekf_localizer): remove `timer_tf\_` (`#9244 `_) + Removed timer_tf\_ +* Contributors: Esteve Fernandez, SakodaShintaro, Yutaka Kondo + +0.38.0 (2024-11-08) +------------------- +* unify package.xml version to 0.37.0 +* refactor(localization_util)!: prefix package and namespace with autoware (`#8922 `_) + add autoware prefix to localization_util +* refactor(ekf_localizer)!: prefix package and namespace with autoware (`#8888 `_) + * import lanelet2_map_preprocessor + * move headers to include/autoware/efk_localier + --------- +* Contributors: Masaki Baba, Yutaka Kondo + +0.26.0 (2024-04-03) +------------------- diff --git a/localization/autoware_ekf_localizer/CMakeLists.txt b/localization/autoware_ekf_localizer/CMakeLists.txt new file mode 100644 index 0000000000000..6ace0b413d7a6 --- /dev/null +++ b/localization/autoware_ekf_localizer/CMakeLists.txt @@ -0,0 +1,82 @@ +cmake_minimum_required(VERSION 3.14) +project(autoware_ekf_localizer) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +find_package(Eigen3 REQUIRED) + +include_directories( + SYSTEM + ${EIGEN3_INCLUDE_DIR} +) + +ament_auto_find_build_dependencies() + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/ekf_localizer.cpp + src/covariance.cpp + src/diagnostics.cpp + src/mahalanobis.cpp + src/measurement.cpp + src/state_transition.cpp + src/warning_message.cpp + src/ekf_module.cpp +) + +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "autoware::ekf_localizer::EKFLocalizer" + EXECUTABLE ${PROJECT_NAME}_node + EXECUTOR SingleThreadedExecutor +) + +target_link_libraries(${PROJECT_NAME} Eigen3::Eigen) + +function(add_testcase filepath) + get_filename_component(filename ${filepath} NAME) + string(REGEX REPLACE ".cpp" "" test_name ${filename}) + + ament_add_gtest(${test_name} ${filepath}) + target_link_libraries("${test_name}" ${PROJECT_NAME}) + ament_target_dependencies(${test_name} ${${PROJECT_NAME}_FOUND_BUILD_DEPENDS}) +endfunction() + +if(BUILD_TESTING) + add_launch_test( + test/test_ekf_localizer_launch.py + TIMEOUT "30" + ) + add_launch_test( + test/test_ekf_localizer_mahalanobis.py + TIMEOUT "30" + ) + find_package(ament_cmake_gtest REQUIRED) + + file(GLOB_RECURSE TEST_FILES test/*.cpp) + + foreach(filepath ${TEST_FILES}) + add_testcase(${filepath}) + endforeach() +endif() + + +# if(BUILD_TESTING) +# 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 +# src/kalman_filter/time_delay_kalman_filter.cpp +# ) +# target_include_directories(ekf_localizer-test +# PRIVATE +# include +# ) +# ament_target_dependencies(ekf_localizer-test geometry_msgs rclcpp tf2 tf2_ros) +# endif() + +ament_auto_package( + INSTALL_TO_SHARE + config + launch +) diff --git a/localization/autoware_ekf_localizer/README.md b/localization/autoware_ekf_localizer/README.md new file mode 100644 index 0000000000000..a46ea7181315f --- /dev/null +++ b/localization/autoware_ekf_localizer/README.md @@ -0,0 +1,211 @@ +# Overview + +The **Extend Kalman Filter Localizer** estimates robust and less noisy robot pose and twist by integrating the 2D vehicle dynamics model with input ego-pose and ego-twist messages. The algorithm is designed especially for fast-moving robots such as autonomous driving systems. + +## Flowchart + +The overall flowchart of the autoware_ekf_localizer is described below. + +

+ +

+ +## Features + +This package includes the following features: + +- **Time delay compensation** for input messages, which enables proper integration of input information with varying time delays. This is important especially for high-speed moving robots, such as autonomous driving vehicles. (see the following figure). +- **Automatic estimation of yaw bias** prevents modeling errors caused by sensor mounting angle errors, which can improve estimation accuracy. +- **Mahalanobis distance gate** enables probabilistic outlier detection to determine which inputs should be used or ignored. +- **Smooth update**, the Kalman Filter measurement update is typically performed when a measurement is obtained, but it can cause large changes in the estimated value, especially for low-frequency measurements. Since the algorithm can consider the measurement time, the measurement data can be divided into multiple pieces and integrated smoothly while maintaining consistency (see the following figure). +- **Calculation of vertical correction amount from pitch** mitigates localization instability on slopes. For example, when going uphill, it behaves as if it is buried in the ground (see the left side of the "Calculate delta from pitch" figure) because EKF only considers 3DoF(x,y,yaw). Therefore, EKF corrects the z-coordinate according to the formula (see the right side of the "Calculate delta from pitch" figure). + +

+ +

+ +

+ +

+ +

+ +

+ +## Node + +### Subscribed Topics + +| Name | Type | Description | +| -------------------------------- | ------------------------------------------------ | ---------------------------------------------------------------------------------------------------------------------------------------- | +| `measured_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Input pose source with the measurement covariance matrix. | +| `measured_twist_with_covariance` | `geometry_msgs::msg::TwistWithCovarianceStamped` | Input twist source with the measurement covariance matrix. | +| `initialpose` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Initial pose for EKF. The estimated pose is initialized with zeros at the start. It is initialized with this message whenever published. | + +### Published Topics + +| Name | Type | Description | +| --------------------------------- | --------------------------------------------------- | ----------------------------------------------------- | +| `ekf_odom` | `nav_msgs::msg::Odometry` | Estimated odometry. | +| `ekf_pose` | `geometry_msgs::msg::PoseStamped` | Estimated pose. | +| `ekf_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Estimated pose with covariance. | +| `ekf_biased_pose` | `geometry_msgs::msg::PoseStamped` | Estimated pose including the yaw bias | +| `ekf_biased_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Estimated pose with covariance including the yaw bias | +| `ekf_twist` | `geometry_msgs::msg::TwistStamped` | Estimated twist. | +| `ekf_twist_with_covariance` | `geometry_msgs::msg::TwistWithCovarianceStamped` | The estimated twist with covariance. | +| `diagnostics` | `diagnostics_msgs::msg::DiagnosticArray` | The diagnostic information. | +| `debug/processing_time_ms` | `autoware_internal_debug_msgs::msg::Float64Stamped` | The processing time [ms]. | + +### Published TF + +- base_link + TF from `map` coordinate to estimated pose. + +## Functions + +### Predict + +The current robot state is predicted from previously estimated data using a given prediction model. This calculation is called at a constant interval (`predict_frequency [Hz]`). The prediction equation is described at the end of this page. + +### Measurement Update + +Before the update, the Mahalanobis distance is calculated between the measured input and the predicted state, the measurement update is not performed for inputs where the Mahalanobis distance exceeds the given threshold. + +The predicted state is updated with the latest measured inputs, measured_pose, and measured_twist. The updates are performed with the same frequency as prediction, usually at a high frequency, in order to enable smooth state estimation. + +## Parameter description + +The parameters are set in `launch/ekf_localizer.launch` . + +### For Node + +{{ json_to_markdown("localization/autoware_ekf_localizer/schema/sub/node.sub_schema.json") }} + +### For pose measurement + +{{ json_to_markdown("localization/autoware_ekf_localizer/schema/sub/pose_measurement.sub_schema.json") }} + +### For twist measurement + +{{ json_to_markdown("localization/autoware_ekf_localizer/schema/sub/twist_measurement.sub_schema.json") }} + +### For process noise + +{{ json_to_markdown("localization/autoware_ekf_localizer/schema/sub/process_noise.sub_schema.json") }} + +note: process noise for positions x & y are calculated automatically from nonlinear dynamics. + +### Simple 1D Filter Parameters + +{{ json_to_markdown("localization/autoware_ekf_localizer/schema/sub/simple_1d_filter_parameters.sub_schema.json") }} + +### For diagnostics + +{{ json_to_markdown("localization/autoware_ekf_localizer/schema/sub/diagnostics.sub_schema.json") }} + +### Misc + +{{ json_to_markdown("localization/autoware_ekf_localizer/schema/sub/misc.sub_schema.json") }} + +## How to tune EKF parameters + +### 0. Preliminaries + +- Check header time in pose and twist message is set to sensor time appropriately, because time delay is calculated from this value. If it is difficult to set an appropriate time due to the timer synchronization problem, use `twist_additional_delay` and `pose_additional_delay` to correct the time. +- Check if the relation between measurement pose and twist is appropriate (whether the derivative of the pose has a similar value to twist). This discrepancy is caused mainly by unit error (such as confusing radian/degree) or bias noise, and it causes large estimation errors. + +### 1. Tune sensor parameters + +Set standard deviation for each sensor. The `pose_measure_uncertainty_time` is for the uncertainty of the header timestamp data. +You can also tune a number of steps for smoothing for each observed sensor data by tuning `*_smoothing_steps`. +Increasing the number will improve the smoothness of the estimation, but may have an adverse effect on the estimation performance. + +- `pose_measure_uncertainty_time` +- `pose_smoothing_steps` +- `twist_smoothing_steps` + +### 2. Tune process model parameters + +- `proc_stddev_vx_c` : set to maximum linear acceleration +- `proc_stddev_wz_c` : set to maximum angular acceleration +- `proc_stddev_yaw_c` : This parameter describes the correlation between the yaw and yaw rate. A large value means the change in yaw does not correlate to the estimated yaw rate. If this is set to 0, it means the change in estimated yaw is equal to yaw rate. Usually, this should be set to 0. +- `proc_stddev_yaw_bias_c` : This parameter is the standard deviation for the rate of change in yaw bias. In most cases, yaw bias is constant, so it can be very small, but must be non-zero. + +### 3. Tune gate parameters + +EKF performs gating using Mahalanobis distance before updating by observation. The gate size is determined by the `pose_gate_dist` parameter and the `twist_gate_dist`. If the Mahalanobis distance is larger than this value, the observation is ignored. + +This gating process is based on a statistical test using the chi-square distribution. As modeled, we assume that the Mahalanobis distance follows a chi-square distribution with 3 degrees of freedom for pose and 2 degrees of freedom for twist. + +Currently, the accuracy of covariance estimation itself is not very good, so it is recommended to set the significance level to a very small value to reduce rejection due to false positives. + +| Significance level | Threshold for 2 dof | Threshold for 3 dof | +| ------------------ | ------------------- | ------------------- | +| $10 ^ {-2}$ | 9.21 | 11.3 | +| $10 ^ {-3}$ | 13.8 | 16.3 | +| $10 ^ {-4}$ | 18.4 | 21.1 | +| $10 ^ {-5}$ | 23.0 | 25.9 | +| $10 ^ {-6}$ | 27.6 | 30.7 | +| $10 ^ {-7}$ | 32.2 | 35.4 | +| $10 ^ {-8}$ | 36.8 | 40.1 | +| $10 ^ {-9}$ | 41.4 | 44.8 | +| $10 ^ {-10}$ | 46.1 | 49.5 | + +## Kalman Filter Model + +### kinematics model in update function + + + +where, $\theta_k$ represents the vehicle's heading angle, including the mounting angle bias. +$b_k$ is a correction term for the yaw bias, and it is modeled so that $(\theta_k+b_k)$ becomes the heading angle of the base_link. +The pose_estimator is expected to publish the base_link in the map coordinate system. However, the yaw angle may be offset due to calibration errors. This model compensates this error and improves estimation accuracy. + +### time delay model + +The measurement time delay is handled by an augmented state [1] (See, Section 7.3 FIXED-LAG SMOOTHING). + + + +Note that, although the dimension gets larger since the analytical expansion can be applied based on the specific structures of the augmented states, the computational complexity does not significantly change. + +## Test Result with Autoware NDT + +

+ +

+ +## Diagnostics + +

+ +

+ +

+ +

+

+ +

+ +### The conditions that result in a WARN state + +- The node is not in the activate state. +- The initial pose is not set. +- The number of consecutive no measurement update via the Pose/Twist topic exceeds the `pose_no_update_count_threshold_warn`/`twist_no_update_count_threshold_warn`. +- The timestamp of the Pose/Twist topic is beyond the delay compensation range. +- The Pose/Twist topic is beyond the range of Mahalanobis distance for covariance estimation. +- The covariance ellipse is bigger than threshold `warn_ellipse_size` for long axis or `warn_ellipse_size_lateral_direction` for lateral_direction. + +### The conditions that result in an ERROR state + +- The number of consecutive no measurement update via the Pose/Twist topic exceeds the `pose_no_update_count_threshold_error`/`twist_no_update_count_threshold_error`. +- The covariance ellipse is bigger than threshold `error_ellipse_size` for long axis or `error_ellipse_size_lateral_direction` for lateral_direction. + +## Known issues + +- If multiple pose_estimators are used, the input to the EKF will include multiple yaw biases corresponding to each source. However, the current EKF assumes the existence of only one yaw bias. Therefore, yaw bias `b_k` in the current EKF state would not make any sense and cannot correctly handle these multiple yaw biases. Thus, future work includes introducing yaw bias for each sensor with yaw estimation. + +## reference + +[1] Anderson, B. D. O., & Moore, J. B. (1979). Optimal filtering. Englewood Cliffs, NJ: Prentice-Hall. diff --git a/localization/autoware_ekf_localizer/config/ekf_localizer.param.yaml b/localization/autoware_ekf_localizer/config/ekf_localizer.param.yaml new file mode 100644 index 0000000000000..e00d5e1c10ae2 --- /dev/null +++ b/localization/autoware_ekf_localizer/config/ekf_localizer.param.yaml @@ -0,0 +1,50 @@ +/**: + ros__parameters: + node: + show_debug_info: false + enable_yaw_bias_estimation: true + predict_frequency: 50.0 + tf_rate: 50.0 + extend_state_step: 50 + + pose_measurement: + # for Pose measurement + pose_additional_delay: 0.0 + pose_measure_uncertainty_time: 0.01 + pose_smoothing_steps: 5 + pose_gate_dist: 49.5 # corresponds to significance level = 10^-10 + + twist_measurement: + # for twist measurement + twist_additional_delay: 0.0 + twist_smoothing_steps: 2 + twist_gate_dist: 46.1 # corresponds to significance level = 10^-10 + + process_noise: + # for process model + proc_stddev_yaw_c: 0.005 + proc_stddev_vx_c: 10.0 + proc_stddev_wz_c: 5.0 + + simple_1d_filter_parameters: + #Simple1DFilter parameters + z_filter_proc_dev: 1.0 + roll_filter_proc_dev: 0.1 + pitch_filter_proc_dev: 0.1 + + diagnostics: + # for diagnostics + pose_no_update_count_threshold_warn: 50 + pose_no_update_count_threshold_error: 100 + twist_no_update_count_threshold_warn: 50 + twist_no_update_count_threshold_error: 100 + ellipse_scale: 3.0 + error_ellipse_size: 1.5 + warn_ellipse_size: 1.2 + error_ellipse_size_lateral_direction: 0.3 + warn_ellipse_size_lateral_direction: 0.25 + + misc: + # for velocity measurement limitation (Set 0.0 if you want to ignore) + threshold_observable_velocity_mps: 0.0 # [m/s] + pose_frame_id: "map" diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/aged_object_queue.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/aged_object_queue.hpp new file mode 100644 index 0000000000000..2b6f209c7121e --- /dev/null +++ b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/aged_object_queue.hpp @@ -0,0 +1,71 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__EKF_LOCALIZER__AGED_OBJECT_QUEUE_HPP_ +#define AUTOWARE__EKF_LOCALIZER__AGED_OBJECT_QUEUE_HPP_ + +#include +#include + +namespace autoware::ekf_localizer +{ + +template +class AgedObjectQueue +{ +public: + explicit AgedObjectQueue(const size_t max_age) : max_age_(max_age) {} + + [[nodiscard]] bool empty() const { return this->size() == 0; } + + [[nodiscard]] size_t size() const { return objects_.size(); } + + Object back() const { return objects_.back(); } + + void push(const Object & object) + { + objects_.push(object); + ages_.push(0); + } + + Object pop_increment_age() + { + const Object object = objects_.front(); + const size_t age = ages_.front() + 1; + objects_.pop(); + ages_.pop(); + + if (age < max_age_) { + objects_.push(object); + ages_.push(age); + } + + return object; + } + + void clear() + { + objects_ = std::queue(); + ages_ = std::queue(); + } + +private: + const size_t max_age_; + std::queue objects_; + std::queue ages_; +}; + +} // namespace autoware::ekf_localizer + +#endif // AUTOWARE__EKF_LOCALIZER__AGED_OBJECT_QUEUE_HPP_ diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/covariance.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/covariance.hpp new file mode 100644 index 0000000000000..018b93f86d816 --- /dev/null +++ b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/covariance.hpp @@ -0,0 +1,28 @@ +// Copyright 2022 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__EKF_LOCALIZER__COVARIANCE_HPP_ +#define AUTOWARE__EKF_LOCALIZER__COVARIANCE_HPP_ + +#include "autoware/ekf_localizer/matrix_types.hpp" + +namespace autoware::ekf_localizer +{ + +std::array ekf_covariance_to_pose_message_covariance(const Matrix6d & P); +std::array ekf_covariance_to_twist_message_covariance(const Matrix6d & P); + +} // namespace autoware::ekf_localizer + +#endif // AUTOWARE__EKF_LOCALIZER__COVARIANCE_HPP_ diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/diagnostics.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/diagnostics.hpp new file mode 100644 index 0000000000000..b194c3e956341 --- /dev/null +++ b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/diagnostics.hpp @@ -0,0 +1,49 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__EKF_LOCALIZER__DIAGNOSTICS_HPP_ +#define AUTOWARE__EKF_LOCALIZER__DIAGNOSTICS_HPP_ + +#include + +#include +#include + +namespace autoware::ekf_localizer +{ + +diagnostic_msgs::msg::DiagnosticStatus check_process_activated(const bool is_activated); +diagnostic_msgs::msg::DiagnosticStatus check_set_initialpose(const bool is_set_initialpose); + +diagnostic_msgs::msg::DiagnosticStatus check_measurement_updated( + const std::string & measurement_type, const size_t no_update_count, + const size_t no_update_count_threshold_warn, const size_t no_update_count_threshold_error); +diagnostic_msgs::msg::DiagnosticStatus check_measurement_queue_size( + const std::string & measurement_type, const size_t queue_size); +diagnostic_msgs::msg::DiagnosticStatus check_measurement_delay_gate( + const std::string & measurement_type, const bool is_passed_delay_gate, const double delay_time, + const double delay_time_threshold); +diagnostic_msgs::msg::DiagnosticStatus check_measurement_mahalanobis_gate( + const std::string & measurement_type, const bool is_passed_mahalanobis_gate, + const double mahalanobis_distance, const double mahalanobis_distance_threshold); +diagnostic_msgs::msg::DiagnosticStatus check_covariance_ellipse( + const std::string & name, const double curr_size, const double warn_threshold, + const double error_threshold); + +diagnostic_msgs::msg::DiagnosticStatus merge_diagnostic_status( + const std::vector & stat_array); + +} // namespace autoware::ekf_localizer + +#endif // AUTOWARE__EKF_LOCALIZER__DIAGNOSTICS_HPP_ diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_localizer.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_localizer.hpp new file mode 100644 index 0000000000000..84018c043cc14 --- /dev/null +++ b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_localizer.hpp @@ -0,0 +1,199 @@ +// Copyright 2018-2019 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__EKF_LOCALIZER__EKF_LOCALIZER_HPP_ +#define AUTOWARE__EKF_LOCALIZER__EKF_LOCALIZER_HPP_ + +#include "autoware/ekf_localizer/aged_object_queue.hpp" +#include "autoware/ekf_localizer/ekf_module.hpp" +#include "autoware/ekf_localizer/hyper_parameters.hpp" +#include "autoware/ekf_localizer/warning.hpp" + +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +namespace autoware::ekf_localizer +{ + +class EKFLocalizer : public rclcpp::Node +{ +public: + explicit EKFLocalizer(const rclcpp::NodeOptions & options); + + // This function is only used in static tools to know when timer callbacks are triggered. + std::chrono::nanoseconds time_until_trigger() const + { + return timer_control_->time_until_trigger(); + } + +private: + const std::shared_ptr warning_; + + //!< @brief ekf estimated pose publisher + rclcpp::Publisher::SharedPtr pub_pose_; + //!< @brief estimated ekf pose with covariance publisher + rclcpp::Publisher::SharedPtr pub_pose_cov_; + //!< @brief estimated ekf odometry publisher + rclcpp::Publisher::SharedPtr pub_odom_; + //!< @brief ekf estimated twist publisher + rclcpp::Publisher::SharedPtr pub_twist_; + //!< @brief ekf estimated twist with covariance publisher + rclcpp::Publisher::SharedPtr pub_twist_cov_; + //!< @brief ekf estimated yaw bias publisher + rclcpp::Publisher::SharedPtr pub_yaw_bias_; + //!< @brief ekf estimated yaw bias publisher + rclcpp::Publisher::SharedPtr pub_biased_pose_; + //!< @brief ekf estimated yaw bias publisher + rclcpp::Publisher::SharedPtr pub_biased_pose_cov_; + //!< @brief diagnostics publisher + rclcpp::Publisher::SharedPtr pub_diag_; + //!< @brief processing_time publisher + rclcpp::Publisher::SharedPtr + pub_processing_time_; + //!< @brief initial pose subscriber + rclcpp::Subscription::SharedPtr sub_initialpose_; + //!< @brief measurement pose with covariance subscriber + rclcpp::Subscription::SharedPtr sub_pose_with_cov_; + //!< @brief measurement twist with covariance subscriber + rclcpp::Subscription::SharedPtr + sub_twist_with_cov_; + //!< @brief time for ekf calculation callback + rclcpp::TimerBase::SharedPtr timer_control_; + //!< @brief last predict time + std::shared_ptr last_predict_time_; + //!< @brief trigger_node service + rclcpp::Service::SharedPtr service_trigger_node_; + + //!< @brief tf broadcaster + std::shared_ptr tf_br_; + //!< @brief tf buffer + tf2_ros::Buffer tf2_buffer_; + //!< @brief tf listener + tf2_ros::TransformListener tf2_listener_; + + //!< @brief logger configure module + std::unique_ptr logger_configure_; + + //!< @brief extended kalman filter instance. + std::unique_ptr ekf_module_; + + const HyperParameters params_; + + double ekf_dt_; + + bool is_activated_; + bool is_set_initialpose_; + + EKFDiagnosticInfo pose_diag_info_; + EKFDiagnosticInfo twist_diag_info_; + + AgedObjectQueue pose_queue_; + AgedObjectQueue twist_queue_; + + /** + * @brief computes update & prediction of EKF for each ekf_dt_[s] time + */ + void timer_callback(); + + /** + * @brief set pose with covariance measurement + */ + void callback_pose_with_covariance(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg); + + /** + * @brief set twist with covariance measurement + */ + void callback_twist_with_covariance( + geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg); + + /** + * @brief set initial_pose to current EKF pose + */ + void callback_initial_pose(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg); + + /** + * @brief update predict frequency + */ + void update_predict_frequency(const rclcpp::Time & current_time); + + /** + * @brief get transform from frame_id + */ + bool get_transform_from_tf( + std::string parent_frame, std::string child_frame, + geometry_msgs::msg::TransformStamped & transform); + + /** + * @brief publish current EKF estimation result + */ + void publish_estimate_result( + const geometry_msgs::msg::PoseStamped & current_ekf_pose, + const geometry_msgs::msg::PoseStamped & current_biased_ekf_pose, + const geometry_msgs::msg::TwistStamped & current_ekf_twist); + + /** + * @brief publish diagnostics message + */ + void publish_diagnostics( + const geometry_msgs::msg::PoseStamped & current_ekf_pose, const rclcpp::Time & current_time); + + /** + * @brief publish diagnostics message for return + */ + void publish_callback_return_diagnostics( + const std::string & callback_name, const rclcpp::Time & current_time); + + /** + * @brief trigger node + */ + void service_trigger_node( + const std_srvs::srv::SetBool::Request::SharedPtr req, + std_srvs::srv::SetBool::Response::SharedPtr res); + + autoware::universe_utils::StopWatch stop_watch_; + autoware::universe_utils::StopWatch stop_watch_timer_cb_; + + friend class EKFLocalizerTestSuite; // for test code +}; + +} // namespace autoware::ekf_localizer + +#endif // AUTOWARE__EKF_LOCALIZER__EKF_LOCALIZER_HPP_ diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_module.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_module.hpp new file mode 100644 index 0000000000000..36fc9053ef4d6 --- /dev/null +++ b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_module.hpp @@ -0,0 +1,156 @@ +// Copyright 2018-2019 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__EKF_LOCALIZER__EKF_MODULE_HPP_ +#define AUTOWARE__EKF_LOCALIZER__EKF_MODULE_HPP_ + +#include "autoware/ekf_localizer/hyper_parameters.hpp" +#include "autoware/ekf_localizer/state_index.hpp" +#include "autoware/ekf_localizer/warning.hpp" + +#include +#include +#include + +#include +#include +#include +#include +#include + +#include + +#include +#include + +namespace autoware::ekf_localizer +{ +using autoware::kalman_filter::TimeDelayKalmanFilter; + +struct EKFDiagnosticInfo +{ + size_t no_update_count{0}; + size_t queue_size{0}; + bool is_passed_delay_gate{true}; + double delay_time{0.0}; + double delay_time_threshold{0.0}; + bool is_passed_mahalanobis_gate{true}; + double mahalanobis_distance{0.0}; +}; + +class Simple1DFilter +{ +public: + Simple1DFilter() + { + initialized_ = false; + x_ = 0; + var_ = 1e9; + proc_var_x_c_ = 0.0; + }; + void init(const double init_obs, const double obs_var) + { + x_ = init_obs; + var_ = obs_var; + initialized_ = true; + }; + void update(const double obs, const double obs_var, const double dt) + { + if (!initialized_) { + init(obs, obs_var); + return; + } + + // Prediction step (current variance) + double proc_var_x_d = proc_var_x_c_ * dt * dt; + var_ = var_ + proc_var_x_d; + + // Update step + double kalman_gain = var_ / (var_ + obs_var); + x_ = x_ + kalman_gain * (obs - x_); + var_ = (1 - kalman_gain) * var_; + }; + void set_proc_var(const double proc_var) { proc_var_x_c_ = proc_var; } + [[nodiscard]] double get_x() const { return x_; } + [[nodiscard]] double get_var() const { return var_; } + +private: + bool initialized_; + double x_; + double var_; + double proc_var_x_c_; +}; + +class EKFModule +{ +private: + using PoseWithCovariance = geometry_msgs::msg::PoseWithCovarianceStamped; + using TwistWithCovariance = geometry_msgs::msg::TwistWithCovarianceStamped; + using Pose = geometry_msgs::msg::PoseStamped; + using Twist = geometry_msgs::msg::TwistStamped; + +public: + EKFModule(std::shared_ptr warning, const HyperParameters & params); + + void initialize( + const PoseWithCovariance & initial_pose, + const geometry_msgs::msg::TransformStamped & transform); + + [[nodiscard]] geometry_msgs::msg::PoseStamped get_current_pose( + const rclcpp::Time & current_time, bool get_biased_yaw) const; + [[nodiscard]] geometry_msgs::msg::TwistStamped get_current_twist( + const rclcpp::Time & current_time) const; + [[nodiscard]] double get_yaw_bias() const; + [[nodiscard]] std::array get_current_pose_covariance() const; + [[nodiscard]] std::array get_current_twist_covariance() const; + + [[nodiscard]] size_t find_closest_delay_time_index(double target_value) const; + void accumulate_delay_time(const double dt); + + void predict_with_delay(const double dt); + bool measurement_update_pose( + const PoseWithCovariance & pose, const rclcpp::Time & t_curr, + EKFDiagnosticInfo & pose_diag_info); + bool measurement_update_twist( + const TwistWithCovariance & twist, const rclcpp::Time & t_curr, + EKFDiagnosticInfo & twist_diag_info); + geometry_msgs::msg::PoseWithCovarianceStamped compensate_rph_with_delay( + const PoseWithCovariance & pose, tf2::Vector3 last_angular_velocity, const double delay_time); + +private: + void update_simple_1d_filters( + const geometry_msgs::msg::PoseWithCovarianceStamped & pose, const size_t smoothing_step); + + TimeDelayKalmanFilter kalman_filter_; + + std::shared_ptr warning_; + const int dim_x_; + std::vector accumulated_delay_times_; + const HyperParameters params_; + + Simple1DFilter z_filter_; + Simple1DFilter roll_filter_; + Simple1DFilter pitch_filter_; + + /** + * @brief last angular velocity for compensating rph with delay + */ + tf2::Vector3 last_angular_velocity_; + + double ekf_dt_; +}; + +} // namespace autoware::ekf_localizer + +#endif // AUTOWARE__EKF_LOCALIZER__EKF_MODULE_HPP_ diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/hyper_parameters.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/hyper_parameters.hpp new file mode 100644 index 0000000000000..02958199cf2a1 --- /dev/null +++ b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/hyper_parameters.hpp @@ -0,0 +1,108 @@ +// Copyright 2022 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__EKF_LOCALIZER__HYPER_PARAMETERS_HPP_ +#define AUTOWARE__EKF_LOCALIZER__HYPER_PARAMETERS_HPP_ + +#include + +#include +#include + +namespace autoware::ekf_localizer +{ + +class HyperParameters +{ +public: + explicit HyperParameters(rclcpp::Node * node) + : show_debug_info(node->declare_parameter("node.show_debug_info")), + ekf_rate(node->declare_parameter("node.predict_frequency")), + ekf_dt(1.0 / std::max(ekf_rate, 0.1)), + tf_rate_(node->declare_parameter("node.tf_rate")), + enable_yaw_bias_estimation(node->declare_parameter("node.enable_yaw_bias_estimation")), + extend_state_step(node->declare_parameter("node.extend_state_step")), + pose_frame_id(node->declare_parameter("misc.pose_frame_id")), + pose_additional_delay( + node->declare_parameter("pose_measurement.pose_additional_delay")), + pose_gate_dist(node->declare_parameter("pose_measurement.pose_gate_dist")), + pose_smoothing_steps(node->declare_parameter("pose_measurement.pose_smoothing_steps")), + twist_additional_delay( + node->declare_parameter("twist_measurement.twist_additional_delay")), + twist_gate_dist(node->declare_parameter("twist_measurement.twist_gate_dist")), + twist_smoothing_steps(node->declare_parameter("twist_measurement.twist_smoothing_steps")), + proc_stddev_vx_c(node->declare_parameter("process_noise.proc_stddev_vx_c")), + proc_stddev_wz_c(node->declare_parameter("process_noise.proc_stddev_wz_c")), + proc_stddev_yaw_c(node->declare_parameter("process_noise.proc_stddev_yaw_c")), + z_filter_proc_dev( + node->declare_parameter("simple_1d_filter_parameters.z_filter_proc_dev")), + roll_filter_proc_dev( + node->declare_parameter("simple_1d_filter_parameters.roll_filter_proc_dev")), + pitch_filter_proc_dev( + node->declare_parameter("simple_1d_filter_parameters.pitch_filter_proc_dev")), + pose_no_update_count_threshold_warn( + node->declare_parameter("diagnostics.pose_no_update_count_threshold_warn")), + pose_no_update_count_threshold_error( + node->declare_parameter("diagnostics.pose_no_update_count_threshold_error")), + twist_no_update_count_threshold_warn( + node->declare_parameter("diagnostics.twist_no_update_count_threshold_warn")), + twist_no_update_count_threshold_error( + node->declare_parameter("diagnostics.twist_no_update_count_threshold_error")), + ellipse_scale(node->declare_parameter("diagnostics.ellipse_scale")), + error_ellipse_size(node->declare_parameter("diagnostics.error_ellipse_size")), + warn_ellipse_size(node->declare_parameter("diagnostics.warn_ellipse_size")), + error_ellipse_size_lateral_direction( + node->declare_parameter("diagnostics.error_ellipse_size_lateral_direction")), + warn_ellipse_size_lateral_direction( + node->declare_parameter("diagnostics.warn_ellipse_size_lateral_direction")), + threshold_observable_velocity_mps( + node->declare_parameter("misc.threshold_observable_velocity_mps")) + { + } + + const bool show_debug_info; + const double ekf_rate; + const double ekf_dt; + const double tf_rate_; + const bool enable_yaw_bias_estimation; + const size_t extend_state_step; + const std::string pose_frame_id; + const double pose_additional_delay; + const double pose_gate_dist; + const size_t pose_smoothing_steps; + const double twist_additional_delay; + const double twist_gate_dist; + const size_t twist_smoothing_steps; + const double proc_stddev_vx_c; //!< @brief vx process noise + const double proc_stddev_wz_c; //!< @brief wz process noise + const double proc_stddev_yaw_c; //!< @brief yaw process noise + const double z_filter_proc_dev; + const double roll_filter_proc_dev; + const double pitch_filter_proc_dev; + const size_t pose_no_update_count_threshold_warn; + const size_t pose_no_update_count_threshold_error; + const size_t twist_no_update_count_threshold_warn; + const size_t twist_no_update_count_threshold_error; + double ellipse_scale; + double error_ellipse_size; + double warn_ellipse_size; + double error_ellipse_size_lateral_direction; + double warn_ellipse_size_lateral_direction; + + const double threshold_observable_velocity_mps; +}; + +} // namespace autoware::ekf_localizer + +#endif // AUTOWARE__EKF_LOCALIZER__HYPER_PARAMETERS_HPP_ diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/mahalanobis.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/mahalanobis.hpp new file mode 100644 index 0000000000000..c1538a72f56b6 --- /dev/null +++ b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/mahalanobis.hpp @@ -0,0 +1,31 @@ +// Copyright 2022 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__EKF_LOCALIZER__MAHALANOBIS_HPP_ +#define AUTOWARE__EKF_LOCALIZER__MAHALANOBIS_HPP_ + +#include +#include + +namespace autoware::ekf_localizer +{ + +double squared_mahalanobis( + const Eigen::VectorXd & x, const Eigen::VectorXd & y, const Eigen::MatrixXd & C); + +double mahalanobis(const Eigen::VectorXd & x, const Eigen::VectorXd & y, const Eigen::MatrixXd & C); + +} // namespace autoware::ekf_localizer + +#endif // AUTOWARE__EKF_LOCALIZER__MAHALANOBIS_HPP_ diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/matrix_types.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/matrix_types.hpp new file mode 100644 index 0000000000000..fc75dfe72bb9d --- /dev/null +++ b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/matrix_types.hpp @@ -0,0 +1,28 @@ +// Copyright 2022 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__EKF_LOCALIZER__MATRIX_TYPES_HPP_ +#define AUTOWARE__EKF_LOCALIZER__MATRIX_TYPES_HPP_ + +#include + +namespace autoware::ekf_localizer +{ + +using Vector6d = Eigen::Matrix; +using Matrix6d = Eigen::Matrix; + +} // namespace autoware::ekf_localizer + +#endif // AUTOWARE__EKF_LOCALIZER__MATRIX_TYPES_HPP_ diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/measurement.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/measurement.hpp new file mode 100644 index 0000000000000..b8db07015ec46 --- /dev/null +++ b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/measurement.hpp @@ -0,0 +1,32 @@ +// Copyright 2022 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__EKF_LOCALIZER__MEASUREMENT_HPP_ +#define AUTOWARE__EKF_LOCALIZER__MEASUREMENT_HPP_ + +#include + +namespace autoware::ekf_localizer +{ + +Eigen::Matrix pose_measurement_matrix(); +Eigen::Matrix twist_measurement_matrix(); +Eigen::Matrix3d pose_measurement_covariance( + const std::array & covariance, const size_t smoothing_step); +Eigen::Matrix2d twist_measurement_covariance( + const std::array & covariance, const size_t smoothing_step); + +} // namespace autoware::ekf_localizer + +#endif // AUTOWARE__EKF_LOCALIZER__MEASUREMENT_HPP_ diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/numeric.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/numeric.hpp new file mode 100644 index 0000000000000..253da4eb7f6dc --- /dev/null +++ b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/numeric.hpp @@ -0,0 +1,37 @@ +// Copyright 2022 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__EKF_LOCALIZER__NUMERIC_HPP_ +#define AUTOWARE__EKF_LOCALIZER__NUMERIC_HPP_ + +#include + +#include + +namespace autoware::ekf_localizer +{ + +inline bool has_inf(const Eigen::MatrixXd & v) +{ + return v.array().isInf().any(); +} + +inline bool has_nan(const Eigen::MatrixXd & v) +{ + return v.array().isNaN().any(); +} + +} // namespace autoware::ekf_localizer + +#endif // AUTOWARE__EKF_LOCALIZER__NUMERIC_HPP_ diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/state_index.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/state_index.hpp new file mode 100644 index 0000000000000..86fe83ec4aa8b --- /dev/null +++ b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/state_index.hpp @@ -0,0 +1,32 @@ +// Copyright 2022 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__EKF_LOCALIZER__STATE_INDEX_HPP_ +#define AUTOWARE__EKF_LOCALIZER__STATE_INDEX_HPP_ + +namespace autoware::ekf_localizer +{ + +enum IDX { + X = 0, + Y = 1, + YAW = 2, + YAWB = 3, + VX = 4, + WZ = 5, +}; + +} // namespace autoware::ekf_localizer + +#endif // AUTOWARE__EKF_LOCALIZER__STATE_INDEX_HPP_ diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/state_transition.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/state_transition.hpp new file mode 100644 index 0000000000000..e6ce18e76a3a4 --- /dev/null +++ b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/state_transition.hpp @@ -0,0 +1,31 @@ +// Copyright 2022 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__EKF_LOCALIZER__STATE_TRANSITION_HPP_ +#define AUTOWARE__EKF_LOCALIZER__STATE_TRANSITION_HPP_ + +#include "autoware/ekf_localizer/matrix_types.hpp" + +namespace autoware::ekf_localizer +{ + +double normalize_yaw(const double & yaw); +Vector6d predict_next_state(const Vector6d & X_curr, const double dt); +Matrix6d create_state_transition_matrix(const Vector6d & X_curr, const double dt); +Matrix6d process_noise_covariance( + const double proc_cov_yaw_d, const double proc_cov_vx_d, const double proc_cov_wz_d); + +} // namespace autoware::ekf_localizer + +#endif // AUTOWARE__EKF_LOCALIZER__STATE_TRANSITION_HPP_ diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/string.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/string.hpp new file mode 100644 index 0000000000000..0146176b7ddc1 --- /dev/null +++ b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/string.hpp @@ -0,0 +1,34 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__EKF_LOCALIZER__STRING_HPP_ +#define AUTOWARE__EKF_LOCALIZER__STRING_HPP_ + +#include + +namespace autoware::ekf_localizer +{ + +inline std::string erase_leading_slash(const std::string & s) +{ + std::string a = s; + if (a.front() == '/') { + a.erase(0, 1); + } + return a; +} + +} // namespace autoware::ekf_localizer + +#endif // AUTOWARE__EKF_LOCALIZER__STRING_HPP_ diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/warning.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/warning.hpp new file mode 100644 index 0000000000000..f43c5e3413213 --- /dev/null +++ b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/warning.hpp @@ -0,0 +1,48 @@ +// Copyright 2022 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__EKF_LOCALIZER__WARNING_HPP_ +#define AUTOWARE__EKF_LOCALIZER__WARNING_HPP_ + +#include + +#include + +namespace autoware::ekf_localizer +{ + +class Warning +{ +public: + explicit Warning(rclcpp::Node * node) : node_(node) {} + + void warn(const std::string & message) const + { + RCLCPP_WARN(node_->get_logger(), "%s", message.c_str()); + } + + void warn_throttle(const std::string & message, const int duration_milliseconds) const + { + RCLCPP_WARN_THROTTLE( + node_->get_logger(), *(node_->get_clock()), + std::chrono::milliseconds(duration_milliseconds).count(), "%s", message.c_str()); + } + +private: + rclcpp::Node * node_; +}; + +} // namespace autoware::ekf_localizer + +#endif // AUTOWARE__EKF_LOCALIZER__WARNING_HPP_ diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/warning_message.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/warning_message.hpp new file mode 100644 index 0000000000000..b379e35763f54 --- /dev/null +++ b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/warning_message.hpp @@ -0,0 +1,33 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__EKF_LOCALIZER__WARNING_MESSAGE_HPP_ +#define AUTOWARE__EKF_LOCALIZER__WARNING_MESSAGE_HPP_ + +#include + +namespace autoware::ekf_localizer +{ + +std::string pose_delay_step_warning_message( + const double delay_time, const double delay_time_threshold); +std::string twist_delay_step_warning_message( + const double delay_time, const double delay_time_threshold); +std::string pose_delay_time_warning_message(const double delay_time); +std::string twist_delay_time_warning_message(const double delay_time); +std::string mahalanobis_warning_message(const double distance, const double max_distance); + +} // namespace autoware::ekf_localizer + +#endif // AUTOWARE__EKF_LOCALIZER__WARNING_MESSAGE_HPP_ diff --git a/localization/autoware_ekf_localizer/launch/ekf_localizer.launch.xml b/localization/autoware_ekf_localizer/launch/ekf_localizer.launch.xml new file mode 100644 index 0000000000000..76ac35bcba38e --- /dev/null +++ b/localization/autoware_ekf_localizer/launch/ekf_localizer.launch.xml @@ -0,0 +1,40 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/localization/autoware_ekf_localizer/media/calculation_delta_from_pitch.png b/localization/autoware_ekf_localizer/media/calculation_delta_from_pitch.png new file mode 100644 index 0000000000000000000000000000000000000000..0fa459f96dd7113388f9aabb59fa36ec5de9946b GIT binary patch literal 56991 zcmdSAWmp_d*R~5GK!6}Yf8Qk5SP2T6epLg#+ z`}gy;j2&I{?2RBytZl4}s2vRKjf|`vOl=&`pgMTo|HNpf zsOl(SZ=~mFW@G(L(ag%|y$}L|fsTQ3r@4-fZ8trHo@F3aCZ@fj zScrXFeh7$f5MqLSimvI$t6r{(JMCw0jff}Wd_UJ0yWyTjGzSJlVvAQ9bAt!Fwgk;Z z6^OpWkRi*#Egv zb@4|>gvfv*eVGwb2f+A)TQXM+oZs!!V-XRfMTJL&)A-EIpqI}XE{%4Z>ldOx6#h^D zv$$YA)5u$e_}>CMtKZq8|JnDq5CRn)?!P-jP~gJ;dnD1vZ+tQTo`xv!Q_TOFhd~%r zK7N7XNe?!!B5;q6)}(d?UFT8YkV-TBrrYwK`kEidq!xNiAFcBH3YQb#VARk`vL6Lw zaTPfXEPPN%kuFKHQ-UY&_+`a~H>mh@endfKoT8&V2C2Wt^uxfIsB}g(5Ecvs|ea$#sk%xH>yOK)%|xj-RMX#etEC@Q778q3sTTw z;ejsoTtIMDR^)=TSqZh_puhgH-zo4uBY455D)A-KdPWrATG7>ZW=5Y|HQ?k*G(9vc zv0F(MS$WcR3jFe8R>I&yoWQe^=tDoYr9|s==-Ru4*FPR15v;TKZaOGw$m&CsU<^yRVOgBZ{m@?2E zxPFPzXE#hqp+7}WJ5DPUT(5%85;JO|JppB zgqm5hH^Zn>P3;4%cyk!tZqB)d5Op6W@$*S6T+#*J#2E7IO@!|ZtRs8SH1Rb5Z?jdd z49IXJG?Bd+VN*luUdlV49%7?9<@8inW%~wkKoHI)QJ7+1z`)bH(*!BtAmYG<{%d9t zHD3tj@Ntaorq}hVbp+y#eiq_4lh%&y~CQ$26>&w99gG zAt|QcHV6>Ru42WK>1LE4&Db>sc8GAP-wyI#XeT9^u;_~lYi$cFHM9(56rks}yqk8dWKTC=%ZO!Z`%jPhV#7EP+1k^kH4UaT7S0b0DX+)(JQn zPy+;svSiEtQVnCSW-bDEE5rDo2l96nv_}3hy*M=jI@{ z>Q-=U{xGm+#NX4g9yp>EFw@LTyw1cS9s|q!ou?!`M9$sScByvsYHx=Qd7oC9K-xh! zP?(u-2=tGxRM9j>8|?uLGqatqP)Wau;kaSbc}APq+1={t_I=(7M>=1Ru1>b)Nrh}n&XvCc(dFZJ-LUO1?`)ITmfsf9W! zH}h)Y8(#$&5C~-YXMWf!$*@+x@j^9hX)i5thJe(9yW$0x@*G;)&n_=07v6FRPp%!m zredfgsZf{)HwiZ00$ ztH(e~?QovvDvtHIIqz(~!mAvlm=+Jr7C?kFz`r zpXRA|U6Hu^8PU^be9NSpqHLv4yxEk>t^gB^>7%Yy$+hdU0g z$Wq_Q^Hts|6qbn|DsuaAZW*iq zzyscPt@qSNU4Sox)soNUhd24M^G*yZ?xT1&E-p*Sj`FD&r;hjO}~YKVW@!Mm5hWor@EB8 z=(#IlH%Q7+b>3bFTVkPLfeI`WqSm_j3>ln&w@h84#=7{+sS2tzuFegly&4iqEL5|I zgY6`BwLN>u(6V-k zI|`dve;%?bb!SU;Me`*y1guLE@7vknIb&Ib?a!3 zVHI~!#RBqiYe|gN+#H`}_&J)WcaL4l*HCvMl}hSJxw(<=a56S?q9+QqoMC^pENp9w z|KpY;OH7mT=Td%XSYj|^m3i*!%Gi!5(wiEtc3O>Xod3^EbH1AY{4&T0dRV7s1Az={ zx7@(Qh+8BL*Ui8MlG4O{qYd{6Ky7exv_b2?S8p=Nx&2dbjiVt!MP5ry{55y|6H`Y; zveK2xd2N6G|r+|2na@>CO2@QOiG2sqk&Y$I|tB}rJ#t|&$@oZ#l^ zs046ScwvRv+;`8H-Y&j%i_i4rH+XPdPW7#XQF5jr&I1T%C5!{zutuL@PDy&^M4SC% zM@89rtQD`))PRwkDQ$vARXDWFFLx8hTQ+{>?$d8LI}-Ix*(3h9%w*o!-l-eiFJ~S@ zhQwlVIXkX)=a{K%sMM=P%}(0HZ%G_q6V=J zrUYiu=vrk&KaQqVj~%WC&tCmLkK7C<) z=L&Z8!CI(eetFm7mHb;n_{u@R!PYAK zmnQmSP@S-WX^WyqRfAl|lY?G`17x;NU8RJmV~XCSIRn+#sa=xn2Y0r}v;G;w8fBx{ zixCb2B$aIqdOi5jZZp6#Pq{!z1BJH>PDq%6k#rNe0Q|51OI2*-^&J;rJDM>`LSnEA zO*rcCtAcGX!5OcBEB{zWKz$c18Of{b>dxo|_G9f|W-mMM~2d$V!m;Hbb>f8diB2vYd%dTyS3dQ445m8X2g)^mIkP;Vpj(_gXWG>&=n& zul=0~Hzn8mPd!vIuN0M5+vQW~NQpPiD*`g(oKtIeS9HjgZ_hV|}NH%75A- zvv0oevFyhd?VDjn4`V>dLZP9Uq?1ESM-uwx+6wy_22gMC#^EY?#qC8Ep=wQhC?8u9Qv-swgX zkA6l7HF#QJoAcip^GpROKJ=Uh3MHNbk2b|VG0uo%mqB{cEuy3=&kKw+O{^k*ehIJ= zg=e*g{}$DQ%@L-l%|*C;p?kdL1$CkS#)cJ!ZJhkH5S&=&FF*CC9o?uCt09`wlr*q1 zycDT28sR^q*d8Zi!+=~eZVu`R96UFa^iK?u8D#;B>2>MOTNkbut}g=PIqL0okb(yj zT8q=Bf)A@wZEAN&NJ(kqTm)QM9v2zW$Mjq#{KVq=TP>KSr+mP9DC_fjXrP>mf%W%7 zAiHMLEqhaIPUgkOZVaJdZ+V@knY?L8t$poV~)@6&^(G4K40)&rcZ9o>UyqOjpQa#9H6aEO@jA-9zA+0 zJ>98yB2@5rLOz}pdBMA$2R-%+zF>H6MKp)*LmrhlefH}3*BJ4!-i=ZHbEDaM6Csb& zx!SjO@J=zU-0BRWBjZITcJd|-p!xydsQkrje6|anDQ-)wZ8+lKD{=xY^XJOn_3-8p zA@Z`q_Y~J8pY7f^|zThpjD(KKX7^dceD#7>S`|$T3O^M^@Uv<{~hG^U*I+ zKDkG08%IUQ^I(MTQ1Gjy$X@)sU!@eG@C_&5KOqU>$q*Ut)+Z3QskTk$S?%PuZ_fdg zO@X&;-&M2Hy{ssOd7)<}j3?srF(HE4wO?-S@0gURolMu$kZCO>)F@1Y)k(Uh!bm0l zjlj1s^P%fItmQA(DVIEKF6DYB+L#pYqXDBDs@aiMxC<C8Qz}{{FaF02|j1ABB){Bc@K?1D}v;y7v)^pk|{Q@p%^jp4H6Q^g) zzr_Ektsvmt-kD8LWr)o__$Iv=)qieFZioiAyOZ66s*R1uKl5z69XiXML7@{b0^?(! zR2f1qTCDS=W*R0G3%e$;{d>)!w9~V0Z?aDcnTSJS_e^AM+3qv<$G*UO&Gc?a(1N!QC_15KF`Ot4!61tEBrUa?XJrQ8FE?p;rvH;)-LWbIzFbWd%wJl zBF|H>mjuq+Q4Tbf&md7y$v>l+?}j}A-US!=35FEaZ+ErfjjqF$ zb=2WT=GAme_&>lk1}@LZ7>s)49B3SNcKI3$nsc$hsg+;3HYB|ZU8Hw+Qy#`X?*qhlluKn@3Y0XZ3N064kM z2bW^5h5jMKHHzE7N}oSoUKk&uP%?tzTOmB#9^3^MP$pGWgdBkCQeFPbUGsOBt#jwC zcgI@en-S1l*DuV+1U>wgT1Dhe?PKpg!k3)irp*AXXEusrE`nEu9e`qQnl=P}sFyNb zM+=t|v)(DWZA;jY0Yx^E*<1u)pn8(XsuS(E${!b?_2x(9`3cvCJ!jv;Y|vOx|4z15 z#4gUKiGQL9n@e<;d|z}`K`B&uAMVZ8>U@K1!m0_*2oQ=ZkZu8u5f9_c8?f;uDd?3Q zZRpL~K;+kBi_PB^d$w4B+YGhma+bPr-!P8#VghP_Di0=gHUXuvRdt?6Y3l0E4BqIYmk;Vx1JiQ7)~dlrGr6q)qoA9@yXn}=$FxB461Z4 zTZ`O&7+}$3N&9k0*}z@^J zqx-0F7rk&MR8?7Q@}HXjePIJCr3aONWR`0c6a&U`w*>&yPMoS5jRExr_4`gZ=pE6C zbHm8%Lo)@IPg2s2KRW6i60goX78lNLYCMeKvq;8CFTNs{0)wKX+5=Y0ax+pQ4z^&9 zy$LfJDX^Xhe`Z&2S6L;*DRF8o=%{ykF&m?vO@7IHyx&(vqc-t_Gqz_n(ciaRzEk=A z13nO9Y<|2`fbIBAaijs(Se)sP>V|AoenB z;E^jFH8^~gGR}3{l=OmyI^C-4wGwLFP1ll(^390RtXn(RS~qnO_hGMJv)p}F>M9X> z#iahXW71bp73{bUnhbwAg2}j?K=r}1Lri!tpd!0huJ1A*N0QORwu~k9cA6#CYE5?? zD`~8uZJST2WD@t9%vEmHXr!a{Gde=hXaNOz9Q{tzoqN*M}Uon3akhSQPAL1W#Zn= zbaGlx{2uysiU(V&!N(IkZ#msOBP$H*;48O%5Im|$>ICJ9E01gR?zDHvRO}@`0fK?Z zec*q?F7`^o=#X?>lD9TTCEj}EVhRG$CwpG5(k-+>g5u>dbtd9&!>Jlc+i|L8X7jV@|w31F~TXF)KAW5>4g|FZfEgL#so!7qu64F^Q;EB zH+PIDi!@XAviGP~%@r>>wnD2VDu&E$C2EZ^^ili045z7OjousH=Mwhg<+y-{j?X+K zbW~uW2gX6HKL0mEv?rZ4zQJJ(Rq#!YjF!m58RgjgxWR3LDu_(Eef39I}vLmOZ#@i=}A9mR7-IVwORFbo~+El4aCKxr) zF@h8e_}o@^Wj`Q=IC}vHVUBP*Q5^Tzcx5*k7d5oRoz1yY5qQ$2v?~2bqw;s46*Umt zeKLh(yv4rk0IKOO$^#w)l#YS58xQIMdbj4z1Y|}=&))z5IpLa1270G8u&;R9vd6)a zg$br?J8g8(bUm5LD$~4j_1g_hs?5`5&yP4QbE7@HRnhd^e=WJuy23C#q zuK*|gJ|a|yk8j50rg_&@L707QriM+p0OxwmS;q3?g{xP#X-Y9Je|v&2Vf1k1-djVr z&!ofAHd|d@Gp}N2^!UkcEx;M&Yr>#-yE1;6bPV?gA{OSB&al&-+ zZeeiXy8RRTS?|H+#4SdTDSreHq{0fbBlzD}2@Zq#d)jByMlAWi`JNu; zy+bK(w10!$fhhA#|9^QR93lRYvOi}|)6N9wR(Owad8;`8W|%faWl8>xe19T>NO33q z-z|O;GSvUQgzrb8|K0d5=>PrSQ}BO+{QsQf|Bl1@BAlWAr>d`s&6<^y*8YEcU8TXr z#l@FZ@Bpk3=9t}PyD?r?#-`*EJ4au{Pi59nau*)nP5iA;f(w{WL_Gs+cY|M|@BqEo zHk5lbf{Z-Qs0!B1v1|r7TR(nb@_(MXJy~Y=xIH#y75M91&X*wKvIsI!;Z%#HM2$yR zy{HH&5(bm+3ZfQC=?wuS4W5G>(l0YN2Y^ZE!)W+Dq(Hsy7LjD``rWSr|6bTfL2?i`RJ|{@h`G6GM4?{~V^^jwbH zP_>x|zFC9|_}l*HLOsmX41AM&MwT@N@-<@%t$h=FPpWoc9~1wzp4gR>_>;xqnDHl9 zMI6SUk&2Y`#mnzV55uh}`gK~ivULxiQ#2S;rkqL_gOm?5vx4Z^!*iDu9QUP?ts{3O z4X|;)l3aG~X8Or8^*Q~>Ut*D+vv-pDcL4Y6`**$=tA0q*m;C+!#UlEx6owPXT|kW3 zA$~w|?U&Z%qO;nIO+IWTl0Yo2J@ZC~ZBUWgibM8xP;L4{H#RBta?r~Nwx)>p_!;hT zy1NV7?!Lo)v2s(ogLl6{a)Ijk+g3!ZkanCmyM6CGMn({-;E0DKE(fjq1 z#<{&M{P+n*rFq~!PjL*tJnqjNe~6r86fx}h??+;Tv!vYjW<2<#of%p^Jg8I`XSa36KQEey5ItBS{H$hObx)Ed z`^99lp8m{DK?_3{%0QHWId^{rAJ!l<0k|#z&=}l`Z|gyEb@u5k@m?d3{U+rz`9Bh= znf41GJ%e+;>;57jO`gSdvS;nnp5bZAdkcCxA@%j&(oBGp5Q@k&Izox@6;z*}r?H+s zCHK9px{eJd{S$54#9==jZvdWEl%#qVE0Bar4e8QmKp z#!EE=tSax)^XZaB_WH=3%a6zs4I{u!hybBTxDd`9BEFcW;}hG$%Q3;R;4K@mICOlO z3*A%M!|^MY{z%F;00%Q=)%h0sGu1*>s-V>V-OsXtWurWNH0-n_{jft9TH6)GDE)s&rC#H2G&2mc^5cR1fYs=r51$j1~W zCzD@g!Y?nt#z#vU6u30KA_V5@8c?^4whrPP?oPx!a6%nqNZn3+a3a3_%Asl5xM>nta1^ zjj-d>1A9Dzn}KpOZDx?ecaO62(;}_p{F?X`80G4}Wv+r;YeZV9yIC&59;^J{SMeH7 z7MDas3wxPtSX?6Tb%PD+l1V?e<8Ri4L@b8BOip9%S?3;$cnluX)`w^ES{}P#gU5AN z$J?7jy?h#f9WE13G7tq~{aR)mjLH}!&j&;J)&poEn%`4Udy?P}68Rv6E$TrU{rO@1;0tETpw^@?3wjUZ z+n|m<$GJm<*GE2NOD8*H3&4{ZIk5wRp~|h!XXST)CF+9fJUmOG@mpMt*{mTBf5&TU z?=g41>v`*e?fLLeWR$mX^O2hMl>aE*sz7du#NurlmpsYG7E-}-c-iagEQQ-1_(Vg? zz1~Y^tYFoUmOLXuHJQ1K&M0$vV#T9(FzJ`oGgRCC5!#54Jv4Y#?$73OaPqb1j_%WC zksbB&@EUe3>iZ**^_tANJbrsk_Ic5n4sF@^HEBIYSK=BqE9+Jax94+jdgi+y%7Gdo zmOqjfP$B{M9b656%elhjgZ2*D3Wf9BkU0{hN+9E`O|}Gs`-+ zt}m#xw#r_ctF$a}wWFf{m5^uY-P1Q=z)m?xirN7zcAj$2NdUo*$b(d_Tw|Z?6NVz_Bzs4a^BEJWQ0>5Qc;_?jEu^T`t99o~rUOP2nHeXL}3%yazb$_RE64KdkxOs^}iy%G05-*W-i zyx3=6df4aD^a(y5*I?r9&UK{ZfXj03M$6*4EonEE!rYRE%j6xqNU6IfxNBR!_~j}i z(sH(0v}21nC%}^ahP`6Ex$QbKctBMb$bRRGdo&z;j?z-(jX5`8TKv{2wXA~jj(1F# zJANID6v1_R!1{|#yao^}eq0JZY2;ito*2^{;x_Oz+Tx%V- zUzjD1XmxGsw2SUucSRr^t_#k>WUjeI{ouT1nQj)KMlCs^V}-Y){uMQ z1cZ8yd8zhIH$P#$#kC)25c?2(;SZs_7)&}j=GZ8_d1gKKIrm|39x+vfi}Llwd`|#x znZUMl!`E<_@+e9i02^!1Ra(g;5lMM63mL+O+LP9H*foVG^<<6B29wc(cl{BLfZ-)7 z^;AsGaADHSvhtciJ{(x;2yWhGh&o9J7S0-IbE%~8l#TXxoJVS)>YU|L;rFs99h=-L zcTR*>sW(|Ow-+^KtMY;!&*Uo$bKSRLPEmI~yrUMc# z<7UO;xid0@6Pa+cYv&GzTLVPZVP{?Unm`|~K1ra-z#Pn_a=A%k*^x6+DzZ}b)4DkU zf#<=p_1*#1_-5#+R6B5ajbe%*9JynD9G8r`@=p;-p3d42vPdNmTk&~Hwa3(!qD6zGAt{pd!mIF^a>skU;=29jh1kFs}bYX>pmEw_^ zxT-wN&c@-_0g5Bz4NN(GG)8Bae5?k7j)|yW-U(D)?S#tg6+iP!WMT{PKVflJXv*IGSzC|UR>OLIum(Sbup(K>xP#eRL|9U z-br99kS?DiOzp;!ntBi8x^}+W%I2MbNOS9$99q+3jGOhc3o<^x%azudT8=5m2zghOo5>Oyx>x~9ZDT_3K@Br zyWRgDEBB9yz;wRqn-q=$$>C_K4K@Ua4nFF3bedqHv98%--N}tIOPUl#_}b z^*-94pd=#P8H|n_H%bVla0IVRtv9!W@m6&7sfyQNE;B2#e~ip!&LfbUUdEl963mJK zHj#hwY*tJ;ksR6wB4?r285ft!{xD!aMY3 zoxg8;rz^s(J%U!|PZUGS^D@PbS8x53lNss9dY;`h&Lz?lt&L;BU7bSU6U`nzI#)FV z7OE6o>;*r$4W8BROP=!3UpfQjb9bhy+*j`)+8ge$nlQ6I(Y{|N#}$?NEp5K#YF%=o z-Wv4d9fwHmYX5;g5(qvc{G~o*#oqxIfDHbSEjHl|t;z=@*x{LUwuUZs9fUOIeTBHf6x2gF^3&mNoPL-w9%a+rc8lpN zrebZ=Y?ohYyQONIpMsD7nYYV_Ndu1k`)O9ss}s1Mamk&So7v}Q!u+LF6n)3%i)YsO zmKCUu3y#a84$bxUw=;y@wg(#E_-oel{8>~VA(j{3Vr*Az60Ccczq2#aa-t*6;Avhp z(f#kl^R0?)+LkuOR^>G5*GkhRP)FutEejI$+P%ea~v)m;%9sl8z`!Py)|fYrg^wO|(X} zg=uQ|RH}F3C3~egRmHm%Nny`ixLW;sJeeMQjtMl&7!lq>ieIJb)kEY{j56qb-VEOtd)~B@{7Ua^-I^G?8EtYn2tO zC#p!Ovy5G!J3Ot(XNRA3pjKR}(!uo~a1b7VmPQ)|*7-tZ;ly3#0$y|htJ;L4ESMt< zzqIdaI;uVw;hesb#3|_uwlV~zcWZm!*)W%<)T6)9ogVBQeH{cLP#fWrJC$V9$LTbu zMM(5d$JUWW3&ut5Ai$fwRwetFHpkN*KCoYHsl+ZSw`bHzBrSyu>I=7$1aYN>y_}G8 z$@Jxj@Y&R5&$p06@&>%atYQk-9FZx{URq1IExW(63ad-!M7%DLQWdU56?qvcGYCy_ z7tS1XE3RTM45N8AxCM7$DFl0~*JE;|hufyk+B07x_H22EIaOGpW_cc+Me<=Z3U~QNqr&`7B3kdZHNZ!tYp10EJ=kH17GbSpD<0_iciU4jmHIjwsPJU;JdF*m?vLPfAFs2dbtc> zfq;j*!;%|nFWz@$V{D&CPxz?dd45B?YEbOg@xCO=Ct9)HbO*i)>K7q8gM5iIJe6u#cDH)ov*qa%j}n@ zt56ddvaqPiJZT^2VK*-ZAPV-zRa;A+9dK4V40wBD-e_nBtmNRR*N@3agku)E__(T! zl#v6q!*Zu{kdq+IV+XxSM?TdIN(^SI2w##T`w(>Om8+2Ch|tR4P2=- zJ?itz$9oi2LRK{dcB=7EO~|v8Q_@Ne-rjGHnYoUu8Al+gg3C#1L8&uYdI=*?S>?8U zKEoV56wAR%fWZ{!WV;j&mK#~3HeOrM#T#LTS?_mif;925Nio;mVH~v07?TGnN0`da z3`cIkD$Tz~R4XYbCu`*MQ1~@}?9pm=x;11F&f)Ly4oQAaElZiAB;jgFjVFidP;fAr z?`Ogf-DSI=sQllt`eTGF9siq_qrqB zCSy^6kV#pIK8;(%1Xi7)CtJE$PK|ED_a&|dCchnl{x=ir{pfDT(p-PxpEcB1?q5&T zSPd;!+gG148_%a$?3v!K%;+|eZjiI&+X>6ym|61*sPw_whFGF)zX!p{CSxtnV@zki*{FZB>`FX8VMlYf zDQ_62Q0A7L$_eg*7TO=U7b0jdYMyC)G&3vB%`XW< z-NNpi-AG1!cnf0T;=z*azi3T!tv$uZqhZZ*<8tM>+dL}jlhY`pb@i!3n~cVFeWQ!; zSh{f+sX24^e}W}^Qdt{)^;^n&^q;R?-X}t&Pv!BiA>-ee;pHTFr>R=RyxI!|Sii8r zSyfo^l6`4$pfPJa$sX7#1oa6yd+y)$mleA}8H|qL%V*?EtGu?)$FbD=dI=q1q0?2eRI2VqD>CW6L#b)PXn@mk^o#>E+5!reR@YVj{gh}1*d(|#|zC!v{zkmt^IKG%NJM-SUfs;Bt`8}J0{Q|nUhWSF90?8p zR&Va)UnKLbU^t%NilKu{v>#Lh9}V=|tECiOXlHt!QMQ{E`zNVZDUo*CjxY?C!8~AFEtZyZl!z}0-GD|<#qk;w6WOC6O}Q* zrcuH0u=M5?nCjy`_9V@SKd@Up+PwFw3o4{XbS6#Zp`p3wb?qZ4B}U5}H_Cfx!X00n z$n5Wp$wnY}r;#n30EAiTc*mE9IkzhW=Hq+P>0U;X)HFP}$1iaA7a5KdmJT`ugL#vB zsTtC92nB7Es)Iu%5EO*W?E7w_Z$(|HG#jo_oB_Q-KYJbeM_=l@`ZB}T4{er2!WUHP zQiEzEwD`Y65L)>hd(GFyIdxTyfcYhK81Frm%EiSua(*t&~DQvW`VR z!69jAG5PH07C4!1Y=*!!*<~GWEv37BIlhJewd_u!v$Xh5!~5-}Ik7ww&e-?B_KX>y zj#$upPyW6iF;7HqDt5>|b1GFb|xjS9t!?23%4EpJYj6g2A;>TNcgiwevSAQq% zT*u^7cmVB~OR?YXm;!<$K*VTd2X>|sNVZE7+xGzyHUT5*95SvWG#3M#N=!oUb$4Cd zYjJZrOB^v+B)55pEnP`j~ky{9U+kuQW1x;)IX@f z<3ev#r!N-TjO#uRzw5(Vx3gPaBFD@ZQ;2(Z`|}L#4I*D)Aq88n0=-`Kbz2^eJONS^ z-evoA=cz!~?9jEtUaTwit{{X#q@m3q2@(4K$=I6c%LIcq{RhLt6cnE=MWvndjcz<1 z&tyiEF*=`D&)xAXz|!dB^5ra~GS>XLhqvhBg;u`y=nhc_M=#u&ONzZmdAaxl>pHE^ z0|M)cEtJpeRn~iMnQE&qax0t`w7%IJE+`~)v3lm6glp3lW8?F*EGY8kbQ>}^ryPaH z{%6^yLrO#h_UZNn_k=Vur0u}vH|tB(q_wah(@S+^ekyU&>kIJBf&&nB=3$f(Q!sVv zydHtQjh6I2kIE3ylzN1jl8N=98k8(EbO$ebpdN8k9uNy&@=r@1U0HotCoISg47>F< zc3Ib95LcMGhPjqo|J+pa)*haq&?iycxl>QTXW?-KnoLevPy5VF*Kcz>vE#|jI@3t)PQR1qa(HtY*6D8znQix4+v6>G z=%qg?T|sQFV8nxAf5^!N%8nvpf&M>)MGB947(62MWtnNBZfof@WvLH#p!CtJVE;QJ zyWXkSfW|JIA`~c;^Nr^Pgo_rxhW%cZ)|h%yd``kv&zI*0{nzR$IKcZXuJjK@ zM}nvdqsGRt*Z>MaXbViOX3FO^+z&frPL>)bTRHr&<`&d|Vdgm5RBvd?x=_*g>B1o$ za#`MwFpGPN(tnL+Yl+ zVLR=2u|))zLGD!It(A_owIIvB(|NZq4E9LxEmP+Ui|-&tZ!Y)Dqkb&KL~z%&Z5Zo_ z$kgIbspF)@B5pGQn?&G}ME`cmAWMbLl2jv`r>owWuo6c}W_l@~mDbm8WQ-cgq5px0 zhuygQKmkr#W^rh!k`d8h`e6^#azsZbyoe?#n5X!go$&{>*@>HHb%{TU7<+>`k_K{g z6=3lO18gBA%mQrknKYB%Y-%~94+NwAUUbX^?aQ-!@m1FEJnkOJbo#0)@Iu$f}4aXC*f*N+1#HbXFJk+ znjpp`-9Z>f1mh{4DgeERv1R`HP%`#SAM4IB(A0S690)Mm2u;GPYir1aMLvUHgDrp> z??0QsJ0xD38AYeTanDA3&4#&-g8*jrt&kLQ6=jdFbWf(gWwm=mhu4g}0bczfPdC;f z4pGQH^|*dO=4JS(fxE!UC?N$$&8$Ie#XZC7fV}fKy7casD3mFASQ@`Hl&_Ll%}Nd9 zbqZ`I@)1A?q3Frl!mxiX!cNxn_JJTKga1IUo>2TR3*aAo^bq}LWM!V2v61*LZTzO0 z18ZTx6As(_+e75wN*0!YV-;%Hw5arGuP&s}g8rJCbHZ<_F#XGqIy?`>C<=%uU&rf+ zwA>gnURGLpN&_2JTWoNK6%etQ%3OEyYc%Cf`2!N`rtb8xvpS<5n(xmBMTO)vl zh1GC1WJx2ZrR}$5$(ui#G_RkTnUPge>V3Cg`n1uR+1bU!RAyKO2qh&Yi1>sAIW;vg zQPEG{-i@bcSJ&?CCycy`AW>=(soFRR$~=;1edFqDy{q6-4kV)f#)? z^NJofTvomo6MC!r9T%BpHUHCh=hreSEw(RaS4^>t)02cNBB|tI=Y?geJMk*2?zTjf zF3hL*LFB)ix%4h~3Jtqd(Y-(wlS8MB8I+_rD#s z@0Lng0y4!eRiuuJxB^mMlb9trZtxg^lw`SfE-f;R>vwAu$~Mw`X)VFD@{lCY1eznI zM&dkp9q3lDNoWsJYTe3a)WdJ7qW0dTgPa=WKjJ(?Gn;)2IwEZ}ogJEgLwj;5j32VH zIGC#Bo_NYdr4OutK|?D~91Yx=hl|J$1J@M8^JhdqIfH0x6mV>QlYdI7O8!Cn6GfvX zQK!(7-{VjNG^k};a!`vtvJ$y`v3&lu?5#RDo!Dc7zzifMc0bbld@<|FuWqdZ4!XPU zlSKjDD>NXjb`I62iH)@%d!2tazH|Vd2fN9UwU#|JP(=t0qp?*xqM5mO>hmXQg!ok< z!H{`NYSd!QbqozWpP?cu-Ni6TrXXZC&xGK~vR8>8{(;Mo0HUgO#3EfHy6Km?mwRc;x@A}#Y z@OqtdJ_-ADb#bz|vhqo%fSR2h%V2h-;knz%vbtt zq{WE0wY{DD3QuP5}=;|Ki-7NScsWBqa(rH}{v6l)b~lmg#9?7Z(>f zIXN(ml4oUQ!8@Ygzay0yRbAb-?by2#t~Wk5K0d#&ASNPmD~3j?ZE$ce?g!)fUOVY{ zjSEYA1ZjI`CrX)47(5N_+8^B0^`RWM)f5-o;4BLc^B%+TpJsO-%+iM?`WLdt;zm2N z=aih4hT#7&YCJ6~b&O4~e5CihlEF*)cx6P=%-{4&kElho{mH)g^S}6#(kz7!-G8}b z(|$gso2)+NNbm1kIy^&_uUy0>_&ZO<_~}yK;TK zvicMOBzboScE^FZq$lm9PyF_u7&YTE-v5|) z%2s;hA`||Qs5Yu8O&q|-Q!!GWTP~0o3{ve-`ywk99*$at|6|VZl5anC*>q`_I&XH_YUIV9pS$O4FuZ&B4uS=CzqqutR2@q; z+OMXj#wItZ(eSq^yRw17?7ZRkf~rvfz?UyYbab9%N=LMfk5?rdr0=}jTacWz&^I%q zLPA24PZJ_8)A5=-*2S{bi_T#oQ?B=W)oy|_Q(sqIR;EC+Vw?H0e1>it6|0NPh?c)Z zUTU6HzS4&~pnzFUjUv`bQ<~A=j&;61B_UJ(gMpUXXr34))sJFk0n)_V4N*p;yb*|1 zm&=(AP>gzcet$6bi_|^__0+}rN^*(G146u)0tEdO&@C$6C8S z*;ZPkbv1#?@#qT0X$k82UFyc^N3aW0l5|C%tr8^z{P zmP2#Qs2O!l&GtkNi#L!P`_n4?`C*Ikb}Fl?$YMI}-@R)c9>(S8=hsbR_3-dOz(7$^ zyK%`&J-x6_(~R2MFV)q2R@Tua?E3C`x?OfYunm8&UAY|i zRpyZ`BH)gb4=*o0KcN#g36}4VQqNF7gN8@q0%3R z&1Kh=6}h%LEO6doCqo~{ahXoYNHibBMiW#}Gg`Wq&KcSnpoKLt^Skv;GIv}esfE!N zX`3JKAi4`j^gBa_8ZKtzH~VBxMIkIh{zR{O;XzZEfwPr6ogF0$LW9obqx!#Io}& z&CUJ(D*EvyeJmjEP=%er)YMe5PJyed>q`RzyF8p9d3oZ|ls|s_D6XhzH)Ms4QSkN_ zs;a62L%u|INdEq{6b>({H#`H8iB0ow=BqnJa5*T=vvANS2qE%lm8h z_Z@EEzKtONR%PeeMV?r9MIZUu<|r*?@g@&;$uF6%8nb>NH%IE147wH)Tm5f$jNIJZ zpni#tj<$DphU^m!XuY`WgT{SPOV>$wp+@u}t#EZfQhn zys5lJ>lZW1SXT}saV*_c%nJ2A#F`_OPu48nY%OW2yWvH{52dowyd5?u&z5#$i!#~Qg`#`;T-Lhn&#MYkfs)k90K5|G zWh{+$(gn=si6?J)IA$(F2|t&<{==+-wk*MPoi75mUdr`9m`;j{inm$BCet=3yu#|U70GmFKKb=Ch}+n1&PC?!~rBRFfhtD$YOs~l*{2G_9Xdz z6LFt;w8qeB7AIw@a1qXAH(CmfFS%&tJt``y^g+vx?r!lc6*iMLbaDy`n@J0_X(bZ= zm|Uby?Ud@U0)I5^vD(Y6C1&T8TW42qV zb*7b;vCjW_%WTnSJmfJ++n($fYiEEObc?7qv3TFce8=;%!fb*0P}E(GP^3Ovv!OoY ze~N~!q%h-iYyUBtHk*rJ&GqNL(VBzP=HfoJtB%Bfe=}Wg9I@98Y^bivinEt3q%gMS zGsYNctTxnkKD%c?$?CAsf)Y+DY^(cZWQyi{qDn3$Ik|7+#|IR$e{dULN{ht<35N_b zumyF@87@Td+LI%hOA>h0_0x2*gH9)5fUN+_7T#3)-SO9&Nhr!U zf#*TuQjyYOR1@1>0e*Ft&l6R{=C+5%HIdx5&=)+pORkr=%CBpEi`m}urs&NsfAD1F z$eFrkQ$A412kPYj8JC`c;X@m0+6sv{lpm0~>FMeJ?e8~1u&!yb{>`tfBuG&VP|R7p zJUduBa^Kk4m_T>b`B_@pJUAF7`tkm_^EvyIFklCe`yuu^Oxc$lc*O%SsGdE0f3Vu` z2uCM4ICug*9bVbd+iSMe5jA?C@~*SQq(!#TGZzcc!Np zs0s)p+5H?Vr$Eb`)H0WU&3s0eQ(2768hx$9(^sUoZMpn8mSEoMA|7`|+4O#u-Lnri zGm?sihR+;S=tl7FeE5uuk2JTqsgPXoQ}8z7jIF^pXHI|7%~A6b8(ltzHowNGf-OF@ z{juDZdro_&+-#-ep^7;a6cis3$98D_O--zuyZgfGYWsVnJAmM;e{)sAQ>3b|-xoz8 zUAda-QMp-IGeHcrDP!1*j*(F!XDEGila7I*`3=`(d8J)MX(@-xtQWUQTWGr7Z2jlB zxajzJMBqMu{v4nO5@ujPz=JyvFid~HM?!zXi41rGzy#zZtGc>+m~C?t@n(x4LPGMM zE?%~PEv2NQDskD>hx38}DJui=ffgxmL!%8t#AP62>UteGIp%xVI zo&EjNdBYi_n^hor0XTDVa=seHgL?`vTs=InpFHV;wdZkMK~GFf#KFadS~_UZvIXk! zyy0L6c$SaSwJv6ks^uxmya1aoD^5XsNocy`wvy@Q9^NYFpTWw9`!9A?CVM?0< zHf&N$t{0rlR0nT#R5a97`kq_GRx@*kCsNFqjtAMi5yT2O*kQC!{{1(o!a`n6TN`nX zc%0TE3;sYE^%xe?*Vh*r4b5cWt7!R!hnpK4Odj>6@CU#e7_vsDq$u26U+LZ>)yTum z90ZucI6FIoC_~_Ym6cVo7UO7LYaP&eRDWNi=1*@&^<3TpyefX-5w*2thD=p{@tkzj zl5=9kf-AWM)(e94?t=%a>gtlOU*~SK+1lEoKjq5TO_lJS@oRGpoj)zsDDMGCN*xVX4#YHBcRB`q%A{JbKs0WVR$?e~W}DCp?lK*BL;4}W`p zxbE!n1U^Uk<;(Z4m@Rq|*kH**0gP3Yl|P838y>C=h7z#dwy;>W)!t8vjrEtxoF7OR zhmv{R*_w#Y$ud5I3Bi|rpE;!<2j5MP_q@3}0R{%=MD~9LH9`ZZy8JZ!0ePD2SvcXz z&8Kg>8l_MEdAn0%Gg}i86Quq2i!@Q

2ekEU zJtvLFe(u)M(UHia3Wtx6k5o8OP(#BFE}1e1C<;;$B)y2bgg+xi&?62Za)90d+!odu zbTXq7EhsWKokaf1M^k>5qXOw|X?Ypebzr_;>i)+MkbYEERD2^MFe#)$4O;>qPl3|c zvFrc|>iGCLB{g}_l9HD1N0AEFj=O@3ujqdV9l1^lGS9$ANMTSM z!PopgY=y_7KUL7p>-V%bxiW|PU-I-MtqU^cPHu@N^WJ`Hq8^ zYV<=Es}5OfDX_Hm{{DO6qO4%Ha@8$!)rWl5uCJl~&bm~mAVHqm!O^j^r{@<_w*!#% zXU}c{&w1{OMsS(;{pP#q;O5`1ts`H|cRE&XSH!$9cPTg=CapI+{9Gfq~9DcDgx_nQ4Uj~!pU zz`~HgxAk*Rn$c*}g@n=LOo7X*ES0;#>au)_JJ|0;x>N}~-z3OmfWo4ty z2&n4be-vN!mVi`Os*ah$?-Ksu&I9&$8)_i&!i(1bvfYCW4QxM^0>SJ>L4GmJBLT7n zF{tmpPIVuXWD4N28t%nNTQBe&>6@$`uJYqO;_#E_zJw72cSoqG{y7g-Rz45+F#Cqv5&cak?$^7> zYZL7fnuysiy%a@qieERnQl-qOBV-Edi>eEyu3zS$u^B6 zM_rwrqM3umcC$jaCT+u-12FAYqyAsM=#@a6!rtqP*_(_(OP;q2cR${LxDX{xB3hsk zqUX6|xPScteRsC?BaiExV9#Rp`K@Z}CDXPxf00$v-`8VzY3>8kGZJy<*SmeCCsCmj4y%cR*VqCBOu zNs_LZ^`rlX@lSzy>mI#?uLsf-zJaIm)&j*;YFFvl@r2k&n%{g8^{c_23k|a}9Xe*_ z6=0ozM@A;%93PShB-HHIUj!33^q6x1SAs$_IxS5J5Y)`fEJf#dSRK+A{4AuNMj+r& z4E+Wc5!3m1-ijJR97tJY=futH>z+i8@_vE$fq}@>ieF^xiz{E^?ch*j*vxxYu4rNf*}u_wF>$0$iztRDJbQ>Gv*6;YXU>z_(KYI_ za4|x|_~g&ReLcRKhN&QZ_Qw}Ak3qOB_z!RI316R507^i@oCh{7jwwj#y!Y7FM7x#{ zx9?|j7+Iia3)aXL^N;w|zk*MmJYgk3M<73Jnz;C#Xi7H2-?u=>&^g*fh*B9Dw?8(D zh>Cu&c~A;P2*xh^$TSoyz-AEKTtnkid_4Z0`{>WOxhurG`%T#iAZs6h;>FA(SEXf?4D?)83HQ{hoC_uD@KCpTfBY6^p(f(rG4qcHC3r;)Th#EF z^kn{Smu!TB{`yOY3CuoZm78AP?H;<|kGDjM76s~0;` z!%XT_Z=s{jK=tqU8buF8_WqSJCJwClTBURJP={(>>@L^GUfP?RMJP%?^4mc`-r85_ zk)wo3HTMhO^Z<(r3JZhutb&Mr(b~lG)K9r}f?>Ai5cE*<9Ig)mku@&Ud24U~ySqCC zu++Fji^pY$2&z(e=wCVoHkzeFPQ~z5dm{+YQ(k2t&13 z$CGse*n%|;69GssXD)6$x#*ZO4{HP$Nq$d&@SCBDA5QPI$BV!0ivi2TJwWo1#|0E6D4qNNo$ zX!)(Yd}Ku6+qYK+Sf-(WFDAlp4HRN7jpw|y(|PRk?W?5dDRya~?PBGp#URh;5EetK1ZMj!RLIq}N~VWWEI+?+kk19Aven#Is!6B^i%R}F|HmGAN6zE0LY z;Wn^;iFIWvFt3THTwahJDb9~I9+ebS{{435s~`h=oR~$L$4{MN+ti3tEn+SO-%Ldf zxq8d1>~(O*Tx3I_NM@s8H}W?tCCNG>7Igw;?1e<{ zG`k@;(`Vb=y+nM8;Ul-d(j28d{mMeSo7{THdJiYNcrQ<09)rHE|7pO+zM1!^N4<{2 z_;q82@bLUe$Ui- zAljQVGc%w~m&avHGb^SE_44o5Hm|1n%uK2pwS^Kg>Xzs0#vjz}wLPu9KHr>nuARwN zqaWmEA_a!K0_DZZuFs7}Q4iIsU5uNh4fScCvGu+~liAlR%O{uxGVR|8+W9*-6Q@Rm zQ$A;fdUHK)PH3$q^+*^U`Iga8OFQU6lvkcVpX$YOu(j!t#N4F>dZ%OiiwMNs?Wu&{gyv9q z{VtoWZ+!8BJ4RzVWpAHLxGr=*znGuVJ- z{O@rBJ5@=McgIEl{R&jBLc3Ijdap#I0~h09ogRL1=YJPIzg!ihnOADI(O7FAznBt6 zRqoa8Tq2z{e0QFuIlVj1v}J&IKcVAnG_S{?B<4#}`6o>C z5fsS_-0MvW1%P^Zh6G`47*};?{RUSXnjnIGuSgRs`cYJrQ(2j?*d9><;xuR(w6wIp zXJ+c#U0652zkh!Vhye;JYEx(D`VWQg%MQE%s#z+pJ;DJ2qoc8ox5ht8WkN46s)VF>F?Uko| zxukBxuA@#dZ59$5SMFG{n5aayi>vw&AD-|sG_m!MLD(V*>A+QGVyyMaSEiZfuGMU^ zWpgpL+j*&O35{N1ma0O=M-S*Mk36)l^id;jvLuI9<`wnb-RWl6kalTT>Q5PCGSz5% z+}SzPexBE*EPb<`8|S4Kn%zg8XP!QBu)H~N( ze7`+GI^^WZ;(|kZw+1%m2yZ+Yt3X+pTQe?Q*1L?t{8xSeSOWSUrWGJ#9yNXzH4%zOF(WBT7`L0`piUQ zz93Z1)SR3+pn-h(@&!}KTk^z5ntmk4>m>lf}W!*wlfPWJIUs(hOooS#@!{xZC|qD4|a zcwb-NLqaI&H1}#j<6Fkn{zDC=poK76l;sWr7_IJ%wrS5k9wy$=J?;g-j zHg{DVe|>OiUbraiQ;j1*7rUtSYe!!!PH|=22Y0_U_@R8wE^bpYMr7%0rnIFy!L&1{ zm)Pc$4tP}FA>3FCd|~YxSuqDim}e_zNAegUjY^5#e7A5QRR@W)P$@7_)42I;WG>%tjP&R<`y3Y(Pa zBntZob;mI+&Igd(u8L zUCj7IL_MK|90>w$?Bbu$8+&^Tn#l&w4pz^$O8Z@p$1SuQyahoayF4FlSScITH@Q6B z1ABw5EFd7l#4I=#(kZd8$v<$%Pr=wB&-dQF#TDJfTMx>Js!*{Ue`y1R_qd9NUy+L}B_NJC>F;C)8 zb?JkK7dVb-Xf+vWp*VZD=236msa`0LW78v5wK7%}!Ec$;oIrg^sn*YEVaqB48#r3e z5Z|O%)MPh)EpEc{qut=ufD~0+bbFf8GcI$Yh=3ZCpH8C!xS>AIBkJNAZOsyUPEU(! zt|xmbql2I5JR#rCHt5epG__%BCt=;_!|#?M+l*J?+OdRI;gtJN*?Dx0{e(Z%WfX zaH$nQYBoFArnGU_F%enCmfRXf^)(f35qi|J(enzu{ZB`6XerafE%c!hPIkukI8tg7 zleuA>=18PoPV1Xrb`o+J{r)L$bB^u7zyyQ73pR~+k0pBQCqHcRMAow5%nmBQM+Q8f z^Hy^f{U2f9&3gSU<=)FjUc2h$+o~1rON8^d+O{|S(HnIk{t&t zpH1=YY%$!Q4}YnuYO*P)_Ue^9lspaBM@59ZKf?;ceC^Q!gMz9GztYmv2jlCz&fo7_ zTN#~-p@AX@Bwes&O#Pr4>}_jo{4g-^5|{wE)M^Xge+Prx|3n8jC*rfbQYik%-GZ$sN>*nH6y{tLu)9PZ2sc z%Bm6cyI;HMOLPtn4(>RJ&Sq@{H!{(Dcx*kN+7qI{m)9%6+qg zp5#f%kLk0GUpmi_gVCO@k{z_3+%Fv6NId}lzChoY5}M6gR%6bH?7|FEN<~3vC^`f! z1X^2ncXxS+QiJ!EyN8wU02Qi##xRD+D7*8PRw~qgBniX4d2UtO=H}FdgoGf9xbRRy zgI63Zt*>Vr8<9dilgrz~`*i*Rd;r4T0|ockm=-7$trj!H zTh6ad9}Yl~2}PuhL4PuLQGkme!_w@eN^%?uVaLE0<)V%Ych=A4yjSM^b~XE=8`){U z74V*{QpOZ|$;Cu6Vh|DL%Z)joAUwbQX*7(Cp`g^T zxgW00q$WLc8VCH8Ra9JoW*~9(O=g5p7sy<8|MG2ZLEr_yfV(>%h$+x#C>yUlcYuxo z_+WGRx7-DlfS*oQv2`rE;#@D6`yfLF}2^qk?8k;8_t$Bt4!|Y z`uIR;L1yxT{PltU`k(!rV;Lxh?qg(Q(WCz!rjPAH4~r#YM`>LimcuL5KQgK3HKx+N zC+nYzTAAUaS_=0jv>7%I*NOAz>Us2JClP=A5R4(5y}Ifa1VFY7+{uHM7t)x`%@ z4*Xm?Pd39f_ZPW&8*vBfkNil;5DOO>8!M@zf;H=NBPf>@4ccF-&$Zk6$?hzO&VJ0$ z4WOiL{|%Yc}G#>xX70pQQu8c5F{NI>=peeygw zGV&2d0UOGONi<;?ub^aI{xj?9*C{Yl4v7Jv^5J()* zYvpl2q=j$ufW-AZtS=}$5;Bxyhg!R-PxH-6H>h63{X3qtJ2@r#Q@;JI{kE&nZ%39k zY>%*z(X}MO%ZnQow&mTqn9r?#!mh-)bfdDUYU$CUpQr*3(Xoeitvwj8N}PV-{iZ@z zKZqs`c=7ycb{?nGpw(p2t8El-dR#1b`6@zF0+C_!YGd+6OWQ?*tD?HYJc`fP^|VNJ zWC35q0&T3TQiY<m}yrS3e#5gC*8Aw7-M z8(v8DThm|8_e+u(yCR{XsV;WE+2Ypfn98>FmhU@8uYczhh0G~MzRwP6OEwejyP-E@ za6$D}*3!!ro*K1}f%ce*caP5e`1j z+1WHO6WK$oW~k(X(W}0&%FV;$;9oQ5!Qqe+_T$GNpnKHU*EfnDbm%T<;C)5~%{PnQ zr02JwbO#AK8Mc`H?Se$P-K@8s<6}SF)<0P4X3G2L4C07=W2|5 z%f0?gbBOshx7cq7i0VCMw2e|@=K};iwDS6!ap{3Gb4h@Ca{aYm3m3rCc6w;A4h&k zd(kFKfojImTk7vY68JjbxJzMa=yTrZ`^2*?m*b^DPlZ!wci&V;Ea)3IJ;iS(o+xP^ zvCfN~vKvp;kx{J1JLgK1U}|a$&tKc=I-^Gxi@*|%vhU`Fcn4pDP{a9f(O8`aH#8pS zjz$eEW@_C41dfjn@20=-K3}Jq@xHL}KB<{4u^wfHGk_FH83brlYBfxc_}|Bm9}im5 zNtJ?OBpd~s`tb0VogC1)G;avl)0eTi^G>=SAzl&w;;c z9mksZKX-VZ9hjZh%Erfu%QpI)G`{2_3c^_ns#9oqcN?b(Q=bI(GMi}ypzsy4{<&G)~rR-%d2IEHcm6Um9jFr zgj?#DLt*OXb!`23-!8Bdo>C*Z*K1V=hONifHTiqEE-x#D4Zp456W~tg^;h2SC=FZv zv_7Y!uj4W9VIpHOZJpdv{2qrZBHoE$31>j;2DY+G@0-kW(kso4u^M<0)}x<56FXG?O|o?EZ=&o!9?M*5`cm_odJVwNxL<3nf17-YKTd2%t}A4ES|t z-O~D2yx~gy1zt=IogT8=+lMbAgnPR_hM7=DxV^WJy3AR+f~-$#&mZdR)_mlwOAY;t z!+xuiKXlx#t~L5Saf?@3&eK(Tw(I55#MBEu1JftJZ)cZQEooUcXhx6+Q>EFFE!C;# zUo-lDIm9XF7FI}%jzrmG)Tw>HCptZbEr)8p)3$wT;~Fx2GbY{_C1@GJIh#%Cxng{M zY9&C%6i;#7CZM~Y*1@mqg>tj0n?IQtUcUS#>R$~@Dpj|>(SBriyXK>-Nv1dI1!iXx zy+mC~%gL8`5h0-3EyDoSPtBPBKl41+oa;N62Zu!OMga9{b_7$Y!g*nDOI4e7_OT3 zNUEp>D{-3Vevl1{fiAd=!O$gMpaG*}<6waF_xC5B=LOxa{&0_ zED#$^BA5g!QQq|X@A>&X8iGz>?Luhvrlw2JKQ)EraC z!&d*bAB}qJA^YxV(*HNoA|fn&|Kfq(4O^jRH`{bA0TEH?&pP5Ncav16#KR@im9I?C zKZM|WH~YSHbKde~U0QJv%WGbO9?^iIT9>t8pI?1(Bx=ZQ7CWk73=6{)L4$jumg`cN zL}c{Ae#veB8&NtVbAY>*_oZ1r7Aj%*v;`p@XM0&E@*faB}}=-y<^RNq|U1 z*9%;Fkg8UHoWxLe9`j}nTS51acxHd*4OdKZa!6VlDb(}`+(u+OM7tCpKb|2Dt=wsA zj16qwgm_(-X+&pF+o<9=wrN$v{=r*P$QTd!WDSMwx#2a6>{ky)PA5-IOIb;oS8ck6wbm z4*HD(SBFC&;$&CkP$5r~g8>o>RA`0Rx7wV{`UnFekgrvJ0QL+DPnFe6gke)G{rC8I zB8*_b)Rv5%-t@aLgkuk3;@#UbI{i04HaWRCH*oAz1fD5K>7-#&9~E;+0%E5&0Dm0v(U6^aWz(AxS z>%hQ({V??~RE;#y*9M!%;`(~fe}ilL)$s)SBv?ngvp2!0WqH$F7JWou$>tYG{eKQ3 z3*cA-nL7Fc&|Ts{c-zUz-92=C2bh9GLZA;#2JhF^)umApM!@C^za zEn;*4PWu@Ik&c%EbCM%9H8F`L zxrUOOn)+Rh-urT|U1OFzxfd*BP;tC{_inkcW+wyqMzg50V*~{p5jYt#a&ik(RgQjs zeyotdbSq|)s(df=J?VSi->JlW;@{x0imCZ_h2RWV!Qk+~;_p{xBKiMJ$D)<#JC%qH znK)PCyqPvGff+-c=@DY^s6dtj%P+(W;>3Zs2Bs($!1VlzxnU)ory`@NNen)B4A?D{ zC}ldmpXpTp9UZ|$5{g&_G<=HhNyG=BoJ=`l0y|C7*ZHdsmAqxX17ctad@bPC25+m4 zY;0YfS4HUX<=OqP-Y;+yLx^HdGr%cSokn0EaCY8_E2$O-hJ=EQJh#*tqsfStUs$-( zTX4Fp|+H!k@A0z^bamX?-tP&tFu z2Rzb-c07Q_3*?8uNGM>8{R?7Ga_57XV9XK3-5FsWU!7l-U z!F7R~*lP~f28acOa{;EiS9%h~O-)Ue1d0ELZ=#h(ws~LIV3>i2mlxsMb#P$EXMXkd z+c&?zf7Kviz+$h$9)j@$Y`g)$#$n)9RrO8gnVO$EvY^4yffr`2?bq zg6RURWChIm;l%t>V4>kl!T8_c4wS@*8e2`xNz&vmHjU!g_0G~#%cqA=U7?glh?dLF zB78pA0)SqC^0#1IPD0{t47CDmZ&5|gh_#MJE&xNw*DX9vZSB|Azx6@O+$e`paBya( zB8w$GWz$qsEA}|C1!E^f#R6RbWNvxc zALexjJ9iDeyf>GsjQ%O@8@81fFq(U-9AueqCGRM{qXULso(Id)R-o zp2HfQfB#%xU7W3DMrc*qlL59^fa9F|^0`%nN-n~7^hL-kX<}kR<6va-2tpCzoB6Js z$(kq+g0~7hN*)md9bNj@ukT^357G<)sN)erhUl7N|K|lbr-j2*q4&)ggitK42_n7Arqvg0u2QF?TI(=mIYz-TG+#a1Yf=G=4SQxEsm}4&nn+n7U$AZ zi)(2_JIDONs=&g1QHpcmtheD&v@-qcJZ_{e`>dPOuIjKZsS-Dik~Y%x>$8k!^c_N5 z9QhoqtPR5NDZY2?sH~p3o(5R-oqajcUSUleb!#xNlb4r=tOVzr-FAwn@Ku!G0kYLZi@TdsP;6*(1cFDotlrOxFpFq)$`urI&R)$ayQT-P_ zbUdkyhj}s>K#7#g0x&o3*BN<%{fF%=FSjTj{%2x=6dEVQw5fByVITu_1)bT>%i z&qAVe#i}lhg~Ei!o2kku0Cl0uf6XKUs@u&21Cap3FashkCUzSR92mEN|Jpk`n!vz| zn07H(^}w#ZvN4<|Aua8Awr>WR9}Hh};}&VlUIr%BrJ2feg0J}cKVn{Kil zx)dFpcP7-mDWYT$PCXFxARd6;c7R1TZ&(HJNG_|XrN!^(PxhXk9#&4yZ$KIl^FZL4 zH)Yq3Agz%ZMNkevn8(+4u+*lQM{p|IPe}3c+XpkHgMx!$)aETbNTX)X`q_O}&0%l>kv~2F&KaiENFl)V0{Kr0@@1*KMqZrr*C2+p?h5_ z951r$5%z$cPx?hUaJ0eFjL`h3|%}`GucT23xYeJ_$%m zFwF}K|0GOm%s`b<;Y4PrMZZ8JCM6|IBM&I}9W=C%3&#wJiC$GDK}mUebeP4FPhkB3 zvf^ya)y_m&$aIZMOj42@pgK4rn=H!9%c1Txw6f}gtARRB_ZFjMC=piXbnyU4)_$wW z@U|^260Y^H5#~uIQ1Ky?MMg%7yn00h6J)Qd93;o2V;;c_(s)6;I>-#!3dsbJiowUQ zGg87IEJ5BlHbwx7BRENc*NAbMDkwaJAsWAcfS9d)z+^kR}Q50YqtgaenJ zJmcZ1l@H zYb;efW|MIzrHKt|yo0GekoXf>Rt$pKdhTs+alR){HsfPs48JKzXR*4New zAXuSQ8O)WMn43$zdsk-IlsB{vp^}}QEmb)Ke?thF*xH5%1);>n#Q|tTQ6>(@7B1cZ zDF?!hj-Fl&=H&)0-+y|Ob!@7|86*t~;5RVflai**>Lt!Jw*hNFWSTyxcicSwKvOwyn8`0A74XjyCVAltt&bMX-igv4Rg-&Q51<2mLSEn}=H}+KIH>0Rsb0Dj zZ7ZuDJ5yEQFRs7be-X#1?OR%UAQ;x*K|42=?DK4`fsh+t9WT<=6uVSO+em$M!dVBa zqSs=?pqbXvJI`wP+x0$EvNx}k*4F6OjUkq^%Xkg_>g}MtjX1Or4jIP#oM#WIUaQca z?%0?!jf*ZYoo8`zM-{VRqwr(3CD~nfca>lkY5koR-ub_TQQdTh2}cr=%-nCJrsn3( zt}d~H`m>LJpilrWHq_U*)`s)&(eN05kBs1b9U^3bUs#6V&7`FL(Cat_IGe1qiIEN%b^{37EdVaER0V z{QOFXWz;8O*{ugv&oM}aLZKo6mwZZa13&03FgJrz?+lo9_x}Cz8eO<}9OYo8_rELi zgm2C;Vd%SlRd2UC_`E|$gY*qGmNxJF_VQg`{J^>&*<}nru3tYF?Uf+M=EwIGNcrA( z8atL}CGuh+-tOlFe{@lH1vBo^Q9{#a{Qb^A6pE6sZ__imRcp7>(-<^VzMkr86jjq< zX;tsJCk<@zj-&9JI4d{~g-x;8^oRm{g>kNm$~m*DHaLx&R!6Ok|@;=DB`DlZ>8 z*KTBK83_F?IID=<1T@|rs(Qru8l+gnFbYfkDLDi)@q_`4>gFh>EWr7Jq~$o@bPvul zALl1v+Yr-65a6&!MsME87wOkQt@RD6I>_~+epShaIMDEP>=$(D_k;V_$jLmu|NM#N zFV^@&J&)vj#UivkVN@32ABdtapdrB;nI`<yQu&V`!ChT)ja!;|!>H36JEkvZw3FCFnDwgt5)-vU&>uz3VnSYr;4N`n zRYb&kXXj%fM`vgAt+A5Or`+K{eh|?C_5etVo?s=a1*a`B9t8|jAj*t}%YC$XW<7E? zHsGb7F~Z>adZ4@Kwj8Tj{OcFc+WXMx1u~nPpT879>itYW;0tirY4w+&cf-%v!+b9pA*9KPqhh8}Cq<~+B* z!>5(E70_RlZlDYtF$>mh2Pn@h(=S{?GJff^S(sjw%lP*)~`0Sj{L;qEMHmP#kE zE~K$i3rwi3RzXLz8m;%fI?}Aax%MzNHilao7AMNAZOpHxx+2NMwSJnSG&VMh@xm-F z{ijc#0Ke~}6Z{4*DuJ-K08}>l`gKWm4Oivyll${^7g96ISghAy1KgomVJ3BV>(&c*_+zhr2aqEefM9FZU4WSRidaA zrJJpUN~LH?dub>kEfr1LX%W&M8nlO|*7tc{_kDftzv27-!Q*my z&+|OS>-Aj6Od71?m2GWAS@O|ZF8wP2J5-woJH5y4L>XgWWX!W7ePrg4SFCZnBc(se z7$4HKv}@0b?eBY$kUt&&k;Mn}4V5UNYJ(bQ zClT8M>4T5M#1{0ECIBT7y;iKfTI4WEdoh@P7#IuoHxvbJ$&`k!1ZIe(!JwzeUQJyc zt0pGOA<H!D)b#YeJ0+-si9!@SNKRg{rt-C=Yr48hAUuhg z_$izd=)+vA0&mh)cG|T%JF{y_?h1ysXEmfbk4n`3X-rX^H2cyEv5Jn{tZac*&!>(& z6D;MUvxB2lCk^}qN;$SWlkk`y^561$W`CT2%ZM72^^JfxzIT2mtEyRln!6FmbnxCW z6`lC|4W7cGFU=2FdvL4yD^T;~*YE4P#M|CGlc?#DbH+KSN{6=NxW@O4I$jc)B)R`C zIH?Wdr=*mfokgG()5EW>s;MbBa7|o7LjAq%3H;qWrwQAw;<&g##D z+hqPSURd+7IsuDf4wv^?j|dOn<8eteekzD5Oec$4{ukbhd9Q3aB`O{f`1gsvp6~~2 zJbZ$;FIi~Qp?V5B~b)Cza%M zoYW{5d2-klp1@2CBOsSp-# zAR+aho2$C`9!T@BX1rie-~^C)Hew&!{Q={wz06&#eB-bABSi~DH__105Ln#Ce7a=L zt?Io1`r%A7fC`3N^ny?*t{k2d{C7pbi2MW_+u+Zi6#yFH87=huu{S8krPoaH-Rt4n zl#jyv2DX(>j$dw#w1j~_pe^ZAZkm7%5&|F0%N?jcCKe6G98LNCb1w{(V+fXC(vi{Dht$Vj>pz&{wlN$SOS_-)sM|SN$+7FLc z|KEl2bCs#xsN)D3k$RqSkG<5F>wgcUnHGr3x9TanaZ2ARrXRqso~dd3RAXp?6MWm~ zqMrdb!dbf6&VP)P)?SEQVXceg)inl8i^g(>P*Z}VK|NtT{vz$iI7oyO+}weZ=5U>}?J#f0F0c7az)7lnlMaj@P0QB1$a~#~)!7UUVNj{xtQVlH)8eSzgDs|>>McL>YiaWmFWW?yMF{Sz z9qiO3@z;zhHB`!LB;eP79-&kHWqV~snt+Z$@ckl|2yyWeS+;~J3V$vxE+SeCj259wg8Lz#L+G6M?L|;( z*2KS|Zo(RE#&}3wO%2Y>x>s3cL{%huSQA(v7LpNE)xfwOvL!feV_;wyvUN_c8NY<9 zN$6s5B~c(F3Nz%rfwgrDuIDL!{uGQ4p!#?Us49w1^TJ31EdY&O0uTG~JB_dcEU&H>a=6ga(3~=?I}pLGSp%j3 zmQq6_qtlL4S|2N4`A@l&MMp)=_(`ta2l_>{$#5k}qxp;NLO+sgP`e*MHX-9fC-MFY zdkg>wq7s6H%doI&FPXY3vDV@;Ah+etRw5-K5D-0x9Ni91{`>2;O@i_o*L^wM+W!sHj z1G?Y&J^396vr)x^Jz6DB$}_$q=x~Fpy1(5R#~?yS3>DlPs<8Zmhrz)_WYXohGoiT2 zUIZbBdkKmWOdL^D0^)Kw=1MfgM16AjuxFct5j${AAtEq-XKZp3B zjD|mWeyXR~+eC3l|2W1R@mo3$Ch5;v;Y3Q8qbhs63ukSr@gG=v&-zuJfSjz@7_v>W#{J`Va(&c z%zmT}aN%^S=y{NRhWpv@#O5U9;&(wOVY9PGl$BGvN7wy+u&|0)8C|4(#@YYj;&}AH zx>ADaA`R!m&Z_Q-f;6X82S1{$TW+RX{bc3iZR9m#UO_HYzsOz^d15W8)a`dKM%SBHOlmU?haV*tT2MC*#|Gz_^o{+=U{tOfx?^K?|)Kl)@O{}_qL;r>Sv%tPj z6Sc`sBOSA6Vs6(f1+j369?oxmAd_)e(&LnWvAKn++Cs!uG7_0imGS7M&aB6|bB0s9 z9@*I6@wq_FVp(y4systKt?=+z)pUEFFh%}>lr%;$(4qf%q&9R@C%piYkyXAC1724@ z8f}Ml>4Iu369FEe&joTuppD3?`to(4;2daMUEN?%QkeAMyz(mz;v_xk>FDSzEG)8f zbH_dpWh5s{)zPCbmQK1lQ!BY~kUDbl(1mW@7*TI@K%vpmm(alUZ=z1~0_`LuBvcqr zj`joHtQ5>Ww1FgvFf`m5LpU`X|;0J{>q@Wp<2EYKwGOh=J zwF6?D%x5AAP&3H-S2wea!QE=p-qg&v5GbhX`1Mz&ky_G)@An-KfYc^rz!+Pn z0EY2Yw|_m;w8Hjk|K_LSbXxhh-|O`!E?G6I^5<22k_r5~zjjJsQ>8#Rq59{fKN*wC zd8XR3vg%e1GoLUO-A=1$y$VW7HhssLE)sqDo98AzN>phy>8lo1(d&Dq`(|WtK&WK(y%3O@ z7w644Hj|x#_)nq-5e={ZdJIi3koDu3-6$4oK7D$5Wwu`xoD!xWRG4pFDNupR7#gww zp(hkKgM;2uNxyBVTGs*I`Mr3-j#3f53aa|guWs@}MIC^~stq3O1cFFHiKhrg41gRE zS)0WP^~aAN6S@OTc)X74*sr1hj6Ohf$*3_x;VbCvvwu zILA{3?Uq~H3g%Xhp^zm|0jxc{bl9cFq-NeQN4?f=s% zwv%D(UoF5tOF)0ZK3NdZ7M*YXA+XX{4=bYdw4?(rvhPIuT`ZZWW0Iq+rJ zB0yE!y{s;I{@m!*WKXOL@`#+A-W`8~Eq4a0_1^EXzs{#-aJB-OLb-A->jzMYoVRZc zfv5ozC~&5KevJe24e(q(n5dYSaEYM>x{3&EW7pLnrf~VwfX^x_h`t3u9b(tZR8>@< z{S-lv3evBLAhY}T@3#+32rHtKApk4jTwX7JkBrpxZ7d2C3b9)~;J$&w%7BUf+$dCv%`TrXU_0Tx@4}Y`__zTc>&|acl!&>>l#F&Yd@(93w$*C zOIsFGMq+t~L5gP<$^>842FWrybD7z5i6t!m@$}c#IcF9_LB=<+t9ZAE z46AqgOv}28nr6ty@S}o!oNRFS27H2ol9B)_B{$djp}ct)so#4T!7~;XT!1_YdaMzKu}TAwv!uIr`Kd~lyRGm6 z8wT$31(HK7SlC++uQ|~RLFxyXhqAHe1Q2l7C1av=fB!yzhPj9mmke{C$o7$8x~>0O z6S_#|)8h*+NdlK4iB?hh%1CKp`mRrqmJH+M7#|z8^O=l{3`PNgr@&3F9eB&l&F#E0 z90`BL)9hXh5aN^-ILHWL5Vt5puQiGX5GCF3?s%ixCTi4h&YPmwD@L(ZWM*3WEn=Hd zz`8;lG=ZgEe03rZqfXDlqWg>VZyMIHcDE^W`PE{66J><^ldl-QKN|#LmcgpCGuEl^MARb19MR ziG>XnV-V&C;9>j#-6>OAw{ld2>AAUt9vK+Whh*7DICAFVBZDG3u!rJ*8u`KX7pfsD z-v8ml<0zL~JGew!6vz13LSkApF+KQMJH1N525CGiE_W~-^W6Ep!} znv8wRfZLD~{URhVckbMYL&)FTw{KTzEXM_m_#i2HihhEEfgxD_`$q3I9I<46v$h&o zHe=XJggSv80lIrc+{xxoU7b0w<l*5p;)C~!y`JtZ7#E7+ zdx?(be@L~=P*O^*Nj7SBY_u~#GiRHG`?^O?+$Fd}dI@RzI> zE{txaK74pjhcrar7-j*7IkAD(m7a+c*)-xf;isyoiqdWrP ziAafaIDPfs!FDjzRUvqvEbvWY#A9Ra{-T76EInQNw@_nKlX|w^*7N7jW0||m9vgE? ze_L09BZ(0j|LT+ z2Dr8=h+H)_yQtEdF|>$qGic(_sQ~KoI%g+I^fK2^Cf!vB`N+=0V|7zC3{57a3ZPl+ z-%Gr!^Tr)@tHgD)qV#|EF?~#*!r!sHZfF*^4Dw+m{tAx^8sLkV3<${Rfyv90U|=72Ju94Q4usZcN2r34bY$pz{Lbs7`b&j z$+K%2KyVxn?T87HV}a6+7_WAAhf4iDQqVpTvE*l0C-@27EF*d1u0ZJ0C=MN}!qp@g zE-by=8lM%OUjz7B8zX2Qg~p5^QTh2Pu@HdAMUu@gxHqZWcsV!@=K7&}#3fuCRr0)r ziM2F1Gv&4Kk5__TLk#zX+8QZmsfNeR@971(%ryZVo7Q{dXO&blu9w$GZu!4Wx!m1F zh8l;E?e`u%+J_B+*gZi@6Ro#Bc5pzwxP}DZ3HAkS?}3J9kCfEs&u4KF5F-9% zmsI-%DRGbqCe7sparFZqrX9-Vkr%y^_H`5yn&ylTSm9^@CHw5;Rc)D?9Y9K@Med`&qv(CJH1>VGpm5w#8j-0751t1#dGn3d0Q8FbxbUzF z<@%*~*qDAgB(J2DUQ%+jREKvrJFW**tuUx4KthCN2v<_dW^{L-3H7P><=i9^EHx+! zyTL=z1H z5DT+ydFALS3`S7xh+k%*`Q*qlo_R^`iTrakAOK6T4iQpbY`U0TM892Jlpt|HPCII~ zTG?>Aw8{4ey^(ZS%e!#Ouo3HDGrFRYSFUSlbe?*Aj-nPJ@eWM;u{l9s|g}Y z=Q&!n_L)r2+Qp@FS6P23?c4PB;&Wlx6_z=h_$&C&_N&Spn$OakGe$0uCLR2B>E`|X zQn5kSl>wf;UzsdFXG(=$%NW8@BZP>VJYG%!azvo^L>x-jf`015E`mB#HC6P~GB|ESKc5WPFml7Cw8? z(ZsMxervJU^^?`GbRh1X03b1Kt{P({*_o9LwKQ_z711By&e9w?q7OM2z+`BHrXtj2 z=((UMYDZcCtkc8NY!rcTaUr_}$kkD(O078)C)uH~!grk|&P@TBWe_ak3y3#AY+!p} z^ge!}qsBEw+xS|azR0P#olU8#{esr=r0m4#6q-%moMNv3zyQei^bZ}v9bI(PZJlL z&;(+D9ph7%fH@lD3C%T*aiSS%iiK&wB)EF@87x_sl$2lxIs%8)&peb2Nu}-=H5v>3 zJlWFos_YL$T!=4^AGUpe`~a#alttghWHe5O6Ke_dy11V3v*@GniBaA31!>Diu$K@P zOg{Z^TTkyCKsj~}j*tJ5%i<=wmc;gB76ipAJJUN>BRL>L5x-a_!ysg}!$D2q}87X)@}zsbQiLDN{skE?(oJe=NM2 zrtkDyr%$gI5B{dV%x<8@VE?2);qA!R=XuuE8m%UlMooj3mltlFwoogh{$;Nj^))oA zBI2}DvyS|(os{%>^jRa4c}7!@|KzffX?Zhzn|J7??+T65=6Glf8QN z0Pq7UR;6pVR~2O~#%}Zm{|!fMbLxc)^V5 z6aX1N875TOsDE~D#R)4kXd8KS%Nnsx5fR~-g*{gDl1O01n2JJ367Uo3?hYIc+#DR2 z>Z0rrl!fAC*u>m5H!!gN%~p@}mXhKm@l{US^p9)PrDud~RbG_c^{dm|=}O$r$2F27 zF>g-jJ+kBEbKAV*+v?f9q5@q)z!-g*@ky!3v$YkxPrkUNJdoa{N&V>h>DTc;TYOCq z=hBe1ofez1wyqCVl)fFhH$30B%lOtcM=zzJgWWzU?-Em|_f}au@0KrP3%1!`aFU8+ zkM>l{ywczox6sEE%SYNId!>2r7p=sZCI84XyD3V0SGSE}pGi}D&Aap_{l9giPNlR` z%aU!m)5G442OB=iOr47~d4~o7OMwjxi2#y2^8+FN!Z!F?BY!VsHvfq;mDT}Xe!9$p+9%V3SJ%`nOE)6-}!Mlyjy`Fp?_PG4R=k83CW;I;W2lXWN8Sfhu+vwW; zD(wlHZJr=!RNuAuRrR2oLiZwXmeD{hqlMgVqv_Kp?&=)$6n@yP7-?>V?HRu7_vQ^V zBZTf6dYwr7@wS1nu}@G0qqHRlW~2}5@U>cw7x0ZIadDRs7)6|f*Iwex5ArTPz#7#% ztOdSkNDC~xYLHC(fa~+bbM^Oqg=BiEaHkwb$s6&X>UftDd9Z&Jd*I`fI0^W|BxwE?$uFo zr|g~+L@-!M5ER#=M+%SZ zr&sfSZCy7BPkhw*&FiSaSJ&KfP3Pgpok4~iV)l~2E(ER}s%(4SGN8|SktyHE_Fm@MNlu>6y(W zNrRHwnfcYzO{#4n^acJ#Dz&HDF9fCLh-FpQrK`_-?5#$&8M?YRpBJMsfYd%bgVLYRf081P#hy}wDySehccQ+9U3%~f1J0_ z1J>8WkN1DB%DXcX6+3>&C%e&+)Sx8MSb9F*>uT=w_XvXmpM}BkJrZw8`p%wHK4YFP zxL4{*HxtE5=Dy+n;>kZL{_0Bt_;sg@SI%GG(&4J!erS_7kaP5Bhd{o5N9XSmzuaKi zG6NcZ5AFfk`iWJA%KQ+T`p`Pd87Jd|u}rirw;j&JQb`8-Wv-2gBo+n4@5$6y&N zxN_{PQ#?!EF>xoCS=NfYF8fZaThlEOgS+<7b8nA-^7*ib*YR)f(j%C@Jmr2cO>CZ?=}=t+#S#S-YH^P`4s;p?(6Gj9ieftdv)W%8R-xnt|mqhIX9-g}r3Q^z4tx{-_G;3%o=!0VX# zqp>kpR0U=0A9x(9i$2>{7}+n7q+tAO?U&l(6_-c$0x#`u?YCqaaoRo5rIhQ~+e2!0 zW9UTffkfMeR=U}$zAdiPX8NTw<;(o*DKyucHVuCZu!mK2tVG%@PU+S!>C?@c^Lw*I zhj>m6UDlkI=BhckX0;{rqIFYLs8FgWg*+c43$MDg!Y@iPlf`Lfah_wpgoS_h&a)|e zb?V)pni8rpDBel!_>_gMI@`L(uEL<;fQP{H$Y007&a>OnxeRp!NE#>acz&Zc4}3C| zYU5CLtodV#`EH2<`aY^WW7JY&`M737B(Tq<_e$GZ@sz zHo5fZ_JK!3%SxIGmz7D)(^pj7*`F>jKk4{hIFUZiO_-c{GJ z6`%d_`pDO{-Y-v|BpgsGQLKJ>Nz-3xo2#%%$%PkkN|)F~EZAP%Y7Q$D37NNlwOd(Z zaAG7V(w%;kL;h#5$w0SCeWYMZ@dGX7$%K>a_k8V8h zi#M_UrZZxfx=%Yrt!ikLELxUxEn1O%SD)SS5>1(8C!s3~1~;Pi8ZN$*9P``mtc7&$ z`L9L~7$hs3AC8at8~Daz8jPy@Wq%<5}g+*mRw+CliKVIYp~=%Uej4$8rMUydu$C zfZEYh>;ZFuunJ;FE)q!F{j|R6l5J5rQ>+iv3%T+-@3NF1J`{g!x_h%Wmx?LW;vV&2 zx6zRHV>b1U&c3Z=r^mNxK9p&*Dtml4B8=YC*YG)s!03c#*~2?!j;BQ;ItNd4+}pAw z{xi5br1uO*A;Wmf8IvPI%ygtyg8Js_EDvS);@G$io1M%B>XRnK4+P8aig|E_%hg&m zQqqc`#-Gk@b6mXxWBxx=LE~>amGvLYW&G79?b`AxsIhy z?PxTkkQb<0V-7Le)%wwLzu5js!z9f?HV!fMGtLKBgR-yyk6Ok$kN@mAm35vaH}P#k zhRycIQ`Y%jO& z>u|lpTy`v4aIE!G1j*e~&dgh->9R)i52!Yg8k$Rq$La)L6uQOeT3K)^eKbb5t2US8 z{>0@yCSOekc33Y``l=k$t(h->kn+^|;M&4@A;r5^@BB_;KW#|7QM;5g$NP15Q}mgE zcFELns+D88jAxnNn=>5@*{D9*=9{7S`{<(Yq*3#;8uDCeH6f9Z%uB0k?|DM*@ve8> z?0ME|(e0{rK;1y0bncs~XFOv@` zvs1i}x5{`jffRyk8BaTlX=uog@I62vo*w8ah%T3x$~SwYSc)it;KK=+qWWs(=Of|h z{yQ8w@9H==?ov`xLT?Qpo7K|#aVA?%Ol(Wz%Nm-Rd3qnW(K`AVhc`e)VQI}ZcU4cH zrMjhze43QOwj4x|^YT@n>_4%wEqddZ=tS*9R>Aa{2bFR@0e`Se&hkt9fHG3fxLur>Fko3E}iRCP6-X znJBD2PLNr~RAt>FZQkMW^|g)OwU!!P0X<2-E4qD${Ap`qDua4P=S$G)XhXyEf7&-FUzuxY&OS)HfuaLmg(S!ds~DynD2RK`9AZPkZ%3baCFO-V=phs zoWEYuT<-ou+pHz7iP0ji1CEmA90%tunkh?30g{!@JxAA41!xAww_J}~vE5E*F?~wM zHYGdLT%ggjeZ5JhD4wT}0xfCDOvOGo1p8#ZG0@Zd0NW!WKE;8#=%@ogf4((egZi8x z*;LSW0%@gAlleb7*BcKx zpE0HIcL=1j|7Uib!PRzBX$|=n{o#8Pt3RKk*DnMx&W3b-YI&;9C|tKR(DedpB=(NWFTGQD_}yY0){H>dj^Hj(Swlu5br?-{9~v*7EC63RR^`L??I z{iVw>tlf4`K3_IZ4T}vG$a!)*?v20Nsm#M+v^TG?np?@K?RqMh{HCa4DR}3Ott*TH ztXZ{>4QldS7vqc^E1f4-|9GfGefeY7oh#rca^disQo(Nm_cL3J>^!tIwU)P->oAIx z?%bKTk3-}7rr236xFiWh2i>-u}__s~CX;4XaF#Ojz4 z{Yld0g-Z&_X7b|8msHf6g{vP7*-U)g>xzZbMRV9_-^Fz5#`^{~$`*v~@!xX!OV!d` zTy&=D&nx|>`R?#ctnddb?e49gHs7t<7=3ShxJAz|zdDP(o}U}UOkDOiTvK?_qwW2w zO=)0`kwq**#4ufxqpOSlP;6r=*QW~6q2BK#vpKW(b}22Wnz={!M2OQi2!F|T3n>UKo11f%ul7tk&DFCJWF~~p!^M5;Jd~`LKUfHnFLx~gMv&7+KkX2;E*z~zC5h830Avy@b zx@{`Sq(!Fyx7h{dZ$ch@=gd*?*tD^ewmeE+F6PNx%nFR5b;Ez?7qxz`806{~l20rt zw3K&iSEP`jKGw_Ft-Fi~W0S)Xyu=EU!5^-pI{pm2EmpP8Qg-y#1qxy!Yg$ zc--R?D?_YLRod)V)SpE(S-XCyV-cQ~qWO7eSMYb!jHHPq!P1E)>Fwv9ZB>%^eDmrd zo4ne|?W7aY>h4^FIj2k#$a>#Y=CuTpiy3FpIa2D$f9$>3@zA+mBSDw%b6)u&ei7#m zHJz;A1#6Avr6+0l(ng-dc1|n0{OEn>QaRQC@NDJGpmm1P`kaMRN23(_qF(FL?AsFgJN3I5?+tR}u+?j)Solb{ zm-qRN*LDoWxWxJjor)%>3j6c-0$Hp^IMe`L~MuTepO#Pe&9H&a;O0y;@f3UdW=5y^a`D3t0ztvB|xM_ zpSSbHhfEOqK=`X&7cFp%SsfrY5x3=2@coFSGhMjz^Fd-kfe;gOrGJo6l)&w4s}wap z1am*pTN(?uqz13D`n>M0&B*La!Uu21HwKJ`Ig3jKW*@X-;?yOQ*}6SeC*4V8Gcz;Q zGF73$zHMgq6LxvJc>_13X*r40r(KSgQda(AB&fAH6s9El$`6_vzsiCBvel_U&Az{F zA&ZVV)^jHP`6FVU83VdylzaVUeCtOec*+xLjeqWPa_^ZKw=Jgxsi)<` zRjqdI1E0dq;rND@5BWx%z4z|B%Qioc+`afba@3fY_fF1O5QWy2kJ+a4bT(y-U(T42|F^Ltkt&h_Gz;0%@_P3`a7fx@7+JaA3M<@Vg1wmq;+{ll95U4 zD}85m@D_Kl%Hqt89`oJbkTTP8xqZ?BhXA|OZ|T2fX=!;mM!+A3QJ=OS`?ghk1}3%5 zXE=uyyCu{=pO(s&B)~!mzxeZH3T};B5YJ~^7h9WNA$;Z`5K1`1z%)nu`jQaQx`Y`F z=u7cJuG#I|NjW*_9D|^}mH|U36dO1)V*KAD8C*+Lt=h#dtN)$L=zp)LFs*RlfFvRIEva(EY_Oi6bejJSZzWLnRe+;g7 z;Y38tHs5de`UP36JTpfu?T*}|m>K-Def#Ki-vZsb99^@lP^0_0uVqZ-=dzb2AJz>& z`h?VFKUq(?*4BHQ?JR{jFIDzLw1Vzs$6rZ{3$`c!S{fg_vhj8Ms|TO7LW3vYFW}a$ zS>G7gPjlv`mVjX9x^v!;gwk;E>dPH_dwI&TNczuZ2axPu?(+8PT^gF+y^SoTw6o&) zGNmd)qDPZj`3U60tLlRR|=zC=Y2y3ezGST?hXVt z{jgU1HoFm{Qn@r+ag!j^^f+_7 zmBp%fQb@;jGM~N+K-jF4IF|WS7z54qlHOlhTPxn(DYgGu^bE81&#h5#f$$NlXlXS* z*h5LO?$oLRy7bq>X$9^~pvrpiY7jXp2rCIdkfhB_|3@82#8`VEVX&Wa#Sv75)1MHY zCx~|(xs3cVG%4rdFY(p4X)gBmGiJ%-nS4?%@ldNEsHL#iD;Y7{B|5xVCfY58kQyWS zd)*UsGzQx8$#^g(Z}a*z?Cb>g`*{;dzDTk;KdtaaiC7APMHtUq;!v~vX}q~rZ%f~4 zlG@9zU9VhU50$@rzv){ft^JYCMrB1ZKR#S0BD^JUB~m+$HISbtuJT+|uG;Ef-TLXQ zln*bQMo8yh>g(``WQ?nqTl0sz=82S6lZAE+{jx7VUZ5DTt7O?tFW!XV@3#|ShhKfa z=kC$HX)CQ`UFzZX?fcHiEgE5&A1~M4s;1quEbg>_dugC5`SR@Q`>RQJ)Jfx3MAURU z@0lo^cq2yoa?Dj#gG?@wQ8`2;C8{Z&?2Yyhdo@GF-HZLRPD%zWT{+|p9P`I0w(8Z7 zWN^pMIx0#RKhEC$AzM%PNwE8+v$Ew}&mH0^e|fekuPl>jEuCesI42QznWH_8#-_bC zp_E?D_72T(?Rr+wlJuv#h1@6Rou5Th7Ks=FP3zM9AC@3j7+F{zKq7J4d2WbNkS2l8 zNItRe+cd&WOcLEA;NgrSY}Bihg?S$9E>mTzRz5P7>;eLB`^?@1nI)&DvcPV!0wxUu zXr1TA_T{lxSvJKz0zyKB#SJkyNWaiWo$dBZtdEhGHyEyEtVB(ShB@=s)B2_y%S~B4 z3B=a4ef?O5O8Raxvg%)dpl%`-fnBAWP#Y|2X8afcF;}uWRlGKKvm77#0HJ@j0Fz*x zYJ74+;Shzpcgd1x?jZ_)Qf6j}u-8F*lkdd_P`@e?@LTxVsrtiwi-Bg*M8!^Hg~N1h zH-1i1?O1u?YIXQk0$t~|oUhuE1z*ldM+W78$@!wqqvh@--h2M6?~yJqy}qXk8|tSX z*3_|z?c|)G@eqz>;C()~B`R_##8sKXP;;otY@6o->!+oKoGez|LXuMVc<;Nnvzaoc z7Os3-T-@=^+W4ywLloDUNW-0*O?4ITKOePN*8J{zSaq^UC%rRl=i)fsJD=Ua{mzxJ~K=42WBe3mTJv|#I2-W$O~*K*zOO}|OAwXK!q zchRDvbK!a=5Vm5yvz_e2_{XoC``mVOouTeHJ)^RudP0J#vf$l|?h#8*NzzjPBDYd9 z&8vnqB;cCZn3+>*ah{?oa>%4<>F9FQxVqi`G(Jc2!m41!-P?M0ckN5IR365F+>z@&wqaI#}Ts%t#jJrRZCmdH>W zO^fAmE(RX?hp-8PCj0|)b~J`oE-`>{kObDA(=Tcd9Sqe`v*pn8U~HNxd8*K6`AY3i z9jz^OXTAIL;78xSG07KQZ+NF$Uma2Q_(rh!rxfzcThToi+N6h{O6ESUkX+0Ow)$Co z`SF~}s@>N2n`OR&N<}k{*Z10qw<*XTT6_I?j=Js7?|Aj0vTsJ49-9vZ3krr0>j|%Y zE7kEA)2oS&?BX}oxLVaIYdrJgn#**`b?vunP347gUY9x5H&xGjw#3*EYwQiXzuoB2 z`n#8|SASf)*x`NR`pSnor>FS}q6w1xB9dGm%(gA$SB>UmG?pyRmt zBCdAPTPiN6zi;7Cu*1F#_jewu6=^PdE?a%JOR%lf9BGp(M2u#fqDfW*f3Mr0EAR|N z3z}0w5lu|~xB2-C#Vt4*gNjS-1N5edd^P~vOQ_h93fp9CQ2*q_nWOuCcHKNLC$}4! zx-i?`=|9(}y-Tddi2<2*7{=r;8E)Vo5vEYy*8&1pY?aCX@mqW-6}Lte+_aqrU5JdP zE?fS&50MXQ;Nc1C3+Ni%XAhj!P`#a8{IhwrAygs1T63{7@>}m(g+#Tac@Fgl3;fNz#mCEDy>MsGg`wly z@4w}m2sLtwImxc|+aRy$@+a?DcAZlX21_q5+Q&MXWrYc9YCYx3&2b*(%YD-Hc___T z^RT_n_VG_#7Teu3>4XAKE~(UQi8!Q@>s;2!|LoV_ZJe@7Pp{^`-SLC-eX2#?pw?5L z?-S|ziH}}R(yy`Z6B!SvE4db!O1am0!~Z1Jrt66t=JnDIiX!fI{rIQ1vVtsKM_y zb&Zh8P_i--i&6`syq9B)2SYizPbXfnwoWz;&2NxRx^I8`bZj5biC0;VMDMaz-*9dJ z>vT5SpIY1b2-O6qLWjn9vfY<+pLUVPm3LREI8!70e$)C-a=Oiph$ms4M!KxqyN*>` zxW8Jin16ka?9CWw?i-^muZKoNPH$;w-Ilv5I$7l=Wa&7&wyyZvL-Ep|ksile) zI%>_tW;Xt|i#>G1PbF?DRtpKUnB)~Cll&NTzd51h){Hy+B;KMwD=TFz`0%^#(#tN2 zO-XtMTWQYxvGwbXy?x+g^)qRvd+l!WiOsdf`$-ZHd%iZ@lnbXig7ISRHO>1dxQH8X zop(Ps@W#8Gu+1t}vyG5o`%_7vD&5mb4pZba%$3|KuyT#gSFoh%6@4ibp}eRi65d63 zs--z;+0(4uZu+pPVUN#3@0GRu+^D$gHrB6ppWWbL7gWu5+JU zNIs4)5T}PzDv5ver(`3}`$06zAkw0VBMz}hq1?IOHA$Q}H|RsHLm2mZUJ@Zw#Q8z2 ztbABvz|H$M88hRYS-;9JlV0*~%FuDaZuk+AB(4^87)>aKQCry{iEU%0#dH6=++=AK zR>)pEE~38f_ojfT<{;xn2JXebSKnMBvUISj5$*%DW&br!zlR)v5G6rC2!lR0(+afT z&LAccVP#m@QW!KG4TYun%!lpBB63{Z=zM>dP0V3J56LHpfS~rPL^|Y{T>P85AD!?S zH)eURn?thsw>-y8= zXBy05)pWV6^5>Yt;O#jB#ccg!-%jgzubmZ7bedWDn5~v`LaRphb<3kwo9!N7^%6WK zdzHEc1o9<4ejZ?u><8B4P0rsos@h1sskSX&+^pf2w{UEvWN)YE;GfX8pVjWqwt5>+EC4+o#MhqI{S|@ee!_g z?P16+IQtWx7`789d~lRKO!R#zIr9h(UqL{K6QLvO>f7+ev6YzPK*qoaRYPosKK8?a z&CH~=r|Ua%72n^eY6*H5!GTNd#xx`_Tr|cAK7x>)$j2z@-O5A5`fi>JXf;?Vd_?8gj}2?+QnT;M=w+B3IJ;r)(^+C3y>4^W$GbnQQI+fYarw_Hl-pFkr z{+E#SLibC^lVJ7Mv39H^6DHD4vG6ds&mTnPO;5B_l3hSreicwfFHYi_s_kwg!9=kjkj`M+|Jj^L+=nRa+ehv$}&Up zOps=$fIGp?*^JAIq|-s@952TTk=;YGtB(7^4Wje};7|!m6HGD1G3kVG|E5aVqbG@$ z6_3IzT=$^^s1qCyI6P*rHMDe?Vk?|dc0y*BW@b!)z7jXreyuBRhK5p8Qc8mv$U3jA zps-ITD-uU?v0jO(!X?^u^bkyIr*F5WHa|bZ^dmWFIBWZ8k`WDw??J9v2?V)il`hg^ z$RnWbD2BU^PQpt+bi!pd;#se6eXo&l8XKEg{$P9YbhV@DO7KIi;tPhdzaVQyK!!1# zZitbvS3Qt%XLi8=J`3P%@O9M!Bq_2qx3VJa&i}Fg-L|k8!i@!;Qq*$E5r+@qxC3A0 zjKZ4s?CkZq{9K%fL`;52$8x$R3GEvOMbNxHTJgFY{aJn9=B~%08r$dO**$YYIJ;`p zWQOLn@}CidFW&tO?l0oeaGWvYCMyZeWqmy3%Omjfz%xReIv7-C?Y(2^}k zEHYK=XdG4JRLvBo3?2V)m^@%Vy?7lKvv#Z;!aa7BX#8piY_x1I#b`0Wm5g8;0yRoY z!{|P9AFw*G9$d58Ol$W?=utzFtO~yu2C*BI5=2TdUQfAu2aT8m7ev!)TvS#?qpavF zF8+Nh!_&~Wx#37$rUVJs?5;_qT7b5F9eS1v%k2>kR{jXX6EaM;>+hJ(hxScRud$Yv zmC^fEev~GckhylPHQedUk@GmUDE;dt6%|TA5fGN^(;)v?8lTh{ClZF%7igBk-Mjoa zX$qz3K}yOLdTv{7F#>Hhp}z;zlDd4^$4luStIqo=QrD~VSRo<^#2>er82SRYDUk0+ z#CBD#U$qUym8Scanu{K5fvKp*w6(h*!*`~Uzop-ymzB|)Z0i^B@+${&sivIJy zp&#iMpZx|r18~Ioog*jH&3d%T7yll3LuXYOi&`1}g$sYL${6mpdOsWydX~s;4K-Jk z)6_M1fr0zaV~9?6+~eQB?6`WBV jKGflVul)b)i*GWpwT^l1*{K}01&>RziZXAc^t}EbGE6Cp literal 0 HcmV?d00001 diff --git a/localization/autoware_ekf_localizer/media/delay_model_eq.png b/localization/autoware_ekf_localizer/media/delay_model_eq.png new file mode 100644 index 0000000000000000000000000000000000000000..41777d756b9745cb874eed3d5175470e76ecc8b9 GIT binary patch literal 4906 zcma)A2UJsAvjzcypeW4BO(NEVhO^UU!$I~(&EA*t-o{JDZKFxK7Q-)9d0|Cih_$&aah!V_tPVo4r8S#$OL zvyQ@_UUtShd7l^yOcA#S%=|G63vc7W&H6%?_Y4aQe;8ax%h)INN1E$Xaj0;!bGiG7 zy>~1d2mtZp4)-CwyO`Q)Jv7}emFQx&Ex5+&JnQm|INuRyss6bcV(9AniNnI2D=q8tWztznyYGQ@Bc3R&Z?`x^ao z^`rjmrWXk4?-l*SX#%7XTRw*nf{35#H^q+#cO|ld(7L+01FJGGa@7C9O6TKFc043c z=jYqE9D=2Sdg?(bJ+8{z!qvW4J>~aA@LQ+T2%U->r$JvC(g`fNJ1?smZKdQJ7Z)ln zp|(_316-c%Eska`5Ok7kTQ|t`J`vJ;Hs&g>-3-s%PvBKDR?r-rd}~An(+d0nHV&mA z7fze+B|H@6r}vh1jO3=oH~n_zqPMNkURQRay8@rQCK^Nugo-*j_X$Q;YgPOnR4T>7 z@@J(7SEfo_78GgTWU8$RrZw`eIGYv7@;$}S!{sy4$|bQqLhH)TrlQb*80C(BPO?(GZH)e6>KJK443)PxipLVdC`}dm z$v@FwC@xJeUs7>@F!+^jU-NF+xFgIk!4ZjK370=%=rm2&Zv9eU$PTd@mfayL+eewr zN>iQ4k43%{(vTd5+R|k03cW7+D2*d?(W#&{iyL>K;X<2*JERz+-n)h`Ro=j-%#jgB zFN35o&!TZJ+@^>%jzr3+5?lnx7739tGdDU;_-0dP^_Rdf)|nq3kUWCo^z8kd|Ei@s z>reOCtBi#XUloaWQ=)WNPiljrJ!-U6GLDuv{}Z&GUnZ6-aa-~TSudc>vB=x()r z`v9Fa;#sKQk`X=xpHeVewHmc zt2w0Y#EXxoGh}*P?au>Kw_EcyT_j5cI(2Nw8y_nzS9`XE_)sd4K91p&iUu5o^>Nb+ z*`95y^~cWt7+c}FYe-vR^cVzJSM`7P@~HBllXI(1NwHmey6`yvOwJ$jjG=&vq?ClT z`7^X7K8NsAXC9XVHbR7TwC$41{n&|}h9}gE-ywD}AU?kLa>&njI~XQk9*0Y`P`(G?NxpyX`Wxxo=0R zX3(ihEuOYMZ&jscR2IDDBrK&iObqI!6WEh%S}_M zJjaH;eq_pvs4y^Q?k4ls?PKz2g?BJ2Z{EF8FYp*HbHXn7xoX?V{_dGFS7W3yA^=8{ zqXWAa<HIdhh<;KT1vmNw-ujp-ly(*^fS-3`~+=cNbcU*en+{zqM#k^XL55 z2P`{ME;XHeCfaLUSTDmTEr0|>m%oHsz6}BE(J}td(7$E3e|7G9u8PIS?D|i(XfNn@ zn>@kxl3P^et_||*?JfxrN18SK?Vq{r+CDD{*em=Un8Y74Anr2wU4`(qZr3rI(Dm)GzUSPoc}sa|KHhIS zxA?S1zik#qNqpO!Se&Ov_f9PLN+6SzIkl)O8qSGP>+8KV33}=S`@B)c?s2VvaW#rt zJlIbUb;7isy=F*J(mzNC@zaPfpu1A0PNqZ@mb>w*-lH~eK-sYh2qEQFL%&wC+fbR1 z@$-u)mHS$y-L+r$q3jIxnSoA=$=5xZ={BxjA4bw`=~aatwEcRq&HenHPy@LJcG))C zO(vkME6sGuR*}I1Ms=~ZI?!45ek8<#<8sqO6&d0=6e*CQI=3So4ny76PQmf_&=Ls$ zh)&FXoDZW3G|WN?GK^DGlwhI{2)wDQwSledialpS-*(Sli@+pw5&?4J5_QrZp{(0G zT*%lfqE8p}^=b)%J6RuS^%|OZBIOL#z5xH?l$|j)43Kv1q7c{<`b&?i*Xs|y-tls;@Svm1qj36G;eTYTb6@(`M`A6gct2CDO zLsCb?EpNvG`3K|xTB38S7ho@{cQ#eyW#q)mFoL;Vd^4*TI!Q3gJqsoHi+|JlzQGfJ zJohsX_ZaX6Mj-ERo5mEm8=d|=lVO5$KnVx8Td8AYqhaJO7R-kI%; z37s`AmIJRbUkSd~uaXZXtzUaa$ik0O?(A!Qc>KpMp1H7k0t5r+PK^6n7hG7KvmFqY z%c-yH#+dNW0H>Ye%j_EGhpflm^R6>PNxvxV&1$a~1w@u$h@?RJ7#G{YG>m#w|0rrA zOmG4y0ecP^VlqC@xcb^zLIMo~1>V8a@;@H~h}P#^j=rj{PfeP4+@jOATI8<%*;XnV0Dv^NcF>Q zGr@JW)R{YjSkK?s*5!_Tf@AJEY4Og_jVOLWRtAD;<9qhVPoRYK5qc(bpG%?CQD#(k zpTAdqM$A75ck5Y3V4bunHdb}ob~m)07p9p={J-)X;ZKVlPxlL6Xd8>bw#Iff8%KbY zegm`e=|#gc@6#l7_xs|;41{{nt(GK)4EvV^z3#mEN08K~w7dSMD#gRV# z@8u(v*_MIB%zWD~iO4;hre=bs*~7~{L%9?Gsjq)PrA2Aa6P||I6RT7C)-UI<8E+jk zyDd!Rfp>EG0g*tP?vyV9mYrN@thLqO)wW7wuV1*xn5cG1!#~L03sW+fx6aYF?3^oY zw~p=%uSF>8L3u-v7BpwUxpNA&ida({2X7Z!N4okY^z)*qtkRq6xmq0Cw}e7pwjE<6 z9Ti#>GdX$hvI1>V*tlDv;9Qx7U4FAdKFQu#%c1HuBGwV1)s>I${?k13Y%d9)eupD- zx>Q>|U5kU74bX104a2F00B}$ynm#Avcd?VzQ6Zf*yzc>g)X##W;ShR3H~`yD!Y84x z9OB5(rlU(}HgyHT!p0|id1izUtY0uyx)K6-fU8%#uyUi#cB`)bL z@%1Uwi=PKx%zw5m(ZmGO%O0Ok65IJqG6!EN!XI^K` z24%K2a;)qj10pqagi}bT?SSRb7-r7I#Ik7tR(<}M2STgtZ#?m$o18+60wnLxhoQKe zUwBN0Yff|}T88UVq7Yps1aJfw@waMNbt?(~WCV1`YMyj9X#Ze>Fp{}<5TmO-b!Yqk z6|es}9wgy+553O`N^4Zkw;DZQCOnV1o!k@mk(5K>grQFSN0R(6@8^H==RZV5QM#2} zPLe@_*ANe-?I`A()rMJ$2+pQ)F)UQcP-Zn#;&MwQsFq;-$TxrXHmbVgB`(}8J@rHi zcR>=BP?8J(bg9sDvcne+jt0id6a{m=a~Uqe4Brcp6NkzBfyNCJWcrTRWH$JMDB~g| z4cFlum9LE#C2lO^K;R@vL$-9?4}Xi&vxkJIuQ-8OBl~&a^@@%{-TV`^1e(WjMAu_z zX#CEI>5~bDHu8#LL7TcV0S$AiJgU$v;U%?P4|97MbGU{AstXWZ2+Ij|CTz*5>$Q$G zKfWnc4CMc$*b=X0+l3#e5{Mqhk;UDsQ{Vh=JW74Q&~8YQ{4T;VMKfczC5sSRq34B- z%YQO`_{zg=lk!lO)2EyLZ$Rc>j#FBa4SzP#!*Z;yUD2LyQSak{b0^-`G>E!2eMY3v zJ{({5>Bu=tsGnW_*h;1b@cV_Gw}&LLtn-io9ymwh2}aK^<{6r4mPx~j_2P0j8YWZe zpFgS#x;%aI5IKd$x+7l(j0arK=v(^|vjAM9Yhc_sMyM?#M`Me2?)`k+I)MvrU3|c; zQN-qP3954USd8Oyx%O&loL zgDT(3w%tE0S4(Sq-Bmiimfm*+`DS8??`{tLEP@&pcN4|w2g)=|s3sU$rvmwp^@AF2 zetfqCMAQ8weHku=&q?)~dU?P52LGDy=L2C&n0;80BC%Rw!_2;V4^fbsqJPtF!%gbv zH=@mHwWPySGw)?P|9HiL2c$>>6K`-aLo!{rHcYrN4{7D$ep={IzL8em4OmCXT{92-sFwkA-gwvOV^v}YHLF{B1VZS- zM3=%s6%7YCR5S2?AgxC)+JBVz!yPzu>0!O^JVQFrKH)u5XnPFS=npZoqXLDIRgB;M zVX6kMCBVJ?h&q=}}7W4;9cWuDLMwX4`W7Ma8vyT5-5%1G_R8b~?*^z2+=@ zzRM`)Ecf-zRiLqMfh73_Ca=yyO$rZu@A z5I$;o?|x9>D%bwn`f54)A?hL``FT8`Dg8>LgPy{BF@xEz-Tk?{%W!+5>rv zVo;lnQ2=?vQkr>OUg@%!w1hXcKmAq%`i0H!H?LL{u$VpJ0B2X&S2ENUi>Af08^|H7pQJijl2j0~GWSOt99@ z^uWkhTW_1IvU1Snr=FdTJ8l}tDQHXv71BTKX*Ofn%6^};#~*y|g6kUT6lq)G{|g*8 BgHr$i literal 0 HcmV?d00001 diff --git a/localization/autoware_ekf_localizer/media/ekf_autoware_res.png b/localization/autoware_ekf_localizer/media/ekf_autoware_res.png new file mode 100644 index 0000000000000000000000000000000000000000..c771e3620b1610a08b0a064a51bc762f7152347b GIT binary patch literal 69064 zcmeFZWmH%1^Dazxw;(N`ba$hGfFRP1AOh0ejnX9z0wSf--6bjAUDDm1&;7yg@Bj1b zb6%Vm=hazfE!Xn1Znt~id+wQQX0DmpK`-T{&{2p{prD}8pG!Y|1qB6{4h02^i39^y zeDM_Zp`a+Bo<9{+c81=bMb#crxfQux>g??K+Ntt7C7p7HHcOciixpop%bsgmUr|@3Qx}*5Zky#_WZ`2~(xT225MmGwnJ&`sCJi{Xp$!#7#a2 zXGGzo5oy(|X}`F8>YR_i9`U6?{XQXO^n_|m}#(oTnYKPOYKe6?=eS{3iqG?|IY;mg6;@^-J&W2%0TeUCEgk5 zubTuO>_7PZ@c;RT1!0)LgPAp*#pi$BgrdF0_<#2L`*QCqB#L&sG^ZdspMSp$WW#^H z8szf-x8Z-J_kWLsoqfCs)r$?DJ%5gz=EwP$IiVHZTU<`sQyXdT7JKaIs3E4TVUw$8^ls#Cs~jPB^ei zcMSvx4Js`1(l%Jw!Xypr#p)A7ij(TUh15{~%YcxM^Pvpt8cy10|5DxKY_L8z@@)1W zOZ$(qU#dc}>CU?@S^l-|ssz@pHosW@=fZ#P=fU7jRA^Oi!}HgA{S&ax(~I$E~pSNfNj5IzF2`W#mbsQx97Q+TYU$+KpSzm{R2 zLmeF;3{8t`{dsN!OEAgY7W_7gaJk&v+>T4_Vg8XXlDTPUY2{P+W3gVTsGMB&750nV zePXF|Ia&?Er7JPpdBkloWq*5paW?0sK*e^(fscpx#@IL~D{GJ>h1W)$DhllZ`y)V__16dA9X-3l$Z0 zuXeA&bU1s^RWgkD8SeY{@6TrJFe#U>_8QZKJuaup&2kjd8eERvHWbNZ+3xRx3tU`W zYMu5xPbZC$DMv>~+uGW;CE3{6hI16GtgJ*FHb=H6OViwTtJl)JJV(E)l!@Bf9)3V4 zFW+r(TL;lygu*j z?DX~Zt=+8&F{1ia1^ib>{!5%cwB!b~Sf|#Jl;1uu8@#)0fD(@Q z>GmWpIe9;#vwvhu0Os9M+TA1n8K-%VIJUVYE;BjW=zL?BilQ%|c=3EqyAFr483n%m0WmEK&s?0@Q z6Y4s@-kvCy$r@7qwYj-jS6A1Y%ri~z?S2I_LEhhh*(d&AH4<%Ffs2!TznmAGH$kLU z%vNv)BX~K%*~36jui4;UO^pQanJl}C-A=9Hrnbp;a_)7}Ka>9cnBdz3A7J5)O&Zi#M1b@mD z%ezSwM>Lcta*kjM<c5xuDUd1JNu;e%E#Ch-tkKtlVoUWP|Mb@~ zYa|@j5_)Fk`-(pW4n$PM;$4rseYL>&C;rc9>kntYpp*ZkkNJRvq}FChQoJ+!MKTU9 zZjOA44AQsn-!DDZ#sNh15zYa?YYoDkEO*3#K&030wcB1jT~xwVA_@vhNoncu(9n9A z{3l+@DCrMq4{(TyYpj3$`1M-{}ak5 za9JPFZs&bW)U#gk zStHs-flGk4&el4KTy2;7M*`(tTr_aZ06?%YoKsm@na1z%4j6DhK&zvEk;ZqU^qLfW zd@d~?&^h->INqXpb;!muGij78PZS$2bwu1PM=L-qnrIIwt7e(WAVXo@VUEbnbNW~^ zVRz^G29LWFy}M^frk0kT2W^B>5o9Ux@f|SI0_dwG3%;hU&dlep1|I$Oiem)2-FnhU zQIBKhzCWs_9o02O>;ovfTO~d!E1UjHCoF6EFQp_3Fmtb@b0N+m$W= zYfM@dp{tA=*IzaouUA-tf`X#y6#9C4-msBTw#xfma93#(v!&+NW0xWRSM8hp;6lsa z?>M|SAg{_YC#-LM^VNKqoWPBbvXy~Cl9;H4+1%2yAU8K7U~X;>h&5wladB}pS8Z>u z-VM0by!~pswZp?hBuZ)k+9IBU-8n&|0*=~^o;OWCu)gl%(sFV=i5$kd9w(zfQ|AsD zyB~;ny1#kzMog?($7!~W-Gb)JmoLC^mb+gZiriiFS9D>C2L}g#&&`cz)G#RT(Xy(4 zc7@DE+`CoS*eCuHk;J^b&$H)g=y=3=71w{w#XASJY#hJDyO$3&I(;aJc$xS|hjXpt z4!`|6mPOM{wcUobjCg0NklW(Y(gjommhJieF9<^TM_%pL_OrKZmA(!8`KIKAk)`q4 zR$Kew7EYOpT)rwHA>lO2&+}Yv%Nggr`mr~5VEX>sHmwi z;GyKU@b-V=JDPQx7rI=}zzKT9&3(Gi?3Y&DxL>5*9@9CZYP~mw=6@f7 zPw=QcjD*K(t`3-Nd+W>?lvr`DT4BkBkFV18YZaBz)17HEGcy5xejFT}+x-9$b8w^m zUoGZTN+^t|a9$6Z_>a(e zp&DkWX}VpGABj@&v6oA0+R#f-%^B4M_P;s+1@{!mIrpQ7 z@$yAq=aE$X$wadisWoUPnyB&7sUhVv061rOkn%02*m zsXu5ZkqUqKfX$#aC(YA!Ij8XAXl-x4F|9G=2H}WC=TR6@|1({k#h~N)AA;Or{T2G=eEU-=srcB~6Dtyg z*4g{yfeh<~LzJYr+;)gJQEMwoAX7wt!ech;phYTwQ8a^7curz;&$TiI&X;|T7xchf ziw!$2&us=G#yb|ONdG(|3Me04NLmw8^_BR)I0P{XQF2s@_ANu}8H~TySx~_GGi_z` zKLv;+`Z)rm4<~HAmWY3?6T)jdVIC{x$m>*DQ!+C%v$96Q*xTE?pZ^M&cRvbKrcVJ` z!N@ly)7$ym)5`F03^LQPJdIc1V)`ll6Xddi6S~`P!6YRm1pz7kr#8wzw~r9)eGuI6 zL`_zUB(lWvGbhQ;HVHIg*ugt9v*F?4jRt?tb`Ih&2DO6i_4NcUGgULQExI)K9|m>c zu9fBGiiKTWT|kfT4&xikmfbe8;v3EvQOh-Nz>$%#rDkE;{*jU*__ZZ%c5aeZ+F5Q%J-zwYyA3IPEDCZ;f~5|D=A(#cCd`ba79!T-Yt zX6-6gdir22cH_Q>-P0BmMLsvdmM#Q*9<&Qz*yezSq`Gc?J3h8YH~`LEuhCP8gJals z_!1y>D!vv#PY@j-V3PINsxM-CowoqIi69fI0m)HZ5Zu3H5(#9I3h(TXWf+!<^{U=2 zpPgEk|JBNjA07b#FuI+&`m0IfG_G+~9UX0LxmzrcTtj^;6+5QS}IGi>J_hteJ`g()Cf@&Kuce zbKg%;Nl8i1bt4Oyt|o0XGIQfvs@vP11TiERpf1L}NnEdg_-AHjPL>)E8|dolf-G@6 zvJv21T8fC*?cH_%-N@)@{ZXI5e5gk`gn?3}9XdWRPy`Yoo_Y6ZFYoa1aDXc-%gfud zwQBjQ@i8%Zn&s~XzdUn)Al@lO?qR0OGKA`HN>E1WdYh6Y|iQd@33m z87i ziL9n8EP(68KtW+A4$G^ijSli;6h2>o{if`Cxcn2G#ib7-*~{F~JT%JXr3jH!5ijAi zrKdG{c|Ae7g8Mko4Tva#9&ZB0ot!?F|@; z&F8vV8Xpo8RvNUSbSt@sYvuz~$ga0=Zx}rWPHKO`Fk(;%Y==8h4#AI-mUa~!BuIFY z1YK;El}Fk_2y?%GmywkvcU?~h=Ecd$=?>gTadEM(E;HeGb&vKJDSE03*y7tx6q7aI zlP?P3)n2`_1@8gagoi?|G3^e30XRK4P|O|033{_TQ*B?j0>bqGOmffN8NS;b=V1&ZjQj-r`C@stx16RCx7X(`s5xC_v$WcqT|~Onf@6CqnY>=2|dHlr9FxmxPgioJN<#m5=ttd`c3&T_GsgOQqH5q@XWiDLa%!8 zpn0Iaz?ULXUcc;bZEdBN3RhNDZ8#az^6~M3XjMo^h||v0igfv7LzSj-gF4{8%F-n> zY(QiH!kkoI8!DaD6TnS;;;~BAX72Cq<{&}?BoB*QW?WpHg2;_M2+|lqZqbZLURGWX ze607|B)M#W^~8^dd_Jqcf4?UFhx^eNMUs~KzT0(~{zS?wZ&21x`7lsDM{NX8aF5h! zrr4k@7(`j}39Mq)!C0@9m1B~U{z-MaOHb|45MU|&3nJ4}Qf@%(S9}Pvw&^m{Xz_F+ zj<<5w*86|~GJE%~2od(khUyoPbPA&L^+88}nn+qg0;X)OAGzqTDB^OFoBxhz#;mTMgvtTMZ;-X#b8lyw$;;4BB3j{k6OW0uj4e zC%-tcKSFr$6ASRY3VB3bf6#G|SF_duw<)-?9AN+Jr42yf5`-_|^4D?!xJ|#qJh~>r zzXKZ4JU~Ab8$8DR_i~d1xJ~tLtyuRTF$3ghAfS`!RMA%cl4w-{xXri+kI94o3hJJ> zCYU(4g*HfuF|2uyzeW;ZAR8=k7p78CIA<%Jq>8||~%&qjYqxfMtam*K%JI60~$j;gJ*0#*Qt<8cd&Nc zZ_)H0#g~WJB@RaXy;+JjB9+AusMoWQ)R>+yvj1ZQsnp)ZNvTH#2bqvZ%!oCq8)h~3 zsb>@p@0xTCc2OIE4d_zG64h*Au#ois&Uxhly=NDUPWbz_X{ZAZs+(m3=ChN6mKLyD4WO_H2_Hj;ZT6Zzq{Ayx$d`#y7ya7KX$&GNB6A1?=m5$P;?KOJS( zyj7I0*np3(l@9(Z!@iYPnm0uw3o{CoU7P7t+1>$5Mg@qOanPV8|N+m&1GRbKNZWQ8fow!D6D%fy9x z`5&{`1{IW2KR>14`>BPAyP`TCT9Bh7^J{l|7pl9W@}RmnX=|X z+_`mQ>UZ3e`&)R|LNtGzCu9xMC9tpwbHl|u%ty$b$>Ds`m;Eqb-%nW6SSdWNkJ5gZ zprW9Q$x3>{&KK*;X*^T4$fKKdRxO&Sf4mBXKiWCb9>|IbnY9B$LQv7rGOfxoGL}G$ zbq!de%vT#_AiD(2^U>XDWut?={l1mQKUuTb??~!WR1}N)C$)iJ+9aR%+Y+E%>R|_= zT&p`%TV(>SMLe(6=4D_7?L>4vwm?DXo!8{hSFFpVfyQw}a9iT%rj!T?-2f zSJ%rd+4woE?lMjW zYC0Zfl8*3RggPEuB@)K*r2M(3@ofQDMg(feM$RGLgDf7JN)efN0jNiVM zd4v=992XR%1iLlSdOxyMFFL4xWzQ)L5~*&_FhKXT(p z*!wu5o{}QLwF9${6L9pTG$>gMV;(Lt)@F#9@IsNCJsG5~oYx#<>tWTGaYHaJPxFAh z0QV4;G<>JnEamjh>j7!>bEL^eeMZXV+(Stn4_QkW>fEr?bE7wE1AK1abb&Aj+dACu z1+kzA1IyKJW@0h{>Ym9~4L=+6|MzoT*RO*nd8@-c|4MRQj-1#rUFLR0Xj@x}#my;# zpBLz5_j02nzujq6)EjMZItlxbEF}N&wcn!?e@5l6ZXu{As?EUk<%xJIhb>Ass@F-BIT_(_xwj%ySWx*D1H^fKz;Iz4^ zHBUd%kF@df(thji{54-8t0RSG-?1UAWE`Y;9<;>8B_bfk8a6UAx~3eefP?#95loqeEE=lFo8X<`_cBjCEl6WWm*c)(VS*8dCu61ZQ9GKR z=+l!2+|mTh4+wJO=8f1N2xsy)(u=snBh z4f;7f#Z+7P+j#@Voe?Q7h?xK%eC;Wumu}nhiuUcKv*s&nsqR$Ch6L7p)#&HN%j3C8 zwq@o4^(5#jJ6^MlH;3LUUl>=*RZioIZuy&Wk}B`KdfXYxlgcm-vQiw}@5oZpJ9x57 zzTF&sZ;-Hm=B_qn^Dh#?3L-#cMKL7XMX zV)MFWl<107x}sq7?X7p{fsBlde5xRyao?v5sfeMf-Q$g6VPWBS<(gDcJt+e51#x^f zi><#}0@4JW!o5;xXlMXcUHZ0nllCDq#IY~T!BqNYO$WTxL=TYrAVa(`_&E24*ZC%) zRC0r0S72QWB4(Pwtw{LKmlsPx$;AW$vbeMoG_~JWo`_)xlsWwDjUy^ie=hu*UHS5p zyosO{87X}fgNC3fyK=<_rW<^#G_0YCOK!icLb29##7z%F;iF8VLVM=ckGVAdMc-UG zhqkmOSJ394#K#e>b|N6#pQcPH$alOMx^OlPdR@JO&Ul*fqPMev*Sd~gc*e@LYH#Rk zsd=4Q~$59apR^JJ}n~+ip~6 zUK4j$|E>Dds`LkRVzMG zx^2=h=w3FfZb8PafRtYAgP56THf&tnQ2WaUQG@US>4fRl$Ux_gkXsjnHM`!gtks2q zsMR}UN9&ZxvK5i{?|%e!03AYS$%1BMG{9^1EJM)!usYyX`b>jZ>Q<&DeIED5 zP{h+ij{7ufo{3!GWc7Acr#-U5Qp~E==>S{YwwnY4Pi?S3ocm$SZbgTYKVbjkt z@>i@}QH0d~b#|wR8Mow@Lfo18bs6O|Z{9Vq)zqJ=^}4)Kn_E#@^+_oydMTFBdx>eP z;_F1mE8D%V<1Tw6v5xhk*%PhiQdLJH1o!B8eMCUQ)Kk{fXJKO^-6boL!PPPFH+g-W z*z~!*U5kO`Y*Girj-WWAZr2u7nK8U^t`Q!tz4*(Bg7y>^s+bI~bm~`2P3FVuL2zb6 z-bBRd8jf8DxWy)CI(p#)rCjAbs-BiE5ev(D0X!S+5| zpru&fPggL`V=~AMEn3SO41CHq#X!+MVryoE*Ss#%u-5DRtWZJLK#0%Wnl`tz5|>dQ z7w)aEyB(pb1nMlqr`}h&=I=zTXX-LwXFZsyuTUs`%tdU#4uxkFc36&7X~-?=u2j#* zP2{{D_h`M=)%Jhy($>P$9&un%$h66-i~_@VB;7YHaDzlis0AxwRE}r7UnJ%ifKEmr z)ONfSmYcRQMbDg6izOgcPb}}y`GY1HdG$`IavZ;6Tw^V>KClcmD%=mh&b}d@1>oSF zZ!wyWu+@*bk2GfiMb`1NAM&H0J2?D35Q#id1by!-5@$kLdqnKSz}t>V#Is85Vms3aXwx&$;k%=e==QTK2@09bT3UR%(X(F{@72SsiJnms)b4Rs<3*zvo)q%EGMQWJq?E4D&1_|gh@!wu9F z1PH1ETkA=2_Eu1ycvR$X?OnF`cQB@kC1gQv4Kjj_^TQxjSZ+_E^c#6T*Wto0lJj1K z8gn}VK=qEf{g%e9cw8L9H@T>w zhK2?m=FdYh8C+xQSz`1+1Qy@(jWQ~%zBFFD(u?p8kCB;R zAlTXy6EXGh$4ppS**{7*;@DmrD2{heENf-uo|jXb@3JiOYF3Y9Ss(lot8HRJ#7(bR% zAbk*)Et6Ne3y!`@AScC#f}JN-ER@S1VR37Ug3dW9L!ph#d zy>&L9;FflBlwO-6D`~i@TY9>RnwJ?K4Y`@dT)d=5+y$f54vW&&&yibO0`DC?R!7qq z7d>9$*y1O~e7RH?71-j79p~R~mSbaMF+&?Q<~}{xl{&gWiXP(@nu#wA+vT&Y?&oEa zyX%z#WJx#o{(Fn8Nl8?uEO>`0(p4jRv*UJc52XTC;!J}Oi}ekarHC{1&|};!$?H1!bl%5j<&Gy+xMIjRg+OeNT+_K8!_n;> z#w9vp-1E*Nu}#H&n~;20s*-A<7H(sQp1U16sUzu^{txG8^RG0mxy}mnaAS8wJKK9@ z{FME%h_4a_j^7q3q)@{YC*W@^$eHK85ymVpFhC1z)a@pBrw2kGrCJ>ywhEX zJ34lK+0&3S{po$egc@?O57ijUjdS3E<&`r%=J5Fq7xohkAlfn8h`%d*~D@a4(1@ie`HLg6C;n#e% zL#KAt%_u>unUn7>wQG_i7vbKX*Y2s~_-M*hB|e9d&Eb-uY%6boHj5Lhp?!a+=4^KAp} zI?FkaC}iakN>(L((5|ed!wFuqII+FX3t>h)3tg*Jw`?<$bZQd#;#Qi%rn3Nf0o%2u zcOr=sZSv=-JXg@k`H??W8zzjGyU$LI^LVCurmQCM+vPQACr}fB%^fzF>tVv)rk#Twvx^MaZn&mzO2X!rex!FC=_xaTky!b#8Arugu{nD3{Bz zBX&+bdS*UestRzdoU#zfp2d{nb~1&bYC{h@Usg{@a4STl*{OpHc}zy^JrQB&UawkQDS2P1umtlZ{b72{Wayx@VG2!9R6Nn6 zuGLwYK(MaOZ^S;^p0rwY=>BUr)8Ql^*-d_cSn}4|;PMvVVTZ?Qy(;3LrU##~m_ZTZ7?qM1AxS?=$W`BkJ^g?#ulPwlg9I5JIx~=HvM>o6D#? zCcJ%n5uC9E;#!(;g4T7wk#%bc#8X2EO-`%ICMnl;?IXOW0ONI}Myiu+ z?n$|R&~UPrxJRl0QkdgXZ+$sh%GS-Ve9fCreCPX8+z_U)rKDyCxx_K>^l1GK*h6wBY#C3@9IqM4HwH(ICiuSq zzZQ7>F#hRtNC@_y8Jhu2nCk>NPf^<0hELok&NIzq$eZUKOC4`Y5*;$8%~W~TZh(U1 zE%Th+oF+eSlqFue(yU5LDQDP-gWaZobg4^WuAtcV{pYnu>;sLyFsozLM7N`=*PqNn z9p2lct^HV#aSeH?vGZf$+JbNuur&{Pb)Ur>{@RBJ*(G!R++fI(# z5x|H1(Dh86)~SNtdd$`HA1k*Eq~B^7wh(LhX|%N3HdGJ2ls+5s)~oykxsFIEhq7v| zR_UJpNleB`l2Jh4+c#?N#rBy~3czOT?T(3ZtSns8UBY_(@s{v!fY>*}u{np9&JfD# zQ26fCIZ-6B(0~YNNDQZow?H>r%+#$xTU(4dZq#v?+KUn>v!CK1yUSyBL2sfy8%`t zQT-;={pj6CwlrFmk-KK&+5KM>CQ1$2FW{B!Px9?`oZ=+cmKU^hjz>IP3k4)~xmqzYSsxwP-Eu!p znhTwF(n_pYoqC)u)Sn%n+cF*#Fb|A>=DKTlw z=qn~F%5-ur9Wmb*b$W;`{@tn2!4;l3CpiEWQW&c81=RgNZG^1e@aNEpbM!|t zG!~aFjGJ3oh`4B-J$a4!d(6T!Je74(b4du!*Y>ni-M^wEeVfhej~xYbrUaxSOgUz! zY<#dv#BK(GRROOSN6KDU|GW`S*NiCRd1waSAx;B9xA0Fc(tv!sGX zw{-_-VCvKG%`@HUG9Mqun70(~%GKc7e*ozG<~rlYVe?{(M^3=i;A>kz_LxuCfT+45 z9#(0OaU*i6%)65Q;^UhyQwom7T&&8f)9wZyCOVX1$Kl-XCJJ2Pxf%yXbI#6{g$Oo^ zU0kpIh|DYN9#oy%nt=d-NZg6YJ21>X{buWlmLT;!|9C)_>4C7QWQ5 zFqEaCth_~QmOqjHK}WfAxb-bg<)Za$qW~ukT@(X?1)iX0G|sYJ^#qQBbsz4WS-?)A zO##><3XQ<1A1u46cjflL10Osc%3)j4Yy1dks zzA>7b9c_h&{yR^;t8*n5J}1Ktfj4x)$^?4U51z5cw@0i1>QcNcO)PmosQ9@VqgUf{la`+%+KXPoR9H(m)p7o{j@TUHhA=MH_ID|yAkxEUN}h?8 zo2$Yb*Jp|mWitG)9Mr}zU+`&y3gT^TRvGAD3-K6o^CygjlsROf*yfsC^-P%HC zf!V^{1uIMDMJK|E6aX5)=m4KblY$Z650uaEfGOJL%^n9QH#c^^~$pa)Xrz3)MPYle5CY}Z?xB~p3>j@3TeUgd-J zoVmg*(tYX6`URx7;`hYCXD_((1H+U?kGC2K&a>tZ8nJx~8n{ZUWCm;Wc?5u(;87%DSO-W>Y6yTI8^jQ*ev5uJI;<5t)BDZIHw;VNZ@sAJoUOrp+}5${ zoi9cop1GMP6aVvcRV}6nIi#vUDDsA&Pe%)x|WJM`RmO%%R`4_%*_b74_(>U@69(aHOgVMDcu0CommiW|hrK-w-D$Vf83^Jt<*M|HK zT{n}}8yE~r|E8{Cf1n_o(ks!CIFTjtFVO<9h#te(Kc^&K9Sr)0_%nvi_=Z070x9`? zN=eqzpmkOBLiuwFz)wtoXs9WKpcYzD1^p~%Z z1?<omNa*i z!W;))16C23yQsUF2?vPB>Yy5nP#`lJZ`GF_2}X+jhk1%-w&izNGLCjlQhfC+c4mw-DB=K6*lS#4n=mRr9y-h8J<5Xzdl{LX&$lMzNe8HElXxb6+Pp2}@JRy5n47 zF@J(vDNT!hghbg+EYwKLG!F&AQ>3aesLO+yRh30CfZ)?`a9(>n59pH>@{G0SW>rTf zVJnJ)rxY3haC^>?=CT{BWKQX|W7Nv2&k{l_?bX;z`1m{)9e?=h>Zb!b6JjunF@YM$ zWA*q2zOgUv9JjKLDXrzpaF5|v=m_>Sc%>wN55P`_J&^F_28PfFY5M3xR|6df%uG!R zHGsNIM2k1UOnsUjgV0)Zc=oLRe|iDx$TZZSL1B~c)_OJb0>0TVdG;V4HGA%N5&Q}1 zx5aLN7*05!CE`bK*~`OuJ^@wK&bp;eXoK_DE z)sEx!6f6MDm%rA7%MSJrKmzsxMnKyl4ze;*?7B%>DwdBz@HO}czPSSIC)hxC-D6^j z3g^UhD;VDWOwC=)P(y^j`OCaN&P_w zZq4Nwh|-a|*7AaTG`OCdn@DBU0(c2liPrEA_~rzo_0TmOsDWNvJMZn4G-M96$^|Xw zcZ#G43R@PJd1e==BqC{3+5NU}DpD2Pg8?gxH58L;(KT3t5(NRM1$mhD4!fMnAY;&@ z(F4<7BM$8kYDXBQB-*Q@R5yObgihe<2DZm!Haw$iHL!p)|G?{pu@qvBU9V+c6!0ULB4=Rx5> z(yJL!AQFQMc{)U z99#laW4`$Ah2&*QLX?gTm;?r(u;GXb;(E^049b~{h56mFZ9^{qu6H6yMLP>CPo|j# zZSO-_Sp^+)bijAfz8w`jIO1yD&|di}Uz>4h90iiLHR4pyJcLJ(ek3$)U>>k%v*{~X z`}WY>GSOma5dx3VITgk?ZsV&Ft*nqq!hX`*Qx#;46U!Wd*0C(NBtvW3qo*)16>t+3 zC}1m~sbc+%dP_5Bt7LyZ9e&)aco@&?b5*dUeOljzr*dx^0Rnl-q82Usr-wt=JmMf5 zZ2HYy<>Xq;zEUU%ciuizn+J_)BF-BTci2UrFqX=uR7`TC?i<4vl7N%dKC1t$0{jFa zjQwWH=K=lquOgSufAyXa@t>7%eM9fvm}NS9*0dnkF^?)E?k(@ttHBqfcMuq{J91kB z$g!#B+l6{`b2FLf*NVx)3}xno8)*ATl<6f?@0%~wBnvv3tiV*dC#(79az*K2zOmQn zC$(jvQ&{$$rUUw^_ehSvyJCR<@b>gD5rh+b=It;!c;UcgB(PE7WS@fneITV=#hfYc zV;oW3?aKr^;6!p+d54vRGo1T$3BW)z7zsxDpfEfTK5yo;XKKt)vY(t2(DiOUiS61T z_u}eOw0O@eM(AcGtK2_wUeDt$!91@(_-lL`>?kA&T}K6n-2ywsihCd?EB z?+lb}pF=?9K>+r`q*IFq(gfk>EsGL%j9m??3BeS{+dF3ikKw`hv=T8Uc4}~r+F*0;NzJ3Ph12N2kPv3H_ zR*cV!w0OsDq@3zO4m}2XhQ1fs(q@Rlz|0crZ&?gIcg0Zcv`U?;mT*;-oh&%5`2k`c z;4{9Gm-4@zH*ucVen496@{=KOZ>~d=5raR22mmNQMETZqKGT565+52c<`nUk?sT2@ z`;km}IOMzWw-G4KGh~`UekrhVPIz+lAo-D{S{D6$1=Dwf`~iLKZS?Wf@v3yhZZ*5} z1Vx*F^9LnTKth$m*a?TtHQiYQwKHIf+im0>0k(Jy8TxJ*X|D%{i49}F(sMd(SeL4) z{*3j+@($)mnyKPpTA->ULAf@c-S3u9gDo*YEq=CwQ_t*(Gd#c`H?MPVQMWi0IT^IW z6s)peqJFJ)s9|W5CQ_lIPazG|hnX4V&TV>FNr=$>IQrBa^|>4*3gn-a_Ucrgm+gh$ z(99v@c`oBO7Rm4ss|#O>F;hElc$al-y^xet&^=gft^aGwyBF^+C0+x(R?n1*xBT%j znfY*W01Zjho6vgpuiizb-SzczFvZt+u}bnyncrfn3=Eo;&=uPS$5Q$)gF#R*-|dHp znJVD43r2A+lpvgl2W=Ap1Q#lMo0Vuv=jzD!+(+jpJ?rkjt3h|(@!RQ6r%@EXJ10l4#(pD=XYMmw>Y#~swXKnqR0kLb($vxtxmd;} zSeoQ(YfOiXNAH12PS5~3IXGAhzM#QnHrA6Wl+5A{bPDA3j9;T6Z3RTcBOqW&tMW_9 zO-v4ueva2go6=X^Uc{!neOT67w0nK|zBy422N`6t-u9XFAQ=XeJGkNnE0tFw-2NZ} zYaGyueKelANvsKn@n8~PFP3LpkF~EF8pe0Z8VPj00CWHwx0ozh`IeI^qo81{aQ;8@ zgGy9UMRG|+K+IqOa-z}ePL`z}Op4iy2S!Bnn-$i7Ad0x4fCg1|kc=e+h&%w}Mu3g1 zrj6zHei3R@Af!63szHpusBHnVBR(E&cxWCh&@l<0nU@Qcfos0Xv21oP3UO)+MXSpZ zR2I3uft(PZu{u#}E}^IrPS&!fIk$sav`Glg|KKBo;3$|RlR--4JF3Vx1&xvHpi>mg z41yUcFhg{>Q)UOgU%|j&W@Qx-9-hs2Ht*&2;ze)eyk|EGq`T+X2Z|)?=PsAvE(Pj+ z7Syx&y@=_edL^t+hq>xIh(-)XmjNA@#1avRKCR?mt^y~+>+em1dfu7?SOa8Aixtw3 zlo3C2JNVcuVGRl-OQD6I1O9Qw ztv*p31<`g62zUEv!Io_feAur-o(_`gW<|@ z(Bx>G>H_)~r_2gLqt&3mH4SN2kFEc)=AEV*>@a))8 zzl0BAY-n3~`4rV1Va1LcnL9rvj!ja$Q}Xpr?jL;)3`?O?)srsd^M;D%%9xHqqIGAwiS;fo?qSKsAx@E9gDCttjF@ z+6e?nF=0cTLgCv+MbPnF!iD+i+!^KcS)^3!cXo_vi_hIDWz?&-77k$uVsayH`*O@n z847w0_SsowP4?H(QFdOrfq@(kV!~$9a>2m_gdelBR6mzaef6MXWi^6UT-r$KYE8v& zxMRsHKHPIa@Q7peYk0XWR%x~YOJRH~w}aG}SCzyF@^^L;({?f!h;?{ltmUDr8h&q~mF;K<_h-Ivh*swvK7 z>i78i@v^mtJZ~_KD08@+p@9LW5h_4!g`w5DGhf^p`W+>1k6#lH=icmpIg|_(cFNe+ z(Q6mcmC50#tFG!&my~{gl+5NquR}HTHzWopNUf(>eQ0fCWog>L$>GebpGW#4o6_1~ zj^cT0k7?{pqc)gZv~cegw9f8Bl9}s>VTo+t+}OB)-3YCt^711h+yA%mki2ifE-5Jq z+?E?N?J#hp&Dwo4rrsMz>pdMz;+VgLK42q*A?CjR!)jpC+usD}Qt-<|uRxJ37#WnM z@W@pcX7L+lh+gobmo%s4-}7*CFbCWL>JXq$aW@5+uX6KoZyZ?`S2@7Qb1&%oW=F7S zM@-rkDkEue5L~RN7EhW)XfHg1#&MVp0qeSC@UZ|`DT`u zI>^hnH@v}5aQ@3CTH444fnOA18OEIH6V&zWoe~QOnwattBvP^J>TigyQN~hzC?M#G z>s!U5kgBW38p@dmrycmKWu^pl0k0{VNr`CDJW6JeAh8!7Rq-`u$6JVPRLM0&3G3Bc2^CzevT(6C*Qc*bx8q`mpn!^ zP5GfD$Mi!3prLh~gFIBgh3ye8}DXP&W*q}x%nJbyow?s7zFkk>}qZ-cPHrV}iayBBM z!Rfjg5FxY~SSVE?o{dgjtPd=Qz&~GHt00u3xIVQAP@v(eNQi)L&thMQx+j>Ku_Ovr z!fhzg;~AV;f#5}A&ig7#A$1H@UZ{S4Kmd=!q$F(F{K)k>%}*FMWkOp@wGvtQ@{y(i zB~8+Yk2;r1m=aD3m%4|yJRYw_GMovK!cd%cmj8m$MV@QPd~7XwqaNipBj2mO?H@|O z8(8P})e#F_@qdtS{!-oyJ)4EjNM~r`8l3DJ%`>vnmw3%j8Tzq^rQp)O?bQ;E?~|)~ z(h3LB)#ML(FJl#|W>J0Jod|9`l{l{E|F24}BM%Bw+qv zR!orGhDS=nf|=vdK~xqSBxwT-F#(}aY$&wJXkz`)f-_M1z*d;&@uis8mEZX@;3@7Y z9FT+)NkxwRQSKqr*t>H6(8(kv&YDm?S@6_#B>Gy0byh1#`IJ?tT#MTcT+!>N6cYBr zrut`xxz8r3c2gsCf`*nh(rDtS(>CR;&MTyzBa_@}CcEkmF814JO);ui-N7c|SW&b%MXTg-5^uszq~oRr*t{xk?}M7xuzo)C>#5PP0_gF< zWvJ5@gXj}k(6p^c%UOl4N0hNpOF-pv%7*NH-1{1X+u^M6d?XWDFqc-}bCr1m8+!Ta zglHI1FG#;GaZY2E;CxaVV(_V%QNW6!PIekA5Z+#?+%IyQU!)l!{|25 z#&{v0m})tg?M*A!vr;*>aZgjvwaj|tj(*W$XZ<&9OmAL{M+5W~i%F5*=5PvRu$qE~ zj?7vWZ*shJ0UaULQcZrC%kcR}sEo6exsQ|bQXkUey2uY*jsbQUqa|~m>u*rWg&Fuy zyHL%M!>d=73DGMN;x+Ef$Kg!Cq^{P;Lyfz=YX;J?(MWdCT@fJ?m*`QqP$6761reUp z7M2^Fz_>VLHEAzuH@sgCRVsb*z`-h$sAOhf)`eqYn*FRn%aarCaLKa|gy_l?Q-c~* zA~uIl--H0;i(K{zn!&~enX0o*mf+RcB`FRZ6KJq%jGtAi!q-N?wQzv(i?7BWGhDw@%9`~{frP?9WgmHiyX%@!$KlHddY1m`C+As&i87b z`)WjHPXq2IEh%}Ll;4)pG*Ac58wW$Igc}j#CbKIo={fj~`Wp;PNZiGOXyu&ncicjH z{KHCUr=FAtf!0a}#HEiw#MCfC%tgbr#7(@~6>(vMe#!=sH60{gu3h++6T9waoV

-1Yz)bkHS z6||^kQ?s^y-HEsnz|4okMz!d#N}eRTTu+gBM!PM^-ugY~{*a16t<>4HyMF_H>p1F+ zy?F>k(1U42BImDs){r_ybPP%g-k-9?T%g{50`v>iocP!#*RNTfd}d$`K0BAk>~u64 zD9vx=EzlVi5p$jIKaVo5BsaX=PPY}2q5};xl=ryCcxx` zw;)pE#R6}bNUE_);8_14RO9o5phrwIS=t}r2x(|bTYF`1V*W&(RzM44uEcaxeh7{T z-T|_cp<(Zq+~rwqI~k z9=pA-t?XB*@$4_s4*i=gS2Cu0J6l#!{(|8R+T(hQVr-O`B_3r844u3cKYj;m2x9tl zr&hQa-%A(k7cfFH07j%17=!wa&bF8%&4Tr%Uq{#XtN}?|Mv_N0l>f(rXm0L6GEqja zlZEW{&5SJC3b=dvtnIf^{h*#t(6h=7P|^5>2|6UhCq`3*lZ>vVV3Q&UIBa&p!Tmp+jfj zE$Y*?P`$J5gYVzH_EbbE2jL$;-z)0#1G=Zve&X`}MB$443O=RqH9U;?z%FJ($IsoXgP`J@C^5ZO(JVGhzPW20yhWoZQTci0Fii`e@H5}Z}aw_6vRIHxPu`kA{1&r*^}V_Mmyx%!KR^?3yP;>l4Picfitgr zVhC13m5@o9dEGMw(Hj&c3x!ff#W87e&_8nIp5nGGSq4uK22+5Fcs8~p5eExikzFum zxp5%4-i-auRGX+9{zc&8)yE$jZ?!_tErf; z8%OI``0O36eMB02GgFBC%39awvL8yLk$Ka; zN1PI5uZ*ec)4dkR{okK_)VEZ7OZ+q?`@+-yA=5`rroCYT9TmljP^k&u} z%6f;IsHv7NT~3n<3xY7-a+{Zi_2On$Gx0c*=lo}LOfmp!=2DK zUU#OhL%dP5d5VGPVXTW#qjL6W+>bu_)X;&uA>A1Caps2FcSeay&i0vwu^f`Qh*e?H zC0TV0h0bTBtSIE3i1>ZMY4&Ty&yC{Scb$(I7q%<~@7u}W)Y9FXMgK9>gaer-5%DS0 zPZ@#vS;e!D&4n<$_cVDiFOYqBS=qBC;a$c`e$`2-?N-#pE?cK^1&-syK-V8G^Rdlq zPhT3_xli!`%BFjPetBWWN;KlJs#0)T*Va)~^}@#C5w>4Y=g^;Y8Nwqp;G$7XI$&!F}CmbY{M ze_jB}g`S^IThbPIW$taQUkA$n(#kK_D@BVCqI{P>@Sf%v|Cn&TAQp|a#Qgk4qwR^! z+QalZ|mB*hXsNDB;q^ZtAa}(9ex!msO zEpG$2?)nMa;gXx3{H12BNVj&iR(*-17>RQaUSR}4$Zs3tEknr<>hybeXs;J9g!5@x zZRor^R(L(9ZEkcZOFqT_Wc=?fv(Os1xtz4z$zBcn%Kfc}75?`emXt|$cfOp>UGUP! zItt!G()S+m^ZjsPI_0m}lMC#UrE1ir0n?6`FW^Rso>IcNcXdw?e02;yP3hz;llGt7 zYh9k;mtM3FmL4}WQ>A(-SlqqM+rAMJ^VN#RIV`flBe`+GR1DuE_5D+!`0h**cin1b7sK~k zEqy1gOdT1)`1%y^I%(i_exAN%K$_29w-9#3hkF8Zqr@D;atm1fPp5)ZBW6;|re0F; zF9lzyz-Kq9Akrs6%|ty z96*G7Iv@ytnMBy3AqE-i2tiPGzg55K*!s7;oOW?PoXhD_ii(MGP8NyD_xtPj^L-go4E8)Ow^QDtc&yNh8;HzP@e$ z^CP8Te25PCR+H0clsVko?L_@DAptQ!;IL*aw&6tj zD0pHy8sZ81tN7#6yDRmK+5f)c^18Ip0Po^jng3J-oT6{^iL^(Y4G!2b=ccjC!FS;e6ojQo5--o>!-szEkX* zE)@7*g)2qY%g?Kru2s~prgTjya+kk9JtDXI=Mjs$E@p{9X*+H{Aa{u6h)egQRoqXW z5I!8UX$`yC8mZbbvG>!!CVEr!_7VL554j=s{k6V6ly} z_|ju{K2**tq$cK0{^lW=fLZK}_9GmjA+MOFolqa;qPX&0*+Q;N-b^t_!C(Y(HZW=!#RJwyxv!!>>BRVD*UFQc;k4!=%RmZ6Ymb6#Yi+PPH z_6gS;c0NNqyqkkI(c(Ym@-Du`r%rNFBs0w`=QEoU=g#RkF8LJOvyg=Gh#AhF@-%09 zombK#_Qt<|65CX0i`X+Gsy^*m>VH6GIAk|ZFju+RL*cuI%OO=|pQyyK@x0Wb?}ozP zfyOY16rFr(zxF#G&1H$YQH>jKX6tRQ7T37rUtEJXoR#-`#rrbq89Zc=WO*L%VISBi zWNKd85?HPj%SOyJJEW+2S}PuK`Qimk)WI!}e(2$UqwYQ#lCMr>SN*4WM3MroTAJzg zXT(?0;~|s62lq$i{Y|}ZBvp&5;3VrLyi$Z`GG;7tvub+{T(qA2<}t$=8L$ya^e7AGq<>K# zdN;H#t$+-venCODPS#&|revJHSdl*NE&s+wL+t z)?kQ9ecx9b?AC`{EA7b=ri^xg;&bSJAdH;Y#*%{tPjU`#Pye!vS;-H*C=-&)*dbrD z_~H|HP#-Gnu)t4eFbQP8T~{jE?bkW3Ji67Cy%L`Fwzd;5uC(!066&|2A$mAp?EWyr zj~}0p=gVFF9x_iWbPvbt6EV?>ZPm`s4h#TJOG#mbfw2?BmE$$mlQl3Z*YDeJ7;zdI z5mBHuV@P3f2Py2j_d-P_blfTd)D9T?`02xkx=H_=nD-ufcJw}TTa)N zpz%>D&d*-;?Tpmf@}V9U9ySl+(gG!|YTw0yu`~(Wj79XGqT11|Hm?Eu-lKlIDs^9` zgB8(xq$&u6TTpu6g1Nal3^;^QCJVaAD#jkxrIfq}u|J43LP1xXJ>*15R31!Fp3e()r=5i%e` z@`Yb#zj(xqOK11pIU}c5QFbe4A69@0$vkmZJ*uJ-r#>HWGj*ki#e(I&Kpv(eVnE?; zh^BmI@$2gHZ5a4hA}5m!9X=JQcIcX&gbS7$Vq!M>Nb=#9HOos;j>0+&Bt5LC5Uk}r z++EeHa?IDwm2lpghmlD~W8bVJqN2=hMwteFGw=%zu01(e+`stXZJjA@9v?1bDnL)_ z0<|i!s$!NV+K8&OuUcd`{Yp_I(SL=f&kOUa4d};(>pS&8K!WUv-<{&*LzJVHJX+Xd zb>-QeSD%VjxG&{Zv%)b$P!NsTih0-P!E|gG`o8vS>6MF`nwpAAAIu&n!~516$^vs! zBe-h*$)IIrLXiSPK6T&m^U%7w_;8Ef0dihR zBiH0=m$&-5QT!c`{;o>(hs6ORDS#c!9c)+k^?$!dg4Nz|qGP<0nr?i;+)TrZDP zzHa-?#xR%UsYDMGTq-*B`frXf-n9Yd@Amff2?rT6*a%(eOedn?;u8>f|Lu24NeLOd zD(tbK!F$ut!u3jsQ@iYi*DW*!1%)DYj=4^qZ9Ec-*o1_xwv{*VaJjTfepKHYFduRW z$ro5lY*|#~_|=f(gMZQIgO?xoHWjbm!{tNbkz3UCcSpN8o#xtb%7nBEHg82~E-y-s z#s>!V$>7ot&XA2nTCa}}IpEy0%oWVPv?$r6gEa7(xao_C%p1*BY$r-?^$?tM@<#i89ArXy$7*=s_r7J;es z?A<3m#npKRRd6y(ii=^@$LjZw41A8TL7@vaE0N;8xzAVu6U4t6+@McMOneF|Yl6o~ zxl|HN{n{+?C!BjB6c2;kQ8Rd9h%AGT*wI=eOhRGj;))k@x>-v_pOT#1n2H@kiv=Im z;{4c|WXit>mnT+N_{A@KsqbYW<2NOkO+-lIYA4zxY9*A{Vsn2Tca-1zD5MjAI7+zp z4!`OL1&N~?Rhg$joOEXvqj=R4E6MR}>^6|a<8MXsCk9|uocik^&eb)BlM@qPvnHerF zu8xk*$_?66)-ZY^0`y4jIe>I_%62Q(p70$^R~qYu&(aB9FV;%D@Uq%h^OuRQ-p*td zZ;l>Y2UPE~mwqg_ zA`oL1EgIU&_k4uUxv^>)w!MuNnh-u`_;~;3&6~GQ_6#eW{(QewI2;=pN#R|3KiHdkSLgR*iL%$}l2Ybm~U&r1jT9Mb~0v}cvSY82P+ zW64NL%;{AZEZLjyYXbY(lXL@BHmH*Te5(B27pXY3W)o?9X%>ge)nI?)UTezcY*6;+ zrdZ7V@Smdj&9B#`=%lcGsHY(v!HSDb4G;0H#$0`);L5#)Z6rO+Q1^gowZrtRl20FF z3RT}MTm0(6afIQkj>K_1z6; zpm%7tUvG)ikLTOdVBw-@fYO-e)Gtu$9N5m=#L!B_`Wy4f??BqLmUT)Bq z6&lFRy$va-B0X`^ZaX;O;GSh%5l`PyeUvS=+%+GCnii z$%OuOHhdc9Wyw(yrS!YKVibIqQj&Ry2Dcy<^_zAV5cRlusj4aanF}ct9-l>>IZ<^p z*+I|>l0L1E6TW7v4w404PN~rO{w)K=!~#}%`cT$KDdjQuOB8qiq&k#Yb$pXpia3_f zX-rAw4khdu)n@Ie-QbeUx};x4*!ZEal?YnRYaVQ#2>n|`k* z|0mi8u?L=>k^sVSx0(~R9@0t96$vS5Dy3i9EZ!vB!QB5WNs*MZ|D{l)UmnTU4viwF zuI*3b$R=+MoiEa9#Dg08Nms}7D_YLlzhkQx6rvrPnu8hw6z_QzpgfS7iZeiO4m$kOi^hRSjI-jR;;oncX6L(RMACuvMM%ebjWt zopO1*cr9ncCOtDfrI^i}f2&sfU{;JaF)xi7$rbA;G{3A(SSJ9o&mf-L*?SKYu7{&5gz^E%lbGs4z)~P5}dM3{`N;r(#jr(Qt z;XtDYo)I({L%5Kj@n1JX)tp%=x!B%iZg^_t7W^B`_}Oh za3rtdgk+F5O5qt5_Cv{eoo#t{P0!(CJ?>IgnFf6*Ur?N49sISrh}c_=ea>?1aWS~IQ*O4c0*%W%?d*o4q1R&l#O8fI zN|w;69BpFx%hWw_;!dg?r+gls|Kw*=q*oq3e4OYFE~0G&$DlC&S~IC7fx%CX@p6gW zUr|b>rkNBynSXu?K#_V|`_em9-3CYREg5UOy#6Xd_qLj;0M>Lq`Se46@z|V(n@btp zsJldk{-@vym5DZ!IhJ~kt%%e^gU(N{JJ72=f$bC--w)HT=BnBteI8m~z-43Jnzww0 zzEF|8NYdzGgcS3`l>3pZ!hKoS+LU>y*&zA&@YFZGvc#!KUcDYCoolZC_LNz(ejACztY- zSm^AkEogQxz-A&qDsXyu_u4PeK)j9Vx@4 zKWMZ*QXgwN+Hhb>U4zeJ3=onHz=J~ZyxxPc^7(Bo>a?%xzd2)S>4;R(BNX-L&2-J+j7lK~vlk9Jj3fBCvuNsC;r36$ z2f7|U<;D~Ph|7Ju=04CoWkyX1IS2QXe*PkMs7fzQIn}U#IolTIb?MTJ*0i;aJ**a{ zPO>DL=G*SQRhJgOOH6}u4ZAL~-t+u>W=Ta1Zj9%ESuG^=d;_^IlTw(s=`q>ua z#K~^nT6sBZ#lLi_(pL4&=4SSjzNh_szQne~fACZH)r^w^?6_^jkxeNO=sr~~Q`$`- zEMGE<^Od3HY8ZVg%ntXk*4bc;T@@UXHiC^914Y&8rvtJNUfu=aGX{($g#jH{D z?nvm6>GCX9a53Z9GY3kXcg|m!pK%*hJ*?H3msG$7j$L8g>VkkH3b@sa*W2Q*y;XDw zvR8dwt1ooE67b#wNS>L_R#s}RB8t&1_7(v$mT9jlGsdkR3foz`Jr^0j`FgxQm5yi; z#ibvUc&;BZ)ES!=c#W0h}dB^%IpMJw3ZI%~x8p<73)GX7g8s1H1{Q zr{1W=|K>7RXTpP^t&Sq7!YNqZ)xk`U@HCGv+qw-R>=V!P&Np!Ruu3*o7Ob5GPW^a&&yaFYPgOU^~a>t zsDCU}9;va>>Cnd29{z?ep)8!d>V|$Cnf1*t=L4<1@V{I%w(eTDbe@r1tVpyaz;&IP zr^Uo%f?@X$N->~80WID3#QQFiO07T(RZpJ&6eowy%!-zcgUQY(?AZO_ac#jz|+y zY|?hq@Mk&C8Tl8$O*7QlUajK&GwL2P+obZHaRMRMw?O`U`&wk9O8X$#oo>_vn1geV z)PvW&*sgdgTJ}rHT@Cm}vy+f^9j)x>YPd4>$C+&s^g!Wx5~5cH&tc$H8axIOLqtK7 zd`fmxjpe%z29Gr#*XqHiDeLqVxDWV=bF}lApo&ZnW}M`&`oW_QU8!_*E6FQfIU%9F1$3A+urJ zRllqb@EX0F8?{SkdlUMnS9PDS49OLCLL!Cxc6{m}aP3~8l9VJ8;TXi?Q|WmNd7o}x zdk$4qGk4+YI;bkJbw)T-GY&4(>wRdEvo?_wKaUlXpHLi>D0^C!n0viVE2-3dJ=^N_ zdBLnqg3y7l!|ehOA<;>}%jbR^BBacREHe>s$Xypwa`#lz2%G6`cF3`{sTfNY7x?#p z9-hImc{kpH^qfS7n@gvm(nco9jpyJ_iWNS`=abNr0K76xM+x?}3&;k$knRr8F1M{3Dpb}J=PMpvZoXZ=Lk`R@YW1l9>lj~pAB8%hFlMi~PWbkS`B=rC zERMDj;1@gP^;y>A7LShDE!5jEUm@uk(@Sp0dd<1G5}&_7y4P53CpY%XnuN_liGU5( z75Uy%4>1emIZVO}I`2H`u<~Z#(^=z-@LxvE28qPzE|{Es#da9Bqg~+{1n*{x#*6YP zwqaYtsEQrI9+l=C%(ltl5(i>bjDj7dFhUHti{I@*q9?2S!En{R+i^($N|D_WtI-J! z)IAu_7enM;$!yJcJ0X#Z;L+<|K_2jmAXF8-%MCLV$~*V{I?WvR(P^{SOWre6)8YeJ zx&g(&%e01=wpS?X76m_iucH^&E3|Av$`}?HztFBRogd*tZ6e3aSzvzo0H#5Dxbl9* z4ycEc35!R~_VK=rjXv^)$V^=~M+a0m-tBFg;(~&SNsiz_6rm0L_x3I^)#*N)f3Iw^ zn7hT_PdH)>!kehV$lZRGOZ;?pgsBv+>=ytVhET2qYH*CV`f<+3}+O3KE{?pDN#L4UfC&r)+)B6o*5kMfL4s;W;+r%NO@;0U;T&1O~PrtRr`VI@CmX3-% z(YmlOW6t6pQ9CLxr&}ElPKU7he5jdqZujFdJ28JJE81O=v-`jd5VKgH|4cAWvwI+9 zgq%x6?_}aV8#xJsT`qb&<|CW{`F_^YB6Sq&Hhh!tv)1*dbk}dTXY%)Dym444hcY}ONCo;sIsmDpOB^kvkpzzHI z>I~@0>UIm2grTnS&ei;$Oa5?;t#Z}wiefk8cy*)7gFuE(Vz%>Z%qI6kHhN}zorb!7 zL)=7N*cWkjt;*hC^iz?4Erd&Oz77C+x72gwDYFj*!`o`Em+70n7L2-_%(NY_KVNjM z<-Iz7ladA#bqOf=Xb1wt&@12Uef-Z0pp?$%V9DeYz&5m0xqGLOPgx+-dA|eE;oYM5 zOghYg{q!;GS%3q8FNym5U#TiAKw-x{dr2ywMRUn*7?Ko0Xi2USZX$3el2{+EazD6H z6#N)HVnsW;c4YTR!9JMDK?R>CU5Xi{Vn#$tAc@4j7sj4?dg=S*~4j zWww2ZnEu+mm+XK{-Iu?4sO!z~SeOaCx$&maRhW8~;P)1hFAs_$$fJI{g3Vc{+ZZ~V zyKX~V@qzg{@EK#}Nht-a?DJxd<)gv+@6!mMpOH-P_#b%vw#<-X-k+)Hw>u`w(b^o} zw19vnYGQ4E`2#y)0tph65yCtj7hjMVdd0@gQ+}~v!xzf0Az$=ACR@XlKM_TJrc)L9 z^?y+Z##JSLkagekzj*e6w(G?d3nXHh#@y*D&SIE=89Xb|X3Z;N5}BPbh2jbl1cN6> zEgUzJr9R*wWeU z3yfhJlhD2+^dc4yF~~*NeVQ?ER}mc@os*L@d3v(T*E}t>;>Qx7H@Xblx^ll6pxS3N z0_F@UuA-J!7iwk~-OKEE2TD@nctIJ2i=dn6(JNwSRny3H`!Gix;689LWx|O}M7@{K zOBmk2&Z=Ho~E;~T5TF6OE~*(u9sw5iy%Rs+hk#bX$&-@^_Yk<3chO=%4~ zx@*!H$fZ|PWiiP0@w>fyMzGG(3#sq$$FvJT=Sv1`<%a$2`IkvQDw3U8Fc2K} z%l#(KK>kXJ}gXNACh;Ou)nx#R5Z7n~+8_e#ha(ntCHi1do z@wj&~{-)9d&3y6aWbs>uUK1^Ae%1T4F-!X@iPd;2F8bdbS(M`~Ei7QaEowKV=^AQ5 zB&-r(BgOl8-wqbV_8IZu33Z$3E_UxluwRPkgxYz17Pp_Mv`&S_D$#_-1 zx8Cnp<32eEm6P&aSNFI3TYKqqk@@Aje#77wqb0n}glV86seVJZzMHU`$K?q z`UIAM`h0+U3ri_iVU6Smxl~xS2)iBO(kF9PqjZ)c&1~2TyfhHqF$=d3Hh7}$H_B<_ zM{GM};RwZ2H#)7u!@fanWw(&FwyxR=;I_Wl(nQuJOiAP1yob{4A$(KnK>RJRSy(!? zwc6&c8Edn*r~rg}+|wUfSpqmK?(`s?ysro^c~n-L1|da6q#7`H=TFi*+JnEDxwD;d zqV7kI$vt}@i5i)h^zBT%DlRRB)>-#}UC_4MpA}H?8t;`6y^@Yai%V^-SmrUKVa_fs z5(YupnA43^0p$YnH^l%ihFUqC zwy`|FF)<@W>3?JP=qKR@fK_yvUiXYmqbg~%Q%Z9wY|5xlk#mqBL^YY5{eUuZuSyf8 zLb0tFphpf2fIn>RyqCV2r$|ai6a%o;V6#T1|4ZPVK3)`_UlrkqnQYZeN~g0kb*I&TtAae-TXgkD;hU?__XT#VMi%-4tRFN$a6f|U z#@D{RuG1kC*YQ;s+E^c|0t*XD=9f1@I<&*A^ZzPlK%W3*lO;Gc6DnSxq0iExrF(NB zOB1sjcPnuKd}aa)(D~*S_?;NeKbT5@NYp^kNTDQ*?tLP-!cZU(cb7q3?_!zoc(#1P z(D3mY$Ut$ws_4@1i)@ybB3rl<^(O!*M}9#?VBA~!)qF|>=w5)gN%k&E?YiP#C=#aV z37O5E?dnRwL3!iI5f|6yANFSO>Tt!XjM8=1ZHiNnofo9w`&0DH$r=zU*(z(=H_B-g z`s6I26!yumkG+HDei*;`E*1qjYAh!G7}gd&rB@AuJoqAA&GQd8G}?D#pX{p7b0|to z)=%#y=4QmFLf^Gs4A9mNqc=Fp8d#*x9Y=ILfB%sQcHh!-m38U|^zvOl0{SrDc_}jU zWtWJ?6ATGRL5BuYKd@(0Bo41FF=s2T9*uKCCE5E60t9f2^&P!-#&Ts}girrocJBNU zZtwVNuEGDjI`i~=fjNJ;^PY4ecS3G|n^phpC=+bf5_LcU8=H+0XH z2Q)+jMIy;70j{{?(|FzWs*~M2RGUQw9oRI09cq1L0cqlefa7n#1({wzl4%QZsTV8;s4IwVdAQAh6Ew zD~MOuBuSEMkMt^7xT~iDNi8jgah6SdH6vm&uB`2&|8Ogrnh2R7scuju8_HY_x%!sK z^I}ct0#~|vF%KWU$}WPrb^?wEQwT8f?w&G}P1B`Y=|6OS&I5NF5yifqQzBvfAMPZ2 zkJ1&g4?j+Oh>1479Eei<<@aN=e2XvA$EYJ5<|XKhO2E2b z{n12p%zKZ(0MtYr&CnWTaaPfxSfLkc>zp{oVs{4h^1m*D!7MI+*yT$RR50YD7s7cv z8C+3sL2%rzufo2QY}xIIk&*Fe#i4ey2d$EBii=L}hu_r$+Mt!oY8!WYZ7ZA$4(U$@ z*G$X|a1~F-yU)2>I=U{`;vd*XgkpB{~dYiYIGbf zk0UHQ5gujH>L9)K9hjg!cA{oV<>Ve$SP~06qpO!oMw<-sYsJAZ>qty#YO9160XIE2 zRhGISU=B_cyMKWg&2lC|A)njA(|@~C=@3}%s$u0@rVGmh?2EadMwUBg%KBy|vvh>? z`{f zSMer0l`Z!h-?8Lz_rJxcbazo9iv89xVD7!R=?Z?}BpcY3Z7BGUoWViihR_dK2jk7* z;bC&{1%}J|=g>9O1!R|T?v8}ig&K#U%j8otKLsv~Ql3kPkX3z==oOS&CE25f*1&;^ z48&udC@?n9vL;G?ou_jx!+locFKI?Aa#|xn1Rn6Ai{`Kza#&F&&o*sr# zFjxR&?}%0ig4B7t=6foWN5m|EdM=lD*HpCa))CbaB>OK(r zMK^s>(ZbkFNqw96^w0k&0x*Kh+O`e%4j*0m#+1P0@Uy)3PnR|5BiA(P0&Yx{+s-{g zZ7|36kd)bCc}6O-%46oHU3{*r@Rv1fL<4R8DYcacMc<6Pkp2r{o4*YL`2XDNOVwE zlQR;A5$tRG|Cn%z-6UYbI~C@e>rWU2P<&QNQ1#K(5Q|@oL_|UGNW{vuZ@C}s!7eU5 zlcIUqyGWqW_N*sS9VGEvN1E8LHKGSUzcc)ghGYTTuIsNtYCYQ8MD|fAY%D-{kC>uV?M7M@Z8 z_+U`TY>sMu3VMipo(wWco?g$Nu-!2TzO}*kzi<7>1gHk$e)SUPhRvXg&xaH87|Z%? zJLDY?$E9zJP9N>>^k_{Y^j(8wkg^I2v3zDB3e564ppD z+1~wlZDtxY*z3XYzmO$&(cFi4!ON3v5K$C^j&7LeQJ}UOKP9@co4p#S%XR z<~1FQqL(ZtS5+AG@@luwjm_eCR8~{dnG@Jit2|x^j~6Reu`T zJ9EJ~qAnjQGIjb7qZ!C0E?o_c4C1UFcSgCDo)|^`@oS3ub!Ow?5Y6B z64*_F&Bd)_+lMGCm5P<-KVbR!o@dR_B&hVpmeHClL{dW4#C|==vs{LBJ|E5#y7cqs z+1A>b{RiI}g7>VvtMi$sTq0&ck!HKUJvJtpFr^=1oaGk5qkEoWp_~AfJB~~RNgrq^ zA1oh>)t6z7^PJc8I#%$zL}J88R-%aA^_ruN_IFp^g@}c_=N?{q@u}!l=s*ic2Z(PS zy;ad6NO9Z;^O#aJCAobF$(C!nMuiAFlH%TV%uA?O8RkmL1EanmKX^(yq9|l7 z<<3+K%a`Mq4e^1f%U=ke4XRkvCNg&B0V-$_M^gP|ON6Ty-dU14me>Pt7 zDn9%>tv*>f#G$zGGfG{)uas=(-;p!WK4uR9z|yFFRk1CJFXNc)mw6 zS0NZ#_a)?iS+czQDZiEVfiE5EbHOROTD_}lZvL0secfMlrOXiQp^%a<-Sy6Ss|?^U zY*tU>N85}hlnbf+AW+y@vEs5CA&ku`p8n^QLxa9A<{4#F;UvI|687r#32$Q{k*bi= zXz3Ywc{hs(bwyqG*1kT;B)B597MgJM2PW!>+0F($74FXecz=^5ZoUa1}O%f;E8Jv$M@KK(0v#d=O*b0_y??E)y0eXYFKnjL>~(bFe= z{`{L8mdEDkR9?WoV`MZF=PxDz8BH^+Wr0WrFPdVaZ6}%~y1P>A|l2(RUq555C$3 z3_`I78XCf{mWDXBO2jt4Gr$-+)W$(9*4JEbWX~Hb&ztJ(GRT4{G;8MC3@6gQN(EnZ zeY}BD)s(?>OVa?F#Qv4bFD?P1bY6_K|QJFr`Gn!Z>V#~uDjv;;)$$mSs*&ktA) zF{1TPc`Qdumch)QH*D!J;WP)85Wq8B`qb1^*z&u!G+daiY9S@{`h!<@=>y!YQV#ue z=)Q1_O&!j<$(QMjOAl^#^lI-jJlpJ#`0xAcal>X(Ssz*L7ah;_-E!-QB0K&flAkw} zrgm9tkf~#YW=zb9X~eEIQWB{zpZ$0;l==b74S8PB5&q#h$+{RY=e3>;wgkHkM%&~R=a%2n z|Bd2?P*Fg{gB)Y`mFCYoPZ_at-d9Sw=x01W04kG4%<;v^(LSW)>h6={!_-G+rrhrf zr9XRCw0vI42NNdv_OK6#f;)PDXluOFi2k@oC7JLKhcsLwGWpJu^)>leAKq3L>?uF9vwF6#1^ z2lJ8XD$vdeQvR5iguv^(CVB?gLSdcq&2Y^*R>=%31cSZLV5*of>mx)=O?yHrTjvKC zQO>hYm-C=22`Eqa@WAotqeGW$991to1uzurXwW4VLTtYW6D23^o43ptt9!Q4PToKk z*Z*j{P0AzBi{!g<&JqKqmw@2-0cFC0xCKyigWkfnnIWIJw9qDkUAKwX|>e& z9DWXO$)R}r)Gv_i+BQO>?w?Uc`Y|>5N5y=@gO)Xf_5V^kiY)oy3BExQL*8laMVYG$ z!}ZuXEQuXDZ@+Ubp zf;E&3g@HtzYX>wv%r&7r3$MFTpR*iv_ld_mM+fHqwOx&9J7L9&2xj_}jK8X<31Ao5 z+SdA!9xO7s9wS21O8oin9q;o zX-waLfXNB0Z|u+qrbXuxt^2LrI>zbYKnr!m*+>Pd&Kcww5sm^dGap$C)Tf|hkw2|5 zw{iRwxg2BSWpRK$T0$q*PXKw30?zh9u@0xyOF*YgwBv(lr9N%y@7`^#RX2(6;t{;v zRfJeR!0=Nvbz(+tw+&_cysFgi%>J)@am&wcM}9xF?P`>@e$LhLJoTS1GkpJ2z2Kzu z&)uc@`O46QKJ*TQ&(F+A`I)aREbOt#=e{9SBB?QN;8ve@Xun07 z>kL#epaUgJ(BU>Gd2_T#ac=wOXVY$-A%0sh5L6qDcL_8r^o!V&;@#pUb?F%$ z8#lHKw5o_FVPS32Dkipdw6|OKf4!GdO2Yeyc70%LuanWFczr{B@@8{J+iu2yYf;(B!2wy{7n?Qlmb5C9%z_ zm@RU{+5|CsQ{HdrhN%MJx-YMxDJb@hnz0*}0i9s>=3IV0P1f3L=$VrF#<(mCBC`yb6Z zH?EG-KY1LBxzcC|edA-r1Pv2TML)HGVc>YS)K4uWRNGF`TAU4HYOk*?lz*5CP)S_G z&1{#K$Wz*JOJ zpehuf(e2zfJ_*;1!?3xz$$f37@o%S2fF5at5#NgtF}LK20t0w$Fkx8YTlpL4ooU~J zQj5vZ?(0rrQJpWU#q$nkKZkPZcb>Xm94(y6-{yY3d79*V*3NQ(K~G%w#Wk6Y(C6y0 z>o^8P_{tYz*EYPctEF+g)!Y4Rc=m$l6ltad8VlyN3hif8Lig6*+b+%bhmj^9Z~??m z)7iVa)ndlu$8^KP=bN2cHrTx}nfVmj0qfuJc{sK5IYmUGMg{mDzo@!_Q}}2^!q6~I zozvRFLMzLl=Dbt?$GaDy`R#>}TH&h4DGy$WTQV{)Lj+WnCX(=hQi9mK zAjb~w-qeXW1*1^jR%gJhYd9yvl|A;tfV51w=Z$97PNtW$Z>%q$!8Ds-WPPKHTS!BM zzcMd=#=sj7tDTNM6Pk}WUh3=;8pXb-d$5f|s-$eTw-?I6%NKa2vAd){#2TRzULH<_ zTuQ$kHgD|X_e_@IP1|$XS+VCHB@Wf=Cz)+zbPP)~C(NN!C_62Ui-ThZT90nW^Cpg& z#JI1)B*(g%8b7H|+Y9A-oaCeuc!wo1QVF+NWZPc_!N6?^n1nV#?q%L-S!nKrKIGhz z97eB0bmYFcj)dWnx{6}#1vCytmc=x6&;IM@yGKzrgZxQEsVc7Ci~`6P#D#`BvH?j* zKtLiPx;gf)y1Lp=Qfx(o_B_eJ%ucuzbGU%*C#ZZ>ZvWBIJ^V1C-(n5-Yt|@L$@5{5P_cO zUfmY6ZKXU1^&hp%E0Q)R>ulkLam_q)l^ZuO7#{ys#CzJ=M#w($=s zi|%3kY<~%=;2AFq0(|75ZrIjN7b>t@AJa*vgcYbjVcQXgUe4qwx$sJhq#iT@^%vUJ z1=8DGrH*l(FPxpV>>cb&Ut4p0_oLcC*rw4<`&{u3@#XwYa)?Ho=4}4DZD{-2G`+=~}&Pd0kW6p=jzn&p_n8*ZgMm{O%bS2rd z3m5t+6*@oiFJ;8E+BYwckcOF2ezer7EaFB+hv;e`BUo6(5{L@%#8D<9{ z$3ky5f!jV&vtd_+%BjFrI*vkr>UEH-x0+?0hOP%NFhoxbI4gHzJhhQ-G|kZ2TP0IK zKivrZm@78S4EBWXzBeFFxq@hu}!VVRZcZ;2Dm|ACi5Xe4YBA+PdGl-2xKo{GAm zCQ)KTPrH1mPB*&E^KY;&K?FW-MoFzD8aiW_Z*JdtC{6Lr-EUkJ7>(n_^gG?sq0P&L z2|VP>@S0GuLZpT2Dv1QdKR}^_JPO)qY|W~M&`lchnrrIQgJ)pK!M|@m$VKA<09(md zl~_ikf3aBbr%1tJIBC^%4S(^ZcMt^-_?ITK9!u*=lz{8;3uHqmOGR=Al2Hfz>t8zI zJw<}XrpMb-;+3Kl7qhL3-ghb%OJRp)QR(nse|z&OCC}UWkVjkWe6+((#z6B5rSONw z1UWTz;2{ZF+RG?PdvYx)$~6GyI3IjWKc0|4gT#o5bX|b_je#ijnKK3@>cyiBltAoZ z)kZ{tQvGFng{I;*vR9>lk=Ha*%v zZZ|-E(8{jA`j0sW7d3*z+<1vU%6i%&y*YpSmms&jJm+`5ytBFK%WMtrAKmnhmO{TQ zbgTR+(|{*n1PN+_>CG!^DKE?0UoJ?ins#ks=-$^rkJ1UEBS}B~x2OsCB*FFuBn{dm zy3(jL4eh3L+Ij^_e?gT8%Eax?AB)d5VPQ1GfSu_c>^wT`?v$#DNE2Z`m>wFciRygb z0n;9GA`yQY2Ch&Y6sd@O@50=GNaOX!{OPFx`7H|Ng^$0=LRcmU+@j8Z(07(5M`b4zC|(I+QX+p$aJKH)d%1(tq+Qx($+H317gksy?G(w)_xQ&kAVBmtU1wo{q~E zi5^A`{GD=wMybrPy7h$8nTmE|x4XvEtuoJgTadyF*j65`9#{Whb^3AdCo+tUJZ@NB zUgmdyui?d}5UL2seS+y$=C^-k_!C%+YF_(9fv>*l(~hm&R!Fq}!S$0m_JsEv9B5X! zMH#ooymLbFec0&Sdg}~Z(=sklWy$`-Eq@Nh{3BKmOnx{AhD79bLt(9PpI~6|U0mrERa7#U*%0PIXQg8T+3ypl=c^RK=6YyGic|JWOh!{SUc^68L9Ijf(l|?Mw4Ofsgq|jKtmR{Zm#qITn&sy zOB`Sh6_+!Xz-SR;6&{AqoIE|dsPhca8Zez&6orjg(j4>A|8yuIM2-K-3NXrwQ)e)j z^z>`pJwIr0GY`^< z2s<&h9|#@M0H)=y1OdtPjG?zyZM$>L=1WQjZ5(Ogr#w|T1Fh);xM_hlPeIUe@j9D3 zgF28cwY=1p@3G0hyDP%q<^GaYtU`{RL&l4Og&zM5JP+}g2N#P49Fb`W&VuRYl2*}o z;|X}b9}3`LmO;X}`O9zI9UzHtB1H%!;+_`ONzfxne9eS7x7rj4cKb}^elxl>ONOaSY zfZ<`RgU(-jb1RAH{Y8SMKZ)(_05y$kXZcFs{+TEvg9q``jP1z*757z67@n1?kD;qz zb<*`m_o(yT1G*0|mgQldO0%}}`1ugetv(sc4Rj7)xitFo81}kY z*S?IWxVUlqu$l+Y=VI6vxw-#-8CV?6=mV8mB<`oLSzS;T0q&8uCIF;2aE7k~r|=#E zN34Pr;5RMvcnyc~Yr;1x94w&883+nQhqm9VA`{d6Y2n`zECBnX59+cWP8vkGuq4{0 z`+3nHfCB-~tIo4>c~Xi_JSq1;(w2``N>9HPOE)>N4C^=k5jWu25a+;G_h?*+x3#)^hmpo;{=85dJi8`9 zQL^@c&8kh=!6HA+^-)z6Ev9h7^Fy$a2D7hU9xL_9gJ-I(eAfCJ+BsvJlh=6Q#$!RCd zSbCCM;LaQ$NC^2IS~*aTk$2*z62d^s4{SZp@L9tMFy{tRp}Y?NB+dI8*Aq;UC;xR& zf{dg~KbX2VxV&)jb}|~@P?YZX-%cWD3Ta^_28vaiZ*)e z(UyhRPTmZ+3O(z1^$#2~Qqt=+S7}cX9)&IJP!Ih{xO>^~ozTMY zO4Btycji32=~dh8e=~`AV=DnattEHy@J$4u{KSIu?gG@M2t=F}tR#O$E_reL)E-)q z6PQ(a{UUa~-hDA2dHJ@rBK8-7-rV03XnZ+;nIOE^YNZHmLT)f3iHmVt zA2C!TS|3rIq(146w3$z`3(Fl0(FD8=l%B<>#96=XjK5uaf`HEJ6Fe784w2>)nBI6$ z7{cY4DMGg4F#I8n#hO$EG>WqrmWUXXbZ?yi778^TN^FR@9N{UAYq1$vUYbQ+YF}eZ}-W$I37^jGQ#es#?sr^2zO3(ZmcteZyMA!27 z%|?og@H<0bWI|V}7TN5rBc%r@k16(65Z~)4_u|!A=moQ{HAb#%TzM8DQl?EB%{`n- zj2`cWwE4Jy5^9(`wJRURcHQ*_2fmRE`L&JnJK7Z5CYix119N8nh8+9q2YqemYx>3z z%NK^rz!Ru^#Vuw&x| zDw{xv0u0qf`K!~OJKhH@#YKor{?*ArJ$z)*4V=ke7X9k6p^Tg1<1AwtsrzI4y?zm+ z0*w*6d^r1ji@K@hTQSg7;XsU*g?bv$6Tvc`W)U8(=fP)mt_1%p3~XgU5;6azYHPK? zzOf|eH)c9%C47f*V*wK4Kz|{d0vux5|vy(a~vu!p}`-Uem zBe-<$Zu}j4h<3dJ>1Yh~^NuXYdc0W5^iFE)99cT|L%3{-GNF&tG+O4*xIX_7%P6XQ zycc{ecLEqh&;~QI@NWp^ANT#h9_o;?t0GNQ5zq`>-ZmA`=!0KO%Q`pZct(vP6*!8O zgW*K>KlOiYfzu^|vNO7ci4b+BZIWrg8K>VC??Ck~5Z%Yvx@hD68_%V4k6f$7TurZm z1p3czWjuW+?FVt{#loQZs$u(j(BfS#Iny$%@cGE0JAVo+4k`;mxsRt91{-%y9dqM2 zI5))6vnN*_YZ7y)A`%?8@BSVwm6)R2x^NY}%VH*m8NyfdQ`28RrsC2m?vBNCT+tov z?xCYOCeGsG7ck-OYDgnJE3{M`{p+bF^lKButzX3!d83>ofOK5&+d@4P#vPLAj%K0(CRSt4FPi^Rh@P@&Mw1@iBVz`_GiRXC%B0+6H}v?5@NP;TzkUXlO9@G$G`?wa1*ygc{qxdO|a%*?yofxWatYbjkCP=)W? zbuTGPa7ovK>0+yKF;1eoPfi57^W8l#5+^VvNdLqN%s}g068XU^XzilAv`rO~(~m8) zaC%>Fi>YSba~d~of2#Qw9?sQTcvuD4U@)_%e1CVrETGP|pHxv;zn~9Yp7yU<0!CLh zWpf?3D7v?0aXK+(@NolI?ous{O#qTIkhL0!&_J49TPt@CSr^W8kw z+Og1^C&&CaO7FKJg-|59$4VT%Rd;4({C`_eJ3Ix`jBfv=Qu^A{H`Og!vRACisP}}Q z<;Ztqe8d%K8*gk(6S)Pgvk2XNS124U4(i1#y{F@4z)xGAYW|J`lfanlREE^9KN>#4 zFa~x03I0Cd+#_rJS6z0YTZBiaXl#-j@Z#^#+Yv}7vITty#qBaZ6ENUU;(Hio2C#*E zAXzf1WV*-acIIzGI$Gz5m{U83mj^sbs<%>?{n8-6}snY zJ%Li!gqdOPvo+jK7`}xO8|mI*HuUSIM0Wfros(CFM7don$1(q#WvzbB^4RRe6^b|d z{PZ8B_Lh|<tfW&J%THAUlRMfGsC3E$9 zjRC6Jb8k7Le6QCa>uavxihO?i%RtIBcPk1d`@R&*Nk&oH}8 zstE0Z1Xl`U%bQy|XXW>wtN*&7lHQ@G1%L9hq5K6==6U2F^}>oz|7` zz4Z@d7xjU5t2;P;Fm9}s73tU-uNrBCbk>6`$LLL7xy*|Y%`!e@tuMg=#sETj7o5_4 zAX&~-U*|JyL!=trxhDrxD2ZymdSynBlASwOva;Je(b&Wy2~5sB(^f`_?}szCa2bxe zKlq#b(rasP?pgkX=~8WL&{Wi$WmwmqtTe4unY4-3@&X}>DLiS{>NFUpf8GBD;+|dG z6{3Uf8)(G3SaUOc<`8uUM}lsKC|s;pf(X;r;meph>&wP0{F&>~fv$`HUqiK2b#w-X zhGO2lxeWgSx0*s1QCT<6Xc0QPpYO!Kcu&O%xnF+gzlj?-W4PaWd=z{Ka5(YuE)r#Z zWbb^L?XY>WNHb`!In`3zyb5V9MXFPJf@WPPWWVB(LS;inTvr~#y z!SA-+^J;6)$LsBHtL-=>88C4!c%6VhhypM}e5O{H>juj=7dtEYwYxkvXwsgo75(;1 zjTA(DVPT)sGyJcdG~nr{=1}ej{glm?d^0~Is3+TW#H{OP*WS;pxiBszitYZG%d6C# z(l&|T;J)_KxBDL5^X0@j8*V1QNeo}5f4|I2JQG))F6f0-HGtuYep6Yo?-a)5x+ty z_RY2ZuJ~AR=l0F zq(Poyt3}l8vL!?@kDtFlA0V9K2=kjL;&P8Yb>ie~7A|frN>>LTv&9Q0d>P~W-Rxh! z$v(;QfTLSSi7qh7l;YcOKc0AF7I9}@_eXK3qdE)9Q6{jIb6n0+cd+=P36b~-3@rG= z`vR%@DBT{BUT6)K%wR5E|nxRO`=#PYIz7d_?}YUiWCBde)hlIH`; zVUJ{_o70+AwshH0s)VI>!-5S_#Q#2rfrZHks~lSOtomXpTO3zM_tp4g@9mKdf6g>2 zqDN2pZwHtx;x4t9=4Y$8lw%c43pv=D%S0(4MYacuSCMkj;S;n+hkh4*jiLR>e(sFy z*0paREE<29G5)&$#zaJ&R(Uiw$Abu($4?@?u8w4OCNb;YnTVqk%v_nni>fYOe$kN4 zixg3wICu29MZ6^CXy0>rXZFTASAGK+Q1MBX@ezzmqmbX6? z*%i8)@9VCu+vJkJy!CSIvKsa;t^MXYe^y97E6(6Q5w7>SD^V|F_;(7ZPss|8DzJ%2 z{=It)tR42@@cM0yp6_2Xj8U)T%P~*iFsw%0xGY=bPhjy%*L-}*uX%bY`t-VuC?}(! zUtQUxh~LE<2R|*LBFc3J#2$f8u-N5&2_S6qo*rH=;~NnZcOUh z`haQkBg|^V^N6>Dg7!rl>4ORm9C}-h&wQu2NN*t>mPeQl?w4o@vxf?W&zhJtx0Jp& z+|-@I)XvXGv!wcbr<>{muvCOk!k#Q-Izst$JyM3S% z7+4ZovDvL5#fhq~vg$)}9Tv}S(L~7G>@nunHBB)x;81x#SxTU?SW6!1-|Ttu+lyKE z`%j*ehsWYZzEKc>Y$6Vl&xj!onh-1dZ7RaSSkgM0lUT{a90>9+*d?MgoAkZ)x$T^ zhq^6)G^Zdo1ZOG@bY4AuLks}_>*V%rmNUi4mq%XX5#pyWvg$tid9hUL;MOoN{WBw7 zLiYL5c_EI!NnCaEO4GNh{R6Y`{P}P{oHQsI4y$iobJvsNj@i&ISc#f1-BWp`fDCf$ z5}^HS(7_(*U(9^)`1al>Su#Zhns+WW$n0lpqyz;xT-cUL!{n^K_|AZFvMORDg8Y<( zKQDkfcHCNd9FCT+JbU6l)(8H;`RujDhTPg5{T0g3#uu~UbiJS;q%5)Yb=tYBH>YUd z)bVa<3#MM1>(G*7W?jBV=q^$|y;;bQLS|38B>lXEwqbt_*&=Z!vlLHQz3!l>6_5MMZA!bD)*xZ73mTdZfrRjXLn%5;br5C4`h9H#XM)#l=P;Y6$k5P z%t&TgKv1JA^RxB7oX9AMSCx{oa^Yrl@=#4WRTTk$qbzvrH;X&oEOAC?PEhFXmHQD! z*N3OA-6IML*%1!ur1izc9TxFJVfwoI$oFk~fAWx+vh245P z`Fs9%)yv}5M`wt^g1%A5+RMa029&nDzOpqk-I*Y6dK4RfA+WJUa+-mmmbc%scgBgY zoWFFlbehrN<@s^_WHMrnt=GJMPHA(OWreHcna@ic$XWnfrpKN@N3xBTjox~^z--idhNOH)dj!GufM6)%&a@RVJ5<% z^yI)~UhwiFziTt@_dQ!;8)Vf56%2>NS@tRT$riv~8wnX;o!p&mx0Vb#9Nr=-`Jb&& z9ti2>=i>M5CYoMzXt>o-=8P2RLXGCtFP^g>3}mEP6)TnJ4kV!fCq5`gIxRm?o^OLdm-y3nRBpa;e?Hp^RIgsZI zln^KM+VjiEbot)`O$Q4EOSOHn4h%qbyTo<5sgSa^Qu|%r554yiL)rqU#DbZlS&;_^ zPb6OP6eMhCYtyh;<#OQFtc~0J?}m481(?JZDq-k8M4ls@E}jiQJo#~H)1P&mCtTS`PE$Mou7hggQa8y!ca9Tkka$$5KgrWv;FwxEwMRso z)Z}@@<+W(UFh`%}Q8>IloUf!)^|S)-PDi{pk?&od-CGe0e~~y{qxQOdD|be4vn$|V9!d|y=jRbRcg2=lgO>~~5ew+r4?^Hz_w;vOEZDYkZjl;`+&ice*i zRoo5Rbk!R9`JOte`k_v_{BGx-v@$AJ#?XbLR+2RYteJuv8oQn;Pe1l7pK`(Kr$3Mi z@e97#qC+IRJdP&pHlKe8fBSISTuA-b+Zc-KllY_Q@9Jp2|0w8Mu=KET0Y})(h7xvP z&^V2lnGCeL^k~nSmo2fTF-+*q$>G5xyK;jY?22lGr7B-9otup*T-2&+wC|gG{9lDE zwKU)TKwCn~N+-|g8pUxrDW>^CfMk=gLGM6jgESL4bQBm^ZsaW-1r+c3cdyO=@U48R z?p9-Rhe`WZ0RMxW;mppjgIexpZF$wJ8+(l}+Up=L|E-twrrM4Lc_{MY75o@-5-aZS zl%zgqx8|cB_}GzE5VN)o-}sFdMP$V96S~p?{9YUGr4Bcom2Noa_&zi_6R}uct`hpn z?V*ZZMk3vTYX%*r!zRC@a4+KWC!Dcu8-yU3kf$#N*Wdj-yN4 zGD9053uu(1mhdWd^lc>V2X0YADs_`a+}ohPyIA*(E`jng{dz>4^kcYT>=}7Ul3ZmZ#rEMA=U>0N1hkzK%b(sMLKR)o3;IA3{Jw+lpi$&>N+S(z zOqfikqh&fg)eV^oLQEdJJ6T)O3I`{3AS-%`YK6gDv{kNALriM*wb!mb|+YG zvY-t9qhEcrFf^AeKbJH^KAg;TdzLL~sC(@6;o+XZ*vI1xi+o#ddcWpfTQ=`=m7cfc zpO9)_EARC`^-?vhlSq zT~gI^1y?&H!lxVjJB)FY&o?cIJ8j=XpDTY zPA(bUpPtw@^`6DIa%BS-7uChmIo}Y0*dkXOaE=jm6nW4?rgrxAv4n{M;<1>hD|e*u z>LdKaGXm~Jl0*?hQgDX89m(PS^^z65sz=$(6F^~8t$#ezhCJnowSUJKJSKXLjO@KSG&yIX8egK3(L zYf)SYeMIxL7O}dzdj0x!c$nahd}HB>AJzq8z=sraoTcQq*4EVQ1ZlP#?j4XU~%HM${8mNm2W;Wikqv|?jtOFR7V;z zCux)4UhXC(1uCk()vKd>?bf(BzI|XQrh9o=?mlpkuRFac-Zbv2hmD5u+vrM4O3KRq zNLEVRLe%Gl`+l`5)H+}8sVtWUKoFIqlK!{zWD}n+4OowaS1S$uV)pBLM*W{@uu~vXN#xQGeS6d;9tLmukVaQ!2lfzj$-C4t+e|ZH?7BK)mdj zO(gkK3&Un+Il!6aRH&LZ;}c4QK|F+3c}z^!_hvzR!W2tcj@N@Ig9)3sGDN>ig+~9z z{C=+X6|1{X?64K8_OKKzM{8g4l<#DJJZ1fr(x&Dm84T>PdHgtgz`E-`!HcR7IHI-& zus`D*=l#81LeY(3U^?4msS8K`3Qaj#z~z*}#0dDT2);Y_rsa@lzQ0s_qwL0{r)}S@ z`RLwo^2wMF5Zt7f|HfNo)s^2ACHA8dyEa!VG@xtbBjI0T;A4$-kDloNu@kYFtokL^ zAUiW$;!Ea^tkR692&p5aOCFmihx*aVPm-kb~)xvFBXfm`-xSZQc&LjFuq`*3AF#QwlkuUM~ zApPFttCnK%MaY9e^yc|6nXsQskr>!u0{XO9#&6cvkAAq5z>!h%xPg2!lm>b^I2fUQ zLf_JIHY}Y!I9n<1zKL}8!~dY&s&?*D7s}PNCokMHP^*|vBoMG3yC5=$xPFnm;8%Ra z8viZ#d*H6U>)^s}qU15&Q4VQaS+H-RKD6~-&6of%ph2lJoqOP;a+Brr;@0j7tSWRl z&7)&1ZBISZR7x9zu0ZOz0qf@add(693g$^jKkQ7^=*zc?fZ=KIPKdt##}4zT%lc2g z^zBa9U3pEuCa9j2aeV**i=~|eb>YeYmB2j$i2nbB7`DFiNYdhJ} zNQg;JG~zb`x&7bDHdu%IrSv`SY%L+#wSGZz!(+UsD)o~|K8y6G7NK&_%onYt)TLoK znS2Igvd`tLGlyZV;x$4=UW2ZxWX0N7sGr8mpvXFt$mw+YE)w^@Aa7B^a_CtRO-GTL zP(y(6+@D##4k4)tSvo1e}=+V9@1Hpvvv^sKU z^K1lv-^>?4f2ciCWN|@TrDC<3b~OuCG)bpaNSYxs5V7~;M+px;L!Iicer(}LqKVMW7amK!~?=3)9LVQf~hEtbaKmRZ*N&4OS>X`q1iUVTUp^67N zr;U|Z+MvSYZoR;U=#+25rBq=z1Zk}Y0M(ofNSRW|GhNVB&Vhx#;#)myEGJ?ACniHm zOR=HU6><_OS&nS-P0~l{Sv|o?;G_kO!%ZQ(&+I%CZGLaJz2OdJTA%(edIRBd`P?ea z(cX|M&9*eDsE&x}j2JQ1-O3hOVPXcqN%QYlj)dY0w)RlHma3`RQ1`5cZHRC+e_-I8q8)($~AUt~cCp>~u zLl|4f=kSVl&#{aOFwJY#9A3Ae5E!Sk@GEY4kRK48yu!ZPwP2yhI zk;x_Lo^23mhLA<~oOh1#wZB@LpeuTR`y$p?{HqJP5NwtD6UGDLMB5n-AYGL;`<<_G z-y*NZYcXMu%VUo>0s@l}apu@PKe<=I65O>@;c6@0_<_Kpv4>a7fjzKB?bJg}Kh#cb z`g--uhcc!0M-kO+%_6eG<&9WpkJ956e{q2S#xJ)!I{P<}3+mNcbYFKHS#RIfaEsTQ z__!_aiz@QpSSw7k48DzAy)%@2%7MhDa_rnLt1ei~(sWHJb%i#5$Mi$g1*A?qm@CneGnWeOA;{%Jvf8a4e%c8F|G5B`A&8A%gYLaG}Elv1+0nNd3x@}x(% zS4)I8-4P#W=9%f;Z=aVrLwEI|=I7hv)78(@Yj22SgDzFf>_|WJ?Io+WvMcXXN~sV1 zd8dnPB?q#;h)0L^?E;ZD+VGA68i5+ioej{Bi<{9AvY|73d7ECIy}9GF=W9O{cZUWG z>eH`@ukuJ0zFvs3Vr*PI_T)>x&K8FDo=lfH+Tep>EI=byMezn)t~^HJe;EVl(?O`F zt^yaht#8vnyczt|{-l8D{J2Bp7EH)56RU7VJdWXU$ds(l9v+S1*uN;77c~zQ*U@BTO+m<5`MXU8UBSa_Uh2<+T zj->lL+A4H4(`y;YeaU7KS)6YH0S03g=N_ssKJ9tx#m_gdt`ivu>rK=EN&*mGqW{AE z2D7z0$m>qtvsrIbi%4aK^{NX`9a=>IqTsA@c%S>-(w`eIW?B#mt&h0E4_5KM^Dduv zHKOb;*chE@(-hl2ACIz*o*n6T?OoRt$x6Q52Dwb5d3GcYl^n4YdSG8g7Ih;bs?J~7 zhSVkgR1K12_i|x1LYGM>l>*D532WsU%NJ=lF2~x;^qPmG9T5mXd8B;!Q6-L(n1_L^ z_XD(a=|S~svo!x^U&!kP!GiA=-Bec)L||_UdYEeQ&*cr0+Q8|$RFb_#cq0>Z4u2S< z3TJ9{47>*2A46}e<5sgd|Lcc&l|3JpkVL@b>SwSiXlySOjqOctBmQZA_JhYS2^LdN z`^zHD_>bW&Pz&KI`*h!#a3Lc3zB95Y@SCScB7+T!Tqf2O23TV1{8ATxO$EDd`DeIJ z%3lYzcAQ*ar#LP|2;UzP7pu1A?OxYTIWF)|FkNh4zB2Q zicXIF7hDa12%yff$53bQHx#fO&i$bgm3(H`sEByge)8ufcf?QM3Yf&sxQ&Ecu-ztz zHorJIw=7%off-ej8P9$s@>94|HEICIKs2sTEqrmM*0h3{c+~mIC3ZiGcbiEsEIiiL zCL<8$(((?mL)HEOl=7qA;~qPY3wN+qkQ`vRTd9bxWzL5-zV)%zcjIKPo#D{d>S2fd z+mY}%DO!P%mg;P#PwDHhK_*+#J6u1Or{VxCG=t<|B=MXy8h9?e6r?gSVm5%ciMRyV zrhCVX9EoB^K3aCnyF9Wr)6PqgWMs4edFMdQaJVo^H(vTmouPZb(wJ1K5tOAC(=Z*y zj<}ZlTxc z#94YmVNk0`7L@;##WHAeNCq6+yTrq)++Zm4;6l+_H5ewhH@gq>G*5>xN3$6<9XTeS zA}>uhqc&8kY;iP~dDFR|*IPPUDhVNOYYK~#(AP34yKIlr*~-1-`2NNCRj7IcfYEWE z1A-O@GFjoYx?^@J3_qzx&7QA$Ff-?Co^;~UH`==LDz@60jyC-?Tam=F+-XguOG*1c z2re^9+fU%;(ZQI&!Q2k!G6Sp(GWSv!xwZ}`UtjQgCNkeXeAhE%t6hHjxsQ1eMNu9X zP8TlHOt>C<2=u~do@iH)(8t}(L?-d(M!59Elnd~w1}{3ui#2gw(ai`;=)RY(H3B;R z$iVYsMI;;_Z*&=G z5L!0;I4A2l&I%c_1*l3+&V=u|0FvbroC_&{Y4;_@r)(l!7A!&A{Pe0Oq5W^uQ=q(X z?%1j>#G>KVA9`1Ryd_El1WRl!<*Vf+#n7xnhvlc(kKE&4lo@Iwd3qAcy^(`upOVv+ zWrYFwfF%uyzp0)f3q9tuN7y0Y%HX5nFmFoDX1ShvP144GVnv%jlt7JUKOh2vqc{a* zVcFZR9P`)3<5wL5>LL&#HAhupB60DBxL9)ZA~;I@Fq2E-`n$FncyZ`L<38kEdGaF<2L z74{^Go^oxgEcc)uud#Uu3j;Fw3@9$9t2WanflcJZO8sK(&QSt|nSwD}5G-}++-5;> zFSwWcKo+$!UK3;U;qr2S2rk#A^IDNPvHtbO`2@EksTZ$^^3r{vBn2t?%TmE7^5^=m zJFDFcaPsc5(sN7_K}R{-kB~br0D23!w%z1O0+%V;X@evlH6uOdlwe@Qu(q3#@z&Io ziwYZi71gNUcRvbxrPDi}^dMi{;@exHLekZeBnwY^8OL)NM-Htde#HcQeq-PLPQZqgw6+^kQ2uj>cedNFkBTi|rSGRGPN3$bTuH7JM z#=rgLm^?nxt#D|>53ctw`bL$QNx$XHu&@_O*^JKv7FgXu1A_RiIZPn4joeZ>wB{Hv zBL?EGu4Xaiq@MQ!hJmM zc;>{+n;ZReqa_-dKgXy#5DT>8Nx*S zs6es3ubG*P8>mrYVqzE<$v=pQ6Ln~PiZ)~p_9PlWb|mjjiVi1U6W&D!plE-fyZl3=~%oA!;#UHJb2|7J@?LS zSzbgKe*JmkOPrjR*4AYc;TAAENG(+zwX@t@9KHHTyT=p~77j+>qydJeED!97!RlqN z+GC|~EH|RN`(vux7c=RL2)!5$T7(Ce#vAAn!`_jRv?5>5((pxIw`1k!?|S%~F4RRJ zo`)g`M!>0i(()Sr{1q=(zFxX8O+tuf&U|hvVntCesebwPmC8;;yW#jRAzHls2f+}@ zgZ&E0Xm2(%iRQ;VO4@Ca9bXN~axH1EYrxc;ODh;82?9{LXO;W^h`r8ab(qU5C^&N2 zy292tF53Kxh)y}*EM0xguP$yPs806S&V3HZjTLi_g@#^UL)iB0HtW7w?7?UgBEzR0P+(B=(siMf|N8YF z>w+150a^m$>$b@1&NQt?<7F7K1ib6YnT+y5gDeCbY}aW(r~oYchJFfQcYB>)(0=Mm zO8T$Fl^e#!33lZ*-PJEMMC0(KAC5%!{p@@WxbWmq!m9-Vbw(Qah6Ic*kdu;37V#)%wEw$GaTLDgyaKI|0)c=#-VmLwyu_Ue zr;@z;t0z|iL^@X6v_h3JlM8Y%*!fihU<_t@$x=NG81wxOPkT#`RS}8>yn1!MZ8h$b zDE7yum%cw9Qu7)I^eNGOuMMDLVuXPzB8I{aDi9U*HLOM;u8bxwu|{h#;vMtqU+vMQ zWZ)t!47qJQzvr2wdtRT*!TM86(d4>l9U^ov{()Jg`jx@zbb2F`g1(&WY;qo5VOyjW z@rP>`onTswo1@Q@k}9dIo91b<-3f~|Uvo4E=zMN&Zh5jiYNU(`0xBRs>x zk~AHKRLoD;LWV3D0Yyl2868R8=+)uEF*Fx%K=;-mFBOe2Y)GTCd6#+0F>0{ zyfIT`)HR3!g-58*To}FWo5cNwcS~@$KYnUu{>8_uwO73Y~nQVb>`4c4DwXaVu)uwtE#cg{l z)MIluf-vP~d%|RCT3he^H%`;*pRkWPEutxT2)A>l5uJc!cx(>iE#sIhep-`UNE01z zVv)N$#d`OT>7CIg;9zh85NlEt&!J=B_ljzF4)t+Qdto@oOA`<1cR)YsHK9t}J3shV zF}>#9#Vfi_QQ$uAOSAj2F;0wK-jy(Rq82^EW-hdpqj`W^G2{F9mbrrKXXacTcl)l5 z4!)vXcv6_fx~Fuba2dM>FeLa_zqO&{NTDpa&%oX1zPY)44ADl19AEyiU;v;LBL7h0 zuxNkZnF5=ow%99aB*t1P214<9mro|_JdqUIw!tGu+zEJp2jAXkIa05E=h>WIdns7| zQ(Fm@eI6~dQ7wekDvc(B1|-rCVgFIpq-fID>TTV>*bw9#aQ^zmpNz%sU=BH!Ggm?@zhF$m{TBSVe^i2t^dh z^=8Kf1LrfOI&P2*?MH0H7U3of7j&Zowk9%7Lh_Vn8i4Uce|b!BJa)w7M8}SRHYki| z(HCji7zh_|PU5Z3zbv(i8J;#cmZ$==s~lUI-Db5#s7LA}zotRS;KRsqE^KE;5?&8> zjx~e<@{ni>8ozrH9b*^<$!?_yLw2v9HeI((v#VN-C~ay%r;$x4R^5!7k;e~z2wmRb zS1kR#+R!}r!eggAG4I?^hid+pAt8en8j{gf!7J>3CJG8neqAZVYzNdl*bOC)Hz>Ud zouX7~d=$X3uB#R&TZx$l-%&R2rcSZAKnimD)48K%cdMFGYadoLh$$Jn~Ir~{N;-qTzD;kG??1Ca^Ge+ui&g}bhs zsr&T^Rfo@Jbt$K&f*6V*p>e0SCkb?KE^b?-I$Avj6PmGY6SeD*xAC$xy~v??;Z=Jv z#tc4a?UoYuqz6U?#kK$OBTsRG&_TcPOCoRS_HqQr+0J6`X>^h?Ps+VuDFi+oaE?bK z$7S~>8Db)uMwz`?_1=JPX-(3=Y`F(e(jK@Qmgu;@j;M@4P<&s+IJPQ7ys#IE$qrX( z(@Y|UHlAG(>WL|3tlicw&e;oli2{toXlS`vN8kuR7q95XEEq&NbX2wp1-`9ksx2Ni z(@`Nk57K0V)baXu`j}(~Z~=$fVsjYV(1~xjl&N+*Qh@Q&YP0-AZhS^i^)~G@repv3 z$qn&IGflbI9)NvTwv3Cf22t|d&Cc})g*@cd?y^3hizesw_|i)_0Q`udd5a1f;!&zc z_oqmX{VN;jCUNtj1F#AT(9Q7%BMXRS+G8k}@Vm!Ym?tnR*<*EokP=&% zCHns15N34b+GEWiN*4I9M6VlbdmlfIn`Dm$2nRg+KYlA|ZC$-Nm$APs9Wd#sqF8M;A%5v&w#!=_*X_!(zY8h$wylhEFKwL>(@6*3 z(LA{TlalKnWsZ&?=fWd1OcybGt-`9o%w_ts*FrmWFYCw$P~6FphDP|KPsZ{9h3sRW zqN+^P_qhg@kM~|s@?4z=x_5Yy@XZQr^rtM$Or$K#HZ0%E1UOaNRUDTdBAl}rUArwn z^DGEX!+T|`V}B0aMDPjo_*G-Yc!4YwI!VlEXgLFdrxx~k$rtrxK|lT&Uj^qv3kCX9 zRcygB0bQXcPX&+fiO3CeU`-O(h}m5WXUg>dS7TQm4(0m(kCtOAOCqw5P!v%VSrVn} zJ7sNBDl*ExjG-dQAxVz}%s znfHC(=Y5{%zCZW<`P_Fv&jqB0;+q$-%v1eFD)WeW@gu+3*g|@*z9OsX0D5wtQhJ=1 zLnQOpnsy!JHudi3))cXTb<>2|Keo}GQh;^&`bP8UD9xXvbBSnk(BVwXu5G1yO!+dP zr`m=?T>AHmMmuH867WL_(eKhLP{t#OqvbeC=r_@m+APizAQ??^F9H zJa>=+jhnV^_@=`q@b{AwzCe~y&q6eN`g_qbg*Eu5`%d&E1pCCZUTk=dH*yE}N}ePn z<}T=pi#pN?L+(?rFgUD-bum}oVkjSJ-m_kaX+!X^@iV3un=RV;nTrvMq?MTo4UkC^ zP0M{ZnfEvkoAs|RroFxa**CYZaaIsTlT>v@;(1ccB5yIzrRSDO*?fDBIVwBs9{q`) zFO8yUSU2DEmqlR1HfbnxFb`m6&nLg)=j5@d$L59M&TSlT>`uh&iYYyn!MrMKkFf+h z`nGZQ2`m%{H~=I4jfyi>fax&Y62fa1EK9}Dt!@@y+`nyn2NIu|uB9HwJS_B%s1&8H zYlIl;X4v`T3s(09PVIg@02P1r+rl87)BFDbuPJ9eL znmr++c4LpWcFoI|a;mBe?#|0!J8Ye?rc5MGFv60G_p2}2Ha?wjxDz-ozfb7Qc4=vC z@k4HD?ty0F!iVE*ot-lh5&+}3wYR6*zXg5r|D{;no)%y;-s249^RszaLNJ#

E)5NI5OOd+(ksi^z-pY-TVlbT|$dvNXpk79b%jtFP?} z8qK5LBSxN{g>Tz673RGRoD~p2-4IrGjgkZT;c_b~)Vuc@uEJ)J$>9Uhh?9h8Q{UrR zOY0M;g<0h!F$HQV0?1YNAvwZDRg)#x9^5QG|XTaxS$xj)eauRVIhSk_p4XWRryikLa9<+ z&H1IJKe|gUKp{)$fJSF9Vc=$rn)EMk-mxq^P%hR>S+I3R`vL`}FoKEoDG_%3C)=Kn zXa_xr6Vu0!TC}ICsaLLfy=~LI@H29`a3q>vehQdW-@m(7^%ve1<+>9Eeck>SXUYFq zz<6HnjvYG$6dby-4ro9RKK6wi(-jasm?m`TMjTYj9!S`hFzZA+$or#{N2vkNKl56v z?XfM=E3i=-5hXc-4a3a`HYqqxdMsz^2qk=cG;LV$H6dxu=+S-y--n(G>Kf82P5Dhn zJo{e!Fm-YiEPvM&JB%LZ zZ3uc2prG@i)U>TMYX0!7*`_2`5nL{h_xo>IJWAY0JxwJ?9yRKo_gA`?J=~6Nrh5`_uuiin7? z$@i_h&HnNdDwh%4AriGPYa!Oxmga`F~Spq zGaO13mouHlaXZs|a^|8J(Db#+lZ$9IY4RhV412L|&Oi7`fyL#^Q&rll)GxqX8Tx88Rv9b&0+@NzN#+4^@jBG^Fs@p{NCKv2&`r26^=jnW=`@S>;fm)xpQ2SaK} zuVrEH#NE@lPHGu*>I51Ca5ThbfWvjwR<5XguWwQ7ioO0 z=qOWL2OZZBus^zh#JeQ#qupix-WtQa-g}=ej{x230_h{V;?^p77Ts?5*O*W)5TV%_ zTh|eFfYQF55{+-$dCUN_?I~!tB%bWAjNW)fvy{D2QLDE}e?H`|xxAVe_54*e(AU1x zQ?^#0MB;0Oy*Icd2VaMo43|yGRgP5_@vFEo+yVPB`KGC|Wl(-p_-8S}6_zb^`n9R4 zIgsu-X7>Q(sq%ALyvf3gR}bcZhf+tbxcHpeLJvCCYG{BdcPYyEeA{N32k9>@9lK4m-RRp_P2@LRg9?YRXe ztcbZ7MK4Uax#8W}81+L`PG-wTvz73S^nRwn3l#4|jWHH^c(wSN7ap(XQThsFo(%y> z4b6?r!{t%lR6@!fOSA>>XB(na_3qL4;!Zqn*;ME7sehU0aDI5hAY2pyG2B$)R#mdz z8lu>L-hHAWAawY-67!JRF0l~i3?TCFE{E#3x4(4}NArt_QTW%*(-I2HeUL;9l($~@f0nyeuh@U=|^TneczVdm2)7QLfwNdlyXU@m@dIK+$_jOkF8G-tA5`QyL+x_BXb2kEdq)5s=;Q zXJ2=mR962AV{HidJ#}a0KcZOh2{!M~R5d?Mc|jj;+00=01e1z80U#7gN2<#-9cuUa zw80-ccsq=!H?$x{PpBC+j2yKbP}hm+IwE_O`R2!uG9EK;t188}Ln_6T!L8Axy_eN= zix!2XA_X$ymk*u5FyZy%wLF`Gh8fB*^DEvUb}kvTim2eElM)sAmQIo-{;p}*s`qG;8gRzWjTwF6tQ^W{V20M6GrWSXFV53IYSe3)_-tcdEWg_^ zwiY4LjS(2~nM(Bk;_GaghhLDpHT6IrF3i0h$Haj8jYW#{MTg4C=aQ&w(CswjTM>QJ zY7SkJixX^XiQ_~6!%Sd+E6@@Zy%ODTo`;WcPIhQd9V_k>^kytVmQZB5CNokIbU2P; zIO?DWJxLini%^!G+XcMCXTItGGSha9-Idp9`<3g_i*(1?M#ybFs6Y3EIHfI=UxWZn zSW5ihXd49EZ#{b!IVO!Hnrz(|%QV#cFH3vArkk9y*XKa7n#_DO{!suPyo!E&_W2(tK!*7aQE<^RkQ$D$w1YvKKZek|F2WCy!nN&X_l`@E{w9Qo4@J zO;2V#7?!mavW;?yvIwB7NFu;)0mpD)wX9QOqKJniL{oaoOb?K7;b9@%Jpn1s<+oQE zs{g#zPnekq%J1wmw^eMn&6R)J&U~mGtPV36W^jEu=77Ja=X$;8MB+PPQOD`a`AT&> zEhM4y0;9}v6t*qlVQOlvsi`su$U{Ro6qIQld3bb}=HL5yvldj`Wy#p2&IptL_c7i` z4mt#0jP!oLrEKoqFPY%Q?edlce>?ZD`Od;K@jRsMKX-m&UYtB^yIIOAbD~~=&vSa| zL)ipS((2V~2fFt(d8hF*iD4K!(Uh^|fwR(it1VPhqo3I_|Ja2mT$n_`cq&hP zeBO{DN^4XM{d3vU@hMj|HCu7D3$tpAt2>SXjm)cq6lQ}9aYNZ!f0gC7C&!pi7%257 z07|BR`7#8_Fr9tu8|UE_^h?N$xWdH7g3m{_S&;a((h(EpafThw1b*bE14hdm|Ci3L zw=jS$x13?yDIhRHCj0yO0iakA9{736%Iaa%QIXg& z&W&QbAV>lWqUx{KgHY<7QHKfIIbZtlcs8*pq;cNrs7SE< z$kMEC0r?R8#TlrC5-sxt`)L!BN%>90mFLoXxFgncnvjO#K`F()S5G$*2U;X z4(Y1<$;nF%e5NzG7V%m$wVPoEx*WWXU0oTuwH2rADSOqGHixt<^)s2jdxEEH)sHp{l z#H3A|9lXo>I0pLgp5p+CoZLRIoigvlIOCN4T~>MnP)mJk)#ukF>WBt{PO4y>f5rG3dYrT4Uj<~%S* z5#~F`JMtY#Lj5;hh*4$yXw)%4W-rWPwrbYCWUNtX6Gi!P&}IE`BhtJ^?SPyd?Jq#N zP>%=})NMI)-1Q}i&R$X%cGzrn^w#4$&5Blu)bfzQ&t1_iy{H<3&)Da0-;iB(nOa=W zoF{&t*O+%BgDB-n*|`qUYpV7z>3}O_5a~6;^B`!t+X5w>`Z63Jbd__mN@2E<%eE+ z?`)%InQL+lg&H6PA3=&W1O>0uZNcKS6U7=dQaJ(-i6ZC*6`18-t9;%QIzx?)r^sdzd7c4Emd@XbD!rGJR#4Wn_w4&~w*3r?qc8vn< z0TO@!fjy@ZL>+Yz%*W71v3CDcRn@FbV2`xH^LvYaS)lYb#|S~2AlpiT$dwXqq?W@D zgBT*0wv?2v9+$Y*O12{UjA+zpOH0eW$pK>TPc}~aEyKosi6J0Md(_p{sm}8<3Hwx4 zUze42{BS%mR)9lh9rhb&y0H)0FQz@9&f{Ra)Z{z*DT|?kdHovL2OaA5@5v1eD zJ+dNg=|``h7(Ro%Z~r^OR)^Wz=y@$utvSNE0#2*P8g2aV_5zI{7_ zbJxpLfZ+3$gDYEGT26QE&rsm**oHX^UvYd3J9gPV5N5edPj@CiI-Kp`Q{X_0s9fJPvMX z;Wb7h_CJJ=tPOEvqGDoJ7`u>y!W>gpc33mNZeEg`5n5SY9SZY8yLXTyx1hkNrie%+ zit+LBImAV`5$1J1kb@(dB9aiDKV~_%^Kn0$NtQ30&_AF__(gZv=V}uv8%G`rXK%KI zw0g-otdxGN)h$y41BiC0gTj!N^Y19h7%dR8`+AJyvaia&=#Jruv4`Bq{z%No2O-|S z=v6jhu@3!QFMqts~Gf2nv7YUz(Vh z05b)>&ouj_ADS#l2pH5ap5L!^uL8XiGJ4$0@!O#!v7C2CJpIiw`I{_vnxr z;jl#&?BA%+wlyd;23!YW?a+{)__I?f-34b$A?ykigdA0+(sNio8KZ-rZ}HSt|CEtI zfRGE0SR27m^DnGQ+(}!!u5SPG>JH;nsyP>Mc6HYfP_e*9tiVEPomp~BWG#V0e+)uR z#4e|(*jT?+fCGJgz1M_~czU2vyW;!$`tl1a4QkTe9=l1JiOw2-s3+}u5xYCbaiBp% zBQ#Rz>~ZyP!bxk*jMD@Tc6j@~Pc$V6lLM!Ej%8s8w}w2y`CyngkcmceiGJ!751PQ{nr6gCN7E)t+X}%Rx}^uo6c8^_ zb&T{v=MpmT5J&nYSwllSul_2p?Lfoa+?=XMcQL$cm!J2V+t5^oHD2jE^h~v@cSdui zwI*nO93r49a&j-RSPC?Er7dFU{?E7+Bv!|bjfzxWP6hQ`Od9KtgwqS8if1h>lmli4 z!7$-x>Nvr+v5cik3d4%7C%Lsq(kd*q7&dvOPmQEP-rNPf{{rW}pP5hU22LEKPajmw z6GFLaEr8TUzx;kpL3MRCM7w}7H&h{-%>82m`?%jz8+ z*SD+@$==rdnYBa$t-8{2O}rtbyuq2Ea^e_~Yrqp{Yh~r?>U!Js_oCjzf$}m4m?+OH zSJ?AMKk~P-Ds{cDpAl3llIgcssOooea!OB67vtw2?)W3dIa#pnr?(zAGqn6IyqaT1 z%gH$#S|Kob_iTdBfQtX^%K(0@qk}d$qhYh)qQ+?JQ+YOcxuf~u<^KOKthZ2xnE!>r z*)D{GHwwiGqg$+P9aWGGY(;w*op;8^ukxNTHr}4C=|?z`smvJf@fuL;%nPd=Sx?)t zA;WE*0<#MWJRp)ORT+xk{gy!&11n2`ZctxeT>*K?U*_wn>RMKiB#3`1-@+KPgveGI z<0lUj5=iwesA*c@WJz;K`6I($qnWV@Tb#x7Khs*j-zZzE7CLBgs^8eyIOz2D?c3p0 ze%<3y`5bo(POcCr>xi(hu$Tj;kd3u<-V^XT0-@g(9ab6+$GPtp_?F0oT56l#8Isng zF;YNK*|i0QS?+~C+6DHwkFLsPIGi?gc7$%3T~5K2lgotj^^xEqq-mjPMqQ@RY4Tm7 zJU4_-VX3#bw-bUF!T2nLjnd_a>?+4-}*gnS`R(}j~2E$hQ2%ilQXae$27T` zTS`U6+O~S~&-Xx|%je%W&yxS45itUUJ-CEBy zj~cr`!%}$VPS9bCvC+W+@SW(S5D8VdcMpF7MVAm*S)?{z&GlcfJ**vATfjN5j@!cf z;fBoF0R#*x;|PjqX{tF~dBG`j%DC#+e%f-%#mw8=+vQx&-xS~z`h(!Y=olG&VA$bx zQ(iT2-_OraT_koI=H>0%x29T4uA`X;e`N!7IRX})_vvzl|6O;7#|!L#ls0{-4fv=n zZEcGSm-20}Pn0e+F@OnpDyX9D^<@o>fjRCs|FDUn{Tj*NFhA`2RtOmQdyWb*pA8a& zSa|(7Wc!9t(v}$c<1uc16(1yG%TL9dSj1`>UaGJ4@;0pgX;9B}-Y=U~B;ML2N-{8-glO}qFCtPm+ E2Ti?D7XSbN literal 0 HcmV?d00001 diff --git a/localization/autoware_ekf_localizer/media/ekf_delay_comp.png b/localization/autoware_ekf_localizer/media/ekf_delay_comp.png new file mode 100644 index 0000000000000000000000000000000000000000..54d934caecc921be967da733cb2287ae2208e8d6 GIT binary patch literal 147442 zcmeFZXH-*L_b=>oI0ugfkwX&@P*gzb0qGE;NRuiZLQ{H4=sgq_kq#mP(gmc38b~N1 zAR@g<377;3y(M%)=)6(SdG7o5e!1h`G5+gAlD)^?tIW3M{LQ%%{ZvPd?lSx33l}cX zJyBQIzi{DV`h^R>TmAVP^^Q&Pbx-OSjknSh!$1H06F;jvL%n44Q8D!~aCh+Wf9_>} z!O_hfVlV7%>t%26=I!L}vq{scc;UjW3s00E83tsLrouc%DcPIH_5LaQu*%g#mwA!~ z-K2^TmWN(8R>6a1^-FqRS|0Rm+6IqxQ>^b3O=YjhC=cE0J}n!*2Wc@rZ*ZUZYLeyY zUX3pFV&4dgakvD!-RPsd=ZfYsjm7@WqRrpi_*NaFUI7W7cMtdTJ+CIW1Ml|JUz}Cs zP6k%*4O5N}&#r4(5$XxKO~Hzy)cOBxW7Px{p7GzS8QO06fBv~ZBnWZ*^Ybb3e{TOI z#s4vyT=j?k5WF94NoC&3W@+S^9kYoTFvO>?rqqk#F-<>N>~qIDHl8 zX;p4;r9n>z9^y-Fo#d%fbKJuv!_Bq{#v{%gmJNX2zrDTMNv7<%pKjrxt-aCRJHVsU z0m0Vlz(v-xFD?h|z!Ju!hhUO9@MMMY)Eb!Evr_z9n`Vq}gb|SOYF29mon1jy-LZ9| z{pLZxN7e1V7Uv@l;m)Q@o$*z68~Z*lpilP6BNN4kH_mB)ilE1GNd7r-m&T0YklHsM z#&%vGuR76g?EyH6IJd9ZX$?E2KP#@9=HvN69EtryLr2HAeV%Rqd(o=)P>d;uEu7Xgg#Q9KIzhpJSPwakHM9+ zG&E+u;i$mcF0_(<*KxjWZQRHZ#TO~ZA#*?so;qU+99wf%J^m4i-o3JYK?tNK$je^FSY zko=*gV;_SFnE3dM(y!hW7VgoK#j;96l%S6%u09HAh)Dt8xKH z-c&kV#1I&hx+As^b98se55Za(Wc>#^KV6t*&+Fg#ii!iVF9Cz(oNyX5qC=H?eV6l% zYb5+i@F&qb`IYWOxo<8HqRO4ft&^j>7PSL^cL5yR6Xi20`<-5XLmLSR#lab}%z@9- zymue5yAx1LLEEk>Iul)c{iag8q2ivr?25cR`ISC_T;xM8Z|vIU{@x3MZ%?>uhTPC< zZ&PK`C}f74sxBJH2N!;On0Q1X^Iio_tezoLVxrUsCx~7fveV;@ z?ICuxeI~h=frK>B+}_51I-jCgnx!>qJ?Kth)fPE-W0+UGJ*#R0)8JSFBO01}T*>(kmb2u z@E%COS1etIBmUYw{fKMwM;Ir6*n=Rs>p{biiq-btSSpomJ`hHKs>;lU*{8AS?gMf# z`T2bAqROYUSm~%{cU`Gqq4x~t<}hRR(g9(-KY+C;Gc zG1!vm=Du8}jkoA#CWHO7_OdEt^^_;NE{Sd!Npc zfVkh`$)SJ${WgVJQ5Rd~1TzPScsFduKU|RQQm*maFNhPd(bx75KF50h=X@7En`bAW z8GwE`Hi=7=E}kx1-(b`F8l+L7vbP{swH&cvna#3=y3Y~Ici8ol5HCLoU%7c$ z1@`IL&V|lv$9x%TL=V554BS0by(Pu#HT!Hd#P?n-=t!K$boxA6VFkajMDoW}`<-mP31Qh6vG{`XZS(|GXLerFM9@q2ETFow&B~fStQq$h@{@ zaeHt&xyOu>6!g5HW((ss$(q|2`qz*ov*Po~1En< z+{*gI1re{DTdid!*H@`N`whg+kMW`DOoxnnP2BC}@A~tMnMwNm4r}=Auv^X>dsmhayCopbEXB z2P3Z>dr+8Z*GgYb@2g2k0qn%sesCj0s4t@~6+oaHTCMvjwjP@SV`ic}=R-qPt&~1& zn%@a^=H72jME*p)T(RGg2# zGrjhJAt@;H_^_>)((Od*7}s!Yk-3B)ul#b4pDh@^M)wicojbU8m`|4bHirljZvJGJ%lMtH&_#v4 zyxnh9hX@hYypuT>cD|)sKnRe0ust3YNO{vXTEP+4=PDJ|WRI+N;ThDwd1j}WJCxYE z{(wU{UC!&Ij(~pR-71qcw7gr&rG5Vdc=i=FYpn9M8Co3-OQV-(Vz77hkjTxwdXY)Z zq%64G$s<#MXW#KklI>SmjA?ELoO2BR$9wzb-Ff$84VYrt#!TE-Vd?;UK^C#aZ*1s{ z@h*`eDFe8_B}t$)#hpPR>s1a1Y}zrXxXXcD7FddD8Y>^y4MDff0_7pB1$mqirr$my zTg(6&1It5x-!Dg&yIq-f+7nWH5UifbmBY?tuSzPeB;Lq^5LfGi_e(DpN|-`mqy&r< zEO5K{KkPuF!jOWp zxbsgTN8e~`eH$@N0iBJO7%AaFuFx9l2Dpf`6P?nelY-RtNp2I2!@wJ6`_Q&=XIO6Zu=;F*E4P{ zE#Df5>vel;U!2gOQJU{U7{;9IU_~kutrEDlD+HNq1YmM+iX93Uqnn$^v?=3-f7cz5 zTi8}T%y`Oipj`USX^!mgy$5P{!qwz0G&S>b1EEewcGIgP8ik)@AelfPzuv=}A;qn( zP%}lCi{)njhp&8({BIv3Ha1+$3!~b~0ls%r1;DEXv)@MTU!rU%Y6%SkJhZj8{zK2; z9ucZ)N4frKA~|iOcrD=VdHY9Y$Xblcb-i+&ff_A=P55edD1DTTt304Dnlm1W?cHAt z*y)~u8n_kCN}q0|*thcky-Ql$ZP#TL$(>u1S&-sTHq1PJSnWfaP*a=UNZ0p3=L<^- z7qlwQS(|@PdW6^{t?9nEjyMSjYB*P^DhL>5E1#|}B8(Tzj*qZa);H3>epB@xGN0^I z?%q4_YzlziylO#@U~wobr^Gd+f54R=FT?01Wl*cXc!+51Po44H`{j&S+hiA`_H>_CCz0bK@ zPrA-4hc*)o03dX?jeA(3^M?1V9IBNla6bgcsG~78Q_Ij1BB(Sb%Gcau=lrni zVo0nC)$U%i#wS~b=Pv9{MDm65;hT{d%6bBF$_<4j1+{1!#F+UhhKyCPE1Q)aUi0zg zT-$;mOZ(7y>XB2o;HIwfH{(K-Q$se*OsUTSPs-6uI_o)pcM|qDh3b5+cbtutV@eN$ zLp1`+*H>5V8!@${Sw~36B~$-54up;akJ6`O&)n#Ar`pM;X87wBd`5>(Rb9ALR#ldk z6Y1IHQ0wjavUcv=^<5LCiViVabMw03{>2>ajyR(lpsZ^ISTUDdSTrnW(L}Qs4lcCP zyE={?=@~xjikZ+cG-3`nlUGo%?VNAdO^b=uq{qg%r&UgUJp)fmJ8D|+<(wI%?*^1Z z?49pagw%E-4^N!R3*L*Hqmx!0OGti3?}Hd>VXi^hp;Y_3Jo?E0el!x%QQVTbQq5|! z5>s!X2+SdQGE3!ybNrMGw@j{<5ic@dsaGA!SD8~p|1UE=|jn4ZVm)JyT_^Dm`jP`*8DDsNcd$yDsJQMnouSm-W3 ztV#9*Mz=-mSd2k0H zu4PGN(A!}FOeV@ zf~KS_u1ON+Bb4_*cYQQ+ch4Z4+uPfTBWVP-1T^PlZP}cRueL#rv24iwlO=Mo+r%{VX*9iw+_6+1MejYE|eXu zdaSslBthlsjV+pMdh`^604W*p>Z;1Lsazv>qvQJH$ocTo5VfFd4aHe#TKDsn1E-@M zbsnjJ{DPfrejPOfXZAFGjGy1`o4gn2JP8}741AF?n@1g zT;5~@UxUv2^%WY_qo0ZYB=&`+A*DWep_L@_V;6wDRnQ$~P66eTnA*U{hyy)kFh`w| zerkM|t+eDHg>7I*q_#3q2U@S7j{eT705Df7?fSyU*RE_|QS7@Y z^th}?wZQR8re&pb?Q$0nPkvKkvwz@1_N=K-_4(qs5^Y9Y=arsZn^CC&E+JN|v`lP| zEe}_pF?+E~rAA(Z4f4Il1~u-|sHy7ECz&V~C7Rs0%LD(iSeB70H_pl}ZI`_Hei4av z^4Tek;&-*c=wwGlnc)|NUSp}C4s*N1u|rzL4qZWpaO&LSjGFtD*rqX1fFMU;jl809 zh$8b1CJY!+;pGG?7PXMGx2EgBu#!m!leyddPv(3S%md`+Cd-Zb$$Y9Z5^8y=7C;W} zN(t6*ETY3~F-k~NC^@XxzN>3vi{WQrd12-n$b+h>?512=i|?ZSF9Su9puP-Hznh9} zsoRkfTm!Q#EPkUe^h5f`(v584WW4|p=HNSW-mgQOs-7;uoDvQB^(*J*JmA-Z1nA8w zjBF@ot364v5l=AESXjgt9v+)o)^N}%+77PNSO=d3$v%-3=&0{Uc4|B+ex&!FL!sou zM@3TkJI>fBduL~nQi?&LriZ7D*})?-7xZj;ePwlNM7eBWp1yFc4Ya|=xw-p&K`z%f zd4&z7D`_NMd4%M^dX;K2GdJsG&dxDXW8k==JI+E#fm6&BLQj}scsYh=Ph-{T`K}Jv zZ$sq`JHY&a{ABz3K2AlRUqUqbM4IFIxB|MIsov`TAMO()r8elbrC z+>R!mHqDV3|EiU3&!_Z1u^r$XgCld1>>%$g`R;R;6PtxonsRF}=4J z11pg>62xWWQ{X}fL!e8CP0bBExc&i1PEg!4wNKY_|Fu8X**1cXX{8{-%l3)&lj#0b zGY&(8$C%X{0H04G-)zMd8 z0Lggp%uk!Km?o;U^YO)Y3}gZ}GIfc2;MJ@Az40U8)8W|Rxxh+M`61@}8t86BPe|e# zPYNiy|M_yv?Ea>ON<~IwY}8n$M)ILDx3B}&zE}sIzB(`n>vgDQzIM7K`iRZgk909PMin$&Y8P81(v)0_5fx;%X(fbV|JVATpr!K`+0WwFW&(6P!Tpds4tjw$| zV;T0g?~ZV{kbC8zn+CeAL(6xA!Pu@y0o_got}} zN%wgB;bzUV6(4c)&^KhQ9V$*y`nl~?iqcY9>5g)c@ET68s&j(gS=6*I(_BYJ3Z>Fw z3`6t9Yi1sL!G&+->MS zb2zvIi5_hwEL%yMU!r`j{MKxbEi}l=)Fir~Nr7?tjQ&jjYzm`aK*wSnm$C(X)c-ck zCiby2!dz+?Y88#wtb-j36MQdAeufxLjPSC08nxW-x+ejvsHqER*?|Jd?U|&A7 z%ilBi3_uPc-_G3R*DOy}x{-~}7&PQmh^2LPmTiNT?$Hf7@){wH?VKn46LVVLwG2o3 zY&S5~7T%~6&@3OHD}@4mM~gRh3x#|e{Ex%8$2@YY0v;DxZC-1!zLBSPtjqdtp4Md9 z8SO8Qc%H(LItXY4L~SE?V*SX=;F_gwN35=(npZMEwr=<~So#qnoG_16EMR}9c#FI;lZCpWmGM~ZXp4+t0(d0tQ z5~M1AY6yN0DwbX*ck48C)eFQe0IRZ|Hne!8r~5V1^&^FHlOMSbXgiIll((%}!G3A3 zD$$88yDlW~2k55aLFx0}}oEF}_EEsNtSa>Sv z|GDVh)1B#g>QdtF#G`9$i8t?;mTng(XCRCI?$EmHRn!ZfKhy4Ghs4JtJ3GnQ5kjM7 z5Psgoo->1kZHbf{G;#|3_0D+iH5P+&*2du(vIIMImWrOSc94`;&Y!oo=?R}J1zCB zuGYLfTYHXF9J7wYV8|c?It9*O{QTSux^Cvj8?;5N+|N_$E&3iDDbM-f2>Km~V1f$W zO*}j)TC-5@~b zV^<(;aSHZXCKVmAe6}0&0nG3%u32nt?6&v-z9Laq2VOhLw zlgtZ?=*F&ib8w`65ZaH=ar|PWHvKO4KZ&;K&PmScmag)l;UCRfQ$@-hN=rI6#_TH= z77Mf%I|WNWPY>=$;org7zb(53sp#3GQTEQy%Zh_&Frk4w%mIbfriE=JoN(;?%b%Ok1GPRoL+Ol=X_I%guM;Qovvrx_pm0p>sHGg6AbP#S@W^H}=QIgBx@A%3 z?hX~ZU%%nBJEkH3Cm_^GmvU&vIH7fr9^NrI-i#sU1ksn^acIFS=4@+w3XBzRd5CNY zFUtO{1?VwBqpY-}SJHQfyYEf;boE81fwa>Njahr_k8-xjXzRdFIiwK8-$O@5`t&!w zlhGb*J#&E`=_cwQg#LV6>|(hx6npFS6;2md7_$#ke1It4Xs8vAIM8<-`8~m zEck18ehk`4VOi(6*v{HZuRN5sN<2AIb+6%vHr6jc)Rwrxpm)>UatT})Qj1*1IF*6N zsX4RFI~mJl{o8@Zp%Z(uf(e7HcyPyeGIT)OdXpq?F#TS2DC-J$@YmH~9)-h?N|=+2 zpv_>FrhLS@pyJxfZn@{ik(>3&$Qa&PC|L%Ja!ocqnfil>g!5gdh4zhqxtt&LrPbDC zCK%i0ja}&3uuLdQHTmo4vh`5kvWf6 zgAZShOih-XdJ1}SWLIztt6b_SVUKIm@?WAekX29LTe?%wW6s5GfBt0M=gn8a@oa%D zYZ=ig_hS(W^&*J`r{no(k%_vdXDW!wYOFD?oX&s(e#$v?En#p{DHrv(4mE$E8@PF- zJ~Z~u!@hK?=FzB>47ek1=$S7!nhJVH<|0$#4Io4bNH(QA1?vcCfVv!S8lBA&>-}C8 zyUXqe*F5n&tkDg7WQiB+YwTWDE8t8hRjKKeITY4R`$Hjw7VSHkEG8=v472PZE z2h<$!Pkw+bRN(3I6-xow=^f_86|ae=FQKf*w8c4vJFd%eayKWfWMH(I<}Ys6#OkWQ z1r1WKN}@uadYYtJyCQS|$|{n0V;oqpe93tTxVGL>Kk}gdZz>vAeFr8A+J3u3O$dP1 zYHs097G}mCc*{0S$(@=TRAr=rAbl0ayL*G{Yir2Wv>lCV#EItfr~QJQI9_dY*LoJw zN;9HH-12T3O6omC7a=F*gd4A%o4O&`3hUE}L%HvaB(@lbUUER;Oq8Zm42sJ^5ZFyB zwvL~3uFt3-Bl>Ey%YAgW^E5+TOV*?pcV_3TWi*JH(kI71F{cX`{I#_w?1z%z--m;4 zNt_IR4C{+ic3+w?f}CzYIyW}=WKbBcEsgD2h_G7&m6jWul_AI-`4`>b^i^$3#4En# zf<}b3O}@Fu!z)jNZOB0T(s2f^tLt?!QK#F;9v4@J;o6>D)q-VJcx}D?(>k?Dq<&|a z49I-*sc_j`Kof9$qDVM9XsH*PbHk9D0m?5vsm;0K8x9PTTQPSO3AJj?(8`MC8{{+S z2p9XAW*R+hF+%7i18zGy1904v5ED9{M(~mik0)m&K~l-hZ?&wn>^0V1nRev}NqJ5~C%%`YP0g)i$-qryiuK1D@Y1Q_j=n(3 zeN-`1?fyd2_oowknvD$zN5bh?84a2PoH?oikK^1B{b;VVyHM7<+F%jENH-+#)K zOanH0tOrfjj1X-$A>HE*y`>PZMydCIjC$9Y68}s*5K(^R{-yxPsneXMVcoYTtG70g zT4o) z9DFVH2F4e)2kAs8ceo~ET#{PgaKv&Q3c^3>pAYntN@{+u;pjW{v4qZ;_!wE_n{mv+ zHPM?vbShs~W-=%CwO4kvznoA?8r@FPT5 z{4p2{73+8PD)*Ok_m*WDQe^don1_8~4n;`IT-R<+*0A>#D_JTW@084dW=_-=zE6gk z)0|eB$$G%_nuQnu@1uSW;P_q9;7QXnf4BjmNEFJ?1Z({4{nK{H;Z%-MsxAL5~X_Q2^;3 z<8P@YYhm@vFJ!y#$*pT&6s3k3_*bRU=B^?fEvzfi}p-#DOhw8N1<&@4eB-CzWFk%|CZaj+`tsa>PUj6= zt*uR(>ABi=*KJ&BCGAxH7IVPu_r1|k{DSBfZHa#t_Rwg#MbsUVMj_-}g{v&o61pQD z7tYVD7h6Le;rdWTtT7e?%lrIU2-a?Y@l{ee#tH!w{+rQkA8>0o2o>gJgOSG|CZLhV zA-{su&%cq!2|bPHcX@UefvKHU(YBE?e(LiR3uizEhQQ^LW<*F!@kben3Pr}iJ6YLh zI=p+T5-3w|oWs}2MyRj5Of+nNQ?rV2 z&IczEdKS-l@3{AM-SOHuh93b32|{~81Bmk-qFdLSDue7cr3nP_GRShRoCNuN z5@nf`61zJ}i5m4*aJ5|CSHwDr#}$bxhgXrJb2Rq5pmnk=uLM;)Zi#1XZC>kSZB&rg z-oL1&}GQjF5`?r$F=RFrNvZApHCQX7GxXZ-1`i z)zo~(MTSy!aRH@5|wYJ0uA)=sP~;S$j0wWGzPUt()2($r5FN% zOfuiwp{VcEDjt@48x+o+v3C9MNz!Kf-ZS~?l>Y6S#M*R z$!kSinQZA=T_XcAM8zow#w6G0=d%IGHeb6E0?JTXIR~=oih$}wj}cBTeZ9JOqg3|D zGm(nznQEzO+U}kyy@fnQEYqC%`t;KNl!b@(6RK1Vii#@7>3jC)oS`Ez={2j}a|Gil^u>9R6&O{xF9VZ+I zi9WIk$!hDOC*4p-J1m-Tmrpg$Ud@|_98(G&MHbU`b&a;k(qdJbD(tIZ2W%ny*PHp* zQU?dM3)f3B7cTJo?Xp2!} z{-cMe{qDAwJUc&^s`bnQDO_4ws75yT;1Uy_{di1yl4Jp42FRWyi11JylX8A36r{J* z8f)j6)F=O12(>?!Sx!fVa~|oX;Vk7(^J?$heg*!ehm+qT9hG@ec80s|XQp;%wP1#> zI~9IUen0+;5y(4z_1;yTAu0TxCw918#7p>Fu=NxZuWo?W-DI}x8%4!D1TwhJERKR< z)8fx|4uW{RujC=iQd#|rN6jqv4$eAD zcVVtaZu-jb^u4c-qN1F8mzA%wTru0{RC);=(37IX1&?{xJJ$StAOCoMw?+L|q4Vdd z-4w*m?2v|UZ%S|mGsEGRwB-;*n1V12C7*b4{vzpG^ufjA227M`+W|ZV^ zoOH)`J2Ca=mR)g8O^EgC@w)H%V}cqY!^Z(o8FO}6xzlMey^gk-gHgn)9`5=!Kk$8#3J!rS=AV+ z@}}u#M zd#<_dapiar;>d8pP9lgW%f)HiExkexMlZzNTRP#f00pius)rf_8#lN)tYg-h?y7lZoVJp+)-y7ph#&uczm&@)W#xP_%=P)J9h zI`1%R5OdFJff+;6f`2v(YV_EpEO->Vpbq*9|DGSE9*)7?^19D1?1vpsMqm7`l*6xz zS`AwDmh_@^*U&5@L>SjHZ3ADAj*E^eAzFgacDnntF&snpXb4w|9Ng&YU;me^zwH1O z`M7hE5|h0)8cffX`onlB=h0E!z;pf3!`+^sby1;rbe6djuMH{tsmS@4QQvVOghsYP zzkE{@?O&*bP0z~c0Hlm?=k^%Z!|7IO)fNI$9~~v5u)+LtBTvV~6*vF)s>z#ULR2r~ zqp-()mGi^Xrx(c(H-c^U^aSWPXePTZvcWiAoA!xyjGB(>1G>r_zMDKew8hZO3Q9!4 z@=|=eIj8YsUa{*MmClsP6;egZ^`f@nLmRcRkZKB1yB$9{AT>%YKpAG7JuotoU+~uc zeJ>UON%U2-jv|?D#zDM6bl9&?oxaa)SCZ%~{_08Um=+oQCoxi8eGc%Zykr) zY=PE0dPZjLeOOydU5}k!51f46T~O3?oVw1|gx_tTu>G&)O$M4&S{!aChMjDnHbakA ziy5ng%;0vIGNUlENtk4-{9putzHZN6kpA!QIGseFitN!&aVmPq=7_(B65p=1sS&9c z;GO6E;OH9!-;9WALJuH(ru`#idH$soOGYxE?%6>XFlT=*MUXmLqu1HVp?m0Vre>;8 zI)Uv*f5L!HA8ECqqiE1m5W6C{epVy0c?}gf7olz0zUe!a&SvbdxB|TX%{bY9;`+Z- zfA;8bI5CtdURC9*o%rdZ_1U6H%T5aLq#bxN6HYH;(cp2kw@MxErebhIK|w)Y-g7R# zJQ+OUYGVo>ukI$}XUvMvP9N6p$%-%b@_*i1@+$P-qZVJbcXQ8!dAhC8LB8hZ_zX!` zuHdal1;Y)&hdZr@nXTA*_uL-4qrFkxu!DB)>GkxOsBVlCg>hgoQs`%8t}`}c$&wKJ z$%i4SUyvi70wJLVj!FTkO-*vH>UT z!qdkGot+osI#r77iT>oAbllzoNTIr_!&z|Me@JtVrJ=S+AmP@ zg3wLI+vFdFTgTTA1ykBCa-X1Dk5ML8fs0fA1kRf`CmTHHmlfN@vE4b^!ss-^-I-0bfI$=9r!9_Uo z*$c2fKnY_nDpe*=TRHmy9VSGTU(vh-;J+RXGE6ADC)YR~7cFh<+TcmskOzXc=?6W} zHm98=Fu-6_gRAj5Gyt#iT7UJr;**U?CL+6$@?A!3ZD}Fpm8o=KaE0;wiu(EXGZYMX z)fL@c3&aR;I!1>BR(8TsSi49Er3Ta}im{p~L9*lz1{ zvb70&EtSI`5*VEAm8=9PAqKFp+8QIjao6+im#kr@fKcP&zt4evYS}GMgiF<+1|Ih-u2RS z58D&LFTYO?yqVMDC`V(iWK|pWDX4Wcv)|18*ru(5kz-@4WsEeL$sE2qnA<}5Uk8VN z^CYifqJcuzEzP~v7rBGCCL6sw+IE$6eE@Tp22vF>q?NQEV-Tcj0k0L(Qwkbv2%SvU#SHy)0#zI`3edM)|e5yFjEFNN&Y2* z`&aVl#UD03@9y#J#9E)^A63%>Po64ow4R>@W@(`1C313&j#MCC{V_-n>&)@Dm&5!g zIwOU7H4SzPvR~%Kg(jo)*D&{i9Lj6VgGh1_njh*~LZN75@E z%up4#T!Iu%ugK3G%$i>BL+7@kbuHox&G5>@yFsL93#R^*jc0rI{vEW~df`K*TJJDJ zY1f=(T-~CvkrC7IJi&GKX4wHl$E}#Cau*2RCi}2*`*vp33Qtp%_ydoDsm9WCxBu>a zEKzUXygA-%J)chmo<)WoMDpbX*o=#%iCD_{Z)8OUlVR4U!Hy;`A0Z$+e&8Lyo2jJ6 z7w*eBEhhL=yaj-xEY+AG4#0)TWJt=K(1ddeYF0TU8l8^Ou*5#n*R0#8u|ka8zpa1(%We_I^h;Jay_r>7aD(|`fc!TCV?r*`ecqZ?3@w?+@1PC0yW@KQk0NYbHIFO zd@g07h^_CgsMacfe&xO&aMsXkb)mzB6X>QXmD0isxA3mu&wV2CR}~It7cpuj8pOlJ zk$KdVGr-bUS%FjyU+I~(3%tE=DwNuQExP}K)9lw_qzly^KNg3P&{iJI0YDG7X0Nb{ zoE%NGvLtDyiJ(vS@saf0XXL6dhy;5pxx#&FF#^H&6v}{ z0(oKYwFzxfoMc`jhMrIQ9fopgmo_PCzA9cvE2daGuOlbqR>9g1Sh5fE@%*XTQg+|# zTqn4~x3NG~s>khu(@+tKfa)-%1&uL^`a~=Xr=D9rPGtBMLr}LyeCsJ*G-Op1c($Dg zJeUc$?JA-SHk_Xww;m3->y-Z`o498>Aq{%PJfdbF;<$AmMRB&CAx>p;uoswHCKR&t z#5)YCC>6h31BD$ss3?DGb8vmT62V0%a4vT71rUk`TF{w#Rn$QFIDvd9#Sz*1Tsr=q z?d(%1prARO%Wa^mv!{zigNRW8wBx zAH}`paEa>fmW1h!t z8(PLDhD54QTbrGI41zGC;mj55)$Re-x6V{=A-=$-($~NkvdxNm2$Zrt({}pEx6~3p z&Ji*Q;ix_OatFQqo2AXLpUZxB==s|T;Pp#4Yh5&hd3YQsNuy$2x5H-a!e$QR-2OH< zmcv`^BY;KBX{Cns`&akV@$?iGU7xP24)`G5XP?~xxG}*3Il+h1$Y1d4FVu#Sk+uM76 z7pj)67Y4JTLt1m~4>k|8hW_z5YX7_AUXYRhH}1Lc;{W2?TVdd-CNkBb*45O^l=XH9 z2xx%8h(+3&S83ayC0?PD{4?|M$?g!<3vDaZOylL_i;Rfqv4c~i5BmL&FJKFD-+zSY zgN3D~rHze^NF)*t*RPtma+_BtYh`0Y@%#LbgZUmE?Ck7@0!G@}+JS+MSTKu{R*pho z^~FCd?y+VLNPV}xaABs?PCUKep*AfoP0R08_%$30zQQ6T6MW!dVPWCm;9zKIxarN# z!NDDRFk4hqg#p_fX#s4i2V1OA8e;q4pDhLoC0nOh8dlQB-t@ zdPb2VySTWRsCZO@1&1E5*C)SwM;rR~vwzc>B8cXK2immWZ3=GR*W24m3%zAh(9&Wh z(3>M>`z9^TWRp>drEeMyZ9QD#DAYI8(-WJa`GGaij^W)~(E;0Yot>R+T-}(G($X4J zA*CpDx5f?(=27mO!NEZ^l)@$J^@&QEq9TXS7yq!G2cOh2%XnKvdN5a{XCTZq+$jhnzw3jrgu=75^aO!G~~ zF&AG4hob8|{QOb*U>V^b9nU<}(a~{rg;7~JR%!qM0HC?gYD`;B_s!F_Sgv3H+iRiw zCHHOW++Xzh%zeFtw%S}@$1hP|@oH3%kqP)-{hS78Po7mFN{HDJk8Q`rQzQxp(iLm6cVk;}F*Y!w(KOXsH%#Q#+syf8PH=?B&asXx(Zo zSRkdWxtZFdjI3i>hRguFtxMHLq>_oqL&7!*wH z?1BiMN)BozF~$W=9yjNdx-m>7W3gDJsE;2%I*%679b9Z7L*X#Z{ySON6+Zp$g>j#|nqAxWirO+7G(IFi=MkJe=nf>hPzCqE|y@MBh zOEW{P7u-Oq1vNi~7;7g^veH?kvP8@^5AdtumEna_r%GTCaNeO>sJnJ`Z zIeB^F+8Pdr150HV7Z>lHY0|IyH1+msR2btim_;IygPB> zm)6$-&%gYB+?hz78GC%EBCRvrwZ`-ZW-|NbkK3;!BfGvvGosPxJ2ZAJL@ z?W2AvRS{4qsHv%`vhr&b3U&R9lZ3H}Nqv1i)lt{g9qR7xj*5zEbiNM#NX2tYYG+^l#TN3?1|X<3;*4CB=pyz(ut zrltm<=nN7{g~Q=g6Hro8^8NdFO^aS9i88~or6q@K9lqqA-)Ly&=jIdu0NpH^VJvoa ze*S^yoN}XuNOo3sHiS@QRj9wXu%K>2eVf{@E2%GQp7&hPc}4Z6&NNF69UOnOiHQl0 zcq;g^GC%K4tf((4ENn!fxMe(UNlVuk7OE5sOGrv~batMdECada{mQjEe@hEB(bMxh z*m`~pmx)(pWMJ5y=ROahLQNWlUU(#Ac_??2L?W%MtdK}q4;%++=oOynHn}SZq^zwB z7Z5^^A>Q8JRJ*0F-ff@@kn~>a-@reRl8{i??SF8Qp34FW#zu07t}HJvZ|Pr-n4_|R zDqivN@k)RC`}&b&7!WnmbB*G>?Ku&AiN zuP>QQ4mn&*i?~je5IsG;uv4NnmY<4U%7jy6H}}?4DLy{6yr&TP5n+!ns;TkZTNxe#P$r`o?$AQVq$B3$=4`tXvSq!C(C8_LT4#w2 zs(}HXY_&&6M^hz|3O@=63R0Q;zQx(JIbb`6S@6@R<2Rq4^6zgFMAuPPW@fVB@72pW zP?7uhd(NJWI@D%Uu@*<*F?Myd*rWnPUdnX$%gy(n`1Z|%^u30P98zUiUGm}d^fXny zKPUuxJ%663Q=BR7Zbi|hqprix-oEhq7Z(IoGS=2ys6;|riE3}!i<>DaeX%}2nwXiH zISb=>@l(H*{u~}3Pfbcn%FYHj4rb+^?G-7Zp)nb6P40D`!L5o43wPRzuzZT*)gxB7lEcF4 z^6$Geh}cJu`rT$n@ZWP_R~24WR8pel)fMtxUq!UU(taE7vx3OHY15`FP$AqVZ-6r% z0eG42DIAISHH?uhTkNvABRR9)*4O8QC!?aGqzYqVW4p10K0i3@e6Ep;mv^nBe0^wo zdL2xy>eEx_*dy$^-j5}}eO`nBl$u$FyKYZON$Fo57XA72XLr8CMtA@EBFT3{f`emp zyY!#4@eevXM_q~(u3k$wD?LA{?YO2k}iw`S9SZ|$`L;jG->|hpm8O7+N zYNkI@Kg}X%Vlps4)}r?O%rY*%+d5ZjWA%6NA>O%}8EtHp#i{NEPjBo_Ev=3pp(W*< zkzYZm+&~yP6g))FKQu6~@5qr7ldAjNU$eWry81ju7!hSL68VVv%^%Eaqe7S@#RUa_ zQ~Umr_3&86)X?wW|N0__W~SlVRDS=qZQG)vqm2eF<1|%O8GjzRB ze|lix`s8bAmF}visTK;Zd&fg=A zS{w&39-hd#G$xqN-dMB1fPgOF-8SuMdu9Io`IDyoZeUx+?d=p49c&@;Io{;O@$qp5 zCXZ`adCeaV3z{p(2wD9eu6HPz4NyeZ`2TB8TeIu#S=()0Tuir*N1YBBk{PJ&eOJGaA7!tqB1HuH%)A7*gH z+-Qc&%9>f|Fp~COaRCC=Fn5v_2lBgm^{1NeO3SBDaRfdB5u||mZ_SBH+}zy#-b)6YInRkW zWRmt$Hc)XZNik8K>l@XcJtY$v#r8kAZuC%~UjFx)wD0=&ccxfbdD}bpAwU)C`^^0K zP|f7UgAiC*DZAsU5Ir_3r<>ES_t}9R>?r2^dZ;)7%u06ck)EmN49Qk zB+=J?zH{desc0etfh0!xjm?oq!NE!wFMf+WWJc;MEq?uaut|YAS0QO%a*Q$PFi>?q z%E}LDKAPt|Rc3c^AT_;KXnZR8w%Qe-BRDvifq@}$TA-$;=CyoC(ez4XQrmcMv3nS! zgxhf4Q}u}ASFc_n0`>796A@YTT_5oU@#&M(d1T+d=D{YUlZA;6-?^F-m*1*-Prj@6 zTva!(k2y#~V=P23Dx zQz>`tD*D_|wRi7cNIlO^nJF$M&5wV%mW{CAH?hHIhoRec=jXi>&qobU{zUQ`8%u7o z1Zl*;`Q?y|c6xh82A{Na`Mv!o7W?jJrKhWKofM@HVUMsv@a!10mj}W!@?L1elvjr` za#Ko)ifXNtbgl`}(nik?R!d_yLnUZT)E#5$;N<7`9f@;41(bLBGPBpD0PYJyT1@~Y z1J5BPOUqF#0xyU6Z2l+dL*A;!U3Yd4zJH(fOF#sQJja|C>)fYLpE5Es=J$Epgasbh zb@#pW=i6I%Pi`pq4%|C|E5CjFw$J=)=7pf;qM{-M$FkMATBOJJ*4Bi?#QHdirIhXL zcBecJs6G2{AhlU&eQIoU_<+wk#8VIzte=be!mc|nUHjdurA2o2HdLn- zM4Dy;$}T7OlIDK@Mm}pLI|r%0t!-@VFLbu>@hMYG^hB96I5@cd$MN~})zwvmbyOzj zy4C;^-eqN7eBG4r=FQ@CP#j)(^ytykr-zXv*9tV=ytnTa$BIL7vxaw!&B~2&A7PP0 zYOB&6Y-?}F_20O0qb^o7Gt3YY?!Wz(4i3_eKm6k3`yU(@^gN?sWR%%4fedMnT<=x= zlgJ4X>?-%~-ShbKGtldq!>OkUSNuFYJRpN1>MCBiP&m#*PI?x6x3~BCacg^q zlj$QYiEjJiDcuZ5-tmbEQHQ?OkGuKjE%mPE>S8|wG2l9Mbz@vk^6^b0()0210_K>L zIBhH}Mu-J6-Rre7ZEn_G`5Ao@Le?6!5x``uF@y>^nS3mkcc|u2aA8dK6R<6Bp3z-#_ z4lW<4(%X9tI6ouNegI0qc@>p7{Pn@oD3qaW3ZcMVAB;~XBqZpYMoAVRBco`2qx`hl z^lKt&X|6~b6QsSxlr2ax#nT8a#nabsa3+64AszYn@ps$2hYugx@FbyhGBYzn2@^eC zrmm@JE)q+9MC|BY5-nSFtwIQW+iSm9qUo9v7!+jI3(`!|J|!6$8K@vbC8kFW;#mBj zh}h{`Sy?TG?GlMiPfJsd*@B`(^7!#YcLRBZJ(QdCE`iYpW&W$XP!JVwVWOZgc1&&? z$EfdRlb_$AEFmubSTV8F_PLOiI!Y05Gd*kKky5F&{O1owquTf+Ml?wyWpvasP&hq$ ztaPbQ@4aP{yXtaLi=|LvVj{5i&5gCCwY4>*kcJ7*h$*lD9>0fGVuX?vdYu5$aUpNt zT9}x;(s<9}zhloHf|jk~JGghR(^9Ydgi8@(B8s<)iV7QjXB3keb)cRy>8Pp`de_ zOn#e~*eTkcm70|F(DS~^(^Esuf(IoKsBnqM64pX7L`*cgXA}-pIQpp>?ZJa! zUNV6lb8-anoq&LnDNdORs3*O!y8`zdZXW!DK$p0s(=c~7?$>n>7Z(>};}=bqNQINR z`BfLWBI9q)U67amoEUA9qQMoXy0lcjvDVygeZ#{80Kq4T1NL0FaA9^~VamI#%{orlMstY``&HfMMxnkGSOsFc`DkK9Wo7Tsm^3F`pzR(r zTbk~b*@4{1UJMqg)8F5pP&AiPa-BySa`W?dvmh_@k}m}&h|o7RHHpXZadC~)*UCZ2 zK8V4st;@!oQZtIT_Vs0Grsia4Tie)FhcWx|y1Q?y45aoQPk!t9m}VzSD6=%5|IFgz zw1Ka;0HTMJlM}AvP_P*?A+4Uujb$Qs*!L7*?}O}lyHl&Tm8w@$7|*y1LeC^L&D}hh$t_ zT{#cjZ*FeJzR7`M668C}+Ze_-&#+dNw zz8{^-G(Sm)YArT47Qo}s;lmywroU%rFQ}^K@vD?R0oODb|#yMMdn# zk9&`(6z6APiHSK6KhR7y$TB{Q)m(Y%cTZ1`*L2}qayZ}sik@982_#)lUo~Tq*v5G2 z{;n>1Yy%Jz?{-LWb1U&hQ!`7IEGa6hUzA3uIfs{7-rZ*HiY=g_@wifr@=)+`6wxc5 zFP01?{Bl^}cd5P~96T{G;qC2>Ov&$?o!T;{8ZVXJG6te+TQ-}s3GsL(B-{zaU9~t- zEIFvZ!k`M5LH>Yv_gW#$O*?M

DdA*J7GsW>`=Voz%@6<)K-{Ajmq&=Wuxj zgHd6s_Wfnvr=Ifg@YuE{U5egFyMO;a%5Fp%AWCZYco;8Xl*h-)aYe*tKdoLplo!Vfy4 zuRKvAwjLByM^DcY5RTg9W1F;y<3x{GVsg^b0Co1CP~AgGS-LuG)69Mh^eh4`)x_DA z3(|IPGuo_?TD;d+JtAscrnDly?$2<^{LKWK>*D3hrn$PPoqf)Qdt(Igkdyl)EF$i* z4~*EZyR7W&=Bs~ZsiYrFfjI;N*;|~9eg5VRdx$)n{|-t@*FP#1cqMUYN6QhT z@S-v7ki|Z}g9uKig@uH`r6Jp**x@{S^v9g&PFowB2=N19bOIlLmU*lt#J^dZnwr9w z(c*GkUYFGV0w-to^|6g@sX8cHEv=E^;i$)tUCxD<3ORxQ2?+`seVcD{)Xd!6&CM;8 zPQV1$S1Ro@zOa&(mPQP|(X`b`I%IWM@i-b2P_D@MlioVy>;8q#BjR=0yoYKLRsCrY z%xGUS|ck1|}pg^0;Q$<;MvhVxZ=B}=kCQB?(Pqo{LK5idAd|0$=DK08Ptqkm= zclq-ELx=LfPfPJPO-X~BdX1v2ANAdk)1lzz3oUCR&|(8uTClCpf6?a*BsBX5{7Nh0)+w7df!) zR4Rx<*RNkE(f36~9l|jgSm5ZUx}brGSEo%p>Ew_sK-a>$1<@g5&G&+*t;U&Ho0c`{2ua0yg#Oiavl zBlYr-Dop%F0*1Y3au#F1WZEtH(f9oI$^SAe&tH! zd*>#A3C0E;=j+!oaAD_e!*+ zKD zc=(Wpv!t)ww_M{Zn`8$7fVj(--d^vI{yTe3T_P289r~r>R28BqEo6z}KubddH~j|S z8k@)+9G}dNbWJ_zT3E$2G&HEbOnu8&R#wvW^7%kzF3E`8`S370+9Fq1R#uik>dnpB zfKHgg<4RFTe)gT&iAhP8*b~;dE1oskn>TMpY!c(h7kR3T${fH=@%(x1TWt zDkeAI#ZC+OY;t|=usM$lvy9DBDwvuMf<{BV{Z8tJ2gDhzT2RWE4Z!EQ*;yUpdf#J^ zQ7oluqyPaUR4jejg`7iBaZCp@AA#8T_)#Xd{tzAv4Bg+pWr2Kz)`n5}Lne<54Iz)Y z0fIu&!l+b!{OFl!e}rz^9TrK+HIRzHvDA|D59e7@6BCaM3SMT9xEmPQt)*tKKFmztUjYHIN)&rsyfd#>p@lwMI+SHE(_we(u&uDdeU z<8%iPw!Jn~+;R0JT^|(2YG&UOg@}iKeiX^d)!p6QKdICZA2KsC@^sS$&Fiw_XMP4U zORfJITohr)cL55ZoCl%P8&43k1j`K;+k1ZBEh%F0yfJ^LO~hW%n03~bB*1w&DKNdMcW4;to&GD)s1b~}vx`n6^2*2IK_^G)NR+ge&%ujO>g$jW;0&_N?P zuclT`o-Stec?hvHIVmX!Oq76$93Z#6ygXtP5+N=I)N9Q(PEJlN)>6a8x;<1>QJOnq z>djNzx(1s-JwZWU=zDSr1MlxICok^??ZckF<=eNJDq5pwl3toS_A)SVM|z2hhyZnf z(`sLDcpM$Av~fwrHS2%90Hb}z3F+x}9T^7ra_=i2sUb4EVqQQn=9pGfS)F@>@+~gga0lh{gZsl7ct zV8Mp#W8F(zllQ=K>b3@hF%JjF_k4%`rLrYS&f30rrV3tO#rk~Il$2B9KLL5-&v?us z&^l}TUs6|Z{`T#t9d$%R1g<6&)EU2Fi5QYVMn;2qPJO)ehImX&z}>qSjtjF#fKG7r z{c`P8x>30lJNuiZYz@RQ5R`Zw6bXjrvYsBf=0rR;)()1*-af=LjPo1SIBQ>=#a^lr zZReXI^YY8ruk@#{|AL%M{*(Am#{(XQ3YGNKRBj0gy+n1aaHXGd@~=-j{`ePZ5h}wa~gxld^; zZFfd#=~{?r-^1D==|3N+j~J!{Izk`j_{{9a5*$fZ6;SR~dChP{s3 zHv(WpgYVs|sjaQ8sVV&3AW=+fneg_lLtn`@s_@#YbHRCb-NO?TUJyaC#jjY0 zgHfGDM?g_=v5}Wo%L~cw+wyhG8<|pj57{EZ~bkY2U7_XTW@;EL2cX0A4}i{NC~s3g`FlUed_$MTap- zdKw$`(`Dpo(7(^c zU9CYifcZQXTMzmSsuI13?f0*d+|tmuz-hs>lBhR6Bybf>PJhjjBfgu%wf#utOrePXIthbIb50JM7WrC^%@uocdo>vV67s<}p( z6=okt8+vjI3g#&2+n+f2eYz_*bx9V3g)~htF&V`kV?zv3TfhPXGWwFc`xQwW=)=&= z(Dy)$AxcX;AMd@`iGcIAV*+7)ad{*@(BJ=jPETJnur*?xZn_A_hL;z6kUs?k1Qu7d z_#lS4J>J|1?H0-5CPbt%5Me-3Ycqk;fEm2p+}-c3B4l1_=a`3R9BtE6R<6TPqV5OD zc@i7~JWKR@0{oSLgUb!+o>Y)Z|` zm)RD+#DdYsCY2ANAIeIEm&pg zF&FW`&1BF8zTI~D^-x@vWPw5uX(2SER;pwWT$Xt~Jt#8dXJ= zFZ=TfwRm;)2`(<{vF1d`f7Db|z}1i*_#tMeYo;o*Lp~~oMsrzRoi8d8C2JZ4MktuI zQM^hpIW#nYhfq>hMkMup`uK5cF^d7S=lb$UN2ZZ4pyq`L_JyfP752+ugt326$D;PZ zBEwFDK<@$Pf!JzBRfDZabY$dIUnv+g5Kg@gVXZit)6+Or6i(ibuJV`U{q zMA~WK6ZcJ}XLohefd{HB;=SL%O|ZJk%Eks#mDCs`%#Eavnk9-eMn-Tb7(^s-12_;!4k|^0bbAOGpKB96-=sc%=uuRZ2tp}95aFA{X2fa* z6L##_uUp%h&MPTRtp9Aa&IM9RHz>w+bi?I?{M+>ETz;<`%98^vUScP}J%~yKSH05U zLRJLD(9_!sJrfm2;uWa(hRGV>ICRrBsj0(QWCONr+h#bqF$z^5O%6SX+!P=wUeCCTV4H@EK87VB=>T1oa$Sz*(zFEenTE_p3X9FFGa<# z#Acfg`MILMVFrd02(+o`rFyc9cpP@YdesOd7kme(X zscrw+xnQXp8#_!-Kc2-Kn~;~cctU#lf}vrbGd9b2(=dDwsi*Ka)>ZT&D)DFLf9*{- z-aR?a$~u51zd>*qePkBU@fh6T1-e3kY+Dw8&D1L#2QcvL5gwkNz}{U(*8xtPodL@b zu*=HI;5UdKwVy?Z-568z1)3ov^@(8_0KOr4FJoU~2g3s})?q!cUYmWFMl&@Ra%!>$ z{hn=*oW1`kefBi3%47_JjExNdm3ltpBpR|;s(P}no*pb%&{}{Yu~I?WUV6rxRS}_O(nfJkQTxsu~W$&{B0Uh-*Nx(bq4rYYJ&btQfM9`|h@8f4icwr<^e+BS7APHhh~|L=Pi z_EC4jIrXj@w6>!vW)8*2Y1XZf$$ z$S^-hr1-~=kJXR!hbt(ZIdjH-c&s!mtg%Y>r$N*Eyn=!P00Ee-u0j;FBp#zMW;w%p z21CY*R{2WgV>4i)MRYVXs^o;>`!`3_2a-gDU`$D}4p_}!YB%W17VeHkOmDMXpZvp2n<2GxqtsU%VHy?mZ1=YSo5 z|Bm3&Zj6(7tC>phu}N&DV?rV#NH?fS<$)~7QeL2#i;B=3b3R_yjnpS;-I}zX6kZ5) zx_|%v&I6c~A1lqBogOf%BH3N74Cstb1OIyAZd)_eLkM^fOs;McTTufS4D4|6;zgkP zQiA}P8}<3}NfgTf40SQW6V1YNS|f;bPsClh7#ID{$|cfK%;V(T>!aUT`1vz`{klf} z@a@|-m`q^X1b3&w1<~mMm{T~L))@ktEYp&cIXO5WoPi<-YV|BF+pu>xz-)4Ga>AZ8 zR`%Qp#y7xk;03(+>J_5@Am%hb+I9XVvVsrEtH1cZ$Wfp)Iyv7Xb`Wr!_TQ!p<=?v=@mbliWJ)f^`R;zw}z(l@u(A zz5L?EQ7hRvSPe4ER>tqr8jhA#UNr)V_>ov<%W>8e^QRHGM>hkfK{CL#68`747g(V{ z=g)ygfEQSWg|YALhQ3BNr{qhy!{`F&hpB<-0CjI3)CTZyu=_p5xCRH;g2CFgdpCKo ztO0C^9RLBM2vScjGq|tO@wQZ;3c&ezD1EE{kqx6^iC_)W;(Z2j|D)3X8H^##5$?FP z7v<#}`_<0OBEb|4?K&%+qb6I02q+A3eSJ_t$ux;@kEoeVZ$C z|L?v4&j-W{#N*ljX;Xtf`hR-e|Np1|8y$>EA=M&<{l5nf9>jJ>?nPLHQVh%uARw~? z+XPhO;-n6sH{9N^SpYs4!MVK%qz>P#c}^z?YSrgwk~O$M=s+idXAY_;V5wL_Yz zuGk=rXMQWgh@sCHk81!>J48>v@|nSbfd3FHxi!W&DD>%6)wSRL-5dyB4I( zzMG18tdFN=!g;oU4qa9r9_1ZC>`h%=);XO(*V`RR@IFzg?8&mL@3ehZTH@DnNn=j> zscql|iwX*koj8H?q9tBn-9{LRL0SMTF>jW_Z;?_^^rH_TO~3Gzq-1IJEJ7@Fq^HV+ z76wT|aXTCkHDHn9QHK#=&!6)cAA8noo!)G)X&{RuB9hO>)&t5zCj!O=_YQO1QAQ)= zJ`Bb-(8y#R4k}%gd#+cV#YVYjgMqg@uKInH?3t zjrGhY)lMsLMRK7Hrmam_Ts-C@!591}dUKJZ;o0fI;b9SzPdnV4;Qyq%ajkO=M@Yem z12L54=uzWOL3;s75k7yF9WpHAE*$vfCt0!60=SGuN+FZCcQ4}zQ~!4QJE74h1rz#Jg!F@>Ri09f8r zaS}YVBB2x6>*8V(y`titJo!G@1m7?4A$Hd~lRR2n?Cqy3l+$o`ehiV4wV}}P0}FuG`Jw%g_RA{=z}Z_csk#NS}r*SsZgF+a8eZ2_ZL z!OAyQ+GdRg25HyvRyY=Mpq61K$!89OjBrJ`PEiu9Gd(Fi63cfRZyc73>fH_k7Ha9` z%a^eexc#B5c>JyxC0Yp(q2O?S2TYDCm{x}4z$f}3819GQnZC3 zGa=y<#y%OW7noz+Y1o z9HL59htjg$hk#3Wf_TWEe>rADmF27_!d(VGvcy%}-sa|y^DqteXne_b_?JrSsN$1J zY+Z_uXr=jmSAn}I?76OWioQ^)vxF%OjMKL3C-E{xM%D3b+amnvv|sEloyCx06KzpRe9V#%K1Uc1w;%|pr>~`Y460eam$FVgw z9VRxMpUqs{C1HatnZVu8$oIa(iq}thxq%xQLQ93>&OApQOWIo>hqQmR)W* z81zUJR4DStaKG0L?e@~39JuJ2LID!iPuS^qjZmpce9|=04rF9z2!wuukp$E`T41B z<7csKdWtVg9*%DRd(H_3 zg$1Pi|DOH-pZ=e5`2TK9Rvvw}WSC?ju49xzneszjUji~v6r3`vA6}@InCPxMsF+H_%KEP~SKY#MPN~ZQ9(xwQ zIsVtJ-Eqx1)U6WO(SCtGgwX*1c;vomy~M=NOF94h8YA{Sg`>B2bX(zi!5i{k&>`>Z zZjdzMnH%TKJj4Dr7g1#N>1~(D`!()Q^FfMFFrYYOSHx}>*rRt%6n%{?4vjio8xzUE zwBu?S5pTrGX(6m~i|%51^^e)$Z3(tBt>&){2Swf&)R&hO+9+j+l(!eme)#r*iQV3i zSd%}vhT7;7k9vJ}>?nSF<3?fe`Dz8q$VO&fs>mnJzm;*p6JhS_H_ukQ2qk{Pq{99C zm4t}flZU5I@SY2#r(F5G;muLeV&m46##7sqZC+cH)}UZcrW_D+5`29g`AR=gnlw!# z^C_@~6hCG~ojo-i=B5_=gU|o_qtx0|0mEM2_qtQURQvvZw)JGz>fnp6-k#@4s~5fO zqnlok)|2orG2f%f%aZ)2Eh~dDpQ&n%L-vcFMo~>s(e@=(KqR@?pJu7CV3g`){_!H( zcAfF=^yS<)soy!!);WYjk5Dufzqv(h#Xo#z^@rjNrAx+~W8YoaA>jTw<^bx7qZAk9 z&T35epke}S#^6p&phpAdH=9eMR2}v__tvVKP7Qvw^1n~FWwmn?gv4EkmtnH}%0)jXO$n`dzI<|=xlxcp~2o;%nkF^|y~v_7oocn@Ku9>c`xrfl{h&JarL_D)=v&kLl?*e#mcg zfoTNkQTuG%*p0hqcU`FQfE9}?J z7K%D~t@pRk-Iyn`k=BoEkxqm8F}I60`Zqka!pEjLLzi56F1ti-h}M=36iq&Rc4Ukh zi5AEZCApTMK5mqP_G)e?RW!ZSs^;ZBlf!+T9P6SfW&Y5TS^P6st@A23W&EW*3V5Cl z1yHM5HVCih|6VBAk^hBadHr`l)%Sm29z&{9MG@eboQSkwKsCEhO%u4pa|d z?$@dTpw7&G+TS5^llZ=kHZ%PGK)bJtj9#yGc<7dZFd?HPYfH<5`TdFeU$M!ocnA5h z{oOI@MYJ~O6&}6nWmcY53H?nYlZ0PK)NMJ@`T3)#QrDKH(W8YlGKue=C+AOcof=d5 z*ikt&^xluVG`W;R?-ANIX!(&HC<;1tifoJT&of)t(2Ex(usO?no)N0;`2KjNL1H_+ zm-C*bP<1Lt#uq#}YeVndJ6y1Lb1wljD5^baZIr`YeQ!kdCs?|ZPiOk@k5<{)VagP{1r$I#d4X)z*&x2^3ibWmC@+sj$#J20d{Qi#o=$J_r zy=i5y*R!z^PI5;IORV#I#0u*N8y5S&c)j)9xDgc}KXTAPXv#6C8jJq#wNq%Fb;!1t zOeddFNNv_d-zn|88)+SzIm_OC*r417dscHxOPh5rm^etwsEng|beacQ6@XjZCZEul zpm1hknWy{kgD^f)Z1g7v3-g%|3B^aY+)Rndt)ko(r=$E}q5OV5)6^03POvk;h1Jy~ zDf~oi?6DP+pNRJ8;w|i=DplF>lbzOTu+&GWQuNeJdAKnkzo(}sRQmbXsC%nSaLW#0 zN(r*(;KAemNtv1asPBl5a#Y&=PSuQe=B+7+jds+(;DJd9>A*BUwM%sEwT-Y+FG`zn zjm1liNV#=@Lr z-9N@u-P=2*(PiBfy6csncGK;xya)DPPX6cqu1%-6UC4g)u#$Y0MSaT|js4#?Nc(jr zbhsNo8dk<_^ms7646a?<-idl1Hkrfo8t4k0?93sN8;IGa2n%C)c05PFnDiiOV=>|N zlLHaQQ_a7W#GPC9L&afcVG%Fw``q_19o-WYbo=)^gOG)F4Axvcs0z>w!+P5`i~lc# z2`grJX68HOSWlk^H^6Ki%|G_qu6W?OWd0Lo~TAd^{Sxp$XB!@quHA!S@?mK`^ zLRN0>RG4;spZ_~B7SsQj%8b^ z(`ufV(@b5!K~Xr7W1P%%4b~%wdBh^_IRP&_$fCC`h_3glOf-I+y#9Ah-8e$Y;q2hh zo)ru=1Z6d);ETU1X|MTjBI{Go9n`RHv3M)IEbS<1&dRE#nPnRzB&o~gyl-DP77e^_ z)J$i-=i8o#s^#gq0_HieoVPaHMBt+=-PxIVHiYm&vwxpTywIsETOqAHdHArRTpuk; z@F$YD{k;Mp5$D9p$Cpx;i(&-z?%BWj-l!Il9V){L*DMbFfG}liWyQjJ>t7lMhFFNQ z_B~=`RfZqy|6Tq84Sit^L&4`-hu?3rnHPKH^~8LuU_+hSz}VT^o-*^0@D~oZ!Xb0{ zu66hhRzj6X#}q%Va;G$Pyr0)d-J`qtTo~=@$7;?~ z6;A(p71NXH6~`=4}qd&=Ga54N3)IAiagY;ycS z{>@*5lW02JWbt?GnGOr{O2+73hAaV!h6Kb^<{XWsuL_NcvF#QjKnon$ab`vtt8EC+v{%1h3zS{0NrG}_| zdn-@EJO^=CEWZfHFaqy%0ZNbxrU_2bq$@OFvEyl|8*XT^5xW{{Gm^j z)f6DjVUUu7V~n+lu}F`C>GfEqv zqD%8V{Yp>x&eH+kiAK-j&)F02U%shQmLstjE*A~(OA+7bx0dS?TP~JfbNa1dOi<8~ zs)Q#zI>NGxjg9E?3)q?MftiOvJD{lYkn>hLkN?KYzo=A)ZEWXawBR)#`%>SsxWhl= z)qDCI##`yq;tx!$_1?wme5>*On-$L93UzDVZ!5FIG~eRy9a6Beswb<&$F=|3s91PH zBqN)FYfS3+g%>h8UeYUSu;8b|_3BL&VW7wH2DXNa_4IuWo0mAkm`2_^=XMO2WC(UV zpp1(OP-Pugd1t12+dZO(=D*)~`Q8ypby+@nc*45D_W1vc7m!CzJtYt)8pHO5D<;yf zYp(i%0u7Y1^4q)fZ)DtY>V=Lek|>9f)@*;2m!`h(vqJNduFnRfJozx^mAm}=5B?af zGnOUFYYK|uWSgl@os`o~mmJ>h+gtN&OQXC}v`R!#7E&sG2xwxk*5jk2H2388-SZzT zK!Y#x<5?0&TeNnGv%8AZdNw0?D`8lo%QEGfBm#keDg+Jm|g#2;(At+?M0?}nx3Tz&hQ)P ze8{$Hp0`Y{yKr6(vOlzVQPCxMD&>wH3WhB7$;1iLIAjf+H=@tS>{toG33Ut2B^U=# zsM*DDGfw!IsKAUZHpd8Wdt7*uONhBQ@AYY)O8(cL(JohSZoaemu>0c6@^@vPOM!*< z{I=(xe^La?#u|6HGE((e57!VAAY6dB1ch{!f>ym&RdS+B%-C_}}!C!DS&+H8A9zpqaz zZ{Oe9+qRO?mj$qq_foWq>HkjbqZlOO)Kwf*vb@G{IKTta3b^&jfq{=<(dUoBcsGXz zCkA?YG@PMFWp9+3PSn)s=#TALJjF0RA_#h&IZ_eiM`V*9x0>j9Mq=xD>0?fno%qy! z^-1{uTbNmgDk4t{If9`K4tE;Ku|7Z<9JZ&aEc^ri2sm+m4Z~dWQYS=fVG2y z2F0ZQu)l)zoS~B=&l-Marg{tAxo?Z86lW+7w2jjGw3hrbT_8~(&VPO~qsG!}t~{o% zVSKb*Z`*^_jJ}z#(Nmc>I~%rln#SENj~mHe>gdBN-+Qe)*s##|ckplatpzze6Vnn_ zeZjFy8%Y~AK>;6mGkNY)&zk9MnwXRlaBEW9i1gA?lWQ&UW|}zZptpG}tZbZ{X2(a- zsFWss`xiKXm&N$D=#<#n+_0cLT% zCmKAhx;Yor`ts9Vsu{*+f9CfswQca(4p-V-{+W8~pZ<$6XI-Z-^)W0)%iC>GI+Q;Di0I7Fn$d2D zJsc!nO`D%v?H3x_`x!@n-I?6^d_ekGv00gryudluLp#w1;x_qxmN+wKWCYGTNJ2QI z#~c1J;tZ{+vu@0Auj6#Ya-1TBE}xedOR#K-W1F}$OKu-!pztPQr?gUj-<(fbQPO8e za`G$s%BQKk|BH*wDYIzTYC`VauTS)hFBoaJ+v843F!T=nr*X|F zn_=%>t6lxi$}N?S-#wA8zwwOvwH04|XYN$)$B(sv++9cMQ`mjcC$Fl`vQLhhDv>JpNHSqx;hSCnX{RCwrzg zt^Ov^;i|^v=&`kujQcj9%h=L3J4wpPd6jn@>KO0W8KswOsIh&=ls+sakyzT?MBdog z9=130UPL{Wng2hV_6m!N;@G$s(C`S@R$NSmTbsbn#r+AAu)jivloL`Or<^G`O9bhe zoRYXUkKvf`pf_L6Ie$DN`}uxQl7VTmwa`$UpxfV4qwG|7;g2&~-CcUasxt@5#bg&< z#Mt(+R^^F$kA037jUKNQJ;JkWEEOM8Ry=!GYcL|;Ze=R({Q%`px$zQ437=Ml(rCTe z>M~>Z!O-_fT4B>&TID9*a&w-YLu({b*%6xZ>7fNF+0yW2kBzs{(i|Du%*t{JS_Nu~ zeVTs)=iksSURmXjHz+?Gd1$@)mNz+gBPz`}C}}yBx0`E0ihq*3Gp;?ht1R*fQ||SR z6MAl?kp&IaC#It(3Y%5B?{l89T3cDZBW3XOvuNIx*jIg$y4hCdq`b!rS|x|2eQQHS zMbe*aoMn|gW*&6jsK`!XJoHia!CNM*tZVl}nsP+qJ4;D*-Ip%i(F}H<^_nQnxvo{S zyO?XeFSaqlC+ki^-$p|~?}Gh3J*CjKJooe{_x|%>tQ~X$8TmScjQNCJu@FRAKmEwLb(vlWkY*8I5yNnn<3GKwou1}Yh z*q6oAo^yI}73BAT_9M<&gIbiX$-Nid^021DkRv9xCtqDY zIX|%_iaL8t)1xt)DnUSd<847KbvD}?qx8*&!H6q{Hy;`p8I>a<_ODI59y(+wV=jN4fm)Z4&TgLd8kL+D8*x@VD zn477ySw5&X@}Twp{RbHqTC&jrt@OEN)`mH0c&Xj1&Q4up#;$`}?2l>H zVM&3A!2#bD!=K?z_5*@#BPk09`n=?i(BbG#k^~lEMPn1{afN#ULBsy1>z;_6pPwZ0 z=?X_ICupn5-Fp7Y*Xy%giZAJ{AJk*Ck%14G<%eMaRE47&|_t?=Rvd+zi3LI| z`Pz{;wb7!4A3b}ZreUIfy^G(-;B?2x^YwFwJJs$OIgw<#WLva+;gIZiABi&3T?bjp478dqPU90%e@J4mN zfMMC@?)+Zwo_nq1?5_QCRrb@`$B8nSDfCUOO~5e)F+(vuP2Zn^ixVmKu7NqRfg{?| z<+EoaEb3wg_`#pF4O3w+8S|u^MAx zZNGKKtkPBQOYdEmrz?kQ1NPoMh!T)nB;j1&bFQ3Q?@I5bh7H^?y}*zfM(U2&(tZ-H z_h)RlM=jsh!$a$5e+!dggyTYB@IXITEBRQ)YGuHuAODJq2C#UK`6fD?S^w5Im(e>! z3JKaqnqXS}F%__z2VZVm>l4zuEiO&{+{Hj3W9tf|39RY8k2{le0z(3ca#=Kwhl?OXL`FXop7-CzgOEpx1Gm&p~g zzufoEoz0%{imxa2k|V=l<;BYu&ik9xVxGpvwtAZMly0+nQl_*t<5kQsT{dlEjaK%u zHV##}1d@hmlkr*?Zis^V)@Ng<$xFrU8)07)PQ3chS%_jJQnBs(cWty8^rdwz)dcpb zmCF4x@=mmy_>jJO7rX$Ja(Hbk`0r}FzA>$d0{sNLF|uX(^JSSNodvX^YcnY@0<+ooo0yOMWd zatMc*z%uQc#g!*|p491IZwW;7d`h%XRBAoYM;eRa=HlO|yZe?jzT~#V`s(#Hmt|$E zyXFSh%e@&>mAG5k+4;D3rT)gP`BDBU2pZzmxz;SWhxnZrnDKvCqwVA#2U;x9xt*w< z>szk&i_FlRyYJHfVQr^QJNQ-a)O-PhKmju-yjL-Olz*%z|h&p8iZDY*dz3=<%twWFuYWu4jPqimFO^&6D}K@eiBr&D-xs?mzGA()}hPe_K+R zeV1mM1#7eB`m-xXNUL7OwDvXJ2c=p|{vWE|JRHlm`yRifQc5VKghHew$xw)r$kaq; zQJFH&WUeSGNit7Krc9Yhh7uBzIkPB{slhD#)}{CJec#{x$8+>_9NqUdoaa9GUVH7e ztZHX|Xv08#<;{2FGfZW_i>MkG5JU+9zTnO&i!WDr)z8Ubo@;zl_9Da%^UT@>H(whP zbJzZJTW8u6^L#7geakc_MZ6Bi$!*3t*_+&w*l^bDw`aeLCHLpW24;_f^Mb?ugWDgt z4LVA1&{CA+vgxi0=sl>^_1Z$-zS8dc{kJ_uZGU{IWoq^v0 z6-p=1SFY|`wST!iDNcN4uu}TiOS!nWvt-!+ZFjnr<#k2HMTe{Ub6j_*XIJ(twKkn7 z_&gnXd2U2G?43V*dV{-17t?9`=|jx}lo}a{)+?bttxDa+D88NS-@3Z;ol-OFgth$u$_O0@J2n$v8rS?= z{&0cm`U)}Xg@8;`fp5J2GC~JFZ`7Re{U+k1B5yMlveKPDI`>dnZ$y5Gg{}Da?Xt3B z$&>=tu<*r`Uw-{m)^_^N)|Z!{nQq*@=5~BgUsvHTf5tC=%k~EqUKw4uC+hgbqiFE= zp|-t}VH4&BUjt^AV#n$a>Wz2)ZR0Q4c)_p1;=tciT7}%!OUr+{J~+9ZDD^Yj7T;#s zY46sP__~`lc0Kp{H1@Cj@}38dvE_|OIeqoWOFy4({CZ8iil~K)@u|*39uuCAoc@;d zu&gi^-=iGt>&xY|s!pVoTC~K2BAntf@{EmBhTfensZ@}8Cu#@+{boD)^XKX4{rDDa z9+P}nBA@#uaOxOJ2^oL|gGVhfA4?8Ij`!)Nt8EKZ-S1%ivO;w9*h37QaRj~xM|)<{ zGD`#Vi6>>y^5Dy_Sh@bZdE|j?JT|TB{=B7POhQdeSdyqLli$S4gS{0HCIe*LyjdFs5w$*0md%_Dhxp~C*eSN)TaUL{KE3Re< zY_1TXm3$i_|9@NnL2_2ecC!>yflI<+ zerJZb=DwFXiyz6?XovDrt!bVD*H*x`EU$YA%vM1S#77zhA(d?f;{i3gMhwTeFFHw3 z5NseJO(cX~=6FUG)#d)4 zy~XVXZa1s5(}IFnAFJGcQ*P5u$@g=Dk)2QC=R*GfYl4(LIkxdJPjUnM@*`iUlh8n4 ztu7Cw&VHyS_#7|i?SU8*Mr;C?Y#Ajr=%>bUzZylNcqKn~)Nj-SrBNXfBzwbkwTbf0 z@d<)Fv3o8gRI#t8I12 z(YN4~?b^s)SMCn+u6{Lhzd^d>;FBRY721_1mHj$woXY-BUZNd_Hi5mZtswJeFm98l z0Y7AA1+IL#B5Fuk{&W>--8`jRas`XiyyD!&vF}Op^MX$2OEU)iYb^gd39MUl6E7>B zn`{gd#HnnJbRPa6M-(u{Qc@i8z=0_vj9*15@TlK988ALE)d*eOul@bInK1Bo|Jt={ zceP$-J$>rs`*&%{Ld268rd`cR4pxYot$ts*$(4MK05!YV=%&jf!^&CzKUC;qiYibt zNZ&Kv_wj{j`MNbHv0N~a+L>o&Rdz*9O-)yqmHs%o?;>tnh{AQNUmYDu@}_~KV9c}(hR=Qpe;=kdL6!C2t&LQRQ{IFp9|d=9XY6}sRuaCdohyC zNbQpzOHEj=%J&4Mh>Mtc9fa~(^}Bc7-}><_kV`s~&~#U9FZuh-r;o;eJCVSjqtlf! zuAIg5pVBPsiyjm*P;j3}QT_ct>9J(x1k{f)Fa=!=@EXs`xStfM&Bj=w--8Fajem%8 zeR4sRb3Vh=g`D3|HFt)B;hq6E-P3z|2Q=R(*?Jq4zdso%tX5q!)QtzwB@XoowN!H2 zoK>!^y&WS?-+|S|&=`@#4PvIL#jta+WI`@D?geU|*eP$WJ>EM6F0QsSif3Idwi|y7 zkXaDVco?J{+yAZ%bl))yb)&8QzAWmf%~iCZ1^gLE{13!tG@8&mfjQ#9B>91a&riCT zt;7TkxmTPS0R8nfsGtk!E*J5tPFZ*8+0Iio>C4eRmLDHHns}y3IktDto-dHE*z@em z;20ibeWWNU2x*F8KP(n1*AIEIA@;Ody*%DWr-Nrjk184!Iri;H9~yf9`PW0U!RVv~ z@!yA_hyi6p$OXMC+q`L$qP%>#n8S~rI*fxT?hnR1|2-KFh@n!=I}_Grt4}hyAW3Jj z@fVBCJF!m>{I=}r8VKjWl?qEi2J6SjWhDcbOwW0C`FZW)_-pI-nb3J-H@rd zwo~lm&~5W{wa7=0^t(W%!eKl9H}9p{(I39hywtS(kT^yjKLdRP9?plCOp(y$?L+?`B!Pp+q~#Gpda$5L5h9< z$B9kZNy?FTf>%Ai*)B1v)3`l4ewr-SuCThc6JKi=kr6E(cz`zarP%y%tB~1q>yD-S zh5q8j5w!F8#B7d8= zs{phOFlmShnO8fE|77TuEkkJf*U5Ytj-tq=J>+}T7eYaHz4Qu`=F}I~V{#unhsAr- zCx+FWTJ+9ePTn6Guc7vBs5d!Z;)tL7p$>oF2eN~hfp^FFWS*9?3`ZbIU_W>eJoswM zb884%DsufZSE8Xh$DTMxJG)(Zg8zl7kf=krg&=RCCz_mYA<9bwW6-M}opxC^79yEZ zXc6Kc$S}Eo4qnOZNaK0-G!hcG2-kpcTysqOc-SAt=4S^=XY>i!?Q#OEAFGngB(~nK z#1}$U08^4P9t?!@zSVcN&yj@czFNNha@WWC{%_w$h5>HqurG;c-#~z&ztS#;pY)Q` zPzk-EqmuY3&6pWdnR_vwD#f;Imy!&=5{&%)!3wUHW$#y}|M(}iUtT=EGJgDjJ1IRe zprzAxuuA^L^*=B`6))40oWEHr?UdObj_~IG`;W@s?+I48E1!x9MsDQ@gMXYCuY(SH zyrH(!GP$T|N_Q6r=K9;|3`=+BXuQ24syY+S=&JbNRVl&z`gJ~ zwdK2aK7Mh@U}<4`wZpAqgJ|7;4h?;9?}`4#Hv6~-zEE@GhIsujfw2qdN7Dt~pOKSq zn1;d)DaeiyQEMBUtPvTC^0WV<0S?+P!H2r~YA^gb^yf)coNT@sU(%sjy2dp9D%qgh zv3t0=(bL%MvLDJkRYBxxA-axgrmjqHw_rW!FT+4jf4J^_Y0kayZJ>W8TueDQL`85? zwt?g2bz$iLj{nJwfCrQ#uE{UnxDDL0IU6?U^(Lxu!INh?D$q?wriMPPo@di6Cu%y3 z@07p6Ja@p3BUSvXtR1hr@2=*>6ec(9Yi-Go@ZI+oo!~E_)Q}(V_Y51z$bYk$LSJST zp^dNb5)Ad#`A=7FBvHq~CjE+@PgY`O6vLO{Nq!EFk0$A+LgT3d*0LPWoPu?<-(yPNhq3#NybK83j438&Ylay&oJPt$bJD5W(EI`nb+GxrUGOGV%um zCdw*k$nBv=CY68eoUV>pvZ;W&u(ixrUdCKA*U+YrV;e7@v-e~BZjd=&Q4#?WKllh? zK!4@-YAcdpqv6gGROH%_%noZlrVtZ$;OiZBNf&n@7Q$XxlzU$>h zXe(_eWLJw70o$I-Ll6Ha%Ww|=o6bcr_>!&R@c^ceGnycKAom8gYs) z-;{kjlTPD2{*JG9OI{5%*~jld-%<8i7s*JX$vPu2ym#XsC28Mt%JHxATf5`7`z&S+ zSLP?6bcJrmJd{{W^TY%M1cZd3inCHGrH>dn)sPKM9=1gLGqzC5(Wq>Z^( z!}tp`?_rb$8?r5Al9~+-3{=(BW>_!m50?2lGExL952zw77Ji3lJ!X24N&21P2&{`a zzId`86a|7Xm;Y}z(7xDOBVW2D)%ZgUwUO`pRgnx#jpEkArADDn(Ao+iZWu?s0;9LI zQWmEMs0s68c9_V=DC3OtPU7W})vLRRt6Psm>|s!SQAZjD=O-wZK$U-4E~%Lw#1Gq| zD8mj+fdjMY?JdR369_y9815|=+DS{Vi8YMpC3AIsp;vD-1#9ybKbp)N5+g~xP-oyp z+yz73#H7CgbFRk_!!W)GS!l2Tp+E{74g^vX3aYf(C1sAQGWoFH*?e`-WRaz`&WBzx zsrlDQkqQBjM4(<~+n0jmvaU`kSiu2ALP+s0nnYo0d>#r(8;d1ZSB?m))}K(rPRd}h zjHH6s0aH#otUQsDZ~T1gjGz^0{fT>)_4U{kZJPg=AVZA53HdHgC-r!j8F52&PweKtra!@{1XDzB@mb3 z({Tj zd3p4KCwAk-%R)6CljmNGYuB!QjT#O|ER++^r>J7El?K`n;0=s76Xm|Q$<%u6+MM8a z*-{8xz!73An4O!}ukCOTfn<$gEyPKk&?#EfxDGRl^d} zz@%GIZSQK|y6^IPZz2TlHaRM5igtkv#|4abV)7Q#_yV(2zklN>!z8@742O;VyXv*X zDmQ?(Gr{qGOJH~Rom~QM;hW-5_kFlikw!7_XYx$Dv(Yi}QVHTSCb-s2aM{^E*4JfoZc zDh7HD-OV{vRa52a>vtx;5tqe!%+|Y)r@OHchxUcI^M!Ev`Fow{r@u+Q5RZ&R{^rFS zx=R3B{Pm_BnyPb(uWB=bb_d6L(Pm$XIS{j{WFCvm>3aXw*0&==a48911DkD4yH4K5zb= zPt2BdhsjwyM3+nIlP(;TA9R>YF!|_rCgCEDR2r&YU(3D*;FJidPa{HNgm+l{Z9sET z`t@nHixkGs*XJFZjLPcLUo!jR-_v(pOE{!dF(#JVeUI9YaXyY`81e!&9H-^%)D#`i z7+ul~%x4o$VO=&Vg6;5oQbEJ`hIlI2dxosT?Kz(xWpOM&O?n_*bk@A#WIS5u9 z)f#fscbDlTOw~Krw1Ty`2@vt2-g!2s$D+&^vRH z`!df^+pVRdqFvyHcxTYy(GWwJikVB1=pRwYgQ_Vnotr~TG9@Q}?q|xV|9Jg=z)gRC z?i$@LB5c%J$Fm%jIr>TK`17~AX4Qot5}~H2+Olik!Gn1kd@^6Ze96L)IJ7|IGF#}$sE%A`>|n%z)K~T=mySd)KW@10-{zRUPIJbjJ@jfpe*RYMA}H_dsCQZjf56 zo(uGtpF`={(A!KdL@#lC?Jwk^V;Ni=P+h@zHVzQ-A%S+6kumYMLogsw)^>h7$HJhV zl$nHfx!&;TXtDiBQ&NnJ!ajyhn`PqX`_GbtTn*q)}jZO4x51u0}aEia*SR4sN;-+Dnw zNl8ILp^w8B4;Kdj5&=MttOs8ZD$BwFK2jnh(S9&IK#>kJsq5{2l;wl}RvFLj8ZlXJ z^HvR0t-69kAw7E6lEQu6bhFCe?>pjluZIVE-w<4c5Pgxy(gKcNKNG}sRQae=E1NiQ z2}JzqyIO;Nk59|s>5;lzLG^N!P&=dz6JBVafpq9no!$5sOcKmJp#_}Izb2P178qnFP%5T6-VS1FZSc=2}0)e>5@9?2k$bH^%$lIGYc%a9{=eL zkUg1My$9V9y`kT7x2k>Bt7`;Fj4e?&Y5Gw8)rI^UV|IUUWxZ%zr8#!ER9Oc+y1H7( zNs8qT9jeWx+V7xq&g#Y_=V2|eWGnx%xS#R`0lDAf&e0S7B4ifazXe$3|HFs&JR_Wb zrG}4>YmMstE}Al_*0%~QEA~C2#nKwmZC4e+bcDX1+7aryWAmE@_?~|zA5lO+h~=N{ zNy5jz+smp<2L6LZGGl%nZL$7ddkk#obLt}%QJh41|LVOwT7S?E*(C>M)IycFv-n@$ zN_V@<>VIhdlu{3li-t3fc_)t1Z{kH<0@MFgf{44LR?rG%yPaKG+=QTzv$lRE4cF3w;qJLmFjbkr|Hy{mA6iIv{xy)H@s zbt5k6dt`6v=Unpt(kcDc3Q0w|A3iJ6drCqv$x@C>pO6pA|h0sj81 z)~Uz}|Bt%p=Jq;076m66zNdDS)|Dtq@^fs@^7REbw2N{j_?#a3>Fa9v%?mKa(bZLa zPbCI^2YCgAejpzOp_}a`pv`$(_Pn#OF=Y z)EIi{^fL0NAg=_TCWyP)*}rE7F)NdrmZk&m80cSvpuU*&8T3$cY#{6quAh*Q>1$=d z4hyC!;T0L(ea8REYq|r|kH9i2EnSAfDMkd;QiFYAUkGo%DOeL8+1%_z1^p@-77J?8S-kY~ZTge3ONP`6YfHXra%*}CNK^6=vg0!H_(@L+rdUAFB2>fWlNQv%Y-Lflw;k&nl ziXT1lHcmDst<^ZHDaz`{7rhVvOVEWUL^#$Uaq8hdO!UI)p$>-b3GO>e;;zXWa2A?#1Zsk>DQjw7K8tJ zx*T|!M&BgMl> zt|f!}4)=GD;Av-{rhtRtA|$-wf!rN^aqasCGy%?{EURKFilv$QgCytsZiy~ad)`=Q0w zppW+2IaOZBm!mN-$pJUKVRnPrz*^F?5@>w!`F(D14Ex8een5>c6W5GpY+oonaU=D0 zW}%TzWaEt1GeukPcjj3hy6G!pxrwDEqLnlM%lF0DAvO_?{rMbZaFASghrJuU5@q?Y z51yxfOIK79e}*t!BSR6$Cp9W<+L3KKqMkNdeQ|jc`x>o}w@v<_aVP1~I?Vo1vn|im zEd)FjSA|Rqjlq4vAFxiUs;j%K9m&ON9Sa7lgkAj^8Dy(N-eOb1vzKTR51kz;rfI9c zp&QzzgqF-DU8Cg|RO9zX1S=W*f;3=6458xS=xFzE9~hU%pr{E|VW6515ea3*$p{*+ zeZe1KYV$MJ?{}6A@`@j2J?lI4#LY%QuhpbiH}MJOm!o(UU2ZYnU(0kK%KAse#fwu?{G?bI7@jP{;?2i zd-d}%#gO!f9m|b}ACB&!^|M~u^?m+J+L?XugqdHM6Ggzr)ZpKK;2D6>K|t>OvICu< zovV*hqoDU0Ni{ll_2*KxpRWT$-A21Qm7S+bSQ%8fM53a{@lV{QTh-n26=fjtgINa| zv}#G)5KYZ_h{Y;$1+?VA{R4u)WcF7P0QL9X&miuIB$HeM9(V4guJ?cQ!z2Epip%p; z4Zo;%+=0`WjKL>6xtWP5I;O)NRwGXBySV3%@wrJ~#eA9D(lq9j=GTOgASE34V4pZX z1Ex4F*)Z|Ckd~O>w7nXy{K}pA;!S?Z*>6nlAM5A_Py&4(U*9WXxL^=kmYo3#gQs4m zIt9Tjpac5t*ChqGgHm81+5hG?lzCQ10YJ9D@+v1-VJ|uE&}IFQyku*s2&=FJos!pk zYn^in;m^{){Rt!$5ANFsye+lt>67bx?^TXk>Qv?*sqhg=2yy~4Ssf3>qsUJi&HB|mcz zOhPPOoHB@#cW3NJzTl}90AiDfWZE)oXAgn)Gjyg@~ z;8D{nM~ex=)k9KcwL&O%DtQ|xS1(Y9rYF@w%k6v`=V6wiu1=!YQyypcF;rDnCL|^< z%+GgtWD`XGT`~aW{`eH3cxcC5Z0b&>Biv$}g|lZ~kvTZ~8@}S~?8m-VC;LJogLB-T#jZz_D6MT=Ni(r z5$7$A$`OP(S-c1==HW6Nq@gyt#X!is#Npn7lwpCsYnGhX z?5B^v80qMidQ7X{$3bM{q-ys}bhK2>j*}vUgyrhH<^C_Ebc7xtE!tMWdcr>*v;|NX z1s{p}+vC~frrWB&FpwML`)tjwAWpV7CxRNXC+DISXlZFt=h3pwub;Ylzj6TQankeW zKTAFrKm!{fC4vZSF5DZKckbK?({Gp1OXNay-la1l;I8%pR}`KuBO`r3h77KE%Rcn< zl;q?zSGx7AKeCo!zOZ_6TX1Up4}^2ybPDub5qm8Z$@MgLKOa&5?Kv&nUN3xbh|JK!bT9nWLh0Dj4JHHm$?|6HEHoZLScP@(@#qH>jcM7~ZyK%#Y{sK>P zOG_wIK^qA>J3s6&`9`}#fp0}8L~PqW&2)f1aCJDkz3X^OG%I)oa|0onjPOmdIC2TW zm6F`IXGEXYInXt}<@vmw1bAFlL?!lk&rce%MgDn($Pl16yu*4vO+N{VM%0ct|0D|* z)PQaw$LqpYVfcgE`AXq}K7AV+Q89CGdrgJb6rP^@fqU@6w1U_+r5ZyKXNVyNS~ld6 zm5>)z{C`*-8BX6>+D<;&$$JCP%^t?3rK?`Aa^eAL?%8uCxfUvR)hhz8)EX!W=iRGM zR0mJARP$Qv=J0|)<+{7j%|lHQoci^i+4O#ghG|Q)N1^-d)2>Nx2%`IK!W{`Qv$V7^ zSOLnwIRY*-LMD|BHr+ADUFUv5lNgS7u(sJv2c+((=jGQYMhq#S?y#Q||xDfiCNl}dvce2DZVL{)` z!9ocAZ4E3dlbVsC@T#UG<9MLSiSVv6&1=buXiH=>k7P4ncXBG|Fn6@Iz1ksXog??3 zVQ5TlnOa(MV~bW^wIPEHjc*QVwQ%If{G}vMXwpNHA2d>Y0KCG35zki=T>Q{FNRYE1aWRTjAToVGX+|;e!?`u^RnF^WBNb3i@XH4>0_Rxc|0Q>kq zeZo)9aB&3sPF69~8P75n@YRyGtRkL(@)lQje)i^lc2q)U5u2sA}Sn!D+KS_wTtCm^csZ@0zzOm4%9TCUHo(gtKxEO^7cJiYqh}K?LM!uEWx8}+VSDf}k^vgB(w4nP zVK{-Txf+_jAM5KO$iS>ux@qk#h{VCN0FD(8eS1Aumf!-2HKT^=GWf&t_H1(4Dgp+c z%T%QKG(SM3tjn43vKxrZgQp&>5%7U%pA1L1#0|l|G1nqdM+=Mevq|Fa zC>@%U{7j(h=3d`<_1A7sQRD;=n8KRy8boia3rEN68-JLfG#+?nj$sj3;HGlyBCtYq zl^=IpU3#Up(s5nc-4y`H_x&z5iF_j))%doe4ZG{O3kMHRQhK_-6bl{QBjlAZUM-zm z=W^qQ1ympLK5}!XaI(4`k%Q3}lH@ywEWtRtLB7Yap&7vf&zw8%-$l0Syt3y#a9|WO zdzv|$F!+JV6&Z79c3I)MkSd48RLsTT@s{nWV2f5-dL?Ug#sk5(pOL4+l|TV9;E3e=AUl zI-{K8V)6gnb7YNq{o+mZPGwsShXNkV(v=-m5tE8y+_(;^($>q3P=}s97%KXIbnvi~ zlT7IUu(O|&LB@u{)=-m&ho?(o1DY;mdfk8W!=)emA}oi5Sorg_rK=)Ny=KL^woQ8d zofrS!y}9HlJ%ZN}L||BeaITO-(b#NIGlf@J-kaiDgKTK`pa_c1)!;*xK;H7lC^*7W zSKDAc;3M;Oa*|Xn#LgiZwK6a$DZm(WsaK?72bjj_q923sMPcFGit*$}$_TNXJ2zv! z=`7E9t$oBQ|Kv0sBi;7oXIC$spucIF-eRgK-ptf>w)I!!^^v;8e3QN#awAIGog-aY z>3J7JZ*8JZW@Jcudg}zE{7Je;?i<%;_jvR5v2W+Rx`E$(V16mMd$HR!R*~V{!|ySq zrzERmN4zwS zF=^+MZLl$@X4ld@1VA(_DEW6W{IOVw$5WtU^$Pgp@5 z7S<&w-1wNx;BFFDDZ2r;=W?;ze6%NgZ)rzjn-y<{`h~{jR~=*Ow~nbgXP&^zl9iqTkYZ;EM6vtGA@rweM{4ziQE|{H;F!;UT@3k_WgJ?-niH7p}5jxOOf@ z6^fs5X8{NFf;Ji}YMGZ=w{8{8-`0#SwAO311uE}T^ka5amFn@wk7o%OOTrO z_fs~*FVeK*;$;_#1Vq=_4E?Sro?;U1AMXc%yH#dvA6x=NVdZnUh|`-cf>|KcpH4bJ zQQFkW&`I%$n3>3UnJO%;2^DfOBc6IbPc3+N|9VBDr+eUYj-F$d zb@eBANvZ4PuY=McwjlQOy5JX?hikFb(f>uHmdxMgYRx6Tru`XD!1(HrrKIF z)gd2T@g8rso{xN4GAY->--hh|Ju|KM;+^hR8y@25uO!>FG)|*+*B zgv#zUYZ&pVsfkn_g(<@6_(p<=J_}794<)4sP(ump#dj+23agdf5LX?nnMin9>kTdW znSW5)UZrFlWahu~kZYAxTgQWmFl^%EMP|q2N4_b z*KjvU>J?;ufasrgxuo;Wn=4a8Vs1J*I=JX-*Wv>YFGM1&vIfhqUU8h9x|{Y!;#Sq9 z7DFE3^Iu@c0_#HPQg`BW$J2aA&o}xP((zw z<$JH&<6T8Z2B+by^F5~t{g=L>*P_8K;RyyQvp$?uu6w#-i%7i-92%p+dn3 z79IbK#dURcFvr6&YGG(7%zZ>|LtN4u?+-}`M03@L;{&D{?sPx}y8Y89f&kd3mvz<0 zqge8jl-t}-v;nZhQ^t2~fuNB&oP*6pT+NLn+-}{zjUyJ^7t&}CFe&XBV|4$>-*$9d zQx4#?+UOn`IHiZLnCw+{jQ&ockKKl(XUEI-o}MN6wspfBRepbzc0iA#4lRLbi*_XJ zrUtB!#!Fp6#C@U9k08ai>54-9>RVt8%ykq=ir6 za9J%JEnyGT=dozv;E<=opVVj~!FEVc&=%H1O5Ao2hQ$AhSabrNL6eirr7>;^i-+IN z5|6o9R`XyGdr}>-_I;lv_I(nC|DHrH9_dBd#3`3{%iG$0*w9yWeDx>&drZxfFGo z6mQn}?0M*Z<-G?FkX4OnDATT9X3bs(YWP7g9n=yM3th}RIc-t;JbplgMIR@RtSm~^ zT~Z#qh?rmc)m0Chrm%J>$d!9e3>F?ZDu5Hmo!=K!0|qnyBD#x^t=)v4<>t+9fA3Rk ztM+|UTv17X-n%vN#LU~g^~#n$rhcI}?+xZ&O*oTC={0A}$F}lg5Dr}Hra8E{3|=0_ zbHd~$7O%aS`@r68UUW*Kb9_=(c6}>*RHq4=3IhY#mOWy?)U%@5$UyjMn+$s|+>9s) zNWF&DLKprNSRQB2KpebbP;W{h-B#~rZtlr-MCm;(!Ww*h58t356*3-aa+V9Ym7Tz5 z@FLF}ms@B)fXg$&a+uN!RuQhQt}EX(iKj~s!A^(9Jj?|#n{d37G3BcNTQSDzwtJ_w zMI)DV2ytE&w=9M5%V{r6n_nLd&_BGmGr;$GCuL}`XqOQ2Q$e7*;^S0fhPdQ~p3}|} zyJFF@Jk?bG`(>s=28tnVRw5n`|#UW8ys+(6zO$ zbw8J-E`2RkZ2CQP`A0fU9U zMF@c3U0!|yDmb_e3NO|D<5JEr4lRRq)9Uo!5A4vgmF2}v+xg9VUIp*`>$R}m3}b1L zrIL?W$BjQ;ZKCL3vYvA$s_IU>8Ab}vwwxC8Y zz2W%!IzvwHm^0A4W@H?3adn05%;+hj1hkMKT=op&2k3HuNec)DET~EFtd?%)?%Hua zEsoZ%o>^##dDE@sd6&pjr?aho@4c9CmaEy%V5jN!>IXBwc3v(w$dP;9YV%+r|GciQ zg_{Os;0R|ImxonRB)!gj~f{NZgM+2XCJbW6;N4cclTxjD+95Dd2FNtrjb8< zLPOgtdU=thRNq9-_i5X8z?bmNg3*{;^7;T)3W=m8`WWWU%aphk!M22NnAB&jKvRGI(K`c+icN_VrO&pB znpG+O>8O3J`QvhHQEY>Ou`yU9O(QU-w)2s;0d`HgGA;jsM-G(E*AqBZ*q3F=cgXbb z9R_hLFMx-~KCXe~is9O$$Byk-ubKOE`6`Wjn3=R_RApPv?&0MOCE6HjA}#H+P$%7B z>``o6G-5gC!>? zr={^hV;QH%lJ*Y-4puTsVnrr@yNGq+&%Js#va0)a5X*;CoIJDcNY*8sD@>a@)o7Xr zTRa>-D8*Ztppv&^$H>G)3_R#MI_AHH>XH7x_?4vqG53YsQj>M;I}bPa z+h}fQ7wX^{la#;ufl6GXwO1F9Mp#BPX!f7QAdts=WeQO3>q72*nTQJSD+nJfQlvN69n}A=t_(9gp*+lQt2$g5z>(>IeHsuO7KEs!bdReH0Qt zK>EF|4(ixR`J|(ftnA0I!?#_EK?X%v6}>5L9-hU81*mxaaefWoHCSxEP|1gZ4w#Qp zMxtJ;dn9HJW%lQb2_oqlj{gdQ{5qR!mRknuY_CAN(tYkq$nwckDk{xnOPqt_ndiCJ zaPaJf*($n*9D&I>IYHEBykO1%#|?Xr6!q}xMhJ?7y3hM{Z0z+*l{-E7>y%GM75&}# z`TIf~MoF>Zfp;i!Z6%X)a0&b$K17ynyK)7fAT%RYpX#lGZf%~EklVvUkcenrt<$6j z`<4REY}uZ2aq(K*Skl#S)sE20%L1+Db^^xK=bTW`rPq)mmMxC_p~bMtfb@LZ+qVPD zf1GdJ*vrk0v~82mTf{)NfbX~jQfd8%*jDnZr*^NNF>9bn>4|b3rV^+Zs^ogjN9*}i zRE2`dM6Mq-dY%;hwl8?cM6GSE;Lp*I`dL-AZDVSZ0i2;;LQVPFnWmQJ9mH6A#X9PMkM#7l%g`LupZjtXp=qyR0 zgK(;^zdw9Dj!0(D4qSy*#kX&J={9_|Jw{j;b<4d*3MO4amO*hm zCt!82#9eIt<<>8qnO;4vzORbYRtXBaHYG0#FFVY=7#lxdyP>Z*fMUxAI|}_bsyV{V z?{~9DUWo!uWudDZ?c-AkH0SQGT+SB|O#Ym84bn-QT16jKUOf(LZWQW3euX?phz#f{ zFtryKQ(~$#^g1X{uXx{!ty4YjG&*nL)*nt=etntw<0dlgG1>LX`PVZg?gNlMdR!aw zsMG3q0xH%i?S;FulRkE*Bql^C$DUmG;CsS)F!+EA4lU{1hP`QdIVMWM!!2*vF%KoZ zuE1XGI9T5j61zfeNx*@D%!~%3mAG+KQxb!IV+W~D@15RHyfkVa+Nh-KZ11Dcj`Fy) z^}vN6jz$iB=A-UBEv6^J6dBEAZtVXpShhHp#4!t$=9hRlh_i9$HLxkVx;7E#6gU=9 zPW%%heQ`F4lHd;(z9WNYGKu;c+O>m0}-t*&DWP z<-zGlnLibV*Q*?g6aYnTh2LEp0bV1AJJ~_j`S{@*e#UZ8Cn?lj*il zFD9NSy^4x%=LkJ9T{*v7dgujh;W8YdQaw=oOp!>NdbTV9%W~XwyW#nrBpSX z?eFKdg(jbq!#&4M<{5AJTzJ!;<$dL+X6oP@_)mKo#U)z4`Ngo0TUX!sYslkM5|~cl z{IVoE|2WdZ^zykBGj;d`J{fk(?M3dAvsKk5zO?4Bc%-gP{5TrXr|&b-ziTc{7Dw4kge9HW;P0f`Doft;{R-esDQz69X?f6$)`rp8 z?+lkLB3?%-6sn~CYLa-kZFXW3CY9w#NbtE^Z+Ia112Pk2Dd@i}$>N{{fN$FP=dM_n zNt0|9EUt8^DK*B1+Kw>(Qpgzz5hY>=qabr^YDv$Cwh-#YnlU}9pqZ)K@ZXr~3k1UA#B zedRhL(k8FtfB5*TS{Q`z66F!f_kXh5*H>--9=@c0XBQzYQP-<$YG`~#P@f2{Z8LUY zml;R*>R#tt1HpN>W&C_f@F%RMxqf3;H&}h*o}qV#d*a1JWBb5zjM1Y3S zX8}GN|KH>2nh=i!z0Tr#8EJwjYjxVzv81fG<#_t;7q`2mu97t%f*z5)jv0Uj6^nJ& zygu6(qlb5_&>mQF{$d%u{Uh6a zW{JCU7GOQ-qwUyo*A9Il5C)VC;;T=p1Z~cX$~dy_CG%*}Zf}AN@;kpzDf+XFAeT$0 zAhz>ISMCxzoA>2YdPnZr@Q?0~M*yr4FZ1#eE@OfJo_FI^!MzsV_+tc6UdDFzikzsZ zsATN9^gZ!vsRkn1hGb=$e=+b`Own3`(>?Wo zRl&I*60`(RtV4HRMHOHs7sucb z1$|-=DFI)ltcd)Y!yp?nbQoU&PzuWC*y3U!mbdj4%gr$n%BL}ZTWeU}JXxpqQRs-0 zDW_1#>T_zJ@@cZPygfv%?IJ|<*ByBjH_;HGJo)5$^1IokshaNPk^be)`4#zDS-;Ry zn3@tg!t%MxK*$~Dr^xUR5I>zIuvLJl6UjIn@yX0Qr=S3KY7lBaV5e{d0y0B{MMR*d zC4km`Z|`~G!!9SD*%E{z)wOGNMec{VXh_rxkK-A0jiHk&qix>vAR3;t=PSgDN0%vN zdTO|=X4*xMD-_4k8|6^Uxp_D{J45QwqjI}DZ{4GW{in!02vf^btm{(rS(Np~e3)NZ z-kvD6dRRg|oZOVfb2EX`|KYrlch&mko>LqA%@*o@>(^&bGnBldIu;k-O2<1%QDlC5 z{N=G-TVfkx4_{l~s`#!DbJ7=&Q^;+({bpE?McS~dNGHSN8fLOJHFpqb!=95;N^ND6 z@^F*k5!rJ?c!w{By8n3utcp_?PWnHmCpJ56A8Dwfk#X3)zgmQoyhWD}7nUfe8)SAG zq@+=LsV8ozPxXd4ux0;_H6b(l3SK&!4+ftPuRdSf8+I{bN}I0d-tvqYdv{-!!TXEB zdoBcAQ&UwP7N>rebn`6l&5seKqTXASykx1Ox16AP`s^mtiMB07xxb$KKs647t| z`Xtxd3(;9@oW$-I2yt(o0qaJIFb+p0co+Il(XJ)7-T1?oDx#i8N0c8~D{*RK;>h>6 zPm22cH=dSznlwGlo4|7;P*%%IYRwOuI)G-&tn1L+i*3lv%$!_#z#ZXiuO;kj3MFd- zawC}zJ88-p%2kt8h~(?L&DyilUUqDdzP5%;UTiE-Da*1+t@T<_4eStQAkMcY7InP% z^-?tI#mDsF1BpLh9ufAaq^MU)&ds}+@?0S&C58uG7<`zRnA{}$!2fa9-Pr2=ZtgTY zlqd1IiF}46m5kciqLf3LN?8sY=DNXOvL@Uvn3>^{C;F|Aa=IV9{nfTeEfr!BN<&Z0 zZc09MEp^c>ocfmS|7o&v{l7Q*V+ZYIo>X&A?v(eXvB$O>rQf-)*Coif zJSFY5oz3%V%U~Efrby)%{P9PaQpY!s5T80b7v{E04{DuL)H9F z=;{}6e`0)>Zp~^Lb6z#9IP-*7Yet)ugmt*vfhUF)akR|cpAzH`sZo@_>KKx>?EqE9 zwy0bGnkBsDkZgchw5*%6cWVvCq%!r&&N|c&{h42XAnza_pKL}FTi)6PG@RilNX2r^ z%4!8%Mv4dQEP;+}JmZIhq}}_4!+LehH+onQvh1 zWyyR%LA)?Z$j-i4=2K&U@C&Q>{myOG1ttTdmk1*4hY4kw%1lKIg*>IdLeiyc?dIOH z?91t=HXOgQaJQ(13H9xd@HDGU&pE;;tdhRbm)2EYc3)RS9X#Q7+R7-Ln%Kpse0ihD z3`1Bz!zaTWtO1~l1N|CvXj7vLUB`=YdzjkxoAfIJBu zcEed)*6{Kq93Kt9U#gd_goV^Np6Wao3rVShCS!q zJmov>jRPIGtDWnU987)uvXD5DOl7ffMdG#S=Ph0J_5KatU2o7_jQ8S}2xfqCx3)qA z@9-I{|4T&vj*})WtHs~DLa923*ms{9-f51>f4VNj!+*^FG^=6_bU3&wQ71sSLZEAH&_V(WR_ zW6iZjb?d&*wEQ{c4%{!(PBhZ|woI<0^kF9St7`j&JkxmY;ePfAJ$!EZEO=SMTf7MHC-KmuuCpXX>A=hzLF@U_uvc5x;tqvbu$}Tl+A6ocN>FiP9 zC*w=?Wzw|Zh$67Ojl@#uEgjLWztQJY=_A-K-R~)j%a=?!F0J0O?S3VsTZo-3cYXU) z@(##lSj?)_zg?%s?%h4Ud#iLs=BJ;dhCaR9!)9PSl9Vd2QFI=xyYS$eWdHbkG z#`-nNz_z3s+qPbGP0vWmjcfl9^<~hUP2h%*bkj0To>kAQOBXKeVY)9jVT-C37)l|^ zB0oR0Jzv`l${HI3EXaHFrsZt_(T_^jR>kE-$3l6h(!K?%mMDtAmsXt3Yodlu^|M>o z$dT)DPf4QVuZC|;4<9;uIVPMw@G`2t*h(WW%Ap{kUK5JmQGLi3c04)$bG(eA{PSZj zYhxda$h-IR%rTjG=<;R)zlJ!q6zXU!7>-f*YsI<6ClUUVnnBhJkJys+aOn(iL%2iR zi!H_M{UnERuyw?(-OLZ@<*)SQ7?kjCQoVSdl6hW!G_@e>4PrROY7AG1YhpVX%+B}N z&p?Ojqw10CdH26ciRbhEc4Qv#EIYVifzPvyon{pmiVX{%pP!>QG@L$`iTwPvXbevZWZto%MWgs#s*C z3vHOpyUSZX-ReEa_(_X`*v;(bekOh@K>ebhdEgnSrza=$Ae@3mQf+YE={6*U9K=}f zSMCh@U<3N&`F-$5L$y4t$4Vq~?7>OQZTEHbsixY~$G0L9RYpzjY&8;NCFCgyecR1r zvK#y*R<{Ui%Ed@EK5_d?ZRwvVi0Jhh&9}Sw)em%8WxwYpmVaK(fUi63kAYoOxN5Nl zRDb^i&7(!90oPp!^HShFfRK?~fRR12eGc#y|4TMY0E1vM6{t?BXY2$}&HaHE*REmq z=@?)0iBnBKUnln-THPw!?nuX(SX$1^&Uz-tV`2j2#VN%`f5C4IDHbo=o@^w9qC+ev zsiupJntlW<&+))Ew*UR!;x9?TPw6T$cL*G?)fdxNr7DB%!O?ok%(Z2y!N9mQA$Zc992RjYXUT4btKpF6~K2@M@AeHXj-Am4JJJ2NoZTBlt7=_W5hbAswA#rYmy zjV$};hhG+pNncy-ec8mRB+h4@cg$7I7;dHTO4;bGY+ND~F!*kKQFt1?Ok5<|%rLZ6 zNBP5=G3tRoVQzzXX){>$MeMsZTucE>AH_p6Gdqx13E#ZwAEXEAF68`z5NxpfKO7O= z4wW)YvzefUN+OBmrlcK3F@@$ZoPw7`f#2a18WLjJnOjpkYI(#g`m8##?tk60-rfu& zEhlk_1AoGmgYzSr9O#?tMWib7a)w7M@^LNjt$cyuLG%OKM>EST`+wi`Bog;BEK#a% zO|D}pY`@ON*FnQXS^VmPpShjgpU}%LBaIWCH8p=_5~xzL6)w!!o7wk_L>bd~|pqI^;*`C=lZ zrLV7VZ=V||4}KPS-KjVz1z?UdxUh)9od)g^zn>^u;ESKO=(fr?dzWJ z5eoTfwOiUG%rK35?$D`G|_KWzRb@KRqfNMi|&nHieXnNapHRJcEL zq)e)=brUTu2p9nM;`gVpH!m+Of+<7j!(I`}k^!D?uaK+)@J(Yqm%~kI-|7o6@oCU8 zG8!VW-F;VuVixO5c&C4O_znc;FZ2HxCmYFmC*;3GKgLQumR#Ib(F4Fo5@#fu;3C4p z;~hD2{Go~o?lq;CL*nc9zP>vcPq~w@t}|&^_cAuNKHs2`=JGelvw<0~jnwS^WX;b) z@agE+SQerAW};yl7(T9gJKjLB16Ta#_iti1>UE5fWKEQ@BS{Ad~ zlR5Tl2_Nak)Zw`B2q~k{Gv1%9-;hPzX8?v7<~F^`2_A~_r>x{pO@2wurlZZ7eOt&R zqsO4#p0Zqe!bL6l(=frdyRNkhTt4_0vE}TG{1K=eZ0_vp%Hr|drX?>w9}br~U{@9t zY$r7M)J#l<5d@2L+&osnhzJ6I(#LRA4&L^Veu;LyI2Qw7pntVSl%pFz=#5 zT)IZCLrw=C!7-y#-m{1Y5Qgw5|9QFkaCg?Ll9J=cj)j}97evETZi4^nF1TCoGzGpE zCl|j_Mp5*Lj=2xr&Q0VFq6vt!D6wK?kbfdZSPwNBzY@?;I-lIHb^FzYwEE%{zM`I) zac=D*g<0L3Q*L`xS}7!y!W6IMbOiM2djBY}tawMK2ciw0>Fqy!WMX%!HWMkE9zM7mYFTe<`l5d`U$ z7LYD!DM3mB0ZFBE(;ati&;7pf-7zl1KhANed+)W^df)jz^Lc&~`bEtt+fJ^o1|Z&m zZL_BGk>iwL*Kb7$0>r2#yNL9e>~VZqT*l=|UtqF>0*1isBw?;X{4hSgmIvn`uXg{F zS4ARkw^3xhdwzkpm(BFc_~``2t-u$D8g@D*Y99yNP^d+X#oRSgx_Mflun1fHWVw@g z$`l9*%ebT@sOQ=xQ=ieJeJ@bw-QeWRnEX9DTBuj!2z`9$Cp;Ct1n5RGm#8W?9>+*LIiMj#3W$HgX*I5+qbk}3_lo_3_eiM z1($Y=zpXOw6yG-dQ#jtIaMx*N`}$MS==Z9{Eo=uU0lJ@*cpn+})&GtsZwia`aam#5 zdg+`tGT)4Z&&>Y^^!DYKn{Apqp88s%yusDM%4W9|gW2k0|0N@lG*Z-|7fhLe!#JFx z;mgNr=LG>8wwl?mo^aV_@O-fD;}ZvV-^M|>_HNgUzgGf@AfC-g@3ZQdZa-Wnpt{WG7Cr(6mR5M=3l(Bp222|PX2o~R6J;>~p zKhihx;2svgeRXhR%Ap_!Z7m4H4p=;n)lOHTmN$EB6^$jaoS4G8^M?raQtImNS0i^{ zUmiLct~yz`B9s4aI3gX8=57v*jud@(fjRJ9U|9oLVHZb{>6w|RgajzA)S*n*)P&mL z(eC#Q7}2bXZ?m$pvcCpBRYTwNJ(zOwv#$?zxR81dtxeb?Amoemo0o(By|`#DmMZ?! z>Hgy8>)KW%XulNScg%C3cf6x>;f+(ncnZtJmBt@ae{L-ZTIvK{Cq@P+_81;*bx>b` z+9zlLpoj0@JM2A-27>8<$`Qs;H_W#Yb6L zS=|bP{$UQ44=EhzKmQ%`CVWx5@piYPAI05JNE9b>vXTY)0X1bNOmIm&$sdAS(>X>N zN&{%PJJ!%6@MMd*EUUY@xxunDGU7hp9S`g0&!0bGU>r=XM2K*oLUtW|UQhvN+!PE7 zeh^ztNF5NTZz1pB;-==};B%E=vc>JIY8o!W#JX8cEdg6TD zq{KmB_(zXvkzUOf=rE@fD4&qmtG8lyIl|j7oN3+Q8LNF>6P|$++LlOBXKeNe&+p6i zg_&w23>ZNu}S?t6TDHDHz z#Zq^X@W@B{nbNNmO=iq&MUxUOE?Ly{$d$b7r>t@eub=+V!eAt9%koaW64sVjdee4c zGzKq@Ogrj5H68!U4wDjAB?5!kI0Kiy4y&DQ%AEFM^8jukmWZ0MoPKlu&}wIwDQ&*< zv*j+K$L@pAPGTF5RKKWr>=)qZ=JYG(Sf48^^m;1fz{|$u3=(+@!Fpo;VH}M2C`gE$ zAN!u8z%&820l2B&8>e$u8YBI1@0}btc=M9igMtL35P|=1fUDV>EWY|0t(BVJ)Y5=j zO%F4%VTvWpq>$LGU!t-^A@zHTO5=;I?QO96V;Dj612@(KtRs04(c$ELS~d!2p^V2I z?}D3{@NwBci${

s-8aaUWOPX;0!P{I$b$#8+kcyUW#%Hd6Mol1J~8K1{VyFtpWP zh7r`u34_E6GvR||4df1XZNj$`LitEC>u3_R-I>l4;~IEqer_{L7agA5a}VjbUf{x% z$&EvUr#9K!nJ4rliT>dbIf1w?O`Sl9GilfuHS@Hjrjq>p578pix$@chM#clbEE()( zOqEb4vA0v6kI6P2bDI(gk^acTj&CDH-z7Iz2?-n?YwOSDyrUmsaNt-7O?q6kJ0u=e zGj?ASMSi=E`Hn52>vI=v==%DDWH!~*f*1)?=*3UdkUENdlAh5M*>&7s2 zl1t09^0KsME#bXeeal@S&w00h{}1uzp<|%I@rl!U(g)JVFV}C$+l4sNOrC)_a`U;% zVoaGy$l-jS{SJdp2V}y-Kq)W=II{K zgu$|7!CDRF+rN~)s-YojZcgA$+5PsxRps4tR&n1#EJQ-qKFLjQ`91fh|JZH9sDQf& zLckZ`T}hRh6T50ahK+C^SFzFO{gLrWak|@_*d^2$8$ofg?zyj&iSuG3a}9j;XW_nv zY-_1wslKyq4F${Z`nArhcZ&AuN62YWNE(mOhOdx`ZMT1@1)cS=Y2;3A>-2TcJ)hJ@ z?wdQ!k)vEjNW>vt7sYMDBU3`AUN7FW700;a$)z&iWV_C1m`%sJk7ok@s!b`3)5TMv z5JZ5TF$;evfH?0E?_(Z81LOH<*K}1|(=@S94NnQSABF(UYlq_jrwdlCO_T??vL`&Z zHlLq2M|S)zsQ2_`J{AAQb=H60TiIHF>rA(oK`wtHVw&!KQ=a@(w9X7I{ke>k;qqS9 zhoHvU@(sbvIfhpbOTsMcyy@wTYon!{l_$P|K%3-3$j;m)B9aVGGz`b%0 zoSBT}1C07>nfQFUe9o<3{PbEjOQPOXlUP05$t+SZ5!(pCJMhB!vq>=d?CA3#ZO1gR z-Hv|l{0jG2U*+8bQI*Iq&HhKH`wKz!D*=Y02_LG(*9WZzlgZPl%oxbo=I8Aaf9(^9 ze`91ruPiL)6~95;0r&eyn3nqc@7x?Hc5@30IVu*AVSryqT8~Fb{dFbH#4#{5fhCLN zF2TTCa~D14ryFdOe6etfZ0Ga31cl~}OB^=KluN(Qt&V5)l=Cx-rjJY$S*xU;+k5Gh zl&Tis_-O{P>HLwoe;*40^ARl#kgy@KfcSlymYKm`YB2WPNj}mX>o@Yn93(rbU2{`w zVbY@JFp_Y>8ludYZxW0*3HCiPTz|%Z;kWV5SMU+SZ6WKJYd|^v!1vzH%)TK?%T@5= z5*az2G{SyKLlsrqs)pc(kMUY4bt`kk+_3dN@_W51Jov1MPLBPXhuHA3mpI-0PWIL=t3Fr>M@WXZB?uPt`G}Hm+WuLUBh>q}#EzjVF_mm%Avu z<;D-soZGQ$_(M^(R#BT=i9>hM#KxbiyL$;?uKqJt)i>N1Lbq-DRxt2VN@pI1dsE-O zn7~rrAxn#}Pe-!!9ponVrd=BW_1`4soTFXQtH$zPU-?h-7}p%p3er)1ZZJ37L&b znRb5Um2bNV(K@)E!F90$;uNXur@?H>?yv*a)O;rW@Mza0{a$-2M$p&^S*picI z@o?|neE3G83xj?-yI6*}RaB5f0{ftksY$EW;`9F3xHy`3&2}udxlyY6aAenF=wFnl~-47%d)D=aj7xSh4y1KoB}bk$@3mu z|4M~lA2q{z5{PwV7zIf^)@c(ZC2l`%q5ypS3tw`6j|w&=BF5411~7NAyc@7~PxCfN z88%Y2&oIug2k{lUhV0ool&}wuFJh5;efy49vcex`sht7>6QpuTCBStb01yLcKmq_C zW_Y=`axUk?5hEXc54kDeU%XThJMSRYvsR;(rI=r?{kP&zmVlzRS=1XA?rIUrK+oyY zEz^2jWYWN7$=K{(`+hJu@ht+TqChbF^iKlKCUsIWFYZpRPXpJWj=Au4z{yuw`1Qu zTQhr{?fc9c9oOrqW=@OsudnOBeSb+%FyFu1Bec(R<*Y^8ZKULz<5NjDt~&BTsWqV`pAt=gWpW*JGU=Mb60D-nP2` z@d9+_@f9W7oOv;M64`;q(*O9Mf}QTt#V=0PwPXCbL96Ap=f2x39Le)k^OgS}_p{Gk z!Pc2SzuDfJQM_j14lKr?qARj)gElDB4kRy*xwXG0b1esf=@htJD%m)7uIH<0$amC@HR67<6uJ;35=$*i7r^9fsahF?dY) z7btEz!nl}L1b3Lj`PH~LkBDkqVoXYOR8(~Q_F8YZ-Tvx}8HwJ@!NYf0s1c%&{^7rY z>wSfZTLB>kqz<_`jO&dK?e)CDM_!B_qT+k+8`1R=01>0(<6o?g3q`VE_%Xc#Poa#o z^oD!go!6{~3+w-{=K4<^^fe|KOYj!-DP~$sEvgbyXF2At!b51+xn@ZadcNNsR_+&3 z{tEDH&M^8sk;11LVEu7oulh?rELwBZe4k%!p@T^%^C4t#qkosb;SU&vKMxF zjapZ)SO!PYU!hT%q1gK6$$Kv$kuN^@m-gINH4)5SF!A$o>G?a4xBS70@l^0B^HXX) z)bmXgZ>X<0P3r^Ciw2XCN4tBO738VBHRnvS>nzChVdIAn{Jy!Ip=~S@jgKSrO^|8F zFfJnkruAyUl}B%CGrh&5@Q%Dt9S*aO2)x|Tez3Zl10R9W_Zbo@Gtu93P;#c@!6Dxj zpd`>Rs?Z@u{!fIcR=(hDx%}>N@JCI+=HJQ?z1-yEb7w5_x%(|{4wzRHU+1WRi~Q$x ze|>2ZGKC(cXg%YZ)<1!(>&V zgA|vS18rWn!3*}t!^?(Vo1p50YdyGQ2CX(U`J-W1pF!M$_)_>;`H$lC-&Ypq7h2`!BB6YF`k&6im%#R{)vATDVAeUo78SF zlQ%w7Pap3skFAd%s`p9C4_H$kHn5>M>f)vfaGUuVTY6M8xxea=9Zas>_)7eCYTMNE zDDm*?RBQ3B?n@&7+OruO9tE(8_RNESRg?JC^loUOnPmT|o}#FGHe&R=E&CUaB)WQRB|A628k8dClDr)L==Jb{bw z+z9Z%%`-hZLak9y>5{~MONjt;+WB5pNP>Ir4qd=J46#QhHeikn6b5)EmU2;YK z{9S~lQPv;vuN0;eD`BL$&;|LkDv8L1uTa}vk#mr(xZiH)Jezq7F^MTr5S*1JW zP}y=EHDetD^e7aNiSV2mmxB?lr&ue7Vu0k4F=H#Vy%vT%~fy$rJNT zp;s?Lt`-ar0WRRps{J(P*~l4@Qp8e0s$FpFD$J~h#ub?2KYik`4E;aCu%{0b^zp%> z1Yl6W({X|P!O2Ny{|Riw4`gKC{jB@(%3-A1(@mo@U$zpvuk&pvk?S*d%L@Yor9rdh zK{mYZSctvUaM3*D$=SEPg;!GsaUD??wg(2b^rJ{t<@9R=*!W%?r@V`c8?LNpOxasL zyX$M*+Vyf0lfhYl(CM9NOhf>&?o2%fQccd=dY4|Q$4l7xxnxiyclo8PoQe)>-}LJa z;t}n%x);f7)$W{8RGp(#eXjGi1}V<%-nnd+m36rS{};n66zAFQBX?d~)R+3aBJ8SX zt=KgZ3aX|$VZJB76Fx8prjEGYSKG=9&{W%(b~odBjXz&@iMvh6OhIRmB)xWz6_@tR zqU~JB7_}_=TEWZlBXhvPyR>yn_AW(X&e>k&-wcm{Q0?J4CiQ4^fuM*V&k2XTw({j8 z1-ZkUd?vD%w1`r93z;CgLDrKhUQE7qvY%Auk(RML$7N z$HK;Q%`eB6N8Ev_;?ov z)X0}!F*!{Oe98R@wUu>rb2wPZkn!8QJwCHrsqI{qI)!JTT|+B5*NzY^e4~8}5JYVz zDfySK9D}z604lhn^1`^Nz5`7e9Rg+b3^2m~`*<6NFiK60Z$Rw3h3Z9;bqsRf@k(#2 zI$y&UGFz>!X64sc*gL{k#~p&c@002$MsCMa+vPD`try8MN7>qg6v%&O-!Nk){Fr1R z>F8eBOYF~uO~N*pfb zw)U@hq4N{Z<)wo9S{=FIzzn;MN?wY}Mprj~N!y);1+^=cY&rAv6H$Hk8wS)>f}HXj zN)i{GY2-f;-eLH5IcWXN*>1kA8>@!JcxCZQO2mj=?>=+PYH#Q6qlb@rxrn~IO?Coxc}^-zx@V@ zR${s5N+tD_XYIq<4#oq8#dXrhduK((G7s@F1y|4P`zmn)T~jo2F{nkF2|dM0m47!_ zq1H=jBbhgRud+J~ACn&iZTF`ZT_r*V?RYiA1yXa`TYt#rzp_YIw-&lKW=KeDQrPwX z-a3$4k^%My0@DozI5@gSN8^8kIJFCk7|?fsoR0L)(xh z(=w=6WzUzPC!4395ElpDfwyNv6*@M`%A|<>U3%Q7J7)uOQkIRKu`z?3c9px=vqV;@ z&pw+LVLNf*w`eb67_S#!vNGqVeJzcNKm+~hPhMS)=ubnItWg%3@oAC|v$o*Q{-0A` z#t%#^EPx(^k3KL}x==$?LxTeQDj9xzW@_5M4gu8b5RTp{`V6qZf8iXNG10eiDJcwv z8VY1Vo7V|sUjZ%c#wC8*9v~_&{$K_+gDyC(NGtbd@R{W!S>*2}+gex%sSSVgh`wAB zyT4we+nLVnLIA1GBA}V&7d2c!Af)SGwQnxoa!X^g5W+qyYinR`d0sY};p^h2S z&>dyk<8C45887%f=xose3^hfHtXK$8OK!cj>)>dj+dhc7umLTN_)+SDFY;|w%yiQ< z53WMw6FWnl>+S(f30pFRP zJG=0!jbp3+WbNDO$5n>eowT?ZTFZuY))zC`auwiIyyzs?}$^slHt}>%VG?ZjBoz+0B2g9sAYN zGWo0|XKDCyr%Z{fCip_jMbudaLTWA+X=OlWJ1s2@s3~8*Bv@*$EiXgS2O*6#44eD+ zTcF_M)&G+D!yIY)`SUhV03fwaIu`#gC6Ax}=c8ep>J;->8W{F5CA_^)+wFucA9(+% zPbGAE+>eIR%m9?8-9L48KN2m7;NJ+9RF_amr=&EzY;J+`sY0#lXM_G?d81?wU!k+9 zn78UwJcqY%^u59?6YjS|0oN`(;pEWj?=sEG#EfCeFU2Vh;c67;k$I*miQTtfG&{L4 zxgh`S#od&omc)hIB+)m}S56jrI*PA^n>z0*;Ib@7RaY5N{CBr-%B(G;u`=SIgY-h) z?_$xMsC#$WqXeL-34jG-F97TIJW$A7Pn+%_!OfuE%jVUmur2 zox7f81X{3xqvlk9z4BW#JAq$V9Xw6(^+MmA-_6{;bO~)uVxV~oUj)sEUls_Y?`nOS z5>47Nc=w(ye6T{8;Loy0EX?qaMhdv1CiS(o3D7GA(5RqC1ZxEtA$WO}(^crjysDwn z1||)_+`z{KGiwK*K*tD-D{v>fV~cu0UYuzspQJ@|rXC;Ok~tBLIP=KlB>I6Lx%o*` z2b?_46 z(P7i00rf1$u>; zzcs=n?+9UBbx}!RxaSORlH!GoOMY{W&EPM~b$!zSmgAlO=bM53R%86^V{G6dG~9nxoXh5EHr$fC0c zglA!T3?yBdb^mb)AngdPVDt!@^RxZNDo7-b77Pv$WU0kRM*ajmhuJf*IX!%M0m;4V zTE%_2cFd&XGJJgH3kA0V`h(bRnr+?XkN@4zGmJ$=oPGiR#q#_dbDr{!9UT`zp@LVsH3xE6p%oXyH3xm7Nt)=Jb9c*BEZiN z{0>|^ys@z{T^*e}{QMBSHmGsLLCh8ZW>4q{CU#a^ zv7gL@Z_D2)Jg3fTmk{vTaY+agHHOeH4gxpWebS6;6YA6dUDxyu$>-1K0OOxKYjr2F z-g4;Ei%_Yldn^|IG^I3&VEoHWz5>=R@6V+UNg9e`Ikz@$v7_&#i#YIzg|R{^gW@&p zQ_y<0F*g3OV6C7K8Wz@bMMH1a#zZ&?vD(j0K@AuNr?EKI+UqM>SST^L^&+wV19No=Do7>)j z(y6K+ZKD7Y7R@vut70?@0a$d90%BsavLO&If#Yd-xU!Mabjx@dIJd#Slbs!W!B~MM za?%WU83yV=6Gj#jQVOm0}G5U^ua1A|M z7+`GPHmKuElxX(g;&R;gEAQ;QiUw)EU^FFVDpeUrj}M;cby${fkP;K&>a=YD`EhkDIzy2<~`mwPksVcUTpScU=Y4}N1EUES~v4Q_7k_HQmwi2*7y6@#Bv ziHQunHShz}KZx8+RXb!r=CY^9ril(q8`ERq<9VyaBTvWctYgO%ftJBj)zP`TcDo~f~dU&62tN`a3 zbUw(cK{7{2Rdur&kI{Oh*cgnw%t@as^^cX(SKrFz@gd{2Jz2PQi+#I^U1$7N`Q?uW zj-?FQ_TXW7s{gPEn)&~x$sm4>jg7FP*4LlHRRP3D=$kjN1i}PLhRc@)wRCnMwdR3W z^!&DVDh2@mz2C~=Ekf=hH)eo=iil1!U_wcy) zL_NrPC#y%x>2nyd3ocSDXlAX|M3^jpn`Yk{1^JvORSA0q$vB9(eylUQ3klWgXm9q@ z^G6~EM6@^=y6uCXs6DcqjV^FSw$HxZ|A;ODNul!CnFclo>=~drgXs>n@)gp<0GS44 z={caJcsMvLEiAyjx8TS8peNx2=4cz8UV$Xf)WFpA+#L@sfpm2aH=Z+Q*t37^>hOyy7)F)3!a*aid{I10S*-4 zIB-Pc4tX_b-HHEe2RGUW^LyO#knZ{rTq28(<>?H5bfiq9KF&_RB8jb*;$a zs8%c%;`iNAYwMQ1N2!d59SZG(oemS6yg8}CLg5Xz2z6ERD^o2@UQ2?}H02n`UESM) zT+=)kBZ-bC*6P(c3gH736nuD?h3RhuBV>`A9sYSkn2D#aD)++)0yT)Q2udgWUXgI@~9Sp(~h}j$u^_SP{>^$AD@9iwMA0>(Bl2cN0!=esWfb zGP2RzCywcYHSNihXq`eR4mSh2myGr5Jt)y`vq|v?B?o(ZfbbbZG$8eoHOHTX3kHCP zJ2n0VQbZYGRd+rpA6E6=i|~&g?rne=~A$QxLtiLyZyOS-CHe^JhF& z!YRiwEt(IJ(B($_4)`+-0-_E5PBE8RD(WEz2RoNeqmQUdv70J+bY4g=_eV-=04GhG zwv1DM(_NM9w-6oktkBViZ~*{XIb^YEW^MXM5nTN~r(g_lbYLMW<$*e;#m-qJx1Ipx zEQJg90CSO-KtB!+-V-_~)ACMJ(a@N>*tXu-v!=umt(NsMkGn{MiF!p~KS$+8?q~>! z3}BZQ78VAUcA$P%ySi#IkR7)EP;t3*_+p5JeU(~`fbP;$AG&)K=`zUY@3L<9;Pb(X zU?IQai8-o>>Gid_cY8f=$~U-6q~E!jwCKKb!!2PtB==2#y`3s~)}dm}%tN8E6xx~V zMmBm)p1%w2RxX!lS&Mu%EdzS*In`}tl0X@Z$V5?PIjl9?#ji&FkO@s2kg%#~?jacevDfkw2xHb0V>6Nra0pvG=6t87JSSJ~X~tJC*Vym31%5=?QcQPGUi!A}u$;F$4x5I7 z0j${q3AKe+paTpq40Cp1;t2e7Y~YB^=StkU($w0|mKD;Di`9Z$prv;1ceq#}BP5Os z1=$P{6l4=2@GR9cb8xVSH9+0j zb8z?$Mfjg7cW^d?T&=6C=qopUAYTXD7rY~S5?2B2z&heD(Fh_vC2{9v zJA&1LSkmU+Bc{dCphZJE@Y+ksY1twE0L)Y^U0nb}POMpo;paW{EtF@|3@j_uFc)7G zOn78>pqhC!U#d9%>tY*;y{R3^?c|wn>wJ+MA>34<0KA0@3|BXo+s?sZ)4i<}n7es+ zushywErtF8h98SOl<2Ak{$B`tPYIBwE*eaYebMjNn2ZE2F$7iW+}&p@HtaukO8fVK zE_M$7{J90&Jy2xofnDWYwQmEqR*ha!0l1A82r`9k2upg=7SzK&4NR{HAO5oFq*3;h z(3qz5gUiuW1%-5zY6;;7~QwqNkWMN9(R(UtFsdWDbW&< zNO@=lv#c$|y1BboB}NH;dcc^k=Z+6us+?k17%QyBkelYkigLF2vov3ppV(AAik)12 zOfm)~#@LwW2unB=grM^y;1tIV^nU~+zjuy3lQWu)ZZ10CLyT^Bhy;U97kjLPg;0w` zOavMuSBRYx{JL1{^gKuGLy+qdJ^! zx-mLd-;N%<-z!^Yy#;l0U*Gn}68 zPvzwR+}i@!Hvb0ypob|Rhl>NP`pHuk5w8vVZ7e?4-nb3CD^I`TahjRuzpT6f`!RZ* zOFudBLKdf9UqL*!Sb|4%)wJl5-1D^s@#h}SqYWRQ#$zB+Be!D_O1M=T8U!qrSFUb>&B?0H*^RkB*H7R)RkJ(e6 ze6hu73jg%-3dtX&=_8#~z0w`L_}>Y8&o1%BcY`X{1DGNh*Vyji2PY?!k`Z_|fc7}T zLJ3Jufy5Udw@UpVNL5knv=9#sAc)qi7B2yMLBv9zP+!Th1PJfu;n7E&M18pMtWhMD z&zJVQ`}mK5KjzJGYu^rrwX+m$4wl(ykYeg$M^oie8B}6-f&gSB-!r|MEbN970t!S~ zif=xSC14%>@}z|*1Gl&YeW~F^q9FN&kIX}+%7{71Bf3Tyah?dU9crp)#E`g}ZZb+i z8P)dl!O^Bcik)R=eGX4>W1}yuI8azldGG62=)htG!6X1Uf_w{f;?MfErk0iuE4=6n z+|#0?DR*mR;uW)pEJv;P`f*4*_Ro`2&roC&Lk=ehii8 zS8m0C!mUh!mY%M`;mw|Hx4JR=(b_Q1Z3KVUbf4rIosiB=0|SZG@0u7A#li~{WKP0m z7+sB`yMvFRxd#S(K#^aF>V&EZ8)A#-A2^o19~^|t)CD3UY@|X5TERWfZXbJPZemaq z1;cwj1@l>Z!UV*hnwy(3{nO5;;hYAtS^m)SBp%SmGzzr-%+BsaaMBQ!sbW;*q^<1T zoPn?0ujISPzg5G-g#FS5utyrsnuHc+yps>O@aCPw^pU@vg8(7&oBtVJ$KgTZp6M*I z^b-n1;XddQ0iggY9{9;q*8zb2>5)skB5U+R(C**|2h$(U?Eqv9X`u-l7Hp2!3MjxK zx~GCcM3twp%kq5S?#P{s|8vF_BZ{lQK%P`p39Ui;=eJwV6eAxQVj4>q*2 zGADS{A!!Fsl#vnB&_PLFo_xj+7}pCw(8ls`cPIL_lGI}g8V!~ogP4@k+HG9RB=NtD#3r64w`)o5wxd<)1DYjIsHRK zJ;TktPSaO=hCNM2_XykFZ~eE?IJj-kDg$Zr|ZF5Tn(;kw9&PyAeO^`KtRnxo9$ND#3JP4e9ulmN6yo; zrVRsJTU~DM4G7!5*IS3M;lehA<}55NyNrm&{7%wGd6DBoC@4Og`j39V__A|@Mg1?) zNMFZ)4;HPX z>VCzmOtmMVmVlsmoCE}-oS!Pd{)Q?mFW|TO*@eU&hJxj97X#YM1ahCJEn{;N&l(v~ z`(YR%{aEHG?8=@i=Bp05)xcddr$=9hK@CVLLHyp6kzYU{ z8U1m!%V6Ein<$jYu&}Zc_B|6ps$olUcYpirlsWx}Ik3h(!4U&Pl+j>2Gza<3n~!^= z;YHVLr{$>4Gb7F^y9pZEgliA)>GcHIQWh&2cYfZ~z4qT@!lkl{WxSzP8BB(#(|-}z z?@Q+#ZCuTAQAj`I7@WFdWEB4?fP&=84P;T}R`8qW;hA*;(TyK9^79JCo~VpzO`%>t zC`&Mnm+K?$>dZR}#X>Cyg0>K?#Nvyq?e$SxYcP7u&+ zwM6fPoC3I!qUO0@mMck+ahs5?DNxV-oB5>Q=3etqm$dmr6JcS9nC3^I`!3 zqWo_}n37E_4N*HtBv;7Ejp6HFtq3O{o-^_#hYz|*<7c31jo54BD!5{FSl7jX0~0lqxUQ`^d(Q&-6^!3RbP-lcgs_%XuwcDln1@0xFT_O>VX4QAY9Xm|{9|vt2_-SvK z>F&+GC1k{^^1~g*axuLML0N~xO(})m@=4b%>rH+AcOI@y91TwyXw+BQPd^$P9p+zi z#6qxZNh?l|pc-m3*~F*2v&WOGBybzr3Yz$uyi=Tdi41NOB}b z>L^<2?(xzg3~5$ELqy5VMwwYzE-XDU+Q0>vcpmfc-2O}(5(cUCz-v^`(niZi9_I%5U_9-%k&J^Mk9Vpc^6Na#xzniQz3$;QWHaHVnVo@yg)9p@Hx91k zE?={~(;b)7{^`mKNy%n^EIb5!jNo>GAbWL9%@Yt$otYEddzg}%ghz!8|kCZl#l8kb~8U3Z|(`MFU2Hj!kE{I~se!j{^g z+;=y{Mq}rJp^s zR$3-)FevV)gIeTMG>(H{0qDtIEZ<&6v@eJnVfGyUC`gbq7_(ziE z&g6Ampuw!5d}YVQq>-X^JMo_SmHH6pgAL=CQj%oSD2YmP`ABf0!EkaFj%dK345Cwg zT)LH9A|gp0Ghq{-`WFYNY$EgL&4Vsc@>uZ8Sm~MISGA&H!AfULzvO84D53c&b11iwV(0^&`CDI* zk3^F#oEOQWI$@R%J|UrJ@fn}_HI>&+V#mX0C?BqTYg?RRssr5M2j^GCTs!Z#IVSe8 zTo=T%(MAay-|IL(vQX61VSh|rDWrJ!yUSOufBmPYGvGvKb9$6ooo!vFms_!eh2$v} zzt~=4PrfWZR-EwtN_pp-DfM^o>rsxC~n!Nw_Kg^ap1%fP|5V*jT~H#ErZB3?X;E(#$!&fcZ0^C}S09q^p!yRA4mq z>-PeLB^M8f{LK=3vsoMyG!*ppYx$wck55v<4H#)yS){e)?RfXY?rCk4RYlLPPbAnE zOWd|xp?CVUa_#+vRfFHrXLFzReeq|*_dU?77{7rJ2p-|$hpR*9qA5S`qGI%`V|wrq zU)fi_E<#A|hc_i7lQ829^kooT@C^PPB#v6@tb^9m2N%O**hwfm$7V$-rBYIQN71cY zcoxO@`9Tf>8zxxIfsu4+;dC}i`JY-#m362tg_Ol*yUq~ zzKh!GJE_+#3BJ$0jz0A#bq&~wZCUnznSC1`dBN~E<$;m-ZpC#RO?4*viHdi(3TY9p z0-U(_=xZw)4{8O7c%?pfJ(bpPR1ge}I$`+X2EQE8F5;P0t}@1G8k(L4c^P;I;FY<2 zIrc|_4o|Ev(Ea|y00GW>$b5ndtzgE*hN+Oo>!hmP2s_$x{fT3dsHdDG`HF3`hjqnQ zT1O4~zgjhpSx~VfUhwx#O5Dq{A1N#6+%BDRp9#bJ76)^=J~BYli1b#s`>!s`0v(li zFTd{BnHN~-@_w>>*DiZ_K`xRd`Q)S6x6eN?%c)pT_tkjmBKa%gDmR8Q74}&{+De|H zyG(gk$>?EZHq`)T$_r0B6ftcro~qx2t^#;^_rE_aV% z(uT3V<;^rms1({Ss|s-sahi&kd8*`joFwi1Y=y7E&A{}TmrR9aTr38X_Nntt_=O}> z$;ix}@-%_d&$K44YfEmXTA-X}W0I}yWc)Cn-O5byEuSCHbo&@Ep4Wz7M^-7ufe(f6oF-p5m*+TfVu?WgPM zl)mS`%Y5%@D7c5fawpSd&C&T#$pa?!JhW^celO~h@w`SiRobO}QOHU~ot?~dS0#*rG zi?4}!FSCt*ByxK}8$C_vc` zJL$m~Voa4gLrDtC-l+Jfth_9Xl>@@6)uV4bOBwv{$G!x)1sr&ZU%e=y8&zp*(fvN* z47G9SD{cj2vsp0G*39pH5m*+-3Fyy_doKN0Ri^#NnrfE7(#yQ}_hV2ovvu`5a-Xf- zwYsIG)MDOyJo6lkHqay%^Ms4V+AYNEb+Fl;`uO}ziALO6*Q?skp6Cyj-(7AGd1oEb zDZy*^_9!*gIN)pf;(cGH@!^;;~PL4X)(0Hh=r9(gixI#vD)96?hOegX21PIKdCM}tC_-NBRVpzu6$nuLAk)X8wLmBho zcsMsZ_NPKarpd6bH}lIP2Bp4lQx~ZoAx(wn)?*$8zeKn;^^O={st0W0mB_!Bv}1f5 z7LI?&kwl90$hxvc=dBt%@U5~l*jEOam9#fp-+i7u5;@`^Z^2Mgb za?-z1Edx(i5gk4X3c~BZj17~8X=X4Hgwa+>cY)3u*H7?o)g#tC_P$4FD>3}9^+y^j zgNW2@??*-@og{Ycx2#5nd!gtm%2V@u$-#J}EO?}WlkZx;`S7PZr zFj7c}V~o_Y-wPKVQmbrx&_H{jxW!gdI~;Aj4PmA@1WF&=1F$Ss*^E(LzAWo4rwSH8GqZC&o)|@K4!1Fr zv|AW{J$@Ubth{{-qY1Zh6G3%;4uUj5l>_tC}dZm@t% ze`cg+md@$i+N$I8B8fXLdi6^ZE5qXQVY0RgF0aL1WxQVquf5S5wK3wm+BH18VO8m? z-OP9`LTPhr3*BN05BH7BQtM#|^IrwQ0`Jw^bFd?wpDc)rA4~_r@iVX)j&J+x6Zz^K z$3)N$INnETazwMp188f>I7ZX}n_Smq{aMmQ|EvDke!m1+d#PzF3AGnx{XWSkMu+Ae zu1_yLnqLh=HS+Mw*bx|aGiK&+XlzS+`9bx#BO0|DEYgMMkdaEt`h$AcpXK;w>?HOC?QRctscqm`uQ+kAmHZO zmF3D%q47*>A)1xj)06^vhGq(J4Yz#5*3L;7mBgoNY4OFqtO^<(BJ^j4SArCCg`zlV z9S=|X3w1A37yXrOpk#mcNjk^LDmZcC05zs*(u}19V}tP1Lt-K$KdRio4;U%87>ME41(}qbj0|0F!wgsJ-{r5F@ZnS) z8Hwim0I%(IcZT;-g~uKI^J`@Zc4@Z=s0s+Dvm0&c_6_InW0$f6c?-Ts&zUem2Ga`1 zniFVL2;!EOe8ERAh*URu>692=Jo&UA?t&nl0XM|o1>#Kn2>8J|ASk!9bbZ;i=4y?E zDT1FY@8hJs*HYAFdjIwi(`O(zX59(N-#qI$&+1p zCBs_RFb@tgd=SDtVaNjXi`T}gz(Y6=1G!*ICCJJEMS?|5-Om%~wccXEfHRRYEUI zZ~!w5hY5eiriq*78LnzVnZUFA+rN6=8xy{4ITh@fJ}_vg&u`S@WRJ!u=^sW-N?REE ziVK@s$Xnp}>G#-OBOvo{`05$#etftk$sf7MKKw#*0}?g= zc3b&4Uf!yWjNIIJ+$Ae11Y4ENM&G7LKmCk!q}(_S@LCrd-zJHT)v%21TdzslAl#{E z+YoP2kn@w{`t;-Lw8M+9yf-&e^6O56uwQ+8AfRJEL?U!t5xMgFJYncu+|rkm{Rze` z&YO#q`+AEr9cD3aKEGDCUnn&Fa&)xEL4SKEw0?UI{e-9gfRor0Lqk#o4w~zRGIk&| zvdFJb)K&q8>^s(!z?fJDS?_J+3XDYlP3SXzdBL&g+wr$?kAt=P5*akD5Jr%1M7Z6D z)v4ca17*iAFZbl=iVy{2KRqy||M34|>aF9V+`9MSK?D>8lx|c?Nf8M_N|X-i29cDO zR9X>Gq*J;z1LoGt?P=irEwh(mZ|*% zu_HCihED#`QUWu`!U$u3Ou4albl7-2I!7eQNdaOo_yM0I&*uU#$=S&XASM{OSerOw z-_zZNzATMWS&T+g@S8X91sxbtlqvB8AkWn1biGNHdIa=mPS*r^FE@H_rzeO8RN=8M zE@)tVAd*gGq?-alJ((V+*ah*67t`|0DFSmTYO0BK7(#Pp$i3u`g>9j251@lXP{lBjke4BRJRUiTrL}-oQ#c zHvSbZbrbN)J11ZG4k?=O2n7w>5i%Ia`A!-4nZ{qa zHO3;wkffv}C=98pUJ0#=*`7!E-Ieov#x3|gymLCFd#^b&^M1yokXt{RpzQ&CT3{ms zFi+_B70h0tPz75F zVrq64IE?MAt??1I0!hkwfNmNa9^PSqGAVku)E6~$>I)h+At9GcmuaD;0#Z&m=g(8& zfxIn94^9I_9_rI=@=VNfQ1wt84q3swfBLvGv39e%HLR%lVgJh=(py-F2Wj_6cZ^ED zb2A^6>fawXIP`jj(EQ!5x;eiV#$r)4rcOm|9OHSLP2||c&0g8bOKYp7r#5GvIizZT zIz}-X1)7UAm4a z-iF-ihu~p&Sy1qVs2|9_U(Tm|c>e090b;}JOvU$I86ESh((kC0_Z%j;tTV}|Iq&@s zX1?f**D1a_A-+04g3=3k6g}8Hmitip;_tW*9V6aUYF&@Satt)c2$lHwnkFxzn6dQ| z1qs`8FTY$OIXsEdYwU6|%Z~)(PU7^hMmfIjoSPtZV=*u^ym-ToL=fd%EB4;&cg1_V z&L=f2ud;94b=w|$dR)U=L^M{JZ9Ja9c6kHwkz>pMb(s$vKMmnPR=%ZNu{&R?r_rlR zewMs0pW=Rm8entkaMMC1o7~lk>3E>*neyO#mXfR1C#3QE!$^GWG>LJLfjfN z`LOXGyJeoBIbU6n!e$ssUjT460viP)i;$}TUM|qh0?by%ql1rFv*6pq{)*vIg@VM- zpWCpXp%=2kaW9$eOGnLs#WP>4#RxL8nBBX5%k<68*?;6aL>118?`NO8 zzpy0yOK|zBc0GY%!alzz&xFq}Pa~&wDpixW4-_tVd*czRix0bC%!$VZd~X#a33SO^ z6OgW{6DxLc$#@eA2nc|L_X&n%Wc4(Jnh%h85V3#g0pXYn875E|Q^M6y6F@|)WCT*H z*W?r&-;i)Lt}|Eztf&A$U}1E{&o;v$umY!;(dXdzsa6*s)g@?mIqEb%i-I02b#-h6 zU`;~8!_m-GDgcGFa@}LIC;KM^on6&KE#rp|OJ&OnER3sqrOS5st{@OSuT&6shJI0f zi5#5^*(Y(*Ja45*f14cf#trwPm;aN!ft}{+2O53nuR4-lMm%0!vL<|#lB92!{2*pW z)v2p2?fLJZhcd&G-qxSRJp*#9yQm!wFWR2`;lV;|PzDBUNJPcP*f!Q{#hg5|?n2Ze zId0wVkAGx%x?dxjvi2|;on7wka%PxM%xS@;6aO3@7*-uE^+`Rl! zdp17kF)N8?xFJ8pe?HJt?U#`|o%|h}hIZ>gg|8_$drCx|nkULCT!;@Kd}KH~Q5fZ6 zy!!(Fa1a<+MIUR6F#riyBE3caGQpHw;@6DgGnptG^jrjEXRm>bp}L@D9@eLCG?sEK zw>L)MkFSMSf14#|zF*;dAMXUnsU!UPm3P8bj@0dkyMHnU9%hSGf9y#uwC3&-Ws5?H zo3)ov#bZ&LQf~X$ZaE{T8~{na?4j6Vi}D5JnHzEzjxv$mSpEL6koIW+BRAL-F{=FwvqY#0?k76$v1lB5P4g+ z_hm8-8q!$~zqqJqncMiwtDi~szY?8vkH7E_O!%9B%aY@yNb3=1VKc0g-%Q}M4E#0& zLX+4~@_2IMjDXdAKbp3!qR%Y-C+*4)sxHHZg0Y5?Fn=FS?a8&9TwBlW-F7`r0ZasR zvPp@FAD955%G0><3Yuc-N^G7yX(*a>w?6ur#_a1Wd|Ekf!DTW(N4b~Br9b_|%kz8F z#+S3$GjfOJHKzQrNrhSDL12;c_fwnfM{_hus*xHojRfbfCDnSz`VP9ws4XQ#cg!cU zNNmstNb<0(yl_x>PwPs0-Au-V-4^AVeRaC>+~+<)Gw-btVy_l->G|G*Us9#L+*^ew zuRi*+GFzr7PV^N$8NJx(U*pAq+~qg*m%KicR?lWv^VK&xsl4>^!RLqpWQ90>2cZh? zBf<%+s0$}I1bf&vr+t0njXl^`&s`ooH`zPXMK%^TO1C=idf&X} z(_VASRPS)A@>ox5$S(ux!v^t*>oiqN*Y2|2{rv&|`8gAb9q@))1Bp_Y#D4rW$u#7+ z{u$7a4|K!VBQIEm2<)Th*joXs2=NpoUcJzpKxC1%RZ$&wE!?>PAMC2I5I$LHhSwtzi1<$P@-}w2q5auyWSujw(Ga(0Jvg&fcHa0cEV)36~HcL-zE}XqGY1 zbq*}L&=FZ0;OEkMiU+%$$MH6(YHZ^10S>sp-U=Mnom&B zcc&6t0yGW)7RbwMQW?bAa7RD`6B=gzT(qz--PLt~{VWQo6}64M$q{0Jw$Ip5^%YoX z-mBfuK_W!}LnI=C%+K$Tu|ENzE1M?%?zIdoZKuUR2%REEl(D^un#5?zvwUuM_Z2asy*GUp*TcA7T7{)b3);eW zlQZ;xgkQAw6$zug$6j{J=vW_M@R$at!2JBhtTfc)TP|*HpQ+k410`@M-Yc?(w|nkX zGTpff?HQ!8{|8X4%5%E#4htnL+f)>m+OtU7tz~`bcuP~Ba6_odU5cTVX9|kHfq}R= zYIi~V0NA@fxg`TnJ@D$bhci0Z+2J5)LTes>dIi86kU*0ulf{IUz{LRy45A>h4#op8 zTbEpFY`>EPoT`!Ud@UL)qO3%+|xLlC9*O1X<2D+X2J4k6tJ&11AK)O=jlj!Jk{Ee%)`9^TR$;elptSaL1)P_o~r54fI)gwZ+yXodaXm zvIc;he|1wMb}nU3xM@CA-N z%PohFN8ZJaISVHtUFJ*N(~uLWV?BnT8m<_|6|q1@IZ$>NfwmGuLzN-%S65}DR-mll z2iqw~K-rJi^|iOlWc8hZA}Vk;r;D*e`!WT$0Tng%h)Dlm$iwU2YzXJNj==!QL9%(k+$YW@xON4C;PFL^j&Vm>eTgR)l6<~Lr$JZY6|ri zRNSHco00bxW>B1O^4zb%6h*gYJF(B512SwZiF^%cH=G3;X{hJ0u$Tio?tD*Lo;+cN zP7%bQqM&sOC^*yFTmMa`6y-dm%c2^HfP=6(Vqw_pJ%wA+a$(<3N#aX1oTO2-=U#Nj z?XL{`qb?e=jj1>z<(G2>-RmFWt^T0;q`cxT_2U*3rY`K!4~?9nYoq^fBHcTh|A>!e zVLk9YHu-}R)w;2Y^Mm1;uZ*;`D9FG0YYe2<)SVT5kdFPM3ZN&T0Z#njO6$@ zNnJ)2W*yEwqLwBmn->NHd+RQoSO)w~``0vkAyg2wZ2=(%uIbBBE}N0KOQi!{m)wg} zaXlXMKAu%{`r?%;>N_Q_taMR$V02Rpx#CgjQNqW|-PHAW%!NMc2zYp*;+C45I6E71 zd#$h@_nL)X`%wcO=i!;1ZV>F)+jAp0jhh?Yua14|?{@-{en^a5!ezR3%Mn_KU?zt@ zHo^Gc(7h86;AiMH0l1zjiiXet%Xw~8xHxM9k&Y)o`q?s}@m`vx&3CFjEzqy;wHOPx z!c;t7vvP!(XSJ(lJvi<%A0cjGN4g?zc~!L4Wm%h%Vu=2OKeYj<)ds>^fLTDV(V?e{XZK6$34H3-{E5hzUgne(RznC=qhgf`P6{LK2Udnp>>Pw6@F z3j8g;A8)*u#_c05tTFUVf3%l{X>I%H&1MrqxwIWcL_{P-Tv=P&0x~p!FK5yv!`vlw zE2l$e(6>k?$Rjin9~~Ur0|iiJW#uMfnoEIzJcIRof?+wmk~*EdwphrH{2_tm$QIn> zBi0l0Rc#1!iUtQ*t)>dO0wHC|sL;5znENA#^05<$TYXXd9~y0=n1dJuR{r6QUo&u6 z_N0nF`}6vK#)5MrRR1a}wni+|3>#c-B3#_v=OG(nX$j&Ns@S#xpA27-x42#I#leiL z(Z+PMQ2aa9f5K(AU~G9KPok@el-1Spun>q?B-c+=+-`T&Oa0JyiTpQlD&7hH`t|c| zU6-qq6Gk!`z>U3MU}UjAe*eA{$qAI#@MbfD)U>qR062oUdf^F>j6feF^cjOTFF5eu ze*6H-A>?&X1}uQ=v4Dt-1Ufn308E(^^L&TiiPge&0eP$FDoE{Roz&gye*Ld=bzu`) zSMPi;uy=RpiPS(1PIx}jchyfa&N;dY21=PK+_-pXg(t!&Kj;1gscRAlJ8_b{MWllo zZ&MQrCgMjE`JAX=^Zi3+)_*T3JOeb`vGIV(2?Ae1hY8!0HyJQF-~gfJa?^ImKLOV@ zcYNorhp6ObZUUo&l-Z;q{9b&-oqfp=$R9-@ zwha^3YAz{o(<6MI_8Ofv=@$qz`W8*6umH%&*_WbF9p7Ag*)wyP)FnwD2*`oU3y@7% z;IZWNSp^Z%dn^~%;?j8m3=d#ei1!dNG8wY`yYKyV$WGx0fRixs(v~TTS-V)zb-E37 zgNYb=Tt+{;&eDXd7kezNkf|Rvyl8|93mxlfBo7_t#Y9tplWZmbElzd-Hwveeiy4(S zUhKRo7EnIyUk#0`SNqnHH@XfrO%%sd)5pdk1)B?9!Q|x7q>Q+H;XHWF&>acO3YrYj zAPjeGyN`hfrlk=hKxnZD=KBFB&A$n71*xlzhrpeC*uB_( zO?OSdoHJTbjOutV`wv2c2yRmFHLO-+?q4-|k_yl~0{3S|gAkVZzS@845hzWmt1ffxZy!#3?j~GKhLqWoEwe5Vjkwdh_NDWPA1)>p?yFuJc^7 zsAml{#1<5Qup1p+QE@T!)RfQulR`Nd9lyhx;{8?{iOF;^@dZIXUt3 zLzo(_O#JP+WJS0yrE9rEGXc`Lbmn}qyj$C&Yn&LdB>^nU) zmK(%z{eMH90740nNc(jKt}#%kjYJ~DmmB`RpUWO(;G@@0`ar6BY;89+VMXwfJoI-O z0boZgpc1N^>X>HFoK$5XPVlm=-N#%uQ4xAkq$QCC`)M3bs_KFWgOWv~l}{Ca2$SO@ zy`g)@%_5}z)-$QnA!9Jfe0)EL7urCAB7oB9y@1{50r#bUBPWxUnfYXWq6wPsmD?{6 zw&(hMXCDfTfhrStEV$>-gGhdjdKz}pdiUGH{IljnO>q-;650> z+vTr~bygJF;47&#^WWg#75p{F#6U2#I#D6hS8eTq5IHUZ0hky1MgLsoN-btVkDs z?|Z~mHbZMVf%+PHb#@l85pXo|WbnS#OVTtPr{+~j2>V&^*MTqtr_Dnmlw?&f-dy~o zU}X>s(fhP)*#G_P$D=#idf-9p$KCrLK5g-(>`z}Tjnsghp>ln0vlKDHW-c-0=}`MW zn@xq}SA$JXz<%6nrOiJ3=OVPDgR%Bm9^}Hn&4FJ7ddQssI*KI!D`RtQN2eZ23Txgn zU+H`U9P6r-ygcPl=+S==%r8ZukY!30 zdIm*}ox2kt1o8fT9V}OX&p(o>(p#-}MyEB2goal%?u(zLuyiO=+}8Cw|C!{iELp&V z%cM9g8k`w*5)T9Z1di(U{$%>)tI|5S=a*WO&cKl)lat9%Ht%cfs?vdtA@)03P4|INy-Ng1OVY$k0hiD0uALH*ZFo2_(Tx zwg=ujG4G=);}?)%k_dtqyZwjOM(o~YtpU&6b=mZX(Ixn2pFZ>&nNY}yuEbFaviEGF z?#V^sKU)RDR9mkj?EDPQ?|_Z*k%|l5E~~9`({*cYM~?3rEsnL)?1$j5P7B?Q><_|a z+a)k4+tcaJNX+dCT{L;&bpJWBll>lLK!AieAk`JD89;nI_0~GwPgDwYvfRk-rVS=t{9cmGLOYR1Pw8X?a;3rR!7mStQ+Zsx&q{ zqw=?kXB5VBLyd8+PqtqMJ{;Ub{9OIwug^Islu~%4!yNGX{Q2`$4iQ{WM=H#LLPsE} z_+bQer6AYEybi!?2ohybk&yTZ%i96E+hGUU;|9h>#Db6*YTD;;y1!}GqT^bJo;Lrp zH~a0R+!qOjkI9kiTY$+dLlpwUqZOg9fb#P8=|E=%NAnK{*>Wj=#Yq*S`t79%ElL|I zkhj<92f|T3!V2%UaK;wfk=vCcC$LEb1_d3L3&WK@%I+Gi!{jKnOdD1=U`t@pwGJmH zxO=eEbW=6#QC1;5q!63gh*fKz=Xfc)@=wxdy-AcKad~=_^^sb`k=mustZq!ux7@X>m9 zpp&xxrn=$I$+y6D1BzSQZ2N()UsLHbzylp#?+pAk`XqG1WbWzEYvl%Zp>Ni=YigYP zKxJ?;6q-z-9+SFO1u^er=+t9@Lhz|2;x$({OU??cTj$ATlz$zEov#aj%{X#dzji+Z z&(a9Mq-}9{aJweoDv(HZN}HXFwd2lq3$Hm=v=rE6%V|M34*dC56mlOX-96M@&;7Ms zl+}-BIJIBNS50;FT1|ntLq2D*t!%mfc#tQV51H3Wp^Z$a$JEQoz`%ZbnDs7NW+R4! zY)I7IAZwz%G+lB!^yl~iMzVO8U4lf%0MQ?Vy z$&j#517{|x+D02D6ObPS648$iQzCDIs|;8g1$jBSP0vuw+kSXxR_i(4UBDDC_J>I6 zV3*BRYF~tBmHgK3QndGd_JU<}L-p1w4|{lhV>8pW)IU>FHvTEbu-lz&Y_{u$5h4)6 zA{8s#3$Kx9D!SwjzN$CnK5a%3Y2(sQ7@l^lErrl)swg{t4b;~&m}A|knn)t?n0}lz z@+(1Y1xj5&>nRAlIwd8_YL6eM4=o$k*p7JbqlT_`gNO(KPZBz3E5=r#1%&^D5!~%m zV~XRD__lAiikr5An$@dp|8_1s_d4eI^{r<2_p?3v?Ami0S{i}|6YaQ~&(XU>>07H& zCCx`mK@1)rpkcPH31+Wfjbt2ZAlY$f5-lzFyIfe#n|`kFPtmh0b0=Fz72l6~w(cRr zJ=Q#%zEWIuxBGG!-;O)(X}7R@QGn^4m~Rj&<)9B{AML z^r=E*4*?|}Aq^Qd^`cY#9>5}iW+%RrWwH5qElXDb9zyutXVcVUW1hRJtFbY?olZ}A z6o~hI@^aiw9!_cFxWcs=&L&Bs6)^ zdWkqTDFN+ED_Dt+=2OF+=e+SsgQK%)c?ypweYGfsmc1qSHtIfls^2fArZO`qr^FEC z0dRg47&LfV;nw!;YEc3nJ64q=oKGhjUv$QCb@ud3f>_L4S5lG~FVLS%c&<0CRCI>q zV+^>EFTo&#i0UdKFS3-^!O1t;^G2Zw-}Wt;86BAwqGP4jYNE-=NbGZ@OEuojdm#EF z(_d!th2h1_l{i!2&M0}!iB!N$x1Xuj`MMFP8{D6_9Hv)VPV{pMwfsGGDJSX8AB0lc zL;D4YLST%NmphQGdP1B9ou5Z)wrSuWV0uGgbDV${s|=|iFPn1U*SYt6V+u;v<(Rz! zk@C&BMq`ey;Nr7YMyHk2KfznM#3_z(@Lwy=YNe3<4SeKY1J;BePg>{q&S)|c5~ua1 zeM~tPR}&_4FBl+X3{2W65)WNvFp?`Tb8mJ?qK|cVOR`e6R2JR?KzP4fWZes(3C&1Q zDr;G-8IumBF&9>HUzdw!m4o(o}(PZ!Wqan^5vF z=Mker+IV4Xblxgz(A>G!f$f*UolQTX z;P_*!4*2ov8+dUe>MMOC6}Fz~H*bH{&{{-!|N0qOxdO;445tqiWOq>D7`(stVhc90 z&|=W(L~Mk^L^m>L#QP=80=|G@sH7Vc5(Ttc`yhAr0f@M3X3!R5M~tT2>t=@M!8CRg z=(IetsMF&r53;SBt{7n4N zp?#H2oS~Xp1w6W_=N^XO4xAOtzXWV`T6|8sPl^EjhM^h;XSo>((nw7}Kuk(XI#vqg zwup37{K^Eofrn9GTs;DR(wMHL=4SQlmej(d2=jwcob5LnOqSwjTrZ&Z)b$fB+x5OO zWM3LdMq}1cr7a;6TW<0t5Z)DXa}9PN=3=8J5AXo?Cp;aXBmLbrNS}#AN)y)nJ|z8{ znIJWXoDLJ=uAhl=D*%xs#KII!X=qO)o}%e`ByeN9m0pAac?6rrckFx<*cQnLCeWup zPW@GD)TdW^_6B@3AI*zYisFALD8Se$Xzykov8{ni6VcpR_y?x}>xS|6;3Ed#lg&1q zQ6N|bsy_g-`+(Lwb96^ca`HX%?=jE?RwIM)Mt8BI&Hsl5kg)7~-nHUX-|Yxp&ugK2EQu#V0t>>@91p@ohPlu_zGH z3-5q|!l2&j>U5$y%wR`Nxc9;dR@Z12W@e^GF9FAzkIxx^DS7L(zzC@yfCsM*}9hH+I&^y&bOW6VFn%)Ik|;RJbDrUb64|$ zsHf}IN+Mt?Nl8e+cjH-vbOStPjSi=2TZk^uIsvcS#R`mzL6NJRLIX-VPW5p0LAW$f zD0slS^KJ)jKkElC;r@JD8&*o7g&nJOa>#kVZ}dgaiF-iK{DMs>gZNVa%$ek>u$7Nb zb2bFHDT^QpArJ}2pt{zrSO`i~wt!aRo`^5c%Ijz0dXzuvcbeLyQ< zNJD;0OScir4M!&Ne&(pdBX|;ZuzTk5d-xYbBW<49(WBThn*3K_viJ9^$zf*|?d=ll zgxT63eVF}b(HYr=bv&`|`-PyHX~@u>UJ|p}I$FdVx{WY}->U#mcanXDB7Agp56m>M zn3bI3Z!{#ci{EfCoUYkobx5&h*HHgm%&z{xH@eyz-3!0AdJq>{^LtD{l)cw=L_1u6 ziJj%<8v8@SM`cpg_OT4T8KsK+?W@a-vTx}U4W(rO3WAtQzQibYl3-X%Tg| zny-#g>ZHBQ8Tq>%1#{9;c1~|L0xZ16!zrvwgGugF7+(tgW1BkFEhVHjj3Z*|vxc_p z{KkIf`s;>7w-Wf1#FKRygKQMi9eCq9p$CJFc%VVW*Mqb#zE)iheu3cD@-vKD>Tyfd zjxwvLa^{CWk?0C=Lohi29im_e7I!^ZLTUI5YAlr`HYwRf9V;Tg<;xS_8GrLPzCj4H z8^>|ISnhtWF~l!I4K~0q(tP^98B`Yz=aRq@MU&CfpMrR|k?Vlw=yTat;~Qv>R%7Q; zWhSIpWOi9I{#NJ2GUiUY(>iEo_;qKB)vL+IkM2$g=MOT=?K%2lLZk++3fttgKY#u} zI~+#5ItqBgUtc6`MxUMV^%s!JCjW8xhh5s}FJfCup~}wzg(Abn0LM zrXWY~%T!XY{E{-IT>8Se^gQymaetXU*+9#+K5o%;!?Zi+N30B0Nn2w7KFjBaJKBem_2K#5%-Ub1 z!`TuzgBKj|@%ggvfG0-?gU<=3;tU!GAVrb!464~{^=y#Ds8Xq0!fFj4YO5DMNyv_t zbki{oHT)KA3wNDfc`KnfxZ&%vQ^84kqiYuf!6i+w2fHzIOz`PyASbQmR*&!5HqgE~ z3a3O}XJUftNJ31E%U)hU>tdX^Lc#EEWX_2(R{58rrqU;sGMIDn-5#N@5Lptfj%}Cc z+~t3H?f2l%)g2h^-qddueGR#u_Y%A2E|Rjs4%TWRVlL9ox3xp_dy)S$4N0b--`-79 zIEkO}doEWB&y-dMDk^KJ7$MS=u6If+z?;GlJwQa_>I!Tq(-;$kIZobj(sr$k)vo)V z&HK{qKgVDq4mPLtNB-{{Z#ZcQL6RF<<>tf1j=t5lPebIg4(b(rtDBg0k2%in#}O{R z+J6p-g}+D3)y}mF7*kNO=(4Cp*<;e{T^7#3umSFpUh?3R@b-0|edHvNfcChDV;&xJ zSZRY(@)P_D%=TSSzz*za0!f%v2o#QL{UGw(yx+8rgNLV3P+Hpa?Hi{1(jmMZ3mf-j zBS@T1$T7V<7URRh@i8CV^K{_9gHqYC{r=)lHV|c>bs{Gtt3$03(hAs))vQL!Fyt2( z+cmUL)4PxJ`kXw6%US*Y_j^RIaK%cA1-MepS3SWAcSpHuo0*wSOJRV3z~&0v`=Gpi z2#w)o?U)x1hhO(A@P6;YRtGtwt53haxdI-U`#TwE;hK~5$K}$k$cD_pty{O4nO}=C zV9XU9F8Dh!3u*v2e59#Ke&x!uF}vDo4-jMe49RmA99&$WVu`qliB{l{$diae<;29r z$5FEhr#}YG`zWZ8p6G#<`+FFi$N0My zo!r|2zm^A!J;B*9u0Z~;Bdok3XImE@$ z;N^{!o63L(1x~{9-`E*kg{vKqT7)1J*nFh5F;NBPn8)~V7m0{`mh$sJ-|7_D&SIb` zAvP8x&$8L~$sZ5%6Hp+<)%xE|o`1)Qv`M`4R83x99+(-H1`1(QJKkC3bDH@EVI?7> z*!V*Kzq3P{p^pdI85|at3g3r%Icxx3f|K{)_FrLa1m;K~`y0z+{+XV|gvoCGJzQMO zM*jP!UsxC?CW|9OEOsyjlv(W%E7BTbZpZK4?yzY%W=}AfaDSndMF4-hB>@*KfOde8YH)%!?miV*8#< zGqQxjM{r>#>5y9u*D;SlX$2_(NW*{&U4OJx=v`maN1j0#VGgSiKxYN8&`;Ok$Dt*d z$NCrm^5nL*TtaYqC`LKIn9PsFe6uQZQIm%dXpInl%Efhc?*m5-5tzaIn9%zOvji4y zTYW&~Co~$B_VG{MgWRF`=2uc_?Pn!tu=-^&kqU&|r{YJLT!qic0fcAw_Q##i7)9^g z*#URDI2#xm)zU9RH*|Tyq!9icRkIR6j zwl{DoLgjM{=9i}0MO^H{T4I|orP&~hlCp- zth`}$oxsCT8a=-T(2&Lc9O(QDK+B*f_M78VQ+;4cO`gmN!kf5pV*%Q&<9DD8wK7`W z2{->@K1Fcc@e78a^!er!boiR!onLDPKcq39U~k9srU@v&e*Z3?MSz*yj;eKK>jpaU zs1C5=+j=v{Ft17)8jfnl>}iEvtd2EZg#i{8siCK*XK1*J?(^JPxI#k%|2EXqTSE82 z2BfGMk_|2qRLanlQ;tFqeSr0O@uD6rQ>#}D>Mc<&Gv6YC;2BMMnVR}(ljzG^zf7j_NI!ghdjl4-+P|yZ20y--QC`!T7*VGI~@R%i+9&XR4t*hf+qMFhV zQ?e9A*yUtq{uv(<0y=5*ntMz19a!qH+f`W_7Ec}3h!{`e;^2Ux&PN(eLbL*}=jiAt zGxIt+oIBrreS+d$>xbnrAS2n>a13vE-dRwE4{izw44U1BiBS)maySFrF-Y+O-ce2M z54ul@Ro&LMC>wOerJ6~uKqoH=$sac);i1^~!-lEOW3V*6rrD&|I@kVKbSFdB5+;i) zBy0|SUGje3yvfYWeD&%_bQaQ}WNFFzT`LI%1q>Wm&v1ZV+`Mz=mo~kahs}gVuc{ zY7N~7wCi3ensh`#Xqk8yh`NuCJd(iC7&#I50RN_Q_I83IutT0P8ukPFqtOVHD1p2& zTE-oTvacPp71&?s`-09&D}`cy%5(y30L{7ASDq7n1Rq`#>~MN^UaAK>FK=H@7OjuB zK4doZ^=%Gz?O*}_u)uDfv|ZVS9+zUChx~g-gC7X)eJOSDrhM*(gbDr)opoH|K-l;Z zRCuHfCuwLopEnszwrfkzvNu2eWL=F(HTmvryEez~gCqAiK;H5z@Zcd3#TST(7&f`G ztT72COr~u+W&L3AK4yD`u;%aJ8vv7GAQ?bf2TP5Ofj3B7>xSE~Wwm)H1wd_`W@M#m9e#vIr;R4Lg11*_R z_6>`ySvDARAlv{L*?|R;?wPD`v4X-v0%GD8ATkXt$#LeRHN>14OV}xbYY{Bp-t&7= zZK1T5e{T@M{T&c5EMRzJV#wg`#&s|e&*MgDCZHE_`?0)xv<4{1@|qegH7lzHNMSMS zazeS6syPC)eYto63=F)K(D;3DV4}@#Cji%=SNuNcU;w?p1>bT=53w&1+#l6C)DVx- z(1&S2{U>K%i-Z<9z$6O`ABjvJhONJbmgONM&*Ch*N0|3BrO^VB85(qO8&LLg-0_9! z=^t$chJO7z;9gf^{RuYP$aA$Ckg!=Ct7Z@lgh3l43-#_5b(q&LlgtykEGEZlbvOgb zE|ZawQBhd|P?@@EbCq@%-Hfu|_h^!C@&@`A&tqxw$F*aGbSUfUqlso!Fo5Rc;{b=g zwbbIlXgqld+jpbF`rwsPlE7*ptvzG_qrhR>1*>1t*yy#lGBSBQv5y%JFgCEwWObhJ z^``dmwy7L}L8xoyH`^g{^0xUU-u!#0w#{e?^U;d0hoqz=E-nE?Y9e?9DJau$Q33Ps zWRny^;D;Z8&^#I(UErb=e6N)y?W03FPk&u-Vf%b3*E5j59Uq@JVE}Q_Fa;rCh zcX}S@U~8H9!CBz0rSz>jGl~tjPbHl#Z%IjAAQeE9K9a=nVd@5B=^>0|n98)BXsj}&P=;RGQiIq$AwoY#dLHTEby0IxzSsg+zC^pD!6!J~v!d(F!L%$gK31`k%; z05tTh7NDk+$S{d?Ux&hlm4;>t&EE%+`Q2Fo>0{VkCZ3lS6f8mZ584uW%WlEQL@;s0 zqJ!lJ3(SfO+zPF0mkL5kE+X{c7cx*esT`ppj*E#oS#|L3?CRn#E9>sGcEPeTt{r!J z*FL>CRGQWo07F*^kGR3#$sp$S{L!OF)4&w~(BOD+@C9)PanqT=&Zgcr4`vn!zwb^d zDv4*T(W=cAj`x85s=Ni#_E{8J@>MxWZ}W?L?g5CatCKA)(7gu@%P>#uJiGwUg8|h5 zLOqndNF9m=f9#ufwXzi8$>+0SeM8f0KP2I4D{X7Xn#?+)XzlAvAcq;Kg_kb1VLl?^ zZh27)-R`pSP?PeGh>?Eo=xw=qGUwwkgai^I$49VtWzWpawE4rXj!BDx7cOM>?eetz zGFZ^Q)TIIq!}KYI&=PD^l!!5fNPONci2-|`wcnq2)+Z;2^uF4Pjo_@sY8#C}b3Vk@ z?$b->5O>_oa+m|ctz{pYy!qKWlILvw1BK>2(?Rr>kdTn9xFNIKLLFhN#T2W76-f-R zt$}faZ*^0Bj-F=ONDR6DA<(qd9@dl|dTF2U(sZxgJY2AW$VL3H^u`B4Uz*?NpfUsy zrun(K27{925@ZR$RV~GjM?kx@9B_TPToB#k5-b&GwtP4-r9W1zHm}%=s1EAmcU71} z?8<7HmnqaGlBG-#@ne0I1AhQAd=T|G00m}yD6RWKZw73~1rRiJM6tYl`BGYY zNcUeDkiIN@Fj+8~rQj>&d7J9-5NX9Q|AIE=PIGHCJkzueZnU0#Tu|%PT?Hml2wI`w zcH@Q>yby4hL;J|F5X!1GsxsOsjkK5Zdkb~)?LtP?W>2MeOSV1XH62{1N1zWN`%r5; zqNb}$O+s=TLKeu;QX8tyOUH$}O%u2ENR9oJqw$f*7R{O*eb!P*;Nr`h(z%0dL zV_svk;SkCVi@qwa5pA7=#L1|+Hhw64@aM(Xkxv(w&R??*7VZD#4uMh71F5*%@Y#&9_uAb(E6~%~5uA93m z)CleRDq0-Zr>eMLK`d0kWU>D)ZeOQbtzVrZt@Uaxw`9rewNf0RuhYEX%FS%nw0Y3& z<-U2K77#AHn)Q0r$8GId4gagP>)V4( zWtiGK#bl$F4B1b`S3UJ)CbbQ7CJV3;2Fw+5=$^yC!-c@!^gF8R^r7>zASyXengPYvs=CN zi7G#;6mE$Mxpdj<? zPe%7P8y7D06!qaEuwmV;CM%>f!BB-eKQ&fge{z(unxeq57rg2ff`^c(?R`S}t(Sv5 zWx`S9sv0(fwoV0e%5VX8PoEf)^ukiH7@tcAkDgqWOHf-?0+DUP~L^|?{*lw*TDNI0kj~cm=!Iko&y)QS+d!if4OMXOI`(!u|*!S=V z>8teL(B=75nq5>i%pu~^8o_ND3L+q(%6X4eW*sdUD({i4!ur@Ve0;@j=Bu`_Pj}ZF z%$b)lXKv;8vXW|DFPvMro1*J(kfEJ2*(?SAOmxM0c*p0mls)f1j`3i|xCUW`PI(34 zH+Jw7IDI&;P=0@+z3?a?JgQcDAV4jpfI#Eyt+fLAui9M|9za$ExsF&d%?~uZ+&g$TDn_fT_LooVzQ68nLa|Zy2K<+iH9&u=vdyR zF~n|o9ThT2R1%xbpv_UH-5K;*=H}GSGMS&Vw)TL0-0EHKd2!~OPl`Be;=%>iK4Ke$ zjP`5&c{(Ji>BCj26ltn2Ms_)W!{$_-2HwD(?*a=8li41+_kYb}1zZwnxSGt?^DMR` znonUuPcBN%L@roa`;mh`0k&TWB;Z${&SyoD?Mnp^@i&mU@U2OWqV?rycGB=2sSF7l zqPJ9BXLu@vV>bTn6T)x58w#JW4QR?+>^3}%oDSi>FyG^BU`{(bo_%C3$2us~u45M1>-cqtd`UHRGQe|7siF4$QtotTe z@8E{~F+L_7QZVyu%3i|?Rh^6-nTW7j_tiS&iMGO)Nc!t7g2QR`|4gsmzl*z%|6Xf6 zRDS+x1pI!bbN`p~ljsNf1;ffX?0eUYLY>8Cz;}}hYn%6PmflqN2%9?H8j{ zt&YDHDekJdbf|NYuKJ@<^y0OT_09Px^Jz=sz)XqGRg_aInCcoNc~9T|xGvK_L+xy_r(v>JFx!%pTJE!)7)tPy z4)^4X3qK5RAct+8vaNbYP(io0Ycsx)=A-1ymclX<=^=L-tt2Hi;1+!9oDhc?4WzUZ zudi%^|JZ714e=Tnhdu=^YOCA3++48uF7U$H($l?%uK`o3T&$l+wTQOm)2cahT>DIx zbjRy#P_MMMWb}CV%c5kI=4S1}8@-&W$WqR%jiw99 zxLZV|qwePw7wvj989CSuCZF$!yCXhtc1=G`zCvyjojTx{?zS8)mDAh7VW<>*F_t8^ z_@2v_uC7YXaQ4?Uix+)!$}1alT($?%Z08|iZN5rW)Hv;sS=={X zlfj*rp*Eq4ta0+R*fEVPIF8Ir{B zuFX`cF{Fv!)vI4G`eDY?EI{cIfZMG)9&Sc^Bi|&{ZK6`R`Qe0zzm3hq{vT|)tzMo% zPcKeA`JW+Uc@Qc`O_JFlPp?;0K^VpK%qnx{%t9q2yD_C+d4wdI#7-&g_MN-=Pb+Z> znV#7m&5T7qVSX{*O=1ardy)DAg)`66EKHj+i^sOiLRDy}Cs)dtSYEtQdU&_~q1`d- zW--NEH>F6TmWeB*s|zzR8A|JXTv!G|NB@~Jmaj$>yc^HRn~Ijs(R-_u_!9+vVXZ}u z-|Wy`iy`~{#%hnu#c{jv&!#-D?J{_bJzK&o{@78y)70l*PK0OzBzRXyKY=5i7UqJ2ZM5N)hxWxDa0q9C70jKySLPR%-X}$+V)jIbcvHQ-i%0N z@_3f6h{@MAPOIKLw2U#*jKEbkV7A*SU+x&Uwz6?%rm3-(f(x}6*5dnOFpV|s-c$X( zMm|lN<%OF!uP>$^ZkINt*9O;++>?c9qo9fX^iga*Y)l_%9-@jiY(|;;nm3+~>`2s) zap}MQat(%N`xjQT?cW_7p(iV^@a$WY`D`$Ko|snEN%f^XTe+;CbX`OaT_fmKyLQ(l zU*ok2Ctd$Po<&-6(kBtmlg8`EoRjvf93A#nKMq~x;pySh?;p0{Nvh@L+gGHWy&EON z`aL>67UdLLH1;AZ_9@{bC`R(`&L(1SN(oCsgCon?xPWT)LRM6v9BJz%GOTPjF&UXHC(JbBlAQ z7GjOYvhiobDJ`p2XHBIU3ds_O*_(TGqmc_dcjtk`BvM#(NvfIPPoRKulO;6IHnRtq;q@)c)Vh%*v1jpNtJ zGDZMH0RLwQ9-1m%cMkx^!KB|#kMGE{ZQ+4b_ATOTxZRvo3@QRhx6Kh=M>W z^J3!s-mB|lp%+9=HZc9v1J}G;>$!EG1s8U`kJ(NI7ehB{J^N$DI&OJAdKto$TK16{ z5>DHz`4GlvQ;pSwiTKR^e$>HP=*GkZviK8ZGi+)jep#F9?&xc`XyOPm(ByhOB|f;f z*J$@weVH^uELm_e(S1~rS9VDEW-sE5SyPENrR5~*Y+W021s~ElG~Luu%e*-@y(XmW zhZ#BG4|;1qr!6vuyv;F)%PvY=mrLk(L_ud|CQfEfDdq#al(SBMwRi>3 z(a@;<_R=(PES56k$hInh#L?~Ku07__>w^KXuKrdc7pS3Mz!)|CmXbu`Yv$9fN*z0% zx8vrwA8k5AH|~z$H=%Aw3`!c15;>J!O+QI|GHSb2ZxF%J3M=^4KM3M$Rs9HTr87OE zw$*_>j4-~veC0qxC?YMX@VU%_?N})9GADp`R~$f9C}~V;21t_5)(e6}5N7P@!gMSW z^8j>Ag%Ljv&+2e&83f(Q36WOZ1EW;I@LW7!wgaC5y^GKWnA1n-l)%JzVg090-U-#9 zE^ZF=^n^b#0Ci#R-uzV&WB2X5?6(WM&v|LXsSyy1>p>428tV-c^(`AB6WYE{V$In{ z-L>Hq=36E(Mgw|+dyA6g9J(FuR_}My$>q!UH*qDMXva~@3gh4I)cw|MEwbLD zRvnT?Mk3PU6I!@8CZW~t)muyjoC6?;6(UH-fs|jR2ZMlUIU>2vep%6E^hy}=lB8`- z6gKz9qcEFu&@B8FLAZU896&6}G!5ciX+>>X80RH&mL=NKF=2 zZDi}z>6UoSO$22o8mg!EKH9gn>RuppsK)!+%BoZPIZ0#dWi!*I!G9xMR(9akHMI%` zu+1ScZdlL*;mWzzx2HR zd_LU3UeTv>ec83{Ljdq`0uGB`I!5iy?CJ_%oFZzNqgom1hfJ#%Ot_RYPA6Q-Dj$g$bs#d)a^XD-3Z%fctXFB7+z zHKLeS`)q+a-m!PcBa~pHg;%SM7d$XObY(LmCj40jzC;XYJzDxeY{|D-Al|#;nviJG z!--JMA_wB|IZtY28IZkrEBAgmmO*3lS?(T&A5#R(i_jny?6gj_uyFKTP>h0MZrq5| z_I&I_GJhd2Syqs5aWr`+#?&RR<5GD|7-^{D2E?(*aS13;$)@?Gd5^YPiw{aLQja_d zoXjs3XDiq?$*lyx0eoiD=^!xT-NiHp&ys+}%%AZRW>)t!x+1Zr$)mfI_Q071 z#<`%8`CmegS3$x6Mm<#KQW50TGjAH1RljR$x7?Zxj{&|X%pGA)4~4|qTKUe-xT{<> z>l|y&Rb(u4r`a?}2&-dfv{pOpHdk-rCfJ5LO(zI?YvyRw?~!KSfYA<0Y~uw1zZ=nd zK^&$i1|(pBtVDc zac(a{_$9pG#0{^FEX2Ase{_Orry6`zgxI3i8+%OZzxG;yqBP;6Y`k-1q0)TdHmP=XrJfBHWxxlVpK2)IT^yEU3bzni~g^ic7 zaZMuavAlehGUbsF;RKUXrk8gsV^hXopFUR4wg131qhiBmY}(GFx`#P30_-{)8zZCBAk+v0kpkTz13Z9FLudo$RHj&B8U(U>2 zk6~<>*kK1Kpg0coll1z*Pq6xOm1qtJQ`J*U0iI%p)s2y*=8TK3CCWc*q&DngPDtZb zfTyp~mrSNH%wJ=_xF`*>7?=t?f{epI$+5a+#;6-Qzo`~6)^mosN(q&*+B$x3GTXVa zAc4*&r)`P#uIINFX`iffD)4ZKoWHjD_%ZgW+b+g7VOdqx*l@Iz5Iv)Xbdz3OP3t0q zUQzBwt?ltsH^ZLOQyleX!%^AS8woQ#8B6+PpTg8eKxP`!O znR@lfK2^&2%^4~UlZ;XhNutk%sR*pKleQfa8y*>l;iRz-xK?=DJE#OQ+-{Wd<7ZIS zT8^ebca5pVpGz|?@%p0bwk|h+(FOMO%raUSW~zytn}o)-wi2?`UXA;JnkMGFmb{y4 z^y3(Q(#=s3JT6UFDO9sQVYK)tAAj1=%6GR!kCzc&yEG z_>Kj~phe`*WLajL?sWO!n?KIza5;?+EzhjyA7^z4egkR2EkhYbZ%;6o> zASKGa!45QP9A46dBww0$mAN1dDIoTsPZh~zqPI$Stp=HO!JbP6MQQ5SvFT~*hpIbw z#a_8oxy0ug6HN1VFF9HO7xfe8c2cAY6Y6@>z0^?)I#edKQ5C15xI7%sFX7@`L%TMT zUY1^z)X=`LkM?CL8ZK=Pa8fLTB9U;$jB7l0MyYdp4xkW_uG~&6}t(t6|S-h+~7jy+H1X z>!yf!7)Y*GJ`B{l$m#~4UM!fX25OLOt#^H*9T+@)!StL1sA&;om!e}~TSFsBFFd_F zGCX46Bvb!ccxK~|=ky9^I%L-W__!*nXZcQgkCe-ucdONRC39Y4;mTn%u1QVCh=%f` z;M@VhaX%5QVNBK5s!x22la^S^3zIwPHcZ?PSnr{F0Bss}T`}bPACBuPFshw-^jLEQ zTxvD<88UUot!A^omZ;w~q7Hz4yw3(@m`x}}Ek?A1T{(S@{JZCrNpPDHrbB5WHakAu zN~ydJ-6GrKgGQcP>xVTtZX{5aI6G(0)VFbQ%z46P@S!BqtQ(iq4rA1yvTu`2*V$Jw zX^$4l=%!P{v^wqurv4pvu#kBIqgz$Y(E{U(ov0m_Z1_IuR(T&-bt~}!(HaA1O8w_@ zTG8m_6v+&7u#5SP*Y%>?sfr42H1Afzj+#%#LH+Y#PcP3?C~!)xp<(jGr9-$VWGAb7 zar*M?j8UE@Nxf|{SAfx z601jQ8Nl6npF9zs8OdsB@3%=X9igVCj1>}Hn~e7T6$3Y>c}6?YY>E+w#w~4pU9dGaDF_8?q~#izHBrpu_TF5IkAI89Ym_3$ zW44+TK1b)caB|gQm|TUVH$=y*4k+5{iVv-CkTIjIMOaZ^*$hgx*cF=PhB+3>hAF0a zA!@CLQG&u8E0gW6TM<@R&X{LpuM3GJ_dtqH%)|OOBm0wer|~jOy`t-4Ut3)CGADAA zt3aH-9_Hbj497&{VKgA>1|LUV;{Y4C&9H`-;kNQ1R4d(vgHoy}Vm`tHaGezAL~aYD z^rY>lca@eT*ftWnh4Hwa@E%7w_g-r#(q%^SGKQ|pq ztC=e)hN>t9h8+)5nw3{}h%g;0?xhOr`K-uA0y(&Zvl|Y1v|uHCHAJS0f8gk%p!_ z^~LEVMRY&y$qAIP&Q73^tJC|sj|}#e?};)qrn|fJLEYO~I`pYS)EJ3-ww`0hy3KnV zDNYZT>=iBRtnCR=xl(Ui8B*fgIZe%R>ydWjQt|9b78k!y#f?`Bd6gfp=WM;j&xpygyu#i4#=KzpW>EQo9MM zXxb|^5H~6XWjKqL#CVEQDQv^+LZbwGJU{WZ*fd9F*tvMb4L?qE;Fv~yd6c>PSX1D@ zlVRN9cSzOn!9q@nQKAE#=YFU`sBX6S7~EjZ(wpar1MSYGf`M%sq{e&@Mi!R7P2I>T zYIM|8aOWbS8$y;SC8ekiC#mqk$-2gPafeBK!zVj2*qyV5=augAke#&zKhJRfm*<6d zlaKfMl;pHl6nj=isMy-#&4Juepy9F&9KuFbFoMrmfLx*1eL++E;mX`=K6FUffdu+7ME_;^#u6EV1ZR? zClpDgaWC$jwYT?9m4DDeYh<%7OTZJyI`|?vuEEgAEqb14K;X@@U zS0?sBfQF`)s5o*S$q5ok>$KZ@5Kzj?v*N`)6gE0r%hM zKOBj)bLV-wxH4H{N*7S1el7#nb5G`RySo7p0Wc3&11zfz5M4-OI;D56yh_gS%@Wt3 zI0b8p==(c`ZvzWi2%i)h7AokO?5V^#qmcvFqpd;tQ<*}=S7lg_Q_N4yEMEIVnVz(n zq!xOI-8XYH5|~@A@66W3ew1D2dIbrRSXK7emV}?8Xnki4g8(^^JFx)m^M`s<;Fmyep1PLgteu3Ocb&o7DoQK_N z=Oag&La}q*K7Hg=^`HP6YZBpPbvUmkpD9VD>C&>UtHYmF65ba~o7!=y$J;&=(U5%S z{N3xWcZ23hf?Peg@SZ$A?xuLPp8u0KLi3y;F|v8Ox7$A&Q;hh4DYcQ@A7lL1L*&)e z*2bJFAR8XE8|4SpoTg|)eL-J-91K)*IF~lRCUUyI4xO!Dewg~QRa1}>(LN1dc!5#vWCTGDW_UYH@G0}oZIu%H zy`yaP@BHywB05*$m8w28VrD65ej4jhAsEUDb@p^c-XdEoD9HWBXC=gj<&-9dWNuQ? z%2I7W&)oU8mn+!VmS8=fb3R_^f2YHEGOa zVzpvqD5q1}EOvQq8LyK2E=JCpxfa@-uV1dI0Ca05(59CM>$7h-*>LK%+y>w1d-BIXo~Oi8gBp6k+9%tb37e%%)^FqDiJiC&<)mm* zfp^5$zW2nE^5lg%Yy~$@ck+R@t8h@(!^~v7nD!sW_ijAlCK`knI?+)-JN(ZRSO3*>XFqL8Kf}W3ZI;3~Xg*H$D6e z$d&p}E&POOrM`Ry5p~VQ3M!tc%31!$wZ+h`bocw;}{3|8{&!zkBCgay0 z4)(I<922?@gXmh2#(70K=ZuU&0xUe>;TNu~5d6B82Fa|PV)d>0qGwYZc8f0ik^Z5c z>#|Q5xq2|cZ^a5gp3kpSMWkOEe|hVXQ5sdJ;6qtguaX#(UIF(I&g^?FrdhagXfU}G zt-R0TK$qB$WmnEgYFj)BegCn`gtV|Eav-&4?7$GH-4WZrIFzT#fu{s(tK057c+g+4RA=>Xwy?DzxSjpz5BThcwh_o;t27%Ge%$WeEGMm-1y@jN!s>K1MM{$=)^=4UDg%ktQc|^O z;zw9sKFktG4RyIjCk#oePRPU}h8#|8o~S@cBSoa)gAY=p(vceT28qU>P1K;Of<(Y*+dTN0{nvP>!~ZYohSYe(SOr1ORV*LiAG~mdWL*^vp;ns z889TkzR~jmv6l_crLkMZH0^e&9oEA$`PPEiouuSp_m`#sg!c4SnK37@sEXIlH4*Zp zHm?Zfq~qK4@U?o#M|r8*qB((A>MIr*eQm*RM$#Af$0?F;9!PF;V4hP_pD4DCos#>y z(2K;xQlB^9uhN|PML^B%rT35lgS={fN8KE5&51R2t92)Qf$t)VvJtCAD7NDpz24~P zITQp=D9nk}K(vvZ($GB0+Q-SlLS!5qT)qeQhF8?b)7|Z|geAWDj8-|nwwwdIE!!B> z{c&eOw1oKqZ56KU=y9uv_Ra3NrI0L5+Q23)XQ4qi15Xw+yV(^JNckh z4^MRaD-M(gC=FI<19_hDXI0OWiBVEJ5!i)Gh-IAhsIS-xZn@IFtj}KbSXO#}&`GZ?x?_4bU6U zyv5F(Xhos)^BiVRPIIAE46S!}&TVM#*2+r72+7I#Xu@TnZu9hZzB7N; zh4Oodk$r=roY?N7@2qI&Qg)Lw6UI6RTZA(c-m7}$rtBEI>HsCCc=Qtr(>Ot9RPHRX ze_rbkQm^_xlaw8C7>~Q2Ya8Lgg7~qusup|vd?+SJO+%|U<=th0?A`%&!0v*?@c0l; zZ(HyN#^AF%bXLFM-Df(nifhx)d}uHL!zK(w;5u?|*^zz6yzHbV+T(FQ`DOm@3?U>! zJBXtq{Q5|=4>$Ki!K;EvfbF`TWtB~&qY23j@A@_+`V{Sn%Sau)@Dp;XkjINK?10#GsjUOSs z!H&sql-ukBd4!&{8C*8T_A6Ouh4+q-mSM*>J{?{ERxw$?*;72viX|gPGJ3e>$|oXp z95%`C;@TgAkE>*8x9V!1nnj?*M2H!%Y1;?&HK(^QiC@66IMpOhk=r(HL`DjgEDckV z_zWMd1?QhV_uAn)nuETfXlc5frffuES4(o(-!Fz?qzMYAif|H3q=!mj;yqF>P4VOn z+9>*CkG}qoJv!15^BZkGZptXq4#J0Zf)l;I4b%JdLftV<*WYL1l8ZVApo_ z;3wWNoWfM)f!^r4xF>J5@0X>5x&Y=W9`x@8><=A_yEcx0P=p>{&12s8Q)0?ko?JP$ zRAut2%|~L_+9^kMA1z%rJsQNP39!RxKO>FNijr_a()*ln=%7YKdc=RwSzr0%!4(l1$Qn zJmR6p=+c{faG6%t;jXwnD@^oc>Y#eP34od3Q{mDgg1u{S7}AA z&z3metECB;YtNkHZeIZxLPT&kY^qN`LWVOBR|lU8vBU5-Ztpn8+j;C_5Bj^R`BiT9 z9&*@ovCiX5!F-HL4+HbhFG0H=J)+e;l_lkbA!j~q#b&P(X0AUk@Xw4rK78dgBbZ(a zvvvi)vvZ59Qp<)lsO{FsmQ5H#nJsKHZuHDmyoub%shB=PXko#- zseO+ae8eV;38I>V7NokmQ!x-v@edD|M%T7y$jLV&N~0hmSf?ZUK^vW}XqW4>#&aBt zO`!;`m0QKjDK2xe@BWYP$Y)~XIb5P$S_I0f<#)Q88fO0yV ztANAZ#mJiB{wKTx8?YmUEO+`*&U`mMNt}pxmZ4Wu!hqLpXwQKV0$fO|!P}nJi<#V= zUkSco)WsGM`Ye^|(Se?$t%ynJAAR$h`64J{aL-uzljXku%8YjuE4uuPy7u;3tIP`) z!u2KZ2e-`g8TSC+w^F!Gv>!$4UBO>s`ye2u)Mabr!;8$eQk@>9+DK`G%0tN;Bj7h< z;+TLk%c%193%Qqv&!raXt*iZFG-i&g=$1oVB=%enLriSUp}FPgs35nuZG=Kc?#Z9HbHBwr)%<0xo>ti#!yWq$v9Z%5oX7s3 z)oOkx(6dY4d{@Fx)L`gC4*4-yNkxrV#ZlCK$*MHL4(7=qsZoTWf7=CpEa&(mcAkorT^zKdeDH@kT*=AT zd`aVyKS%Fq zQOVF?2~oE;<|sSux;r}yi=0u>?!&WT05we206{N)zH>HW@hx<6;Fj!y-ii8Lyn6i=lZ?Yf^n4k1$I>i@CM9IlJot-C-ZzH7O z^{e{l_Q~nky!S@K_ohJuHf0+wI)q_UuT*%3el(XD-VTA6+y7H{Z$l0G{S&)iYuP$b+@OauL{>G=WuzBp>P z{g1aHec%sLD!V!Q0lC~UqVuj;G|A~!xfb_29zC*RMqBiGsAc4LT;mwMBk^)IJ1NQ~ zU16T`CY#s59(Lnv z_4FMUajROqW%2JRmH&9(d=bE4`z6u*^hiIQKe&ODZqN{MxJFN|g!`}~`G!Q@5s=Gn zEEFcoQtmONRgnYwYHZo+ZkU*{J#>HSC4MN0IA@k}KDX*v#XQD)ya{+p;0 z^37H@FaRG<|ITLdQg521xVF(tAYr}`g=Tcg>$Nia@rsb!a14cWbHWGoiu3s2-Ct!Z zdPy^TszDe`fYH&1gw{#3asVPl{9x_~;6iyAN+Z1&g@kp-P|x(>KM3Ae{nM(PHzY2r znsa}baGxQ^X^f@A+R2==uaeeS`&e(7z}V;Sx&nV~6~U6(x~9&83|e3Q@kGZ@=rSuJ z*|O^I#SvPylKJT0gLQ6BI-)dculS$lctrkJhV-cl{}k@w{UNHjB{>wc*JX<%emDvL zp8*a71C-7BNt%_RKZfdF=H3n23i3E~6zx0ojuMc+n~w&dT{%4)H9J1l zUfGp7w|Y0bhcayQO^Cl*7V)pwYdL&x5~D?Y8xFLa3j;vS{xc2Mz%;;XirMCUL$mHk zHETmRiT|fFCVbs@=Y>Viz=L$WE(s2geAh3o8q6hu(J#>Kby0o?1<``Vm?;By`{ z?!#xd_+%2Q@Q(yz0oW6KgW{OFtuMjo-wRO>*=rIYFKWBIjwI|2?)%B^9(`vX5U0>p z@IgA65&^U9o>%c_yP;=|MEFLy8Fg==OwZubIjYFt-Z%Ri>S7@!lG5E@HfZoT$a`8E zuNoS?2~O_rZ7hF<@JaE7{d>aHNPM3!4<&WruYVDq`ujhW1|n6(=wnVAuSbJE9gAzv za^C-2a({hAuio?ju7$tARlCU_5b)pMrszL0{QvI9ZIpb*j?l^N>)gf8Z_inHkJ=ch zEz~w>Fge6!TDPuDR!V{IfUmu1;v;R=b(H(^qbF#iM^|9XJ3iFQ!uJR{rqtB?S}~U3 zz>{;ehr^BFyTs?!j(D1yvKom1(scoA55%|?z@+a9oZWiv+> zik5z$Nx2MKx%C0@NA&bLsvrK(Zp?ahFI4$HebDHxCPw<2GOE-H?6`(^8++7N>@e8y=j(1 zZe7D(TFGuywR>zJtMVKhW)dlNd1a7xMqD4vK}-^UJ9wU!1rLev<=?gLWl{_@>#X|h z;}n}H%f`Cj@{@sgv)^1VFdud0z8ab6Ib~kOe;$E1;a-U7>w|HSq|3UV&HkZ5dUl7dA@t z{#>QKuj@VGpZVj)#L0T5FD9aNg(35LEOW*lcK7A753aU6XR1?Qye1OC%W(l5=uqzR zA#?;4YC_3QT)$Zv8z#1_51nTRo})^cV>z1A&mp_CyKVqg*=?-%{%(pP_9xfS@Fz#~ z?{ev4)qBUy#Dg5fgY5OPT6QP37p-cuo1W{lYH52Nwhh{>?Dz|sWlODldMn3h{64=- zi;J{fK79KSk5le4$jT0{dXXk@6NVQzBx=AB9o?oh8r!G*EXj?p7U(#f^s#49W-oMm za?YeBz0?+84`@tF95#M_A;*wAV^aJp8h4ZXGO`(Xf`#~%oY5J2$HOFFf~q7%X+!I| zR@cCTm9SW=@|~25A3t|^Pc>&y(CMw=$l-FZQu=nE+68c1h1!EOM#Fj2;>t;1h_eWl zySemVE%_QI)?n4`7`|~FB?W_}QL*jg>&fIaZ-`!j@{yie!J-jNSXsj zVvrz9ltEOK-iIGNL8k%oilF_N$MVNiXFD3r5a@EpOfDN*z^S{@f{gUi_Brhtvfi@# zzPbl;+$8Ne(yQ*?6YDR6pM=O3w;a^5Zq{YZ&Zu*Q&?&PI3_N!iIM$!9#X!PTWGs`#3mwlabJv0qxW&golX{{ z4)@g@j9jFMji2+d#(!+)xfRN34QjKQDGS~1L~m1dfge41eBFkZiuTR@jUXV)V31q= z!Q_K)wpg_ti!gHeRK;K7hN$i?Ly=lw@U8O)5P>H`+lVr)`_HByn3yP6W1uf#t6Ntr zp}wzt_yFzI;ds_RLMrPv*&&N=3U2(+*U2UFAYkos+nG!>@3pEJQmiDW#r4`t78wW7 zq2zE_0rsm3m#fE^UxH;;6^caPt`%O)jTD| zUb-L=){fx^ME%`$_8{VSJ2ZnK zHQu66UkMpyzK|*eA=R;r4L&)$Qn6@&ZAZB@@TuLfv)w(%iSW#e%#cs9-e@jCH`**L za#6akEKw64;MaxTsrRee?VJziVio|R`H8h9npO05iwCICx`|!cdj*Fm+=P8yEicwUbJl3RWo`{xV zJeh7K@+=+I!_zj%04ACpz77k$*1Gow|8bOHf6wEcd+!jDnFY?#dT7_#+9-FC2G*SM zsZ8!+V@VrjVxO8vajm01g3aOyevIob{;~MB1y+w~-PWU57JKW~^LbqRU@IjAWVL(L9LT6&2_4P8GavWee0M zidZ7I;XZxHLH)!rp_D^n40NK=fcrvkp1B}%{~aV3SN^y?Wn|$~y%WmT6V*4nx19S* z)vK^jgawH51mP?lskvwE0aqG4hd-YWLc`<_Q;br~S=7p!NfE zPSzVxgXzJ}!fYS)DJX8MhYyrQ9%=`2fEnl8QMLkeZ3aEIWC`%wg@n+%%!A$b`yN0= z@=hs9$G4^6Ty7W~?#=8w;dzL@rOi<1^97U4F?U%@^m?Ex_4-ZR7JlQFmdEi*&>)6pLa-H1#qgX-CkoMNx^jLf_5~(*6NlV*3 z$L)Blf=WG#6KommD4JDU`~iEn-Qu$~D<6>8OyLsCOL!PT<;%cJ2uW<6Ep>M3shK-P zH%Ohj#IrrSw(dd7J9kiw$TcJO+Cz(FEn(intg6|9^jFK~8B6JsX_@2@DXG)W{gcur zg+s+8BjPMr5@(08r%^3oo;HHNE$gds0%w~=82^^S(GJR|03n=f4;gf?{mR|OWj{i@ z;?+FGFF`)2lJxdjlAM0p@E-jic0Gwbd#9ACpfXl|wpl?>cl6~hPD?r=>Q{XfGJ~+04mRZuDsV&#p0Gfp~DcNhRgs_?FdtjdPVT(cAL29 z!qTKx->}CM&Fi*R(pUVKUp(EsVQsUgmk+WfzW2skX%J#2Fo#VRgpO7`8+e~l!$>st z2ZrB%Q7M5OUeD>KSN05PE4cqBQzY%{0fx!u8=~_{Ta182-#2D+tUaTz-!p5))kSh5 zG!4*WcwY+g7OS(Gy^?!npGWzE(x7>YOlWcPOkZm~W71M-s3K120vr1$nB+A*sqG6} z%~z`Y9ES-ycGdUE=5&Ixv^R=IJ4DQMFh4A=;{SY_y0l@Wzu*5qR493&jny!%hs3J}t4(qS$}6Ud)WOPzPb)yjmmfYL(<-nJxlgHZ^2 zzT#nc>Zxo{-qaR8)|>i)zDR>MsnhS`X5_Um9@%`{e1`re#EOD4#q{OFwRKLt?h2M> zg?!vsXxxM=;07892Vq;>%agsyHDB|mQNJk-dQ^O85PE4H%h;tQU}pilQ;&wd0roHN zBU)3U<(YUfBm6N+SsyEn3B)VhGXZOkeBwIJnLQk2k5e8-5V z<;6j6LRRYrb-(gX<4EzlGZ)qK){d$w;$uTijq|!MJFIWo#QQf3MLn~Yr;uU+Iii#X zaB7ZW%7nShlAlLu8ZnEvSJ{wlo%)xsFm7PE%+3zBE)k2(k3j@7`;;eX$N{8VZsZaM%1&FIe37ZqQ zw~B|)=Mp846WH6hTt^;0!{TA_(-F$^2%?jhCLp};H$`(tat^oPFq%d~E6!xzOry^t8U*8@+RSvA~*)Ui;q516K{cUY$^Oia4z_(b~)iM=}FG+qmb4B1$cf}*d4ZQZ> zKyr143AU?;Fj^W)io4NXMYJG?*vXMdQfS(x|DBtwtdR>SU^~!%x+P7adipmWpF2ix ztVhdWLrwlx3-Zf?{sCoSXyrnWk|KQ~ryQA&nWogfnP;>cE-cXiDur|fF{T%@sV(8s zmyR6xY`IFtgm#SWdRONnUfCQ@!$V^@^j-TKGulhT-)OchVSh+KHhr_P2QRW1i~@Ty zXvoe}67feM-TOX;h#KW81yV*pBxT9GEpmUhU9X%6pZCnv9ISU;*dl)TZy)^ZjU2j6 zo$0BQqJP-E;=JxlxABHC^^WbHFvGcuSb|`7IBW1-rB+hJWp|_h7*{u0it`WEc~avq z@fQ$M7v&6tm#Y{U@e`{H6J9Ju+Kx-Qcui8yA5Nle$!Kd#Sao@r1!LvNo?Q2QPD2t| zFdW~!YR(9YhUPv*iG z0Q78O%9F$NKBN`_i~K__{JMf1qX05K|`NXWfNV8 zq;g4_#6Oyvr}A37`>Q9J$)$f5-e0k_=OYlwzy>7;eCY64xW)noaOg@32LKb*sph6y zHGZ7Kf8$^f#e+Ggkm?!U9tL}QXwOX34E|&p(Koe`TZ#XQ|LUI}JA(G==E}3h@bK3D zho~%*#Mk@#8m{QyR5jTA*<$+=stP0BdsiyDB8=!}f9+Si-c+wVSAvNS4ELe%T+^lr zQDmp>?d5YH`7sS`51J&7za3x14wu*k7BchS2F1&xeOT-pN^YDml}^`3I(m#BdQy@` z)wPN+D!vkl$MjPV)-%}nL-0$mK_QDH_-Vs@lw2DCe+^XM7k2QDk3$biZ zN&DjqPQCf#1ulgn6JX0WVH(Y6K5$j`pk;BE)gjLDv-S{SUy@{)nvO#x0c+eR>Vu=l zd~V*IO}pjh2+S#0W^z&DU2oBR`@M@OFY(?nplpYTYyH%Qynv`}Po4HMKD~R1sPsYR7OBknx`IDKU7>MB19;3zVE-lnXf$?hv?8EF_ zid3zS)L*o_b~F^!tzFALe&<-*P8QM_?d+A$SwGySQ)33kl~y@>te=#@b*Vprx=JFngq*>&?tf6u`J z%$J=_jgRxE-+`OMJLWUFa)uFS=}Ij|d+)Mrcijt1&-WZ_7WTxq_pS%3rXx$~^$en{ zMICo07gm0yG`4a!cDzS>Wv6z!Yf=uTbpk61*uCpMa9@|2MAbr3M^)Rh(Vr?l=b4J* zXsA8!>gedeQb9Ue?9q`XeP$mRsw(_{L)~7`ehR>+S}2n>hy<{%AZOzv+ZSHw^Af)C z_t17pqEGi?j}U1YDdrZDw))WlquQ+ygJW=jq^I9NRDHeLmll|1u@R*`OcmT)y|*9*%f%dikNfZXeruMJ4%!&I^W0z z>rpRGClUVA|AS~Xg)z+y(%oqq0BO)=6%JQMk@?EJqEDR5zXocIU7TAePbgh998w?L zf78e2G6VmxywUo@G`JbjbjAv#`&PI%;s*xR{K=U%1zDOJ{mDJ{04mCHaX|j>xz6r6 zd$xUc53Dh&T6yqk-5vq?%l)mn1n1EEtZm*z!_}QD0^r;VO`z_yez~X{=3CO!9+oUJ9MoBt#s6>(l`mAZ49fjUqrS0Ew$@Q=;Caf;o> zv7MMwK&N9XH9*Y-Rqxn0_*w2#+40+55)(5HWTIM?$CvaTFp9hL99Frfy?tf7GekLw zD;{k)1|<$qukYnRJDA(PT-g!bRyTXqH-9mb*L1ds+>kWc&;Q>r(6*`OuG{B+g|D^P z9xy)A8Jljog-V@{>WGYQ>OcoH(Mxmq-4`B?&sAy#eWIeKu;Shb6;PgNjo{r!x9uWHvH%>(G0It9mOss!eaKzI?uK;q%_*uk{~91Y=Z|7H=C) z5_<aE3Z@fcSYWT%K-fSQ2 zX!b4zrq-m9T%ZGY6!{N9^B3lqUGe-c)Axt(<6Hhm3IApPPO1M9M*pAx=$zFZEyPZo zIBZZ%c(^rQ<*675K#;13!6b2M25B6`iFLB8&tafV2=JZQW%dnv;%(SP7>gN53? ze1G}TiBkdHeavj75%iqcYYN~!tvxOF z25p-9^4VWr>q-M?!;%aZcWeg5Zq2DP^Bg3Q!Ia}d^C(jhMf*TMW*@)9t1n(~DkXRVuyUQytE zf`q^DGN%0T{%KJde17MY`am(Yz{8>ulE#YGG`%7E2O4hD8uWYT78JLp2P3xztD|L? zAucbjyhYPXh-0Yz{r?a4-ZQGHuX`5-QBWz0fGAZ%6A+M&RFwcqReA^Mz4t02T|m0D zfK=(dgc77l38D8EdJR2<7T|1t@B9AmId_bEznpWv{rSLP5cX#6wbzlIzVXhF4(VSUT$vS)6kGh63|(EB34@dT<{0pLcVPgS zYbM|}Tk!r(?(RJ0T{_~^S___M>K7Ly%Q{4Lf^0bPu5{OnhWnWlTG>Kw9xk{;gZh(# z33Cn?(zr$N7L7P-J%||W%|N;3W3tzI$s3qr@*m{BMHAP>$eG_gj{rve-rtR*DQDae zqPv|H?ewBl=slN0^~~X?q7siY{!J6==0ilh)dOS$BostkGc6i-OirvV0oX3v#I`OTvz1s z%2)h^>du#jX786o;Xm`{0e*Z#8IljN!p@2N`y%U3dm}HoF5X?4nN=g1gve8VTuuH7 z$eVqO!4^FY^@iq19>y_B)}gnIpsX{?6zmod<@A*$);q1?S2DZYL@%;8n=K}j*2}b3`4g%fQ%TqNDkh+Qm2|u7PF(3BD<#_ zYpWkbN+i-+*~dR;ofnj0K>?$B`q3Q|*)o#fF0SxZ6DeSml9#+YQ-IUvC?qhn_ixyh zU2}b`Qh~QY>CU(9G3-}o;cC6$oO4CstmRv_C1EcgCTkFwe?~2~^6(1=wV@*=fKp=& zJ#Gz)$-nUB$I*mCLSlD_Z^ahd5P|I@B{bz%awJ8_--lm}Eml09ntZN@Gu`_0W8O|tvDDUX}GfCy9MWg%ztjUDDTSM`iNQsn; zSbd_cM;(7LS?j}#wUM`Cw>Hx~_$9d-Ouo3Elp-?4j=> zg)O}8>HWesMM{r++21C5UGRguecYLrHIS8X3u5@`Ul|_SJT%Dm^A!RGb-S(#z>IvT zs<$kBHpL&8u5+7_L!vr3YU@_pnNwx=r{sz0^rcdE(9B-Z5&;J&i^-x8y9GpGH|y71 zp<>PQ2KB&AX2XQvO9f1nxxq>Im!|Bp%$~C^%)sHx_jCfTUkOexjX1b|8d%{@)a`m) zL`YpyGI588()fVJkmxTyvF0{91-{SMwE|!sQQ*@mnZxi>r=r|4wL)vzA&%nPW!NH zBVQxKyOZdgtp=V0q!DO6Jx0J)`^r*H_lk1*mIy7+kNSu3m2b7`T%mX`j;&Rn987ky zCTfn>3T(DL5q(N$kZZGGVt*^#I#o{Eky46N+~rPr>9G2mV2rCCyALa$eRmNW8>a?F zF>w-^I=zEuyuz)RpTN8uoX8{>R8Yv`vvuu-dYmFEI^{|Cb|R_O^UaHtSAIJH@`*WD zsZild?qE97A!UBn7B&^H0jyP6if=f-(ujASCZXbI6a|^U5pT1SZn*ig>JMakwsSce z@4yT85}c;*Y89|7as5yJAW9K%w)>MQ-u8F}s$NYBrdMWnzRU9@2Rb?>m6S){*U(@K zk+&+Ow~3)a=e9fi9r=(B8LU@QvH3FPx=?%CmOI4xzrDptp2f*3Rv={EN2orh?GYOg z;H==kVE+lQjo8b>@d!zlo13uAbw!X67#GBolVwPcq z82QI;syy-T{D!~+XW=H%E?t62hVI5Q(3de-uG~rnHpX8=xXC-McTR!B)y=Y4VRtv5 zMVK5%-5aYj+L%$}qm}B!KDRRtb7l15F|u)vxC!5gtb7pGhxn{F7+TldR6CDO^I?o+ zir;U(GIEO747Pa^`H%16RCD;9Y&F`al>fHQ?^9K+YlI!k4DA=h+t+=qd)KV-3xyFX zc{0WDYD9|L7Nu~|6SWrdb-%t&%i1ZrQ(h%bwIPLSWj^lLe(o3jh|@4w{qx3J!5*pT zUYzeAMo#bc1K>Pgmd#D-IoA@yI^HC|mu$rG=FXy{(r0Il=+*ao`7!)Yyut2(kPQdt z|G|(N%9ONrDk{>1kL8fn~)J;XQI zpJF`>-2AOGcRU~kV!2RmYz~{BzpaX_Js)Dv{2kH8%=j$s1EqMHeBRk->(4Jh7?VcO z5Ba>M%}Eu_056c0wTP7rUihv#O6#{Ic9zS+bv0bMNQTg!QRQahsq zLPHL6nW0GMf~>zk{8BMi#XGbS^g-!K z^31Yr^?BEAy9d(9e)}IAo>oW96Ib)8Z~h|>5Q9ed$zVA?4X4fu+hL9&aIm7Za_oGy z8ojq-sZP=Jq)-w@W?K`JzbaZ%MTs$TM1Kjxrw;0}=xbC`G{VEurW;}eDzE~{`+gI7 z3QBHFIR6EoUHuN2Nsd0BRGC|ufA-yZ@x9eE7q$Q^_oLv7j@sW5@5TxPW+V^T&xnXzs)!!2RJ+>DO7R+@AWWSt?I`TSgRHV+gOxQHJEhU2ZBjhh-(U_K~JZV^TpJUqEV zHJ}{<1*zI5+-9JQSXXkX%N}~`*9Y_m#4%L>(3+t(;JXor!@o9zngYeECCcTqi&ye?2rnn)`$C+shHVUHVt5_@Yrc_c-Mr+MN#-4ao)U2O( z1pb|o5h$vqfIwnSAPv&_FQ3L}2s1zWzAe_O@zd@lO(!@CWi_AmY>XC*IZfurZ*eYO zR%K)@Q^vKiaGQAM%r@!8%w-RKI@Qu@H=^AZ7aM#}c4XYkQDpjL?&He+>JkMK*1dwK zT=ze?3;ceC-=H7%eUIOndD1azsO}9pskc#JqbJjM-mdBXsPq-xtP2nCy{YFqHNi`H z1qE(9Hda3(j}{@2eM7~mCXPK!rcr6AReqKFf~@^T*n!xSK&0JvdRi?Ism7}Py>Y!` z>m2?u$9klnc_l`?JpymP6ws-u1cK0$w+bH5+Re%X&>%R4Bv?cQuDKU zw|-db!2(+s7QeVhFv~pz=<3wVw!za>COC&yN$zC>bqIj{;C8#;REC;Sa-ItJ?hU1a z=Eg0bc!4u&JJ+7g5&U)gHXr~`ZrS^_K!vN7$OO>gZ60_3jS``__tE8K{vYphq(Ga{ z-HYY1t^^NT-5x-ch@SbxB!W4oxdn)oEr*+8Z{P_afR3Ysa68HK4(*iUKeHyLL+WSb zzomE)I^e>X34{T(BLBF=fT&mdjdEI7h_ue^hReNB{?=buJ%eo*t>B)P(3z5P#ik<3DOzv z{D#Nhn2)8at8XG!1wFU`5USj0yS>v3H34*KR9K8a#8~kDj7f-Oh*&?B)cc1Cg~q8Z z-sR;P)D`{ab5T@Mj~}W_>8)d0W;4<}+>>`Ulq*SX-rQ6ePdjq%0KboOW$?Vc`i`<069mWFv6En)Ay92iw{6c#*wu% z1!_I-9s$Jwrf29lz7L>)cq&AtC^qO}mhu>Nv+d$ym}WB1jVBg)3rC&6D9+9NvFj%j z0+CA{7q!Pgae{s_B9^MpWuUhrPf~Y=emzRr4NTNhMdcDq`|7yVD8IRzJHF}rSvfEn zSn#oWN9x_#IA0p_{lif%YoAO*3?9@^6jV~YQ%7@L4X)atGJ!A=0y$m;=>I`B=h!Xr ze@7-sMhN)L344p%7ln8zkZ0LHfW87|@psp!?7O(XEJ~ZxE6@%zUbsb#7vret2SZD0 zpHs}j_OSnwuKvSUKi90+|2KK|2Ae^+|Gx;C|6$htAOCRZdSL!Cq*iS&n%@5oj|YLU zP{4hbSHJRAH(1Hsdhz9w{a+eW_Wdl6zbE(el?a!`de9V`MUlUUPSBj)*Nky4i=xb& zudyWY(jQYU7jr4%r5*V2xpwz{`txri}|nqi`BwT|J8p{U54{t<;;QV#arF~ zs(A}spiK+?PZP&CMGXJ+#J#!Af8YGSr{$mJ^xv!H|K=v5xNi%zDE?Pn0G$7u|LDJO z{{LeksW3+td*UI+2J5-hGrDilo^|bu4risz?lrm|6@|?7-cejPEH> zj4(IZy(`}?=cIwgHP`rBQ2eS#*{lqXi}NQiKKX$1-IY`6rQHBoGYbSNgw2@BMLK!w zy~k3l_(5o|PsTQOnmGwD{RS-$UNz!k;+@L~zo!LuT9GVL3*3@cfxv%>_$%0u9{)TX3DGURX`k$a`4| z(6oq}*$#3!Aw$gV!>lG$ncLN1GCj?whYEJpt&k5_O=((W?yDi^LvI!~=Hv6<`MlP5 zcKA(VkZJs&_ZH3{Ja-3+#lIHzi}X-kGya6{Tvz2!00F;!?sA6ip)Y+ZR#JlE?pH6dTnOcAK5aBH20dl&?8BjF~+2OS^Dg%Umma8$>i(bOD`9myU>gB zC7CczZ-x!-%T&0eCzvl8L>UmFkDu5j!57Ojwohg^`XXJ<3gh;Up#ok%PW(eePF~Yo zc**#4`YC&GMQ)F>JpIu1H)H3xUaz!^OA3B1(9Cx+-l-xZEM}L~zUm|~KXQWFA9e33 zyzKFD>RojZf;`dJj+;eH4VhmE(>p_TIS0smFYWs%q@mtnQ+4lHK=$Ta~Xym-gbraPbnlxO2 z-#7hozJWJ~@PX&-hV66U8aiO}ZFrhmZX+%qr+P8Cv~8h*hrERJGvsq#nsa{Qn#+K3 z^PbO!&9jIC&ss6C>erOd<*>OWIOdxPg|Q49CUGVRo*~8-&6OqzXYRmG$8E57=~5#S zec#3X3nw3Po-B*`4(QTczl2zdW?Gh$3DiO-+0#ivM9`*+;75BH;OV+xkVSg%R`V?j z$_Kf@id++toFUmq1{G=VcmF!%1Jlt7K!*E4PbWkz`JIq?biXTk8=KO``S@G2^A_Iafs8HRw&i*IE?!C*iRg*QfRSqs z^1f9kA>A9hlnjCeSA`Sk5)6uu-;d2yw$4musYgg8oza?^iSs!#hpX+B}zi!Mq zAs%Agl0PCmblnSBJK?dJH>zn*B$k{|BHVG0wd4k{H%68wTCX}^gSz>G+g(KXSoS)M zW#?zf6Z!Gl(Ve0jJ3J=hr^1+&=6$ksuV`ck82PT^c1P#+X!^VH-@Yftp1CEt#(R3A z2RU6kPW7{pd4JuMbNjsdJ(VQL=8g~WtWYr}$lYdYg+zNh4!0haidYr(eD9X_&s^BO zEv>)fL#oW&CmC{=N)+e8+ZFwg{By2mN)8<*ueGP%W_;TIW-jiv$Q@vu&Grcr&(P2N zSOvE6?kIi&C1;og{S2t1KZst|X2(jWRg&m@$GTz1lAzazDkmN=43$Oc# ziJQ%c8qmG&Xiw-u&i9JwGi607y!7YK6p=z3n$+|g6=mS_k-FL#twv-%BIS4jHMsJ1 zJG=by8Ckxg>Xl^aw%zNe{vq`#)+5)-wqPSu4LcSyOq>lL3?FbD&wyz5CvtdQ_oJuU z!lf*|l0I)}e?}-GPWp{3r$i=zVuOhT>qlpMAw>D1BUE8Y>W!jKAHnf^mz|pPD`IL|Jvx^7jSi4e4uYiU?Hh%Xp^0jHY=6l)0{L+AqvSrLgMM z3G-F&n~P@*tY3!`(VloU@;5g0W$W*8m+g(6+4%9gi<3O*q#AFGP$;-yF_(D>4ED)) z+p5iVE(=grl+rBgMR{v~xiIx0xWkf!V~o|=jq|sNRN7j1bn32-c*c35jkE2vS1v70 zC?lLwSI=iApJMB+C2jD~uOwl}38M2bJEsRWVUg4i%mqsJ^sAO;J&^uVsLK9m;`&G8 z!1%0kYL#8Qx$sYC^N5mCsm=UW?O&14#y~dv@jhJ@%2>u#bKY2g?_gnt>&!=-{&iWQ zaJwC?Y$QbAhyiA-KO)}8-!8m%Om{@=lhV6>RPf+Z7Ce1xQ35{R*dXLq>7qP{2vjfN z09OUW*hJX*{Jz=!3JWay=uLpX-a^ZUd9vzj&IC+OT%0)5QnfTJlE{S|zK=#*Rb3gN5ibXp7J& z6UYb#(}f-XZ7W2zMFfY2ioY_j&(v+Q2@Q22;M41c#9K?#Jfj{4ebba)eTZGp1-za>eKY$(PE*!tSITfrXenvli$>2(zF>2Y<^ zZEa|tjpjYPPJ`&ztH1bVWniG`a&403q>=LbjJZ8p)nsA8>y4GmQ!nlwx#(OG<#cq!44tw$f2A8qa%X1xksaPNH=v8SXd)i3b z_miQbvtoJryq`j6s{SMQ+oHWBZn-d_;{bbWc3WR--5q3XA(=u+U2B#9l?)q9Z&4FnDya^?eq3W8UNWgKb69PxI{C zuTz%Z+u%#+>T}p0M6ZU@x)&ZFH1_x`^-ew~{WN}-Ic9chkPf+a`@A@_+ICOm^^QFy z=}`28goOS6Hj0+!RG9TPQ{QyYr2yPr^#n$vUqNZ0$N7z?_kLPUwItq%MCs#kql`d^Kn?z*#jW))5W45p3c(9XCf>GPF{y&wxc_H-hI=K zQMNDK%SOX6>J00|q%pPO!9WSNpws#}iS(C6 zJ!VmZk$kQW6jn+{1Opb+iveL%XF-!~MxfMzq&$D=g(jsHAE4JgQtQ4WNnl%wRSPYd~a`N)2ZQlF&WErQi0jozx_ zKZ>~^#H2*RBgPEWWPPay(?N=JCtf+P-kYir2Ep5Vy{b^^KObDCh>a%RiuMt|?mDba zKX%?~g&rG`M;jd3d zy7@{$;iN^(U~=PfY&DutOV8D(@+Grn;aci_iSQ(1VJun2aQIPC*jYusD``yWF(JN! zROea8w>mb1w1M^QwaR7Vc>(V>ex7S80gruv)_XDV*5vM&_1r&||HiXRr3 zsYC?b5`iDqQWwO*In`1oHtv%bfl|Xsrc6f^@h=;8y}hp#7sY>d-t%_0z1mdPdwkL4 zH#j=eENSqPk_|nO(7pN&p<`c4Pm(I7;?GGmHCMp!ah!8XWau4VY1HFrq(obQ8!74b z&h*rP)#-O;(3WOFE&XnqQJ}ctdS&j+_L%G5szU{rsfHN=M`P_k&_r}y9y2qwXMI(w zFcj6&hss0U-WYL37R6MqvBztP7@Q=&UkG@X6sgSVZNrpd;5SE3dW<$X{$q$7&%cwW za^_>p+34`LaX!=u*b=`Vk?x?+9WpN2G~b8$=_JH8@p|fpg$g(Lt#Rnqi)*RmVAFxN zXvob4&4bc_HK(bwgo<`qu&R!f(KM&w^ICTLQ8@!W0Vyy^{2YgoMrbGo?b7+jE_w+x zyq5mEzTJr5M_MhIvNJWRDE11YVL-ks#7Rg-7(|&*msV2zbE&&9J)&497qL>AgscXG zr+vuO>LRb9uO>M_2~ZSsD$LEqHjme2hqSuCM7Su%urc%nvIZepgu>p@1LriJmrfcn zmF;OS{-x)5Sh|JR`KLm(&ElUOB}b~JK#5q78}Tavxv}bE>bo480~sz~hJy{n~6)z4vAH_^RfK_{>R8>Q(rB)U`N|h&Y%!Yi@r*K<%4*E-|*6!+d<|>!t)HbY&5Tx)U_se2)z4c|R zd%-c|diLWcK?JbMiPtMN7}ohnWAIwvA4?se+TeMi?^FHHPnOJs45h(GYS*>=+-4`5 zNCKTs<{BvKSe7@$C?V4QmqSaTrW$6_l}3h7Tf49wkBhI|rMyQTZLK_J>~;DE6Z<)Wr2Htbf8Z6qZ@mY#|p zczSTNOppBXYo5=zB!@JzF7dr9yIs`co`N@U5&wQox*ARL)K$1C1yRaO*%ejPn;SXb z9vr%ImGn|9u+Q(K%5JnOf|}@ifD$Do?0&RpbG8QK`ZP9>OBFUCOqtpYA^$XfBzXns z50FRC<-&5-*9$X1zt6b7eLsBA&_{Ri4y%IqYd4$;VJ8W8a#!hG*D(cU$nb);P8V{s z)m%Z-$pIfjy0t;)YE4`0oA>pEb+lF$izbvov2yv!sVGcvYz6f_;Fx>!yXY`g0QpC& z$m;-D&+5GCZ_glvDT*;JCTrW_{ARES@LqWJ*;jMoDKMwNiGnt`uj;vhPN(4X=3t2)xg*&7jHnJ_~7o&wmK*lTXJ47MQqh1$5IwTxffPVP}ul8)a4t# zqBRJ5D#(3N5g3#|S(dB9KhRXgDf74`@*9_T(S>@@n($(jU|m=`jVvNvpDL-IE^Hk< zeU8sLN^^(yS3q1!C}T_5OSKYD7MTqUNhyB?q)5zh%IQ$mby=X<022+G5Dn14--^P= z`64rq+wKtlo>PUUAm#r1Eh|v5lXmNRlPsgVvB06uSr)W&duS!)x8$$EMFse^3Zs`! zN5M%(8P$V?z1*-ccCt8)bHdMmhjr0{q(fLPB2}3mitJBNDj;aadUnDH=#%fSBZ}ip zG0Ufbzo71r2|E9jXUazUA=mn^Pd;~Oj(z`_GJG=!OdDU zP*^INTf<5kV`C>G*`p0|WM=_E0?lkc$is`baAqvewTa#FU(?*DRR$$*n8%>cza~!} zTS$XNo^DB$ZwA|SChdiXnrZQK6csOQOGr z&TRRe$k9sbZJtAr`@nuSY5<6JwB-$SqUwXm@NAOMEb8mnupjJMz z#n&#X zj4eb42S>Cat+&6%ln_tN8Mh~xilpd!6&_3=#yf)IC}wtPcH#r+7$uP%U;oswqc_e@ zO=0`JnB6~vMUsJ(w=i+$aS|-b)}X?=z4z%v369<9Ny#0q1QEACTP0L{GrB34ccTK; zSRL!E$Vhuut?(}~^RVfIW;o9bFxgmFDR8ac5pfW`;)wg~!?n4iAWAI1KvajMVF9M`LC>{GLg>k;k) zI;f2*_xZpDU(6}0@0_WgzRg)sO88xC%65Bgj<1-6Af=PYmJkm_lT1raU6<7W-XTHX zf<^&An21<3R2GhDQuB3G6Y+LkGnI2*i$#7nK)W{3Z=(oxX)ar)a#J+6?V^Xp#?1Fr zg`ogg{M5gBt^x^v2}SR1_DZmWKh^NLBj)DRu3;MW*i?_YvU%pYAorU5ST#Xv3vF9@ zt)|hIX7F}%-ZuGcX6*rWbcZI6!1><(1%?ngy~c~+Ux8U zX`!=nxv0C@#t!F!xK#>Hg6q&kcxe6{1E?}lRs%xe=Jd_(Xu)X<(j};yzy4;-u^DmsXiml56X%aXYx8$s z|EwZJzly-qA2vA$-eanlKcwJE_KoVAY0g#(azy zLk^p1=|oE5+QJzBBt_9px2FK~Mh!dHD)w`8n8;pI6|P}kLVKXS64uZj(}Z$r*N@bT z$e4FG1U{3JI$9TA$)=?=GGA{`Kf8ZOGq_D&+B_J;liZt95}C&nl!x}%lJ5Y!xO*S0 zd0o_79Nkgc20=SCoVR;WXzXlcn(u^L#j6MIiWRvHYCFYP8^CJPmVBF1NG3MNO<60| zn}!}qKC~c-`=mNDKy+#l(LWC%L_Rr!r~>#oO4mpMI8~9->n|?eWvXlvh?Wv-6zj&a zr={(6mH{n%k-1XfX_qSaR>dslXX1q`VBOEBGp?tdK(Bbu7E!Z;6&-Uc!^g?F+q}zV z7HgZW74Fh_b0Wg7h10Fo9&bO55TE?r9#5O{ zl<>9ObyEbZHh!k7p0%rU0uI_^6tpULi!=!!+zs>Qy&7EE1qKSeWAp~!~0vG+g zKA%@)Fgl%cj<|a6q_?5R9R~|2 zOZOPA{=x}?xGVDdU7e=`RGkt^_;{}v9NV@nC66DW(Qovt^PfP&N@#!TD-UQ^+uzKztd7b(SbAig?8F?7#T=qN#v4EbX_DZjUWd!B=|~LYY5(^ z$~ntwe;-7p_biKOIxkP(=dM00n>w^Qrq&2(soH@b6MfAqg>|))` z0{Y17lT zii}Kb(g^hy?5*8>e`$VeMK)E{RA=4~Vc%1rwJx1E5ZT?lG90OiYTUpI4&~1DOnOuL zO5_|)N_EOYQ4dW5%bPSQqDL8Ii zdeb#JHgj-RM#eCg_g?tW^d(DH2Fclkx%7=4VRtii>qD85_1)SJU4F{&I~O}}M?OEN zg+zuo_Dq=OL&Rb5*E#B|fOW^{M=>=ng)#6$>xilh7BE;skkoHZWh#`nU)ejMte*A3vDU5@9_u~Dn#2h*4*bfj8xW1hdd@UqZt0~>zG zR%$u7d`7ww1;F@9Y@xh&PfW(P@26UyYtL*FrCj^mIFGL>&$L$T_zv}?)6AaLFAm`M zhHoDTNsTKPT-%OSO31WHtb*gO)Au!{x;a5b$z#(JlXl3NVmWUjy|7DAY92jVS#=<6 z0d71pw7S9-(<+H}dhz%_Tmaee*s4AGzk*r=QNo{(QoY}}IeAUVFV;b*Yorbc%ISPh zmS)oFbR%t77WXJ|GILiG^ThRg!`>&gwCuk^rr%}+RYsNr_#b|M3J{BU*>ST#shy83 zNt*-c7sEX01W~wr&@r4sd-2i7`XeQx#}MiYNhsQ?xmUL) zMNB8y>LA>}U3RU7%y@zqG-Cym_CUYW)OT-7keiA$qS+UHms~y8$j>!Q9`pV3kwmWT zR19BxIX#bx1QnNys@j#qqx`z-@2s&A{uBz~-Pa&zxz~{C{Nmv)+8J-vTNvfUt03as1{?<*6l#_NTQ>PHrz6{uDDmi^)^DQ3uf6f+}Nacv8= zr&iVrsL;U5g6&uyr8c#jBnf}c23~6ISTlW%o&$7dw4p;WFtj(L_<*7JHNM*NtINyeLdV}-=231yP zyy~69^(xrO$jk&&KR^B=Lk+bVU9SE*;5nwv?B;88B`rOT_lq}GKU!pze&cbBJUXyo z%OwB(QZpG{cG-0ewC#g3ls`XoMZIVbi|D)tLMHeX(q^$he-kPvBRsbYJ4kgE&^cX& z`ysBH6Z5uZ!Q+n(3hN^C*O|rTMzP0#UsaY&)=O!d5t$nPv3serX>-E-N}{vAGuxj)v2#mm-`A2=5+C(&^!q3uiNJIg zlc`^mRw$kbjy|BSZVxQt_AWQT`7&Oe7}e~`wx8jl2o@0+K5O%8C{F&817U72{2JJb zTNYb`#>!;#B6FxONg<&$yC?2I)Nwu}ulDZM)mg{rdQ}xNR~OT_X5pV%Zc;Ct*~5YG zX^1ELq;v;M8);MX0ou9WHO63%g})bN$ts5B-{&n$AICD!T-#Oe-K*Q~S=3CQO{48) zwQYH12|JVhgk1ZjmdfR#O&PP2#LGV<&wPFWID|QK6aI%WvN>}pHOBcoA1;2;JN;Ro zIo0TwIxnaaR{-1f%d3^i3>zp)?S>0QUh(=;5VZZe8hjfwYlLn*#R^8eCOwkx)_DpQ zn|&?S?rX@~$RlFrR`t{j*CQteF75kw3fCYtrzI^}F2YZkd{Q*rLA%|afH;4}@5%N9 z{m4soQQNiHij(sTWN5B`L_UU6pPs>19ZAXrIvDtCW=E0K*I{lTvf2_$+l0~pIdN6k zn4i1AXES*hGB(LAU4+zN6VlinApYJ@9vpp;8^e`^^=i6Cd0_2$Vurq#%ty|X@1QpJxtXjt zr;=_ZiAR`+d#9Xvx}CaMY^e*!JXGou*t`D;Gt)Pbn2ltV67WjY2{?iNs8d+cw?Sd| zbq~}YC1{I6o99dylktwbRY_Q#OI;8C7 zs~syhUoU*B$j6c;G1qcNUY@Kt*|(OKqN4(eZQ`~^KC7`Lm`z^uj@NOHc)zR8=f%$A z3b|)6DkkJL|FEaC?AyDHVx)Bj^tJcF?8dNIOw__gi-1qTA2-zgg4JLN^zgnVut+Z^TTq=1_1Pr zhKLW%AWG`!6=FaLNF?W;>|C$+#nN`K56fM1kvBXV2;<=*BAAYlgOLuV$DY|$UmKWS zxVl?zoehpEkeZUf#LIi4RqB*Za;~^s4&s#S6Xf(;_#BuZWJ8K1MDei@k>az+0v2!4 z6CS9J1{Z!;wjkUI5ZqOj5g}$De_AWZSBP0lRT`NEfs#Azvo`rJD4bm*GS3XE+7G9G zt&cC8_W}8@E3dR*{yo%4q_J50XC-@zlyFo6zL|0E9y9-=DWjQ>`4$b5wF}n zcFx8uzs&2MV1TYnv=F;z4qMC(xi)-^rCm9wt2>O+2>YFF%uYdH7Cc}D0x255 zN-Q}w!o*-{8RK`Yg|}|-U2iykoT=_Tgd7=S`;xQEc+Y$@`CcKEH8<7Nnmgu zIGz-XRute~thp|nD~}@n=0C9RpHAXNAyXiL*x-pI@%2Tl_fDkg`HZn~7V_y$%p`>V zmJB>P_>l3)F@-^H`$Ei3Gc5G#@ZFr1R%E0{L~GnI@lmGMH2u#0pig1myLf+LHE8%n zgrpt_G(MA{mO6lhE~$Zrx$8gbhqTDxKd{UlP9;!Sese(eb(i|Wucm28fE9}+Oi|^x zV551l6QMjT{>r}vvo~Jkct)F{PE@PfsQ-Hx@2bb1#YeWI;K5(EB>VdR;uC01=i&hu9E6a5nGXayPv_Z=f$Bbgc_{(X2aDfF@~2@t~LH zEkp3vsSEM|MgecCj?dgnj)M3@eQ4akI>Wk}n)zgcWWf|&LL|vX?tCdY9iop|SD`;o z2(7-;=AUSb8dwb*@j9q~RotF9rDjuycNIntABa<+`$cWFw7@nFu|GUX8OzB7fJ@c= z2pfdE!j6XDV&!v?lZB0EmGfPk%sVBD63wd&Bz)U#D~DFiEq0>MSfi%bw&A%Fc09#w z6t9)#P1*Jm@PiSRExI0aI-zFivNhI)r%mL`=oP10ryjuwx!TRO=Wt;Qi_XjYeoe}- zVzIl0?feY&w1z^Fy?0+{43sHmr~^y^DcNmS{C49-K>!-I66|YF)FP@=)$kOu($H_` zN1B|*q)=DOes*ZIb4mRhU?lb0_4+&|)fSczW}KU;$!bc%v3lf+*K$}sTd+yMvHe4f zh?#%8^SxAB)rVKk{*F01;Ewtx&BkR4zo%94K(6Jqwqf`?d@P~%yn>ck9pQO&c5#Ha z1IqHDC&wFC&hU4gCW)>g84)(2+6nR+%z(Vy`=A3>3EMPucO0MktR2FUefr&GXR^DE z-t{`?$x`_5Y_j7A2_eGyzmWt2QwL*8ctKik&PW8fMdl|Z)8m_-hONF z**0sMc-zEbqdiDM5DScqQ%KfqUllyda*3zn}b~Km=O;7cUqqI}{<8xtD2lS%} zD)D)#EG)IXlBODKfAJMl8uB^{s!8D2Z5=*5sRqOZ@u3!YLt7FS<(t+(*3L{sa4P#BtPf#110HSj=sJtSe%Z3v!gDYJrBQ5lsBp*x$j4)UInaH9x0ss9t(26 zHIB=q_^Dyj*Y|njr|Kkt2UP^GGRDg%wEe|5C%Q%NA)?E>gDlZ?6GxtUy3PQpQ%nRP z*AQ(G=r$Dr7*XX>1o+4_NEtB)8{gv}qdlhUsSk?o>!kU=r6jdHQeaMrh^-vG+4wu3@`!3m!!u*ZIVx*af$t(#!+mbaWDKwdwNFqdcY zctJ#v@61*q?Fb;37#Q@M@AVn5_uq}rqdz3pO)i^GF3B#C*h&6sS;W zr-b9kw410u?>OMBqq-%45*LuPEX2e{G!Hv3HRrf7r~M?{MOSE-JU?%`00^nBK1NIe z=r<7kuOarfmXoMPFP*-LB#rsS9vhtfKL<@VIMG=veb=dSWnrFvKfr(}=8wTgFT1U( z9HHYY%3J=CH@}*E4aj2X#CisTSzrSnQtkIMW-kD-!~R5E7)(sSU1PL0pf&Co5_Jm) z=PD79%6Q}yn=WPOqOK=&y%dtUqKI8kuAaaJ<&8XHPz@{|JyVC}w|TnSG@a`^I5?-N z&p2`RLr;N*r(-{)m;v3+LRkmvlsxnL==b)kU(v=D?BYCtvL`c* zA!A_A_36Kr8aR_gC;uD5p1;gaRRaw)Bq7`MDx1xmy~uV&cG06A)};2uNu-3geUhBI z#(8!~15}Lie`dA=k8C(I{zzrOgN8(7KyIjyIU?6w5enRg9c{Y%i^A4e1oCsX0U-Da zVLUng>KgCN6eLFdwvRfgHOc)2tC`I00vNp6C&)1A$4Y);(|bEEd+q=SvwwX}K!kcB zrs{to+G9xk#hko9!=6B(hAVc8L6B6hZ{e2{K(;UX%WO1nwtb|cZ_@Pk*UYas{C6qF!-I0A z9oJ7(k}|-O@pn$P59Ycu5Y0c6mY}MTeXh$aaQt^;(mbNbTdTSS)=*&~Co@VL5T?Ws zGgZ*aa?-#!X&Yw0M)sQ2l(aiL|DX8Ry@}n7Ygf(%*9CL{ZG7?{7W$Fub?!-4*x&xZpd==7?xt#HXlhmV0LE2( z%?YXtVL3lX{$#(Mdh)2sK1lH=T@rlNtGG(=mFSU5bAx3eBe90ZTQ5sYNko2>i`Oh? z2>gaTzBjd4uopWM73^->wcS#%_W#LYo-L*Plh{a`?!^SK(t(}u8en`!yJF7YwbOSF zo9el2N4ap3`r6lD7eM;EbOH58^wh+4uPUm}ivmT?6nkcACNwy)=?KLDBkhNo3vN&V z)`0_5$9MesC5sWHamAj?&qHj*Nl5sb0v@(vN8}Dr(L;*%Bzm@5^yH+G%^pi1fSGWp zp9NUv5qr|x(pkx=&dXfKC&@RjpnVnd(>GtADx+~sesJ0*ElsXVoQmW!yKZFJZO0i( zw~e}#u{h1nbqSn0tC7c69YhSEk41NZ&&YeR0|(Gbk=xFK!8b|+688=G`JE3g&__=y>%Y_Xfwl-_<_a&}Pz{V@YD@fESi z^Iv=?X*WM-MD%Jq?MAAI0laMgy$vN(|1o*v)&J4nd4Dyvb^YFRJct#HGzAd_=@3+^ zL_i^c(t9T$y+?Wnk%I;hI7pLb04Y)e(g}ee0@4#&fY3s(0i-9?yLp~_-{-yeFStLv zdt{7c?6I@5v-aF;%{ljHepg5|>}07B*0O$XA~@`iyuvey!@K*Vsz9wl{{iq!etyvp zC^7hA~Z&2z9;_S=L^=}G*UbBwcABAG-~>p0VF)oOn=}iwLg`k$kcU> z=bO<=4>0_@+dM1h@qmM?LL2$l8jjq3+48o&!n==u@C0h}QHSjv$K5huQJZ(@a0?Gp z>SSTdmyXQbz8(z8mHi4So>Z`&&U?F<2qfKFys>TJ@w5gk@99{;?L|H<&m36SRiMTq z$~<@hkTx%`Zkz3<*^U6H|6Tl%_!>2&<4u$lD&CLyftd80rtG&UxEpGszx>{A`vpBK!5T`n^(n`->{j-LQ^02CNUL zV8Gj)iKFo=GCKFv>@Flf65%xBjq>ZSpOiC3Z!fA0s6_xiE@AYurihC%#4?Tc21Xt# z2E+($pE!>G9Wu#&WY-Kfszd|mv8DTn*yQq)-ThgT)3BD8_lUDB6MI!uQdrtL#(ALQFO||oVT<VB+t>sKh5n17Cw_{& zQg+LI^&%;m#ou<@>oLwCZOZm`z~c%RQQ9T}x7E|_ju#*RMD$t!j~o1=69o0+-W#q3 zrQ_kO(ZfnZ7$#mx?Wb&1+n%DLsw3ZgJnPy_NXqNP`oDE|8Y}B;#TtI+fH_yy{HSwp zH-I=}_@KG)97|SLJKU4cHNQ$G^p`Jm=}XEg0z5l)KA_6tb1q|TVg0*7roCiy?CjvR zz}zajmgPRxTJTx{uc1mC#l6)FNcv@OI{R#gJp2}k*lrB94{o>UQ-o&T5W&s~Z@`Hp zi9sV{jP+=@595LPoo3AfT7dI4g2R34ge|rLRHbifapn|=gVPni0`8dSWuU#- zea%$!TiWX1F^1%T)D#w2bz-81f18G%gG07Uaw99-mO+m~cfGUkqYNRD*43ZIuwG*! zXsx3UTSTa|H)%Y2VJSv9Evt(oK6?%ZueIC6_Q?RF3OC@mROoO)v9m2l#LeZlh};|n@J=g_(UnERz-gAjAA~}(mQiu}3F!POld%u8(p>QCDYuR0qr=0N8UsM)Yti`(;iQB{M=Wq=la|ZFB7K$1oHe zDCyI{vyB5cH~?h>l&zE385{!ZEr#0Hp2{!+uYwIAiE1BxKStj@$O@ zsS-OsM#=-o_DJ8(5MmD8OX=u)3=9PHe}{?)Is6x%`+J+CttOqlY7AJb*^^Df5||A4 zhktgzM|3pDk6rdZeFspz6lj~!1kM&BzWG>njZUL=gK@TQ=w0SmsY-Mi?#5_;;oi?( z4}OJ2lZt0_N+dIc^9(&6H)f<&f%nUH|(;ts}r6A?M10~LP z6-F2Wxe%aEp{%Q@HkDro7#w6#k%+1zrLN-H;s+2GWB16}kyjS!qbZsOD)GS*)s(Hb z1OQz>c(KLjD3Rj2N%_BFaxzz5;jj887YhhzQf@1_sET}?F575cTN#wTRN)$(vX*i4 zYViMqtLHpYh{})zNMQjJxpV~Mr?&Oe6`R6;1g$?PLVM<5UyH?*arrq4u)ry=C(9#% z)$jO{-OiL}-lbMi*I*(7BT!zKQY%&4{X6T!)9r1Z^82`k$t#Lfxe_$iJILmAL%w*%p=fn7kGsF?3e`%$2mWG!*V>TN~s${1=ibAJ92>5GUM@tjbnRXYlp-|9^JxaTyVQPXVbcfZ5- zY#sGJe4P{EdUy1BI{>hjd<`~^w`EZX>$2no`h2I;v5AL3{8cY;`Di0(T93BT`fbFPjCl#t9`r4|34B{pdc z$YI_Pg)*?w1xLR;iI|ExLcFg#w05dgjrn{Q`rr8QLv%V#M+nnU29R9+J-%9>@vIaI zWfxBW>j;mIs@*2Ki@Kh*#{ecmbSo_%%~=Szt05y(Va_oP=;- zDN^V=UPQZq`hy6P$IO39EF5JCReFBok<_CU)vX*#il;bwSXD?n7gVjWi@yGm&71xL)E`Bi(yyEvvKotJ~@vv9JpZE+mX!ZKjxf)b{F99cdUJl)0(LfNsg zD9KSC_3vQ-PmUSn>%AM?J5MX|(pJnfc`9>I_4V^A<(wkpv+cFym%aG(?ejT0fK&j5 zI^SmspZu{?akk;1T5hD&>PW#e(Qk6jO}vHMZ;ENa=tZU&9O`JY z+`Mq%9{LsZh2BG!GoG5}7NkT#U*>jgAyC$aKOSJW25OM$ zjS1`|EuN$z@ITC-KMMEYHHI4Uf|Y5s3R;SZWG4^zlKRE}gKtl)raGrm*UCR40085I zK-0?Q7<0CCzfh0gMhjhpGx#Q*!no8xdz>7tz{lnY@w)GSa`;8lH#CQpyt@BnJ^I@` zt#-!?8;_fj_o`IrHxe0j3c`lnEao##A9(B3jmbEmE}6{BhqEugreWo5>UhAUllxrW zrcR6I)<0Q)h-5ThW1^hNf3jAs5GH!$m|>BIN+#<#Tu-e1m(0w)zo$@qe6}W-M8qh% zKKaUDKskCBv*^KwG-nZMwT%4TO-W9Ian<-pJB|R{{|SMg1%tOey%tLm-IuW}eS#sI zPZZ#RNeCI1XgDPx{t_+E{;uz1Qz-joJ>zk9{GpsuyHbx^2r*gy8(pOPF?RiGYJ4_jw1MD7Q>GYs%+ zZ8#GqQ_~|Arl&{W8a8MBnYPhIZSknV!AOpRuLUxuLQAtzH)v|l8vDkabIX6K;M*!` z;(bWd@lmSkJB{KFb-7orTAiSuz(oxU24i0yJzqw3xd>UXe`=J-Ectdj@Ll%E2=mg0 zxeCWMRZumBHPQBoaLD{=6)1B7NJHxhnroikL~5rVY+;s545!JLOvZUb7Fci=u)6n!fn=rF#kSIY;bfB;PE=cb~KD5<6xhC<`uO~sW@c}}dMWLE8!K!5i77YBO2O9>} z4c=q8NJG!msf+IsHceOALwq?yYGZvLxXJwi&huU|(JxRBG>$|tW~d7oqA3%>cD5vW zF+8M2q2OosMdzk|+Dr9~4`pK*rJG1$FjDh^?0-E4%i|QBe!YRfPfM-erzD zMtRlTpRG7Naw5yu3bk<0+UV@Cu@{zycsxkbfN)xo3&~?(c1 zU!@M4d_E#6R|VNMdk^w8eIq9_qfV=wx-p`IzKUjc_rDWvF4gmoPhHNtld9`Fon;6d zft8}P$9I?wmma7G>(`f@MkQ9)I)Xvkb{2|d4GPuK2r0p8S3!l`>P@u2hZbSx7D%~^ zH>Yufy$_l}N#zP(YEoTfDGsSnU;h%;=q%@0@|{c$GJxvg!NsdO2FbP(+{x=6^yIP* zQ%EKb@Z$n6Ipyk93MoW(g!eR7>#K;OqJ9UI7e#f8`Ib$75D@MoyGXn(uD#{9C!hu3 zgsCwLk^;g>3?mDB`vRcAMVZY=yxqW>rbE{hZvHB8eJm|vn17C1*GId~WmX4%)Ba1n z5+(1rygDu)l$Bg>x>B(&CL$<(L|b&0xo2dDK}ZqLCW@uMy{>~^B~B=C{;7GfoXlb_ zYY*X^9gvnTZt_|ybFl{={+X*Tk=hJ%3$o_h(G$#LVwhdQ+HvzW=frA@Mk^0S`{QEi`ixL@c z`;FxM%f&n;cFrz2u~%^U5kR0$TgflGGtUs3L4LEp*G@3kecM$mw)2_`i|*(9@QICb z>vZ7MWc+tUWkfT<2=bLn2L^6UuH(zRlKh@dcMnI~I`~yRpAwyyH2o~r{T2v+oJGdt z3qH}aUMJ}x6}BFlv9qtI>-P)ah~GYo{djEqJ0=(d^Y*Q3)SDWGXj5<6`}%E1|3d`h zCR5{oygf>aHJ@ru;Lz+jp2%$%@vg;iYK$4Z7M>4b0>vBd#;#^MyP^2QZ>4OU2Dd3+ zYl}8S$8_yRBM_KDVNRWng%LV6h!b5Vv^CFLZ_>n}SmdS!oO@zbKg+S&qdc)@`+?bT zU#<128+Y7b{K2K8P|{4z)Mad-tcS2U$P~{qu9UJ-3esY6$9Sh8q^RxAv_0ZcS&lXO zd@<(1rU?2Wtx!Spip)h@#T0Gv5%pHW%rF${5x3rT>4h(g^;(i*WM+TjxQ}0K(uPn` zjmbz=(GICoI%9y#WIb()*k3bc0OmHWLt3Q4i-)Aw->mHPx~<9*8@3+02y@5S`uV4o z<+HJ`@oIabAo>BK<5F8`V));2cSuQ*k=^~o^wi^UFY*iN{q;7{_4fyvGv#p#`h&DJ zDR0|$6`MAD_8Jf`F>d=tn37nXkTYHovTUviQK?sycjKYWWc_tOohc_dO4NsN$-HZC zXfN7|Wh8GGd~j&aP2j;@IvO{TGxlEH*x!qzR($$d|8?p(i2+;7wW0{pHmQA0o?Hkq zj#SP4N7Y=@5L{Bw&}_ZfT98U6yd*P}0Rv%fL0P_HBJa)7F#g1IVV44uT(}tff8Xqk4P9nC7IS2Qnx#!S8`(Y0 z-E-zS)vd8=b-0UETi;Q}BA{iz66nc26KZyDcC(wj)s11IOJF*VqC1~TO!v4)jb0}$ z#SLTCa`y{vI2V@$(X{iscujb?q5@RB!*!+tzGY)o>K2N#uzwd~e|wEVb_me&I~=zE-alP3 zbWh@HU4s_0w=;u`;ZIsBRbN@(nVQN+KNL}VvzoGXu~%h_&eL&tYo>FqrQ)+Xu5E6_ zx^l#-^N2{X=WVFn-dbxh7(5k(Y{iA!moBy0QgG@@8i9NIfw<$wrqV)U9xP%`Xqyjk z1%EIn{W|E9i;q049V0qdADZEUxAtX#_R!Ru`E7?RIN?Y3BL?!f z$1C`qrK~;TOKFa1SmjB(I9f(VRAfN*<}(B9KS`BUCq2Y}PE8zktNR?9amS2t__jGY zwe}F4ed!ktwR~PU&Y-k(%IgMQJXvsNy5JQit4Fe(ljY|Z!rTBlq3o0d-OEWVYG=XD zU$gKaVvFKjG89ECZU?Ja?(9nsq)4Cl#c4TyWS-TZrW6GT!m?@}_gnMT( z%5B(bO43A#2BeamFkBmPq0MLZVodFTx^7^#j(y$_KkyOJDkh#Kb3ZB{nrkVd*ElJE z73~sJ9Wn-WI)nQ#dt7st^<}HS1>!YalIMu&yZ)8(roAPN{?~%1fBbA02ol_s-+Vs6 zyR`^&Moi?xe>f>i zR*MvtxUsXexn5PS)QTVJk;FmZ9O{gqSGdlFcCD_*{E4I>`2mw?=zt)VP_CO6s5 z#wjL>d-w;bBcRZGB15phYejBOltIZ9!e`-68L6F&P{{4uP*P%p=+ zL(riC_-O8Xf$l>NNGLycP87<@#z`y}6s5j82RgAWE~rt>4m@_Q*%vtGxdUM&+X&&KRvutg9W zX$s$Ftm$>px`M>%1FI|-b#FI572EHP2_yz4wBG>n?hvTU7eS!lxtj9bOR5XQz9F|@ zx-PuW`~89}1yNoJQq%|&{orOW_|dp=wY+09zXXpf+q1vkE3kQ!)hGX&Z z4v)?U*Ej-+pHssMyf>l7R*L&8W$~#D>naln;#uJTz#5WXsR&&kGu*S$d2j~1Q#KDv4RROa;V)GHt(WTfc329B4cWTQ$eR+c@G5sCc-MAYrHNDqpe z=Qu7SX6O(V^2TQV8<-OfSz)KYDVP9^QM=sX7tP3y6SaIP zrYb2K^mj|c$@?B|+`4;9Z>%Ho)>qx55uRtTd?%%%V8L?ha3xzN+Qx%~NY=;1pj87U zXzs{rsPqG3fWS;FjAm^;d-8hlEx>`|)pu#Xe(pwR=*=3$)F)G)+Ok0P9Mul*j>^Ba zV%rK6t{zbTq*+k>)#zaGfEmy|u+z`rM+*KL-oq`;*R*=Z0^^>Be*=KIM7WSKqht9$ zUWMLyrPs6r9Z@y!iIQAjwEu-gk-b@!-vP&HJkyyw4GLM+EUQPg@D_*YE4aJurHM!G zwzM~-Atqwfdh|CSp|)0s<%sUv&rAr`j@Vy114i!!;nUw9a8dDgT|_*UmB|1vx0s&Zc?~&nCoKTrISWZ zt9I4eh+5ySEy+m|~*zy`<`CNY-mnc1Sw|P3d9up;gm;^X9ScPf zcbC4#KUId7aD@+R$T3Ym=blI{eh!5WAn#2rxOq0o=yJ7W&JK($MAe4&k+?X0$i)t} zD34F^@K3RbfXU6ZDS3fmfg#wJ!cJE7Va+WLqd;a;=e+cmSJ0-?lGPQ#K}Th%@x?O3 z$>yNMUS=RtJUYO4x<)SD1$^r-vbUv+qF?TBcTU@P4y>iJRBqwlg(Hbd1Po*dtHUCC zIPX#GnwTrB<5sde$JMsfz;k-5fwGwts-dxOVSj9I?en54yhVW)sRS7?Qeo|W zvmgT@16Re`KK2rCh)LtlPIx=6fWuz2#%{=ua3q@Lv*{r+hC6O!2-_*g6rZBxG&CC} z8POs+JuM&7YW0jU;@^QX;=}R&jv(|faiy^GLoiG7&w^l;^Pn^dh6`X?>DAd%oVs_H zYPd2fvJbeq&;0~M23FV(qpS0FiScqZCmVUB>XR8Y4_;&lzyyq%VTeE?C?jx%HDM*H zn^|h7e6)e9_|L!_Z;b76G}lw43M*HeToy~o1sjb#oy z+tZ!2Px2wF@Y4iRzTp?iTDWHB(_0yz@%B$1vEwxnflq*Hk7lZ>sO+D~?fk6vETf%7#13xPw;&xqHgLDl0y(%^6{K zXz;klVgDe?b-cVXoENK7dKLMUh>o7ow2DQ9IP{tJ)ZoIxWVtz4M3itT?Qd~k=Uc}= zDBs%;#IQ*r-(OW_zfKbfy}I8+obIR|m~QLj{Iun5QuKiMTMq~TStc-)0kp;&bR~yI4$o+6rbqv3kQg1f*`6+T35hFSg@i+Se47r zLSZW`&Az zUBYz(Ugm}>&_wS5pTn|x#JBJ{G_R=$_f+k$%VZ%Gx_$+p-wsR_wsgFP>p?41^X`?$ zafYG+>XphOjW-SMoQCEmufDXL4fnV(l$WUU$)8}eUOmIs zG+e%x`WDcFwtr!%w)~=t{CiJstW|66&TM-GGrbxUM`bkT7%P5rBFsE-d?4-i0z<>r!w)aJ(JRk2{aaw&l_O$+YT0lh zaRMHhJvAV?7=qVwailgCmMbjyeOFzXd{4AqUic%nhPT1)w>ZO-;UNQcG*k?~+}pZ* z52XD?wW-9Vp;^nyA6@>_gyO#3`Pq4)uIsW|FWn~p@IOO5ZQmO*q|A$7@DXG-DJ>>V zRJfDN!lxCnlE!4BE^Zf08buKnJmFqtw?K2dF;T&Z$|YedQ9%?}i6MSKno3czv1~w# z+vUEss^hSxe!f4j?X#-`iv}hIVBXAKj9V1gtm}RhaN}!bMv(^oP0-#K7Plb1sXBAX z10%o+k`y?@$~IAsuO-3n(mb@!x~j7hz24h}1`e2g<|xs7pUjc@28}32z=$-Kw+oIF)k&eKRif&i=Z1l}~$!OSB!8gjDN^IjUFPTsE&P z3V))YTR22-J@fTmrLM<;XsUAT@Z8pkx7VS8)8UYk2+Dkh`bhdTxnNYb2wdERIi5Cw z^92Zs2R|UoS^5asiPnmu-;GP(zI`ekpUSo;+e_@ak(XP3on`%p!>oqYcKBQ0vTWwc zRH_s;h6nX>ZMH!horJaM9iWA;UkoQ?D^qk3F|+sx(G ze;6H)`B4zIRS@F%N(t&Pj!tt*O_3y~2lt!R`LU|w-xudmFGO9HJD+EM;J1)}*AkEj)Zl#Z3ELO1Y_Y5gkjZ}q-qGYXAgC%S;zo>J6 z{klncCX=?qmw-kxOzz%eV~v|s4Q6<>Y8;f+98%#$ZBHmJ7>^q2DiTiU3W-f!X*|1}uWWzp6ua{lzPuw)KS(z0BRW-FYhtjahm^D@YNjG!}qpP!*P4m$X;)xTmBL=iWy7Ia(&eNeip z3Xx)Ny2CEJ@z|R?+8@*Rn*BaEwXUU(uaK>6$p;ZQ zMO|OJ5BsvHJSNtnzaj2SfF#(I=4>hl?+4PZe}H(oC-DfK;jrk8?Nd&OghcjV97~JA zb3gG+Xn|9O%sqBic28&sb6ZH(bPZB8*49mOZudv)NDEfh91TshGqEECUP&)GEiMbA zJYTOIwF2&q%H51;UOT1m=bHc*sxxpd6u@jW1LN%Zb$niFveM<9;f z{QarM1%MX|0H+B+Ds~cX)*!NY6dB0!3@n58$|DJFm>WT!c^qes-D#{ zCw%2luB3S!8*zf#`qSsak4h^G89DbsP%mUV8{X|aoTc6RFRA)zn!XKo^vx$`8izZg zEK5jlt1k+;lToT14gQRb*x)$rJE}^iy>y}KAw+ij^+QvwFZAs#GI;67BDbvmC1n3w zzAyHp`j?7Cc8=hsp!$u2fd?Tqq!Sg>aSpmTv+k%T3KnXA*MIR&yKn*ji5(JXWd*BJ zu#O*GtkmdEw{pIXUf%g{3jF_W9oU^k0R1-w{(ql1 zu=}lnve17N_!0jN)ctqA0*3$!{K+?f_w&uc``>+b{uvefKaHRF1F-#1xBUNaEeB_R YtlgmHTP>k3pI@?9iW<;TdCPbI3oeq14gdfE literal 0 HcmV?d00001 diff --git a/localization/autoware_ekf_localizer/media/ekf_diagnostics.png b/localization/autoware_ekf_localizer/media/ekf_diagnostics.png new file mode 100644 index 0000000000000000000000000000000000000000..a1561c3f5270709791a19557b874dfae1d6f56ba GIT binary patch literal 145097 zcmdqIV|Qi2yD!?^LC3aj+qTuQosMnWwv&!Jwv&!+yW^}lE9N@sv+o}FzwbEb3*35B z6IC@ao>}$7Gb5E0B;jFjV7`3$0xvBkrt;;>*Rn5Pz8ynBejcGWh_L#sz@0^;)u29$ z50q)d=RUTJxTcG$y}66Kk(1dM3p;yTGkRweCo?lUXG?pRE3jUH&ql0PYML&hPG&|f zR`zy8YF4&pp9jBuVPRrnJ8W-aW;x1FCk*)Jjx7WV>^rpW9B$6OEPgcpZfBJ z=!>+Nu$o8C`Icvn{5|N;%}V?0`RmUxBe>xD+A)PRI#I16C9(U|h?JrtvUeFNX_*F! z21aTV1Kd}J*H!GWzN*LV+mCl<6GFHO3g5i=5nsO3Y5wC|?ql6!U%~vDS091(BJpT& zab+~|F;TfM@HlKwWoLy{QAJcMSRVkGe;eb~Y7Q!B;>tig^qkKsg-;TK^0PhpjB=m! zzi!TI4lk5?S`*jDI;FlstIfi-_<+? z1KXjSx(82A|Jz3iU_ zB;1$X^SfgzB&Ag1jgNEsA5sE!QJ%674u_?Ws+#kxIK3#onwcMz(H@!yEZ!P#;~fL( z?F*?+WRttq!^|NbnoONfs+U`??ue#dDA~tyly+A`yqC8|9rxb*d|X))eT8hVmr(vQ zoYKl4UhaqrR^d;snw(ib7~~4V(HobdeTFI*8je@0_#X*B?tLp$0DSvbihV5f&p%go zfE&++buZ#dY#mUA1nc>msuY!iKNTtwF_K*tw&p_IJ&=o{Lw3#HlEvTj?o47X)&u8` zPp@xc4y*K8aua7#N4Q)8irch;*xihGRP*Vc5& z$=>R$w`xd=y{{}kKxs4|xLl4rAlp9efy!wjzsg&UG@}xqtM)3uyGGhgg4tlBjV;BJ zBtn6S?~eb_)Hc$55Ti!ZQ(0vp72=O+dP?b|mDapt&>kbna(~lXFSiYsL)LBN$ZGeg zg+#1Zbg7>f$Yud?diR|pmHK2qXo)`q+O1_Xt(Z-yW!7sF8 z4L};!vye58yuDgQ5HiRoosa!}tgB_}bx?pnRIGrKqY*-*H%QH9E0|}R&#D> zJVO}??KW_PAyrS=akE8#e>ko{@n|OkP(rj}&<{bgpVsKiA;Q#}Z6tws->S>7eZug` zi8B~>zCmzgbyl|cX0wFtr}>?GAOn(vO}-OgMza{r?)IlA4e_TKa>`Z^0^?3pd|FO> z1unI-86pf;V@o6dGym~mUs!8#J-UB*tOjn1Q{KISYl$1Ozpm|NNSfVnw%`T%{W`Ri zsqjvi8eJA5At$VP<#%H8?Ca$!(X|~!N^glp($QWRLfh%~R2oc9mZMb2lBlt85Xw%ZfBPokMSU)T_czNf-=Yxs%Hm6qgJ%SNvBI&n} zd)h@>jEL+h^!)1vmn)YfARE%UWdWVUwWRC1-Q1JGJX|aITTds&+NsZ z&MxWN!aY_ufG(t+?4 z6!;;QYEXjpUw85fDHj;qHIq&S_@5uPraIbKK^eJ&SbHj4cMn?C~QR zw2^ibU}mrr&s^0=C)MKzS1l4-WF_Hx| zHa?F$dfzV*VB((^n=U4X=i~rT%WO1lt}?)-MD^A{HE{lQr=9FNJ#W#BifFC({1U=I zLW14vg5qz@j_o!|O@biJ(;(}1zDmsNcAoGQnM*dlM}huQn<`5}GL70`K1}y)yTqf_ zYLn$NOO>Ay#50;>ik#?@3F@lVr0JsXwVhe_TSOYZ3#*zcZ}L62Xuw0Wg-cbAjSNwf?D0{F61GNJ)q2%lpr z<=!_c0$P4@sAFQ!Ss`&zkEJTF6>E0ztYXYbp_hPYGF3295U(RAb6({QF2cN;aVKY9 zT#!{O?|~I6>jzG(Jer=}mc*c^UFIEwEjoPg6F;wN5@ESb;-s%=NryZtobdeN3LNrS zimPwYV1%$wwhtw=8*)8iV(n>rbg9;_m+OJOE{vQQm8aO|Bx(h2_MY}9ETpOCcDW9! zmEdG%6|d^{h3Af~YR=5b=I)X@ZneC8Z{@p6!VWx2P&AWlPdcV-R)lHI8L9G-lBdx& ze13a!%n(o|;>T|UejmeJI>jTaP!SL7KhzMV2|Hyib)KiA29%ThSQJjf#J*yRWhlyAL4Lf*+cJ67~ z+kxl9SLQvK=}H06cnTCX zSfcxyfcMgsrRmE%y1DqB&rkdr_F%KR%u37mV$C)O4?y|+{z%Hjq;dc_t~j*#l5Xtc zQ-fn3LW{dxf7_yu2@jI_L1p}HE?K&#s`&XwkxUA**m3_eEVnr>_S?_vQ`l6d;^Z#s zJV6%1Up7pVYK6w-U++w(bL7F^(Qx-r9g33KK;keN>}<~9TYEJ`dt|$YA_#hpkl$!D zh{vJ!qz)#Z!&3=MoV^w(;&5nHYD-t{>k%G*FM3ag4o+oDIh^Kfw*`Wmh@UQBclh#& zDVpA2V|o_J5sUbA-!R^NV@-0IUtn>{7pJhucwdK&QLvrj+;J~-cqsoxW^aCO9b18w ziYRDr0OTYbFtXsW0<;raJL9eXIWi^uy+j{>ahjb)*nFBgROe5sb2$qt_mo6N2S1+9 z>6GNin$E1&;m&N2?n~XOU$a@Y;n=M79VW~y<8nMbT|!H;=#r`2wXk}=Ak$~C>pauH z(y)tLs29wW$Mp5+vg5X6+?t*#QTs*QubPqOU}yWtMMh1iFl@nt&A z>NPWNS8xk;e5SvTnvxyM(A`Ez(*YW(Z`=suRv5HeKirDWzO64Y6*`ZIj>dW~5hCe* zZ#om#2f>z6x)!eKbe3~^aIv0>?_Wq*6D^YpW2oyH@XqRQICN%K ze)jSmm7;byF3h`qJca3f?5cwwwew5n_e^$gR5v!==v1VRagKvxxlF^D%J{^b za@B@?UOv>rC<#alM9MuBvmI%BG$=n*$qgujiLJsXt zA>3v4E=%Njw&$7mBPsWEdih}n-3@3=I7}%t;&sj#vg#BIH8-*D2H#&fY{|(R@a-Qg zB_L1@d*!}zUU)govk6IJ5|;%OL8*WN0eWodpX zqld8{s9kAsb#xU@VsvU9>5>bbP#wPgW}RkBTr7N8MM#}AI9`%HN7|{f{yK9sj19%` zBg)Vhhc^ylwza_kp?c!H1MTNj26gqdUlDn(b_i0J3)50JL6?vGL`U4W3}?q23Rx?e z4n4#BdHP=~wLYq6WA)ak8+c~Vb^aPS5?BFnD8S4)g>5G)_ZRYm&6$H<*`nu4>ug(oY9j78$7%4y1t)JH*!h;`}G3?QI{CJ zw(I3o8$M2I$77jRLYVJN`Xb`vh+sKe_g)fmx{8Z;CB%n6P~T(+D1aW^4+Tp-R@tj3 zCI?})Q%&8I^-P>+F_%Mx%1oNo`q%-NXe0+$pjkngGoXhLp;QYv(1iza?btyj2Nc!w@ zM8jdbHNJcSt=rQA%Q`fk+TUP}2iBW0(NJ=m$z_IaVb|^M#kLo#f5`nI?!E30WR+E? zGxph8?&4UGO73A)<g3rS(xbivxkN3&dfG|xQ^)c`sPDb zGaKHx!ivZvms^;OM!Ec6ePMN4?aX)9&PKe>9*@j!t7qpbtbD%PaKs`-+0Gt)$!2Idk~CV~uW zs0gndBe+ma#o(g@v}oYhXyb5On4iRC)WJ+Tzmn~``g)&@mH-j_4Wy^(V5^? z^9SL-tf3(^+!T}DwSOdveAF1TWDPAbij1>)X!yy_i`&UYAUP7?P%P0w9nk;*ALsK5 z9~59ZDTzvmjaXBcD7p>BaxxCv>^h2M;vDfdO8UUZ4pC5 zibX$N6P0@@w^H5;3|6Uj+$tH#gSLi@8zL10qvpNm$P*_ASUT-dsnPcs%!8Hb?0QhN z+qztG9LQ)B|MVD8xYbZScU6v#c;j(WikZIA=mo)PNMhIa+9;02Yl!8PrH@Kh(@Oa< zMq|aAJKiIt1(g_^4L+O?1~+X1MUO|wddtM+I0PeqgDPyAcCxA|Nv0bcey-lCR43G~ z(%GS?brs&_G^y6;^0(okkdQg&-bFUZM1Eus`qkQWpWm{U>VQQ;-y=nj(On9QmmKLt zlS$85fjV-YpS8v;5E3m)b1~inQNFoIYu^;I(dARuJd;U4X=@PwbewPzS036=eaABnMj^@x5&M>R&wAD_n_qN+jm=qkI|}qTSyoO3 z!tkuqQB($Ew7aC}g(o{4q%aq(K}AJT4Bp$cX)xLrV$D}etMCRP6<B{cMy~h7WWP~zDG7zY--S@Scve9X z>oa6bF+7E&7fRPspSRcF@A3`&PGnRTq(D=w#E#BpG@47bT=k_1Z>%IrZ(;tpA5MXD z9Qk=m;s0EA!g>1zuy)^hCgL{z?z7d5*}KYfy>QigW0rsH*`Y-@)5Vt{U73ChFe!U_ zDB;Y^cJcOb!pk0-P;4?$KN0fF+zJO?ws(nq#s)~7ThSnef_1|yB23svRCG{$VUX9Y z>yz2!d=Ha$#gvaBHbOBLW70@c{BVefU^w>o6fdI7DrlE7+_fCLGDCrv=d*@S??yo8 zcWmH0EQZdK_92;&J_OF8?CBUtnOvMScyOrzI!oMmdyC8s8JS-z?U9C<1AZ<>A4Rz(DJA+E4J?BBcYM_Z8uF_h zw(^K1oTV{voN+ERcu-uFO;y;_YEFFaikUsm_v}?=+%$FFfMCi|uka3?|5w47d{$hq zksgf>EOxJLlnd1!O`&33LbZm|s?w*p*)BcZCoM=`oL>i%QL@LIKXLmESEMyQ7S78s z@p}a}TG=@fM^qraB`?d6j;veVB8uxH0aR&>EbpB7ThvXaBjUuuKgl8pE~uidt8tDY z4xdm;%XzuW3#_%oJoT{7Vv0MxUANYk+tBTue`F z-t;U0Xe@#Hh>_fQq~9662&f)fQq$blbPtDsV3bcg;z&mGrPV*z_~ea3B0-aTDnSJY1+;DSrpCmLklVYb+n&;mS1w=Igtk%=L_yX&_4* z*lbY(GtvCcFyzG!IqtH%au3eehE(0-%B+`^`1rt}8L`Gpu4>3dg=%yu#Q)S=ljbE15gfMNgZ$)4zw4h7HYKZC<5U7$ zXZs!my3e0sX3q@x6tVda-;iqj5`UTEv$5(6_@!9g(KLs5PudImk2uPqc^31^zuDN_ zFAB}Kc`$>yP%3<7(~xQPjHO8AoLv5`MTKn(ZVj=m(~wneln*?7Y<%{;WYX8-%Kaf| zXKFk_l!sNHb!Zj_Tq}pBTV;yv!#`p&*%#q}gSVKJ-NM4Or!*LFKiTOaTYf_B0uFiQ zNU4A8Zx)Ag){bC|UdTlEjWN3Ss1P;tv3ts4{)O}PQL2hlQXF+mm%~;dSfBj7I6Ew&3RN~ahZx|Kqz;Z794KqXR#sFoJEMICJM)UY_ zQ;M;|kaKdv^W(!oz+x3>S}MUl+dLNJ!N;pJPcA>5$Cch4BOG;3pdw#|V@$WIs;;L+ z#~6wQJ|(+8J&F@7lfR_E$2O>IUSQ)M!4>aA%x~ZRYUjyUKbQK@Umk#Y6o3UXyu7Y;e9FLs2}@~V z_@}A~j7u6h`9^&{rn{B0`IUmq>t!w7zOoEjDUaO}Ewek-eB7(c(Vah6LZ>tn$+Ta(M^UOmjeEuur>`tSU6W6ty-cqI zkXlYPWAS>9w9+K##Wd>Y|~(V(cXW8H_LKUV9blau13=wEO5S8K#F`aO&$)waDm_@0|g z1{w7xfxZB6i5~@S)hKKCH)Uhx=yY#gyw#^Gza+Mf_%wQn#JS@!tKkrrr6o zRX8?L+g;*Jx1u8&m_x8?OZ^REt+*R8K!lB)bVtdQpK*4BGczb4KGI5AS1Uw0T%$F@ zSx@Yq={6uFwU8+HT0rLy=NZT8C#_N$PZL#i@E18NRkzLMjS27(3f1&=x^ePMI}>Av z($JPAE~FhFbk}h6&)3@7pUX_uWnd}Oq0R#>$tl$#meQ7SC#Hm94OlHSQ~S{{QAZWM zS@ZFre#)L{*W)R0%}HKITo&_N)SB(&_Mj(R1CIOd-aGqGtaC_sf6|l#hurk+1a12P z@cL(*`L7o*IQ?_Z2(UeAxujWMHKt5}oW+_Be+Ai=p5K$iFdm}G-LAFI5pDA=H1CYO zd3-;0G&7WFT5IeNA8W{3A4|yss&P^>dkD%`909wzoa2v20oET59jxt>+vvRwm)D29 zrA53bN7w56SR#CM8G3KjkCz>t-&y!0r<_YsTOap!lC~KtI<68V-?-MEJ$*^uwwQ3?u;9#f`M@Hmek7~&OI}X|_Bxsgzhjwnx*6WJ^Z4+Ya95_w zSsXZ%1Mj{RAK{3Z&K04-IQzRA-F;6xM$IPRrZyUeA>5T zHgQBG`|af|py$WY={-DMBh7E6*U5(baj7}Q(RG`8)C`d>#DFAtD*hAWVPI%a#vyb2 z&F%STS&~9OCVM?Lo1FNzX*d3CJnQc`_~2#?()iPW+@)H~{$JP*womkB7rfX@zxfh{ z^E9V0bl+iA+7G=a6-Vt}0g@TFcHXDy@noX|VQZ(-4mS^SJbBHvos20N-lZ(>TJ9W? zvefBZEtlRMpQc61md{QzZ?d9UbHimvIdMXV1&uvhr4X?or|vtfYUNq0O}k4tLhGcj z&k7w{Jd1rDn=}z?ESn?`tp4>tft6(z>=dOz&(*%rbmK>5%_75IeC1T`?EI9+ZCUr` zB4k%X@>qAa63-%7b~GmOQ1+KhUl$Gu94z3D+?Gj-|?qDC}? z2FUnMH^&V$QcE>1ctqTk6O&P!Lq^Z(Zz=g?gC)0)f58$rp|1sdhsoEI zCu_%%!O|G7%O7)VVYQ zH&xqNk*lo@6at}_Mv;T|T!E^rsy#;h-(p2xGJ|#5UQv;$a}=eB{Dz70xC#F}kZ(~R ztd0cPm(@MR7`ogHuPg`yJz0A`aHONXlqlWUUN1Plk;3jKdIX@Gc+Z{`DER0iMhQqc zkNlPCp!DFzD3PlReI(Z$kxLJEx=+g7UR}? z3Ap(@lIe5$XLxRz0NRT&b{Ggn@D1RTzE&+_Hv}QaZhZmE+qHYtdX{tZ!I2GqR8(yR zNtyq+`McV$2w3Sskj%l&SZ5%FH&|ITSX84jVKj! zVozy%oTe=4K>d8+LftoAefF4@*VY2rzi#GkP(umz>1~vlK>nIl}PMEMSo{q|4|Bt;U zLH#zYJ%)zNPbxpp+A``*F8_@p((4&h+9hiAFmrxd5*6-a9*_=){3_vD)+RmMb(o2r zPVQ^P3C&4jnDVxjE;~F_0c;AV$e5Ur>};gjci5 z8C}wD(%5ejk>}kKmvw4J9O36UYWh{r28nGc)|g@lzWVZ2J@}?}r%PuhsR0Vfrn|U@ zgRH;mW7b^@=!%NzNr3T9OtRQ zu_4Z~a-T@$T;9cWRkUf6E0OpgCJXZ1j1TQ6m7RY%zUy4p>a7#gr!`LwpzKY2cSD|2 z9Ob;<8f;xsdhe2paYap+FgdLH2>ATUWb&Ni(~`r?nGD+;XGL6G-op&uUaa;6 zd=l*jFdY9T-FoQ=$?gJEb95lHhQjWF3@sP#LBuIu)u(^$ztE{yablR$h%ZpW0>>^z z-+H`IH#RjKWV&wddj>1mE7$H{p_j{`N;4?f;#f#9S8j)7^`0%46{a`rsWv=9Cn~-% zw5|-9Huj}f!jhYt)2FOH4v&9UQqO`5ql;tuGB6hk(eir9({c2jV|+ci!#z7Yb+F$v zA!#WYpuoYP##r@Benj!wnltVm?zIRi_ik__*cduDATFJz9k1uH3;tZ9jW)WJXwh}q z>vaT!9**iV7&v=yq~}juGU%H6LzvcZYl-5ff!IWr`(}j=bzp}lH_i0gjER-Io>lSb zg498eZcZKHTj|Q33zf@`oDFfa6dpJ#oFQE!#Th84_%HKcwn4&lwdD8?{5FDYXt*C& z@|>-)&X>|!j7K13_#306l?ST&ejluO>)h)%$wkvHC*6{q=~m+n za-Q9k@Un3wKR&`UeiFO$n5_&%o$zooUQ*@cEry!gUleWs-JLAQjFdd3fowh>3)IyR zIzCXWowLn?)jN(acy8Xu5Q_S!gc@GKrPxdt8!3lyrT8Z@ur6#1u+R>9)JPq3m5QHpIb4l)SR_BW zmesem$fSMm89J{IS!eL~nmS?>WLPH6GTmsg_Sp4$dVKB_Kzu;0Z-e0wuO1A`Y!=nO zSB>{TB@%p%ry%1-JE>OAZc^IR{~DR*@)KF)dcIHX(d&AXPacflTinQb7npL>^(V_r zXVg*&n>K)~-U(oSH(HbOz=5Ls8?A3zi%u(3u5*|(E`)ov)ryun@xr4~l9eXo%c~ho zn^h|WrQQtpu9)CGD!)N~wBqBCkM7Lt3pXozu}w^*qt2tSDQ?jeqEFi=bTRU0(U}o4 zTyqM+?&~pQx}R7n`bcJEvGZpj2w=fD9`c((vO}4k^o>Lj?mJ+7!V{#}0(x($M5@!n z7|-H!jY<|%9A4L~8%sI++b;xuCq4{yo|8PW-- zyK5uc&2zK2@|uD9Lcu%?Y)!@Q)lMG0`3j_-uCfFG^=mZsz^LX<GvGaZv@z z+Vh9E8t-FLPVOM5Hq+-hTUhhu^#+0HvKgF?;QK3j9o6h6P(MeH8+!_-#|oRSn8R5S zU%;#TzWWQt4*n2i^*;8@A&B)T*6@t;pUZp5f16A~kH*?*Wv`uLoBwq+k-{EWvR-*t zlh+@DY2xX7N4KX=XEAq2sM$nFB8xHLb!`zAr~PMrN@uOZjFWPqMnmC0T?9vGy@PMP zcmB~@(=T0{{n@1dbpB%nw@U$uhO~H&Zr%j{Vi9K^$Q8e|OepETLLMDYnQg7y#g?Yb;VoLUFlzAH51)Z3>D1w?u{~I?IB4V*v(ep9Lg`l=akAMh z5{YE_t^paTi_3+>a#cHLZ;=pDH+Xxp&^NuIU&L8`WDI%2C|V!To)1%V4R0s0huo%* z*E}dE8h|+3OZ~O?;=4$C%H3@a=1jezUL|x-tJAqElkO~}o4ulQvkO=5+uO#Z89b61 zIbQk~Fmmvdq^3PlE44wzp!JzFHDu&tEiLwQ&kFTX4I2zjXqs&$FNJk#4ZF?Leu?K6 z9banXa|VoLc^??HlP6xs0yj2qe#SL4$n%FxJBz}iPBdXDl>%ELzkT;BBh zq&`tWFbW`Kx8?iDewT?DSPcUSkOJN0TiMxXE2rEnoh!jUIl#(s17Ix%Z()EvnJ`ps zIr~$Jj`-KDrf`S~|3z^{^GC`p?P#&d~fH37p3@CJN)CX-R*sXqW5X12SnC`Q@e01oenN z$LOMVr!Q;r5U9yTtWCi2spB|gteNkI${ZV6>$W01J{W#pCE0d)!54$>b&Idr&8cW;c5i%zK>jeByX9lz)x zEF6d;a_l>aa=mvh;VBy>B2 zsrnX#aDw+*kDE(zwBODBUSS8xM*A$24FYH%S+$=nH;%BDUKxfVUJhtjHx~IG^=aMN zs)sQ#;;L&9iWJezc><9yx3bgv*5glAdHM<6qp_pCiIkT%ZUMkXPMgZ)wg*}L8bZ;C zaP;VC!o(#nR>2#uf`o%ew#HAY_Vuxabxi1ZFee@$=t6ac@X1+pw#!nqL|N0#|8Phy zOHAYYC@lw>*8!hqgSk*jXAkR1LOj|HIXeHM>W5Kum)23xM~7c;?k7HV zXgVU&$XsAbHau*?TM)ToCVR0JcqHIrVERXOU!zij#>~q;*LhUf!V+txN_G05OTVQ{ zMDnm=0tXk%Q}6YsMj{$)jsL$)ZanlxzP_DrYSEgMO5x+_7fXu|$OO2m6ifzA;G5RO-DEduLvoWo9L0>yKoc=;(w7*!_XDg;G zOeAiz#$hNVuxw3J>7te|f^0OIA@I}j33-&k3=84%+qn3m3X#PT_vfHJZLmAivS(Ke zQg?54_ks@V;~VtloXvB=rrtP862^Uj!nx(chAp@RMnCDz7uw;6f;r*br#1pKb~2W; z!!SNU02hyX7Z`lbntuxIZ{kua7@=YPJ@cBrMS!<;87iLV>YoTCC z4(9G9B|i-PFYvcf*LE+2-nUlPM$r?}#ISe6k-vPyfuz_GM>11^y$uhKQ|G+CG0;<6 z&h_Qs9R=ch>6i#?3{q_D(bQ&_C%QjMxJ~f#P zx09i`RS`4T(aS;#gr&+o(CdsbzcZL|KeD?0)kIjeReSdUlYG3|9sL+!r*B-UaiYR4h;|`JJ+JZak|`ys%sn#;eK>x8gXNGj zaR}$0Ty0B$A2|E#m@co1abG+T4$HN#o^~vFCj9<);cc^)kTnkGTLJGJgwTNHsq?n_#nK1xMyicUEbCAs4Il%SF%PKB;7^ef(-JENlI?u; z%3}xV{{{XXk=89=U<63ISrJ#+GZprdIh>K<^GPKk zl$MvBY&DY3@GZnReQ>G`RHK;{%NOLE^kq=vNlkcdI8tY#eGN`W)Q3!H>bBX*|B*3p zIoi%;!ggU$6-iq`hyTVrG5@F1$YT9~Gk`VlJ)9MJD)&@x`>4ciX0}D0*zTOW%S6kr zgbLI4+t^>5pIFr|K7R^?gR$=X?0MV)3TJy1a?I#dwhIY&hdz(@<_v-)^0uEVpEg6F zum|^Jqc;fOuC&xRC6?LI=}aIZhJxqirP4BF=Ry<@q=JZ%!=gT4>jUN2mzYAOnp&Da zoJ@_g93jJujna_)SaV+bQ zz?j#k$nug9S0SeNGaRR{C-ZCStuhf`KmcShSC$FuxR7RcdgT3zgQ@9XrjWU#!y|CZ z0O~AY$=2)v$^vhC@z3rsHtf0-T-5tZ%{28OhN~u$&0o$x?cB#9Uy#tw!#lGHhYT{O zJim%s>TCmWVpC?x>kvP4a6dyI4 zwS2-6H}X9K?RcUO9<+%hbT=r?iaAanHY=1s;^Cz>R1K? z=+l(EH}rTR>_5J*boksYDCJe+#f9H~qfBNC+Jx8b5S*3WmfgP0ss#d;*fh?m?s`fP_cdlt~bm4Ep|+AfD38D85wU6wlpA(`XbA7JX2`a7clj~?5adz_O*LnwBFs8mig=doUtB1R3zyD!aZGxAo z1MK7Yx~q7>QAes7^`MD(h4k`ImxXeZz(Fim!dBeYTAt>MPa4@R)$4VB?wCYZ|Kqt0rW;`=buc~!&vOVjr;jTGOdwiqw z&pOg_0^>=cHwQm~+juQwx-T@LZ$MO4cce2G(7^|~xF;Lne;~Lt&#U*h@WbDPV@NmO z270B9fq_u#Zq!cs6D5K+3OUo?+itVR7jCn6N6&9lE;f0r<;%XWQY--eP;;k%h+Z|& z4(Cjv3Z9Rnsr`h%yTrY(#wwuR-fZW5sBwa2rTUaiJ+4pqYhQNUpWnm)cr$i`U$2+e zt1R<99WZ>eQ;8=h!j_i86Ut>=@_Y{RWXpn+RUHZEN}a%a7%+6Zf~Yi)sCzaYo6${= zpZ19P9zDo<7}Pg|qf}mp607*#C-QQ?KfgJ`W|bPzT;tGQuEnQ~CmGpakJTZbfCdoG zp`;xNuhn8%#6ltVE`IjyVMw`brDHczb6aOVY_zm1BvH;!mKIt;Zf;DIk%rHlLaUwt zHIYTSbeXdCuAv!4ll4_sle0`9zRt#f$jwNkQe#}kcP_;Y(Fc_Oyuf1e7PR6_^Y{Fo zyd6lNYVp&eTKAkzSVRWeYwuMwqWQoOb0;*S)+telQyJwW&rsM93Y}hvfJ5 zxkaUvPYA`bUmdc?J5n(({|KmBZU99oL}jjqjF4L*YYLP%r!f6KSXsSeb|g+J5Gtd* z&YM~suFCX^`<2*A8S!*5&b)U^!qAkM4+XK#*ai^?e=#!tOn9!6cb@Jk43q2+1l(t) zFSotbk? z5+<$(mIhCGeFLwr%>4o?jjr5-Qy)LvOM|-VSYtDF-H$+`(*g<%d+%D1s z6L1ORS710w{K59s4IOd#K}QLialND}6V{3&|nD#1nHGkbrf3?!n!I zVuksFLtf6z`TgSwqFemo*@gF7r#qrfm_Q(T+06e1eAauv_t*3FVS2|qpPmc*`Sl=4 zyu-l?;!S7CNj=|#u)5y9?P-TTuH^2$J*!p$G`?n&)w^6PrIkXDg(EsDd^a(b9Huvr ze2Xj2(b`DIA|1`Ng2U+vMKf{qqUWA02P12b@1$@~WHj{f$&ZI~2ekGhk1H zWUo~1bVQ|rJlsp8D|-Tfh8=6hj^*C#@SAA`6&klquvVFJcS;%d-bh)t-~Z2uH79yG zn)x^Kl(FvIIWCq`{g)CG@0+QP!K%wYO;c4n=8|Nw&AujeRybjQIOOLc8xIQqs@L3Go($Ti!%!yz%PdNCo|eKG=(|A=Kf!WTP0F;N+mLv#y+y)e%%{C9 zG30B$ZVwk{YZ)YeSEpuw=2>QiX>2ia{{?^VH$pJ*5bN2B0#Y?xncv2-F-)Hdl}E#8 zPlZj9rzqU2I_B_910;W0U-hlyW>G4}XifoHM4xRI!7*$yhW{csXVg0q>NZ}A?nS#pPlqPlZ30u zLkE+DAJ36cu?hjrpTQbTF>)=WMrC&b>e8LIlllN_x%lX{p zA^HExb$`)vyWk5(h#1JbZMgRTPl)VVhv1D+!i&1<&xJa-S+RX+tN-&6&ej@z@8}JW zl!8=7s`R?A9nH8nXF+4a{{Yu1=b#ii6TZHV#jmZ24%dhD$ zt|{FMBz}UBR4J1Ck>!V@SZb+BN&?*}x#(ttE7Sev2aZ7}0T{mr5V|Alu_7aDeJQR7 z*W0!dZ<9V=+`LSIzayqvMReyBjOu0Ktz=x%4fJaEVUmJz+=@=F6~g-Hv(5Aa1jZfo zWXdd-xRoQHXJadI6GHTZL0K|I6}NH}%gv=QUW8GkXKc6Q{WxR)H5O2^nNn^MMMAM2 zMS)#)@*~cChe8)o3ER5-T1)h7upQq@zd97PpQ4M0Dp=-?HKi`$-e(VXqx;>2C=|xacycAJwG(ZK22<-s-xc@_ zj&yz%S*eJ;9>e=IBQR1*1#(QInX*E039#>YG`-8=N~4c98LIhp_6R8|uzq(b^pPuS zx%L1?L8mz!Wd@tc^ApaIk}y$#pMZ%=8U{Qi=EMJCnztkBr}f`n*4DDe>=1BKXlQm} zp(qISuU{dQk#Qr6H0uhw9<`K&p?Z!*ePL)g=%|9AsGy?QguU!Zppl^2W07P;#;0=M z-yMU&;SMNBE~f0OtA=pQr`H-E+b!}Nj%|Wu9uiwTVP8uys_py}BljVZG{htAG?4DI zx#k+(ug{L)Wcrg%I8Ib4J`7mQ*^0b;#~E2wPMqcWc9)HTz&ImEjv`xr|0r-JqfKTn z5>amo)I%x?&ReEsOTjzQ<54OBe5~ht+|3Oh41aflS45f|KO9K~y|M-4Hqd}{myZtY z&kFu3ZKm|lji|^7`!UxQ4hqe$+O`B9k0u0H2|^k2$fq$}Mo6k$u4g<{qk>`VERj0; zIpcTfI>umiY{s*95I#>H7C52QFfeGyu{^g=;jkG3<;WNzCOysVe9M!4xjL&&?@%A` zyw}&fs@R_0_-aV_+i#iN_V5KJ$y9hXq6g?yBKtatNI%;sz=CgOgfR8`dTN3R0Mnfkfyg=gJ-uQxvPjD@wJrSrAM66fP- zN3G?z#XRHSDu|h>4U6ezD$9|lJNGbIV(VA0|9AfFb(Lp= zglbazDlAdXk+o{{0-LEymmYh*R~p+P=vqYro1$l&zZD-7@HEOqTxwEkg&y!M!chQ z?RP9bH){RkS7$;}PG8b&cf!h-?P!$3yK8+voz7UWVPZl^NDwR5G{9J5XP^^b)N$E< zC>ZroH>rX_29r-=Yj&LtkkAjDzom~26lPBZqx0P-s42$}7~l*F-dKUFGU|^&-Ouj?9(4B4J?W*{?D9 zbU7&aa^eYxs2w!5B?;-jwgGcLJCQaRrRvEqCnEZXZ1}Wm_Fk zTDj52b@TfsbORKIH&zT)VXU)3byM&!m(*~l^I2i_Mo(*Wn!W>(z5k23cMg&)TDN_x zy36dcyKLL+vTfV8ZFJdImu=g&ZDiTF)%)Ci&U>qIk4$NRZRYApdiCO(Gh4w$Qg@_7M#7{zd-B%RQ5_| zt~Z%odsyjCgHR_=c6LzkcAEMN#VUI+qN$<4IR~fBhe@iHYs3UA#uYFg-bjBjpj}^y ziATFbT;pxDcwpbyg>WdRGk$qgWfzCyKPs9y8yhD3ztwL6~ z=xPCa-LSb`ap*Yqocq=O{_Mc?`cC-qsAji1J$1{RFiOrZ8@pdK1QGA4Zq(bK$HDvK` zm0l9^V;@9^ZIB(s@_Ntr24L zBlb@Or<{yne?yq$EHe@Ns#baan%y8Epi#TmG=PMOh;@g>6t#3?S3kbEQHrM7-6Xcr zF+h>sg{UHggoKQnZZ2+bs*qgwAQ7!HjVCig>^cUU#aoq;gqq1{8VU5eEZwTJ4Dp<& z7O1!PcnM-B?jMrj@cK>Oiq=?Jnf2D2Ps~uQiJKIBa~_T;GndZDN5CwY`mI1Y07Ohw zG-2Q5P*iNe=Bvk$W^dSX{QM}=G`f$?(!t@ei?>MRN;ZxCBXWpo)ttfmoNiy*QjR7F zpk-W6&g`oKxD1tO8hWy4#5A_Xo{to?H)IK*^hO!5#5>@{Y}EZM@*A1xB=2*x`Gw)G z%)to_GCqO9WCcmNXldj#N%b>QetUDWS!J-M&!~8#OS#VDRhgktCZ|ck&Tu3oa%=lw z9E`3BeYBSQb!3$(yzCt6@gvod%OFAwwX{p-*JsiIC5&c z-1x5A+0gM+o55i=b+(FzggYHqxP4$&o{h-@Cc7X}fDe3gJw?iS5qJ^Sre_4Bc)VV6 zMbvxIS(!Ftj8=j-U#1+A+Xn%9u|>MI>SP;tB`!_;v}(?kN!w)MSWj||7R2S%m%43M zbnTuppYsWyee3pvwXMu^%HUSp;5ddov;k7)tvMo~MQtBv)KGj&^s0ApVPP(1zQfR% z=5VFRxW6G2U}DMRhI+CTP?Ih%Cbcp8!pfmvp$!WLc7*NXOtOL~nK0+Qn}^D;7)Zd& zxR&y+!VmkHan96igSXMgTwn=ZwurL5TA#5HXs0ge+pQMn4}qmLQ3H38YQl6rm$Ep(4NotxF~C&&jyz z?&>s!`uBIb6?P%n`lJIa2?Xj4ns;|Z17L}ZwUae+2q|&ZF3*jvIbAAxN1r!o#PRLT zreJ0diIo~V=%8;&sN5|bemK+BE7Tdt+?6KuHiGbo0&fseosk?-0OPlxtfKfL(390< zIVQF43pDG;*cs1w$!f@>h(q0OprOqxiJfKP+hGi|NmPU);1XrvuB`?MLuTr4S513~ z6&Ce|JED17wX{%~8RhGBoU(rhwLgEJU8K`c(v|#tD?M8CMtR2A&1lyaYvV&^ex>r|(3p3yhhr(rRXDrW_5&rE|JB4*viV+A$qxbg295~*e{LH|>u%=teHHxrRT;Z=3M{4nSQla|f zPK39C6HdG^7<8c|ySExV2s8eTXdgW=eU{xPCMJe&bgcWrdk5me!~wkp&8a?3GU7iA zf3;__Rl5XQxuNjnY0cAG8#m9 zj+*kCIu3HWyTOrm`BS;aFpamzj|AD;*=n;_ z57-fnrbNizo`@u{uZ2Sj;NgcrPF_&Z-XH%CekIz(k+HInUb5AW@d2f2(YgO#=$4h5 zgzWHS8|KnjnUp0RgNiPh116s^T6B?BIL@HLoD2&KGx=RzQe##7Q2(HP0Gqn&@WTrj z+L@zyw{%}2=?eBku;Cj4U&4S6fdS#b);S~*M6-3hCFPfk^taL1Dlz%JBrU%bzNHC1 zVAHm3WWinqD~ALQ5R2FCgV=E-?;)gL6grfj?xp6Mx@d{-f|5 z5gUgP!P{6a(dsV0{~U{kUXEX131XCHgtj6{A0c+viJ>;Cixh~@LDaMY=>Qu(luY}r zex4bhEJTpBAvrp8RqP!|N*1ogK)fcjnb_;D;lK}488W<*T8_WrV27PpzVU+l1Xwua0UqzM{-CtvEt7 zY}}hplPMwaF8yRiVMo)gzEO-X>=22j!JwDuxV6bB8I2z2tG|llwK-27iFUF1ji5qEmgs~kmV`lp|5W}WA6NP$Gav0(pim8 z>65YH;d_1YOTZ!TMa-0pF(JLaP4)_1=)Qo;^F|_de}MDe$lw=KMce@M8twm-7>pEF ztde;)5{B}s3?p4vm(<>*rz(=}%`8;Zh7`=Kb8Uu1i_=p_5w2gbq>v8kOc z@r1VNZhX>m!tEmj)bmPEB~3_!e0XyI2Y)|{`B>BvD+!<9#i*Vqn&vZR9f+rC4_ z6Y5&Q8(2mh>hz8e-v)U$6ARRNns08|j3e-QREzma8=V^N97#Mm=x)wfo12`dJ}x~U za246!nWE9{n!(VxNKUzLQ079K^p7;Wj@`$2Q!ln+uD3qZAH0t=8liESJsvDi)?04H z&^{BA3moCTo4f4fXYjpD4)5QlM=s1V$~8Jeh*@bLuqvqVZ1Bc=;}7Dyfq^A+2=f&G z)i+vP;9W_Rd$?BFy2g4&zl<5LW26t;iZPXHlI2mXXSccne%e^&&T7GGh-|9T2U|yX zDULjg+@!p1JGHmh-^jv9l;OYKx#8wT-TwM3W{}Wg9OClNw~~a_3-RZT$HBv=M$wjt z-7qXAB>I$AeEuq-I0y{Nz3EM>fLhDwi35mCz)@COfGGDbKk5?amg}I7ZF= zepx<;&U-~-iYe1yMf9OgeuzrAvWw~FEcn7HD-HIhIPQB(9r9O?n9-qH|5Z~kG;EV> z4(j!$Gc9p_fAvgU_c7}foQb0}G#U+;i2gss4kr5h;mS_r!o>)>* z3PUh71d*w8paGLvRX_I*wc+Vp&*g7AxG#IXBG>PtEH}N*Z4xiv@DqM+j@ei=+2yE< z_-0(PXTIz3_DppA+&*zZjdzijd1KRXIy3yF^B2kTPF*6k*}gIxC11Pw>E*FL;A=8e zSJPbNgn^!c3v=X1pAXpCh|Xm@YufDz^C%s*_OO$0-L^XoUMvy|K~Bo1q1;pRob28% zw?DVAb}`K=NFDmbZlW)_dV)1N&*V|RzWjR1LO(YW+&`C zBKB(qYnWdJGkbltKt&)DW2;#9>$8gF*0t}(priqBcN9K`X5-4ny5k)--1-v@Nq8WR zUJrtH-I?>jD8jYz@D(gB{M8NBV~Zf9x9!oMQ3ohlo7cUhF{O zxMI8>#^mX|f(1S=UqM>%y?W=TbWM%rOGA^|rT@wuzsG1F2R$}y_kv|9tZsaUUt7-s zWcB9IRG6V-1!qtAFR*4jm0cPyyR4Cy$|{~rp1`yar>cLjSn@la(6ihpd{>cBWvN9H zv(tN0qgH(<2<>Wx&qqDXh+|(GC_O@?rwppqmL9FjvQwFPFl%?!kT3^dt$7uhD;SIS zY`hMAoGdrRn$tcPI^)29QmuFrVa-3{Oy^=yHnOO?V@m8{ZOS*>P!9xMu33HyvtEtr ziI3_RB>=^})3b6gCA84U(30bS z4*AS>%2DC-C{r~8>C`TXEWU0)tk)Y$2foA_6Gi9~JAYQ0`9f=q4+zCx35L!IY%lu5SK5-gBaZg+HZQ&yI7R%|N*F^W@nk&g4SM&NewU&ky5 zF-qEYPnI}C4MRkk72DjZiU_6oTF#8(TABE3gr1j4SoJfOBZF*ypcbPpqsZP3lWZP6 zC(Mh&M?}5;wwd z{T#k3rP{^)Ngd0tEF-KoLC)$^tFTT$Ac8hB7nXIFRo>;NKbIhjk5m~dq0GIc`mImD zKsx{oQA0Z#)xFI#F+ZZ&Wn^th6*PgZ_e@kkz@Lcek{n<~iS(ESIZL@pB%az&+v>*@ z`hXNKz;tBApqGtiW;o_NEV4l$NZC}ZlcFHt`BpFoo|@;OcXoO@Ld&I2@O|uF&x~xU zlI)tPgZ(>^{I3LZK67T#-+_UGV&2Bl35xh1C)u3%;GS0Gyf!xL zXT)oH&e$0$WFk|L^Ae=|Gk11vuIow9Hx43xDPg>YO15zdGBJg@yH+Agq`qdCENn zjD+>I2g^{ z-=_3HEHN&Fcfg|<_BeHLt>u(=ElbocMO$x&56M;q+5J5IIg)dNdH*JN?A>>8w(582 z%g{x#4VGwxJw~>&*S*E)Na+m;V`&bBmxX}>liR+~CRKH)5aXzw_31!4xw?w4#hkq|8r0}!R;L$Ibw0x84v+ghJ--?U zrOH9xfJ?3i5^jP8bDz4FuzZZkldfCk(U5X|GzykhD00nt3(0b#K*aGxfhEp*+mn~d zeG>$=os}s{g`aoIc?JQQ`q)iWVJNC}vNv~Fjc?(@#oYyRAPI4~PUqy=LEb4O;;+Xc z08tOjrI&?jT~h)MR+B85uGvid8rCu}Z2Cs87($Ob>aFk{9)5q!^zqoAxhLyEfL#Ex zef?~^@=*4e;eDxA^9(!NEk8{iSpspi-!0S+yE;lQ6%?#WqXKF*;b^!dW%w({A+ngc z`llV6Axe!U)25+V!8Su3WDa(<7892oTQKSR`277t<<9DYa%W4|Tonfg>rQew=%8_o z6j9ByO_R;pE4O4($bdC^pDTmxXc0K`?>bRJ1Qd@@UhV2*B)fEzB%8_S3+bD}*g#3xE% zgnvQ_WUW+jnbr8lhW&$QiO^2~+2->;r}E?zZOq3NYy@fLPK31e`ZqG%ICtI=se1~T z=Y+(fFy>*qvhrn1s2_Ln-@qxLh!x977nqm|`NGL*u0QyV>I{^CI9h!X%TXhm$Ohp@h@#axaOq;307$rD`g&0G$Lt$^z!0jg{cf>!a-Z2F=g0qbSA{S?LWI~ zdx1DUJ?PkJ;S6TxS=nnFk>A?v$6)h=L z4Id@oCX&@FE_WMT=2DhUyCl^#C8yE}LhXBHQddw`|D

YbpvNBYf`F%rAI);i#Bl z;O*09jjl_wrtF!{PQy#ovD9D5iCz;7#>nKOXRbeIGZOZ}9&*%MB1BVgiYl8CxWIpg zA9NMp>`e6hsr4FvvIZ^eoM`5nfsq%OtU-5wcVHv`LJ=@HlAj@2+tI=%_|?-h{w!js z3EsZAyst?eG`1I6y+;nWGl_`>izAB9nR)DS#}KeY$qN#5r731DWYnN!hI{j=1xbFW z>!E`U<^4^fBz)hO(yrSdCA5ig{!I4VIl`UlMt3Fl1YGV-a<)0Rse;CveSmX~5r1XVIwAcMri|+N^y5E?8=P9ySJ>In%RhFW8o4>55Lf;El4eTGPnm$jH6;*7F z1p8{aHD$$;oPo*Ba2Zo{b}F`$9}N*UL`W6=LvJ1T80xWp=iq zso7G5OPkS^k9T<*wSylvJVp<45XZ|ASOF-PUYt+wDZYj5UfQl19)R|EEUZ@y1Me!b zrMMOZl}1PsK=N}r@5gs?wV^lS=fFm5k={>tDyRP!m02l({r{25h_i%gl^r|>8w01W z->vY^2qk}K#Eol3RrfE81r<@m& z99{E;fd5+i;N)mEeoNbm9Q8;2j}z|aoMQrlkj_L8LMDE*T^BXVmQDo` zGo>{esQ7-KkGcfq2M?+t$~K+Aw~{SKK+?%420p;&HlIqhna|k!x^#Vxif_E;aV)ak zp0mjx%WAHtxR<`E(~^bf z=RM!96i{b94t+@Wrl;@2{daOs`9NZh)Spw*yGOLIKg#^pPz2ver0>pg-dfoM;;M;S zVP6u$K9eIcqW*kEqsJnVUo??qnj2Eu+YMARqD(cWvh(T~mQ?<8jI>ZzXZW8|q=b;r zBm<~oYb|il=b>t061%Yoh13swiK+AP#f&2#)oySZ$3nIGME`S1I0Qk<{Kj=xFN1H$ z%az!JtOmG;Fa1E#Z;dH#w@bf`q6$Y6S!X$vzcZcka7AASaL&=KOX@kZ480N9Hbc$q z;u@{)inULd!8!>rLBY9NE|xDCEqBNj<)i#Eq18R#(-JE^2%zMRF=#~J4RC@gFxOC# zkTK~k{!ZBC9pIrcvBBQ z;1}(mS_K*0Cri{IQY)q#`IK^LVPM?uv*X{?_bcwsFwZd_!JUsL$Uk#s+BlZ&m+EXU zr!0Ap`7-y*PNvt*JU8I+MA)mHfB{?!=~y<$<2W)tlI{VdDNFz@YdG?zy#rc0s~ZK) zMssu*$CHVxhI@1_BZ?_vH=G-Xkv!w6Eb6Z%1bI$&vv1-OCiVC(Xgm{;M7J>H8EYa^(DnVmuv=yThHcA!KH=ZL4vYcfSHbVA zPR7L3e!c zyhmq!bocEsNR9(s*r8n->=)S>-d-B`lsO*3|GTANf#ci0tZ{48jU0&6{s6h}ezo1+@W)UE>eH_j%Y<_z`LrXqgN@Pih@9{QmOrE8WX{GGbUBp_$yloC@ z85A)%InqjQaSJpJ700`TvDyGK;$K+@H+;TRW6l%wFNF^r$|&Z;-QhCFaHE6(yZ@vd zU0Ezby zcFR`|B(@s?2CB~8>G$wE+wD8+?otfb^avo&sx>ddzn6Cqcr-nl1;DijJD>B9mpXy< zcvw7pF{eAX$PNLwH_KzaV(W*pWDZ_nv<|==7&bZqQsm`UAAKyW$8E)QeU8g6Nk2;4FdjCX!zqxJS{*okS&J1Vb-`-LYPm;BaUWbwASOkf3(9Mvdn-dLcR}n{ zUH1J6VlOtFbgDUR5gZrKEl-ZWDKlADs`tXA-CT@Y^>aS|m|;4(AGDrtopHWb5YbR^@yKM#ft@zqIBKTHP(9c6ydFMrCxW;^;B8e_A}K zIB-ylu-rV)ZJ1&ngiQPtyg+SYFkFS>GDe9m#~w4_t}3#Vq~lSB=D|;%v0i2nuRXfW z{$QOU!B4{rK`GN=yJn3tjz}+E3(xAgOMaOy5#rAHaQ*^n1X%YwV;yL(HQNaA2C-G^WDd8tReU?iIBV-@w!!O+-W_DzKMzv)RaC2S~;1$dk%T5PQqR z5)Clrr6(73*d#%EP)Zb5799QGV`^81->6gng-JunO+e;z9g4M;YUburm5WH z$epLwevD*uRwFXvPlC<|kmoLx%F_E&>Ex!WYlI*~4OjpA_PmyU5y4R{h3Kq;fVrg$ zDXa>jvGOd!xtIP>F?{hAqGb%44^$bC8xEw(Ggi0P7u^|IeYkS!u=~ti*-(b1*boz3 z#ExAXNwt1jDouYc>{;h|XY%L1q_pL4y+l;gG~TQ}G;XbERtGVXYvPj8x{&a#9r(~yw+-Zry zGU++lLTHBv!3j8=t?nz@Izok9s}(lkpoy*W5W)XGU#re|Bl*9=ce3l0HOg?H6e^2?7o@J~0*K7{IaykriEAn0Lw?Ryn2y4jk zuQRg8XRH%qZ`}XPJl`Di?#W}4#`=9SNx}%8A%}pHR4pke7);2XYItT1XK1WoY>$Xz zw+ly25C<_KiK>#RYZ={=dPBBe*Ip6|@;%=Diw2>e<##H~Y9k(*!t_~R*)D5a;v2G-&ssn%c* z6$+G!+TGscJ7I_^o_3ML;J7XDF{aP4X zZnS3xcd`XMXK3^?C)oeyvZSU7jEme_QAy=bfb}RO1VwUgD;%^Mux$F2@jTjHLFHZ$ zJsto2)Ia^X~r8CHt?w|=-pyN~S3 zxhjfpG)+!4Wm$dT9B4es^ucSRE1y|y;JL*=E0cc{4*2}I96*` zUt!a=S9Du1#~`^-VcqmqrD*XFG8wbPO^w0|ivrT11!E!n<5n!-1o^C1!K$pf(n$xD zwXjOU;)&w(AZ;ZeoGtC%-hEcr_m1mvb?#J^S80>eG+fp9#RlzpuMEsaIr74SS;Y9@Bd z7mWgtCt|b68~1D7&D2pCsnH4xfr2bEIO69Srv0&Inv)WrP)9&ax78W59=%H}-7Ek5 z79pjAI#z`)H^w)V=0(quSBYCLMr!iIs~tpur4}`J=1*$66h7DjvP7vh?hfnJvQwkJ zG#-~jfsPpq`WALnbsna0von|49UT?D{6HMWPLq6A>Ao=*a~2P(KPH!kD)cGo^+Y3; zzjuQ?xtwuC$~Kxiq0i3MM$jI`rK@MmHjG7MezhZsm0H=cw^To3{WV(w#cbSI>Jf=wX~lz z0T)8kf*b!b!l^5|*$#zG7)xw~7%l?Sek0gVq4KQFN(DKhWAnKi>Dy@z3PDt_U zBPO8`Er;S?A$~4gkf$P$Z(mZAUBi^j?uvn(0{Vusfq+ZkEJS(_penIMOQ znN<>C;xw7&`Dn=aoU_d&Eu{g+j0bj`)sbsoh`AB0WdfzMh9^=tvRMM}$<|pia4kK=@gUMu4Ih6Jkvkt8n zt?(!ok7nIi5b9om43$OAJ6#awOpqy&fvLE3j{PHrSTyqZggpYHU=GZG1} z79^e9TM>JEGs4wpwr%tOv(+D#)e)e>Y9fo6B-q5C&2ar0N1uLKkIJ9W>P!8&ZF9UorNRKe5b+)x z`p!8sZB|6b8PP|PvMRM|XAnXHqBQ@9JfqbK2YDa24>Pr&npWEAWsI7;j#0xQ>r)RH zmun``ct#njmXTfXM@`hK{oZ{Pq^xe6J^EIpSIQaEcea}~{lf{JUrEeKBr2PtXR5H% ze_pTH2H`Iy`)nD5R#vcYBf57e1S5PB%pypy1*%x)A!o?gwrkYtl#}%yg;S%IVKO^> zYhql8OOoI#-?*Yz^h4nn$$ytx{p|)Iv*9A&USKb+a3Z=mv){o{q-%8u~Nve@W#&F3v#&@$Mq1MRlEn*dh-Tzt_+`Wra)L9iTw-cSZ`+lw>k zr;~{fM^p4@jtntnztrhwW6g~V%u^2s$JlrK;J4=AG2k1Lx645L!@zK7e*Mfg0tqEW z;kQK^^2Q39RQCtTFOW=$cbA`TBxSe6?KcC}v z)4%ev9^8;!{lyvP59cehEe=QVG#})&Vkg*O^OwCM?0$Edu_H&U7$J_CVYLmvM9pt0 zx>8%eHe^V>gKp{9i2Z^!u~Q|%8PYarGJKLJTpu$JkjALWm}|e@^5dT`ON5oq3l)RX z?;Zg;LmC=?99?=BV_B6WbJO=|mFz!axkz|jacF5PxRCp1%^`TbHbah~ofJL(iKJrf zuGvW0M?b903Y0JftOh-Ep31TJ6ylP58ta)THrg6l508nj_4qMD9;^weD{kmO%NV=t zk34&9|JlO-0=52c1X(aghW|#&^uCA?VrIt{7vJ7*UBp+JUs;{@3;w0m39wWVKG$XP#H})i*9)IM5Uit01*_q*Q)1(st1#G_oTe)W z_2qG8!*iYW6HJp;hj^UevLiG8m(HUjTQx7%{IxaNQSq~-S=&9a_?hKA*#~P+=jt~I z^>?7LO$@$}eh5!Xp1?(mp^d6Zy{cqV%cLToF^7%#Fvxm?TSyX$52zQJVLlO)tvjFV zT`Zd``B7wsb)#}`9)t+_tolQgkMm4kB8`t$sxMr*AY}4c;B&RVG;sH%`%Q-V&4L~2 zW9iEJaDQ`b6xYXCD_R%Y7I8;K)cW)rkDD_+uT5rexZOsW?2syZITC9@dHxUR5ByGK zfcC^bLQ{?78i=ygvDAD|mD^i%a*Fe?pzVe+5h#wqwU9tj^C+bek`;F@Pm%bDPG zVSv{KJYtYrDA_Sn={AcX7i#U)qbtwmwNrBC2+RU+5<&+G{+!TB3AL66yhDY$N?T>? z73EQDEtx!Z8%rr>Y+2@1#^AWin|IMEzJ+r(T|TE~|1jEz z?WR1Ta&$Y;2S%uCP5`eh?dNkLgoW$(G~yRqHUoH}hiY*V|f+AlxjJWy0hi1F1c(AV_RFF7RB#*K!iwB-o-|4@=ccHzg?K-*EoD@_Ru@BS0B+nZH^8S3%jVF|=eTb^ z)Z`Gb|5(v=`wIWPqza|(c`xR<@Mav8)b?N5JtB07S<}s4#^Ei+q==oyEVWI|M9_i& z2cL$!SX$SgW&gMsFok*rm=zfReZxg@9j*FMcodCbxaxx@(z$r9(4Db-BiyCdTj!XU zaqQiDxq1sUtMTchcZP;OHM0jZcl<(`^N#S*_BeRUc%Ez$8`vZzU;jkqot7d#Bv7Rk zrK$p%>;smKCW^0ocsCrNx)0XU*t0GJE_2KVATwHiCci4vXUPLQdU`-Y z$8T-lKMpcl+#70NaAuZRcy z?Pj65++JUdaJ{|r7<)GP&u0Ct@{ixa{!f8}OH3~NU4@5}5x>$ICC_|@hy)~;dV<($ zk%{GlF$|UGE9OAi3WqdlN=gD+NiCrk`$^XHoUJZR9T!hXPrcH&qnTOs*wLMN%|j+W zypkG0NCOtnA?#T2eE?xLnbxGM4P&O5qVf8GsgC?GdEcHb2U>>Phj_=>7I#EfMvTg? zc=44qd}N|#`X*OS(&HGVv2!u?aEey%ON*_rovQ0gw`kmW?`OXcRX5DXP=0dz#V&!p z)2lw6{k@IRGYtM#x{7OUcLXq4ESJNeiFrqUNlX2Qh(MG@wB0aWQ6?df#~aI%K@1U) zMZJcHMGPqdVG28E*LH3b(zMY2{a?l$%F2NecVPY*bWr(>Px0AZt~DvFS-5Q{rW4mE z@Ej=rK_}7cP}WaOa2Z)MOW*AfvqCGNpBFIj1$aRvwg3@Af(4dq9<${2Z(hu8Anb%h z!+NOH1y$o@hzK(W-3e{|CHQ1gp1u12m}(>Y|62m#_?ZDPB3MJtb@LPy#yGE2o+ec3 zN-Z^7>Ylory`L)@@x*>6o?k#zf@b~|+sQr~9F}g!Q?#sLz3u&Gm6q2y~qfYK_J;e%i0@_&fihbsn16ja|0w3xlSo2>=$8cK|%1#@3M0!>;O@K1dhl9+%7myrcC4 z@n2pjtkXbKWbCVUo4=D_T0}ks_cKn<$HniO3cMh27o=^|0;-url`SRQ*Uq36p>Q@I z;~7n0(=}qqa7*|%P{_I06`~Lo?n~lO`0Zu{{KTJAn{FX0a-KGC8*4W107%H+0;Xbk zOeeYG0HJW?6FdS6DMdm4=h?&}e@8*S(gaz7s#$&k2{L@5uLt+zWoH+!wLh=`;t#W~ zcdn^}nTaIEx;h8v!;DN;u-GG-ZMY4DRc~zNk6HLlne_%q%`VLEgutR^p&giE!=iHl zdq)EMD}ZI}*WtDTvDRp1us0ZmyYduBBQ^Z8#4A~_hBRC(Mo z0`VyqV(Tsc=WU@TGIHFAx$!5DjVczC#dr=5K=tfbk29WmAnl#_I!qul>%3mt_N zgb<6^STed_+Ohs^pd5M_7#OLaxX4rNW|(?CS_se|1_n?G*_%gtzJhRpK;XPY7>U<&KBV0Gl1OV{m`lYWmi)j9Y}9XBhrHv^fori2kkF z>qE~#N(Cm#p2Y93w&%Ol%YpYIb+c2Q+QQQ3W`fvUL1Qa^u2mLF%c#Gk2yeyNl&#qP zDdm+spX3PH#-OmjKIb#8$#kD+=K;_mw>XIkyrHr!Y`1T|#R3CPUm|7Uh;;|LsO6Of zszto6P7guNaW^>R0H5cI8Hl+1@rL=G2Q%igf+s40wRAH|G@>Ii9?d|{b)o3%(sK1` z>}N!>b$Kz;5EJj+99ppvKC&G!A7Qua)4;4%wa3x&65|UmMc%Li)CBCienN<3zTR<*#)7_=kA~oH_ z$QB4jkb0R6o*vEC^^39f3Gy+=0ebS@eYty>d-4*; zWk*^A68tl@p`lHD=Fd2>LM~BEDn$jxgT>HUohW#+o55xXfHsF>S32a@mVk{haj0-Q zWGj1?*iw}CNANZ@19qg!@*<1BQ`MWBj^pfT)KPY7`hcdoabipvNQa1%9aw@^sDEel zz*V&3{h4mFuOz;6Fwyb=F5Cd)AJPD)&ZyD+qRgLtFf&XkMOmouPcMMgVWJcIQYAxs zxzn^-Yp&*;-qZbffDdZ35n}YjNd!mXMeb5c5Am_Vxu{p;CJU+g_rXRu|F%L@_4GJX z=10WHn2SDelj^5@V={m_aK$8;cH*l3d21P2Ic6aiYqSg$;uO!*iRICJa1R|NCpc$1cN3mf?ha?FC(0^*x-ObGgSuYUf_g_akIK9r zJ)!~ZNbCO|f_$>g; z8pR^tdZYD^MiX3VLcPDhNuYhhSz6;l37pP`PRhGBx8hZ8NUHF6#t;VdpILqd1JpTl zO?{I<4C6h|+_a_a0c8Fp{x5G#HOjE^y7V;@dvmLh-gP{cp)frY+paQZpjfxOu%1}9F zT7;8rgs}-J%}#h;%-`^jPZT+PwHGO%ewZq`fYG9mFTFH#P^ETu;BKJgCWVUqUX-ZUN4!sq-b_seG<-E9Lhfq)!O^cp)N-r2xao3 znM;@{(S=`O^`PW>wQYJ+GSMRcyNAsLP3!Lxk7qgG5>1i=JqvS`Z@{v*lZx6%Vwg1c z#$Fl}c(O(p1HQA9^UygtH+r8|BMDG{T;lfMi7kx`eyP~#yd>Kfr3&DIz>ax+puq+c zzV)k!L11<=USJBv4UTQqm0}_@F|*y5ss?`H*vhjWM2b0foHvR(aW@x*H3gNu1WFRZ z+Qx_6^ajQb@z=SfiP-|=^1EH%E2cQG59UfLB_I^kN~#NhjL+xIc>{%?e5_GYtXo_$ z`K3O`GuMX9IgfYoliB!|}Cxlizxx zR2*Ww3tVpYW)$oY&Cw+xc(a~3XVUy?-NG(9>iu22_1Bn@HN$=&mTJOa?=8VW$;Yo1 zhD3`_zM<8BnDi~T+8`d6hCZHPuL&+E8!C|Ex4|dFw5#>EfCaqy+_zK7;FERX05Otv z^btUr85xB8Vv1*$8d2fX*7AxP|DSK{hk?1F1U#E!;_Zx8zzsl3oxhqX)kZrs<&NmD zr`ZoiDv#E8S05$hA!Sc)@gEN!-i7l;zfwLfHp168i#t?h-$1=6X(Wul{{Layvb4nb zDRna$rtyw-hB-ZVB0oR+lf}tQm)=Y^>3%Z_-VTAGB7?wMOoZl{vJG4xD1j*6;Z!F= z5{%3{otsl4udx$Xn9EoIBbWEGy#plUz_e3TQ%^l7$*tyI9p!z+r?ND&@nXmKPiQIS zVEs_7l5RWikdFijqlClQORn2doT5UyD)}pb%*~~boaocRc_@U4K~8%QuNuj&C*OqU zA-^#zk)XX3=yOd~{hCM4F$~kjLZ^-0y+0{0ahqqCW11zyNb#l(o>`K)4l!<2dPDljNBg1@m!2zQp2hdE+pDAo#5k{q{)kS9oP zWGL=Dp^fzETRn=1HS-CD^X3N6FUvoB)cC{6EWR0 zgs~H>e|#aVX1nM1k|P)mIm8a9}A8|+( z{m2JjzvDP|wKK@Dw4KA-Wzb4gB9m#~sn&vD(00E0JaG!$SBgBAYG$hh{F9APE zXZz!#Ru0WX&Cy>?ZPoZ3KvG!|2@nDGz@Tu#{<@Wab|>QxxB;H}n24TrpnpO|n%34q9Sbvj627F@>Auob&o z)6kHcGhaW!_V>AT6m^E%^w?Ki)i-~WrKz{h<^#Vxy56;s7FtNLQC!KuT<-9z&^3MP zQgImjdc@PCFLiL$4;kxkmlOWr|KZyzui{9~ilURX62m;E((P`8nNt!CXC;AFVJt~d zH2^7dJrJoAw$ovvZu^vEtf?%SQ@pnvQg^(pf`JwB( zQ-U!BQW9tqL%jSZHXy=b$A1Ko%_;=f4v}?DAFn%1{|zthp-RZL9O6&ATxBHaJW6S9 zTq=<9#XuZ!?67}epjJc;y*h{@&mYYZ1pjNE%R`Wyvp^I!&v!)B`syIv$ezJ_k>3W| z!1%xvzAK?qS9~EdB)Yr(VJS}oL&vv0vW_sG&b*@uZLZrhi1|J%0hCLN|AV)846?21 z(zQ#wY}>YN+qTVJwr$(CZSSgGwr$(^>Uq0Q#~X3FBff}p;^eQzoNLXTGcw1O_dP~I zX)2jz{4Il>xKwJ!y72AFSg8T|-K~*P$f|@OV5KxUw$X+6^&P=;EjN5@7 zdT=tDhIp7-;T@P#-IX%3tXu^IO@o8;K4})hCIa#S5J^}P2*jahO#dXF4J>WyBE`#)@|h7&5< z)A)I?qR$LMGu4h}%oJAf*S{nIt+cGj0nlr628X2q;0@@>BUDU(q6x_EM5d}?sy4Sn ziY*Bh(EdZ^Hpe$cc}f64!0(Tb?#q1l_MTB^Pja!>IU zR?Ly5e}^j?FCr3o+Ncp8VPVN~fvA;~T<;w;<+&_WFh4mDhrO9;{Cysrkt}=}qia!U zB@7D?xWH)MbSzV(XwG*FV>1xBIW~rRBLUVjOi?#b5Nnj9QPIHP%;s#owla%d?F4@m zs)nTQ5Fn6@#mq_acxK(4LD8pn=bD+>k=1Zk4-^y^o;HR=Vv>=XOWE3uH$^Ru`T5Bd z&ioe!GSln>wnb_g2n0x;%T1mWV*|+ww>0?pSG3+5O9RO!_$1~=$CAS2ABQA`j~Dr< zQ^scCX*u&^a{Be?MxuKpRED~uAAfQ*U1cbXXRQ&t+^MO+oGI2S_A5Hf2!)^V8+B)3AWNXoS{W4*S+59WclBm>z1|vm-IP+wrX$$< zTKb|cW+?RStZj3EFq93ztSRow6PFc?Ne2_`^a_>fg$b!e z1ej3xJjYq#t!6t*Y6-a&AYHH(Fn?U7ywF&}$${i&UdeOfFcWuBbNJF`Zor`|SiKQZ zf3<*DmhWpGB)nK>N7%G_A5cgP9vXr!%LZ2HP9kBt z6!OJaHO%(tJj@q8hd?5A7N3#?7%e5zgxiXWHKG=RDw*_Yj)59$9L+U8+SHUK9Y zXlo*0-OojCqw40KeClWP3b0~4ihsB9Ya^daa6NW#T<@)43y|C!%y9Ed1${mr)9V6R zywj}W9x|UK?=LX`AgztB;Lsby$(yXjO4zdl884LPu_AcQI`krUgo9OcKlC=pEvra0BbDa9yIG9_t#YdI_;rGT|$ZWexqi2Q5EWLHo%pRfpnt2)TQDn10-GH z%=Shb`6~^|75J%5qpb8^VLe#Q12kK)33kdl@05e!o9E4f`#DQVYu)p7EZ_LE?jjQo zJnv{Xpm+sX5>T&TKmt_kOxGC-@GVf-fN_V32*%J1+2F>`c2bxEF6WtQsd#t-# zbIBThcqzUpW;AhQ?Qb6@Pf8G&z+TSDy+ehJIK)DC76v=y#KDu`>XSSGl$dKr#}Qxs zhA3$SZtnwPC3LyURyMQXu&iu!4R3PRQnUxtynySz#h+}n`m_B`0Q!Wg&()!~U{JEa z@}V)qDF)voE6aX{Ne=IOSN5L2`n_+juN4}PpoQ-N_YxcP$!F1!LRH<+S6Fghe(KKB z3P=k;WI%#By}6@#;GRbG$;tK44P&T^k7RR={Rsi}zkU|+{`^ZF{STe#&)m;Si{MHn zLP%Gwb5z{?>k&c>MwDQuCu(f$;_ti2PR3I&IgmMet|cmT;cZ+t=fEfNt951y{d*p| zE0c~S2E(BZ6(by|7gxS$$F?I38VXMtrY%~E&B%dE3z(~S&3wg(xd-DF)_9wk=>ABF z`?$y==$ESq^-F9t1+ooRm3VU9o=BFIy=d>H#);aHEgJN8S6F2?W`xFwnt#m~a#nce z-9m4r)wFPvgDHZUMu>N<(e6Kl1^f;T>mLfkSc?-Jll649`QC65_YbL}ihG|#6Uv{W zASB!)N&gq+alwDiqze(uo=4O3y8X|O75*g6rTc+92R`>0W0gNHM zGA{c+vCe4bPYwx3g1xQb?iF7`#AhC@0yUmzLpLLY)~DLOkk8b(i*2mJ^<>Je3Z#E^ zLKoHQb&wRnC&nVQo-;^qGMWuUOaMuU^j`WnI8(oEa2x+(h-*83r_FhQdWzZORVPE0o*|a)yGgt)R8X`+;lA2oMTT9r?p6RAujnbT1v+jI7?D6dkP~ zS+U=6%@cU*Ix_=twE14S6zJIckyVwM3?>uiP16+qe^hV`=m5kc`^r#x>W6CZdcLbM zs-~v;%?dRON*DE3R!TvTV=n2BW9zZy;u0!^2Z=N<`*G~(kJ%Orv5Zsek4`AhzkA*|C8MP$fINka%& zP$g$y4vhdbz9qrNIX2>mqC13)3aX$v3FK z6XU$R+4(O?R)HbHe5rbECw^ zqT^{}D0xM?zn!QdVl~YA_Xuv_lDrK4KJ_n1bPI`KW0|b^kfOJtABBCw zAqis;=@<9kxzFm4KCS7yLRhBH_+I0?iD%~%Rd;4r8|-n!j*P6Ivz*IvH}}Bl1o@ie zdCfOGo&}7pF!!TxCPUGPC~(U#9$`A;fLPG%oS7U;IMW{1%KZs^$>NPUW4&+%@4Y13 zID`4YB|BVohtcDc5K|hftNFnx*HR!279|0lnyrT1U5OJAky>GkYDMuuc(NtIX8vl5 z00LE?P3@5EBbo9FOr_gtEN&E8S2WlcMOMd10>-kF-7fuhu~$-rPinHiFU-ySl?+s7 zZ##O(KnUd`YrM3?>(uB{qGsXy)}f(D;wSIn!0(0`tyWT(ff+>UR~UmKE*Yh_5@iZh zcK1!)YJeh`2vC+%k7s_pOUcgx1LDpXKxk~TelObR7rldN zrH_kUN9Q${%K5=vHvd2`b%zZF)M_YdA|fT^*yqf>M~kX*2BSR!CFbS%X>KgSgJJ8lLP$K^d}#6^#Y4L^jr&>MgVIw4C=lc%d21 zIoBFmjgKFZUCC)`MKSZtpmp$7RENpZo0E_U(CQeKv=!c_Sl0SMq73A`FPt3V5tf++u z>eS~4(-V&gq_(K&(JR8fA%d7z8|SgomMVMyq6EL9HFnO^%Axfolvy+fcLgke+cNtH z;}cFAFu=USvn?cu85{fYdHZCRj{Y$FM!09w^IkXK&E|$x8M7g_=E`AatJG%XEwEa_ zLF@hO^z)bn`+hOc3YJx{-^eF}`>Tua$14#hgw<^ADSp+o%($T@>p~4H`m^># z?#c^@m~>;eg-ehEgm0d|2pN0f_^|>L7H9A4sFx%U1;4O`-o*q{6o$2Io3~Sm4*xhR z9^|eyI5&&4MH0whEQLr6Z&7ZMH;0GA87fGGZf~$psx8YER_&?CZz9oTtA_DyQ6#R0 zx+qwc=NEKv00!U$UWEz$6Qo{|5lR3-o5k)3a{}&*NLO3@5`fpoc>=D9@Jm7tE+giE zk{3O47SMUO62{()f67~2V#?GtN)GLB7SXn^8RWh!@6)Mz z?_`74<4FeU*vUG0@`>@?1N7VdD+oLoR5Ka?K8{%FSd~B9|Mi{6#w2Rn8K7srbSE_U z+`(zz3HsyS^+L}bND3<)9)h1o7Y zU5)C^q~V7o^feEX=lq3&;~(RPT7y8TpUoXbx4A(hDVLLwjD0wx=XB>6n^T&Lu+%)t zO;j98v_TdKcNQ`MkC+YTXjLQ1Y;#Wa8S^{@0P%#eTd9Jv(+aQI-)>?_(|l>l$%0|- z0@=V;9wQ2M2M4tep&Bb`ssujO0**B`1`v=ILiIELp?hyGHSd zFXY2XJ|>$&1P;)>c}5rZ4rAPNI;{h&S>___PEVh*kHGiInQE3j<($ zvV*6WGIh3>dM`Dq)o6EuUr|#M0R*Gq{DDQERtUIMK$Ln(R7QZ!YAni(?+{vyPljU& z;!PMAkqiHToV6yoL&+HUsAq&sB)=LY)tzn!wp+({{D*Di!07W>{8E`;K_F#yyH2co zOx!cOiT-8g)d0{EVG+N&x+CaSc0=Oy*~p*8_Rr2ZR+xB0V@YNk0@)*;N`&z-_ruGP$BUdaM7kl1u9Mf`_28zJQ$2< zRaW7ZXCPOSv;B~N;wSqDE_-Fby+HGg@u#5HL#XzD7OcF;xQhziL4Z^)S7Mf_rgb3r zy4%s43LeTBSjt_n+WCF}z|f!o@a79d_`eKkhTjPwj)p4O)x;!W(6MexW~(UM(PWf36|je z5d9eLxCuq5f|8sl-8!NHkbl9+=VY2mh5?Y5(VXs`3Q8qY-1b#$QR}iM7-Pak*NA)f z1c7%8;^*Z_Ws-DJWCXmMFne&ifz=7d@nt^(5tM28d{AJL-%Xv>JWTM^=G7M@HsVY! z0y$sP8Vk;r(=h91PnW>9yI9(sob3u)Mc;@E2HoCavo=g`isctZHzL_QP*Pra*c*{b zV7k3ULbgNTX?8qmj~*QGtxQS?fJ15~ft!4a!eE>g7Xpy*gkHF(F~=h?M3E$y9DoR@ zCC=BNGD(w@*qeBIQUX9yN_Duk&rkK>s1+fnz#II<&1?`iW%BZ)LV-75v;l4uH@!X) zL;I=a=6XCrouG*53JaB|3IOPD2?fTvuBBKg-#G3XPc2##{xe7j+!!ltcW1FM=7luF zPfA}qH8xNjRT(tRUxOI&l8RlECOACiNG}Mk#R(G}{lWX+qr+G(^oG~8wz_XLohglZ zYo&axB*!j(a4x^aEnqG!y@vE!FZVjG*BgqKVq}i=e2FOtoNdrFtt@YRhfe}?#KYqD z+Dj_2RGyk&SI>mFonKsiRR6|wH00jOhm>ohsY&k~1pC^*=YU^r+(7Z!sbqNA;PY|B z-2$CW4mA#Efv{*xxeLT+1z|J61-ZP!X8K@3>yZGY6}~NV)p={${e<{1`+?GBn*lRt zjVddRRb1RCe&%%or@yD-_GGmY;$PNuk2S zG32?x3Op#Jj8TcG3#b?2dare2rq@CWg4|gV4Ur7$>_dIcftg_$+`Wpg`K#7@A&oed z17ov+ES{xJ%HcJEI;4T*^9RC$(;j_flA09yH?|;5muMJlCZA7q2f@~Yl)}Kb10Bay zZy+jy>-3L9?GWEGgc!;yP=P>Jm~s4UNg_461AsZFG{foEK>Ag3gM(I(%{Qp=NqX}h zDL}A-WYz<5nBMXYIMhyH#>AzO^sliXecuTU-G8FZ>2Sni(5k)=i2SgOS)A*ZFOYTW z?a>68M1|3TCNPV)P=K^200y&VeZy^5bMz%-9Z}km%ZOY^$>&cBfVLj zUJN45-bma=+k!JTthxu_TrVO_1U5Py(UK{!;>}#5YJPj+b$2cL+Cao}(BOQ_Pk|NV zS3p(U48JoEfIt0#oyYa3onPkbWq@0kte};N75n!v>o=2JZ@wC4uM;aRHdt6}wjX~+ z$ebj8yX57nDSaT@MdM-_)wjLQn@WA>5=Ou$OYU58K2)qBNEvm}6Mt}_CD0U}=w?1?NQ?sjOS0obbVPFs6ziFFaxrA46%!qhpV{qb5ck%o{QEC`3c-J` zIZ0+k4ud2pd?GYmnEx927)knHT7Vkiot54=rYDoNe*_};rbPcQ1Ss#?VQsDsbWgcq zL*COVCo0q3=v(ST)t^*#2Hzya@6RJAF2%b26-ajQUVfEe&wDGuSanrw@H8K~hBn=K zR!pzltlvF2zB(*Ig}1;8gI#&uIi)l|hfhxHhtIg{Zv8%f2#NdR;^boQBP-+a z>AEo|%XBfM8YonFgU z4Pz?*)vb*1Oe9(u(F`ezXFbYiHrD_6SU6kIMMeFS7UHHd67C3Fs6Sxkl%1m)Fe}NU zNjK-s-fATIF>U4%C#iugaA^afc>6Sj!c*_!Z`VbZE|hSXVZYr4s}0%iaxL#b>AcU# zpNjAD9Zv%I0`l&HW+)TmEoEY1nv)Pzqu4&989MdvbvAIRw_lrDF~eUE0WQ7%!J8So ziGd{ahL3>Qua1xdh(`rR_x0>)Tm}TXpMcq#UcrtiyrUgLqxDukXynT<{P(dfd;LbG zQhW>$)m(IgI-iAzei-kgc^b#LadXzBF4(J)#ev!NW<#AP^(RM0QzT&VP@IK}4}awk zpOK}9S|D=uRYYl`vU)+!QDa0Wo1)P-eaL-$;~Tk#5wVzccc!mH8HSdlTTFjY1gaB- zQf_xI-0@_V7g)r9M@vk3xe=~|O->V4Zo+4UZr1v~oB0&TU5>qN7L%H+?p&S$tWpW@WLvGuB{$>^N`*sp=tr*iX`gJ2Yn`}k#N$Af? zMwXLn4l0^kxS+V73$dEt({9vyg-KVo`gVGBEjmtNe9Q~8_1CN!xZ%>aKHL5o5qftM zgP)0QC5=2R`H3&jLWc_BWAD5sbz0uCJS|z-G)~sd7Xm#ECQQD|x$V_-*($o&nDM^n zj!Rm!(bY^Xy ztS|IQ(;wdHXFH3WDU$vg@0eKr`b5ar*Y_>eW{@NGo`Vcr+1%#jqt50;!};zPW_m4j zK!7F{7^nKV`K%!WQgOkh%G%SrT3}!f%He}(=~6NMBE-Vo&5k; z9SxTi+AXx}-#&#OQ>TEbtxHNuuB>*vUdL$eCX&vU)SQkswr2R7I-^%xTNiJh(8E>E z7k6!r9w6Zky)Ajg8ah)Elvn(Fr;jP4OtR;zdGihCLqo&+A6+T-sL)}$tblx9 z({5{MkoRydHb2=;=AmhRYFwk&8mzZS!Nr#RL|9z_Z#(}H3D)BI$9+A+Q6d5^R#F% zl6E!-@$ks*?WpXb8WIaOQk}sPP*#^6NRjlAUW6cF*u{l4ykE^$s``Tkg!MIQlqC*W zq1`;aG^1Bg^1Rl7C;$M00w3JSaciehf9s@J?)|sj_IO6z3G1Q(=vc) zH2VueK$^mle0WAINy^zKO=RyraJ|o5i52NYCy>C5_63y=zv}J9%vf>h-y*& zuU(Ktp+DT=L}t+VOb+JC948=vkfpNfC}ewD9CYfSsws?u>LB6 z1{45upTfive!CY4S>j~+U18-c)%f5*Rf9f#DhP221@J2N#1F6VRq&eK)XD%wo(^ql zd97-KrAlanw0-41R0~ZCeQt+h%ulp|qQIp_%a^5HW!w%nM1*j7A_X92RIUQG@KWFb zD3s3^LHH>6B-n$qR=+lG_x_n%(4s|*q&2@#D0R@I<;8FoFrnO*-+?+4LD)Ok(>c$x zgoQ;$1obX?oNCX3it_}|(wo(>abbu6Mr!-ZYH14}lj`MOi3K6H1$uW%uPCd`&w-_y zF*!%|owS?~60)JP7WmI{AYQD^P^4cu#tb8#J0aD~B(0Lb_Cc*s3e=6+Z61D;#z{_?OIsU5o6Vyb7G#AOMU7X8L# zZELazAq^(u;chVwwJqcLqIb#F2;ENE8i;X&sF<^v&Hv4yofxO)h*)$i?mBDEQZg4_ z68I|`6cf;oI32r}I3ufO9E~Q_RrvJ-7(j(0C=G4#6cSD*DS}zvPqoq?z%L=F^uYZf zr^>uDi8iqQs}9UmEED> zHyjPW;v3Hefbq`Mkf1b7rEH%}CUiUAmcep~sg*pbCW$2yBYKur$5 zUU;q`zuNiTcTg1(iIc85K(oCk@$s>46(D9jJ^90-%anmY#Kof`Mu1gAo&Q~AG&vjw zEH-L%Cv*%#&drstcRyWk_9!8Zg%j?i5DlrbEmXV*ovFN3*DMbZe%ofx3#%vt2QCUM zycmh$SUw(-7ogf#a{*GM&N3WYxb0sE36Cedui8S^MH9*HKY-Y>Bnkd!B-#-zZh*0_ z5D>KDd$FvJ-G$+h7T2w5=tNI*e_rBzmaU1$ryIln5h46!yYLTHU#}+l1u|Nky&;JY z&nnbD6#^M*?T7_Yo_$T!jH2XD!}vpfvm4g39Xdd#;Xk)Bp}d>2*dron)k-^FxlTqu zqMw^Ln~T_~f{FFad@havlolMG`Zm<4m|l&L%Ou4KP8CpG^q=|T`2AU+9`{1Ren7i? z)jBlhGNw~<+8D%d_w>K3;qi-Ngy)r?Y0KTv%m8U!NJQ%~L&G6b2)B6bqyWPcOP=U% zpud_)bhvfQ%Nc(~R-aAonGi{o+|HatEF4RP%}{{=L3T803}hBi+-QpymIk^4P=UP8 zYtX?5WE_s>7WflhS6xX?Z`?y-QgL#u&uY`iKVJ!wa_6im0*qANuPzWQ%T~ka@MxP? zBj7?9V$n?-5WR1BBXh2?bIpp@77WyYv6&_m`Iq*V#bK#0&ov)&l9GM*+sZ-;%Fh%C zlb^F${*kA{`9*%pVLUxp6do03KwZvELI(b`mFd!))-OQePqn^&40`#4D-UJ4-d(ig z71afUXgsaQ3DYNU0Be-_^Hf@4CJ58J3-NT2^Yk~fu^PoCB{n#y{WJkVKq_dkPps`E zq6H@@w?!IGw2|VMO&2F+TxMrRCL?QDbuW5}IsrWYfc@1}0Fys`hk!#%a(JoR5LqQ* zwDh2{Y-)LUpqkEWxN4FI51LB^b~QykUz=#}vv97$BNbj*O+O|TR&ShYf|?+p*!+&h zv5~oywa|%9l*NizOffdTyEoR~{!_`vnit)Iye{_|*x5pJP-oe)@CIilOet~8n(F+J zC$l5Akt~^jh_}K0w-6z-{ovidN>5O((eL?HYhiFfWrWsB3alAy`_qF4E{9_jY5lm~ zE{>%6aP(GKApG~-J_G`B%W`*}^Kz ze$!{E+nMs#HS_fLPmvhZy~gFtaI;7b2+OvVy8uEC2o6(R@XI?K)=yUSlD0OE3g2$v z_0mVt?71a+-akQWG~m^|TERSjI|h{i!$7f;Xpf;Ot|+H+BSl+;M3}L9z^V9P0w5vV zT-1ZSvB(NMZS>eJ8{*Q^0Gl20D^eSTO&LrLlZxMVpS%CwYOKpA(NBvCS`$K}Ufsai z_>B;haA^JC;fPB9|Gzn++}i)h5%;_lEBVL1diBRfqZLLJf*;!0jn&x&?8Luaw|P-4 z(BciQg5l**uEccuR;l3hHAta9ebpoF&dwvac>wrv!gjG-jQZn7z@6aZQb_wK>KH<( zSE6ACf%8G}S6YUXND61Wx}Y8kaI!X%hApKS8G{Rj%K?ATlOTD4sncj@HD5pL-{*Sc zdEkh+sZ0e;#V1J@Ji1JQn<-s~zV?waWdaaoJm)

al zc{iPD7#_IEDsurMEI9#Ya_GJHLdgml#J*e(k(KF z3!>HcI=aE71^lE3h)wsl0;(2dP(a#p9`mQFmA|uEWMkgBufZUK*LDxf78X0M6)jq^ z?gw&IX}$i5zSq+v_eIBR!{2!SOQXzund$r&+x5$UVKR5T-Q1vou@S6EU-s_-)Q%5V z^mtTH3^KZr9@3{je?GXj2#<}2UN18pC@3&e+3W@}ULlfSYvF4Ro{#3m#oNPmd~t>D zsPs0+!kF|_1F}2$ETc9elGJQtp^MNbAm#<(g93ad;h?vOpfpfNw3w?)1y0)01$6za-eso zb{KtxIFuEG;+ya4D(FhL(?_uVMx@(I)rFBCo5pcD!Ype}v4?>c%BA3Pp!xOS5pQb9xYL2i4ox zSB)nNbaI3VVXKZ{%z>?&smNz=4YHf8dHMZ`VtjOI%pJ>tLz$n{h|**UGjZW9-~8!j z-4m}y5uD0)yoQIq$Ow+R#A!Zhy?dth%R5DkPq}`gs{wX@O(i6?8J1IuEy;=#x;Mu? zPR^DaV)W=iBzx{@#%f{*@qxjm2(>pf!M0{N?1)9aMpzdkTfSr#-iz&!s0sYZFIg4L zYFg5q%>eA`VA2jnc|e~^E^ojD)J;*a<$GH3$5(4o5j!I)$2u}Uv!>n z7R>aHmtp(f4rnF1eTfRN4^|6N&&$}Po$7we!CnDC!62J!}TxF{va!3RXN6bq_1D+1_TVmfT$gcl7BRRf<^B7h6XmCgY^G^i^0@mF>*xs{8ztHvuZ zStpXIaVvaprexB3-{0b)N4ya&k$|AcI>OE>NDAxN{utQmBa&jt+j1B?fC(l|n zG(Z+fK(2MLq_J9Sf1jD&&V1rb%&2hR)aX)Gb|1FN(pZlI0D$t3grd*^ zG;#V}+?_t)#LX{YBO>O>L84c(=qk@9fO#Y(l#h0*2qNH-Sb%I1 z5kMG02u`^}76EA}P={X@MlPx1aV_F;%@fTph=16<`TiLX04NA)xV_E60rqscmEP`Y zc6Bwe*`9D~We4#D9ygnqiAevOQ9rj~-U`z8X0cgau=VCcs5aN_EV*U)5DBO|nNZ zR&*rQymKCF92CZ1m%T8q^I8bm^N;<6Ibtc0`V@b`b1EeC+5xy`p6))8f%u_FVdLOmrAnUB!HnK`@cw41s zCRCO#TZ z^e)uP82?R z@6oebC#hDeGfb(GjyS)}eeT=vN-pCGYlVDsA4BsM1AdgZ{Ii|Ia8lHmXqK*S>~Nts};fVH4&|Iyq9=aZCMW zRfzW1&`=G^t?NB8J#*IFBx&6=U_r6NVTS%hZFh;}Pq~$l^h#=X(u_JVPKJ;5%_4F? z7yoK4+5Cd|t~@xB3CIYJD6^Def`Z>?D-;V4-WQw&0R(=boUB930P0ohFwZ>zhLpP5 zmcvo_r$r^k1SN*bm6!p5yKBRd+9;6L_t~xe*_JGS4S|}9+!C5R;{fx9>#d!v3c7S| zA!r5MR%@jB3IntcC384>pkH|81I3BLh~i%&F^lZX_G_qzcElQUY$!}Y9nHZy*lvgL z(=S$Du+rNf4H^wWq=z-<^JADI*xB2T^>HPLd_$`(j#umVxhX{@TTi8(Tf1Z%9QTgV zERc`(#rPUKVcyaK0IK*b1#*+Ki^U=R_U4Q8akD&D1lMa@ho+Bh&erAXW{yi)5tviDL z3hl^B&+eT3zqA0T`-2X6H>*`F)bCF8e|^;_Ml(_G7I?gXi_~q@kpW<2u&r^{6H`rb zM$|iajC3u<#wLopUN@AV1fCAmeJ(HI`S;MQmr>CEIvne#1G`_ElVV%1IMA-N zXk`^sY8>2^iEqMuAV2&K2ANJ+c5%lRb~G~<9MEsh-yic?BUKj=7QeSy+NductOe>Y zd?fawcjLZ~CxEb>#eAXhqjYU@VU?mQ(}yHt9YJw?#Z-1sjf+~8&h-g{W=2evGuo0s zk=|9V-V5CmC#9vzs3|n9yL}NTX?hTJ$THf>k}+;iD*fFAL7W(5HGINujBGR#WiVky zH`95|k4vNE#79ZtP=snVOr=+K@TY$D0i2~kM|(I+1uZg;Wm#4gwNJ%mQnyb4483by zo^_}{oTyZu0e-;=U&zBX-!W7Z`L7N7YjY|zBGQENC09)D&!)?Yf}l22Hz0b*URq~{xI+O^XG;ppI?{q|3ApGtwtRxUA18j>mORQRQchr2PR zyLm$xj7Dxoq`Xh=rCloyUrS2v)%FhX{6al~KEu4w?Q7qeyD2l}fpAS;`tH~z7$ZSb2Dg_(5huwU zR}Ap$4(W4h3fBw?=LR>6YZ8EyQjD@%cK<&$c*!2L&igsB*a99KIk z!_Jxj80+wzM+7)Cd8MLW9XVMk*CkJJla%?KImf2`f@1s0w8p?K8Q%+th+L~4m1fk2 zKnl6a00Egvv+Vss9`lu)Jw|rF-W;zB82IM53rX3Ty{ZY&2;&3BR{9<(fzMWA5)3#o z^M^x^)E7~y1*Gl0cf3IaG3#0cVR{v=cDibAc7Lm)Nd!iJ&%Q5nxneG9?1RBsJfZ9( zCei7qCEUOyrdiLqAO)YE7g6W^pnE^|R<^;W)X^C{CK<1VgqwpeP-V|R1#(^T>2%!` zfxA=2&s3?3i%p-lcBQ}lj1Y_L+D}r1qvYuAWlgD(9QX*an?LH&@iQf!H2=x;2)o@-XOuUC;iK^T4LtGT&LQ^x9}m_eRc;!@*F?yr_4b;VG5@GDnLs*@NZ%WK6q%84Ag zasDj$0g{iIN`)(Ux8BbEHa&EV(D@H(znaRL3k(9!QQ`eS#k?lU}e?Y+}W6DD9xzLU#QC$kBl&gb)0N?f=%EPe(0Eolne znzvuE*E7|s>`Oy9Rhk_MJgJ)ywd$#&$w2e~C6aVZMv{EE)Q2$TXyOxh1Djbf6>f7U zpUKqeGqEG}0_>}FjtnyWWDS@Kyd73=T68@g{t|(#4MR=o_~NxE==%x?f%#qhD`y1J`)ZsMXKc$1&zSIN5v=Rc;(Uj3PB+ z*?Q~mF$<0gAVx*dt7(s^sxqZF8$6nFWPDd8t-e#R2pWIg>W}zQwI|QV`h<? zAJ?Y%Nx26>eb2wpHQnOz6I`(V-IZ}l2A_+`I^56zlLf42w%rPiFU-xq;42M1JK0c! zG!##Z`8L;B|vsq=@PTbsRx`p6t0M#cWQvM z`fK#Jhsdtmejr%0uQ4p9HMU#XP*(0GUt&Jop1(Qpr&?~60^qm;kLb<2XL$0Vk6nu` zFtL1}n0z=Y0tp(NMVMbX22C&KbieE@X^o4sOunB6i9aKsnipng+qpU%=L90PrUzh- zC8F1d2Aa*jUzj1!7*wfOBn-zbQob9416UQOG#UI7c=Lx?F$YJwS|Jx^Up)yWs(h~* zDndK<5BB7w=h0qo&9}572+&p^P8*vl5JOTEQOvd#7fxAYR3KVQ`v0(h@C0TG?;r04 zd7c0}VfF4VB?&IW-hD<+QlK3~EFMXiH;Z9(ziec$C!1s&ZJN=|HygMMdUuz7J_#uE z*Iewbr*bJaCecl)l66Tc7k-AlW_8>mmpj*ety=k7|0t#isL{lUwBvefRwB$=9CxlHJN)Y&37;y z-*3Y933{vb?LS%hJAwC!xTz`7x8z#x`To#jIP9ZRsD16gjdUq8GW#nE>j@I4LDJs* zsPKiHe~mJv<)Yu|+NbN@+i}Cyci^v(*6g4+*S$w-Umr?J&rH-6)cD=o!67r9OY$Th zoT2=?n8Q|22wFjdXDe~FzVQ0!%iLC4k6cvI@rk`4k)-jncV%3PMu2Q#>3vDBy~|=K zG}d~suD_?on>0EoGBw7j`Z@Qgn2_XNLPu(PVJK5wVE7yuZ^1ZB3<&qx5EeTk4mk;(5 zmWyRJ?+~x9NmUaithW#pufrMcuBdQ|Js|!+-tICuj^;rVyd{glVzQW-nVFdxEoQKo znVHosW@ctt%*@QpvRGQZb2A$gF*|Yp-HY4&R@E8VU6GZY-M@G$6QNd1hqT6;+5KiH zKf%3ol)O8ckCljYdV`ECQI;oCHSTcAm-@BZ^wWpfIiy$B>wTl&(jnfDN!ED#o;N{F z1*>(=ZuxO|2$xD)(wDt9ZG3khmuz7zHtw0c-uC!yY*V(tLk1f9-UTgkgbHtw-50~xMsjFBhvm2GPYQS(#-=KO|hg&`s$ZWc3+Omlz2R-1ACPt4*<&=w#v)NHGpw7SBhs`oQD{*ejb0~Q5?5_yk=0tYp0#{AIR7j^+6TDwBClA*0A1JhO!1ao zN39NMch_E*u=frx3MNh|=u%d1KWg(HBijqdDUA5YMJw?9kirJqooNcB*V zTB!hHD(I=eJzKskBW8*KqolY=<^v#A9;pxYMF*-NW4OAAiF=Mz1DHE|y!@2a7cC9w zze*Q~BB7Gs(4*1j;*lvT^ml%Macblst8y~tR%r;JCe}ZJJ%^V|wlbz+>3R<=Es(&3 z?dphc@&kz(+}j%d-Y4bMNQ6f~A({meQJ{z8*6N-ojMY*^Xso}J_RM9_{!!7=)5un2 z!D`J+^pM#sKO@{E+)?79lJT;Z`kSNen}?%px6nGkOOQI5S-98^>E!r{T5*T%San7^ zP2TQ9vHN!$jB`JZ2biea1W!+G3a$tYByI9=ro_LbF3i#;1vkS`I_OU_-L(-=fZIJs zq2QZb@#t=M8tv{lo0Md1la@H42#<(Ji3m)UC<-%vTh$KW1tn=vNfLo*50?~V2pLtD zp1Z9HC%9?C5&>aEKcj_J77<}-?YIRGcOG2~?>!_1@wwbZ{Qy>symYda-s$iDbx`L0 z=$fzPkY2;0WS6hAi_e`gh4!#K(S`ItLYk=>X`N6mkPZSQ;kVHp334c-KiptArSH^j z_}tA)>o+5lOM5?GH&EqeCB^>aij6ulj;VMl;R=pMSy+lc0136V)8itp|sgqaG#!<7AovKoSaB~kSQL}Uw+wMH{>$} z4epo?{PIBR|6>od0PuR|IO8O^T55R zZ8-O*Nqod0Zx{(88pCC}a>CI+D;pjep(0c>yd89BemHQjjI<>Xn91QJM(10Fs|wOM z4~{uJs14nkB#=4U)ORTT!+XcM+KyRrF!aQ(yF#JDXspDdyK>oaf4YAp)RBpNarc(a zr0~%yspc}bN)$m#8_IqVRq*VyEGORVNhmc@p49AavD0LDO0M>~`{ve4rjAH20f?@t zWI#rxetRdPyy#zCCMI$Ic=>m#@Uk$SXUR5?gU7=pUw3w3qBwiHt7nz;e*<){xNL+8 z&QH9hR?1+)e)qaS$~?Tp8)ut51H{im{Lw7xjIa_%R#sV@?lm&!59xJ2TT>exqWD8Z zcMo?u_JXV=gj3D_#TRVJ&Pd?6zDH!YBocVw6PufMlitX)pma*Lmd3#B_AgFAIkoB6 zw;0GFrn`w%6K~Pgrx2GoSEP37;H}7Kj8ZSXQkxuq(jJ^D=bfT=Eth(VPvX(o>IJvS zS@mAwuOQWq47n5(_Wf0pxoOPWpQwTkiB!TVTZ~qDr1GhYRbq;$qA~+(qh^qov`7~l zz&TzBk^hfIX#VZLBSLvJ=XAZ^W)FBNfItJPQk6Lc-$E&p1=vi>?;GTw_BK~6FAFe( z6C2sPJ4o|5wf-_7lI?vL&pW8#_GJPS5p)#hB%~y0nuE^!w`624m0{fga{t_&BwIFr z?;nV?(bP+~EfP059+h=z-)ISAM52XG-ik=Rs{ybWw&!w)WdowNIYu_WTe#0pN=>j$ zK(oNyFmo$2<>B#e0sq9`2cU=g{Z~wU*7dADSmC_6i)4Yh>zSYrs!2%3thq-1DYTm0 zz=L5nVaQs7ZvBlm_$lajOH**;8WU0=JuT!t>7ptK97lVrLB|zaX}&VUp+~-EqdRT4 z*E`n(eN>*qT=R-MZ-|f|PuswRu+VDjA7BT%*d6&Q@)-=oWR2r$thF?fz+T@92TLLpJss}@5*gs)G z4d9ahl`l^_82y=Kms;^_wfroN*A=yVsZ+{C8srwFCNWucnIPnCEK)V;+$BQnvV~Og zDMql9&%ikY!5JdzU_>hm=gpD9jh}hE3Pp*Y9iYHe-MQ z+o{&s74m|Jo3m&T*+mAcPV)oSp2(r55*SfIA}P1B!4oTmd)tF1F7iz657L2wwGjg* zQK|(cCd)-Vym%-h_ys{ATH1mP%S0J|(DL#Fc8rzEfGehU2ov2Uqh+V8j9=e)2#?S4x>% ztDY_(Yzv8a4$5zc#?B;PNf+q;Utz^NNHFxWVh%?lSVf)EwMVq9^VM{^2Wh2({^j6! zLnagP-V!rTpV1%24!gsYDsW(|xWjRqy2tCe=mQZPi)d0ut~$xRGj?Q*{EEVi$+=pj zOFSg77B?eqY;G~JJ}Xlrs`Q9f$g?h!CO5U9Sy4c0rN$^|QE8*zf)kt(3K{8J`l;=m z;7|~fcY^j<z(uM~so7%JR zzSa=42A5Cz`hRt<6$5IyrQS8Z7%HCLG0b?Hb6qN|iG1 z+054q4xRW#buQ27^9hY5SjGap-2mS3$)pG>7vj@Jl?pP}Kf%gF@_RiZZmmo$#vg-& zTUFgL7X4TJJ)%ySg%L-rP?QuAAS&E04|E8?hyX#Pb4_sHMh%UK#deb5^vpmFtmD1~ z*c%-OiWYXa483Goia~KKzU%L5Q5yq!{s-5-6W~LIsI#o!{cS>Texsqp;9lJ*RNjz4 zq!KJEhw=Z$l4V3fR|L(krST4R-oLBbaxmQ#pn695Gd0$~urFN_-Mu{?Kz>a-TcVt{ zD6U)>06QA2;&ZHwApUVRxsh4HZ8l4~}er zFAd+5eaa;q<~W;Haw)PDp(!+u*!gW+#w#vKH7#U`>G;sN$)tYc3T`opUB1Dv1-r|O z-t@z`3JJeEv^fTRr^4*$qr_71GmSDiX6|6lc76$&yUQxD?tuc;t(TBV>CnG}QOqh8 zA^r&#ySII^<@WB6$oGh@L@Zuo2P9(x-=WzR@iC2bgaiv z#!l_7$99J4abW7ROLQXtIp!_@^a9L3KN?gGDhJ~2-}O$-P!Gy|I;N(*zG%3FJQz7( z>!V)aY`K*7`gP)_cRqXn)M{pS9;b>@9aZj|lUO~O78XbVK38<_Lqqzt0~}9_aX3^mya`6tU6=f0%xZdgqKzlR|pZVs5FqGu!mFqRxu- z68$9)E@AR8bX7an{?jCIW9L>;&G(s%S;@$))_dUf(OYQ-lxQ3oM^`Oiqr%9Uo^GM7 zgSZ^Uv2vVq*JR>J@7AE8nj^h(SFa+W!N)xXXBfJ4a``Eyp#q0&Q;v)gvvOCnBag-R z1A7JFl25>SGX|Kg)U&v8Z48?+Mwv1)DeUdR-~a7zb>m9sQ(nxU^pbM^EvoqkhseD0 ztsrltpJrL?M2uT~wjM=wV>K0NhqaLkoRQ;gQqHVu;YbetflO8}TzXweY&NDsfBO;W z2t^PaQadn%Uq&kl7Fm5sd_NLQmgGHW+$*;=3Bds)QV=O{MYAJvKqC5(*yMzicIx_a z-cBnLz8{lQgiQ|tKrL{zyG)(^U`~-N1s-0UC>dpnaYL=E-q!hC4(#ZX^Yqj_rA+@? ziW(VZpA0=vaGcIZsm+$%-E#n(QYXhe1V^7it8Fm`l^>%XQ&w&lNkfW?^_)=oYq^ma zzcA3TITH6hF!wiqg`1j;{{3@uMOywO-XE&SiyhP(mf~Tt^^$NAlGc|WN_9rwC(i>u z4*P~EMq5ZpmdZeg%Cib6zQTEkY1k(&J|N*|Xg z(mn6AagdNC`8kBMtWYU8*~(kc%c*oXb*aN!1JIaarjpgyRO5H?)ELus`{~QN?w{Qf z_ag=p?*G*94~UOS`9+FaZx$Bx&dnLiPjUcjZSsCsVH5k?9-iM2?Sfc5-Zs~fKX??} zU_Cz%h!;q;#B!v|7(GCxEQh`fds0u1bOu3f&=Lq~Hkilryj}lk=BVJlO)#d-)i-D6 zlfKS*?SPfBa%f&r!u?0Q$UOLpzw+rGuSYT&X0&?)8Q(SI%$@+@!yol&cRK0(KCXeE z95FVZdpme@oT*E*iM^?E+12~eTB2Hwb2DFj73dq|lt2yS_X-oXaOWmhRvPr)Sdt{S z+t=b5`hiO{MPVrn3FX@;{0!P z=(7KM*x>PS%3qH6Z)^zj?`){mXt|KB0{_o7_(Hz4xcd$-ah?#y|5GPe7=g5#z3S}3 z<(`%Ns{(FjH}03QeZBw8^I9(Vf1LURe(gq1Rh4Oab{c)oWtpRu9iw7T)dtntkqXXF zWBRISmJxL>Pn-IxKhchnH9GT9zEXFEY774|S9h;p6B<%rZ@lrd>6|~%ET7y$PikxE zI}6>V{=lkDs056KV71u5XFvJCt7_9|dLwgM`(J|8e2*Kc*RT#(^Hz_DiE{S3*OK&~ z@=e9SuGe%q!s#s_Opk*B6R);&(N$daa=edSJATPf*RSI_`rAQBSPtMb`Bjd=RzElH z>b1sa{F~cy{3GYT3XfNrfV?gLxMata_cesX``9(VKEc)CKW|N+eKr>zgS$Hu7Hhu< z?C811vH?xkKFOJrtBxK7;&~cn2fExg}*dCvNqd>|4KuCN>&(Jr8s9W?9X8W!XpZ9d{ zWc&dGHOy!MpmM-5w%t+a`^oPYsihvc5LklC}$LPsv@rC`eh>$ie#7CICHIyHb>h-#|1_+&ibL;}ar=LFNe z!2|lHE`8welHL%l>SzK9X(WMJdNX0jG8vT~Agc2wE&aZUV&ZLNh=J>PWDNJ5c#>3>Fxl=0AtSxwJ+}y(P@Y_op(knr zJN^`Sydp7u8ZW|U`mVHxtHe?g`fpYlF=`IvyP;X|JNg4@A|{=Vb|b=*5nTbxJVJ#Y zsm&&;9Ug0(>`vm6t9a>bIkid9_DJ;unjOM<1%J1}6OyRO$2aUm>#RRon&%_0(E%%x zphkJ5{drIj`X>)oMeARC?fKm@rQRnBd0Za}7hHRAh3u`8MLifVqrQ^k56&M^$){?r7O%1i z=6RBD>a_g}TEd&0zu)!rQ(8B^4m>ILQ)t+U%CMD$Ef6aNe35nq0fi~FuTfRM z)z=l8%!Q5aCOEB63@KYfh$=)O&$<@@l|>u+?Futfi73c!B1&iwRKimTuE=gr+-1LD z@X5+Iyn!NMm*k@`k97VI2~0%GQZ@l3uB*x&n=M(2vdrWz%077&*}F)A)j8#WJ|a>oA^{+LM2-fDOTSC4G~G}hg^|N!>Nk0-COBmacSCQn z8RLByxl=~>>Z(w;&>-oP5{8>v%9TLd_i#sVd`|q^1%Rm3uywrV;6H6zs zK;_F@MUxZBP00=&<-&}9BVP&VJ209q_0~UQtVmMXt#gY;$?5GLosqG9k{cU(^gfJs zSEJ>f_bsdGO-f3~Ww)WBrG9C45-;z1@c$=0PCu>{K4CX8{K z(4};N{DaWM>Iq%O&t<`?7188l!5w&DjbP8`hUAnpo+&tdu9{4C+~WUM${qD7OXN*YN`NYQ>H6>F4kMGK%{glqEKt%=(UD0x2n6*PCVVa;W!*EF*E?79dOKc z-Zob5I)anqv4thGw9{pFYcne}+Y+Mr`NcI8?QQNH+4Ndfk21S?2U=U^#!t{96su}& zE{P`1QKgR96?nduy?0BXBe8#3`bc7fR$ufTo!`2hEe}){m)}MF{!vL@W3*@Lf*X6( z~+yVgL86B{byutA5V%Y+S?hP-b&1W7krm|a_TvQ932^t$$K%)2>-Kg( zi@1>Lk)QA?q{X<7g$?f6|4wWDOR3Ra6|}TrQ!CmBB{F38<@23~15X zl^u))@r@!qckndgWAan&>5g1VZZN_y=mS8l*{d0!Q1+|sPlR~V9g|yHP?P)&Kpmq$ zCPDmLq71xNk7%@=9-XB>emcK6M0P#ooTZ#|6RmTUmbH zn7N&vaA7ryZ9~irx6A}F-qz2w@UNHA)}2%oO^_#>yfD}hZ$BS$oLi7^hL$@>k%Wzz zwFbEImz!@r8j)4ZdDBL)QR=BPKCl5UD@c-Nf2K98BffGRD9n4T3i1v-Q(!{Rx!c;E z5QVY?S}>IAEU4M1^ID9;f0h|)^q3hzu>>_ z7^vUA`z%-?T7Wr_B*Xz-A6Zwd(_j?ofBipm>O_<6E=Nt|yJmnURz-%MWA7ez@wp39*J;T5X_sZIVvSGlTB3^6gm{{+G#x?^1? zjLTZd@ncI!oIW`C-khNmcY|}EsrVYN8*E*+d3i879Ll+K^$lUe4<&^f6d2wJv3ls# zE7>aMC6-M%k)j}AvU38weFfy%hNtMo-$Ho^i8sgEoZvzv96&j$8>dZUDN5ExW{s1Y+em7@3e#jS6Exu}i-Efu!MSvcCSA z{gFhv`pToRHoM$7QT?_Z*v9}=s?T$VyF;;p_VbBN5vAbyOJ()F8t zlW{K3G>mxVfzo%4;^NALr4!Htf@T!H8{=p53B z8N{CtGwK5jyk{5oru8LXN=Sz&!WZ!a;@3ZextFMm(_*nVDBbS#^NM+mt&}d6EN&Z zDSu#&B0&bd6fxs4O!1Wi{gbw&m*cwS&!csS07auB@31d|p4Xz(d_~Q(^0jWvX)2A| zX;}%AOwl6>}Zi;+|!iuVl zRi^4VAzT-So*iWtc=U9f`VQ220Iek>v^mm2$EV)5>1`!a9ZOSaAVHVOn2Z~~tmEjfyDe9Q1_McxR3-@cj5w9r~?G)FN1Us`eZ5*fUko4dg` z9P!5*eq4b8Tl(<=u@7gu8olR-Mj=#1jx{C&CQ1r(9Ug}S6%b`>RjOrFl3!@q@-NZU zpDPlg;IU2FbylBxE?4U#lbPHrt-m;lEj6w!U!eg$UKz*OhrfD8*psdixg+&)$E23j zc;;9;paSbbjrn`9A{Givp}7I6l?N}UejZ-n)N&k(opPe%X{9>FT#NbC8V4cm(A{TEH7efD&pr*793i~V`KI0?7%+FfR(ia4-KZgR?!5_*=3g#SID zFNS)JBE?wwb!pLpV zyCN?X`5a*uh_J76J9XRAE%=or(8|kTv7Xf^3tkoJr5J#$NUGqm7CP5HNXAU`Q`PcH zrpYLAylj_4PC!94_CN!E}U)}7Ek+=(zrL?nfVKhaY zCcw+5cdCIn&T71lB)+Mb#Mz{$(0O}h6-?32&_wF8@~riY<5?%A5SzVUmqJ7hIS{5Q zs1UWgt1ctt1sr(7k6CQ@chMFI3M&~IG8q~~yS+QgFEES#R_mq`kAXh46-F|#&LKqQ z4mnDk7!xKe!qn_VN4yE3yGyA`P?a_vE5P_E8MdNo*;!9dE-^|d&hI0^Q;9TdxIR_q zHIsU44NqSy2A`m+?if@=mk3fwv#Wdd6%w6sd_Ku^QJOual_kf=U@gwta{Ynqbp7Xc zb-b|dz8&dSAxBdPFPj#c6K!nyBSgi)CHc0KFCKjCXl#i0*T6twThvOrdwwPO2!({5 zsHcNZ^6K1{kB+dmF5q0#k4hK|V{6mFzcoqm0ThgswtL@Z;klrIbuu*QN0c9-m8 zX{Or#I;{7Q!Unyy%uk8nEPz3xQ|IXPWrs|p5t%<3)aI8f$afW#QiQU8#410G%Covq zaw{7F$`AMaL=-H1nJ87HK}e)7;W-lPcz*Zf`4DhepO*&8t3lbb#+`0PJoCjKXE{@xSo94H;hPO)zFbuqe06{Y>RxDqqkjtv3ZLOY z=~@R~;eBPKEur@f;whW;RL{*=i`Jbg`lZ%TyX>1?)h7X`mB@LJOE%@k; zk+vw*%Qu+&@cgmZ%n}w)@hx$(|m+8NN9I6Logpc7$=H#yklaNKH^N;S29x20&6s(Ec@3HVQi-ybf=lak_J z<;X7d@;^?!eLc_qE}xsw;LB>&j7!w&MxAAjn8z>r)xujb#eG__35k>Am0V2mTbA7> z>*U9DWZkBoh%2DCRLJ;83;)5#TuUFlFkr4~s6I;Du}eXdSa4X1bL`_HRPv>{OsZ3C z_bUy?>3vaM75)|2#h2Lu&Mn{{pPxy)4gB!xsJ<>Oz3T7X9DwC;J7EgNpfOSx92vgU zZvFJBQ-jMXkf*4P9;~TlfcE^bFgJT@sYL)OESouMXYO`VxBCiSLrWUHd&VmA&f}6} z_!?z&4abTz!*v4bifAIRE^`o0`Ain^6RAYwOcJ`i_vpr2v~*be|oT zQwDC9xG?kln)BaBO|^%Co}a1_O-Z?Ud+)30sG_|pyP9hHnxlz?VyJHTkQewTS!z{!QA2lg-OGx&QJMKzyPic5PcCgj&JC?vBC?m6 z!+s4ewZKc38W50&X@7BxvNC1vGD(L!w%15}?NYb<6Hzpf55JDE^cqX^!YqZMX(&+S zx!s_)WgCAZY{sg7ZqO75FlLpBN3cEy{S^c@0q{%|$YMAZ5yO@io8+6TR};k#yxsh6 zGH|#dZ<|q;S;=w)2-nq{n6r?H3f8Kaj_bYSN*&oncvEM0b%SazAv{@{i{shOq#_i- z7rxz0Ve%j4edMTq`%*pgUT&6%k`f9jaj@-kmB6A0UPcLsHTFva*kodCwuBrD5}VB) zLo_B=Ya{U#gKOWgB2`+~u#TpCG%mP|(Y8I!r{qcr8G`;oDz~&d%H|$pRhO8`^r6wM z7<)Rj^>-e|BA~$^cKW%dsU_gjx2oFb2Qr@fagr1~iNS44;=Ow{(`ehNKzXlhr^zc( ziH+_AQS84CF9{Ll-Sl!xa`oPm?e|_aoL85VS-$mGKA~)tA&gFASXCLk_U$f7zrve; zv_ZHg_XmbkYz~A|>?xG;9P_SCG_rb;I-lQ)}k>O zFsQ@j4;|EeZ*V5Ke1>y{qArjhnZ3^%4VLd&aazG_Hzy0S<$8~Q3377>+CHo@dn~HS znXTG0lQ9Yqa>3#AHl|H(p)DYL`P_ar!C~VIg!#c55Kf^Zeu*HryNSRAw})r+bFHqoz#z~;JKq+&KDD_4!EDGDHDbVXmL-PQRy{- zt(RSF*o&TMN;g(uikzMe8(GcYFjovSsQ=~4pJ=mC4n|Tkb zv(FXoyOOd|TEEZ9R^~gNKq8{a1k)nUNFh0nwStu7B2%^wh_Ng+H8pwcd9M@`tqhBo zig_R!B=87Y6qOtT2^AIWlK05dHzzp69!a_OPCK$u<8jmJ@5kSjqqVJ?sTH6MkBH+g z&C83_zV%Z?x=GXA;AD7yTC%lh)eA>`jB!GGN^fwzm0M}bXcPUWpIDfLx>ZZK8ZHj^tdab?FjVufAgWhxIcW7vmbN!w; z`%0~Z!Hw{QEU7m8p{-_(A@bMlD`E#eR$QB-(%)2RximYQU9hw`B-Wv9$iCLN{>HYVpC3qR@i(^Ye#;8D%L&VMtb2CpE@N4=?jNO)3^@s%zo`=5Rt(n4-|ukvQR5 z0p*bX#C~d&LSmfVH7=e=IxOYP&)L~TNQaDO7woo;*3aV*l9#W3kxZcdq~M^XcqMivk>v&wv)4(67!=9L3F zaYTbeyR)v>S2R8#0J~s?GF%3WC+bAI5^S(zq{Qce!R8%EsBbMMsKXhm^80759>AlD ziUKqa$9(z`oGTO!U?CxPxl>xnbzj(P6vAxHOh* z5JIl`@kSaQKsbf0EjZ)6Z=BcthbB`Kfa__Z1+^mjt`MgJ3o3Z zXlqEex@Rw}&Z+&(vj8jl2J(T=tU&t z8r)n+0`WbA#I@D)pPGQ@r!nPlyN;lqD3Ozf^{YL#eDGGMf~fXv^kJLTU1Q6&zp%Jp z(6W47IJ_-W8TsPBhgolj{s<<%E2`TcPyVKrChH>j4S`1i92X`Wwu_ifId}|u9M}j# zjT{3HP!QLb<%aELHzJB5hLGWh|6vow`D_Sg$XFM( zkMU1vuAih{?xGq`+3@ppPWsWrK2*kzYv zyiR2M^=~#P=pbVY03E5Jj9^9GYD@?f7Bjv%joxD*^-WH%3ty#=vT%tIR}uO!sOf z)T^mn0)}_jQ~b;Z@lEr7Vtht4V-NI$(9CVb{#qtEw>yC}Sw_E0zy6{kaTE6gJi+V3 z_DIYnds;BmEsn4`W(E1#6Ubk(!)={%+(7b)qxYsmrUNxN@rlZaIQz7Rs!V*K&mWxn_)31!GEJF1kSpfZs zoh@E$B#KO--Pin(AfL5;f?$14my_RYu8<<23A$D-{6_`!;4ayv)1o_-vYgAG@KffbfVi) zaSf*?4pUvRo!;twexLuPlFrOFKD662Klokj-2NJ$LZ?fWm!Dt#tWYlPSgs)X(ZPyD zUnS1+9QKZ_pC6KAi-`EKf1RPYY564^Dkcr8~CQ+149 zwXZK5T3^zy!oj;Ed{}2MVngL!@m$=XEG(R_q(~WO- z(CT)#qG08)pp5_L_-}4u!WNGDg$wU$R^nGneEi}sL0{U z5cBXA1wva-E?xz*%n$4S9{*=1+QFLF9`uM!_}Gzqi`Kc^xZG@o&ljZpF{{7&vHiYU z|CUxatqstK?dnjF!xqcG7=(=qJw4rGRntDDd{-~A*$w!$g66L8H+tg!y>xF!Zo;RY z({Sij+b(*2bWk*zhPI&LUyC1?9DS{x3o250SdyO0u1wWH$kmo4 zkDyFQ8>owc1pL|hETc7mha+@VSVWXuh!Y8wy z1l2Mt!xL(>Gt(`Z%NRh%qnof)jNJInG_M>Y_S)$8G4y!*4^VM*S`&Hb!pIN2)ft8lxAL7uxk%5(ZX<6l#0Vs2n!)93o#cdDzV>f9*I86nNYZvt$F^X% zgxFhG%WcAwl1VQluuER|{T2aV$YbI~jSDKOXm`r%8d`7}jFUSPnf^S{MSa?+ptyqlj+r9)0w5jBsv%u_zz9F;ApwNtfjSZ`^*T zU1C$>WdxW37JIf90(uR4c{vg$>8B2-ovC$*UOn3~NJ%6IPiDYTzZo3dM>z1@C}85D zqsVn3HMpA+-5i})N1E_90v*06&oym7da@M%>kKk7y2x&smr6qNOL*|I**8k_ z`gP823^~EL=zYGy=xD-lN4b|HeY^!?L%f+C!}0v|Tv_%owfS`>R}r&o(iDyi{o7Je8 zWLZ;C>!2T_l3@(_HLAdEmRC)ku!HHZIqO_mVnr=mEu~A*Il0KY{V}Ii!oazmH!q+Q)W!_561KqDR zk%7z$ku@C1r7@Hj1|?k=SW00vrV{PgupJVFC{b=2%<8V~h-UK^Lo zy_wl5(i?BQGH$eWjQ}f)hgn;8fv!mfQC8f#E24zNgx^Pq(`u-yP>aq@Zp`Fo%+@EZ zxNs$pgbbpIw1XizhzW`u4y>L*4c^OS{_Aytj#n>HhkV#k4<)P zI^l*N^{)K!A0w}yasR0(KUJhZmes-TicJnX&M~Hmqs16(sL0sS{uR=4;i^d(ID3ps z%8J~afHh-HBrY#zYFMLw%Tj)8Mn=C<_}ULRtV9uQipgwi!1{P!{viyCh{zK0T+Mn$ zphTz5d|+f^_#kQHjp>pR@AckbW;WsiDzZCkA|i8WLHmf(!;*0owv%!(c#I!XZEFM zZyk(nG%qsWM~k8OG6hG?mAke2L&xJziR06gg@P{1rjIx2FtB<=MpK>?n36FUzB_kT zz5W{KPaO#N#@1|Q%2K^z84w{9U#!?uxzQVo z!zM?DN5tuX?(I$L$mTUL&a`In>!@FGT&jsk-5aPW&NL!3w%xbF+MyzCvW9V0!yqcE zf99T&Il8a&VoN5{N_cR&UGMNoTo3%C@0~x>pDjgbb4AX=E=@rhsnOETGuwNvsJ5y{Zi`Oz@5IY-@Bqs5 zUwguqhF^VIzh~zrYwtG1mfIx?%8_J$x8PNHhHYhu_x@e59!4UdtF_qpdhFAd*ryup z{=tod3k-|*F?Qq6bAw1zrEc$6Y?b# zC$>xCYB~=oWO4*6Qo?X7#n}3|Wads%%X8GAbij{17m%(4AAbt(U&U zgC#fTd@dQ|(ksAKmgLLDRyYqg3fStX)rh}B)!j^5S^UcYL_%HGln9Rvcg3`H3vP+!DsCLiLk~ zI=+~&ICQ2yWf!hd_Br5YhTnFn57gH7(lEzxNiN9i1*>>z+@S0PN~tr|{p{n){UOvu z=7TZux2k;fq;5%m=sKz0%xC970r%!m;wP3MWH*bC&l&AuHtGTX_WMEG7O`&QxrD)< z__O(~p&HvqQufl(TxUJPM^_CEYv(d=xjh^0_mLs|Y~QCp(SKR>|EC1eGZoZmM*ig@ z;pcj^_78@od9ek-IyC+5)xn-gWTJE^Yjz@PZ?OeP!{&J)|38Hw2j$~y_-j#e|BD_m zw$z8~u>Us(s^d-iuME^~nl9$zJfsTY!0F!^E_zg>X|t`79m4uR0K);m5V=y{GC5za zjlzA0k>}?I@->cOW)Fjiuw4s>_Qks^YdRiExvKx~F;ET#sZOI2t<#ju;KBwPRt@gP zQ193`7&WT_G42;G_)@zBfeC`O14FSWtbYW`{ixB*%~ZqpCwJ=3n#*v_l(_S;^EY=O zPgYDs*0orC%do))Un2dI$!hD;Z`wgJ-tfx2KTVIGrnc&(vt88R+eLRQHu|IRe;Ce* zPv@(Dzb`Q+C5bI@cQB$!!75KnvG2eqExzBKQ z62cN0k$abBRquZ9ygEZB0J)eMWq~Y_Y+%=s-@RX;5^DB8sC&z>xS}mvG=u;_g1fuB zyF+kycXxLJ!JWcAxI=J<;1ure?(X_3r{B3>_w7FYzJB-pdF$t{U90x4wPnsR#~fqh zRQ9(X+1cLJ-bqSiRgcUbpc?(GHFOGg9EleA^f@BpcS%t2__GT|TQt|8U* z)^>y_)2(z!kkDk7#7y1YL64qOk85ja*tk@urH1!wy11clSpD@h&SAtaDb#sVWsUI8sVdPzJ@vZ|kn zU-05Qcc|YOOk;|Xa^l%|k=0iU6SH-Wuh`Uv=zmXNrX0zQ~`@^WUAlT@^N9bpVPIDLsT z4@@>5+PLTS@9vl{feE`}IShU#E)No~bWbJ)X2x(1!W{~%4%RB>U4B*yxVQ6)roDD!Zh2}gu@ z@8)pd*Xoc0rl}gM^tzWxo*siXW?_IM?aaE?HgWJ%FZyF)2|?r+_Ht#5}teOolK=t(^GS$VZ{4dZ&!{8!5mE> zSRY(^*^q*T@X}M;1vOz01(}X`R+k#LoT)@Kl(IkKm~|q{(%JL193Aa)JsH&OCv(A0 zZ9H(-bzzH^ALGX*NQvk2(1(nmc~2@j<*x;?(SFzeb$wfmk)1QAxoQmBE3~V7Osda_(#XlcuM2vzd6c-tRy zBxzF}R+U}3M+n1bOkg4V=4;CEET`SeGe-UB;<_dEKIg(2DJ2s;gTik@5Bq(#XnHVx zczt}h>H}}Haa8~t8?8VIk|I7uZhEUXF%^Q&JVDLMuAxJi9^kag7%D9jJeMz!;xEtJ zt#`DdxpdbBzMA~FnLM2h3hM6q|J|W&YlIt85at zGugZ!FH*W5l34ETOz;G$nqk}MNb&WI|14eT zOj~J9i}iNhxgz@5KUmR4c~Jv4p6!=!^?JO$ebgTBM(dfDJ6YW;wBF(m(I~S!)u~Fe zvf5GHLlm!i@^0^mS(q@86O;_e+8BS-ijih^{fQToUQ(Xtd9_bl_0H*;n@}EO32HqX zs4cx#Z+fRWrXp{8=xg#a&VIU5;aaD(`%lmv8!GNcn)wMQ%KLHAiB!rWXNL>x+VRVd ziDOTf5W>1;WjO7_DSFG4H;f;NB*0x!)UuL zXBV$`3?8c*RlDJ)q+C*_Eg}*CX>RrPXGaWmMoxuLQl4p3aYfgO|1*%U&PwZl2=cuj zi;x)@AFQ}CNg(gXY@pK>qS2ej<-kkc8~n-pEEv~d#9D(eS6CJcYxWZfYC-|q-9PE# zVHfqp0&Q9?c4vxQ)qy3$0miEPMZ3zjz{`kzg1s`Js~qBIcc8ZeX_kKWSni2hv*`VU z3!AhAAZjKbmXcc2;{O!n)35wvRh*^PDIJ>}9|ZNZxo^;ScqlUFHgPo>tnQ?I{j)WKMJZ)*5SPPrti3w^W=y%3%MH zFOtvblQo7ZL;pB;K8R4PsxW~hV2OBU^}K1|^oOMaE7tdS=8QVU)BPg|ec3AVt-pL^ zXrH442%4jiH(B+`Nm80S_A~qJhqx&YEinh@u4yY!41tUX!JuNPS#eNelWKh+W^Yw} zUR})bqrUzbGwM6smGwAa;8dWp#waToeZpXPO_V>K)r=}}ed{!$r|C@XJO7pI!{^Fb zGqr|!HMalh#-mfd6V3JP+~{xp zq{{qkxxr{OmC4`F;pqERZ{M6zwZiHR4kb`F)pr z4&x6-(N2>4<)G%*mzkdL;zREf5rrvej<0p-Jzsk!cS#%<$wkj=g@_fzC2H%whT9Nh zFMLDKj^03du_*+;MGh}GDvlnTp%X$cosz$PZV$?r0~H}-t2V+}A`pdlBgX7GP-Bok z0|_(v)`B#XzX0UE@G~C_+e`IQyG50e+!D$l_>(ZJ5Q%m(UsY7o#;uBdY+MH;`Zuai z^L(B7RajP+5K@Kh>yZ=>uTMu%LSeke#}8S`VzY2P zFmBL}OWWkUS=F!OSAI-h*6U+Szz=zzqrhzR$hu&}VdyJQ>HJTU8to!tqM{%Y@QkjH zXF&zzE0w<6HO3qXv8bph-_>j;T&~_6xa1Hy$JWUXEga~7B2JIuA+*U$t&$Kncf?rN z8}B*2N!0LplK+U8$tJEhE4gHq{0yYUj#?(Bk7V{)!C$(6Jk+HEWawkjEJUgFj3 zpuRc^c0RsY+8b89G%lK=ZNDPa^mH!@`y{^}h$#ce!$PBC@(waHyV@k1f|1Y2gD63q z1o(X*!9#pp+@J0_`zehJ(eju|2Y|{rsAi;SjeRnY+XuObJdfhv7#H+NXHv?1Zp$-$ z$^an)Dp}ymt6030Bh? zN%UD~z^^e<2lz8J{Dsq-J|Q6zN?D}XVgJDW$?2hTZD*PTTlN)*$}CsCy$4Ay>c&gp z+n$OGqrqXyyyDb7dq~G#RFIIKHkx?9Q0dt!F!1WEnYq{$pG32xc_*hVgX&~5#w~|N zAjs9vY-;}*8ai~5t&>ljEZ%^ST`f8uQk|-4#$$V$$r+&u zRNF0!WjT=`PqW0*;cN>@u`0EB*~UXJDmk>~o2XSz%aq<23!>yGSjF>UKlk6$^P2p7 ztfi>a_kP08bwPmIu;7eHd9vGC?>%>TQqs8J{$L_KXA@2=^_U|?BG9Cyr+X`%dj4wW z$*UgQ2dvZ6a#tfWM2CH*Zf}iI3H@i(Emx1LD&uCm4p)6C^%I@j0YGi&xUQ#8e01B4$Hz)p-7Fl z&c`1Ow}LFPlW9-2E`?ycy(=_hxDP(Rj{3NzE1%SN*1g^rgBp+<&JAZ%j zZKoxbSwCrHf4cVWA3H>2{zsDi9X=Ro(ndGue6-E)wo(^9OEl!C=cw5r< zMQ%0QrtRJHkWL4vlkM0VM-k$PUE!6gN=N!FkDSIDR`-M&GCA^AD>`ntr$p6ad)Moq zQSJ#)&-P2;jljn>-2ZCgGAS0movNEk_W*6cpj-`Grd{Qo01)BW{W zRzbT2J*%A-6yL9G=>zfdY_B@38h4fzXNX03=FS#a0O=MM*nH z9|{U{#C%e%1OF|GCzPHA7)tE!P3@eMG8oN>I#x%RnV-PA?l(j2OLCSFD@HnQ$fx@M z3dN($m->G~@u(f^dia&O3!jDsV6y%bO_nuVN3BBD`Y~H)X;K2|^TvB| zbU<)sow1JQPJuNGYKPS~kua=7xBV^U=W@RE85Tq1cI`9s=-A<-hdsC0aKUKC_;lpv zbSDQBhsUwJNpU>NY*PG21rd`aKe(_LHE~%&=E{i!nIYCmC zD$66ACYUef1IIPJ@sGS-jz1V#UmC%2mUQNON#=zsK2yqU`@^~$i1p}{;~R#2!d}Pt z0gvxKjZi>A$ho_F!xA*0q96hVotRcYI z7khs8C*`J%9%6^SZ%U2vAhX*o4e#5j!}Bb?u@5m6;?f@kJecqMvZlZ^nl)WR_9X}~ z-b+C=7fMq4$CzdrGKW;7rPz>Od8kJ}`XNM=O1)Y+g*?!ujgkmw7(HalN>}4%vZ>1T&S)S^I*sl=v z@)OMEE`aSiUVCs;d-dRmZ4>`=eUa(ZaYvCBK)Xu=#GPFwUFS3^q` z`WbgS-orqu;NfwPT31)?ll2^Zc&JjJYagCYEJwrcc=_`s80<@J=pheBxrMTVP7dN< z?pGtCctYFPDn)tGd1zF*TGB~~NFo}B6sm^-9oewSw;Hfg+!qyA4q`@LN`A?DXd?RX z$M|nSg^Ol&V)Rn!mnZznnY7L`8ehpgBP=eQ*y6jte}QP$U;6!iA}#=+rNs{*p6sP1 zg(f;G4<{O7_^SHVkcV59_mm7)Py!Tb5bRRuL{H~HBMnnssYcbs#RaX?>9E>j(B)x2 zLTBBYZ-)=*5`_dEMzAm9wTnr_r8rpMv~cE95}TeI6Km)fm`_2rggUTF^sHX34Ai&W=_pNW}QF^a&W=<6Azo2rd z1Hhwt=m zWx$95p`k!zx@-&@{Sqn}c|bx!6Hs)-oyvv%?lreFNdZ*t&Doz`CJ7)D%i#6j4#z<# zM&a0=!V*czg@NMP3y<%tP7cU-P<~YCmCv#=ezjE&EOozt9XLP%scw8v|q!7WwS(6q-* z;lSeiI{8D{1a3(d;YWs4v-jGbjE`0dV8*4;OR*p{UVAKO8(GGLt8|~^)`X#*M<`AJ zLF%GV;yztL&}X{wpL7=q_xs1T@9?8bw>1RCt;p4i1&Oi0BdtwBX~J)pR_|Y4WJiBZ zl&f*QgPF$%4pO}OE!S5m-%?|Ty0w4Icw}23N7XrHC(=UeQ>5V%?QD2+pZMWPcO`Fm z;M@R5M|(H5Gl~qybsCMoR#!76LO5>RXvGewI4S~x?O~_dDE7MWN)rBl8a$y3#w5^; zyN-&EASpOOa$4lV$ZH`b& z_2EaR3Ny@_Ba;sO;Lmn4!j>t!9_(a)_ON@`w;BzGI8VtQmUbqjY#7t$M%~4&e5bGA z6!JSyZb%+!q`bbqak39gPC%<7_zQ`*Pb4YR$}K-|x*IZ(XBy$@P0uw|R?Ve&%kes| z<$Gr@Wzk3Rgpw+a4{sdw*Vm8+Xapt>q9F(J2qZdhvs=T$5%i4)HpgB3&Y`Z`WXz^g z)~-4SAF}_)P@3L<1*N5KDK`WB+3?2mkd?P?gAme2dXO4QZ)=Kbo9b#${GpoZ9%4hp zAxaawC3g!GTpk(8%<6}i3X;;bZL8xV3vjtcx1`D3y`G(){H4pDY>WTX*MO7P&H&q- zj}Bp(wKQKvQ@3C_Vr5X77DjxPIO`qWPLk(>FiH1==Z|fRKZr3m)R9SE{TEA9l%#Uq zN5#N!Z@ZlYjb@6;=P_-O(r!yog4!hc4K$*?!7De~*%Glc>k}pZZg`ng0@}xvyS3rl zPDqM?#!i(8tlVFQ9JV{2mc#Tv<~f-R{3l0lty^+zg4pxJF2+=S_sB76<_1z}us19H z&CIzc=AmgFyXAqAI1;UzePFPXI*a10I4BV3?_^2vFM-PEy!cnw#H_U#2?#0$>45)0 zGt=ZdqD$~b$S1AwnzCcAm9Mn|s?l38>3|L>fAevIS9>t+Qk}yRT!N?O=1vSos?=2I ztY4x{kp=Uh5vJiz!AQpR?OhGn5jw@O-CvqRgl^`vG2?swv~Xx`p+XKqmeA#&eoW+WOUOPP!IRe(`_-Z#1qu2cu~XDh1%lw zjnAf_BJB^0qU)tQyCEa@Ccef`aYcEivmf7P6MUwIgGjL~ucr)A|1|E<9b=M`I#YCx zv?8OfLuzLa#d> zRhhSua3h)^c0cLk(jp+wEJs_`G5j{3p@)I0-?I1zjmakbAPiaTv1;s;8g-~sv2WEr z2yY>q*}h-GtAjHOH50muAiSC`*cilPf_%)!UcGY~$;A6wo7^dwvH0OsfCx9f{^*77 zKz~QcGc#UylsL@NaBAs*uRS0-V|Xfe9hI$8x&M9qYV4JhI{9bH&f@Dj_`R6>3K6-R zeXn#m17RDaGGFr#l(zT5P+#|i77GmJJY8uzXom5(z8l|lvu+5y^SR@hKXkDPgU(DI zNxP?zyuwz9j#ZSj=w?}jTqFcUJSeEUAu2+;AQI@Q82RCnJ{P-$cuqW@^F*o)BMb#_CLWy!}k6j=V z2FF9aVt zRy(-OVs7ut6PkY~;&d<2PNYdxxR?F!lc&NwN=o5R;-f`4{rXs0@PZ0)`U*}$+^SSs znzNxZcm4dcG}(W05%P2Mzi{g+CaGHULvTzgDn@ipLWnUn`=hKzek*i&AG@Nr4l`)Y z@vmMMd@RmkJX#61dAd^$p-mfnCTP0xWf(+;A2NR!eDm-Gf|TRmWir?Tz4o;WBL8xf zZU1y`7P$AXNrsGqGMSv1W!|qqGqEY0N$GziGb7h~e~ASVE#PgHt2MU7tL zyIKY%uT3y&S^w?`{+CD1xFI6T8FHn>=Px=Nr~jzRYpBKvHIDQ~VLlwD69@6T=U30wh|9mH6#D_DNI&1pS)XYbcHtFjl@yWSZrp};w(C~M%U9Wvd!T>hd4-7|8bxWD&F;?ea;#QOX1CDc*bw#n`$Ze1gsUrkHD zCC~eAqg%{^-YKXliXO;jMw>SJ^lDA1II(Ha_J=shv^`EMId=+zI+D`#4{L| zY!gIv=@Xdg*TI?Rnoh(#4h2e&ger|Nq?S$PI5uk>S#ez|iu2}OVv>FZZ2KjMZf-ao%uX^O7Wzy<@I81ofXEZ&x;6$tC<^YU|UPV z<36>oX99A%wiQZ8f{1V7hq?v0mYbbeGpGwK+6`s?_iLR{ef3FfzgNJhG;;P|!XcaE`{ODcPq z>(^Jm?@Tgs&G*vPpS{gL-AIuMPzUD*y;lhIBVSM8l(>YpuY|u4(wjTHUK+ydKS^_Y zV=4aQNzQ5qH9cJ@E#~5K%SN!C;3^4|!pQgwc4oqx(cucKGn{GNGWsv;pXeOucf;;L z(w20=RowRFpMjqgwEnQ(ZB}E5dped~n;u7~@U;I6;>!}4)TknBgZb-zxJxTAO5|^B zH7rpGCr8YXRnQyCrD)_ZOitJ2L?@4CLhihKxdqs0F|FzqqwCNHJ)Q`}L3@TI=Ooy? zwEI9|@m!yA1>1k%CsF^1S++m>by>+%8T$8rU;BBl^7qCEbtil;WhriMZeA(;#|L}? z^Y-i5Qs3mP7pgjBt^RR8;D9Q?mASK<1%;x2H!OxGOZhqLG_2fNc>n8w?t7unxMVN9 zll*ToI~4C&Y!3&A3F{Hx#o(TnpN-JOtq2o-+Oe>r=~Hc-s@=?~rzf0?G7R8Jk-3 zRFO5fN=E5vLV9Mn0c_`~3=au`yodY`l~0KzEu5DWI^wNYh!|R};q2PHfw5s#fJTP} z2i6jWW`jw&nwL(#%YSHDkn*BQ4iRrrn7B0MK>?5^y%xh7EvEPIRPO0UXN`ElL^#oS zd61lmj~QgHP|wbbgi|?}9+B@I<6LdeP9Vavv|JqVdssu z1uyAVFcKy6MdAM_>NKsI+57h)p4f<2%S#$pJGkp>CSyA86X32yj|o}#F7SoOf0t}dzaio71xM#op={NavcqpVW1{H?IAG$+ruriU-frGSv5(qTt>t;zL?|2`}Ls@8=`1dUc z>UOnb*x2HqvFi(5Pv-0G)*_(FS_n^kN>*xJr_3wUk?q#I`vzAO1o}{*@{ypbwc4AB zV{cem4H|DvLMffG=`o~shxX@N%n}LR1CUU9<34%IK>eg zeG^}FJfpf%iz--%oRREK+kB3HTvp;tCfTz3Auz9Am7;x~78i|2z~94?fM8JfMS+6( zE7uO@5j%y>FmFmy!Cj-!$#e3iV}(m<@m7VQ>c)`3L?+QA<^*#K>>9US^YBKLS#Nfw zRUUO90ua4Ie}INd9K2Fe9^o(I2x9a<>cJ)LYJxQ##DRpL1A~b%|4e#c1fg4D6A=;F zx*z!XlUn>pgfQ;5_nWBWMaW3=9`Eoz$kZNR6>;m4RFZucRY9d6?62{4M15m``t3hv zL5(^&M@AUvpwEIya#_czY|gi-dH@gP8a^h=V1$1IT)ZUrX2yqja&GdTBrYHkoiMeJWzE>wA8Nofk`7kX061AgjBO)LpDSg?vl39OKlJ*HDRBu0|fNHt%?dI{Q`p} zn<66KM$8y4BYr7}2fa6rUasmb#>IjYVG|H7KD`Ks7pY?TOgTyihTa1j|;bh08{vXtxx}9;H z8DWd#Ls5cS&F%OIaHQvBWkx zKho;mRlm&1w~j@jWQ6Htt>{(|h79kRNc(}gwTa*^St9%2*W-S8M$NJkM@YM;Wl$5x zaHh@o&>8^5m182_nx?Z#>tf{an-<45eveF1MfaWZ3nrUjJaXSzADJ~sJ+!F9`jkoz ztLyd|osr$J*tKsUUk6nHk&w;;edgC?eO`QMQW{R0bd#&w+QLV`S;!O<+9L9n&k(pZ zAadMvEzipg1Zu;_is$RhiodxN*hjUrX>>iIX0Q)zEAU#bRg&QcuM#Y_@{F~sp4PA& zA}VIxgLnq%H~yrDd5pBIM^kAAKjSWK{i#)Kx=HL`1#RZDY{aQNX8i&2mAVR~k-97Q z#)AV#7dgeUK^XX8rr{+DvBk;yLLx&F6M_**`ocISXJ#k-IK-MZex>MYVnW|e2b-X= zIk!1M&jmjdf>39O{^h83z8=QU;^h$eb#pWHj++L^*pOvzN3y;M5U8-|kxspAJdJ}} zf+VI(#)&Lclto{~E5`- zNGpbJ1VhAkFWo`S8Z}y#8oI)mt+XgFg*Sa4(#iLk+Vjd)I8@)xiXv#h@Q&6;gVDNd zjQiWNZ94ZQL#d1l@iNO?jS_?Kj#&(3GdiDs)Y0>OAF(EUcI zVS{+GiL)86-C85dS-gXL4G;cmlGQVyKP4fEzj5S(LCI)NG;^lYOrfQ}e0mWTNCEb-N+#LpKRdrsW!@KDsI z+%aaWzrk)V))FTJ5q=*B#HN5jKsiFe$CLjs>m?tb)%;%U;s_1bGlDd-wMg8aP{Vy^ zh1Jshz^PIp-eA?`Unc(OxMFL{uvrxq4*7nznrx^EV*_$KE)tdiz-X-ZLTx4w z4R?*kkw82zr!NH{C)P@TgBBXa|<7G(VvV7g6UeM|_Wx0|bA!(&M9BS0ZQC zXdjgd;G;l#xr#09(0^wuQ*HnGxqqdfvh2d(iAq|ukK9|ol7t*Ws74}#N!zs=&$QTG;C z8X(IkkhV+}S)Ee4$>@J?_$L=&pjb*l9{=bxvP`47$(v%h1hUNKLJ|+9q`SkTAOS&a zG-JpGw%9KC@hj zEsm|O!(oA`GDL%}*C&#_DH4v{@~Jfm1XCuI5P@$3{mWzedaa?t%OBIW4C+^b zE-`;^n7$}py1Sha8AS{|vkGo^p6iWAjk?Hi%U+zz5i|Qkt%~hpGW;F5BACb?g+}d` z_P~RsjHiB5)Gp0#Ylu>@AyGihF`xn z-~Q~tRc!7Crftio#4glqzfIj*`U}u4-x?UaP-BAi+jLi8mOP#6m125L=iuZT1W8Ks-XJ78g#u-7qSEFwfAF>qioNUg|{<26& z7TkqD*XZ4lYV@^efA)L}%x&jwxL>wK{Uy2Fk^pe zPM+;&DXO%sB|&v9yLU>45;-?3EV{)X%XcyO?cEiPclhc$X-bzqht|JA#kHj$WJH-Q zHS~z9ic<^J#1UkdUU8h}e1)!SRovNIqfC=5Fo6l+(>v&Y(Y^UN-`p+sJ>tJp*m{Xd z26bkeB2(obUk*{D2zB#gvTV1+0fI4m4mt8@{GN{pxw+lR+zXunqhI9kdBk;c;mM*O zg`+RCQd}2!C?pTIuZ(eNZYy<226j)oj_SdoFaRvS_jQP%{jDDSvgP>+BrF2ZIxmD=AyfwdineFDhMhUGc?-%PLt{+9{%&Od#z1!CH+`HFdjr^D8ov(G{& zw${u@vuL;+@dJ~G#`~o;+CFHzeaV@c$3JrR|2pA3@i=Uh7Us%T( zu%%@63Cg}bhj3Di+tcB-{IEr_zdP;zL!oa9gr=A=S$w#DI#g_b94M~fdQmS-LUEcI zclKCt1i-3kDuv-M#0g$}ZS`^aeTjnd5A{JZ&V$S#I@s&b;(t-K9~+u*cRX3tmEd{hQ^voL z+MzbRg!T%`amu6-nMPo|=;voG-Hk2phsbgI=6RV^*oS6RjR$N?eOS(SX)pd9z(42d zr+oA+BTJ{)Y11JwgpGB^Y}=;Dqgu%Ni4;#-W=}!O>4F&74OdAbEBb+Pzpiu$A*Ga~ zf&uI~*Ae7fXl+SgQ$Ak zNNJMoeiUR}MM2P~arBi%t8F(Wp?69%cJeKFO~uQCGk={xI%)E2S^Bj}qDqJn60_6r zl>IgC`d8HPL7$;VDsW6}pSVLsq$d_^BHux%+mknadRDI>!-)w4;X=k?b%y>*gkmK# zlhG8t`3&Ti;MnBU@~)vUL{$Zy!Vz^~Ubw_~Iz?ecnN(W*6o8Ic>-D4Hrz#TMp6O^v zMF!woM3|dqql~{wy81N=MuOPtTW^6`hGZ>MIcCfFZsnws$x4*rbY5PyhAcg@N=JGk z8%^LbgNXk)u!~ZC{OvlKceOt7QDbZyT|-O@K7&33aE;=&R{_`(D*N>~v{|@N2Wo*S zDsfXP&dg~}i!yS8jguOK9A4=n4-=7&f9mKE6+)`+ge7C3$Rh_jw}xi~VhZQP&5@Co zj69hJeJO`HsR+~l=m+RZ9K(NKb-%VbAXj2pm0ukdXKI0zXmHCn8D23ikT%i0V$|+q zsqeh?@=enD{XtK1^JtVdd4dmpQy%l5FI&qQB-7~t}{`y4@97>W#%epN{Uykkx(s$Z7b`bEYkEs zwUINrAiDOv4Ux3U>xz3}_#Ci^-9xESN-v8h)C1M4wK2IqL$$oo;c!(|<>C`>%V^CZ zR{L#_N-}}e;ISd$PLEx3`+83CJ_X?qw|AV7`qPn&jf=eqZ?0j_B4-znqxuPB;uD5F zOL%@vj9k3M0Y}|aRQSM|)@IsAR<4q@R?39Y$pBx|DGrZohf$A;fm0sYV8Wq8zEL5w zCkwWu>C#J%Lto-B0(kk(#o2d{j`Q~V-7j5q@X0FTV5A&r;E@75FD$vYhwDFh>na@m z-rGhyO!imJv#2f(L>+zwN|7L2-KBQid+b{mPxndf{1%ZOe;q z_obn*xvKcMV|4rD=K`LA;>^|Ri9?khA%7yr+R@JlYgsHGUlEYIjcC?yWB3wKM{462 zt`)MqoBXTTSD=nRid>9E$#d6f8<`Npf2C#BR`-)J&6`1N;3~bEAVP z28pfXfr+%brV=&wX+kRk^=;!NB$TmdS$!tT(I0N6c-HPKSN0oOW>qj+N~|MId&1{( zc?*TVO8s08r*IdDr8*!U&V6b>D8I+z8%}tiHP2OI{8^1T`c9AN??6qbi>A-4H>x1R}0hJ2;@m>kYI|2n3#dyU@> z6}xRzf3C-LtF|;ROpCy8SNC+!@;g&n2`e&n@6}#W^KbKOs7g za|u?(XA@C&uVGCNfcHBFpb4B2-u$7?o8VD+V-5_L}F&p-%sB`{ufvS=X+VIC`gu==lit#l~8p|dp2_rL}YgU{N0rGJsEugrD#2l z@CJKy3C>a!n7!|xuxs;2w{>!-EGqC%B(6Dc@s$~VhTS|J@gJ`FbFe4P)IXB@`lVYi ztzC>Ys$VP>n)oXTG6uBYco!eWi0@MX?oM_OQZ06~Z1ou-^HPG}TREH!`x#a=uBs?9 zsy(L-hc%EXItN<&FPvS~={;QXzH2j3k``v=UQ_xlA`gdN$n5yTF4R5G9B9;8ps_U4 zA6&)d?Qw@judWh*re=kL2SZgqzV}Y2M}w7_LuF|wM|;PgZAe1FQcAyM>7EiP^>X3svnYJb?siVvhdZE)(J`W~vfxfDrNb(_V$-%UYOHN#NqO zG<{=~PenjdI9!E{$&T9W47{@Sv`eyldkz@B*{Ip%bX8nYKpTt!IV&%w8mUuDVzPc_ zotQX-&#LMqGM5V@*f+#BI{W9MFEe}H`^|B~wbjXSCbm+=p)ZqMN_*RRniVoo6K=kT zhsuxQ@&6iiKo7Mh{bq%!SZ|W-%N)9RDqQ7QF7jq29*2v}B67rHhpY$!06Msn4ST=O zG=(5B8nAvcak_W;jEzl2ArHt4sBvN#h`|#6cwZ~I(Ep8v=F=MW%Rd!tFs<6-srPLW zZtE6*HbOhl8Aj;tx?36o$UXeN*sf~XR+$(={NEuB{vu^=pjeE;$^s=lv98AU4s!aY z%Q;hPWO;_3)e1fQNUmyu9;B3J|DN&wH8KTlTZMM6R2M?dZbfeT&e3yR5kBk3Z>hZ- z9X(0Y)xf~KlFi?S&R;9MEh$Isd{Oa!h|;BUt!WK^1JQ5^r0Izgye`S`bSNSWCG0nj>`4fB69wd zI-}?W(B(?n#Ma4Z?x4`d@Vf7~0(lQTnmh#^0pMVqEk`~<2n~CMRIbFRH9>@d!B1-V zv_Sd4;{YIVb!z!9Y<)W5$-T9)MiM>9j)uLZ4W$34Ml&u05ntB zkXGkQ_5pT6{(N+Xm`t$=AY9 z#7NywI7^M-69V+@68OCDU+XLeUxsh9uMC^Xwt?X=b}Jz)Oi)tyTGC%!Y5}+T_tP2M@+*>sSZgdhJASoFViU8 z3w7K^M0&~P*u_W53*jXf_&}fXsB^9z$( zCM%DSkBB^|CV%2cz>K2bM$?fzZontbA!x?`o<>rv-cIyWOC?^=y$&-|#IzcxlHgSILXWv>ugb`z8n?G0STt#tv)0sO$LBBuQ zT05$cWBfirW^*)wOhO`^vgu~W*0w2A#1xxgncJHJ{G#+AS9q8St{&yi3u`jWdzBGu zYTq1#FfmU%aaX}%_bw=XmC6;LkEc9&U(r9OI-y4|&rz{_sG#M{76^0AOsReeig3SU zs^tbPQa_P-@dksLolgfOqVZjd>7Z-fz69Xg1pw^wzw9-NW5Bkeso841O4Nlj3} z#^rEwD`Y7#J7ss=krNjaj=J<@V7g*WCFb#VXGLUVa!}vjTJ8J61}OKuhyp?XRlLC2 z&Kp^7xU}Bj9^nxc|7YJTnre;?PqBw;!i2(DH6xAstkqo;W?Xz$|0{vp_Vd(TW>^C2 zet-5obg!n;tuJb0_@ZI>Nxwkp@JD9bG?%2=XNp+7{7DOYwrG&M-c0;=EndkZ^!izo zQ$1DB%`1dQBbmF;(KZx!uZ}TzG_N*v&XY+>-roiP%GulPSGmX)q0ev{=iIxOJJMJ| zg!ucXZ;8F>LL2p!*@(X;aUX%Q>eb*wSc$)uu-qS<5m{W7+D+%x(;|N-&=0WVkPbD< zQkIb!)h`H%0V&mYfv?#m!}oJj@R2Hkb{XWlRk-Ha@oHO(>O3g;w=`Y^RykR%^A+;^xq!4ojwD>w%|~&|dC=;kZ=cPo ztc@Gnv%qQ)G6K&#)bMyj^#018cKF=+UYhv|ii!r8`*aE@eYS%wHkZ?KgE5Cc-&0v8 z;PMsPdCkk6y}ip_{$(HLOnmYEXb8e4!=v0B0h0fTT3U`XO=+StW#W76c0UKd>DW>i z^|ze347cpwwwMGT5w$1Oyg@e7NuEG@0=#yz{u}-8NT8h6vD>2c9&5Ocz?QNhlYU%L ztCkH}O=kbf{G+!G_5q-#^1qJeAakZc?DpZI*vG`)4ELD?>U5E-*$V4>b%B%5lGJ^Y ziJ`RY`I^Z2a&gHfhFm4Pq79YDmz*6^>y$Gxsxw+^HPA}hbLW;yy!|~nF~HL8dM_)? zLtj5#+%aCxK^saifj%UmdgIkp{)1xoAVj%2<(-$@Zt)BR0c&*M-38NbC(L8Bh68Mc z_==)_Ekg(6Pr`z}b{P@|l7L=yw4uO^kx~M^BI`5eW^LW8>S@3hf&GD0F8dyK+lICD zukK*{8xYNfo#h^ioX>>-?M_6HRDf+b+9h}U@>yg8FPSanr8~9oR4T% zRkic4aT?mC_MdDy-~RmGb!_E*VNtiIK3^VhI-K&SzoO^BjvW2AbF}*5U*MWOz@WWw zbyq^@=UavH(>$vK*s|+%dh_n`vB^0Qm@Q0S=QPdPIc76{ljA!GV9+np9FT8c^=6F( zNKdhICQVQociz^nr@r(e@@pAYy%UoNs|YzJ(d&~%k`r@TXD8N{QJad3OE-pDTzw?K ztBEltrZC~u+6^C&5-*!BF~2EV>H+0-WY8TS5E9aD$$J#oyDti7Dbz@7Wy?^fNz|(DpL=A+*=q4RG_EZ{}Zg0`2h6<9sm(_mDh7eV8eC$rzF{(~` zS=w04_W8uREDWZ0S1H@VAZEvNGdoT)O~?%3K((7rNJ9w&f--M;P)@=ST2Gog@R9oC zVDawQ#&GoFbAZvF+ODiqq94Z`O`mx3D1RnaBu)}ue3OyxIdZ)p;w6@r(pd=hr|I@G z;b)XMPJK0;jK(I;ljwct3IW~rvARs(b{F0~?a=nlwn33A7jM~BMo-Pe%X$gF@lp2KI*9;qt@J?MfFs{8+qW{Q7Qc8eusfykq z4IHAgo6oV^4-a0np!&VcF3vDxJ8XS{Jxa>r2~Iu_TyO z^3V*HL@ke(vAQU*OzhxNMZCR6S1@$Tr}B1D*;0qNu|&nOl1h~B>S4Za0)i|ublAJVYFou{bhsMk?9Gxs zkz%@9^(E_Z1Dm?B$mx-`$$Hgcq^s7MEs<60;@08yj9V!2Y1T>ZVDgQH^Vdbiuh^d} z&PlJHurR)72%0Whz0LBd)Vk3lb{X5@xzY7!e(Ih~EuV^TBZ4CvW-T^%f+uW{q9~le zrJuy^>^OC)Bp&>x0x%W4mKP#QckIhwnNr~kQZcIrC}Pa2e(u>9V&Xae|0$%TEh3MM zE|}Q&8W$dEa&zK({9&oRKEy1rb=o-?UDBK-NREY;e{Mk`9EnOXows=k6VQWhpgB=% zUy1U0K4*1Mo{Y;=@1n!BcR}f-{~~jnFBHAsf+2rQ*Wz*z|0)J>zxnF1ZZTMC-T7hP zSsDU}eh5%BJ1XY9WPA9vx?2CbX$>!$e=vjKoCAU%vJ|6b(S43XZKc*j8aptwX9m^k&Tt5m-9Jc^ zPXH8M*D{Z!xVQp0#ao2^AAXUS_--jeQK6RD?kRlY0P|p%v*w%qMB$fx&sd{!o~#q+ zaZelh3IG7U{?!jpJ9Cz;%MWXmwb6H(ht0idBVaV=7+|a#2ww~e%QtI7r@le@bZ)1Xd-N!^Y zIk8Jq;iJyX8yG2t3$um9{VKRSlJrGSb6yMQW!wA9ft2>}+jO~FGXq*gVEp`=# zt6ydN%%~=ifI9#YdCu&;AEpBE4iiB5|JHH*bg3;kH1C(bgY>VZ8f&QG%zyKD$xQx5 z9xN4%7x}2cQ%>PhTvpBP{bP?(_xi_vhJ&vb39ryE|8|y~NSLslPc+`k0{ec-!r3l4 zPcB7rH21wDv}6%_k)~MYA3)pY8ua=Ig?a&XC0|pM863v!Lh)C2Y;$7kPML;N(a;n> z=c||yZ4;dv;uT_h7>Aik_kBliaEyzqgX6XVBa6 zT7bRIMWYyu& z2nSk?DRnK>^p@J9n)35!n0@S%)sYN7XV~NcB$g5*Mrfe;Qx|YFiZ1{^rXTEjbh~ro zYVt{D4GvX5=PI7%af66t9&H#p)0E|D*rkP5JG15(diBr18#4S%LB`LCKYq3L7XGnp>1xU$L(ZmrP(s?C zcV+zY{ybRE>P)LjuSF_zJ76@TI7?6yOnwiYpJ%rnkId8FNCuDCDMlf;8ES&{((Bbg zz?LP8-<^9KR{coDhbY$kvul_^x&A=En5L_pqRwo^r^KSPw=dhO_}wEkLvFZdjw5hl zg>}1IPbQRguf}_vBSUihx7r{0zAMSUSr)-!0hHZNfI&XXK&~XuD_-9y7l|{ z=LvLs3$GdJ0PM~SJ5>Rx-N~NMtUphiIw~q98MO&4qu@(vpUq(<=8GKNTaYqIl=yXmH zvWS%N5`{y^82v6zGuLdj@n_HvCYA)g9dcxJbdlL|18jCrRxb;zk5HmeKgmtxC~|UR z?XO6waIk3Z^-oiN+<-SCpWeQt%l8zIe0>VWw#|49OXgpV9{Vl}7O13jByvD4OGeV6 z7N3{D8{DT0T(T-e6Rl1nV`j#J64ZzjJ^Qhfiia+uG)u$7Yxz0agZ%Fk?@c?i8uMAsx$^bm(jsdmY8S9{axHEY zHeF4BGK}Sz8?umV>@2|o_Cniyu;SB4W+1MF`129wgh;{Z>o`~fyF zg`|3x8BVQW2QxG;RK{7Rf=cxJKhvTFYAxZr+VXShr;t1iAUEZ&4(*7%C&Z*|$q-Un zoo+$mHB0W@y<@j0$46?B20>!PYQ;RArE){p8i~~aYVpW6r^38!bu=_PtJ~ZRXUQgV z&`6Nf7YH~tOs(UkeTyO1%d#u-qfLc?rhA`r26B9d3+JjI3B|So zt|-X6cVBl_s6Q6+tSySsDi4ZFw}o(ykF0j(ZfozTtH;w5=Yi(xpN%v}nNzRtAZ3vm z;Vmj2!WbD{1S-X#!q(3I4K(UZa)u3B)Tv6|a6b=ndsRYf4-p}_>giQR> z+quuwTW8{1`ugliIbpLFOQ{37)Hw=86SVX1XuuqdL|8@>hevzzq8uF7(nEoy59XXg zCZ0WtR%P2Z@)z)M{d-*tYBwNp4b|)2=&Vu>RU%m<#+fze%3?%;FQ%<%`cnx z-ih3@uSK>%=RW{Nez{Z4a+u(=9$UCq?)fUJi}S}V@8L;tU{hLmdWs4G3Z3vhh>(J9 z_hweW@t7$pkszAU+lH+w7X?UqbGOz24d<+~2-)Y%Cai3F zTSBrqr;yy>zHAsO+UGB(K^dm0A$KXHh8kkmF|kMus7k;)y)3?xTabgOckl2JD-d&I z$^iCrL$_w6raTQJq;w2{;TSCWokYcmWxIOz$oZl8r1+oM2<_!33eoe#4hY3+S&AWP ziC1O!|5$El{@ZdB78?2(K0Eo(72}e#GB%y7cJSXsP0nBfNpBM^o96VX`~Svg+Wk+W zCgJ}@)U;cLu}+bo|8iQ-cxS z#ACSJTaDG;**dT5L+Ja(+9mP$z|iuzX65jL1&>h=U#+=(Zgpk*Tu2}$meH1rh- zNCf=oMZ)wlU9IbpSaqkl&a>}PVT{z%1TND+l$+n5nr*lC@!-wd>#aLadvk{!g50Ef zG5BgUTOF9KR~jE2KjMyv7d2gTVZ1DzF@^?aGo{NeFbI{BaiLuJk02NJVw>vT_k@x| z__gYqB3G1Wcy>Y|#f8}aV_$hfO2y@bm@Oyk0qV=~3!voVjVpf|jweFho?AueOwQ)XzKSP20%dWhiqxd_mbH`WTc~E?&*q zLctgcm3UapZpl^tn{Vs58_6Cd9km)fl#1o3I~dud3rk$@MQ`o{%J;qIb`&kfFj;R; zL<^XI8(M6z)(hZ_ILPK-#%0t|D3aVHnllH9nxTT{~LGWYNebcOK*+tpKxG*X;rj5>Y zsg8_Jb6qYUE~_Nyr+K4k>iycQOo`th@j00^^$-SgBpALtG5gRzZqn$C0fyK##_weGf~aMBm~eFzL(CG#LiNI84|Oi zV&hO}br__O=Z;B?1Ydw-G1<4xckp$5`~btdi9XVP8u4Bl<;3A11o}$f5w@;e9fQPS zufnaMrgpC;NmEo_JJj?T~MjEJeF=E4NF%c%YJlQgPNQPR=k&Qyi_?G)B6&dIurMx+wU zkhe|7o_SX_WRv3&kwO0i=ULBI0Th(O9}r8nU1AZK0KGjVr;3_bO$b2$@ z8SI~L`05x|SQ1f1>xS5B{A zdl&bJ&9QC+>n1qA8xmp~*Y-qJx{X47Mm`$fsL3%L4d$Ulr}dupy8F_);thg~{O&U1 zbMttbOLG7V|IZMYQ`g73rbIc0{h=&X^H5~v7lJpPs`a=c?fCHQCUp3a+AGC6a<++w zMXM&1-K74paVjZ{dk54n%Kp%_3BtjUX|pA}iT6PI$n@@U6-QxUF)^j}^w#yu_-0MG zc0H(Z7v6q}@M(m*U!~#&W%;kS^t!brhKOBkks_ibWIPcHU*Ho%jb$

??p*h8I}VrmECFrBqvrs$pT4H_@s{?J%QscWNa=Kk%7}XeC-9HNsMv?H;P|? z#7Lvk!%{#k%S;_#8fli9i$5#i z@`55_lvBTqT*i5aPmA>b0F`GYP>X&xU~@BTKT}a}Wn$)9C4wx;+YXCc0O1%py9bDO z%- znidBR5fLU;ZHg$Tg;u&ey9(@I67F{vHEwXi6k(FOE-eOg<=@HejAtnJ+#C=SYkS!`O0?iPlI2>a@jCV0BDP~liR?24-|w-<>2VyxT#4xM z&$xg7*gPxd>cbPb?ZD{QpBu7B_T<0CM_8Wu6RV#tHxY8P%lf?YSP^$ze5I5U4s_>f ze1XFe6m^GI__rO1{&&hBC(IqmGiL@3<-GCDIWoi_qd|uScCD7_>6SMr!xCtK)L62i zb&IlAS$>#mv44cq2zBZz75-vdDitrzfyNq#8b9Sb8c>ft#rhd(;%D!$Y5|BQ9fTYc z;TR@4LRPAo`u2;|k6`_CaB}f5lp??oW(vZ$rQIb5hKtHr=znhLca3A^9&EDQse>+p zhH`D_f(hG}2>9_D!s?&YkZDB$Uj^|yRFFe-DP_XtWG3HN1ej>URq7G7=qhbuM!QH| zQDu_tb#LjE=4@69Z}{ij%+oOpGz<8rdsqffA+>Om+ud`eTc<&W0=zv7zWxjc#2AYL z6SR8HVr~7wJ5D^)0$Ps=4cnZtP+hxmCJF#QNu-7^NFX~IdkAK zO7Emm>LNoX#hY$j!-3Y%KlZPn=}GId7L>`@^D!;8%Mo^!juX(nMV4a!}LSe(ReJ{0E?dqk?6eo@|n@Om+mcB3ASWZUIP|+sJ z`w`DZMAuH%+s^9y;ol#=+mdVEax;bcesnJXltO6E@@&YY{N1j%AL(5Fh7?Hxb`kzBZ4!~HW~*X*j#JBrnR=6N}sU>+7>iewUBmpxW)`bnLz zD73*(ajEGNUPGSv{JfAb_rT)d$jwVgLh@s55Z4EKKLJ;OJ^)WsIG9PLSci@T^PV6$ z?0s`>B4NZAiUMc?pFdOi zfB(vMvmXE591a%N@3X==@AWJ46AoUx#^CV`-gXv`yU}x{0)5~H-w%Ov zo*S)ajMu6Y2hQp^?OrL%Bx1JVtMS6ljs8Aax9DL z(eKG?nJ!Yrg}alXJ~+4~UhE6_8)H6eeMc;mu}PO6&MM z)7FDK%=g(lMS@;1A8QbCbt`A0Qh|z-2U_bm(!^YWKsb8?VRPtFrp$8<P%#6^t8LDk}_3;;*wqxilR&j z7{)mI>EtJOwLBw$wMWg5gw!`TA6S;(bh%=Ug|EYAt{{oj3PUkfrlP3Ph(FYE_`6P3&^u#+q{wW{5Na?K{E>Nq$yh^xvC<7pB7gZX)DS#D>d zPpO*atkWRndfL{wdUa@j40p+%XM#zfl4z=IDc zjR5E*8wSH`LaT3?%;;%VFD@%SxO?F1PFMW{4NQMya}XrUq}Z&e>FMN7?RYH6Msn!c zHr-u$0%bhgEA#x*92!eJl6yS%@Pt#vd^|=j`4TdECf>uqz2y>p*GOpW?g>N{<4n}g zv&`r7tZ{_qT@B-2P_2Qd3{NJDbes!hj{dfN-Kaagq6#yPpW1dK^u+pgAj30e=vz9# zeJpgdW`MPNE3)d>BicIj;l&wKbS1w`!GyuyC99F$?XgV6dSa>We5~dtN?F!dQ`D1U zKCx@bEXpHTQe!Mzq%zSR=V~VAXLC_nBwZ^&%>^;iup6PJs{QDq6!FMHBtX zmZ>Y);7@H)hW;jVVJ(Kb`!`cN{o(vhZQWye3^1rlO8Jxo4cU!>jf%Q?V&&vK^BpV` z4Q0L`e@Pol!=>OxK}PPulNFG*4>?N%gMK~~nU6|li$QH4xqgbJ{?M)4oSRp=VvR{n z=$C@)D%zn}|4{ z3rezTV=*qLyG@(>D~6P_xoixL>*E=ZliY1=7(L%$`ix-XjVu63&-MH1i=4a`w{mF6 z3GGY>CfM*_#WRu3rhg#PPyc1D zHpBE~wyne+J~enfcf=9g>cGw6*DME|o&X zpVJv#w%T#2H(uA=Uy7#`-A29b2hikCXTG|>l0BK4@+_Nb;zHV%SXl`Ga9;Mybw(q) z|J7*J{b|fP2_cZHcxY&-`#;r`kv=eKYqZ#KPO^}u;n(v2R9ZfW)fdCB@<0z!jBSG|1?E5dHP+up#-wLUcN zP~i)w#2S?&G$b16u6!%m17q-~Ybd}iEPN;EyPP(wDSj$5dlW?E)*T{~I-2VnMJGaA zq8dmKlTW5TKcG~-G=tkYr2fcfm-b_#6h8vd>{w!$SJ#dw6C?_V-Ad*s`Et)Nl{@%B z)Uz$Jy!+%rH?g1*6^m9!-wBi8C3^pb#Ig@3FW0fs=t`C|Y`#|-!u3B`fFG8jl z%M&kW*XZ9O^J37PJzrS2{A3rGJ>*NrENCOCNckn0hD|abvtlc$x6N$A6@P0#dDg|3 zE7Um+MGC#xTo@!c)%T58;>iSg17q7!_%&M^tZ6gLA&A=(Uz^*ihc)h=tGBSLAQXpHDTg4yKX9R@UBsMYIPf4_^!JmhP$(@))6_kQ+^DW+R4r4V@fS>7Rf*ksK@5}QGc z2|Ggn1cP*IZ9P`mg?`jttINGA@sBDs9iKI#K645Xkdx%-;c{EOkmUkj4eEI$DG*Yl zvV#QdPw|KvpL|G6Dv9-FlJHqzB0hP^?&ywtIkT7~cgXip zc1={p-K^-U%gQF%*2gDaY+MW5PJ_K3+s!##q$VRflF7?fp+LKy(Uq zWRh1anPM=Rd)O=ox5Tp>Z1-~G1H*DyzKp@+ZiTWiv*B(1x;}!Nc3z#es+~n}hei*j zcfh>FKA~0f3XfJpmVPfCmY0z zL&8;H51zomoIiUbSdPfkp-g;Sj$1s&4XMf@%hapji4OV9=<;EWb z7v=z=B_6XdJ-YhhI+J_4spm%8W4)MA^Tn7@EDbG8e2>D zbM>PH7YKw^T!LYM5Od`KyAJPIO?Cp8N`VtRPby3lL2>afpR^Ei>Pcv*k}O1#{D+?m zT&{UMl4J^8-j_0zKc0}~sn{4!l)@KioL<_p*j-P1C&?Uw6j@|9bfSi~C*K?MLG{@+ z#}`I*maDcZ3Y^&%(Z%QF?SqX)b0hBt*8ucvWmD>nBEdk+&g<`d&xZ%fq?!^{6 z3gn#=1M*;&^k#deZZeKW!~IezQc}yEu`*~$E_7eAjmbh+ ze7~-G-_MP_zSFA8RFG=1!{1VXA`(SxLQ1dSy}A6MQ1>k{(?K0FFp7LRR5+6dSgI)YP?ii6R)tV)DN6>p`>x4hNq#)2`jzb~hl|*ECz5vt?ZeIs zo@7*p8vUO{?yaD%#FLg1{{q^bP7rr%6v?;2b0R*r(1HfmZR6%XJ~LRc zOP$Yn7&l6X^Vvn`Ts4)#-6lAC!b6L=z}oh-**}r$AMr}2I(gB*+feG_E*aGWR{ zr#!^l0tvkO>(4~w_MPk$K{4)Z{wBU3qQ5hOQ1ll|?pG6#2`8bK@jx!R z#EfbF=|G6oNRl7Ib+vv({pG#3hM6qGuEKR(qLoBRq;rs(D$D9{b_k=+rT#7--Ezb+ z@Ago&)TU!R$w*PXnI8s^u-F0q;8Xd0GT}g2iIFtUp>H(oRz{^zYTR z(UoNfh?v_Sh{-l&bY%_!s;3IuP^mnU8B1-TaH3ZGzx`}gEG^rQx6uRdzID{@Vqy2J zr91##Jnxt4|E#<9(*KhGQor=)Q;0c`+Sh!{0rI@^+PNb=cEW)*JagH|6oDNNW;v!Z zU$($)Vm%iHpM@vKi3%!ok-@U1_S5*6M|0c{1fZ+y)DEr;!b*g7pB(L~D4-mLVRo&z zp_KH66jx)q|GT8TX<|71Shml0qGZ8=)f`$9;=>#gjrL?r*uW9YY80;JT-Q0Q3_GVu zKli|$!7DTrDeHCS#BHHx>&V(Yobm$(ilw5DR@vtQ?Tq-B{G$eI-)zm70@#rjt*DMd zwHW4No4Zz}9Z#8`z8uR}i`EfeQ7fdZqKJ^Ou_q~^BkZ+b9bb6goUg^E5g;uL&yO%= zbW;7U5XhclxRM61H^4fzSn%mF?pCUn!P;d^e5yDIjT#X^gTX;^5C0)|yALWdg42C! z!^|Yy+A5qfAaj58Y|>KRny12`U6rMWyJI_fGcLI{2sIh200XQ(cIwiZKVsT;CMlsf zP+!e@Y#=+`p*e83s1xtfFSyI0qUFaL z%tgY{BTrAsRkbv6!p<;L67#Y)xfQHL+rKA63f>#23{*CfB#_ix+ zE?cR&N=$`#SB6K(Nt~+Bek1O8jd*k8FSCZznOU2OcBrYGcEmdySVMpHyhwE`% z@U%;xW*IU^&LdY^>gz0d+e2mSn*MOWwcA8sYOjlriEgDBu-8(Z%TC@oHHn<|XcT?C z^>QLp2sUsfDYFZSj0H6xIQ1qDeT|~jV?}6&5i-J=ci20g|BAS-o<7R=v;U5D^@N?M zpdiYbQl%j)jW)ckJseS(i8D+tr@N)qB_3=Y98dzQE2#-1@)LOlBYT9bTtrs7j862s zqxG}}DATmbBY&;}O-v(eTrtQXcvC^=n8SvSuIxEPM<7CPXD_5MC#1!ab1B-x)aL41PR0evvr6=&$oEjHeP zi9qe(-`4cmx+)@d3nN4}nK>Icx5*8?iyXoZt5a!`9LmzdBgupLHedjwA z8yAmSST`Z(g96Y%G7W@D*X|+;gLLWaf)+ncx%KX%K^xfoXTZnzIe(lMvpfp$;HGZ=eEbV_?|HpT|HgvO0MjPsTljh`2A}Aqk8!G2E53e8qff_dokNT{ zlriWyMEOenom$_9kRBDuDEVjmp8Tj0FOvJXTK^)w-ovtSY(`8JXyW6o#yVu+buRes zY<-Bv;>6tuR4pzRET>@gFayd0lDa`^~1%Vn!%F_5rHYZV-Utg+C}chJAI!yl!Kx zSg;z`ziNxe@5%Sa7(KJaTOSvf@T*81a8R;BwU z#3WRH7A@a@wene|1#T<-ZImE)RjCY-x-*g`%?gyvAyvgQgPpKt8}Rb zx0rdEt~@%;1MWi&Zg}Y|Mz@|%i&e&k2TeDbc7AQ(>fLmKp628p z$s9yrI)Q@<%XKJ17r}JaolrMfd7nu|*4&qg6@ziB3~4#6Ydox?|AhV>QQB-Lbk z1Et$%k~$xTVMuS+zm8=WuhKm-2u@yBo7{%)^Xn z30lTCjeNse+p}qGh*s$u5Dnr!ll!U#`LKuTi)csLfx#k&apqUB%1(FW_SojFI>KA~ zE##X#sOHiA2OI#=3elc+8;nMhx+RhR^|t$b`EQ*uHa6BL_8+YV=N*x?U7Z>2IHMuv zpB5Rpof{bU&UfCh(rF6L_;3A^^`PJ%bmwv?7eE1d&9_LgD4$)v;_mQ_{yt%A{-2I2 zBJTX!g!db^wYNJCZ0-ocVt56?A;cr_${mVq}O(Q{lb#f@w&jxeq zMnJj?M6D%qP~Kmq91od%k+ZFLj=@|WDr9D7pM#=YlcSUHh&y*Ds_D@FSFN(re`Utr z95HjGWmDaOlfO8@F}+;t<@^iR4c6cCY%r0GcQg+?HmnJ!E%8q0cod^+hM!Tw=j zx{FVCdpJ_N%l^^9hLM@XUJE@v8R-g6dx$(k$H2o;IUxQu=h-!&F@JfgabraKk*q6) zN{RKY9Bl$%^!C#R3CX{&?Rx2wpV^fbPqRBs(QJXU-W@+UypEoXTs6PN@bo$L+rhL1 zpe`)Z$1m5D(+vYLx;!x5=j%6}=hSYmt}Dh8%*TpC?)AN6M%yWo28Ypii?5}zHpu6e ze=R1Tp6zqh74Pb8SL+)}m7y6HBs-e&zwS_)oxXLexUMuBcpvjZ2`DUHUe5f1;nK4J zixjd~*Rt-P8w}Kqdrl0gpkFpL1F350z4(?ub1$KiHh9}U0fhM#>G;mpd#21cG*O1T z)jhq1P6kI>W0)|SFrMWuMlTGPF1IInCzKib^e5`I8dAL|DW-3C3)0S^KdqiVS)I## zc`OFaQPR_E^Z)kN!oCBz{B~XAf4^7_PJ}3>RHFVHV&8krmBU8~DlWmK4jV9z=dX03 zP4`s>@Ej0qY4!R0;NHa>&;7DV1Qq5_+d`PseLNIr?~%bB3Pz6^GV5c_wQHBemez?$ zJ!w{%K`+oB>IF5nt#40`pTV7kQ;P&cA%;r9-n6#3qrn@^eMdvI>v(gq-m=e+N3GL` zyKp1HO$Lia!yQZx*x!t36m@VV+i6`8$4>sVe*y%P&on*{t{%UAgfISVYrTaf>T(h_ zHcr=}KKB(^k}n>XXn7&4&*%Mo2&Ef0bkaTan?EyWQR4ZLDlbgjxgUPJdL|Sc^DT~y z*nIoFpfQs8Fu>@cN%NlKRIyreHo~OP4&YMDmImx0`6-y*O|fEwPRvnUa-*zXXJL-y z)?w^+>C}Xt-$Og@w>5o|8ExdbF`zI$CMxYrpzwB?do{Neq3cs`pf6RbvaEd?3C*{gqgsxA_^4`wD>*_PFX6v zyiy(SrA+F8seD&!oY%-(#?tivQ&2@qHUA|nTsKh_GnH8uo((b1ju(yt{=n~*46R=x zGCufFI`@tXus}z)s5?yoh^Ga*hE;-8R)=SkDK>N&FvDli=C7GwnP#-TunoSY+Rnx? zAm{01@bCcF4KXO*8INw}qftD#UDDa?@?SQ5ofVq>t2tM&fTrLdd&@G(21)vd%8OVu zL6*qKw@=8A`*Tq!`(R4r`uK-nrv%k*0P(^c%q=c5ayY55CsAh~6mZEB#p9h?0TNgK z9TOw(5hknhh_oXhaXs6g$eiPuK`4~cTn{R7aym0%lDV}%+@Azv9Htkza?NLc``F^4?D(%cqA|uQ7bvk z^HWIawCPeZjeckr@$H!Gw6{)gwKLsYc+ya+}q%u1j zl>tBR8lUvUdd((-WdRAp2S4u+kBqURYPJ-G=-i2XNM1_MKD;f!g?WoQuig$FQu)wv zTC{7#+30kQW}>LWt}L|IY-ke&DIqw;MyDPpC@ioHghScXNBJUru&&+Jo+s%&=&%3X z1BuYCer_-E@{EG!x+B`~^(Es0;34(9^*f{~juQHd03oFihv85_MtlK%j4VCrLLj2mZZg>6W`j zqth%N%sUHS%DiSfbQ`%~o>#PbCER+kx?OLQd~$|_s;aOYto}wznNrR2yoa{NxTVW7 zG*BcRbKbUd4hXA$K3`efJE#jwGdk-Z?p;VKvNuugwUV;9&eEZTEpkzbYtPb=+v zD)LsB z+MKn*s&tFXHN%CnYtNhcj|~`q2CsMa_pK#g#=jvS3AS zm-w<{TdVmbX!d&*%7Vd6GLbJ{OWvd55&9ET@T6yWBIsU_yXDZ5yj>ud;31wr$(CjjnIseNNxTz7e-0dj8ILMrKAvzB8XO<`@FeX-z@W;8!}| ztij#Weghy#@UpqFk^X57N!iYaiHyx@{Xq><85@m%Vb`0PDl4hEEO|89GCl2}Apa9y z{?;^9lrqU`6A|iT+p4e-aL8AGoR_CLsB;-|RT(J9pz0iX3s;qp;2Ky!qoYWDPi1=@ zZeNOLWIvv-rzFvlAUMn9T8Wvgr9Z0SJojE)7*N||0)b)0=*#ctM*`Z$^bw72wqC^z$z!Gfw-?v*-A=tjjO+=B+k#8wekak_Q61lis~w50vJ3{l&VO`^2=^7w!Gk= ze>_j;vWhOaD=K;0%#jR4Mi-HLE85Z)eM1!ha0@3}Sz%yu^D=fHcc0o~x?hl7Dz(C+ zo8v89g{52OB#wD;;j^tY12}v#MZUEv=xwSsfKDma5h!O%Fsvstd=SK`A50ZQKdG3E zCcB7p;Wt4J*67SxQ2pbxpxHfoR6LB4`)CNP0od%&W+H>BH({)iUt)qMT3aRD*m?dC_kb?ccrEz z5+x{G6CO6UA>+f|?$C-?9c@O`+N3gSL}T{BYFZRU7;@wLBhdta#T}mWFdD*EE}7kf z8WWYf(3(qeQ9e)@X8mh-y^BBZ%35qjho$(alMpo_b(M!~V?@G4SR)22gU47akhKGq|SF8P!h zuT!V)nVt0y1^)wx&pDYvWl?5aKH3buO!zi}%Jy#b-{kk|ySMbwThH_IoZoDp`FgT! z9v$tX=Q{1>cgQ<@xD*NYnh>u?t1-DoB74*xt@E;6<-TN0;7%-i4S=S($lS3NSCJYEm5feDp}$wEF$-wit6`JVEqR6 z&81Mqq$GM%bUm&|1p9GsE5Rvf{ArqO8P>z;jm^aGdtZeMZv)(wnl zdcyXWT;zt zCm}HgELs z@^ueVw>r&{&+L)`*)i^x6cz$Grc42s?nQWK7_fxpO@-$MdmaOYB)@5!K7V#lH7^?0Dv z$I*Dx&;hEBqn`nchrvJJASW2q8bE}PXFEkdvP5`_&kh*T^6K*=5}dlgu}(Ud@uMC? z4tR~u-o>ld%&UBTFups@08Q#(+4y&hwz&@i=rLVAr{^AqI2`WYOs+5v7e+7l=9W@RfkZ-@s?@XLc~QBCK$=j7+c2-w0JAVs;{s`T8xq z7*z8$S=6e{Vs z7A7mrc*v8jKo-iilKzFO#$u%`4A}^XH&ZUBtXzXL(s}4t|H+0*3v4|lAoo{2Uo3Px zcaG4?N|~lOzp40X9>%LcKbmPBvJ@#pEmhvc6Ro=McVso6$%DNdw%#)#bhsM+^&(|E zKdVXjd{Eo~b<@+|&PB{#MBKE9@nnL|bJy%MB^De4ws)-_Os6|&u;?~tGC|G4vZ-5t zcr)Ap;WSL$g0y(vw09Y~EQbm#Xe_0;uwrlV%vBxCE%c;c#0K9}u4IlCv99@Yw0cn) zQF<8OE~_rok2Rw|hUXyCi=&jJ;EwAjosMXrR5LVHAT0pk$A`Dzc8!u~q1s!Z#>wB# z&5G5$_g5#o=9=&_cdDD+7LFoXVlLD*AMIy5*o!O2zPv3_NJsWTr66I-A(rNrbwqbL zIUkt6ng{DKEV0haKCDmwnc9B)-+)HcnexbC_MXAuSZi0?z#Lp)}jqN8_ zJ{EWW#>U{wTbHZr%dFiTUmc1mRyU*nQBw{)OkrF;P*VPH_YTN-_;a(DJI#i>8GT;v zY#Zaw8|adO@$>Lchb#Q(tyUCNDwTr0>TCzsb?Osspb~@&KTKp;a5yrWd+;p`uJA~3 zI0VLX(5PC_N~IAcKS<`VH8{2j9NJ15cb`pK2?mHStz#3?BNmbcuo`+ zU&KsaIk}rNHvccc_t%{7bI(q1WPTa9Bvmxyd8+{e3oHTME_&kjwR#&T{vn_4*vRnV zInxJvjwg&!=3cIztR#Ba{I#IzpG27Biq(cRbz$)P*Fr29k5WwMpY>%Pr4Hp_Ko&C^ zW0Mp{SCcvkd4b`bqd;epsWa;T(!34kXE)CmlLiQ;upi|}^2QaFn8tiCZ``pxQS|HQ zd2QY0@P6@xn55#e{~Tar6T2XuMG;60wl2Yzn;@q+j{2?rM(BkFVkpD+>mYa%r}Id} zPR%fF`9=&pB|Yje{nb%7F`eM`n(L6>05m;I+mAJy_~%8UOpHLIW}R;wK)-J;U|3SmwD|{ozp0-$}3JmTY?x_jkO5jUBJw z0gh@$#A;x~OH#FXQ+}B#8zVP+o>AKsC~%21`MP_U#(NU}Dld+x>mQv6;#!^n9g~ zLOm|U<*`83nb3V{`m6Dpo`%ZpAloyRDl^K)_%h)@Cx?mf|Ep8`du5BfkfJjT!*H-y zEp?Zgo$+~aN$E*$WJK|Z`s7Df;f&x` zUssH6WCz7V0`40w^>(@NMgw2NRWd1Z# zzE#mTc98rdJ-~;Uu>0V{TQvI|^j0T%#hY!~0wzPJ)tvF1JPw)+vA^8QvcJd@tEw~I z*l%sh-_#}4PGKzhY=U=xk36WI$75lUj`PoPj!u#o$YvjT`UMkY4gl>}vr3{tFVki2 zKAie*6Q*>`e+Bj=ilbM`T9_r!eE&K&^0eYQrkVe?Vf|XC*n-i?9^C2Hj1~v^_W`k@ z=>L*9e2{|pIIUOf4u6ti|LNJ*^)q3Y3Kq&#G%`B)NrwHWskR&Ve;B#RX-O1*4#{^l z%RT6h=Du{MU*rC_P69Xi|1fRufNSki(4m5}xof z$FS|LPGAG{N zj1^51*B2F?O~x|=sp&ya)#w&k$S7J2I~t`qmLn%V){XbLgTl-?J8`aqmEX!ZzXz4} z3i&^Y5cky*Snc1{s9VmLDcSDNfpn((_b;cYD2L6_t)nn>8;FL|1O^K97T_HEhUb!Y zoyDmgl)0|vykVpHtxJ#OyK|4gN5hHw*^c1B%ZqTkANP#2AD7js7f60<51?x);a`K- zqW_#F9+kagc5Z))Sz6S49HeqptwkU9!zsj;2Y;SDpw!FRqhiIYCz4??&Cv-fVaa7c zS=U6JptYN2bJ!%Xf}GLSyYEzIH|gxt77!=N#Ya-~u&mxwk<`XQbK7-uoPFl+<*JFd zSKPC0JQ=PKg_kn`8l23z#HsjtHDnfY)W?H2{Vu%OsIo4&6l*Prip506al;Y!(D25Lk0kqRuf7ml z&w)25z`9l5MsDf8vAunRkWsU6DFF=Y5HA^}J6q=1j1_#$MaBq)DYleLty^0BDM#q( z&oq%6l?R8dE0uHsQ*0}o&yu@=@dXvSFe0B8q2hF zUIA@=J{YfmYmISI6O>-0arzFAdFYwe_0BTKP|=drWO}!(p;Vw{oV!13 z8u*f3b341M8ZNF|fUG9jG7;^exjZfo(@1bwQhRNwt#5e+mkNp@ux}py>0JF6^(Jba zWhzfhKbeu*si!8Tb0|<^qs+TMrP|i2*(yBFe2;7Ou6a2}5Iv^w)BjT_lL%m6%`6zD z5oSfX%1)*f0hPD%Dv@|&SBiE)c&HPVkO8#DXnKxOs!A#H5B@Ij@8;O-svd%}{iPH| zrRw9YGnS4bSc_WifJ!>EN&pqc!J0`{9QIRfzwdq3nEqc>+B5k}Gk1fRsVq<4GsGt5 z!kL$b1LOOiffZD99{Kyu^IR{^F#$^+>wrGyy zoN;mm`mO2jpVD}P?hbJY#vSZ# zl&Y;YCJ?9(Ds=Q-(dr=;EsbYFir}D+XJAVr#)3~aOIE+c7F%b_#`if;2>Bg1LptzN zgOO&E3mK0&FukHmY8x5UrfTh`u&O?HpSQWjI$DD7ldEHDj=k_4{WXXA_CE)2OP0b1 zGRDPFxYHtZr>8c-IpSSoK{IiEwVoz0hVNW^8#i&HviT=Z?}t-nHvn7f!dCgUc6N_< zTQ4#hvruoTf+gwezV?(A;@}t?gPuOkup@^f3*ND9T|< z<9)9wj%p$ys>SA3VQZ7S^%5B$EsUVFdzjd=BxeJZKLWzU93kpVc#fmxSOMvNNpbkm z_^mEdyrpme{F4LW8_97V`rNqY?%Pu<4M#y|{oKpGT0GJ(BvsGOdt;m>x83u?n4}mH zKie#nP2jrV?V};IEiZ3GW3owoyH|hruEZAl;M=J}zKP6*3%}F`RBe5Qz~75_-R1YE z3bXL&#|jJQ?3pFp!NY2qLys36on}~4GTOsbXiRkCj)dAV7c>r%6nLd-Ql_^A&6GXlgIE;$gBb-RcsV!&v?P zlt0DQnu1!=Y0kPi@02FVi2iD}GkMlgP_EJWNSn&yLK#e|v40;G9pQ6H8YgW+%HL7D z2MuPa7md}t*!BVm&jrI>1J@^s*9}%CDY2m+qTvy011f>M*mT6BrYbE5S6C~_!3e-; zVgyE{J~o`@|9}=^&Dw0A))$lwviUSWs{&q^eDEkj6bp>#l*gg&amETblOL7^x8Rac zweiE6?hUwAn^nwpwC%&i?_xdppRLQ^(?8p{#g#p6KRR7B**dR^kbm}XBWX~8i69jG zq9>A!1@I4L0R;sN%JDAz3qi#n8x{IMgewHAOe8Al8<>PAB=l>&^ZE0$77&QWNFHV2 z-7V`y&*6DuqLtb4YJ-!T-e1!*NYTXC0nX+~!##(p1idSB11sydxI-DtH@m5UyZCho z3OacLxj^IK{CIam~(ek|CP*AezLOAJ6 zIN>nFjIACyi=*kK>9m}iw0Uc%_z)J?0abnNPax&SO(A< zCr)VB3Q2&yn9{}9qE0I)zq1+vu;J+YO?j8}24i*YT`kOiApwNmlq@5EV!flCGZ1N= zXSBOrA_} z(*u4>_E@-+@RePD4ZSUimYDDA-=pLj2J9d}Fa{a0sQLRQZBYE(IDClEd`YLtsQiNs8~gbSK3LJ6am3 zNt&P7nT5pg8B7`;P0XwhQpOe0@DXK#k`{`XxM6Q6Ph@gLGq83b6|;uHP<>)p*NR}$ z5d3b7Z@ArC3*i;v3EDg5Yhlel1izdoZ?fWGC37C&Ee1&Sz4YQ>O6{5EjXK)gV0Vn= zRLXI0@#ZudGG+mFmbi}afiyYljUqX^e96f zeVNK_AOxhT>St)Bs$*=r`ynHWIy54_3nY@r3k!ZAJdv*WvdrVIk8D6_!(%_f>!f+g zXL`P4AT?B!tY~$tX3T4hK}uqT)i>LV*_6zHwwhm-AJquvtQxMhb->G3or6ME|6^hA z%h57_3<58X@`8xW1(sEpo^c_uZf_powcf39-~FPw+Kb@IX4jD%EGtzRAQ}PdGJYmM zM)Xgmv`8d&)JRvr4Cw)X;y~FAJK@{1aHj$p&PEeBd$>2b_J$wst$Uz&pt=|C=P#Dr z7rlFl46a*l14BbZZ0vAi$F^Q^P26i+4&Tx0lij&5?vJlw2^{)2kBiz%3`JGw<{vAW z-Ya*>3wb-+HP6Y`ywC|Ru>9I|;3U3}UuKjwLyhJs`ST}9Iug;r`34h1iUwdHfx@vt z&TPM*Gpg844rRzYKU86tnoyt)3Pk9GO}B6I^~HRutAP+~I4neiEyreEsSUK7IA?AY zF{m$sQiBWo+_<`UVi`@yb@Rp2;WfqxfO72RU4JX{HIgaYk|q-50-hBsw;w3HbSMC* zpt!28kNc`7610dRIh{np$j9Wxd1Y>XEsU^`u=Y_H=|?_(Sn`M>E=4 z-=hAHlDM}lqmaJ%_|+bD0-Ey-1O6rwkrcPPdW{9hoSa94Um}WKa}|h|O#%jj=Twy@DP&>ZX zq@2|8;p?0V=NID+%6)2$3E`x-1D(vtCL_gAH!*UWUbJVp=JlM41H^K)$MI92Qn1^gpneQzUd+?eo~c!Bbr&q=sLi%-vDb@# z@~ip~#I{K&wGZ>?zMNn&$1a~ugLqj8_jD@AL{P+=vJmXCEg=ydj^Mm`oxyz8YBFcJ z*>8`{ZR@Lw!|*DPw^FAI&(YmzOu$t?8L~RhuuA`wj_#%_O3KvL_3286`tAf5>0S;D zNyM6IjRIJ2{n4Vg6QR@K!brGqHb0p+8T`nAl86%vHpo}=Q+ z4B{gDVg@wpaRl$$ECK3z2I7hV8y$KAbOAipr#B^%bP>h``@XlXdz@1q4Y38(QKk}T z*~^;2YY+AJLHJSzf4`XX6M+P%><+lbVOk;LObfkmQ}m#~G;d}Lf6*e@Ut4Fi9HqAs zn2h!XqFUuKSjQoxR~3}81{_V4esH8o|7P)EujnA`j{a$AVN#PJH|vrwBtfC_ijcsg}(x|%pG;-y@qVfF=!gg{vk1Zx)g?%_4K`3vY`I*kZ&EepF1Eey zv#6v?z8OoMfc^0lGWix)i^JM%{=Y+#6iCe`cx*kxjT*#LQh4`~o(M@r1#dg^Q| zdAE@;xSw3&F*xJ2wk0Y`7S(sA+x_SrLpSed^7%wh9Ur~^MHe{SG5~;?MfA|o>*nse zEsxnLW%DEsH!AI!Y_BpqJ_gRjNJ~Bx1^`i*y|pqlL;+24_O zz)AX#J27$3Hz+75S`Rarl`W@$Qo4vYEr`g3V?-a38sA}Wk^oQV92s!E$x z*tWvIsPawkBG9j-LT0$jbo9F8?|`GJJ=?ImokH<3zhX7t&vaipKhq&aoHTRde`ZPU zMx8WK!Eb)i-ODyw`*v+XRPZtE5&C$w{qX?M_MmB{G#s6;3i0>vWA5#~HBR;a8GVjZ z#Hupw&X;e+XSq2!IX7B46X~+S;$X!;X|_HkSWrJ>8hotd)yUPz4vXDpgI^gQ6cjYb zhxO+-LQYN%OtySv&7aQvV_EV4nvXdIDdXqFey)@=VW;3{#+;jp+lTJshrp5W^{_&0 zI0BiffL`JB-Vr4n^`DfEDBWO}<6E_bQZ0;R;vl@yI>XFWf z{&s_#cQ?ewcPBBk(cwFOM`M15r3#B9BSM>N8=SX&D6RC4NR{XWVR<>%m}8?u65_*U z$P<1i8Z!ED(Il82obc5EFoT1E>zdCxQH5U5Baa5^eW+?I;Tp!zRSsK$wi{$V&tor7 zE-&6GR37Xux+ZvN6d=r4d+qkS(|6OOg5_iuIL=v;ggM;)Uy>kTbR@6S}F!Q(te-9TRY z$~Kemb=^G^zsQ1;FT-UUZWRkN8l1tqc25~fc~SDPX|TMy@^xYG;bhZ)fK1|RzTIz! zfk?P-sq{kmfN{RVEPYmkpDkVmyP4kOd)Z$B{>FZzrBl6(K9y3{za3zkxqO4s-hRV_ zY*sDdoPDYJBRkQ)3X}cafyMvuJhTPBo^u?X90sCnJTUEzTq%z4`_1iG^F}AFK=EH* zfaAYrah%|r>k&g)nrv%&R4PxlL4M~>u3ke>6)$bfO6BkQi|v+IAT@m}^fS5hC|V_q zP~ocdeIdD~x5mRVDV}?fe12;*sf61*wQj=nPfwJ@F(sc9BpB`7_t6WQ7J2b9($n)6h#(LO*io2AI0+{0diQ=o+ z@I*KsGFc_*c+|_JImpzVtkv$rJg^Y242UI^2DelB?Jl3n#N6aP_5>@WJ~bUq=MKyI zq*F2TV(sm7FvNSf#q|j-?o!o1ca`+SiS4h(ng{&dybM;HE@Nj>j74K;m#0#hyTu#2 zi#u$mEkrmfl=XE++7_Bal|!ytJW5iJ$=g80>i=sxsot&E>ac4BGvf7)mW|?Au=6Jp zdm2E+hAGQKY6go17uWhWzKD)|FjXQAgS!fA(Vv+6!{}7GS*25u9S~)6d#5b@bpw4d zVNud;Mlio(v| zQVO0NcTq$9P04&zpZ}-881^}VlfO1#vlA$~tVb|{j>frLRNNgaqhy|I24gNF04+mL zX0~&Ziy<6%O_X6^I?+8c&AnM*3A;Huh{hZzW`eW#^_tB%bk+~6l6Uiy>Ly74Je6); zp(#lGnV0%Gf#mRTX!W&28aS{Ywt~yBy~J8b_<1YuKwL(iyr6|popKNvld$v zLa803&VZBn5s0Eh>i$xiz2XPl4(&K;PD|vN9gE@X%5s&^oRz$l5w~!s7dZLNW3MUt z3S_E+Er<9TP;z>JHL0o27tLKl3p-_(<9K1Aiz4w>Qfs6Ddg}|V%AGf*y zGQ5|Xp9O@IMRO=--QN(tir?t6K1r}}CcfoMd3G1Gf298Ii;%?eYV`9uaWg<@H-TxPIudol_6QYg-)SKhxUkKf7Ew!C!5v?^ zK0K}~b8_>G(Kjz1E7&Qc6#nk_3=rp2D-!$qchZ*!hSY1A%O-iyrv)_>UJRdmxCF!x zysXlm&}k&pUGjFE>Q^^WsD2j*AWNv%MKEJ0T3?fN8xyx%B!$hOjTSEItKqjA3Gkk@Ajszp?U^K)3 zT~>^VOa1$Dt6eku3bQn^x z3LOQ9f-~q}Vj0QfPHXgmj3Q0&v7Ap%!N`Op%mGizmhCxh0U3xWhiv2o4Da6d#rAoH z4GU$uw&^LfEd9mBf(V=G*AdUmXm3trbP6>^j^gXjtMlQ+{Dl7jdmLA-C&(=hK!)@7 zhFtNRWJAL%S}}QQ@1ijNrR^_qN*mnvrvqkmHn3jbZZ-elnF!{Y~+wo>i+Y!e_cU#?XqF@L$P*%Bxu^*th}0h<_$U?vjhhMz zIghZB6r1drsL%{8(f|7z_HW>0$f|8*;;)XSJ@V9F}L0U{)0-(C2paPZN17#Imm4EL#^lxdQF=R>4 zI!cbzs7t{KX`vd+h%e!@UTqKnTpZj+2Hfc0UCltfXCn895&-Vd8;dz)YpHU8dr%yn z1Tfdmu;uhtfta`&^G*E&9F0iWWs*>x%Gt_NN65l-`>P#&tz^K{G0%p3Bti)HKraUr zG6YaaboyNB>8g;Np0wLpkLp9G2=qs~VF>2Q;jfnB{B!eHpRVzv9=KKZ>E4jf6h(IEVu>8&k z)AqR}U=QAiDjUM}uRxYGY%M6QlPEKaF(yLBtkav0NQiXrfjV@}?hTXYk|C@L&MRt2 zaZ)e|pf5zUJMV0Dt!=FteP5x?j_w!-<&|(<;9+h~kPJBhfsq85;D{(b;+Ik}c?X{Qf`YT`KCKEh0fS*z? zbP>Y+Y-VRo08%nGgA>_Rgv$3oe6J&@y523o-7>cWu{Z+nLYfT^$o7`=W)CSffRu2H zvp4jGz1jM?@4P`2Z>pf&PuDiJeH-W_rel z0TL7Z3zRS^j9Ud{q{Y%I{ASmI^Tq)1iEB713s?FR0v8TgAi(f3vgFb-rA-$8H!*Wk z$@N?Zd>dF9!QganF+Z7rf~rXLNHE2#hp$CKwLGj05P_+Y0QM}tVO|~rDl1_A)?bnD z5itfRUk&Tjm4gCTtub%_RGRLw!NZpXq-^KOAhHpFf`UJ4we0XH3ngleL<=M08f9RO zZ!&#jhPR=gJV0D1J0EL*UbOFo)l%4%2Um`*ec-5ZOloH-ZP}Cu^mAAJ^sxu}$6>MBSXQ^*)YHQFfxex1~Rs zme5T23NZC?v6tIm_>-%DTcD|DnB_n@iLuJ_nI*FxGShPm9bF(mJs525aRO(KP997w zMNaB(&o^{qL}<^PEW#D?BF@q2cG_S{#$9@D2zh54EwLAFK0@LY7wPOAQ2;qni)A$4 z@Ft78OK7adISBp}y6(r?8tQuPQLBd+u0&u3;lw@f*7j{dikm~hli7-;a0=T9i}^8M zA>&JE(OAXbaJ zieRv?t=K_D3$P9tXgX=krjRJ)H}AI~1f%!i0{nr{DLD_0*j%^2a1M6wwO#3AN5=be zmfsi8b=^}G2=U6*3|&M{Nf2Z6_OX!k9iyMQhgIui~A7`t_eesh<} z%Ze=fyF|Yh(C-PhSd(qhn(&%}e8IlKss@T`tsVRHup(blIjR3yvkCp)1;)s?Y{dC> zcO%v1FEjReIGZQ$iiI-}G+r74Ae4VpRoB-;T{8(<=#Y$797XJF`s%W#u(%;+aA0s< zMMx45$XYi`z%7zFAA9&Dk4QM|Y*dvPu=b-x*cER}Qy>gWxTTK?I=fV!-&i3Xe>AIn z8%y?OWReJ&{I#=-q6Yq0^waUoSy96&1AkdT7x`-L&4Ce{9op3>R{h6H9D@GQ=(L4A zxv&3HI3c3+t7JZcdnkdE^vfk{s>7Q`7itNS65vHES7gw!>76mUpMM$4yLE>Rsl2Gc zM+4Zx*#-uJR-%65=LrQ=AeAq0)9MaQ+^VI=41vFI@ZxZGj=Idjcc+2wPg{0|`oiwr zGmJ4NDukfy_6+)JgSuCeBO0XOG~M`p_@>7qaQXr~St*L0B0hZ>!pW8;?|r56MOJ#+ zP&SvF90)~8<_YeJxJz`DR-AG8Wr$IKEL%jtZ#tXfUzPRrA36c z_xqb+>tVAYkMqUT^mW8EO&U#o^X;aCM%yy}m|J?2<6$zcn%MEw(Y7wlSP{$p$3*gJ z8TGhKyo&vM5&o-=Hv1VBjQ+#rM17pq$mmCFIXr7uwcW;C<;L4QM%P7U?shtLiUy1M z0sdzK>m{ywv&-XI!Lk$7zAG;=Y+tQ1XzY zEuVxVl#A^7B>K3ALiOzIYB$$HiDwpOCKV%cNnv<`nCr?5u7 zdk*%a1!`jySW@L;Qan5wr?8Ci1G=^vbx#o7AHHKu=2RDVMsU_r0eW!RC$;$Z5i8!1 z9t1FKoRUUI)74#e{H{v>;)<2IUo zbJ<2oVUK8n;7+Ds&8qc;-&0cOVz-NBd`?bQqnx5H-%F>)IIB%upP7Fa);t(r2DdVr zxPy{f$C`FT#ySw&Lk-=Vj-+6*Y6mTG)rJ*GK)9Q96%3+CQeA?jLYfU&`AscE{qlyg zuD%l0nith6R+R4or%&*@z*_RaK zvJioyqQ&Kvs+AP+kl|Dt>1O4KO+aeCnSauM_%kP0XkXy6n5E?;@n+fkmox(S6e$_j zGd9sPqXbpd0;dCGBZvFDnfULVVZ-^XSG3A7R_b*4IeE=G^x^4YPOfBSakvYoitR>x zy)2K(+fsJ|KXL||^HZ^9A>oE|yiu=8*CnxrTS|lBy6CFQ@54;>zFz6E`Ar#d@ox=J zuRFXVRD6B~Dwoe{YRflH1=Hi+og(4a`&JJRYYDc4iu@0{J5aFJlM+YD$mQz+6!Lm`njJg_LvwzQG;~GX@MbD~IlIEs&F%ReX{ye1*pzBm zoG1E8*>ZLS91wtsxf~a34TN+4EIOUGs)qIo^V(^Ly;aQ)ab9`#w^ZJ{hp7S&N8t`{ zYdb0sdi#&ydbN!Dw(uP5U;;4n%vm_Fx45w0V;**2Sa0?T+(He+gc4d?PiRDltEVSTf*?RY_Cx4@xV+yFS;xe~%*e~n|IW3b_!&I-6!%B*yRp6I8!h(VO1%G2_OHc@wMOWl zmbo89pR)0^{z>5>^FQXpk+f5g`x&lBa{m8D^TYGsS@Xz5^fuHj*M$E+pq&f-do>g~S-cLlTJ z6XPQibjfqRXKGVAXwcM|032yd;ITquk-Ph!#*^}QCr!J=+nK6v${0bg=d&a4!3v=H zcl%wohKuKy_qBTK<%`KfBFeiT#Ef0ol`gtKlD{0u$q|CoRd0u99b1~)4-M{5RLr&= z5x$yF&-S4ezDTo_R^3*Z8}Y#+zwnRne|eRVM7}Q2Jea+6y+vyIZlhAd1`Y3ULdrD7 zIvNo-kr@$wzHnJ_KVS2roNfnTlCxJ2r%qsVGhQ+k8{eL%xCNBC$_6XM zdC_yH#3fMH4BWGg^!6{G8E^V^+ZUM@w`Y{wt+CxeA#3o$EYIcH2l!0h=T*L)rTdiH*~J65sdeLlGGX&Hg0Qh>jA@mp#%GO2k%U z*9U2928;+H&-V*}WlIT5{M6Lni9(1-sRg39V<+p}#;?5NMc{6xL7B-| z4_0Fy8Vkq8-3As^KfbcalP#_=buc$og+ee>ct71CZ$x*VT;+r+FuRhDeKqe@7o34Q z?k22J7uF2i$b}BJU^XpJy=N9%QlICiSd;1%NkrIEJIocHG#cQ}_R7OhNQ@nvlshXb z8@U!m_myjPJ4JIP+gTo{X6H>R-UL^eT_2^ZVXmTxj+uS2sPWju${Xc6JA^SOKYiN? z>%xjhtt`(XbAreD13k`WE1Xoj=Gw6pgu!Ac+{d;Kc7_dCZ)&DRO+@csjmBX2 zXM$iCoc=$MK_t*_Z{^7+ME+&ISz4K7@e?KwGhqu5M7)|)N1*kI??k2yN9WBeIT_%O zSh%>nz-q0du2+rHmNg){=ywNwy%!rLSW<2ra^*|2gUwjrmEFA+!1WwC+91LoTBXY+ zr7qA$o%Zi)zZ9nUrh@v{878Lxa%D1q_O02y^zC=h>JpRM?ti;C8)WL?x2>3$*xwkn zs?599f!wC~(|(@NqAedHp3M9Ky$?SPJ=N+wsal?!q7B{E=HG8BSQo=zN}`Di>Zm(( z?2_+>*}Q0QVgRX^KUm&Kc5W9>OKo8d)9#a+os<#gHU$n4T6Y|>M>bbnB{APywAQUN z?Z11Nu`GS2m=5OcK4>a$ZcN1^Vs|_zLGN0QNQ8M>SaGY-`bEhFMR2iZw+qX+%)?UGZ4W@iOA)7?MfAjvBQK83o&uO{7ykEd!DOtg!c+@E=uC49uCVp}bw)}8Y)HFwd z#~4e)(}Va!*E<@c)SIodzWjH&Oq+BQWLCkjk6I)uiXD&29pkS~`bfWK;$)m*IWF@= znEo5iZzTO4`~L;bCsBBqz6H!zAcq)IzZpbZAPojTCS9Z{p6}ev{EWuTa z z1t%9g{N23+RUwy4)E{iEFL>)-_Tco~wSKLoIk}7aH`+{!keLlm&#h7b!X0Z&*(fJG z4G4sb{VmLNq9CIw1$P5PNN&E;3U;YfJ(llk@uegHR?}ptD36Ii?)*aVc>TMI zq2`y!yrf;6V(b6G+&c!@8nkJ;W!vU1+ctOEwr%aQ?b>DAwr$(CZB2b&cSp~e?&&i# zXMUWYD`Q1Q=2|P>m2uryK2KdcpR&J*`r71)2$^&o(!CGk&zX>9oV}iu)hwuwM@UWM zo2Z*TzGorh9b5#E?U6wanK4Z);*`yV)=H?e3DHz5iCjBl45E@}oo=+v!|xPppCUWu_{-wm>Vk9Fe#rASQ;{jNgAQAi>@D>rN*X~}<$L>8Bx?m2|D zB~~NZUAwzYL8a>LRQF(ZKp`--8VpYH%-JDewUQ2?Zp&AHPu@`zd~Ig+3JaS}MF4Ww zdwm7Th?eA^Xi1YxN3MB!hi$n{{waJyet!j~)s_@qAcQ)4Vj@FEWa-8r*<$d z0~=t;c<%Od!pvMmOC15yW7|ZJ`6#@$>BImw;8Gh}9I6lEDPs=hI+Jc zp2v;og94O{>~%C7qPRv!n!Nf5pO>zth0x&)+2fs#QMgAwzQ}R=;y8q6jA~3!qwCBl z&{~s`QFMfCA%1OKA(g8^KjPxJlr}&w&%pN!-U2HMI7i-B#A9d?5T|!Y^tt&syk-P# zPZ5-?^Z-a`q>3lY*RkoBw`9v$5L+h=jF5!`r2-od_?Y>_EG`hlCKqG?y)FpT>-(2F z0d)-R4Y{L2SNi7{=?E^E2o7Hes8hZ7XhMrn@XJcW6@w#0#ju|RGEddg$?{A~@YE!O%MD}Mn7@q?|FT0E z!XHmR8z%@-SfEct%fmoj4=BT;BcK`koRA(~3?45;T^qMj7uFxFxyD#e1Z43KY(6@^ zSP}rgOy90hGJ(L*VGQ#NrOIq>q2XAom4zJ2!L}{VwxJl5eb1YH|h*)vSbiIOqDF&vjmm` za$F+7>C~7ggZ{MHdC<`Y06^5)b(YrwoyiDZIA7vw$Y~6y+F`?a*#u#Pf9I|IgQUSu63ub$`fCobkPsL?Re&9m~B3#F8ww&jK z#h0`O*`3)jXaoo+;uUsDsb`|tXBa;yP!HWt<`O6eET?H+;FG=n-UsJ$ToJ+JmXgt- z&W_|q@L{77>PEZPd%Pr509pcDHf(JH!A`PP=zYV-cb?o|%oDbf42>m`97Yo^v2vQ= zdGGP((&(Cn$|^_OziTT@k#9jvCPDq+?C={Rp-Bf2k2h8;{m>m+=Q-=CRP*~6+`lEn z`~G50>Jg}cgp|1El%9@!1nr9WqalJ@|%PKLL{qLYY$3e<}3#_yebi2zKdFb2%r}) zx4JV#bsX(JHAiGIoRVJ^+OYXr-4y~}6) z3=J)Bhc7AhbpR1}NA=zL!}dtss+sOgs*-I}a{9Io_YT7XUvW zB5@TQj1c)Z#cR(cOIt?pfl^;(JR)cAFKjHgSB#u^h1kE8z=hQ4Bc-F_2|r?{2fq^L zjv)vuSs}{#GSW{nM1bL`=O)Op!mlK$Wpx13zQ!D6@^F}`^z*1{PVBvs5H@zXuTiJb4f`#^-qZ~rEhP<2DxXc(DnjgHEuY!%(E#0 z^UsKmx>wmPgQVBiiGI~&B81imT!IXMBU-Qk1Tr!jAR|ckZIhr0TvI;^!|(cpWlIzu zBpbK{Cx^8V4is|r26q|Q)|oXmoPH9D9a|9N!AH#V;aQ+E?(4Pou&Y0TI^Bc22wf)T zCW67jwqg$w%fT|JrQxhJlR_$;UANbQ=!f2g^W_AgTW}T{y1Ha{@qpC6!EU;q3>3?J zE4e9f=&_avjjeVZ@6ode%9GYd2advnYbdAp2bbp9_?9Ps97G~|$m8cPaD4~u@HCa3 z96(04P_yFC@#;TKl6KY{;TnT<#-RZCF>gBC<8-Dt%an{cJiCoO7<`8L!AiodlJTc9 z|0J{5*KWm&=RE0^uR>D0nF$6O11~QwXX`vA4FJuqgh?WiF#0gPyIY=^QTNBr$R$0_ z{77l<$tLtVM3cuRwW%RywS;T4i)K0HI?}V9;LB^Vex$nJsoERV>64VnZ6DlA!l!ed zO>7!Sn8Kawn}HBsZizB1g$F)(Z(ijI1-W8%ie+_^+7)qrR2eq3LJ!z z`c-}>I`AjY>D!!>PCQ;kv6DR(aRULfGY7@g$4JvJ+VdfR#=>a`4O6VhE2kNV2Fq9C zc_T?LD)Yw&n6eQIeN?jr=)fHP#oA%BI)mrlI^&}1>v2Y`TynrO8^ORLDP0@!L&O%W!RAXD!z^p0nHeTcW>NwHdZ%ZpuEv_D%PdC9MuLTgyF??U-1jufzjvcOepG_3a8nLs`-mKn9jrU zU*mDv! z`=T#ysRVBaRzDv{(oRs~j`~tUU8}uphJz+^;jaNWg|NZ1n-3{`oyxbfNs78tioB!G z%x#cL-ou+i4Ra)AG+ISIUqjdR=?vHQ7P>>zQ*I&Bf~M8Kid-Bk&bM&&z~G%W4=+HJ zL&*m~^-MijGUY74rY$VvP6~DTDPQSAv2vLBaYEkW+*1IGzq?qrH6wXN|58Q(_SBPi zQi!q23e%OQweeR={%de6rR@(i=|cUdC$aRQzFM;f;n0IsR5BK`V8k+KPINH@1Q4@^ zG$h@-QVF*c;t{-M(2w8G-tB|kbR`MkMU{IsPM4G6Mf)TSJKRUbsFfZy7`T)*^Y=1f zw7*P2+`LPHI z-XyyuU8L*nO)K7*WCF1NP8IK-_UlA9{1jjo!X2n(NVjcQbcHOiYZ9We9PW z=q!i_IC>E7pd1;iIJJKe27=-ioVOU;`eH7e5_NqG>ei4JmT5VZZ<$H3f^L*QLkQul ziyyB?-(eFL5+({%iqznrV4}1Y?%AD2#oL(%N_nU+cLjAY+lzcyN2^Lm^ zMX1Af<8|vQfca|-$?h)coa}WETY#?6eX_1VaxUMF;0*!wCM$BKt?4#9OK-vB{fu@u zUjJI7a7;B_{?q`A+Dfz2>_?H{>X&4ViKq2|&mu0(x|grCOlOVWCc4}06Pmhx$eK?w_mXpBs_c|JxygK9%h279~0NH8~ybKSF>X z*B-CcVXe_}`Csk)V<6)#PeyJ=c9EahM`-b%F#xaJ(Ii+E5sR^yHc|Yu|7+>H4pVG;J%4otu*CL#_Rlvv{L70hxjhQ$Ad&kvLk1N@ zFZSkDBA@)v!dfOB>m1_a?#@9T@Hx>Ek_U+-!StdBF9d)Y9QIsSyjLBVJ6R<$! zJuhc#;O9R#eng}O2gwSgzO1^=-_q?aZ#a$ylY0@9moOBLAxEwFP=ATf-7{!@COiwr z|2ijXK1;*6`&8XIgHejPa1cY=DZQg!`n}5#hsgIX-GGN1BAPwX8%W7kW77xWWDAS| zFDn`VuCtr$)QQEyrxp{y1AU#vWX>7!eZC1!6`+wbg{yoEl##j)Z7uc@?6CP}u(PlW z@dPgj8dVrM&KJ|SQdxDvVM9BFZM(a&ahq}@BUUn=IW#eZ_Nsbhw4bC2KC#9Q_81;q zcya=dj|ec9d%cIzFwx1Ca!}r_Cl_N&*kq>UG>P0}G79qw7Bh)Gwxs{%G+X*(+UZT| zK>v{^q9|lCSpr~%WtbB%6`&0s4aDR<+ND|giAk9xvsB#K507P_{sU38LXHCK=DH2dds zEg1RMM{|ndtJv^{IvUnXAl&Z@oe9r5`7?1X>R|>TH(J0xUJ1Zlvj?9eg&Wa2cpHGX zdw_x{`vqWVi~r|*Tt!KfBCDLwJ3-p=Z*H%=SmRRIkc6$nE-F*?_Zu&^%3X1~j?mBG zR$^Msc5_H71>e9htDK!Zi&!IUVRe3zMzTVM)>0G^|0T4dn?T*tmtd9_`%g;^WkU*h zaEnFGwilKCoJVz%pP~@Ld@Q#o!-=I`vQD>$*YV_h!ki@69~RMq<${G%8vSpZ-Nv~7>Q=E?<>ljCCHwLXi)fb1g z6v`>WB#A`~<--O)ksbujPNXK3-Mqw5exiCbuS>6WJnycGwe{Iszhs)Te|XXN^7Lq8N5iAK^?ywm&#fUdKn;g<2%|G=J9iY z)As<*#Fjexu6Nzql~>lp_IXat%KFWiAP5AgKu$>LB+QQ>Tt+~Uhhn}5iYhPPD}z$4 zg?Jc#h>Q~Za|M43a!xQoJPu79NKl+O5JbUb>Q6TxsUJYXgm3NEE6?=H&cOt&Wp(E= zheu`oGM#H&SaIE7Oc|_VBD@R-_)d^9M#D6-JBFF>+Cu6bWztSG*=ML!yT^Efz;Hrf zwA+pfdebeT2b3HmcmMLL_yd+ITs(0|q)%`f(_U+u7SM6JkCFg75{R zR;hoe*kn-akjppCVCd(x@dqJ)7e>FU6lQJF%fyQzoQsMuP*MiVQjaxRW*j))ud=EA zbT%5@aU{mB^-%1peO{Y1Bx8PnfH28%Ro7*Cd{KzskIa#H@_f2Q4V0U2mf_Z94l{|Z zW#Vg>lZQJTI;HM*Zy?Oiv)aeS%V{9cN`kAovyho{W`(iG}~7D?Eis{ zuKsj)Xa*Y~YI{(Lx-Q(%h7kvDm=RH8iP?}f%%Y3{Y+s&A8;rS>}BE^Qv_6^AWrdJ_&D;Aq@$wlpW|@ZoZ7Gir0lhDk>9 zj{Wq67I<^OV|!&#B^5tNO-`Qca7*R#j1p*Ml>CinifC+7i90FI0^#f>!>N}W&k@4I z4Vqh~FFCB;k!aYj6nHT0CwXsM{;dL~3Rn0WNI6%igCFJKR_k$(ExHfmz65I$tJ@f4;3UPMq#~|06Zo zo6jT-D1E*2=jfW0g7`-o@Dvh3?QG;{&5QBEl98f~xN9z)irR4->|6ci$Ch{X5;W&2%g1l5K76ss8_KznFqydvXuEODx_*LvM zDqs<8nbu5ZDDQ8e<8X4+6mH=4PhP(SZG4g(SEQ7XU6M01pX> z8zIzA*v^28poKn*OJNu75jv<}8=W{vSVy zhiExkz3D7wwOql2excbdSs<84`h#268DH{^W^A#GK^qK%S0ld#Brmsmb?Jd8te9z6u9wV5=B}Tsf)ku1{m)&`H3!{1h~!@*9D93o0`f$>*%JsSnt-cT< zP0|>I0>;IFPisyI`|238kF_>8x~%x7sg@EA-_`~!_t75Ae;~MS@Q1Yp|x66Dt z))*jmXW0Tm)ES}*;fuVt-FQViP)MWpx-&PW=H-`C96YhUApQdFYN%`0CzKdqda=M? zXnsEhd36*_MnDL*0p2^9w&l`THWf2OWbHqA>LxS;E&BNSnz{IEkzVk!O;5eItNRSb zhFiGLJMM{xlhibRpPsd@zD!WRC%mw9*hMiB+_8up> z5N>ysK3tz1F4S)cvo!8;o9H%T{&-z>-l#+#JcH|hq~VC~2HYNgm?Gvke-5Vpd{HqX z#&G_>4+x3tG5A-TQ{Osi`yBj2?DxGdXle{Fe{ZAm$ z)dcH!oW+05fJnZ=4Nf&@#EqE7yzY^_=GH&Uqp9XJjP)k;^pe|15M9HP7q z&9W2}3V_3qBAf8iT%oP6)|A(M zgpTd4%Q5{A1&{{E1pQhFGaFc>zy7lwf22#irFu&X zbq&`Y?N3fzfE^tepq#-v9DGsVs4a`dr5cFd~0K@z`kMAy=iz9+U$cER)d~-C{W2~mUOvyQWMrpXM z;Pi6y(q|_C=x~+GI6b|St=YQV#xa7+#>S%EvNR*+UVnoJObS#!88*|+sVOAhYoDAT zYXt!Qbb90;-AIO}9WlCfkA_*8>DNksG&EEnmX!n)Xnr@LS0=3_Gp(!7Hlh-mn;*8y zixH3>Wly2XfJjiF^&0=`YVrk7bd{9(O?wpQnyx^`p9`z^$(s4X|Ni!nz<N}06}0dLp6R!r}PrBXLD&+1uP&89du-9c-eIH z^;Pj;*w6Fl`OsxMERiC6Ll$2f_bIb2GJSdSh>6ClGy-dQ04V;h`lHAP_HDr@IvqNr z<;%TRjJ>rs2~f782|0}7e!?{Kv>Z;qnS!eIdBjMA$^M+v`+YaT>a;pfH>R4h;<&(Jm&s+Wy>>Wb zV;jZpKHXCWq3eX%i)u**HyZ9yY6eZauMi1-0p`h9#6_%p6uZWIjlQA$9QHhs$jpC# z=Dbj3$RneKm8lAIC8Llwr5x^ZvIX+@(ojZ*@^+O9dspd0t@_W_)i^Q z+%VbYi9TNf$POrw0pb4Q18x}{-f(Cbf%>j$gWU@G5)#0&(Bc}WcOt2aWu#qE$RG~V zzfUdy<^ud7cP{r6owN|tJ#f1he|hR%XsyoikRpJoLoCvx!Qy^~J&L>zPVq%5xL6B} z;+pT-aX0((%~Ns?#{ZK4Jq&#-dd&`k86KAz2X9>i{&$>TuDkkXKO6+c0^1M3n!&-b zTEMU>M#Y(1-q^9j!(i?C+EDJ??xYT$$bMf1r|Tl` z<*2ip#oaqD5$Bhe9fee0N6?|u? zbCwW;>!F94>d_Q|^>=Q15#6`zT|A0`z%>AO(}sT=oz*a% zqUI{56*{d}i`~TcRGWII5@|EvcOb-(!ENaK&6~{o6oPd9Z#6zs1pn`7IBnJKuPm=} zG^32K3O;vfKB)E(##7GSfC9{uqm|RMzQONbK3(?ysL4J&VaQ|`*=&U@$E(>JKG0fT z@47|5*kH+IGirRy%DVuew01XXwUoxPZ8HKf^Ow*K7qS&v!NF*$`g*p@U-%kryP3WZ zx|E?Q7qXoI3KPCATw3gIpAURo<_CkIf0p~vKg-PuyfS8) zu&^*6Ii`P(W&hh)Rjl|ww+N?7{<c!^bP95CEGjf_WjK1!=W`a`Y&@I zzT9s+mXU_bSP$ea{$?+1=&7G}4o+2H={BNh!r_eQ@wPRz%kMT({qqW;;?;}?uCOul z`dB>E<{oYRuH7O%i8vo{IwKG|YtM!2^ANwvz)O5|~ml1n~vBdBI z-?3j=)P{Pz1eJXC)ytk-^jRI9kZKp>HKen<^U%3W9y+r z)K1Cx^!25rxS5!_;Dg+JepUJLxir}g)_tjT=K~S+zHDHq!Rr85IZ%|~v)}Jrwk?QS z=P1uI(K`i?Cv;Cwhp{1DvU~{YnQibrLYISb%YO3-F-APsc%rCZ)we)t58 z%}~1mn+H1tiYiHOu=;$fM<~jFNB@Rj&I-Syako#~_^T?i`$%W`I#4#7;)S!3^~vM8 zrv=UD_Cf>gSJZv}nx|0Iov)@rnxgrO}_K9=3+R^YkzG%U?^@nz& z4CN$&0P=Pu0GXdVBdq7~0%^W0dqGlA^DI88puf`yxqNLih~Mpz~)dSKvo=AN{idBoelTvb*qeO0H2Rva!M& zUK8kVce`e;*MgG`%FOY&IxCB{j(V%J4P#oc9+pZ=@8OISa_`+lNhyx)o+pY|O1o08 zIC;D*SWLf{lbH%b3*v`GK0V0^PByPKb!e$*zuN&H5Oa+1h89(E`Q9jAM?c)PR9Ru1 zidBv$XI{24S`L)d>uAWDA8pnJsZ8d;;p?rftkXJS7fK!uk82lMAR1 zC3y@m_X_iucKUnTCfP62m6CMrFAtDp&gKJibvVzs{a13v=RYVpwo5^@T$&%LLtcMx zyDhQ)Q7B)U(W@9dg6|$mG&jaZ4}xA5vz5G5{E`pinH*4vr#@_jReVu9Uwc@zJhcfo zdf&x&G<8w8JXE6fd9-&4ua-^-`9Y#&laF}E9gZqG8uvi!OXUK(0l`0mz~{~fC9=;9 zvZca9GI9L0AiKAeWe~h;3FP6IyE#F!de{5~87Q}3w#OoGY zBUE>bT|ZT9xu|f5`P;8)#uBAE9;Lr^8P(6WQyRSP7Mqh5+ou#$8<~z?8;1|q99R%wU!g;buR?bB9C_l>0fIj}G&H4=2_6s-`|@ zaBor>^({*JBTxpzs14lL^=15lpH=jYKZUGnlZan#ad9Ic5r4pM$N+6_+(D!6zR8E{ z`b$vq1ZU`^%>)aCa%RWddc~O7&ML$9S99*2k$fflic+&kNoWG(%PpwDGY!AdIo~&j zmLOa@oy{bWA~wd`*0RylhW8z`oIEfbuQx6d<|#+QH~v+BitpNOZ=FTv&fMFsnk|ZO zH!`wJgs-zw`s$LeNjltN|5pQZ@G4{8QahcW2Mv_tGVdTnB|)HHQQIucy^13LO!=o1 zUNt#7L>WvM%*}Jb)&qztdfcF82-C{?L`|D~B*as}Pr=$C`-dUHtwejum7(Lj#-@u( z4Z5_6t%cwIc9h7p;U>K)WF?)dp3jaI+*;3d1msA(I>VHCY^O<|0=sagr!2rv! z*CORln@rUdL7}w8raqL5;<=J}HbHZ%hQr=z4hmZ@4)^3^ zD0=)l>-admt}GUd;h0dSJZpsqu0C%SHk__LRg=z)!zEV&!veOQAk4O@cay1-IL0|I zkLStu@&qMZc&J34Mw8CNG`g6WrrpS+N?g3O^UCwuKM1_q8ml}n@-)F(H``qC5crCU zp!RrmXb2X_XIo>VWwQ?|&w|Kn+O=#-M~zpid+~wCP;-1S$l~@%C23Y;A9hZ%+k`-7 zc_h2_JscwWbMHQvV?B*&YJB81A7QiR!NGGWN_IFu?-sL^2~XE1sPS~0Xa+l(&#H7H z#IOtppYt;_w_2{2>5DWk*%5W``t@ZWs@q-`o6BBbp_I|lA>m`ajoq|XWZ)^dy)wqE z@sPgJ;lbX;85v?}y#3dEGXs-)aIK?l!!v@M1DnC)l|haXyo&8aFcIc#>$BI5o!s}L z^Ywn_0C(t2?+Y&p?66Fs{xi08PE(Qo*Kv7yuNXn@)5@YaUv^Mr=XFjcx}4Jia!36M z5Xvi#!kh&EZm^4OuHk<+7dTy@?cu-$o=7%{bZVi8L5oE zie?kS!91~Zig&xG1%`smv>34oAXOJnzt&OIr>Y=$Jk1QhiVG@o@$9fEcmCy9$BfB$ z)ZzFhz5Qr>hR$-jU#~z-)*LRXr*yQ{S$?Zz5`fjwDNl~1jC4mk#m(vLsWb9HocpZ1 z1}d~rcL}#Ho@M=A%7w+K&QgxHKrZ-P(fh;j`cK4PE_H4iHP`#iH6Q*!&YiVtKD6i@ zsiP?_-S7j8z$sr_b?HyXxtD>M!#*OSLoOXC`Cv4~H4cON;Ec%h+usCf79aRr806;IuS?uz&CkRGpX?2);r%yn2Tl{4Ki z(V7?$9#ieyp+bDsR3*5T7^L0KbHo~cE7RhRS`Y*}8^UOI0*`;f?+>b2#6VQCU!bf` zhg&9l&wp5VS`N-g^^c|MtgaB%NM7bUm3_v|&th#im-VbU^3Rtgg_eFSv!{DhxjYI-C z+1bqvI-Ie&XqSNS;)21$0p#4C_*yq}lHJfTo;p)#?YA~6ATBfW_tp*ZGg z@%;6ez{vRT7dJf|sVrUy7-+GBfO+fFghW9Ut@1u3^v}S8Y#M@yn)Acp8EC-K2M9D{ zO5coVrqd_Q{H62UV9?TW9sXgBts58!fy%Wg1{Y^M6oeqqpccn>TamG8G5bW{qTjX; zQ47GaIrElR?1lCJ%UrzDJXozE+A+k}zanB4&Q_|Rrs`x%4OYXuFS-E5YTX?sJO+_B z51_s2axnL@J+`m};X@Cec^+svdZM>vsrTlAk&w9qPNTC4ngm2m&9~eITpYA>Ys-O> zFh@jExCB6>J}y;L8d>~r;^v3ws(SK8a^=sCTm*HM5#jSph1ej*c{^4sNDVxqhL77X zN1Ec>GS#zf(6t{=uQv4utN9{Div7wFd8|oHoZwsJtIOcBG+cmA(eLF`ykMwwqlNFd zI%nU##Mp#T3G}Lo4|P{PBl^DZ%iD_53iq}61BurE3W&=o&z6R79B`wGI(b!Ke#&=R46%jZp?Z{DHy6;b8^*q3D!l78@~S;M*VGev~D!K)-TEN~75WeoA{!nkdQx z>;}o;U-BDlfWJ&nw5oO5GHl^~04H7O26)Z)5sm{8^j0q-M4lmN^{z?Y*kHP#Uu&!V z&nUVd;~*uvFHqqgwX)F&2*C!z`v}vCj+pbltzbmT3Dma_^n^yJeLrtslOSIM<~v@N z)n&kb{jlNKPzTpl?<3`Sy1E9?`>Vq>fa#mdlwVd7o49-iYZK~Y3LG&INCPJg2!u!+ z?s9Hf03Hwa?jq0VN|zIs1KbG2A1frV3r|RVn=dfkmn>iE)LXr3m6_4vo8AP&n?)UH z!8WOZ@&JRJ^>@UqH+D!yw_!GT!SVnVfE*YR`;T+3xXq}##IkW06Deou+qWa!&=)(( zFD?&`r-~N@*~(YAb@Z#@j;`iz6tilZkn@C2UZsGmvIznDFm59wG+^>}0fjnyhKQR= z)8MJA>I!jPZlFxjkI)y)bb3>9Ba&r6EJGAdo@XC7Q&$Wy8g0J>xye)h^z=B1(0TpJcI2{93b}gem~~;v>ffZZ5uT7oNWVN z%vgH<6~=c(1qOor>bT_&j`76$JXiImBg&TTO|=AJj$$y|Q{(2<188HuX)!n0rroFH z3JxW;zljGJ{|AXTyxO$3PudsWE}K)N`t{S$R|rT?nj=y-+{&k3?V>>fO7#ASCD%Vv zQL=leNeh&mGrINOwFe0B`322Pj>f)`XJOLPdXZES_+ARI_sug&36LRXL{1J&ZNz`y>9lGXy z!rpVXAHB~Vk1C0b!twFvsy|KXAs2;ejn}=-NTX)HaxBR7k@XD3=*nNU zFQwl`BsN2Yh#?+n?Z9VmEyaa&4n7-^0f!z5Bz*e!(cCYMW>F<);ef7`1cI#tu!cmX zsK!$&w#bv-R|{g&J9v_WuANAdLZBh}0(Bgkz#h|wtLMBd(D1U+&51u?y$OHSnR2c0 z1c0phCI;31*m>m0&}x_ovwgbhyf!gxOe)VKf@E|}K8W+dzScXkhD zjpe1eF4b6;fqjT^7pY2)*g@=6WR5H0wXpaIl~lov(Q%?$Vs3eJWWM zJ-kroLv(Hq`%sNKDQYjzj15A_9Qo%n$I*E{?D2P(S7mJG%%*1RX05I97}@i@m}-bu zG41}5bN#E7r0!YX5JRnR!3S0Mscr!8WA^?LP`m_K_t}+5^HQ~AzbyEl8@<R@=2Xe;>;5%P z;&xB(A+)eEt%GJ@{}M=VUt8+6ktk^0{ZBuvVD7F!bz=)<&m9_8`+L27eWq56dkJsG z2ExtFbSA=8`;-vF)>XTo!o4qf^ADA3T+ZyA3rqr&5plkw|^n0r3aaO>k1F57tKuqDIv=0o4bsl zuho?d#3n&GI>=q91jAw}hxCd=UMK1DqIbTcI>AGR2(SvIP>TSY_6p$GZzm+p0ikGT z)!(0DrfQInP(dl~r2Bxz0*?`h3S&;KXUW2oT?BK@FkvAmqN%ak8=sHj*8R#)Ec_x*bcS zdHFc4GDE2l(Ki93?FY|&)XbF(0lR6-r?D8d-!5BFM(Hac23XXUgtiSdKo3c@cHJzd$vNKEg+(!V?!TBHvF3Z2( z0q-7M3gG+;4|@*G9U#_XCyWkl_c0`$Kscj+iv~N+tq!9ow5X-pD`5MRJd-Of^PU|~ zadj`C4R%tFQPJ+e4ol+0aMpT5RgIl+>UVY^@_B-hX=Mr8rgHAo3Fyo2rHObZFN8L} zJK{Nah{4s^^Gwx5roh^l5I_x%z?`3;*7_qW=P;Y-{?K7I8b|Q25y{%D;brg!p z!@DP{3Ab7(hpda(^Xzs`%P^T5Oa1esD}eJYa;?*CeM#%H^n=e0Vux1_T-LWYq)v3F z(6YktkGP}H)E_;Pzl6BvzM82Mj+$9U-N z)DgkHbOygmz1}ll$(}1UQWfMA>|xp7qb;usU^;z6=;^%&iqM zrZ~JFmqpc;!@R>YS-|vnKhE|{7;sE^!dcmRYpa?s3!SS_HsQ41Suk`r4QyltHyZZ*U7VvC32WvDHhz`kBi9db6LZtj^>lc!-GKjyGc*{Swq^BW_ytv|s}_-N z)#iz%sX{``^-axMy&5s@6ZM|djW@>OIX4P_)HX?Pu-m%rM)dj(@gGwVh2Q=zM?|Of zrZe@wX9y09=7P`ZV-rLfT_Bqk8**YQ<6Ug-BWP3WU`C6Wrtc7v|4$J&gb`=>&*U$$k%ITf=s7^FB zkjc;I->E zC)E5sUWkjj=&?4#KVv_X>0Tgnm|uAwPTv8;-(-3}N^`~2`5=+;ub@AxtlcPz(vE5s zN5Ot8v`z%*@(ttJvz$~aDjwsGkqRB(MoKA6?OvtI)+%~2Z92QZEm%x_RnwVDApRza ziFkXJRgK`L1@vyq%QW_S++r z4-0+3)vP&KsE0-SpV`K8rN4Uh<;NVlwz@eiUr$Oujsyb%08r(A3kxVYv((gcHoF=p;J~5q{+d=Pb652X0 z(jAAYR2WijWXZ&DT-+*fonbyY=wHI#C;v0EeegSTDf8$p^Yvk)zoF1XDJ7dZL6&DB z_)*ByY^KEg2G+2g&86;d^by-=Uw;Nu6Y_cbX6bC(EC$k`$56FFv>@3Ttzr~a2>bPG zRwVRofz0t>Y)h7>_ZFcJMYfAe0*gj!?H?#`X88PO8Oi6^;7I0Dh!V`lI~@(mzdrwc zOmZ0Ci02VA>8x|{DIJY`E(FQOhbn0OFuq|~JNn;6B0K*ciR?*bMvvEIrH!d@(z$$7 z=2t}hK=;+etT&I>-T&6xSp~(xZCMz1CrIPaSaA2o-2w>&Y23Zhpur(n(4dVIG!PO9 z-jD=ug8sM%NN8L;SR=z%8pRPp8he*4lu42UZi1Z58L9+L6En zquH0N2@N+|IbX&i({V_7lS9mZ%HHu^G$5~Tcj&y!nCHJnhJQG&t#j`D~^%CoY%|0PRx+xS5@s40e^TY^Z-hyf+LEmT9 z98Q-uh%O{V>%E=;qd~RQEJn5r-JjC~9SaFsPdi+|IVRwo7mz)6C8=zDnkR0ObeJjr z^BO+N&uh1OjBBeUQ?h=M_jei^rX(e8P$oAW(sBJQ+9!T#sAwQ^wK5#LzxEDt(EaLs z0iPIz5e?X}oHNk_^}PF~t3FBZr?GQO%fzU!P{a~j{JHVSc1kZmb0+wDdL8^Mjma+$ zY_TZCGiqtV$%W_EeY<0Pe_SKH;$6!F0M~gP1#Gdq;Ndwxs{AYHklUkKk6JvknUH*! zi>YkKoVUNuWs@O)F|&#xPe@A}p-~N0#pMUy;o$a&=a_C-+$+(GpMw1)2rivhohi&h zvQl_HK;Qp1HDfF_=$f9Nf6IfeEOK`LP+VG>*2VaaPMs5SL8`y3WgQVOUO&fXZrFmW3m$WeHgQ-;_NwaLX~`LsZNh>< zu9K~Zl;$SN02u+`G1SU`dhN%qtK^*EHBxM?A^_2s{4qV}br^@a%6Sbj)s4YuOCM&9 z=M^2Pj6ntXS})%_zZnbiwT;l^XJY8uLLyg4c3I<>0gTOty8)n0*{*FsV9I`HC% zq3XG(T-P6pre|DRLvO*KLl>J}N;y9sE~czvQ#BF}Ovb(OxxMnaZE~b2NPLm^XO8c^ zDbfYx$o#k%Gycnq^V0;gpChS)LXsWP&or)nejWe}kMu-GBlCCaas7)Fh8AJgK76i( z5=U3$(_J^pnSwUUIrf3s_nT*XfV|h`Pfqp{Tos(z&h1FTL%I^P@EMJ3M7<~loPL+H zC;%Ws)iMWQ;}CPhA+bwNo6FBzQsK8`P70f8%YmnS3zw&0({QDz&Nb6|h1}%AQ3u_w zb==K8blnKZ;#lbIl761gt%-w!$B>S&+oUf6uL;8|Zqb|xM&s8h>xD_8L*qY33xsQU zskTmXtv82~yf8dz!g31Y4t~T9TitS}{C?XLz#v{Nv_H0}`81nM#+y|i@rwm9BZnl- zF$nRc=A6*`P@2^?+@9aub?eqI_mx^Bjd|!4sB>zh8mIeg3HNj{Ke;_WAJAd&OV_~xeY-Si zallvz8z<5XFkD~7OztI;8qGlD69gjTz}^1E4a?09E4GSy(1Qo-De%t!#!?zDSQ?+1G$jT;jT>dV zkr3uBlWLC66UW{DGLA#w24717tVnG;|AV-U1|xHqoNvSkO`6g9ufsO=hItiY!sof& zk*O`P4FFlRc?-S$!JZs93jra)aqoo9e?=+>v@vz$<{*ELM^{pI@f!IE_Q7Hn4zE!{ zSP=ITN-MIADPC?3hmI@`^=c~t^us-WieC3!0v(HPO)lW+I1FJBq6- zx%?67e5g9%W<`56GSul(OPfhwII{Xrx)@Jyp@kCbbRs^xFQ7Q+O?WSvxRpY!n=w9$!8ecIG@xIcOcv3?)+by^W!e;TG z+zq#`eqVLyz<#utDt^AEib`pls{Qdb!$RH#>p-tm)-5AO#3S6y_94yK(r-w#%dN1> z__+hr7ayO83)}C%@hW&D7qAp_JnI_jd=!cq!p^&d>q;f?($TskJ<$>q`}(Iu&nhcfo(N(P z>z1*YZ`~1noE0Rw?-X|0oS7**Z<8&J$C>daWz-JMQBqS|Lcoc<=g(-(!L?31ZkbgW z+1|i<3`xMpQroWGE94O3B$z8O53~E*d%|I($n>UxN^Vig>)u$FW~}U4rJ`O#038-q zercv?Mn)x?xF-#_8BIomiwy}f=Di5(Fj4))aJ~05D{$XVBK9d>m0Ks=r;autCa8Z0 z%d{}T%$j|R!1HZKNC#T^-%bWfn^TF=qEL(hgY@oTl9%t{kunT=P%K5XlOquf%wD7P z7tR|Ei>~RjQ?zn0eul4t)#|EYz#sxe_*h))m6`_@ErOa`FPTPqsi3Nrv3UenWI*3bIebbK@!rJ7@ig z!olb*CxNKocSMi#>ALt=7XH&$mkQBg~w9r*=o@BD7A-{cxfPM=@mwU`5_Sh>kQPE69ZpFIqx+-H1OB=Mm2X;V-uqG7wF_89A31PS`FNO zqaje23%_c4H;hYDf{y)cQ#u|jRa$l>MLV104!O|PYNw42_-U&M%g)>d5bC!MNFwp} zB_t(?B;)A>j1isuWms9)hX`D>`;gR@Vp~&Je~^IaXyGm@@fUh0t$w#~m@JlK^gE13 z<_2rtCK9TOZXj~`JDO0$3|0)p6h{ipJKZgq&Yey_SDZZT0qACH?ZfjA4!9Oa(ve7E z=#IU?3lWm-r1H8hN6N#tgJXBU_Bt5YSKC)O4YvGF2A#kYZNF`|A9rcKx&%vkKBJ`A zM3Vzbh`Py^4g>*csg*0%`z+E0&wDqch>Vvr702< z{xcNF(o6Qke;M~ONegL!sc_&}rAlmc;;XG2V$vCsC3m8!gmt{#P_=$TpSpIgU{X~3? zxyE*QODE5GE@cxF@;MQTOHT}i8$(UbvdV~ekJbwD;p12stD_Ktgvb-M>Rs^XS9{+6 zHO|qkI}`%hL8VTgaQT{K&GptI|4hf1Sz1C&8=ojqGQ6=8;IJY?h~30!rAaJb zvnz^}P58x-A02F!$TMZlac=(b0ZmHH5W+HJ!UpJD=pARBH{LID_VaOzVqf1gwR73${(N0SJ#U; zHF@K7%~I*K8Z7&!H)Xe#0U`x4E{FplyA7PyaAr{R2G1PqNTM~F5gRf46gspDC-gst~*;L=U+!2UzIs53{tX0 zXj$>&8Kyl|qlgP2(Vqi9?c~KAi^Xj-QPNJ$`2AE;=25c$d?}&Nst@R%``N`K{j}Y& ze)(n0>eORE=GY34kuT!orRyTZNo@%u9)$uVKGP5t4)Y5nj(PpHk)+%_MDnJcRiF^m z2Z^YiT6fi0Hbo&JzJA8oK;!%T7B59Fb%b(_HuPfG+;oHu;nn8s*jcfg4-Gv+Hcc@Lw zur(!tqR&1q&eCde10J%IqXV-Ow)=HMuppU53% zXSaL%7VE@{k8$`LqR_Ef?gPl5LuwJFgHmJal7;HN?Qm#JiGhQ60ttX1l?ij7<0Bi zvKsHOxTl8;j5>0UbjIJP-$)<(ZUhcRory${=xni(%V!Ac6Y$TC8`hIc2g@xheC@pe z2V5m=ze*nay`s#9qw>df@B@%>XtY*>p(^mq`+Xl7MxL`JJdR9xlmy*b9|QtzB&p!B zZesx?Re&}=zA{C&1b^2!k98l!MX*jC53J$c^u!~B?;|8v$^2UWG|;JQkC z@2UuSSur?hENB1#04E_XtOx)A$^TqOL4yAr*-ZNbeomlHf)dJ*KbtqCarnuvzvjV3Bb(O&c=ks$;i>f#Ma5&&iNXom-i3{_e*Z4upV(Mm zADEto2Lb}(*zR*aVP)H-C_Ulo3G-;)MZdpaSH?Nc>;|h|m(C z@;^@(L6bDN-ts(Es&U^J6wTaIlufwL5q4Ezj++B0+H+v_9a`l}=ik;FtvuTF z*E-rB-FobIH|oKMXGs$s=1)3ejkWdxR!v2;kckAkRwdDel5Cba*{Z&1UQL9w+SRDws zGKNnkXPc87QBdL#FRG8W(j~sF=VXZ{R-8lukKjT?7)Em)f#ouDGMt9^w@n(U2M z9KKIxWEz|Ww(7-7s~d}VN^;BEu;p>M5-i{FJOsXR$PVF)mYKNg?zuC8|X9-;4WZ@CkR- zUhf#@I*ru8UE2C)1py=TU;>Z4eO3EVGs#Jg9wZ|@N=UpdoF`R0h?~X)U+$V}Sh3Q! zaUE#DyZe?1QZZPbVt!p)uU;2EU$YzDXnbAO0mKsWXqe$VqJ8%6IOAL$MQf8(^ceaj zH)EKS_?xKxwyCok9r?mRzUiOZUbn=^FkviW;bAP!o?2~b))AOyQ-J+?1A7uwmxf@` z>L8)H*15+~`=Mi`4Y(|?0Sz?}rJ4yq5kqAHd?GQ=z2Ym}Fc1-7U%*>|2~dM6M!1c( zZa5HoVg`>1=LJy^&iLun@uzqHw+#E61EMpD*uMHvEC>GXO*C(r(k2u-CzX3}@Lmxg z9l`4!EzLGIp|Zxr8s9WKPZPgJR)t|#_{!@&nlDtt2mANX zC_H*<4f&co`Bzu^Cy1GBhvp3P* zDH(tsUCj3?>WxHOzr4}E+l}Kv-5G_^cvE{8?e{i(oxGL)E>5`T=h3dUBc2NhHGev9 zV~%NdmON1A@p4gdd2|HEd~4sqy%arn6X6FAjlr%mZ1ej^WKtXxYvQ6&`gS?|_zU}h zU{OGb5)|zA6Y&niw_IdY)c(;_)+_hxu6L-01gJ7Bo=(cNdm>lF8eTp$;|y|5;Jt>x*rfjLKVyNca+$oXAp!+)#1EHh`Y&(qSt&+ zBE<@$MuK2Wx#s$aUuHP2{n7dDcxF4iC_*$e4!XEyXq4NMc#Jvs>&RyPiFP4oVFmZ!F0K>D3yqhhRP5gFV%1%amyK!WEA7e?RAI?=r?xXu zQPs;U?2?6s+um+;J^MtNyA$4y|0L&(gCH19_xp8W0N4c?9QXa@M$;Uc$$h<3o9(-+ zt@<7IN{$rW@7D{{uXY0r1ibB;nBE6d4JlkIKcCn?n=M)Y$@KJB%Rh%V&)D{XztNBG zo;z{YhXsW~pA^y3BvWqR#t?EmpIUxXXkG|TGxHAC|7!lY&A>(bX{Kf#@@CIWbv`>D zzq!En+PUARe~TSr^2dnr8akjsmSDVJG9KJIfFQ(?%c2oiNWuPV2{UDUr6yZxEdoZi z(V{yL;-CsIuk;>_BF&hKTAx(_l3Wk{ILwvi@cg~wpp2N9D&refFnP=;l!&;peO&r6`$p-{UU&6e$?GgV^IqriAvQ*oT&m-JRHx0c*Lm5&iEn0LWI?)uLo@{k0?!RlRI$n zJ*X_)2iZvfwqR!t1hPbM)l0L<=qk3^f4|aH&2kPgJ;LB`Y^Jh>fJmL4Yd@vy${u|l zb~mIBY7W5h82UR2sHo;hQJ6t})CS0CPt;6Xg2%A`O)gCtwwKT%s|e!Tg(Av>v(Jd) ze#x1lZmMD;VtVPypYVd1Q_~8~6E$Ypbbl~Poi(k>n!NL({x`CFXtBQ?&6guHM)|K@ zUzuPAVm9#MevH%ANuhBlTu6GX@t<^Dds{P!3(XNj>?_1<>7-kGRS_GD$o76@=P6&J z*{E9naw%Oa8IMl*if@^0wGc*)46X6^chMbha9Z($6CdV#WP9TE-rodldVz?&YiA)F zF|d5PfSPNSFsz}ZqAVA3 z6jTMeG8@^)#|OVI^5$XS#^3t4`r&1Lx9SO1MJ**Y`^~~IW0pWVjZ7W6KJL8iP$$@x zrh`#lZ1kCwp>KkVazMN_rw3e|C>0f9e6LoV56NYTSBpHmp=V9L6dZ*w-wyNJykW`i z*;feGzzF)#+<$%2=V_Q?&LJVSS+PgeR;UYraN=51kI&x|Xi33Y{h>#`pH zti7~-5F{>i)Q=`;#d&`wcG>al;#$vB#HQC{+S)C+IhSBVYomBBv;!He)v(f21Dk*m zTA@~a&qEN@)(rc)@aM*LfC$jcWOIXdpRAdkW=*2wz$Bx&L51dVH<8w8^dxhW#3l0# z$tzOr84h`$E+c~rWI4=r1^JL_h?_9JRG!pw+5Lc=X1v z8TvPhE>c+L&6qA3CWuE5to%TutsRAOI&s!yp=fp0XG!M~h7v_0o=H>jCcuiOBQ;&`uW*#Jk=As(4uLy!28xyX*1A{mT z$uy;dKdra;+n)TNY7ckUq*T4rj*+vaY0{VJyuk%`Ht^`%p}cUpf1xyHTZWp!=r*Xc zbt;cwy8Wp;XyOOgUXegSSsAdtv@nts1(m-fG60h?Vlyz+`&tebuL1oDq-FQ~%~eAx z-EMDa?AIzAZs6Rdr2t4@6^wt5;l#qs8O?*fAh)hFW>tkcSaNg3V1N!;!g8798v=z< zz1uO=-!C6T!{-X8ZRoZX3J^9Ais?yqq7<%8SKkn< zmXKP##Q7B>pfZ?QxfD{+5}N%wzhjAF)~dTn-LlgQhit}_!8D`y{Q6p8eyl?7rT8n} zm6R^u>Z!C_ryU1&O-E{YZ*8ErQo9o*ZC1op^nml_;kmzB+R$H=cX&J@WF6A4cr@I~ z{NrHMc=MnpUAP8j$FSFmEORZ#^phM!1$X}SkS;0u+}}i4o?QK7ETBTIWd3iACu|L9 z*}Avy`rNM+ljb}yd`<%XnHW&bN?+k2^ah3riOf7JS9 zsPM%?_nyVuN4Fi^zVtKn9?gAWd7_E_r47Le$UOUGs1ij!dW0T~�{PnX$FjeS%=s z1OJdp^M5*Xlzy`SfzJ)+9~yIN%SuF>Lxq>MPo6RS9PkO3^rW3(m;beoC5-U|scL{gCI-duo@(TB zK$H$MFPCNdYo70yf)Z!`)GCL1s}q8&t#+VDr=1XzI+nn^#AFsbgjQU(u<#I+wrBj( z%5iI!*;renK0EJ@RoJr6xll)PJ>HD&&=xV6Zcp|j`Knb|{{*e7BPpv{bUvu+9G+*|&J^D$zKZXqI2fyN zx~-cQ)!7@}tMRhC*f@In^zzsej>u)J%YWya9!6l8k3V6Cbn^v$ z;*_tPoZ>9T2Vv;B9|gZpEX(XG_-YG^@J}514e{m#dpO!sh_zNr@{z$*BwK2-zcpAF z$+fYlk~&EfCLCEMY3Tgqp0cAeU3Ph;>bqS*%~Q3cTv2_Z+ChaOoT0}KBS(5W^w2_m zX*l|)v4|om8AbN4)%OwepsG~#`mg_b_v=E!su^kYL7UM>vz}0@V`HIcNs&*2Bu>jK zgGJl)Qc-4ObSK&pGzm*8`~$gafX?xjc%CUJz^e*`n{?DRujQqGU63Y93zz;Lml)1Zu$mokxBDNf(U<=V}SiVCGnCji0q?lbJ) zH{K9WA+*^!vZ+2h<;xmLtR%*8xC;>H8N1S^Nf2YfI|%!ymW<$)GW2S^MBipC)glG) zRFx}~TO4Bj)g)qLQk|~$&X}9vnp3)*hL^flqFp48oLuG6Ymjgd>u}YbItYA7BA$9~ zKMuR9!u%%;)0~Me`&GrWOAjY)c+llrg>fJalM?u2)toL64U-$sk+F7bwwWf5gec8Z z#~QH^?00LK>)Rx!C=S9Z?(R!x<#L*n1GSWEy7r8on1l82kI|3blT#v|FCENNlg)HZ z?0}%>0F@qrgMc{s51IBT5yaqcSO;L?{|BQ91{T-aL4${;7}e2CBoF^?TKhyF)|ppNfnvzXCZ*RLih7(4E9^?<>-$l_^=XZ<%NX5eJ#!U{W0;u z5_U5~=H>JC9qOe1^a}am{ZcD|Xu-*YqLcYBT*yVpR7e2nm(xq^&zpC_A~ydo8AYA` zR?NEnZN+#Y^%`&Zk4}QS{)<#32B-jlfHVR02RM@XZ{Wz&0Wd|ib}mJFIh6yI(Ay*i zW`}*^>`Jcqs^i_gZ@XL_3sy#Sxvm*)r3J<7`hx}NAj%(0;Y>Q5lOT0kv5#wd5m-Nw z9C#_`IRa1yw*{f-Ak@tlXV*LntfLCj-QL!YkBfD5V(P0W1}8)zU`7qg<}M*Fd^~pu z6YQPAJGw6+AacMxx#&Q9@0q5}T&Hnjc#=8_T_q4!Pi+2a)S&Thxu0Kq{K_DJtet`} z-Hi$V;6;TS-4dDF-PxO2-8K8RvJ@S5o%4CihtpU-?Z{Wm1;e;E0>YHJ3QzLTU z1ES@z4=n`-%-eelIx*+{5skAuHZ+97MCy(0yLq}Ecv{7Sg+p!Ch8n;on(^AzBV9Xp zlJLrtd(zB5sFmpCn3a=h-Oh5Vz0Tm2?s~CNv9!s$f9~W^f-c?J`DE?gW>2E&w*JLv z4ugM?<&o~uA``1KVVi6D_OLUooat_0n1bU{D&jqk*i5rQ9b1y!k(zV42#e{HEHRVz z?M}kQd8T3JsjO=F??C3_@Xyp=5CX`7EW#O~7YtG_AKaf8F;jqIp|nKwI)b&$y00Wc zBa6!hms%0BS>aZs&5+&Ca(g$jN^p3&e-E|y4XKh(^wD9i{?q@tKkA?*D>5|4#BsKq zTot8>N5Ss#z%9Mral%)@dF7{u-T&yhUr92GnB&kNa5^rLEh|2}T`+8rkZ_@9h9Am@ zmu`Rk#B(dIDc~M--~-P*V_cgd;q~0tbB|iJ>H_FYjSTX^*;>pubkU(*Qxg4-tszH&u-R(2p1=YTe(# zEEXiFKvRq=sYV?|nA%Q!>_fX|wY_!(G;%%gM+m$vl@5VU#Mk9Sp+lR%-jwW#`>#=+ zTEnOo(Te_gGG*I~1(kD-S2w@h(4@*Z!v$Y1c$i|zZpmzcbciCy8EfuNh>x2KWI1B8 zgP{h{M&HN@n+FJ?YpigB65rnOC51d1j6mHIN;WSBL|#4tD31@=z>Z3u8Vsnw3&yw? zG6m6^RgN83evBo~cI`RD#G+T5odO(-WSYP0(NEvu)CRWf3JPYSQNoKUsT)t51%G#` zv#{aP>AUp@g1^Gq3bxU;l^^=?`QjM{zIOCKuvJhr#ScS$9?J#7V|e(#FOF${%@-o< z@mdBoOhXTCiHG{V(}VKZMBw%NU>J@)YMOJ_G4)V&;uZ-)-(6r6#eTd&{h`FlPyRH* z$#{e^-KGkf^RW_wAPMyJj(*~E>$_nUGQe6u_AMv7*&y556&wplpPL6teC1Z1W(SsO z*LT-Ddi=cx(|ew$@M}Dl+e0Sa-&38kH}vfD`T0irK(J&dQRR^`T}p7o}y( z!!(fWbx+ZEu@H8vnt5^kwZXD9V$*@m2a3a%imyf^I@S{nO%fOPV|&kQ=h{Tt^jP}2 z-AvJK8QQs^L{y}@nk)$0XG+L|Lz4({pf~;R$U|2!7^KrVoW&DJ)s^w5T&pNzupfg1 zSt0?X;P1~?;Idcbp6ZG*9*P=b0ent`+iz!VFadX?kJh^YN}oBOF9l}rFN=`LitEoQI26!bnTH+d{MkMZ0?_GiXQm%N>Al(E4E|{-+++TmXeh=2pFKds)vt~x zC>Q++m|yMMrJDCZetwapMwa3~1}Y&pAE6ZA03Uc1RB8;i=q-yJF!;7lvSgCmrRLFJ8I+F3LxjkIfat>xoN84sZi>J z_6v^vALF`d;7$s&S_VamOqYcEbp4+fo|N}%C*F@m-8=*UGP~n$)f55(5D0E(BoVF#P9AckQ);A*p}K|h zTTxe%h-c#;M}-l^lVVwKjQm7MiMh1HfhR_lg`g3v&80Vi5y?jA4b9!c;*{&}X=W+V z0?uyce>2=n=DkyttTg2Vg{z$is8nf30T^sOo!mt0L(@j-Ik;OsAiqwoC1FB@#j(Ks z9J56elTq5d%qh-@y0{zM%ASuBY%I@AU!W7tzlRj|-F9?fDtc2ASuVhR^gNwsER3%y$atVcS@(HN%f zp+A^&rXb1bZoK{YH-54kAm!S@6odwdg(~JNV2c|qnfdVbFhlqXTQOQvVkQ&C?_Vb? za>2v?>?ioVbHa}5l6>Mr6)QtxIq@NcUqeu3pnS@~iIHgLw0FOwCE}Un$A|I=UiDbI zZ(h3r8^jAa)L0^%UxxsQ#JDI{-gdBU;TZ8k{EL5Ujox7aU8Mq5K;~JJ$CPxY-S#X1}d0nH8OOzySFl2^S7Ajn+3WJ#?w|978a%o;b zIkFoD+fH}m{#)xz85Rdq*2ol~!nv@eBI7eWcV!?^3XoSS+C`_+;x* zVM!x!VzJoTOza>e;pGSm>V?9c;t28R}jfbV}4%PG7n4p2hG&jbH!nhwR^z%TwDV1AWH z!G?S^^Il$hW-r5@G&VrQ30Gpd^Pga)FdaGL<~Cv|H`1@G%bN zR;365X}uEeY%?!r%4u7uK9HAJ@~1*C>(}H zW=Z-3ldY~H!#}vbU^j2gIW;p;0Y!d__eMmt$25(MW#~ae$;zXWbBlDnDJT2writoj zlidlA23#Gib$x z@ALxcytfgS)#*IKZkBX}zP2RyjC7TNOpDOVi^-)0T|i*>?2*uNENZw9B?@SR>}AN-P|w^|xEH8hZO}t85CBpKR1tW2R715?u+> z(48wwSb}q$rcy-?6kJ>!5=50_)1*xK$#Ib%@H#z^B+bJWB(t@&h+#7%kc44BHS(y< z`wrt;eIT8}8{e(AGnKCI$?N~;`|@gi8+Kl!ex3~Cm3;;4r)@BrZ<8j(@|G%0!z(i;Ot_k{9~9)*hgEd=!3;#B8$>F!*E2{4nP#N&|+U2i7d zzH1eQ25Ovx9}d*{Ev6@Mkby1k1TE0m?^O3v)F4j^G+h#;pXLgIF_S&4<5{SfRj>Y` zh5u5~HS4pC9PL#K%w3`dxzi5UNmnvJl23THNSiW;N5=eZfx!Aj53s>r7M${=xz!!q zlLv}t)-)#ublm-Fv|uwuunlnBX8pGxCLV9It3~_kYJ9SijcMQZs)>Ye=&WetMn(zk zNd`9@-k^H!ao?j&xfsHi%O0{fxV`ruuol>+mh|X6-T3a_&@;WalJzeB5Ejg@r7NT!$Zq(uZy zjm@hpcXKpn6;=K;=E+C1PXSa;08zK-yVjUc+JB@ITGGor0mlb>u3VK|vjmP;w+oH0 z#ooPLD(+_he0TfZ3{i0-@{aG8|H-!nFM#-k^40tFA5q1Z=ywlb98`O|6&}X#6$-oN zBTSLIn|eflKb=0<#|3d@Mb(s<)o%@x$5i;AUAxBFn1J-@GQ8fUj|~rEaPLwtoj(@B zzjIZZ+wHJC!xG4R4)hRDRS(%&ST6oJ5r*TYtq|=G_%cv z!1)Od^(0nP;3cg4pYDs*OF;*EVzJ=d@ApQZTWR)N3HrrEP?>f*`y)P_ec1nS@PUY`D0G=3akd%_Mt)lKj8zc0D0YtGh|+95DFII z&C3KT#YQGcTQEl%DMhAW?%p|9!Rv%i(I#SWjfIV z7ED_TZfJEx21Gn#;h&{I+1~;xA4E8;!0~qbr5&8)P0b9Se_;E6H)8TKd7#- ziEfoPpl{ro15~R6LW~rYEtufXix{5@4zbnmCCr$s{voJY;Vx=ox20S}gS9S9badMg zZhLLu!+X+HX@e+~t~mc_PVOL*D;kU(P6Vj&$aqGog?fwRG^_|taeS|t05I1j*VVcI zzfiyoCuxSR|7JGw#;GYdM2TVX>YhrLcY6Qdx;<2*5Rbl&E4%9mGJP?@aB?Kv7H&a2 zv3MdL4F+kCGhd$=J9iPn8LC@g$TT$G?}C?;85nm{y*CMBba<;+Lu5I>JCOYq-RyX1u|?0u%FPI)UyvZ?(R~3o#IQG!0xxr1 z^ir0}=GyqQl7uX8lzU6EH;-g^A|k)Nhuxjs526>i!24#Lp|E{*f^Fu4740A(uu+il z%6I<}|8~76ScJ=pm=ML){`l0#bprG9#SSJ_GYPiC5AGYdV5Ow~r_s#itBDg69zO>e zw-E?-epTdzkI{9Ks_?q4_+UK?B32na_*{A3clsq7jlYOs&_FglX$!q!hB49sWbn)T z53BDM50VQmF#!;usf^13;SXygXuf|;>!B3uwm;KONWom`vx41)b5(_9j23q9VEVL+ z!=N{+6sM=)Z!rVeQBU`8bBTvCx?8^}tNx4ev)tSQF@cnNud z$WU^~*!k?0%$loN1d}D9&gd6bvrYt|Q14(~QWSy1jxj9e26VTMtdR)@0{J|x{`)wH z{NoF5sNjVnjYi4oeXiemg@hJy(6{ED(t2A1m*u~gNB`G$QES-*@(GujeyFG&PYSZk@$dLm}-6?_ZZP2ok3^Y({?kECS@Egf^PSEpU!{vu?y` z4FZumIoW)`&}B_bzP?EdO?5W!431-@O2K#VO(%Jj@!bb$kN?C7PE+>hk%vkY1QK~l zGEe?JvG$aG@V@$GLido>g{g*@)%a9iOiau>=7S(Lf08f59i@~uh?_QnCOf$CxC5J)a~HH@?04U_4uPL&=t}?WYpn^M1guL)2#*0 zO{L~2bp3Rcui^xtso87XAe&{T};6H2ZsAWr?G+w(|^9zK@U7zPv{%$Hy>Cy zBs3~!8+ID0S{N4p8@0EFGN#|tDY8V?X#PYRHlmFN{8kTsaH#Ebz4zp=sEHMRyW2n_#B!T}h#?u!Fxm z_DXM>@L^(Fr5nKru!5ob|VSzyEn!k$xz!ZVZIJ@JyyWpZLIL z0VdFc2=zq1cRaKe;rtE38jOwDgGhKaF#X8x8&BU#slCu}lNfvNxtsU=H$*lI5cKo% z3EElq%yt@HzX?cy4N{w}4o*y$6J~OBw?>K{*QDkmx+~mzz8IBT+vNu|i!}`2F|CAu zcEXyTP8IO@`p|A)O_I2kGMFYnpZe*F8)&T;LGU8ko=OSa_DE&5o(%{$%Y=`~YM^8v zN&N0QJPtghun^jx0ZD|q1P4et)hVwy>H0IGUub#2w~y6ZXNT5mQkg`aRy~9RDGl)b z1gVJ8(HVFnsXIvB1x$N5J}3qCOU^eW6wR{8U_m$CsU3h3PAOHmk`8~PiZo}nBSxXd z_JZnz5M`9NaXqIjx}hpk5HCaDk0O(q7N%33YJNa4XiTVFvR-I|i3XqvqyiTr%0Oai zgd1Nn4=24O+gBI(8Q-T0UeDR=Rwp{xT>_Gw>cc9th^nY@6&kKBxjo0ICS=I?gut|5 z%xSU}D#parJy_rpbxdIMoTJK1CwU&& zM|BGZni+i6S>Rl*Wd)A~tPpipEB~QA**hj9HrjEhitz@nbwGt8RQqo%a2DOOP1GCB zm`>s@!Gow#&Ur6Fke328FTES7#}H4RqlNxvQZsnZ-CFIsK(OwCeMzGQx?DO;e^>y= z;YJDwPdc_|BdK&qOhL(h5XI5^frp>xb8TSu>ntwBs~FjaAgV9yi5QU+5)#6>-C&>+ z$<`6hf%E=GnBQMvq_-MiJYB4ZlkiOqJaz6Nd+*vMe-kGr_5?lu4C(3bURD)PQAp&N z`pIrys-87kgQ=<)p(Q2Zs{Gx>U|5L7{Nk88v%$~ ziGaKzwy#gREALgV^JJZ_h;W#0#9Q{mNr__J zEGE1FLMBfSGS7;wHG@;1@sLd61kBE3DOQRr@s;Vy4C%xph)uS3?8M~XG@_Ofdv3lqW&TG+; zH_5$-QyY!-;aC|nF}{tX$;XF}gTsZ3FN?08T_@MFGcmF5Ov)S{pYi7X$wo{jH$!BJ z7wnHb5@qxsi17X6{VL=?ps!Fk;4RN!r~nB_p2y8h?nvr%5d<6VKUnha6ya6K_l!J| z@n21x>*Un)5{bldBws^TEkxZ&$o%i$=y)WEd$)3}f{0&!;X>~JEldADDAxb4j7nL- z_IkQ_<=XiDqsZ4>tWY_(tE8F%Km$76uD`M}{}bx@VFgSM@P0cj^%LU?W*f@o@v8HB zwyoEJ{N~KqINFiO2KiqJ`2Xv7=u-NRm)Ex;VFp-1d4JLvP`AXCfnsp!F@G~4kEqch zh6Zo2yL}+znc7`h)gIU0ro}e@Fry;SM|16GNi22d7&~gGhgti{v z(+`XeKP-P9wBzt5@dVywJ_*C93wS|YCc1dxIFH$Br>@> zV_{-DlJV2)Qrtr_lLzMtjzp;^k(-0<5S+VIo@Nr!JNfl<%E7-2dTJ#pE*!q}W^8ge zJN$SOr*`PY(L*{o%Gy%z6(BF? z9aA4pg5*9dvDU2b;8S3@bmQJQyb&_q+UkF%#IifgiJn9AJUDenlu%w$?O2{N+0(38 ztBx+>uxFJ@3^L^8=F@Lqy?z9{B5K*!vKx~{rLm6t#ct}#`+c)~SH-PDu}62Yc*>ni z$LV0$?G9h$%ML0FmFJec$uNvZV87@xJ#0*g)~!BQ&(2FWyKK?lRa%N_hUl++62Dts z)x2H-kyUB)W&k&A@%g_S8@(ngnLy5qR%LFm`cpMKj_;R~0+NTj64!O6;rKc>kII$K zO^?t9NeF&>{Sb1kShUvVMETxNFzMb2R3l9WCVF0HOO~4LX{HmWrRgjm?Gv#18kZ^N zYX)FSPUWLG&Dlbk-NTB!u}zC*Wi9rm@r2ydyKA)uR)=U`ahx^q}sNz3rsZhE{aKGpRo#q^eHH8GP)cUY%yGYzm@ zohk4|x8`M|T`8c?d5=VE#=GeJJZ;S@$L?H^(27Z_$<&j>92vwx$}gA+<4R9#=O4F) zzge2K`|Er3k->O3fWTt0k37=e+E7^Zdn(@M6U*aapP+)8%iiQDuIUvXqv=VXKW?eZ z%CJUPJ9P4dFLOasD`iJ_lA0jbs-sOo$&fh?6NXjSag+4v_SvvTwFS5jZUq2aQ zKtKTb)ipFsMEDjXqDyA%&}O$iy2w%&eb_2#;qz(LNC#izYphYc^K-mueG8c#oixS`g;QHAEWwz$OA&l}!O=w+~O? z?&?D0CYT&Ype@!M!HunWLI%gM*xUodHca$qMHH*{tVo&ftTM3Aw5>@N{(gElWL>_5(8oe^aEl-7ENvW6Q^_S$Xtzo4}+*e&t)&jN;D zK60?k`HsPLH?hIGJZp!WQKW7y)B)6vTEf2JCt{Xmir2fY)|Rn%s5M_Vjo#rr=kNrv zfcU__LP+j=I$$Y0sI{fA96+~mK-gkoRh?qaCi1`42Xg*4&fwsI0E*HKE>=bnnT>%t zJxzRM7O`AfY{B72u>d>KaP!`-tUY>pup$R(Wv7P#uU7uWGX}V@29=vV#%T6- zJ{*g$NBJ2#C#qJFDe#nnE>Fa;tFfQrj@gRg7YFvt-1g(vs4h)mje06wTn5-z+&oJ8 z!J;{r=XRd{?+8FNxR ziF5c+H7;jG(cZxCgGtcLN3Sty-tPqP+ww)0L78=9)*kg8Wm?Q&Vb6IV$H(-#uZY|K z#RDn^CT`=V-J}LE3)ARxA&~q&RW}-E$#lAS9P{@6pjvK9fE-JVG2I$7!DO^>vhyV8 zm%yF`%DVpZZHS5d${zAM{*K6N#xr76q@f5VxRLCHH^!`+HNuIG{Cn+oDDEd=-R*WTwiaJxxO}J?<6|ExWxOjJ$Qv zXD8pWdG+H<_`IsU;_JzbkE-#ll&lnTeS9@WeMX7gofnK-9#`gjZs}%lj*c}#aVGdO zt;)-pf?6AC@>-e^be2e7ZWWAxM$Q@1n(7NF>p)7YR;P-PM%(vSbg7Lj`Xx~uIXsj0 z+x?_X*4tVS@YxzDQ&0vt$|EqE;rp%Uj(u3^t|l8km+x94h-JDybW|)KY}%OL4J7vn zTjnj)eePT`?{V)xMknmeK|vOCKkUU?VrIRAl&mbvV6^&1*D8FOp7`_99C5;AG5JH7 zGM%l!=veZfEP`m^F7x%VWbrryvP->4)YHBZuUD3Y454H3IbyO)cV*hzz6tRD`gbTI zz*_u+X91K|>sNans`kc@cQR6XPyqe;=MV^_>`|a7B1g_o%;yik>}4$bY`hMopdl0|4)$(cIgt8UMDv|w1;H2?%MdGE$2H}!SO)*q5KHQ z3LC>6<8f3g4@Vdah*v^bkru`9^@*fag1H$(@ZF6+ADVuLBh;w%ey7OSzz%oAVEPsN z2SEvMtK_RWmKJzeq6&AZh_by_4ecftc)fu{r`?P*e`QJe-CnpK zcTc}+1>u>}5GGp`q$7_a&1)GrG7Ja5)(b_^c{_1^tkC7f$6Pm6Ek?SjyMPbJY0E#0 za8BRd?lgjz9_`h7E!0xu@7BR0_IUTZY}Fmn7jFeIGzX^sDZ^p161F(6Y3xv*;{4P5 zjdJwg6%U9qiO^i53ym@?MO;VspS|;^W%g!sOj)y?$rr@V5mtc{YM5wE9t@pGW4PdK zdlU>?q>>G1ArwBieCECR5e{`PT9VHq?>{OtEDZ!kUyS>Y*UC2lN|V@VSdJCn+cm#q zuFmQJ)ht~eCptvOqaBjr3B5W>iPQ5$N8Ygf_Bp{yiSM*EYj6UAqNU%JoaPOy&d5`S&|I;h)MS_8v{%)SApQRR zlb(zld^$$d=xAU#ovDn{`4o4`=|xJQhU}T_* zjwoPcA7##F6Su3=9<%4g9xyVq6_+HXN#MB-kzV)wnzu8MR`6gMVCN>XtMK5W-QkEG zH|-rF3C%LDTKO_r9(JG;RY%#u%;`*?Bh>(jQkeQAxHX-n;CSXreX0b!<~PHF#d1T8 z2PGGj3~FU(x4Mgj$DMpnC)5yJnFaUD=lL`a0#Gb0MkL@E&{sXPB|;O0K!GPuR1k<9tWMWN7>L zuXA$>VI6&Y^+MyOEw?tXD*+t**Q5tbfQ)GR1DZUGFr0*MxQt)bfDMs;S38bV>##s7 zGi15qQ-*9Ntmt3Bd`gClJ%6MEQU7Zih9n{s1EZuHZVcUM+~~_~p1%GJ?@PYMocGKe z<1R0rSIFM}j_dB-657dGQSgU3o9eYM=n>2E5xI7cEr5h-@#K?X`+61Vdig1cGp_@B z8Zrn7kZ5l??5Rx;1pS^!e)yVs-AVuuIhuw}_~ikurhzH|l%W*~T3TU8B<_H}VoQAZ zH7I|=h&s#lnqO9mq%|TtL|ZBUaIVh0fzj_jc-~4_UU$j+C0X0D6VT?#Y2#`v9VP9)md~$m68C}%;|xX~TCY(rRl2o~VyrcHh_;w} zFnX(he1mi8P7aPvBr1@H_-L63J!+n^Q$jH>NnSpwW2*A)@=N|KMX>pwbpf(5hP&|# zY*+Y$IyD&QLPS8P&IqQmWD~7`qrRaVN)0J9Izr8{Oar5ILqo$ub2(DRc?4pYalvGm z9G<2LNTvfx1BZDMhPgn3xkLEc5;9(I%?ZQ*?29`jUC>KpG(`J#Ouqc`Q*)?f14n|B z(uUrSHqI{6&F4Vu0bf_0Xe2abyn56DwJ5pj$EhMr$LQ|AB6z_*b}X2fZy}9>E9F8n zt3s2Sck#w)5yjSj&%S4v6n=Yg9Gj3BwVjJk=iSuwIeDqyZVh_f$1yK7a4}V4_oOxg zFGVVX^4un}z7=apC0Yp&W#J8hjYAPa5pGOSdlD&C&+~>`oM{=3yBo?ntWs~zJd4}T zzi6N~oD$f4*3i10++hzxa>edRe(&5h;s2Uh=NP0+sie!x82pvDF78EK(L=1<)ZR)}Ur&Ag zS8U(cUOQ}A#huwY_PkqIux1k*D;{Tjx`Fq`3ibxOImZ5KZqG7EDw@H9Jihv# z-TwmYXZbWQdh+?)yJ!vd4Vzf?_B|B4bo$=1k`{pAZ@gFHLGL}5neSFnwWN$OX*%iG ze88^upoWckxOm~`hgZhnGzT#8>2hk8zsa2iiI@YYv-+4W#Gc*81O#@jPT7|@!moBQsXgfNembqOsSG4z;ok)z?PD^SmUOR;+O;47}te8vM~o zpa2K9E#>~J3dl^3!y2O#=jun^*fLh`4L3PITjx)vAS;D<-Gaq%;K>=o&982x~B zy7i|@W=_bbZ=#JD&4M-7iN}}Eh11_>M~FkDlS-g5srYieIBf=Y&tNVut86l58gSjC>|Nv-Zfo>&{xCl^vfx%!DEBt!v%_ zu77d;k^R-Wsf@F%$Id|zqqwaF381Bcccx!NuE&94HE?)x8F$y)N7n)b|Ego&jl=1e zU}7fpr+Dgo>h~Yr|J{lC3F8G2*u|PBOBkAN$F#ZdT`+_98oPdl>hTFQa>wcMRCKLGwdHK_elI9OK%z_4}E?(ukV>G6q9_si59z>%07*qoM6N<$f;*c~+W-In literal 0 HcmV?d00001 diff --git a/localization/autoware_ekf_localizer/media/ekf_diagnostics_callback_twist.png b/localization/autoware_ekf_localizer/media/ekf_diagnostics_callback_twist.png new file mode 100644 index 0000000000000000000000000000000000000000..4608a90e5522005fc9eb6ff7b3629b64fe2024d9 GIT binary patch literal 17945 zcmdSBbCBoIyYBmK_q1(K+qP}nn6_=(#HL@6o4EZy8LH-H* zDPuZ`s5>dynmD-{I2Z#=ZEUTLX&j9ljE!v^&1{{nL3((9PGT}wR(BF|Fg9>9x3wWq zHn%qZ*$DtJ(lat2wl&go9A$>lvmB)s5iqbG{S9EEKMV_@XE`oOaLOOe1^@^E62bz? zZkZRG&Q2(5*x)y&OKewokiQ7U30hHIW$egNQd9O+OBKxg74zKkP$cc4KwI```+z|u zZ+8e02nSVGkGBD8Y81E>MHxyLJH6cnbWd z68DdnTi*_x00Kx`T$N!yEH;}D+Y})L(A}znmlkLO$bg$>Bp_u3P{JHx04k`!KQcsq zFad-+2~hc;t9u~4_Shmk>h!bpi!j zI*aOms%g((zOYM!qMXe97#N9;V?pGHj>|*}%s||2#mjl#87z!k>2_e65*_z78qH?X z+YUst<3Tq{8kv`Q+ps$1qQt@Stjk!i%{gb>5~4E1E7lhTfsm6at| zY{oUwdl7ph024ev3G~|=+A*N{97=*=XRbqC^KC0f)VHhX`CDE(?dzqK|9S^a4K%oVS#Vguqj`^<7TQ!p45#lgFEJyPgZ z9H@N`17b0a5qcJdvlZc2Y;75?{H*%EH2gUJvkhX*?SsDwvK=zyzm{+Idzu(v83mIpFoFnCqv++Wt}NwskNgHkgO6j7+oc! z%OpBXf3BvREmqZd@oejz5(J4Zf{s}J2HeXI^~A~EB{#iPT8p66FAA7m`u7$G-kvvf zD%yKlh%Hng_z6}&)h?9gxjqbV>GX{Fr^kQB;-vZoS6K|DuR||#_@ZlOGcObU27!_4eG8gRMHacIjWlG-3LPtrxl_q zh)5=7w!q1b;tsKC8cax=v0}5bg+0}tp5`J1juGr0?HosZ8k{=j$_|GOgb}+luK8sr z!-srZJ%fkrD%NE;X2wnr8k}sNGtcr47HifY9vdm7c88ofaguh=5Hood+CG%2pVtr| zCQr}%c8Qdb&BD*z9AzFL36x#ivcO-}6ykY`hS7E9@pfx4j6aXvyI4j^nmyItGToY( zw%o%I0JYlJKZi<^0W)IjYr+(w-x~GWhgVC>h2&`niIEU*CE1sf9V0J}L@W`jI*xQ# zd#p<S5E`y3+C)6K1VA@|qfG&o^64|s5*sI~ zeJBQ>`IrjaYkr1yVcfG?9J{578mFCZzM))-+#Q`!)VP#eql+eeq2E2#1+2M!iQGx#{`PG zJ6%)ytS%%{F57G%$R$v0Yz+9PN8me-v^7rawPH#kN5fzv^IM0$!xQBrxmkC%HB@ma(OryIkyERgH7xsUTWVm*2ljktUGp zW~#>0#w2s>CfzOu&N=;Uz-FImmxiC(a7r6-q1&6Wcv?uo88D)lo_D=!$SOPX+*qk$ zr}5r8yvsN>AEGg+l^yp;j4f&z0uvqn+wcnh=fFK4nab>x$Bqtm!idLw=hb#QFS;61 z%d0sq!{u@>B^kQ))KC*j0=@aZg~rqUV1>};vy5(B^GyBqJd)Yid1LTDm5#&}$;~}E zKB$NmUXM6JnASCgM!>-qGY|zcZ@))paX&s--m?h7;Sy!vTlvXYotCqV}Qsa-bEcl zjKi?#ua1|z*z|1ti$9DK1G5SbYM!;n#nS74$ehWxU6N^EnLi*uAqO(G!rlYnt_%yf@l?cqGy3)Bo};uTvW=0Y^<3mx#S3nP#_dL~C7cw%t z&lnzbmtuGQK~M{5XVW_2)2w@s_!jc#GttyR$&Cp{ObtxYj&9vQ=4LAi%hVNGpjGY;Q3-*?O%OHbx90{ z!U?~d!_QtF7ro>b(vB$Wsp+1Xwga*VJu!6)f&zKPdf~ZZOALDWt zE#`njsCy7#bg675K&n`I=o(=9GgZOKchsx6-WKowG1FK2SuYA|z@bQC(ac3yg-|2M zF$(^TvZ{zfZ%f7p7-RZ9aE~8f@AS=eL*jV@!IH`dnSt=Bli>~qxd_>_OoPSQU$^vO z)Jn$sWRw&nTZ)qYTHz(a_-p~&ODr2lRGdRB4*Pqu^!fboe9ykvf8i7B_}&R+fl4sm z7E6=}y1+v3^R3<3Jee5`%$mJs`l_L77Kk=mQR}rL&rHz;xP(UCF$Q)oE0O-kkM@p8 zub1sVbxFE^+OchP<+`|A6ghIFFv)Pm5~1JD4dKnl3CNj!zgcX+*Ah$tQaR0AsqI9E zGUaV0k!o#|bUWo_CWKf8mmh7TSX-(azFyDX`FPHn9WbEewNb+it~4gz_yie|EzUJe zQxl+A)Z4%p1&IRHZw+xim+OQ4g+?Md zAa@DWMsTOeU!Ex5+0!<_j$@J~V(mJM-=)@HZ8!)XKoN2!O{o7#v3a zkEN5~ZxnsSf_wW1$z`YzP|MxnuCZ<~4@6F`lw(FC8*;3{blo3zR`Sq(NiY=SvEIo} zxDNQi0>}Fa#Qvc1lK%LUWlVh7U!o$Y03%>1EyE}MaK2UAI^y&Ft4u;_!OZ;A6g30Emke zmSD|wrIsgb)-=6B9X;SjB9rh9?8Z{@e_z1z0FQ$MxCZP8+A**^Bc=MjBQCV$cEfGv zyTzp7QRBRRQH8LGVA_hUta1!=DAP1v^8iCnOOqwYgDd%L1pF=;K=e5xx+39=HG_g6V;@7Wbzc<_ChbN!#fY@di5}*3 z{OvWf2FLcB2muk%KP<8ZvF1j!ETK7Ul@)oriYH8IcNdZmJv_)%qEsQ@3)762dhi7k zyUummgj&M~L4nS)tK0hivb3W;Xe%g@2ReTDH@!%Zd{ z2t)TbY6V1N|Bgo9N}VsCOZ7V#--pXna^x;*wam>xJ7%e?EmS+)s$c0xb|2-%?g2UB z+YVM`tQ(BuPb8ej82|?-a?m7ee77QGyH zrsea}T~3Y7Kp$=Ga3UVYuNBJpf+f(A-Ht{78tf7VlYGPq*RSBgK%T?iuGxt3es?vR zPdHU~dXRt{;BM1zL83$d|N~LGOXGnsdZi){({Dllw42 z6$?!&NR3Xxf;L5~*o;(y7cQD+H)SAnvLrn><1eMUJ?E1y0tJaK9r-XY>{| zxE|rx6FXz^;6%3_%%h_1qTl&ycb|6)z)zJ&oT(qGVVEX0$kx>!l3Pkz}F4 z@m6oXJ>Ee4omeAH6n}KCq#*<%sFS>{BQbrs1s7whlY+NoLAj{vM75bE^?QY^@Dtj`0#~En?4sPlIy%|mTRs@R`1J=`zZL=Z;mHoU%Z*HqK(Q@g;O)V zRwOYiUqLJzyU#Q<>U|rLCP9hlA`qSkRsH87ws}&$D7Dr?R}zmkmBVGR_)s)X1Ojb66yGNI}3P~yXX8_!wJC*PssA)M1SXP(46 zMY#lKzMU_8kNT7zWSRvFP4?HisX-%V`gp`hh*}?eQ_WHoW%H`j1KeIpAvPw}sl8VB zyoq1hTbj>jKFY0i+cAw;d|j;p1%hMq>#}0WYXP#|Dz9H-TIM6-DUZ`#li!iqJahY# zn(?~Blc&xI^bZ8;huFe6UywsvDIMyd0x#1DAOt@W&MPr+DZzoj+0m7qym-w<5s3s6 zu`@t4G~B-LJD=?VMHgX<+RFhN-Da>iX^}dzFtEbczE$gEe+cQz*!B*XDd1)}&I*c< zzI3KX2WA)c{yDS1r*q|e{F_aC@a(pL{&;1(fxqx{L)*!64S)PPA{h}(;N|^;2I%2% zNLNpTnf;YHMK(KlyXKRp!hHN$R)2j9lAHNpe<0)?a=Q+5Yb<`EHQ@w@*A81{H?_e8XXZ0bhqhn17y;sZh2X|kRpojPf6g^8rYX}Pk+3cO&77@Q;e{N zC4A6CPZW37;y65gO+4!*5~_+q6uTSLegLzbn=KC#lcIMkK!)bx#>Q;e`)=^F4K}aE zJn*n?I28?%bWd(VG}hH?H+P=j_Bgn=+3_ZnBjY0`3?lef|2jb^UMV8tHblYfif1Xy zoz{oy2zG>6eB5}e5Fv#;(I4Vs2+uy1oB*o4efmFcrtHZ*VHAswnhg|8L<+mH{@Y$* zicj|JjIPwf5D)`yH}u0P%fJcFG4Avpzu%T^V;^NVZ-+j@AsZzIH%F#!lzP&{=2p#5 zR_uYOMQsM=wuT(E70xh&k=Lfz{p%JN{0f5;Yv8LF9tW4T;Px}?P|M5w3yt3Gi5@8~ zVnupankg5=hr@rH`bF$3jH~v4PMrSjr>`5gyMV%o74gI#K!&$}&12$5T|F$B%9jry z=rpf~&kgS}8hbXl!Epjq^pwAic?5SmbM>=*ZmUotgr>Cg))}=Bsy&bI_nTNKpK<{S zacO}7u$G=grB6fBm|XFB)0Z(g$sPXhIj!SsJHW;wVEKK${gQJc7W6s+^By%dH-hr9#YApwqO2q~PQ1785t>O+R zw@;ykwC%bW;cw8nU@@BA`mDX?gw6AWH@ZHPQ<%Q3kv(CurZJERAU;fim`7)rGQiX| zCS*QS#%?yy+yA`ok6RWCkoZR`bM66IT`_b^!*zS}CVSDU0z28!BAQ4HPy#z-`|c`%zhhiRS68p9?ec zsd+?9C_sUy6h%^vI+H&ah^+h83RPhOQZxrMJn;-HpOwTqt(#5ZLeDv-aD7 z)mwKIZ&B2?H^yA$<`}(d)_XRZn+Flu1NtOBto0?eJuCq?-N_1cvQH(g!H$Pk<(H_? z@|@YyAXup2@y@a{;*Iq>Z|Ea6YAvi;0FY7(f!DMd3NIJ5qYH^?&QEW*?fhw~d34XJ zcWbgnrRbseM=yiF4*2lYL)X24im266Mk6ftCW$6xIeiR`>Gxe`;b87)!82nl3_DV%PF2 z8-VNB5_gsvK!|<9z>*uZE?8PbJoPk)Uy8oTaQBvJDr#FpaUUs3SeCM> z=e@{%VPk!}&Fre({(BjeH&@5-D~w<%a^$P)F{aT&7KZ zM2`kG_gC`^nI0)ws(8j5d`~_f97r6m3GmCUwCp9EJS3ubakMmLye~03Z!hfQ>1c_l zN3M28nj+>DYVrlk3Ic6ex}QIRib>*?egbpn=%9u4f4xm?4pDw2|B`Q20E^ymiwcVd zT?CcH3|a0cLFLc$Z}3IP z{1KjiFoN%Hk24eE=VFM$cnHK^pzOoO8NzTql%i|%)dl&t9SMm)c$jCo6e3fsu!@M%8F?gqFnkOw<)UawR(Chf@cPG4fuFy4@uey_5B)_@7V5zA7K z@~n&AFzUW2D1C2m(W>5H?}wd*cd71Y3f{OdYB?y^MN}qS*$nj)t5*&_Nt#381mfHh z3J5y8>U)q!dqIS}N=moZ*fk8Q4B(sjz;=X6W* zili8pPI&@D3z%%?8E&_xeqG47(O)`SoLOm~ATOjdO=C(Vl&LK{IE@o{teKU~uFqDP zkvwU71ezoqWsI+sl=E#`IVqPpHQqxR-W!a&F)%3A$-ukmi}JBjAIe%rM_536dVnh% z?)y`v*&8L`;7{p=vKr-Pkg#ZKd8FD-$_ducb98y3mn@b<8llRv8+$crNT+f%6_YIb zbhX|3zYaYo{AO?J=25}hZ2hW}o}0j)w@@sw96*(m*sp53Q0h;phV3~X4O;Fw|6xCD zQgA@be=WD0ib26}xi`vEiPwUu_q_iy>t&6ldxT56(zR0wlv3Si@W~Jx^KLEWd|`#h zJvdQlW(HfSBoWLOPciE<#ydPPHrJ&>N{D#&+*K;(v2WsH*k|iS{EBpX2mK zB#+N-4@F;BOT@A=L}D76in-$Zg1@xQ2@)bEg!t#=%+#IEh7wm^MKiq3uU?SKEu`#!ZW&Q14*zM2f=Hu7YLHTf59kyH za}C!enshz)ROwZ|AQ9yht2XlVy9U5odgK(XX^SD+gBfeqt{k-0_pg8(x-nkAv1g8! zycECmWZqYQ9&Xem=EK*;S5Q10)g(!YY0X66oeox{yobXZA@I2evYx8)JmOOgZwF8% z@iBN`BQiCxJjziySuAtTZ<6t{pO&)!Sbe~&8Wl&Dze3d{UH2E2`ds`)g5m6X% z_;8~`U;yO~W~==W7Q}`letS1%bBH;#T%j)yDi;YvXnA_h@apTWy&Ylr<=#G^WuPz2 zK;fX$=(0rI!EsJaGiBa+)U*yPyLY$9Vevrsmm+3|m43vh3N9NI7y^Y`oiUv}lDZyU zEZnGDrL%=FPPiS|S4ms21`(9A849P^N_+kSP{T0wH;j_K zR9c#w4HOrAM;XxvnkTZ>XY#uLHm*Z(!fN245v1(G+WE9m(a$mGD)NM7KXx!kUF%{0 zs6{N16%(jFdmN+IK3hd*H=WD>6HYX(R;>1xJ6UO*w(ueZ`fMKB4u53y-v2DG%-tu1 zux0b}9aLgtWJ?B?XZL5Cri^&Mt*rzC6+q%mBims@DwE3IR-f({;%u^&zv>jTKVJTe z{1lHna@YQ}ASeVwH#SN_D}VAO%@v=x=#z^jfv-gxJGSwvKAS@NXrLoDO)^3HU}%)3 zG@0KxK9Bpw=|_B4Lr9?6hLyoameE-LyM$Cq%awgBUHEzgv$Rx{)z6lNHnnoVo}Hte zm@Zv%V_(5FrwdHt%>lRRkzro3J}TYmnf07-KV!=FIZAP@F0a#w-@@&6>cw|RWXkN6 zJJtm)gx|#(E}Z^qcMO@*GFL0UtkP*cM&$jUSJEoPOreUE?N5)8d)m%In~OR=uGN|+ zg?Y8|TvN~ENMN$C{K=BPDj?I%j=EH`POB0i#gmv>o$Q@+i!}4ASLvcsB=$$;)CCJl z66NeuD6sj}x`f3oQt&)OhLg5emt|zA)bvtdpz?DHLXe0x7qUjNhu1Tg2h)*=%P&4O zs(g%CAsq@Bl>kLJlQLbA@-!-?MMwYR1t`+PjXQm`LZWy@=_xl9`9(lXLW84yYE@9A zcshb81~cJ|mi=cec-88ty0}~12<~rt5_YrAQTnT1y(fuj`2)~J$CvIK==_haerfy6 z`ebaMg-Ye^6C?-a777(`Gd=nglpOxc&4QG`Ja4%u>$n`4uQ$JHz4ohO*u11W0gUEQbPH@L6i}wVHQpVM2ApJM`Z9dL);lk z@IDW^Zm*zTo)mbhC~|=Ik@kz*7wGvUT=J54AOh@jr{GR-+MSA_*&57EvIVi(l~`PB>eB#WjjcRd^HFQJOLQm~n83VoMjYUDczfFHoyONlGUmSS zCx=I<+Z-&{#@|ZCRJ}D3)}b+<@_}$JcQME|sm#vqP0tzJDDWJMzVEQBt8Vu~?gM2% zy$h@bwxKmOSWY*-J3V@BaL}Cg!51cn5ahe~y&5n!n8?Kzw|4-IjtjUKvN}@(tMUyG zY9104wz+^Ky9H$vK!E!9y=);JH4p-1JhSi0qP=;M=kW$`HA)aDV&iPV8=1=K0W4~nM^wBa- z2-)x3|E&i9W1rZ?e>eh@AKoA9lTm+~k6m$ilMvIVu4OK${j8`y zVd290{x_*87pt!s3zz1U+iUTY50|ph`C-BDpD$J2Y=!FSS3%~k8UfQ@e&dSS694hU zOrmfA5oLo9>SzMD=t3Uz^wgIW z)BoNJ6}_>q57Nx@6U+aY&W`?&GMe;v32SMqVU$(()ukR0NLk48Ay2c?R}!lFWdS-yz4 ze&UhlLuK0QpUXRuXM^OGRh=n!uDyrp-=UEM3=>_9@RsTb${T+Sd3hmU{c^ zAj=!EBPZiez0F=pS-rMUqbXnd7BwN7mcVUDIt)*<8XK=JGNYciZUX~#p{bSu3ztmD zVt8F&zlzE)OxfS)!R3&0cAjSSW@;)~;@l8>9cG<6&BI!T0H|L zI_JB^ub`?fPeFn)gZ)#Fw_o8280?XUL(^Kc~Xl?iOCvsT(K6B=ZFj)UX-0qKe4Sk8pSYK5PLj9v0C&Z`v-akY?YvY z@9rqWyjQZkwPy~j+2F|+>h@PRh31_-LN7U!!%WV*sVC2NoBZ5M^i^6?!|q{S%S!E^`?NXWP;p3c>?cgSS<XI2sKb94=QEL}AzEy1?wa$ci+(;HAXA6qrTW= z((h(Kk_jkKo2SQ5bHA+ZEr)Lt&#+!_#5VPyp+OOfebq!)0#A( zU9T;m3!m!myr96l!~)2gR^-pd{RXV7PO{Qls5S9|Jsd9Y@F zM_&>QR~V+P>(KCXqMMa83fn^^Vq(OZ9!<1lSqSb)b(podW{iiliC`Hm7%bE;$xt29 zH^suZdacTbzbKh}j));#$1@wdsnQZ@`toM>Y$<-&0EF8-kXhbYDBR`iVF(gu-#o7x zMjami`P-*bg&yGSBI^If+g9A+O!g-1S=|2O#w1<}<4=qBsvKCMCSFmuJy!yQRTvmF zm4rk8$dfXmfZefEjZv21ufp3TaBJ^=XnHxYerwqLaUvr6CM@3D)pP?Brr(_F4L^7$ zbnaI`Tn4u=C>Rv{R_M5rB|j{IHCi`yxpeD|Rpj7hPX4-@7J{(`98WiXfT#_8?a{m( zqDQ2AC(bZrAYlj1B02sBPH?g8Kvq}eP2v+{;oQKj`49<4(}U}T?k$EwJ=Bn9qcBDC zFEY~SUa<;VA&p8JQm+N@?lLY0`+tJk00&Kd3foA5Z!n5ot-AAO%s6WK%0fL_Sh;_U zxs*I8*eTC~yA!_`6G%3+nFM1&$Dyoeh&)hJ;ISh}i_mku^MEt64P9iOxE~Z!;va#R z1_O({5xL)hv82;OX25-FWjVusU54ygWJ43|Z`lSi=qKZSvdW27m_Cw+u`)Ej8no~B9jO%A&_}oCEP66Z?^qr`@^ODkOhlof`(w9l*%XAQw>i0%d z{kSQBYDfd=%Ux+o@ktG5Zyo^Y$m5LUdfLITyJc=^2fSk0$~{0@AK{`k^9OF zEsVSvUDLgI?ZCI{1EXA7&ycNfq;93+`5S}yW$m^a=)gpGHJBwmY*mi6fE>}-!gqvR z&QvsUZ9GW}%B+7(w@D!pl+;|*(Eguz7?=h?4-WB^8FH}9QO4g6He5*+ ztB^8WvO}Yt8z=eH!QDBHp)HcbpV5KxQ$u*wHZisJPQs&K=eI8`HPmcbn4wV3XfvAZ z1xB4Q_dPrK#-RJGqZpj3Qr1CUm*t=I4&D3e|fKTzo}XE0KX*D0$nz-q}}bK;c(!_ z+%Tcr)4jUy5>t_}pGLDc+5GCiD(O~78#Y`wEvTE?fW&WX9+(V+6c!dH*xR!nl*&F~ z&&P%mkrwT6?HSyo@vQT`R;~Q7$8*_4PThh2&fOr3PkO-gpr0=cjW6M)N@i8Kvm$wM z%T9mhJx{hPO4byRD9cM$G5}vPo1_?lov=VUZ9~!B{y^pG*_ShwVo9dtvEGcR*Y3K? zbp3iAj6S_!2QT98k*( zV8tKLs&hz56rV1-8(s>((5%4Fsbp3z|55EIhuQ;G?^V&J>3y7$MhBti)902)11Ntb zp-`S#YoDs+5q5Ynr@q@5PthHZkR=|>M^dp<7IJr8{)m1wCkI-|*EQ0Rabmmj5xB<_XqGS>oGyl_kB)#sZ2Aj9ck z^-ai`q!`KF9Ro$Hk4;8kCC5AkQ`rwbkrnQOFUOkqFIqz&hpE9``B1ybJ zeB{uSQvWEv)9&|I!RS8-LMjaKmSZqDtMDb?JNpuzbJuUy+ zY(+HlEFt}{NFrejvD=VU3qdy$GWVMh4UYuj;MO)(5aG)=Ov&xPJ?H-yJNo}G4<&D6 zzdv7pll>%&0rCVE%hjK;hso9eFhB42r%$0F1W*BT3|r}+GF|t}UJiNaP0C7-FW=MU zI#~?#Zgir()mP#mMkxWLAa6K;5;7o8j>r!xfZ!kzGWS0!{(~lvvTS(YWSE_HtZ83r z5W@;bIg<8;*NmYmXp}FH0LI?+&R*HLTT)vqSoZYxzOA+8Pf{$r1!A^m;pE^T7+-%$ z{~l1bBW2hf!jmz8i0cd8(Go&{JkZA2T0uO1d3Qx#} zvom{z&Sz>Kt?OcB+V7j1Ej7FjyUI{%pe}lyrJ%-MMwX#`=^yF_6~*)M2`be7f*rs{ z4Q(jGV+}6PJzx0kmO1pyxW0d`mvn9{J^j~!^*ef2R0T-LHyym%H_D-lt5@SK^7O9^ zJyYZzniH>YWKUZablS%OQuD;$Ai8d?@O%3pxrS6$ec-(x<0GF1w9nN={8I%@+3rD! ztmn2Jk{(#g08U3=T9Yvlup3aM82q3oAyQ{QSwVR*!5sbWhpY9Bg#+bQM%^#IREGV9 zOalz8IkX5Ph#Lh8RLZEesQpb?x23ybzFWr{UiI^N6qQN-o&kA$3-iJlF);`8&XY)I_E7ddqb$r9Exq>YUMZ9io$vb_qu`9L9NvN%_C0vFhpW#EA zzEcZFaP*Iy7@xX-zKw#7J$|{~a&P?pbh+PZzn}fRdkWP&>)(5yT0cW@#S~W<@9N?` ze%17GTDmNMeKM`N*>hOUHT(cya(y6IIW*+uajQk%1}HW3qt$!4n*Nfa6fMlsq0 z29p(a%7kK?7Rt(6>vYvhs`8q z4CF$0>$muvUD$v(&5EIdRf>#3J9{{46W&D+)#K{6V)IjBVl!unHWRuu*02%IVU0l^ zyekujQQ(0$&Ot%mb*&IxN-DAWK@q;i>@Z1Cq)kT7=VF}2zee9^?pu5Na%wJnYe`YZ zjl(%syoc+i>}Tl-#cK1;K`&3Va|*-5omZx)&?4{Kvh=)Z2}7S`=a-(l}Y_3VcCbGi=HLLF$v;YS6nZug)| zb88Lj#pqOoBQ{2Se00rUhm=aMjDHn+nsbwzDSJMd3hMS+^D?kmNO*T8e*Z1mr`oI- zIoiH{B#S48#eo7NARqt?eP|mHA~N*Ai*A|})SdLI5SLcv$+kv-M2Z$@eCDlSN&!T* zxmv*>rndN<%Hd>bRp~eRLaq7W_&?w9_w@x?-T&4Y_`Ii^@tMQ+6Xgh+p95q*V2RDO z=X@sb6}5|Cxg(2`m$wJ7G@RKFPv&1fp9@;;-hZLEOx5-oeY82U4tp`fYS9w&n^q0Z zca+q*c#*+qBZ2|PT~muabK=sQ>#!SEK^4@>0MmZ*B6ndw_eXd-R3A#Ny)vx9>Vyd` z!`jiRppk6&LC6uWlsj5j@*5b5J`|aW!)@JASwRnUIj%5Pk#S1%!YcWkBYA^!xd!jf zZIa2awD&69gD%6>^u9E+%-ZkD9B5;Mb-vjQKF(L%h=lP`*RKit1eK0hlqz2B%Sw+? zol?=mO7Agq8V)4O7CGn~tQ85AIz$$=80-1Am?ouS~awP2x+ zIc6zl_s|{1jjQ)vynN+P`N{raSNvl8mbk6Ds2Gs2m8Evq?9VJrYYYKTLU^j~xaOR$ zcltQ$_P73^PG<}%rCEm32oyCev1IiLOnN`y5N?HBdp+c%h{rnnz<<+@siAbOdjpc;%syz#m@o`U)2gxr@hFIOn? zHHtZbdF$W;Ts4Up)>5`Zz;S6vlI(tK1AGBk`4#@)s`UrHkD5)iRn0f&j}p(v-Nd!n zYVXh1lq*sBr(-F(Z)WDScfMg_*)TPR(j^0uMM7@)i>rlVdhUjqKDZvH#i~v-eb%7l)qmNHW<@ zmkU*ixIev{Bg1Dy9fw;ht!~Lly_53Y4pTvhsG9$|IHJl_6p{-Dm23w*X*!<2YNX-} z&CqT=TsDQzGL9xSc|8Z?kyDI>+Dj_YS>OV%)^ERCDNOt|hOj!wdWgwp@S>Ko#L=)E ztl4lmU>=CA-cOC*EPHZ`wJbPXwxXN!`Y~yC&VhLMCtp^ULY)kn=e@fTeW190Z-g3C z)2N&8XYiC}VegVAjP|P0`o+66(~GgAX5NcmBZ9#SLNGofZfh|{n4h1H2C;t(6!;Grr= z#4Ye)Rvu9bG2@qs8ZgYJr30k85Eg2cdYz0}vEGyT3%-=<-es?lMI{g;XKLCZDy_A5 zbOzxUdHDjAfxXiG1}j6n94n+$g{my*K;bWf0I2%io=9ZZ2U`VGb_tk zE0!I%lU%M0C610>Ui1{!Af&&~)>H=B7lmS7sRncta=n~z##3+wleGEG#j8)aEg3>Q zE=6+`pJvRRYN@tRl;qNK?d=1Fj%)?*ct0M-@yVAQ0a$A$D!-AhtT4htvRZOq;4|nO zf*n2J<%d7H;0d(U_}B4hn!e=`u_s7F0catVDx^aA=Q*Dro)*tzm^k8$D_wJU0SKJt^DJ8po z(VtHv(z7~pC7K){%h#ZCrtthDVwa3gr^srSbywpH?613l$`krdHj7y)!IQ#j$h8^5JX`7KG96@c4_OC`aQOK6r13e2+OH^8HmaQg|9<5gdlMNruk# zYAGemx%?eyOL8@41uG=pQ&+9P2?Poj3ya9c<9-H+!T_MyRnNm?`94u{cs;!X{G*`` zHFb-=0hN4M5fWV%1M5y;9Y=6t^AT0_&*dEN&8&KTna>dV2I|b2*uDX6G*Jh zenrCVPK>35rQZUP;<>#ZvwfSBcWLgecg4HmID@3tZ1wHmC(29YiLRcZ>anv(uXW&@ z=SvnSmCR{O)Tbk~mBXJoZ^k6dyBZkxApQIBte!3PFR>5vebOTDTU*C=af=F#J>V{i z7ljQaGL~)ktS{WAOQ@qUswf12BH8Kx3mwz4sgDgu5P z>F#*6h`?2V8%3PyV#FW> zq2JyPnh_e!Efl<+8){&eS0UG|hN&d!b#tIN!t=>osxX4u+i&Pr-V2UcT^mpZqJKr2 z(vj#m>H9;SD;0o}O|G>BD~WJB%P8sk4XP)T=JyMkcVuVl^G4vFs4Zre@e3&14QziO z%+vl*le`^WQP8Io{`{E-yus4ak+^z;-Y)^w;^`CP+Vv{P_54LJOG?+>G^h^%2xrG` z$4r&>>+e4JUh8--EuP|n+u7dOz(&#y=p+$ElnBz7z*IhonvGk>GLIc)zX%UT2NJhG54Vn=_qA6-JUHTh@t?7e6IA1I1x%X{|2v5hS0G%-j*6di zS637#xHS&^)c}6`EQibl@md;*7u!OyUs-4(CJyO?o}SIc#2lU zs!z6)XMByM83^;JRsCg?J<2j*8M=B3yWZz6rvpwIHAn_{6UF7p&qPeD2(W-BQE>F$hl6BKtDbKL-0&v2MRW zh;mz98jgyXymA%z$h{-sGXMZg`9J>!7@9HX@zAQl69-?h5^WuO-rbJA#4Ao^u`JWOQ)M83c5YWU z3O34)$?-QnZf4<<1_b|;1C7*Xgbp6JKOF^mDHMF**n>w|sbzPfIGhJO+e%94EH2f4 z@4=uFg9jzJPgv-|0cZ6yab1hBh1tz+*HN4*J65M8g5K!B(~VLZo>^NokQUmPM=eN# z$A+m@zT=f)klPhz_-B-d0`2~S26`@Qui=uAb43&HBNo#BXYQLV$W{&y6pO9qj_WOC z`c9EAMMoVrhk|J30+-#c*Z&GM1k3w9TA)Qj_B^EiUt1=vs4QNM53a}IK64P%4WHxV zP5IdTWi;kbOM(Iw0+YvMwDJq&=d6WcaTa{szj`1LDzA(IxUPJGqg6Gi zIsQ-lt#CcwtqjM)EpOm4W2Xzo*8kvN`@cfq{dU~*&7*_o@!m_nLB+QgVRd2?D$2^* zpO7#p@?Jy^lAuqYhneOH`2B)Kh+mtH*sCR2k^cz{nSa6eLscG(0o3g%z*}dABPqrR zU&mLdD0vfkJ7tV{WfCGK71X9^#F#pNZk5nWD##`)qKv)(Y#9IWV66SaQY=fz!;JU< z)PMFTEPv-LOw%60y$T==nTntOFb|op&c*XlYmhnY9R9p?9Zp8i!G<&);OTnxNQ2}j zvyreV4@>8bf&UUaRQp~=?gui`H%`Y0wF=Ud#du;>2J)YH24OFJ7y6^?v84D09)5ie zM%_k}Wxw&bh(xlrZWmvgoWLOg3e}1~2gl9gA8T7lwy^fYmCUr88KhOH4KmX{eI-Av z?bzz=DBP&%7ZFRV!H*hkFh`7=!;PPIwEehmV{%=7#|);tt`_wbOgu#Y&$RZ z+AHMZ<$bU5$D<<{=p$414P(rtbu4%GUPNl!td+++qfs$ zSh0o6rrBu;^`)#<=o=ErgzqfpE_ZDqT{wCCcQa^@3ZtJQQPKp^WE;=9zdgu~m)>fv z9jABj#VJV~9;BsOB~jK5qRE=X35&M!jGH2oCx6S$*QgD&#zkt=n!#Eh`iCcR`YU^H9%EgH8hAyd+e)B)cZ(iRVL<4X zbbHVrK`IEI=#SXE8%~nD<0Wi)G8Hd;(&F}M<^JbUQuH{6^w$>3K%bu=2wrh_CQvw0 zfA%D*s@xZoG{!4#+M@2Hfj&P$5WL|IB~X84ZEHrBw}w+0kzH~f+1?t@+XnjlzCli0 zh2xG@{XGpqxa)|ENI?*UKI-)hRNUTJa7V<2Ab5~K#jTA6cSKwWLJtWvB_-vK-d|Y| z1mSKY_CN(e5c)_YP(cucJ`xF35Cox*L;@8ALFglqKm|b%`sjZM)<)5;rm?920000< KMNUMnLSTZNm!rV| literal 0 HcmV?d00001 diff --git a/localization/autoware_ekf_localizer/media/ekf_dynamics.png b/localization/autoware_ekf_localizer/media/ekf_dynamics.png new file mode 100644 index 0000000000000000000000000000000000000000..63c81261a718e8c4dcc4e9ed6283aa6e9a2bf56d GIT binary patch literal 5346 zcma)AcT^MWw?*k79g$u`2)$l98E+h!jy9E$IdM5-$dK08X ziGXwv5CJLiMepyub?^Jj(vXml&_N7!%}GcubCHl- zav>uno_Y9Wg_5|FF*CN*`}OM=@$mouk^WTtkjQ2THiue}=(c|waTToklyhH>(K69# zn)M11qV_km4k96;@B96|^hBJV7?@Q9qN{Bgn!i&J<;~q6(!ch;UFe(A6zEknf#0HC z)C?ftGw_0jL!+&dhdfoML@|kAf#XozWEBnb!~uLWj@IQ83yNi|u~g>&%9U^#_+omgC_Xfp2< zM-5*oV(R4oy7685BDEP56}-?}ebKqtWTy_di4Y8a7q7G25vp;_HnbgS!P3y>2tO8B0F3D`R$B~@UDbjo*zD@ zg8l~jen*m_k`F`r4}TD3=7!GJgnd}Ny~G{s*OIAlvd@&x6jQ>4eP(RHP~R%Mc`a$r z+U*yf`%-_O+xu^Q?^a`^6VuvL2_NSp%WmaxCTzqFzAItsb z;;Rve(s<+l_~W_QNe=e7_T1Uv6!>7x)-^4vkdHP3YunmEpTebuh}dkCZGoOwTqNR@$bS@ zB>luo2U;aQy;bdq^Ezs@q+T7Tu@Ao80PObOdzi`A5EI~U;Kqw>kTEx!p7Ys#;c*@r zIii_A>Ns^u<(Ds%+|neU&C~oS@!sxES4F41*6|RVrf)}H4$`irZ&NMFJy5Eir8)w` z{!Su)VH5n;w2rMw&MNYLv0ySj?W^^bsqv~_3$QmcPSNvQ=9I;`S&b?5VSLt!ORf#{&0(1^AouR)KaqaHSR)l**a z^GIio%9jexnb8knXA*9^D8Y6`_+iiMWt*lRA47H8q2o8~sMP4z%Y5wUn?I2@XYqrp z)&p|Vq9;u9y9i~ir-dBpL*01cd(p%5lOKw|W)V8_uBpUiry7|=Qd~Gg8y5BaIjZcN z^g^J9mS-U87FPEDQu+ptI=oCaPsOb*7t7j)A2*#*AW4S%{nmtLSH%ICQU6f*mG)cr z4y81v@BADlsR+LgweV{_n*tSCjCm~l`uH|kFT?1I+)kTh`zZC30K;l+rr+2DR7N(t)DCB&xAxaIIn`-c3o7ESYPI@| z{Z3~7IovzCq`rE&p(%R$jjN9<+V#1gjcR8v&!p~|R~CcZDwV>j%)-&98`n!JjRJF3 z%IZ@%ocrmH_#8Nqrm~q!lW~pG^YvT#WueNZvTNSy$B=*O}OHK7@SN-Lo-~ zALgRCi6Fap?dbz15Q9(9p`3U(L8aOD037{e;+D!t$1^u^5jKPjv}aGSFsku+-^0As zL-&!IULLcltKQ8sJwCpXq-VMj@fz=i_GipxmWH*TcQe#aNqoA~`DK${SUJ@#;B6?P zKxGkqEngA7Qd>b7FI+8kZ}7{~lOOPZtxh2#ydK$Uea?uxiTIk!J*`s0dDz5M4f4W! zd^VqvlHCVwJjVgM3HMI$Zx>l(S)_tPpGOs|arE$fHBfr%oG|4-{d6D#RMy&7mY{=^ zeVEHN+a!N&R<7$3L)g4YZB$}TK~(NXe_E}qQdN;ma(MO5EGhPdZ7jShyaaCCaO*tK z*LvA+WOG`z$wvKc*VboiZqdE@ZS9-IsdYz_LDlEl#Abx8y(+8qFb%p=@bsSJ@+|7( z(V-LyW1g5(h4BjXMbDL~idZ5>-za-ATzTnMVu_yD^(Z`kMlG9$DL!Ltxj_5NhMDkj z{YsxYrPeyHQ-be>fC47|H^D6G7;tu5s^YbP@hzCvO{32n2)PK>U<@DjN&+X`G{KXh)u0qg7cLtt( z3Y`c&Z{$g^IJF;rxA+|!g<0T@pS+V68I#xM3^M*ca4W;+D>j4 zZS@HDlp{PFc6OV05E*NpTeGrLrPlwVGOjwhzcb>cxfTQVIB!X?R!!fpN5*a^Y_KB# znc7s-bD^}Gx2Ua2xfbnP(QC0rZcWuly6v=?klQ#{=>b2@O;HoL;tHfsrBYBpw3cu& zP2v#ekuT<(RMoTVK3tEZKZ`$Kr7fHccC(GFT;aZzk<6N=a{WaxER^_$5xA~-qu>*i9uF9Tc7c}b!rP%jIKPD9UhS5qq zS9xU99$j{q^zmp|vQXWkHM5S<{--3l zTD#m>XHF(+VB)BGS%@#8M<0Ch4$mLEr}&bEOq=mvTZXUUU>^-6#}LheUcAgMH@_$vgbR37 zZd~f$e+ea**uz5!83bI0a|1+KzU?v&3jaEI=cAtY(~n@9-MKdnjAVSANgcSpPE#IS zx+OU@+QL=Wt`le1w08TB)CRt$wCUMjW8o*(xJp)ZCbj;l_a(wdHCr@?L*Hr|u9LB? zbPlL&(YhjpPrDX2Z@{;P)sz}_&XCjoJSXW}*99!=vmSMM#FVE7bzVoga-EobWfq_@ z8~5Gd^eVS1H%@PVuY3$1(AwRjIO|k<(HcT=|x#wyb(Uv8$Rph(I@h$uv9Sd%<<^2 zZ<4DtytH*{AHa_<*_#aOmEy-W&tr3#2#G0xOK>uPFbxngh zKma6%eL~l^iat?Gg$2R%_PzM!B`Gf>cZ=3Of68!$BvL(FbKuhxh`U^#A`f#^Adp5# z^(cfg-gTL!X*@m<(yg|Hl5;$*HGlM@vRr4$&#SmMA?*`SsXnjM(Rf>6Vys$ieaD44 z&=}63$PGdE73C-Xhw!-;K`iU^6H|63HH#`$=@&y)0AaEo(zeqI{8u zn4!$YOOnxW6n$d%XsJx8Gu(hwtVIq+>m!zZ*e*ouNCCZsdG;6njr5ZsWH0fJlAW`{ zx4OjSD=HG+Cjcvze?YEI&XE;tc;2exsQV=i;?6Ux^bb5Jjp3EFBT^y6@O&^wnX}FT zPKh&Q6(}<&CZMZanzR+q+4d*Q@XY2hffJ<|Vi-P@qs&p~1UG=FS%Wn=L>o$M5AYZB zZjqPL-~@@Yx3HaMmVLttE6(iOKN5(SoRH$+5s4?Yb4q(j^ zJVMDtw$e`mk%I}27)L!xxi!}L#MyG=XRmwb>Eey8k$u@}mioar)_9yn!M~lTae#d6 zzTS+$zOY-VoE+6yi8ETRbq64xeCGC>ou4@Pp1%W`W;D2R`12sUfPledM>7Qh*vp>tEPFGMtf6QfKrv}0<158Ha%8gx!Gs;gD^RJD$H;RwYKCTFc zhyaql;Xqn*bRJk_aEv%M+XVFS&Ya8a>$nI*kruh|xwz~a*{0o&i2?bpau!<-ly|RY zQ2lC@FU7lTB3}n(A~S#~M0H69Ywimd;C(%m-%tZ3PwwcSNnI;CK|}pvhHt3PHgxnp za5qSW<4sjDPXq>l>h1V8XeuERi8i~Cj0*Ve-;>qVx+<%gg>(~0&hnAtCi!5i63xfMg^R=Bm zZ=xb4mISN@lP(#lYI6us$K7(j9u5%!2?3&s8bG4R2PV{YDg*_K{Ur4!6@)(y9GggN z$#o_tq5nCIkCTSP#4@z%2zt=a=>Um8|9Wcu{SeC#JTNU%Mv-w*mmIp~X7i0dSnvVF zL&?raOKUS2=LH(oO5bEK#!>a``2b=&JcELV6`8?M;X&s5)HoUDXctpfqHQRQe(w#4 zYot1S_1jBTDT%iGGj|t}aXe%338}N`qUR_i;BHg3XM}X6OxLyMP0R=qbM^I1) zBFU(48>Tyu|F8Fkf0!Ff;}cgSZRwjG)tQAL{BS?V$8|KmrF=CRy8dl8xR?SP-f3X| zRnBluhzz`5cJ}&W>$+r1Jvi1>Xh2vVtM7<)JGw!-iunZP|FS915)JUnbi&_#X$zi&^PjYkvgAlMGh5wjrwk zwo&5nD04tWg?C&w(EiNe5)8)B^TC6CDk%UKq;SXu(YOgx;O0+^2eER}r|asl($G;F zmI}}y;zO2N`*~4{N6C@C0nF{a%i0gL*!hjtYsCJYFF*k3s&{kw{Z7in@oq*NMoz28^3Bp! zkK-qxlLPj$ru7yAtem**@`NQ;ZY?@wh6%BCm=S2w``+rOn8`F~Epfbk@0;ts8e+JW z570K@C$2_$1*`#_^g^Ju!@t;wwG!DUOx*9*zJ#jLmW<~L?0(L9n)e(VNhF*Gx2Zmg$A$A+IU7n_6^KE%(pjE^{ltaG+GY4%;)Ga9)gL?j- ryU|P00BXQ{9_I3K{($eI3g=p#){#rCKmoDee^WyApt?0+hnW8YJM!+Q literal 0 HcmV?d00001 diff --git a/localization/autoware_ekf_localizer/media/ekf_flowchart.png b/localization/autoware_ekf_localizer/media/ekf_flowchart.png new file mode 100644 index 0000000000000000000000000000000000000000..0a80cb06b85f00cce2b295834a9c2fe94c727f2b GIT binary patch literal 146302 zcmeFZcT|&0*e@ElTSbwwML?yAQj{vvK|n!7ML?H9@IT zLk$pmmrz1)A<3D*{=Re1z5m>G&$;WYv(`6@CGpL??>qC%(|*5shTxaV3KW-aT!KI# z6wjVMeg%PC{2Kx}e}U{TaHTrlK@9vl>n!{1H5nP%*o?|F`0sTWc}*8Jdovd|Lnl*+ zxt+bODX+7!lc}klvxU72_H2VR1acGd?D3=5?un}tzTPM({D3$tCRZ%btE4~~(P5@( zV|D-A^=l4^ZQ&1HojTPhr83oUSF+eGIN4X!EUGTAGDfc^L{810{ocCz_+g9VRl24w zijHp_o{ob?=R3|_t{!Yb`05&`+uWmeFW+C^Pw=fTV!`ew(~H(jv@&}&OlsNM+MWR; z1#LD*W$^6j$De7p0#C0}>lj@-y;jQpUzh$%5+n)ymrnejZwd|;6(|)cUT)Cxu^VH_ z>+6rY_mzIPcaU0ckrK;Sf#f)GF6Y)q8oYK=cg%sOgLqyMxO`#(ej`_!AP_Rc<;o97 zW~QJ~+2=Gr*@j&?hHh16;-I&$GCgBx3W;D%5LmO zVP@t+nCRq3PdebUmRSfhEKbg(w!OWbk$i4em`w1c8lO}fCEj%qkhG2#fLrXn>o zGE!~U9WOfNEr@Z1K>o-pi!XdFD=V963ZlAxpAE+ zr0%hDp2&3v)!Ic9wryW$b-bZ=VPR>fyQ7`uwS-fn`qa1KZ|J$-sH5C$lK4z_nP6iB zaprUe!uPZg=~2cg#k_ zi^RQ$K6y}kPD_1p?2nba9)4>U4)ceET=VdFhlL6)#YnGQpJgbt+#a5nmySo?)f)!|L(M0=)rbD{hszwRb@mh=joWU+><8MxFV9ML=D2@@waTjus_u zdSp_S#a?91kbIES*Tt5BJZn3hy}gZrNGtuZk@_E{c7(3$OB46qCU-&_?UH!1@x}p4 zxk}5>%3*yW$Gri2pMsrMlevEI<59k(QtWdO^Tor9ajIWz#hE6%+Y$}`nW^)tJ$ofe zWtboKc5#P1s|)6Ebl^rAWp~`uoR?rdh3e2A$Xzrsb}n<&T3fZB5+Ur>I5$+c(c38T zArAB6v4g@`=A~EN?dsqMTDjl-&9SAR#!Wqz?XQU{%YiIOZ2k7(QVQ0cd{3J(Vcd^Lv-(ALFf$p)2HL*+Sip~RNHO{d@nc8wk zaUN0jIXO9nqdFlS%)$$OZFz2NOL}fYtLC!5`3mZd*XIpc{i)AWPARlm+Sael=8e6{ zk|Rs=b!=gerZr^`@DNWk^(iYY+WXR?l-pas`XkSmrNU@)KGM!RD&hC~NAF$1;zR-5 z@=Hy9En&OY?d=|{(Kfmg_Urv768?*s16;*Cx~e*A^|)WlS#i;{YOz_eWUQ)UTam%) z8A0^)Y_gq4Sw}6-OFVW~&qVp*g;u(reP!2a>!5{$8N%wKLmWDCzk9gFi}SYLm(4aF zC!&;A43tH9@(cB1USvmw+UFJAwa|4qT=)IlT{)a6v-u9Z_OqU*>t=IaAA1YuLeOic z?zzyV?qbC(wXl7qf{|+DmL}mA#4l{}QnHubVpp8b51aM}UF&1}jgBly4t))KQkWcz z3uhsz`@fMgd@{spwe$28{KU5hE}BCdgAt3}qt!F^to}@ru3g^*GV=2B%F6Cz1XwAL zb*@AFe4hG$rev)&LC?pEs(UY#)>OT@>gr8@*m5_jLC|oJ0-8(xN^y}_Q$w)Eg5SJ@ z`_MuDnMEEpMclL})sU8U32GfUm?3C(EX^cK=0Q6U%Uf$Yvc6{1QL$q7CP@^!+4@;q z#Ah)w9>3;GukBe05m>yOby1v)_phI13c#%zHYr?Y zkT&|&v>nT%eNEQF+8VbR;d|W5VDF7lO9}B5`m=fJLDA7B{VS0(vs%s#2%U@Mtp1PN zzu#5oG@a}#Nq4lbs`nI)>^5}w(0Zn7xXG@Tb=k{&<$0ojX~#kf@S5m)i}nz_B$O-q znyAlu>{O|sq5fzrHbq+EA6c@(_8MophTUJ;t}4S+c3^B5Y<%+m)Oo8 z6f%FZ)~d(SU;Xv2$Z>bE;fF7YReu{yVgK|^EK=*R>)EtPDomUpV_JFvx?o1N#J8zeK+ z-wr!RAPe;vWXTMlb`N$+PWj)*M#k?k*SKz`t0y4>s>VH*l5$_;h_{7@U*y%#NBJBb znEwMD{^$MydAI27Ti~;U678Vv(m&|jQDV~hgKc=NhPp}+jOy7pk8?b-FrXxqjYHuR1rQwxm9+7t~iJr9V zN1O?D(8)PhMg z|63~F3t*mJ-r%T^(7J;~fxa*u7beEstQO}*6koo*g?5yUa;A3wj2`yVw>w-D&Yg{} zoU~LOlwpOe6-5R_C$a!me-|g)``bpFpJ(0dv<_nGXVYh?<7LU(p(_KdY_eo&-xsqw zMu&jGvDP?Xa%Qz?={3R|-g>v3%jmdN7k_hNM;8~XXk(Ko$r(LxIOfWxgXZs1l&<0s zyyJzgab8N7552!ab(tIIzQEqs1JIk7W5;xQeo@>GT+1zhny^>ZfIk{;kjB=pPdHs4 z`2a%6!~J=-+B*V43bo7ctT`uz>Po%nU#|td3pmt+56XOrC1YiheVYBlEctn%JWe84~$>8oSWl({pJm< z`e03q2X1MMgW7eIXX{luOr@ClI9q9W%_Swf&jzoJRRvLpOJH*HiwQ7a|Xn> zuf7{{rn}rX7+@^2IfaExQl2iZKUkKV-jyibfn`9jc_r)mydovR>n05xvkdzZQG_ZoW8dEzPd`^hCjnsD(YM58A!rfADqU^|o z%b)sH{-P3t!PEx6jZRl}9JW!!ud%lq7+Cxjx-D3m&6(o8#qWElXojB=AYNVOfk1lo zdiZxsQC4QKBX$3*VRbhl|_|@kfE^ z>q843q|CGczKkASiw#k$EmAE>aP2PoIYS|G@jk@pn@s{jp6G{W( z3pMB1wsL!r@LQP)*c^Pc;5-BI!*9JSM;nh=7sG#eY%f{_y<>h(0tioIm9c1-5?|Po zp{4QKc)*4D5RsxBui9;mS1KYxrbe2oTFXV9b^32w_V+m`>s5$a@{bJt)PG)to!=dtO~~$Eu`rbE*R%5) z$wjq#$mFaPun8l5OdJ;v8@IVSTqkTq1!~Lk?)XzTwxUO!Ba@QLJP4~TaURNfdD6u` zIxV$2NPecTQO;XAmJQ2gI+-GsOO?ljwXyqwRO;%K?e%X&S9)4|B3_6p%h$`z5a? zOO=T^LkF=-J=%wR%wLsJllNe=XC=904Ade$ke%)GFg>;*nNkA6y4YtvDTnj=)dkJp(Ofdv}S8$bC(RIbwx}qM#UxNE*>vy}C zd(lGH{gvA&*ZW4ELtV?;03dz7lPgwSf*)P|qGq4h)k(?vouNUn)U1b@r6|*KPngD> zAf2SIVNfMAH(w?9WNK#NMM)4#=x;vV8Xv%>)sdQ z=dq?_)$_&q=k3x2QH_^c;!}g&l=)UL2?Ja4@qL2Xe2PIXb6ufauS9iqwDiAOD6wk{ z4M~f6Z3-^WDlYZZ3crB8byZU&<3}dBs*P5JhSGcp)VSQeGW*H?neIIgCnr=FW`<(h zIoeYBXl(SrPKMe=RA&ZBu2 z4Ia<$KL`shWUNI|a!jSMM;w~9fjox0@fid%4LO!`#mU6z1FUDk`L9tqd`V77{$Zi6{JYQmskgYWc}b3kzh~b+emYN^tg5OilB3g9kwqhCy(m3e@+Z7K zdMWxU07t3)N5xQPe>UkXW{1W*UR!RTI`ZJ%)LKL&R+^bnf#oU|@lY>Yc4r_j4 zAur}SSaraw+%xQr4h6{zUveGdhv(GT-To-s$$F3e@6Y0Pc@6MSHgmCIuFL@A^H+IW zc5rvE$dSeBxsD!e&SfxP@MPBb|H>jqGwp(*P`|6^rdzANg<%E%@smT6LL8|z#{l<4 zY7cElUX|4TXD|IstFS})8<#mnbaY5@Wgn%v3=Tjb@Nm+L82^FcR}As&2FH>$P<-=G)Ae3dRITyePK+Fwe5arV>x#@q;tn1s>Nz38kz6T`yyUhD=YoRlCX>l?9x}e$4pFVkcc~zCaf7YpKLcMI;v#4ds z4$avn4>7IsZa$`He(ftuCK@4zke_KcNupIqw;lVzt5s&w9?5?80wtrU-T23UZl9-Q zytexi!ua{|j22OMWGHlbYPi^mMF2AWl0@bC-9`seFfe;>{JOy6T~blu0^siLC!c-#yh-tv#zRDgAXL848>*lufT+HL|sQhPX8mK zyY8EH0db+a zJ>|NfLfNTs7UFr~M7N|O6GF}~as)T`t>q7{@UnhSfQjW|0&A4&CYHF9JZqMNV-u1O zMpv=jNz%TPyi4=)_wPU+E|G+vYVNEi;3voZCCY+$raycqd|pmNupEbck3ikvihf!XL}!w zA9uxi6MN-$Eg^pTPeJMdF=|w5flwBrcFJX{_tH|>RK(mmM2XI5PNXNddnU|lEIL*h zC+|$gTA*`pJ58t6_lE@wr(&YI4_=G40wpczJc*%}eVXWC*R5p0C2lfs76Ok2I!P@@ zVkSRONnhK&TH-5WGvZL9T={?3rNhI+3oBg^xT>qsFxPHA3%_!rq|aufP7j9oqiR0M zs}nw@DR7Kw$)%R<3^5>z?2g{jVgC!Fa0xKKHv<8E`=v(uyk~iMLI{)Z@un*BFKYTx z_Tg@K^NXEghO!Id!7U9>gQ)wF(ovVwRvnP%A-w_8s#HKH9LRQ8hOrd`%AuZ@{JuR+ zRNG$uN3T9cL-+LvV!Xl;KNC*|c{`hbCGP0# zYzt?q18H0|w+3^w;MpDRfQ5{ZT5kd3$oSsSN@0-c4T#_RKR`o`a#B+tUe4f@xFcY* zG5rf5a9~R>?CjPNQxrd8PZM8OS4qBGI1s0SI6U4`0$Y027tWnKx3I7<*BZtk=J0l~ z9MY`edJA(A^x_EF|ggoYTF{bmmy*nq*p^Ax1z2&Dy}tpNqZTNUi1k5%yh*gKn{7G zSZu6#MV0D2r1{Ak9UYxPLC}>^HbK-rS;+F0nNO!igQ_>iDJSqYSVJ;BqTloFqD$M3qBeTj;qS!3&!BZZoW zUAxNz=F>ml#qGxMCS))HW!Y2I(HUEO%~dYFH)0H~c-|qc{l^9xWii(BkuohH`&3TL z(b`H7R?B-jJ40Qs{YfK<`zGNMIk_NdcLDl^5-1dI$##n%9x;@E<9=v;ef?axBp=!^HRwbg4?u?2+0k){wZdlN=or0}&J5O|Hh(6UQ!tbY zw(+4)`7bGwzkoDPr9S!~0dw6L={I;R2?pq*)`az~5|8dEAR$Nqm68=t)Hwib33bi3 zb7J%u0R;F`Tv@rRuuZTx^Vw?WjQ#rcu_Vhy{fu;w3f}m8241&l8oE>_;phM-e}qeEyQYR zW*pSga#_nfiFWNlZ^ntJ?FE1f0y{S5C~LybPQ5tM;QJhS&Qd)1AJsZe-)y46mxzSz zl>@vkm2_gaw}$oHChle@MrslB)_vCxi{nUnY{hNBIjqB~oLYQ)j^CI~fUyz}B8b<3 z=~vu-q!K%XLecF4kwAh}xT25H!w3?Q!n?fzms74g78K@8@_t^S1|G3zI|kbuNIBkG z3YADcY@|nQ{Gx*0Yy5JP`6QkUkCvHscEt&%08S~~JTO8Gcbh((Wec&dAVv#P2~>Wu z-SLpI;tI2lFr$SESpSn+fFn?q~BzITACrq-h4qelfeuSsw~;epNt5?9|alDK6!d3=%6Za@|&!r z%mO}P93cfJOK@olq&V3Q!$NoZ6e4a2Vv!dJ1tEvXmM#tL5dRcbByF;A&`1*w+X0*nE({?8Vo?Je}n_jk)WOKRFXb@ zbpYsp z&$CQP*$`+7wE$t5n3}F_+w#MAUMVXpYZNCtb=<9~sks2<1KV#TBm!V&&^dBCAz@+A zjY?{#S6?5FMc^nWA44D$rU~F*5RDB1n!#>e27tyv>l%dm;_1Tr+~MbsI0io9!jluV zc}prInCfl;MCUF8s8o2Acma}%J57T2)+Th(3uX5pH)TnF7zE}w`udZ_1`TH=_a>&C zE<>jMPEn^z=R4uT_wV2L_xFF0z6^ON`k$9u?s>8O1?eM&XrQ1m>FMd98(zw4yxK7c zJk!ta-*1ZWygDB)P%(=+OtaoN4@s3g9YL+N@BV`aB}uerAe6UGC$N44M5|}dp6yTZ z1NZ#pUvW@PV0BKRo78vkuGJ_~6a-Y>AA)i)t}gr5f8az&32DA{&W@T5Fnnt`lh?Jy zGmsI<(?{b6k`xiTbmt+Atp5r?#lyn`blf8(uTN=%`F=hf?ufmYy&j18nVFeEwqO=; z60-&t#ojBzaGi9&_`mn-026)m=#fS-`u0B{3qG|;#*dD3t0ciJQg#0Z$c8^5 zr{jGGRtLLtNX}osaZlwhND2L^+%Fh`M2nrB-Aj5(o$V~-qyK5|GwAKfxBmiG6EF;XWQcgIZ-gf!1QISr%6}F$vS0^IER;8dEJjKUK|JTa zd$+x3Z@~TIrv?}pISw^AC}clbzm(z&?{&BZlK^0O- zA52HGD@tz$t9)XXl4xX2b30iUi7GIQAQqT=O9(9}X=GAKc91n}UpD`m>}Y1Wd_6cZ zk*p2S{vRV#e05<2$ChkLapG~d{mL-@Q)--+fW7-1i6KUh57l`wzg~TTk~q?RqBrg@UG-0KySQ8E^hup>;+i;Wnh)%vbo8O;VRaGv*-=92M#Co_0 zkE%jc0{$l4JX~`9AVLE__S;z|F*=%d<}J{s$8C&WtL9ckhp~<{1T2;B#;TxF948U1 z?v&?BVah=>Cl@z&1{0O%S&|h`^ETinuHRUPEJmIi4J`V1XJ&+jPMXwpj@66 zk2nc)VFrYb0bgDG?}$bG!b0qQ6~aNA458D2aNn~3`>KshevsU61ClDb${e<8jlg6va12O>_QA18Z~B(d=QNw8Mc8U9IvTjM$i5j|jd)6*CryX-uE;_8yL?_d%9LbA`^XtDPK zH-o6%C)ax)1xT~H>Aj*e<$1i>CdvH9fUulTOlb#35az%J!ujf|^OH&MmEj0U#LaC7 z;Ko6**EXovy0-TE6kYe`S5{VbCyH-_vIFDAnbNk!iLIexjpOZx$C4l)FLmp0&-Pwp zn0kQkqB3FrQBmQI8=IOeGgYimd&EOB^M}PEz$mhlJ-N#HxL{a~Y~S*OK~}I+3`)cL z_(k_a)riK8ZPLje2blcgopgGhfU1Eegn~maC`{(MNqy+LMgw&gJXGhVzg53SN}<*3JW21 zcMnQTgt6dgSmg(sR-XaJ`DLeBA{|E(QWHaCu3V?XcIik2ViaxnA|5-j+@~VS1 zd*1}*Y&p^z9L{IP$^*axaam6MvP8+p)l=XLrl}x#dB=t18GCgAETf5&2QI6A$-mJ8 zghD@f{=rg&2^~^uf1H%L0v*I$f!fxt#a)R7f2QCCsAWuMlWu>r?&|@je zowp~CFthFZo=}X-x;Q=8rr7m2~wo+)1PVQOzGlLzOMT1_UpQgMjS|qOs`;KC3m3h6at=`dlzsIOC&Gsci=S> zK>sTDwV4m9WTuZ2#J~xmKg~4c=MkLcKh$n9-Xo3wV*>~YtmR@N{Pqs2juqg(hx-&P zj;>~NNNPY@KqLH7!TfnTgO*vYER9VCt_5L%Vh&G%+&?09F4&x*fbU<)_4HnHy;x{_ zVS2Sz^=igTN{RUo%=}X_Jt8pM-_&AbGl$1bZ8&cjLfSm4%~jvaSK8;*hpZIKcc@n+ zt%@sN{_ufD`A^~`u-INMC7EAftiteTsrdi=`m8Bf#$g^(55^g-zW3 zhcf&=kk)VSWI&2Ol#EVFnqZ|<3`>9&oYR&Emmnt9AW{HN>Xo~>E*b~)#Wii2zxJ!4 zgTq&ns|p;$3(RS0X<5DiMAC(s5#tCYib~SNtEl_3p88+dYutUOFg9oGTBp*ZI+wht|rF$bJK5G+@rW%K}7WXOb;Ry7vNm zybR%coR=3{nuaIOuIKHU=@ttbI`@8ge z(*75K82X=)X4$*m@+2Cum13NL4Tua@;+LuW!&%Op3@@pb21Q&_;%glYM>5-3<2ePP zxip$i?s_q-1Eag`LV56agRf^GHwUUoWhxJ!bcXNqFp6(ZawZ?{-oAaqTyiKzsjlIE zVJPg zIcCpBKaCY%6Ryv(pNf)jT^TGLdj<~)(sfy&*#D}5g8LR;9pXub4n*I+Kq;1MT&1iv zK`0vbW2M*g7%OO5nY16y%4u_BG?<)i4aNkNH@FUss8H}o!-w0G%4?HGtbdBrhc(P3 zZ_$E1sha7KaPc7j^zhdJ(CGw4r`xu(!ei9VWYF;xR%C1 zP_|H5td(*Z9}m0xsYOEQQ~Kkp>9qTw;4a#xa%bs=Y|&-L5ohHqx3iRLJW!DoUaqPM zD|w>B>cu&CQiS1C-z){05p#`n$!oOg-L+ffqP#hiw)>Cu)1kFS;Y(D^(yOcQ-Fco54i&(%((^Sw4Xt{Gsu1K)$U7Q$l--=2@dm(^tvyq1%0|Ea!-ai^a{f;;$>-lp4qSN+r^)h z?9&vyWcu>rjDw~KCdNnO?;9WCx93=o##)Ee^F@Y&sILr}4u=;gbrBbsJ~)FyU5A|= zNt}GzUT|Dy=M`4})r0A0qI!`bNqP>hcH1CKL(t?T)BV|Jtf;5fG6c7doftL|#lNqX z+UzRGj8^6Gou8M?`ou8U&{^7t+IO{0)O1-pXyxFMcJKHw<@I*lZ=`6BjV3x%t*FM< z4(jtUPqFyWNp*%lYaY9qZ?1Q^HgF@MtsMxOi#ST{f6A`=LL5gtoy^tW7#8FH@hmV5hC+(L4j?uzgYx#W2hS= z!<-j+6xrm+^pLnVNjq`k%^naWE96N|58^PGW1znKs>!=#Bo~hp#Vvhle{4Ehk3N1D z@#ev1ckpfU3s>j&R}92%7N=pK^CfubSlZtAr#1>u>x3QtW>(T9W0jP4cN(n^YTfGs z8*2%GA)cS?j7&tMQh;Bzus_wDP;{AAsAzUzX=CVTBs zSG8=~Av>}REG#u{j3JPkmn*4Uq|)bCvsbpkNTYGp7Uv6M_AD45+X~&+?y-uoJj^+j z*YaTs-z3t^o$K0qQe0R5eDFxuFtxNa#Y}q`+b2n|p}IIc<_I3InxgtKDfku|=mke` z1R~W(mE=SjX|Ev11s94!0!QCWC@3et?48Z>U^ieKvZ1Ht)!TU7l+mcnB)Q(W*pc;h zm5{=$_EnonO0TpYrV-N7p-$mEu=NC%SDksgS>e<5QH%&rja6TiFa^%w<^A+bJbAH? z3qeig*mWU<-oV3U_L1~A5SlC$9)J@MkegBR3Dzh?g-v^XKNgvrWBVj(p|E|+)!_!; zPFw8)hw1C3H53E&lrJaBk#O|ARl(E+WAi0i{q(cIF=l)u1;*5g&<@4gXqJ(z(am3K zpg5#v!P1a*KIK*KaY5dED`q!rF7|nG&1^6}$zm)%P|Kn{ewQKro)~nvISd*m%JC^l zw|7|8J#Q-e}hK8>p2j$zmeWEZSfCQbgOg9eI6xnju-j+ z5^Hm9vrcu>+X{g`F?Db#;!d%2@3tK}k&Kn!pBhue78z#fw4ZQGk{L;n2J=l=wN*44 z{^h*qfCH#>O3gH;+wuddkt^5h9jzdj~~LwKUMa!u_qWD6Vlhh zK3KFBMO9E&KeP5VRI;-#z!;URVhxHU367Y6@jdj zGOQ^lm(^PTY9;0!sQTAz(1nqpEVJ0hhU{?y^m+(=;>9X#&-pvtgX_=|}2(SSv5O~ zzQ@*ZxQ3xadYc?BQp^5v-}BdbepIyuocKdYV>43Xa^a5aWR5DuuDVZ4;ugLe5t1C| zIA<%^k)j(lk}=RBSzMiJsHw4;-x0I^RdYMa1Nq}f@Rcbu$WvA&V_7rL2W>lZ>`B< zWG!6e+3V;@_vPO>jmO|z2lvs|VCm+B237J_3;7MJ?B+SqFk;6z=4b-NL8G3j;j@UT zNvNf#U96JUpZO}uDe{7HY-gmBU85^+TuRTV`~BDxJ#lNLyycFRd$vXm6DZdev^%o3 zx!;3)fBym4-%Zuq>;lRI(Po9U-*(0p9d-?KiLlF6*b&xJw8hFD{seqDT3QIaQ|h>e zF^|<467I_H=wWcQA1!Ptm7;oi?@(ue&f7`b^cF~2;-%8uCwG1=?IN*PLiLNaaE*DG zZq?sC4Et-#c;>sgdA4hp3lBbeb*_6`&g&uBWIyJ07BeBGgR=*f3A3l;c7cZ}|6{s4jxrvHSWScX55T;j7U_;pm9s z-0{lVw>$7{gdnT5xpLF{JLt&}ml`>{LsNMq1IL8^53VnlS)aewc(ZzVP@>s@R3`Q` zsa9~baCfT}6POqJZ*{aoH$YpRF}pf;lC&~bJJQe8W7-@V$UusLRTqrtE2+lvGv z#}+_L6cj76rQe|obz9c!ZE*NgqR8=r=X$^M6mx+pGBjJJw9Mp@rR8CINM5CIW$+!k z&Q8gNu3z-wjG~quA7Q1`S2kPAxc;ehf@#|IHTxQfAE6JO3D%SS*}&&knpyi?ZJ9mv zIilCUXSK5s)k3pF}41G)ZD%etvO&etu74c|L-U&gc8aswPj& z`pbtLFG)cf(#t2c+1ZwSG?Y#{h&b`cPi}6lstS(Z`_T~4fI`*(SdE(sr0!wX)ZMB< z?n^9xcTqTt7Ci-IYh58rDLAde@orz7b?pa8&@d*NTVEG$HNwfqEVx%LUQ@Fiezrp6 zR9@&P7Q(a_@_0|Qj(>T)W;^bzbU#jxMLNxSiEs13akMRyo57)%V87IJR0T-0LeVO~ z)x~S*7ZrLG8XkfQgyNK=p$_`wx|zk|Jwk8L0K*lF>{E5UU_c{ zU)bMEl{$s3y{NVE8fR1!)lmJO6~;8>_AOZFAUsn!EElePmr_^utV_(gkVLAN6Tjh%fyW~&p*`_}p&VN)aCUnST zw}Rt*JypcDccN8xO7?93rdyESEchO#mgq4Xo9l?B@^SBgin{*kWrct7yKVD!Q#^{p zAnJy_#~e6e)R(c`eYS%C-({&F9!K;KrYgoBP>A~M9?V6k*fZbc4ZIAWR*U`gJWKO0@2JFq&-ol(aW;zy(dpE523;bW;jIv*<2eW;*{SvYKj{!4-TybN$^V{iKULYeSf&I{ zs2a)eq^OZfv6|IA!E&c?fXjt82(eU4hY=&e;mYkH3^=nBI>F;l7e>zccZ&fg{wVOe zbopX0<3H2C|2sicHUL5ZXy~vO4L2s8cne3U>&KQ^Jx}@_enyGa$cwSjm)j$lemSt{ zy7JJGv*I>_q>VWLf(V{?^6Agd0&}EGb3KP5x3t{!1S$@?LhVvCXfh=S-*qr=b<_BFZRrJU94+5Je)uC@WpL66fCphA0 z=_&9Q#ZfA&-v$6B6y-_lYcm*K)vdYVv|Zj!=bLNYq;q5fikgpv$<1^n2{h(=__}cM zBnelX!&KUB&T(P$(JYg4uc|u&=C7;fNV>*_uvRBy9USICVDn1B?7fXnMwKk?vZ`Um zQ#7IO@?>Zm+u%9aE9eDXNgP^h);}Bgsn)Tz5skl^R@l&gepfiue7*K(6fRlZdsTfO zsRMoMyqS*XRKyaWx92z??MdY>j~NdNyG6gT6T>{$nZ7e~T9@IVd6kZ8H4bj2cHbX> z`u3M22dcU}bW~}4Y#BMy=+`2K^RbJfUxk7n8}0w#&?-N$*3gqGH;TB#sj88XlV6yp z`SR#zS8zGAkA-)GPf7=EVLZMia*QQ^bjZf0D0fm<4c~PvP83*{l<}H=%a`R!SkrhB zci6QK*Qm(#9G%6OhITT46SqW-+lL`#t|Bjl<}FRaTE32Q@8v+#yP-n~^lvoycv8fD zHs<>kuuOHsH4@E6fY1AMWmh$auWqZ%x-;KxB?n`b2Y!+hCCz``CSOvvTx7C-#Dgla ze9aQjO>R#Nx+v&&E>xsY=ZE`5SqnKA^Kl9%2NhYRDa~`l{VGq532;QpXl9j`ypvw0 zWP@Ifd|!O|m!2gkA5HM;UgGHX@EAVFAySY#UXr!7Stf4G{0)c4OQ+g7x8ODOp;PJc zQrg9V_7MTjW(ueLjD!ld{rPS#Z3YQP8mK5RXe77q%(Pg?Y}XbaGo|JXT-!|59vU z{7v$%Zv@rhl~DUTHJhdJ;O|L<(}%|i*){(><}0-ri0{bm=wRW8FOqMz!?itFq1(lW zJO1KBK%HYWgp786m#eIyS>Qi+~#b0;7DnYdkN5=1Srn6d@q%uDiG$mZn9p#TTm;1)ank%s2`$j*y>S;FcnpnmZn z@9}+A@qCllM*0}tI-&Xj)g8~4HG}FO^%5xT?8Ox3H(#fu9w%6Hv2ZIYeIMI7P#W&K zp)UY!fcC8`*dD*KE%r6-fex6x31}2hYfYSLFz3nhVck_HOS791wc}=TRp^d3h|^(O zkujR}H^grl?ULTh>s!WgiM7-OO;O(VM%Tc>qDV;Fb$E#(p=6wJn?w1Uk3P{o=*}jl zBa^82hA>h&SNDQxynmOC%dWv?u#0p)tahJ8^}g%KsQIE>C_AA(Yb&^ai_<#&NO(b% zYU-+bSAw?7op>d`AE!|r5+py1WLSB{q-j^2Tn8m*Drb-=D^%&y*4DT;yUyahe>5Yt z&%+`TtyGg%07mA*0_z<2aMQ0I(@hFivxmF39w5gn+~r2V{6%}NOZ)cQ$#;faSdWjg zYTSDA;I)986EW*-M1pr4bU`E9+Y+@Js{<9SuRSNK@=VxpGc+4X>|^>+Ct4T}TZt0& zSuDG*zMJ;rIIFHT?6`-$R1=#{?iKX;j_t^I>t7!9RM^qgcl+Xfi457_kJ2a(TuYj&UK&hzVj$&UW2r=@I^>HiM!>8ZgPC>;g;jwx7(2Mm8pk{&v+1Pd9P{cxD)U1FGYO%1Gk=NzN=Quo$z`qv!=4W zInpcZfp>d()n&2XDzenI?Gp?R5o5d(nv(N0TDkO*yt(KA;;|x~`n=NJ1h17zCC#UR z3Y|JuYNsxn%fRxEWn5HbDsjMM?1y9Hm}Kvlx-S-V%-gjc7uTq_Q_FtT6I=T=5nuB4 z*fFB(+aR}&_RGX_MYRD20IC{qff zd2X)6M+#Y{Q@E;tWajfGS5EUeM$gIxHN>XoEikg}Cn|R=39K(hn~D?ee~-iUN$LG~ zs|W5<~%Z~ZkqA?xEX}G$yNJDK}Yl2W|$*7VMJ)vPU zSD9NI;b5ufoUp@JV`ub8u=B!Yo-W{sJ{ROleeB>9nGcQHJA7_RPn$ec!t+LKCX{}C zJNiL}Z^PiTjN00X8`U2g`YFg`iYT*?1GKT$LdK}j7l=TL2~DR0vllF?St+3 z__15feD!&0@UaSa!YkWrpC6rOM-IOq2iIcQoz3;7Tn=cRt-;|+>IMfiZ$<*P(I}uP zNLYXz9!i!C(U4GFwaypbMbpRXzAt;yxRW3zxU zL$x7U#CfV}n998tgu5(5T?a+0ei3$=J@p9)MdM9A3WHI;4}n5z_e|U7C|0WMCx&>L zj-#LO7wRTSC{O-$RrlznkaDGI4C;57~MJiqvD^3 zxVe)pL`bids@5~*QJg&;%Y({Q1+}Bf4OZRNLBe4-lh<19Ypp91^@zNBo<3P+cy?kO3%R-%Ee!D3VVo1HQpNQJ#)6W8)R7D;Mqy*a zkJCz8P?!G$p8iau@8rHAWqLGR%n~={l=gWTZtWbJ(Y!*TG?dkrt+#!EOUW1dE%8ZKie@qz-E`M~l+u`Xn{RbWm$Nj8En(x9c@I-(E~Y z`eT=A-dC<_7w7_-w8KqA^;{~98@iR$#NDbn-Z9y+%s($raGgM8WKKk?R$%4&;t}Da z9#Qmm-W!dmzt39`|7F!7Z{0TQ?I@DkP~AG(RVx?6s(=jREg#>o8QrNmD`PZVzn**6 zuD}cL(9_%zE}CqiI1z(Sv@lNJLdgZz5UVE$2vGI_v$zecpMiD`xWF;y&XNE8gBPbv_Go%?1B!?jnakxF; z@0{;j=bv-ex@+BU|KW0mz4vriS65e8)$_Ffch{$GO;ou;JKV!7HhS^dt`)tjgN_+_ zZuXrlp*ABq&6aK3M^(Knc)@kApm;)X1{xCsMHM>8B9yz9+i7d5Sw{V#qaWRc@dxKt zvx@VCi!y1sDuaTYYkYFXLf!Wj<^?;%#Pr9duY#S%PX!RjL9+PnQfqDWSj&mVQL&+3 zzYl-SHy58NBVXysLd=p5r|LlY58fmcBWG`m<^Q!@wsY4Tg(Rl1$JftBe} zfe}m>Kef$3yw*z6ROxbi=)70O{&bUEz9CYouB;{Y!>zS#$;+QE{N3EO-r%D0wE^~8 zwq^B8VG@KTLksI$fo#turaO(-jaMPlbnBnq*06tBRn<@g{eoKVKp2nAWM$0XiDYGc zCg`lJgwPp#mN0(VnF5kGp{Y}|JCxBp>8s5`yrXLtl+MW-4j}3~pmK+-+sNfr6LCku znT4!yKL`$pM`Q~-I&}nVrkcmhyE%!!O)a*@YWH|~s1v#_*6T9m zy03ZnRbcZ#EmZZ|qe@gzx9N6o`S?#?im{-Moc zUE#aXh|kYsruqz35Kb6IPIb?z_Y(|JGsOkb*TEXa3^GqKh4i>wTZ*EI*-syt26HAg zz}&{KY)PM{su*j`5;enJ3rFauUCJ-SmN4L1QThvlPnU99T)m4U3l^T$!yCB3dL?Jv z=w}C8YnJ*RZ$V5YT=KA5Ww?mdU9!?LR|{dWmspxwd5?UmCg#Syon)7l_wVoyL06;0 zz-j>;k()7oAnb?BVftvLq1Cc{SRyI?efL6@;Mm_t?`rYFPu(d`ui2a`(+ z{;miM-Ew~N>PJ$C+%|bpUKmm1?1*2sd-oXZt+g(?79i*SOl3UnLyWlS{2f|?GTUy7 z7wQCC&4S_pLh@oIkZrz)c-;zTg6(SLlJEB31ltw6hj1^u&mQWJ+YULu?dRyXt}Z+_ z_MB}Lv|S3l<~$;&K3r73ASLe5{N6P1`c@>7tG|)%!Ouy&D}77G?YLQ72|`C}+dVNh zLVFxfuKGo)+-@jk{MPNxb%e{b^K7fX&GW|+55P99&Z_CSW4sTtwPUI_C2%wcOjLQB z;_UtPlcrtn@FZQbAiNM)yNttWPV)(Sx_XJ!UzzQ01xcsssOvKTmu4oPScOwe26O2< z$$5w`K3IV^fck z;|zIb(7D>G1}~*@?KTGswGn!itRz9J9=+(xCt<<FCZ+4T$W$$!$cQWv}j83WTZ~ZAhdGo||*7tS|l3{wgL1uMmlNjf=|8r|VlrZgO zy_br;A>;M(H26`vq{pAd!je=ETqBtdx)#F~Ua#iu@mS8@@D51r_EL&~lnGW^12+o6 zdF@j$u%Gld1SxAbRQNqHWTXmn#kk5NGPb$csDw>dr_pPT|Jpj1=}?1I)@j{uP`(l` zZB*{H)~cc&;?6B%*4L-ps&cSZo8ghC?B);m6qIw^#bo5dqfu|9e)rlMGi{+C&UjjzP0B|FDPaEACt=Y zzeqC$Ko@IgBWi9XyBiUCmOFVAwWz)qiB==-~YuvcH`F-&TOG}Z~?|32Sc{Bg(x z>;I5I?{BQ0vjf!4cXTL4OidQtxac-E{_=zC68IZB{cmKPjUJOkeY_O4au)IisSw;A z5|PttII{`D^y8P$S6q8dkk%NQ2G#s$@pF%*77BcXpL&5JCFZ|G#v|A`s6SITK-Y;O zkO_RqoMv+XQ}7}%R&^Z(SBUzrFB}@Xcr}}z2I{=f!-Vi-LpcTP08&j{&_Y6Pt0ggq zDhT?+|7NS?QyrVHwJfA0Q=j(E5<-WOxx&Ps+z|T*4d*0IqVt~#gN;+xMIIgfjpMJe z9ZX8oJ9qKkdk=0&^gD%toK)5z23eBtv89v0S*B*-GV>8NkbKpO`)@YMP!d}5>P@)Mu}_7nK$(!dJ)mF&*40s*tSvb^so-y9>!~HH^$TaCH3F z{H&DnyD3Ff8@|B*R`W=42T#D>a_oIB)K)7ELT^WQdG0v<O7@!^1aI&QQ~ElZfv z@$-=VaVIy$al@N2eih|dc;;TEz@?R-!T|MsC% zPs>duw*iLb+f@K0@woA44^V~T>gIZdrR0j-F~oBMXgUfjg%}LHX0zAd?`X}wy9Dm> zGy7BoN2nn3f~MaE5?EAJ1T^Ho^kj|ghuaZMk6=7sLrwey4Uya_lp{<(oRXUW5MSH1 z4@CY-%52j-qR!uSGu!;u<22Ni-9J@XA6|ok%5G3CyF_$xEe=0FfBC@TO+k6;>vyW6 zqGn1`*nDMqshZ<4ibCyD&$(>(DPLjKw}2;0SpXf#!Nx`J;^6mq%EeN#vKTzKr1H;N z;`v)t7-)xv?I+946oPNk0ksc!lA)p615{|MIZTR5=A}M-9^_sDtt~!{tk^1rVI#$6x6*&We%&p91xIVeB(zW3Tdp{S@ax z{Oi}l{Z0nyE=>0+pX?`5Q;?JAfN?f%%fgrCem6yCDn#W-XBon6 zQN_a^S27t+tmHe zSZ#v|HIei*tCgPe3d32pP(<$rwZKC`50K+@Ukw4T2jD#n0GdE-fEi)|kgF`vmGhTb zZ31i#n_ymP=_$x>f>8sQCH0z3?p~>rf3F6+L;pZ?{z&Vy#L<({CVHb>Siblg|Or&U{A&)J*7_+Z5#o{CxSs*3T}G$B7X4;$n1Q7 zjTCQKZprX{@v+184$$F=5jKLSN)3Vh^EW}E1k7zM2`zEHr}^HW?T$gGA9Pv1m<1S< zESueqoq15<%?yF>YA>x~vRXxfQnrRGLg;_pI2SIz*Ulp7Xz(pip&{x$@&i99T|o9N zU}GJI=}B>#n(y{kh66en1H2y6T;mJG>!-*vfE1M@4V=4q+h|E;JQh;j=?_N`ULIgn zt+9ca?t)@ZPC?u+1t~s&(%zYW8-8YgBjo{H?Y=_fvj~tAm)QA^0QCUkOA(hq?dd9o zbb8H9(87z^ST(7G4>S%>Pd3RnnhyK{m4=8CAObSSYmZICZ#Dm8bkUbH%>p&`k*e%z z{_7M`-O3TpZ{9Q>4wtsRD&LWR_v~yjjeIdSHU=stoO{zGHMorp;03D+($66H=VVG7 zj$s(7Er<#?0JhD8vixjb0Ny!M%bkwyZustqK6v8`?nF%q(e0+A%!f)4Ht-xhnHtV! zKKv-zNc9Wf+|Hnyni>7Cr{}UvNKAC^l2UPd&3o`t*1w=Uw<&(RQR8=p>#spgQNkltvggM`MhzM=|)NqcuSZ zU77vFvgM?EFF(R?yy_30z`8YxA-(nKr>3(N@i%D9>AWz)6HJ%vA5Xa7{-+keXatG$ zUqQpt(QB1>X=)1L=D6McPa>;_ZC`L#R#uk6*6Vu#tmMp&UHNiW`FMVe6g3~AU|5xL5Kkd1OSe55{^r3c9prciQv;_>8w-~m~lb)CYV}?nD#%QdSr^l zZ*%+b@GvKc;jk|lKcsHE&djtHco_#60?LBVo!kfsX=(qx)v>uBrbCK5t)E zL&#M-9jBoRfNFkQ$J@QR2@L=R6-JJ$m}xim{gWAVu~)QaWA$zMOAh!wV1PRDIGW%o zol>9Q2l3nzr>!)ln8pHtv`jymT$rRLiKN79(IbAZ-DTGwM8XYw`%lkFkbl32#-BRX*B-U$Zf#HjEJJW!XbFeF7wW1S{6@5x#hXSOaOYlDg zcTZGBe!riYnZdv8KEuJU@;2c5i99+3*nEGyi~@2%!vPZzjf@At*|@KcZuW>{vOu*a z41))BqApyB{Dl92a-Sl)7Z(?|gPD>>IT1vDT3uZQy>EOHd{gCgSAxeX`K%MckHA`n zUvSs&5G+N<$H!CqEIwfn+wS5AH6{cm+~-RtzVd;V3*U15_5XJ*+W*A{=6`xQ-T#;_ z{0&b%(#J}lZc9TDCvM8NQ{EW(kO?4S^FJI+*Bf7*WjOVSqL;ksD*`~-=V6BpsgY9S z)8wh+d0$~b$>OP82z1B=I1{u3&p{RPPkZ3w0N^1*;1#07X@y_y?V=BWXLJtTBKUqp zDPZ*+yN;5cCb_8v5bN4!RiFeLIH{+}!*FkRV0k|M)i(4L-Xa8|bx5xeWJTj=EkOV_ zF+F`MS1mno0vmY8nt*`e)A{!o-#Dgfr%U;6ZEq91l7qV8b16>;&`zRmst{fz7&ymt zeZR2OpQ+&FPcQ^a*q(5mk%m?YIUM?Wa8 z0Qc^EOE2;qxFJ{35ZC1)JcueQ^}G?Mp=<26_SrGE}cD)gEO2n7BL`7!=G&@-%FObIX?-RE*}+;D>+>fJGTwvut`zpcRF zHEi%D7~-nO=l!~AO4XJ{c6ne_rsl~*!1-Dbq+vEaOUF@Y`o1{ zkF?UGB{w9iM^%>#plF*iTk` z;3SOH?P3)!AD3BqXqOtdJo?IeE5whpJZkO_(!eVJVzF&x-TZqNvp-qkRddr8maU}T zl!UVt54mi|rTn`#k{{o(yF`zjz-?NT7?-Xjt=PiSLok2hi1TH{Wmr+-zJ6JV8Kd+IiibqXGbKN3190SBhaBx`1Q=JP0Cjbd- z+JAP1X53(q^7->CI#WNKT99pE_`)Jt^O-?jWJt=vBOw9x2eA8%N1JU73iZGrCrHr; z$9tp;SPzit7?=tr?|S)WbzZndZhAKKJBk__v7K{()?dtL-!aP;%-8Sk3ji>l2fivO zxE&4tyAO`7Xjm>NoSB`yZ%7f)^Dj_buxxUGlHCb_fG*6>U-GQ}{P{D(DS7$W*p^}Wx4^x=JLcN}`!5~OCCRN zTy7#4Zw8xzZm_7Ot?nE!B{CcEj!BG3Fg1xtF$Mu~Ov893m@Pb>h2O&|kdmqhTXvo7 z{QUT2Jy0;XVCu9Jwx%;t4QLAtVI1VZU!LRxB$rRM2p^pb>1!ey(8N!j;;?|TT5*L% zEY%@{mDTf&Qb)YTt`}~e0yO*~wWLM(90gL>&k2>UF%AaM`-$=JEr|xyO$Fesj_83UmrBUK`M4Ip(Mi-m&0gcdTFq4GFF*^_ z0KCL>z{LPIDxn#&_3|cGXZjEL2(6Q#fScmt)tgm*e83a$@~lxyP9r~iAiCSq`4${Mls@kaXTK{|KcpO{|>S8uSs2j&=TMk9bHSFBr^ zrR9Kc?|AUb2!WWm%VHlO6VVTrre)XN}u|yuzzIt7qb5i7ZsyJhymUE zS_(LF=FL$grb~Q;7^;t&#cCI z40eAJM#WGy;aQ$|_K(xQB-An-f3-p-0UPu2DPWeodkfEO>S72U<~ieVy34qQJHkK! zPs`}Yk_)28GvEPUJ_|Af=84??$2FO4KQH@Bcx+4qznoG3Hc#!jx&-X|01iH#t5*xD z00j&BM`!8r*v?Z5038c>yrMu6;qB7W5yo97us_@AdjxerQIEw0JPtn-{rBg{K9JVd zP`ezQ57hT?H{&YHvCFHhFudsR3cvapa@CoEn)lV~jW+yd3~W83Ij>O`oh$zhYhysH z(h<+DmL@@Uyg46U*B+|@+69{Y;a|Aa-rHU=tI6`6UgGcU98$byT3C}ERz`bQ~gv~^Qr*j#dxYtf#9Wk*j z)mOYt+vh^1@VZxcDwX*HJC3K^3$c^@e)q}wFNKVknLfeKQ3J=O%gX-SzX0hcqamKj z?E^U1CeM2vbek#hivJ|kKDl=x%u4S2SDEuC9~R{0S<&5fQf-~wXE3}ob~f}s4Z&-$ z^Afkn$e0-MlM1j2-C7C_XbLn{7;)4#VC{d2}yFEKTr%-3s=4C@$w{Dp1A!u27Qa%aosR~nt(T8pB4 zQln^~u^=2vGv*cWHuA5=lKguKm`5_ZQ!t|#A_Zm7#PwBw3eed&z$JGQ^%(#s>=6dR z@LwNt0`#kZPLg93dOTDAiyXKF1Uq-ZBCxvH-{c0u<*&moToF58jh?gsV!wApzILlo zT+|fj{Z3O6QoAMuR^xx(KEmHB@b}hcV2!j44e9KXHFD&kcv~}F#ib^6l?G510SCb0 zzuo)x;#H~B<870p(DvB-`uLgcsF#z~33v=IPdLTW5VBJyVJaq)5KM{7k-vi{&74E5s*N#o4_8Mt%Gn9p&XCZ=4X0V6Y0%+a}YD|G5kB=`^)IJQMAWhnYLy{F|Vv z?+B-#{Z-=Qajy>%5AZjCe>8B&Jz9#u9sc}C8qIly^6Ou_;s^X1-Lj@Lb4vMg{8Tit zpn#<45@qdw{+^U`ndZL2(*6ImV`&0+dE&5FkHGT%xq98j0xFji;PG6CF5$yD0dKQ? zd&_{ymMi<;P5o7UdZasl){^gh;6NT=6-<)TOuvtvFSb0ts@(`lqt(yWmhS<#$;br3 zP5=E4U%*0Hymq#Hm@pAs$)2ULjHtV7vwvCrheA$bL3GI#0v<|m?iOG@lJoV?5XJ;i|7iQuOpR`53KH=l~KLH+m)>*!Vg_DEV?8Dd|z;BPfS zzPRglVPRmC6YKdQl@^c;6QIr|9R^^>NByn7f&+hi4WMd|CB!D z5SO_%F;(TeXU@K*Q}pn7yZmV)SWkF({?h^5qNcly8Dhp<+k0ZEHMI(4!$D(xADyW>!2)NCKxfQXQWE=9jIx*TVG5QQ;cmm2@i|u| zN;0?Qf_;*K7AAeH%WYBc6c-5ZZU*zFkMpmC8KqLuMbE;RF?+F11u)V%Omf|S;a-z)2P{^`k{ z&HP||OYrzz9&1!>GiDr&I-P<2vk&km_byi%Q7!cS(P;CLQ&MoLLitsjkF-tK;%H}=HI@5Z@lmGu>Mgemy#@K4SJ|$s{>eE& zKh#Tz7c%!*{T!`sCf{b9AZFWi-COHPu-SnTw_bvvZHHRm%1*qrE z!{p_O7^r;v)nYknxD2#b#n4CnguTa#V{SS-8-y7jqIx)p(DWBD^|mrdxBXu`oG28r zuWt$%{41<~_k0BJGp&>O%v29YIrnBSY}!|14vWoIiAmpD_YCkwg@p9D40c=S`q%Rm zHB~z(?iKKkXv=yRa+)wYz(FM{*2Y5~9(qlaf zj4Dg@zj$HBXIK`fU=xAb`YAQj!g7MYh5X^KXO(8Vt|Ac|wXSxjxUB+>3^F-c(&+gd z3-#2_5*1@4Uq|{pL}DzzkNRjp&QrfY?87yc0*r4W#ur&K)2!958&%9*@2;1Kkw335xWGT4MKuiw;T1mqx@+;)%)nq=1GzT3OQ?0ZfhF} zCOs8X3+=@1g8YpU%{T~0g%q@Uzo~>mLG~YTUFY_8+9!vVztVx;a%z!uQygly-TMXdFKl^bPkQ8I$S-qf za%>CIIX%99>j+Y1Z><<`C(!dSJnoN^SHI@eQM@%Kbv)Dmq7U~!q8vj5aFm12htCMs89EVO-`nZAG8Q>g{T-{{zz> zTq4cQRteV;81{aRn4nmV{ljkTW&FDe1-*~Wo-$sJPjHpp9ieqRdZ&ODPv3WKdZzRE zO``GKQTea&3^}SOvEhJ+*XEaE!_9)j^cF;2`kW0&N&0=}I&rN26}G!o)0c;+O1;Y- zm4?>4pVSKa%ey)S z>^XKq^1PKheYTx%*Bfi0_TFp+!T8poMXyu$fpS`+-mUf(I=6@{Y^vBYR8?Vov*}zV zT>bY7t|KlDg_1$dHQ10YO3#;9JL&B`5$T`GEehcpiJ7yIB7?HKh-U8F8wpY`92Zu1 z`6m!CWQtnxzf7iw)^#*O6kT8XHcuL+syBtlI+Y}otg30YM^M@)`*HL=3*oHa_7zkG zaXtZbY z4qOWB;qg~lz#cL3?NM|Z?;FZLblo6B?8~>6eQhmAQcO;|^ezvl#`2KxW}#tqtL0xp zLqg{L4u~bYh}_6C^iKtb5Sg!aVh@_OI%4K@`Ex(tX8s(L`=#{*xeZKv9s7J|H9T|U-=c#EYeOH=4(zeFDAZ>z>Rjj*J56A#~A z#tE}|3o;n~tVRz@xvK;^p|>N6wkMcO88d`?{oNF7bwqa~GB^d-YLL+48ssH4ElaPB zgPEI(FFWUL9Y&6POc$J2R$>PTef`fCDapSc3dS%&5L57+L-X)x-Rz!mzAq#;Bm_q> zw%xkhAl{pBy7I3oN0vc6f?5388}iu0zOC?Seb?ev+$*i%p#DMUks`yB{jEvw%I*2y z)yBm3(VZ?T&P~Pcrbv<=mR(#Q!N=D348g1#mi5>rx;g(636EOb+EmV-4*;g@dhTxP zNROJ}W!!@r3Arz(l}zuA z)lUg0cAc6|yxG|%*C--VV|b-mu;1ErNYVxgHu`K50XUEbbHGy*D&4)EaxS$TphKEY04o z)?7zdU!&muRrU#oHY~e-j;TgYFZBI{0kg%VkM8J2?5?6{G0x+^DhMS(YfpO`olmr( z&fd(5;Xr0!OLo(5(l&Fn=ZSR%PjSxSQ>#D1W?NbGI+2QsX?HqIB8NPhEwoML*f}LF zR2ADUK`PAk7U2zu9jVTDjJe!)#@WssT=rg{AI$c>O=u$6Wo;*|H)i=$QT04G|Ix`e zYDi7tLsE?xSg*_--<1VvRmD|5IyhfL_Dd(ig#Xk6P<@(re))R5s@5SfB!rJGXU^e3 zo`&+r1L%t`em{Dgb`&p*+6~k~64JYfX+gtQlJkUOmc@wNZ&5v!*Yl0LZ%@yoeU>?w z#vf(xi*2nth=w0^h*sw=9Sr2TmP#yohibr5Vs9cm z^r$21s;s8_QjBhP6m{-NvzVFucz7YlU@Xx>3Cl~Cj_jO|D28W}ZbeMoeQfEC6ML`J zVCwogNdu8b4UDMEEaithia`U1g>_pO;rF^qmqJyepFbOr;#k5k&JsyxixpGY1h^8C zs)t{bjG&`Vzcn==v5pOU5Ec@GD3Nk0cKx92J#J7ZaL*`fA^Lvro}y@~-?_iaiTjO@ zOAuUq$9I%&_fh}4?Zu2n^(_VCJ@_?FWzDv*i3UbSvF(NlRq2|M_A7!rdlJ*7hh~Zp z7Gg2oDeHZqwUZe0us6buz6q5IOkLb=zcMaIjoMPn%4W6e@3v(WNRt=eR-bt`XsKHY z6WxaH43#g4krO7X3lySjfd zNXk!B4I_QW+(UUJPp}~AX?Vyl#p-ITX4P$n_dllh4qwVOyDcrx#tu~Cyv}r2_}sWr z-pv`CH`K1pkk870qny8h4pwQ38m4Q30S~4_V4}DkKB_id^r3b|geOf~E>vAnlgrP| zsM`4Gl)p{S<+Ftz8Vo-krBJHfR}gn~qjOjFO}zi_%@D@kKB~0nk>p*nCDA!p*;nwi}iX*J0P+tQI?JuNK>Nw^WHC6Iv4BN2}sOmP|fK1cHqMO3&-*nO%7Iz~}g~ z*P}aQG;4#*Dz;0>u3i_kY*X!3KN3w~*InL@<&QW%MegNfJ^492OP^FdzfQ3;8+%*+ z+;Bemj%75&D;2@ln%jJpmY1Hq%bd$5OA7hbKQrK)6cU2=vb0d!maL{G%O!?O5euYA zcxt<@vX8&vxkLW|t#1HrfPsaZu^YZzeIJaL$oA^$oSFkl<3Kv%bZxwxS@=FLSFP-J z{QRF$xTTS~^VIz7P{HG`*`6;XjoadAZprO^;InzAj72mR>xW z^x)==5JqpNd%UbJ_pQ?k0wv{j)@c1FbV(0m;y=c|XfDYeIr6R-*=;;bn15+zn`OsS ziZSSBhBqiBga~iTrGc2tWB}dQ|Lj8+taEaTqm%9b zN#jgT`Q{v{m@Ik!nDka&iP#<7j8)ow1-PvxX4neWyfokU}QV6_P~Kft!8 znqmjeeZz-$&jNJ;Z)FeUM(nRKGR`2dxnzm zAgqJ8OMgMcoK|Bb=FpY1?fUz4<^1;Q^;736*9~ig-go0|ulCm5tpqf@BBPD#QRYlN z-99gxhiypg;2V;{Vq$z|=ES%2!%k(IPJ$=fBr zD(RE>M7_~f37QML@lnT{RZo~~s^tJ*+6@^IAxTRk8DgyiV{YdUFuJOfNccC~j0bAU z_THbEvsEBV#Zdp=NJpf$H*hd({mguQUU+3ky2R?u zgHcSgOwL*HtlSH);j~+lpJz9MHdArYZjvoxmmpQeO;D#68e# zbo=U)SPJ8`4SR#EJ3QzmFqHFSWmnqRn_Reh?fTlf5OPwjm}4(Uu?%=)mxydthNy>I zOT?E}&gSKvzw?qHR-%`DRYt=b9FPVEHx88ADBe<{iLQ*6^w|CSr-L8`-9MMT`UEXWqy<)eR!a9{?Qz6 zM2bCh7kyv>Jkvrw>u#T_hV6bi*=?Po$~n6mt@o6+8oK^KtJJ=TvU65VF)wIfON*AD z2h4kOO0VR|kzMFaS%Iy+9P#d0oxALO;~PIGe4@f6Q+e%<_r4(wMya#HTUJ(9db?>7 zjqO`uS&)k^cPjs;{q@ZRbmN|ORNR-#H1w)Ob7BRysA5(PzAd2yQQH;0bz&7squELA zxWssyDv6nY<(`YpHdH6CtE@U9ub92-*&SMgMrhGNsssFy_o+IKh9D18Nc0rqSz6U|3dQN5FDWeAgN`8+ROX%?~OVkscBQa)jz z%)n{v6*0T?y0eO1O6C~wIl+XlTyan_yb$JN5yTxwPdYY?cEG;3(cv!|(cpV-nvLP|yWv)NqV$hd5? z?0yL9iSZ_4^!3C0OCJdS`b&;Cw&!)zJ>UjpB>lb6v7Y(iz1nahSSo4a>r%GeJjM*K zLfm5Ua#bV{{1=3&{d!fcD&bBgl3W^B6HW%%2eSiKWA6g7)h~E}Gi&-lRM*bSxLsj+ zr`}C4B*d+uxv@YdE;)j@N0^;AKMLZ$NKr#;s9{@}Qk_c7oiWJL%l;B3WU2QocUC`r zvf=R8WW#fXRAxvw4I27(>dtJ+R08~yy;wzttB>f~&==!xecvof+}4FSPh8OnfdwH} zQb?}!!fhqq*0H*kbl*`iAsNJLg~nf<6%1Wf+z)p{LoNwSJA$q-v7Fi0!j3%rUMcyZNT;-hmkjgPo_%B7N#Fkd{)O8CTRq%*MDf%v|rHy453MYu|(Qob3 z2&m*TB%7p2bc?kmNJ1<+H5F$oj6JmUp&5(2C+OJ==Bq#BzEnQ@CU=;Sc^YhnXLfe5+mQXP7+8Oaix+nH*$0!#-K zBL`!mm84`Obv*K=mx7CJN0MMDWz56&F&cv}#0^FU_1y=?S0~fVcH5E#`j^_MXGm{% z4_cb{Bqv5swvkXBaSX^&&r2c{zI;NI4C&5p+lt9ScvKn(#C*HPR&7_iCW#<(5`KM~ zZAkXQo7y8oUNkgAu}KfT;C|swGg)zemaO?LEW1)1&u!7<*$0U1$Y2$vVj;hnFrihe#Y|fY*8582{CtDKndE%*vP^Qf#IX{xD*k`fUyZWS7zEZ47;gt>@@lz|g-*HJJX*&Nl>dT@%&(?otAAMSy(%_;u^v-ifXCEl5&b8|71CP~t3heBIN#A)Y?d-$%ui0TP_)IUjP9XE+ zhukCb^&k&LkaBhLj1BJWF9DCk&a#we9|!{f7Lc8N`v0H>a_5OQ{OkVDAG&+nk*i*W z4S$IhmkAA=<(kiK#hsT;oVDWreD3UP{6GIM8n~Mtz}|aS5iZDBnWZTE6ET&RD9FAv zGr9;ahH$mIo&>~jF|-)tE}3pw`JkmuUV$hq5-wt`t=)JMK<#$QXj7bNHP+l!7~9&` zCQlp|8X3U=NsIS9?TEREOHcj6=9#MZmzU3St0^P+OE<`Bs23}6xP~lKaF&$1dXA3{G8?$U2lh&u z_-klCyJs&waf*r#R1^tv`1L0B{ss<(NMqkE*DkhILE%8R>1uLZi;)oZTs| zo*PQ?ZPc+A=5u85B~1QIz_MR852i<#HD`ZXyI(p)O-ZFjQu8IwNKNYqn^@#?*Lh?p zYo9?@0f>X1ga-0V5oT?QtCaLZ`PMcaGHMok`uNzn43*_AlALwc_>*zf;KW+XrgSrH$B4^EluEj9AhQQsWYWzJSszW_P7_+_luy{qJ(B)tWvVNU~b<yT8v3AH^hoD>Cob>eSW523e%BW;lV38&C+di?}K|Um1RA#a#Un^F#Z`T;hZjUC;TN=RHsR#X#xGissF(GgKhPA6^l&@5X zs;wn-S@Jj`^AA(5js~iCf`h0#p4*Z}+$TF}`dwJ+tEu+~~F8Bnc*EPQUKDS>gGca@Hlsb)1SX!`rL!PFH&PF~98@t1BKWRz>4(n<}6<^Ur@_(rus_3BLAD5F$a@L*C=mrvb z6`r8a$DyIpTDv%(Bac8D9@u=z)FwkXn*z{FS<7D@B^9e&W=BMFu5(i+x^>2+B!dt(;!>N=z^YWj z2;s4l3(<WZmJ9TO>QQ4lW?m65(E$oc96V+E)J8fXU z{Ek#|f+n;`)JwWJCmQQDkPlDU2|3-zC6hvWKJ8ZI?k6N1ef#!cn+5tt>jAUtfrDk! zP9&@OcVk=t)8}yNb@XrFp7HwqRY;lC#xWPC`4?r+o0g{Q458w=#loMp@Q{KK6{n7I_U~1wu zt4E39ZDz($(S@|<$6p&4`b!Mq`S@=-vQ|@Qc0pB4_2H))6xyILodbJS*5xo7(%R47yCT8FEhb1p($Y|6<(V7u^u~zR-f??I(3d}}tJSaH z78GQ2RhF&`@O^vLfqwppqyb74IioY7(oya2`@6@)KY!?WK^!#W)n}NWFAws@erGzT z15C%J5T(+zW)~)wo&yH6+{U*@Fh7B&a)4;SVZFW*(bQuUo9P&+4D$8*>7zre*GNg2 zcwvj}9D%B`KPz2bJ)azrM)x^aO{hzXB39*M&XTNPaz0Y~_eamQ9}%L^9_xt3?wr0` z&SLOg2YsYnhl{6`QVswvLZhbGxTM(_8A&U)*B5cc2tNlmiw#EwI`Ny;z9k0LK5hEL z!P0qv%4;2(p76#~Y4MX3#P{g(g=-%a^)km@*-4_=6ETi!W1Cw!!!=l}oxYgz`bAWD z!=h)l2xS^2Ks~rjIV+b>#@d6bjD7b6as9zEvEWLf+Q}4AtVuTu|RNt}G8Oq?({J-L}Pf@1Sp8K5P7 za{sKN8%W4YmeP&uA*+r%MaiPs>=V{9Z2e90k8Gy|J3d=o-=&;Lsazz3)I9zvn(++!vi?s9qu+vl z+Vs|Xsr~a;olv6T`08)HRR~R;t7_jr#fW`7S_{|7O@lp?Q>@mj-zy;{QGb!c93&>{ zJH7d#1W|MNsH`;cRpZEQXy@STuxus;=Q@3<*uais8?_f&^k#+E{!HiORmO z)LHXQ(e^mYQ|e!$z+8dau$qE?6hp<>#GT2y`IG6gr)@Wwrri;G1`R0P1B$4c5+kkZ z!JF6eCO;>-$KUr)XDfg$j$~D|Cv=71=oBRHbjifgPVsf9Jwv(Nx$Xh~_EfcB!kkI} zhrx$OzVHEullIV%JSl&xPA7S@+8LGyRAkp8c}Fobq_NHBdLJ%jGG=^ynp$J@^8w?9 z(%iXcvCKb%QTaVq&z@(g#sCS3?g|KEFqkmnekiMA`txaL*ZR;O)mnRDVRBb<`%b}FN#1gR~dyysT+H{gV(;n>?jeDAy87nXetc-5*xW zEx+T8SOH4S--FS=gQYygFujkOJuoq!QGWIFlU~*ED83<)8?_V?qeNH0{eEe@Z**P5 zzx=u8A;~5n@?9kTe!^<4rG$NF(sQ}YyAZWq8vR2W{dC5#Rkwm(%Ldbt(R$fE6bl(7;2n_iRSm!M@nrvjsG*@~`y#o&^2WxyC%C`PxPLD@9^`npEM9NM%1Z6}hBaDX zXJt$X=uKr!DqmIUD7wfz==SBtd&qWl=bUnc`9uffd!zPh;XD>;DhhtZojF{z(RY{k zh_inxhdVl9!U($#oV1Q{E5s5O16#gl*D{+_%JmGh8(YXXT*+39sl2YH*LV7H{iy8m zMK(|S5zS}i1b6NeYgXk|hq8`cQ?H5nO4GrLx?a82I-RoDq}=_s#1dtmcWc*}lH(HA zqOr|#BNNf6E|vtX;gsBedH}>0{;t{Jn@h@1$u6$+nf9VsdN>~bdn^I=jEvgM!wTKq zjneQ_<}V7eoI8~eX4m!|S4eYr^U}WCl&1SYRj6eA-2KQewq&#ZlbNJbgGGu=^cGd; zpbWveD#(s(BmQg}0()?zJ+#(k^Cwb8v3i2ZJU^$X4kzhdH@b+Vc*Pb|uZKa+;p|~8 zhBQ~mRP)lh+tj|3yNVpy5BJ8Z5vOLg)74mBO$2M78-Njk=bUT%%`2>PL{9z{?zv>H zka@@VH#bF^zdcB8rdl7YDZUia0DcRmg6%EoWU^vu(>6TIP6gN_oF==K)T^77wpS+$ zSGZ-0XlN7fF&R82oj>CTdcfyed>MC%EF9$|m z`*z~k!0e{uZDr2Fktx8It@ER%qb8WOLS5S?nCXp7Scp-E&8Ux)cj~2`@$)*q{BAyM zmEm_*U;9|f`Y(hw)pb~SFA8F8uax}P3@W&ym+eyH-PHebPE-QJ`TMau3}q(H;;QSr zadVmMeq34ftCCr!@5H62DxPCb95rucZc6bJ$G^TU0$*4$IyUu6(n}x&ES2n3lnK^t z!tBcyX1{f<^ssC<#R#lZ3>vW_%ufk68J9_R%+@mAv&+*Lj zrGg$@UO0sw(LpC4r`~RIOp315h!5E_-JXlOH<^?mphs`gkq7=&Qi;Wo&?49~5q zm6y3mbI^m$CEDpun?L8$%^YC;QEat7xSOBXP*$^_uN0A^-$ZPTI;A9m6)pBuj&FTv zw~5x!I6`XbpJD={j%2&*pTz@tySFGM!Y3nZ&UdZ?Ur(&c_$G`H-lLT?hs!LlSQYSu zHM-oo`3W@>>8e$Hw@G{o*PnU|IFdp zVXY>h6XN3YvKR4L;msEN5LoS9R~XY~UB8=!8=Co)3K#|_6>QcPy|;FK2T$Pjvg}he z=YIc9x%tm!mjs-6JX@yQf?2M3&?c6_)(hIL5zTX3HEYJSd_OD%k}r#~jkE;h*^1uw zkAofNIX!u7^4vKXWqp6}Jwz=>{NYKvt*-iNC=#c5S(;YddT9-DbjB!u`xMoWm@r(RhtOx?qMJ4YUijQu(>5L#pyMZtgDVy zsv%D~PZvqml#hKb%0_ZSW39cYqFj|r!2=pIma~y+04BcLQ#Qq|93PSTL=YEc0Y9Mir+LXH;(GbT_!B2Zmn7l|72z# zM5UFxUWKTfxD_m`7KMiNXkN^1VQX_L({a0|g!}H!ia7#~Tn|)?kFa&ZMfcHaJo?ns zK2x;u4ldNkgV-+Rk!z%# z>Sp&|J9V4uM$WSUHrcerIBXtn?_|1^SrQnmlNR#&K|9Sgn4WYLv&g)3?%C9R;Y)N< zit>|C`|-;~9gdy6t!@MLZRXW4(X_iEtOAO}wXCo0JcHPzXTQ270Iyruw z#pf7SF>d>Ea9FClBopTPSLv}&AH8r{)YK;y=B#Ph_eI-1(@kG9;U;OtA&>poAy1eP zAK$#P>QV)wsrO=PCo0-kyL@v#skv$ZG-5`T_qJJFENyb8^V1VnuiI_m4DZxOn_HRh ztgnlhyT_WJ)Qfr!#g*HG*XZgX8y8>_k|10lgZT*dKaqjJ%JHj{z~&&rX31Jo{@BFi zSusWUo3Hhl)^&-uA}2dRwR$0owdC0>%ssXJj~}~jlRmW1F01>P*j>m)Ab zF*#bdsgkfe*Q)wsy%L?))yG}D?#OhPw&M8{MhEtghpg_GtUR#X&|C1!&c^b43Ct<) zn;BcJkJh*0A+JJG>)+yB4$Ufjot^vO!ZFe0^6%+(_9nH}PM6U<$A9@B1GLA(S>zL&-ksnbC_t}TxwxtMhsq~s{yeGmp?I#!64J_mTT#Cf&M- zIieonIH#_cuG}$mGOw$7eD3jFx|lB&vC1@-;^dyT9TZW%MBi8WeU7>?!@+fEXXa4f zzGa!9s+5`;*4QYFoRoLB16esjvOO0Nq;oCIW?+U5G+&CkHElmG>C?Ej@Db>@ms&_i z5DO3wW>^l642}I9`h6VYF_hTMyPOnf79RGxRbE*EsC%MW(+Ud<*0SOqTQwPdoq^wk-dAs{n|LdMlSwO^$t!Ax$!;-!| z*BbXx#bp_kcxX6h>WIah>Eg+NB>voJC{27__{zR}6(-iHlUfV^YKupM)RYro(P8`h zSpL$<0E??wZxqUyXsH=Q;$6me-vdHPAu$HBg#i72mj6sVOYH`U?%$ZK zf36iEeyqjZVM`xOYs=Fb`QgxU72g#lkxjOl1$>_v%kb~X&hHHSKZ#-fdF%T}{%$`8 zquL>X@qO24W@iBwp>x*C*c^=gaU^Wt!h@`9|S`t)A*@ z&XpU^r{YT=Mmg8STB!a+hbYQPKsQ{%%q=TPpyHf2w&{V?VqAabozv9;RYRC0-up zAP>(k7?gl@&wc{{aj>?riE>ixR5*V=_4Snvzq`BZ>FEIiizQm9GH88#pY<)@KNs{p z&yhBK6C#@2HrT@{nA7*^-J*@7q?BtBQB06bcGSDuNwmf-pg=n@M?v*=+vf#C_ zJ@^-BfK>Or-wSj73j~Pi;w)R(fd`i##`Hcvncy>%f~;<557n3zFrt#XK#ITp(yKr4k{&!3E_%aBT6g( z2@=yZM2(%kAa#!+*EAp&S5q<|h9R`*#kE?OvHk;#qmj`0eL3_a$9nQR5|&;V3{>;I zu>8uE%xdkXZkvX@w;tc}yk1k-BpAQJ9Ms!%sc3LV^x4d>T9Pe2i?>D0b z?(gze+X-dU*}fv*KeZEu+T*ET4EFaD62R*S!dtvQwV1Ry|`3d_Vu zVvE)B1c%S@PNRqd0E7yU!~)%^wf@5LWt($A#{-9h1ET*DuCPSzi;4}H1yJ$9~27+)M-09cAG!Kaf} zTi3QniSa=}MveNb6B%09R#in;`a?@XxNs@sV{5D1pm zhg|sj3~76u$a1}$_C+2BzyB$~d%s&Ste-6XwWa~}dsjVf*JwJYvGtpOs3qkjc@< z=Vy%m%jxoK)vKR`5m=tr?wH=e*Nx}`V}>(s6a7|E+!jLI8gWKB@QYNgRa=MDb zpp`~W$VC;Tw(_Y`r@7X>d&&1zTl_Bm=T9!Vhpmb6Sl4Vazb-L{XP$?np6qaxlh+qd z4uEQ(9~e0pA?fvJwvdWdbIsc-Ak5zPB3wTNaPf6Fy{aN~17S(GrJpBet(-1D%6%1s zz0hly4NoGYhVAdkni~o4sHlYXTYElnWo$bWk+te{!UvE$Z}y9_p*sPzf+RXkbg*L! z+$|99{pwn7-D$uC(9~4s9q<4E0HLL$gZE<6Ng8d+zyUeS{Y>F`r$_a{ugeJwKy&slUyr1+;`Og6Q)7U^U=%`u5yoiZY~M31NJs_0wg2W%K`qXg zd#>JBT2y#o$St($x8{ro;Oy@aWs`ICUtf&-Ba;Q5&NyG6;IfSmfH^GUqlDwT*jsr< z=kHdj7}mb7vZcBA6>s+_XlHZpu&|FKX_i32!;5YnMnep|_!b>I4nZZvdX1L(1}xY& zor$!985bF{O2{8&$Z9yMG2nmuj_cQ@sS|;IxSqlRD{=I(-QxGA{2xLASALd-ZsUR7 zztwRjCaPCHfk4aAf>}2n4>yT7hk}2`mM#bTgTYn0Z~Op+wtfQ7qcL2+eWeTl4-&`} z3i@58FPJF(;qOp#CGx?(=~PU8^A>;rAX3uC*?susJFUGd z(lo^-`*x%?r;K58vuyR4nu_Y~sBZk%>w($J$!OE;d#|Gt-&5T0`yG7OPD2Omw(?mI zzQ3~Zxad+mSze{R4#eWMe zd{B*6Hn#0IT7Am4_lcfd!32&Ne2$R`vJx_RrGDmb2T$->oxsyC#EQ< zZ)F1W@p|d=>O%@wCcO-eoV5ihRFAA z_YEJs&UygAsd@|1uBMsS&<4fK2QT@@K(IEV`a9k`&L3zo1c^52=vhl<`;3 z?ID!(+1<6D_N0w!4biv&$JKgu;i9m*S$2mokF=Z$97(hnePUL+_N`mnf=I3bC?|(I zuO$z2oK051__Vygqlf~2IMeXif$g%PfxY)K|J@wX99^gok)-!9A?`5KJG61?_s%n( zS{dwx>3^|?maI5@H0SgBjV>=F2;?G4#DSfdpRYu6?5SJnn^5O#tNZ27(9jStWT8Xq z+b<|br{}{62q^SAapdUNVZa2+rn_xO^*+Ib-?ff5fYmuG$0hbo29uso2rGP_X%b9c zQzym?E9FMmIq0zH>y7Zu{%R;arui&MSvL1;+O-C!}iZpe}4~*!w0Wv2}*B z=8FP?{zi0(qUl{Qsm%e*F~#2(pCF$vhWn!k?oV26bcCoPz~hfkA|k&;Q+=5>M=Y>q zmGv~M?Esd4G5o0O$sHA5!Cw))`SVR>`;)^fRJ6&{Dke~aF6zZS!n%Plut~G3zJ~qN z+{8b&R@lfpCvP*)6IS^(HJDPcyX`ZEw>Of%)&_T5$OG%9$#ga&;%>G5{%g_H!m$$e zO0Nz8BV7H63VAwY-intBn_mQGDrW7|?(M+`IM83@H7NBal=qKM2}QLR*-sZ45%*la z)UX(dS^S=+Bb?`kB?-0q;gDe?oV7_e zRcmqNp8U0hST2$8j5xG7ScnK6c(IHd?o6XrklQm=auF-!4Fq zytsL=ktg8a`W-YzwF#J)5fx?&TI}V|)s@I%DWidyFPW4ix*d%*0h!ry`x3-YYtmOS zbef5#8aDR2=7W|y38c2MHp?L<3!)^7DBp^k#3Xd- zcE^<(J4T9Kz`WSygX2&VD_EyghXnYaBvdwMmcIHYtxbGN-@~nD?bW7IHV##M$X$2A z=%{0cW4sIsSLFOv@!e+^4eX2VzbxUljnWG46jcZy(Z{=kLyzZyi!t)^O z4hy^0@_tcHAuQ-W=C|6g*PH0El4R~(zp$*0SLKkL6IVYR57oYi&So@QSiaO=p~Bxe zPMc|_r59~~Z1_6~V)=`iO4M649Ur|3f5TX8sZZQU

igjpiJwv z!h(Q(5JKVYP(Ipaz=J4^x~ZQr!039*xd-6gn$2b3oDIJr#J$QV;cmP!VA4(Xd44Q< zkFp(qclPJyaIUrMv2?B~PxMjL7V14A^ToQ)Gf;NnFbO6iJ7Zu+{=M`#>>i~5AMSw@ zP{Z-Z#-GRy!V_$Xc5ymeK<_YRIL@2vEn%^yn0y#9RVPJi+U~Ap{Y9#MDWT#@`E*zD zQAZE1!P_#PjtcKsFV=8bh&i^>D=BB3^~!zd+D5nwugp7MPneB4EKfJwsm~SHQXS8T z_IXtra$DWqq8Iih%*xKZHLm&wXJd@@JA&r##Hlv|hS(&Pu!96x-oD z8dsB1Hci~HyyCQT_15R2<*0YfrRvr$wClup=ZxnHvHdxwopAqbq zC|#bKQ?^!|$r<^8YakcnTqQeYeSLZP?ir5wL`@#IFEfvGCy`Ah?$_>JM}dJ=<4UXy z2hRuKn1a+mx1nL#Fjn1YD5!VV!r-RMn|>@&NH)&JIkzHoYqVE~?49Ib)wp+g+^C)y z>A4vtm&EXy%QsE-<}4((bRGu~#Cc+O`=TBPy!SklVEkCk#`w;AFlrj%-*DQl^65E5 z==|IVI7aFuTBQ1sc_o>|{wu8YI@FRYo@drnAs`c3-ZBAvV` zvk|v8JOQQ;sRDTta#f3c9onSla>OfKJSA=iCE8!iubW2#I^_; z9%fl{DuSg-nee_AX?Hl?v^qlsBqXVt_Q@h&gdsF|@qlLW)c(}@zVsVEm|Ye_nbJWu zbN%vN^90n4igI(AE;1Y{VsX#H%bp^P$#FC<1a- zJmoUb?@;bqXM=Zm)m9X#0EgNjlH5EM4I6P#Hqbu0sTm+Yqu-J1N{i5YlwY5&noQ=*cOg~b^Od5`>#Rba&hhyZaEY=jg9jGa>IJT^+9Z{`t}WdULH0_2(DX zS6zMN#|_4>PrrWjXLlMJrX&FZ`hl6R_g(jQ(3woQ{ri7?0mK*XHPQj5VKb_`Rd$GY zmK@(|u6t5~ul;AiSZ&t*o16@?yYUQn5vrZfQZAb(H_4pB*qo|!hi1IHjb$25I3lzP zk1ly&+LZ@;@PakVaUmLrEM~zoquH1guf=hMJDjfNiq4gsDY%x!HLmxPSvCY-J zs8QuHs-L?^I407)nc0ja)fG{=fYvo$JzKvDE+=pHR~$aH2RUfzjTzr{D&2EO0q5IiaZ{^s**5gg$eg?=AH-mz_Vq`{7Sn~t zYVXm0pQeu}OFd4voGTpH1|=}5-YC+zs)!~!I9GzvEand+W>ii*n$Gd%+?*fbG+G&C z58RZVD!;?bI_6@UvR$33D5=2sDO6@sxE|-n%pD4UmivBbz(?r?4+?N_u&O)vn#5E> z1OFU%~#cTWMn8^{wAfZ6>>kdp8l!!7GasUSYo;pXT?-5hiFL#SMxG{4MK9Ldhv)K)Pie;(hga+I+wzi@R-NxQ z2Ce#UGD_t9mvg&LXsQ0#av8BS<#X|p*T!<2#fo!s4C}tLlB(RUw)gC5uX#aG+aJ&p z?(Tse_cZ-#A~-gr7(IST?B_S-@>7VFG?(zZ${4gB0;!5jMx|FITU*mi^J)XnsC3vi z_U#bel8V_K^ysGPoK z4uMyB!}HdM?fk?&&45Y%o!okFb!n-u_w7m(y8+jsDccsq#I$<(&G+!DvuxznqW&WfQ zHbF(@d^b7ay_N=WCUe-@(Jv0_u%67lx^CuFV_%$&LMD3P%K6M(VA1-*EY_{<=PSC^ySkJ16Lsn4wD6s>78MBbwP-a!>-XD{qxQPjk;| zek@U&N5uI`L5A5!->mhrsMdP?NK)IKNmGw!3I&2!9czV=Q>KzG`tb1r9j5;uj%GIPw2yZ|!QR58^K)w{adhfD!8zH93>&6%p_HIkh2C0*Fx34!zIxGNQYi5I{ z%mJ)VoLYas6)g4Ky18mOmo1eR9wXVd8h{{{Sf^4B1V@#3W`LZh|e(?r{uahx&mzN@F zx^*#eekQ89Op@R!p;`jP=bmxbyN12c`)OAYupn&@KV3|T@@~T+z&hTtvXST0%;>fD zl^N+KLA;;m?CdzQHdAKL=7019dfM}0tb<>O%-FKYFyV$xFcvL?zsZuc%2fhtO%Zz2 z+=B{jOna4yZw z;#uhO^LkaZm{p^OP8*CYeY9s(eE_Z1b5{ks|)LUjeFP?jvZAAJ4q7n`c0V&-|6 zIu}C|02wlGd9x%+2d(9O4{C!$fEF?AAM+s@PIJ%I?qt3ADDs(1j5+BTq>%~B=+MNW zmV1qb>d(5K=ckSr&F_2n`wDO2Kq3X4xJCPsm$HRuaSF&^*thwHph584LF)Ar-BYli zA~xOeGhGM~!Qu|bDn2TtmiqPy7GAUaJCFQ|MTFXdPfNa2AtoUceC#bXii!;NgqKNr z`DHIJQ4|NVvK6hIwNNdo+UPkR1*txGXeSaBxrCo~S7SbZ8Dpo(%>ev8I`cDgI6Ev! z3aF;f#^jS2x&dW!KjXl5bnh%WGOQ!-PXMv@m!{vZOMDDko7J}aXc;J<`+dx(FFZSy zxj`9@8DOs0d7mCU|u0k zP4-Eg(x4c_%kDGlToPqTrL}WO5#QCPhur!EK`4t-ONA?!i-}V6)w8j03Kj!;PS5+3b!|^mB64(om~rJ(6K(72G=%DBv0QsrHapT`7P=}!$M^;lCBt?h zd{1l*h{T_n zGm%Sfx;A=_s z+AyC1EuMi>ya|2%x8{3G+t_OYt+z-ChKamoOd%!zFlkTe{m^{ z;i*W%lZngQ+F0T<3F-f!sI!PC7fi+teV-Y%GO7bxSsE5HFAxX$iOZ|BF%iUe$sF8a^J`n_dnv+ z?rQSmK7|;UH1!R-mafxx^&HJ0~Ugrha97y>C;>aL~!7b?(x z8thsKLdB|xTt}jML*K8Q*F}(3e_@F$gVRik!IUD+ZO#5a*AbSe2T!;bU!9B1wnHo0 z{bU2P}=c;lf%qCSVnJLRX zsyXJ2gohWem+}H@Ks=jPR5$3a_47X^z02j$x&QbO8!{XHt;L-pVHiW(Jz`!qi9sX) zdsa#r1rV;8f1QGjndx@KS`;@nJo|s6Bk#DNVi7)kz2IM>=MOTh+uTfl4h2jFY3Nyx zbW6<*96YHZ+);#GDYNKnqlDJjBm6KQyKUe|ab*u-2Ls9<{PJUhms5yb+J>bPpnf7%F)QzedE+`d+~N+gL#y|P3J z%BH!Hsw!2Ff5Gb551V$}9<{nQ+?JpUgiJ46d)6^9NQACgSNR*N;B?#R&n69$w@Gi{ zXKV5NQ2mU-cSHm^VssXU*it>th5_s|?9T69nN#(xc9Huk^pf7F>^obZwQy{Kh?7t# z*>NIW(xULD2U4QmSG%x?h*D@+BdfUc`zV|%ipdrmq@<~!fquBD(SLYIv5ek@HoyB( zY(SM33=h}m4BM1ak@;C}PbOA@#O6BrAnl-K;xXo@y9JvOQ4M>}x3?go8M!GFe21D& zrN`wXS#R&PY=;)WHAgIL>^Ip5GhSPqYt*=a#sl&J2^ge>>H_;nymOb*Dpd+4;`vGn~UFO zN6nX#foyHINdo(|l>^vCG34??_NroGc=)&m#}oqjZaGLQx(n40{)U!%drGA<=ODae ze#PYbQ{?S;&>*V5xZ^OsFlrqxDZ+_|WYhy*_4)ERBoGl94hoQ454Gs<4l~m#bP7L* zRgnQ}6bh6xeTciudNd$MY9)(X@YS^Gn-_V0KxjN$A^TG1i7|oxv#`vZL>2k0kL6)s zO?B^*$QvUz%@$ZZES`G+7+$b32{;}ti2<3E?qHm-R$5!A1)oqI@~!}5-rr;T^7~&e z+ov7Yw_t@DGComz6Kufdx3RH#7kEZ?kQUI;Qr!iZDiH+HP)pl=o<05%xaq%>b^}mQ z(qRtH7W=r?r8%SXYFkP(AW#o#{H0w^p#@Hjv}QPii%6^ugDfW&NuRosEPlZF!QS{k;IFXY5&C*{r))q^obQo;<_o1QeeRA-sH+FPAfLG2IRK+e1x(a@THR9z5a+t&ryV$vvW*nfG;c? zrH=7P6(HSi7GqBWl@WYV3nIeBN5p(n6Q+V*iN1C2u|V#?>{rzz>If3yz8B%7qaY;c z_WRM;5DAZlCY>LuWi^!%L^F#`5vJR!X+XVes5WjUEtYVI`VNFz#UX2*Pvi1bIN_q< zI);d)zwt%D_^}4RuMmMa7E*W0659k*nJE8DL+;~W*Oq1NfHgr>Kcc_$(DZ!(3+w}= zw6sxo34g3Pkw^oLD*%+f?CZNHp^lY|c#!?e-^RuDS5M3%34t}I&9d8{Z*WHDKsgql zyc|zALcSspztTQtbC^~bhUt>i0aA#~vI=T%$vcp6qpFR&NNI*STU8U`rRvP@{zk^B zvsFu{*|_GurNY}_ZPa`%F_O)^z@HDYUn|7$^pma6q%SFP$5LnSiBzV%Kr0^_g9Ixz z&}sT8FoO>U?b%h?=`$=;xyD^sL&>24_0c5u8kLh07Pyq*qb*Cx9auwdo38#rbjiuU z&l!2&TuB&Y7qJ^a2>K)P(;%hA2BX;{0S^>2ryK_IJI}ay186n2&Uh^>%!o@47fMUj zq79`)bRBwd3QO-t735Zgq+{614=874r=$Wwol3#WPeNjP$v_HKp@^A7blj6-3|pKE z*vx8PS}2fEDdRk*I3TbzPF>ni4&*-tZlsjXp75H+!~Aul`j1c1e}0@$0aKatRy3{K zD_FHT+d_HRFMCJ##3->awaxS>RmoSoER;O1@5yMKS8Fx#NO0?FW?0f$Vm)n%I+s@4 zZl5z+A;&Fajr)+X$hO8_)Z|%ora*yQj z*=3B_eReB$VZCllDF4%dELX({AAei|V#>oxxkF&sAa}(&Gs( z4wIEH7cmEY6ZNkjmx4kUO#YwY0-Unmgd6JO_nJEo;QI9GE_-P?W18UdhIfnGZ;+2B zoaG$1u8hKp6D3*H4l_+!z{cGos;j96e$97N+!LBXBjlJb3g(&UfJdp(D%e8Vd!1kL zkMm2Lm!*mmeQ#Abt&Y~7cxqg#nOWZbgOx!33Mo{&o%o&TQ$j9-Zl(%l=uE8Jp!hl?gtV=1~=@Mq^8UY|d`QX3yj*PSgdHg}6lVgC;EQLE+;|B`UP{ z(^GWY0u$xM(usF>&KK(keGh7UCGyFao>UCNetbE2p$Isl9`Q&EUFn}&g{U@uC^i+l zETA|y-e6X#1@A!1CEn%YHZmIjkfi{M)x!0?OZm^T|DQxS#axX&yZxzP>OHV=Ce>En zvgeiFIrI;aIW*XOo58L0CXWr&S(#B)yhigdQ?rqJemS7kR-H#Cg_R~l4_sX>hvU&m zR#(7_O_HN|7sv_YU4WHKFkytk*3_^4Bc*h6hRJEjl6yIVv*TA9Me;y`#V1>dkatpK zgJzzh08 z4p9(PO`WZb+|$J?eMOHo2^gFy*HG-%TgU3zu(RoPL8*=sDejLm0>M8>kGt_jA_kq4 z6%P`>1<_n9bto68dhN~6tBC>m2!y;X$_QHnIC7>B650}!jA;2j^pbgGck2!^A$JQ@ zB3l?3MH=Q}0*QJvPg`=w`;j_C3oFy(ve5ItGIBgZgwv zD3Jc~mHQtoVILK+qg=qNY7RFT5rc@l4 zL~865gk4uC?e0l`S-TtwgSxe5G2)R81tLl)ELc>K$q^y0Fw*domYAhg)5m1w%XQre znr;wdPgS|KZ-vtcCjK0M;0CH3s$2TP{JYu!J6fb74hnQg-{=ll3xZ-MkTk_t1kunn z_mB!Qbsb7|^QW)rcI!rlomAO=PFhKQ>9a(H@>3|yG%F6r!~`dsU2IU*jaw}*l8G9! zC$d-hVd>`YbEi&}mZ0UmYYXU3_-PHd!Uji_aA+E%_^W!+duk6fiAKX+g_hNzjcXAQ z;zB=z?J{eLh4bNwBayx!+zR7@+mzH7f;i8jUvrNu`)O;*is=%kF@;W@C#t!h{sh%!MR$hf9( z|M^Kc&6MUCu#TWM_~YG<(`||ssDz{-qBP7IGUgbDlyI$WA!+C$LywthXT`S#BuH-^ zD3+G9f1VrW5Hu?OVA(91mtL$Uz>tWVtEJNIb$p5E(!v<9+`~;w%v8cY`KyZ^s7VoW?X!xy6ch#zf!ngHaHf@{F-;Y)~@hB~4F5(Md zwKFPX@K}jz$HWKD;6dpX!?->DR9M?Mu0;#bpmI)IuTs|_JysD0*rfZGdbjLhTu^UW z^HwO`Aq>cGEQ*+9`ck%fDvp_ChJEUXBDIN;P@>O}qPgJU*-)^lb7SGRDV&Y0Xh@`r9(=m#KF&0ksu)|3iU;Y&w(G_iPZhd<+rj^g>L6m_Wt#` z5IikESYQ+zQdUuVm7MfbhuldLtZ5jfBC^Qc$rF`8rVM{8wY9V>A_s5>Dv7clTyu^; zwd$lGg$VKw6&)6X*-9Z@Pkl5B2ziIvRrn!t70`yj0 ze*Dp-?6DnnSIuAZf7YmO)E4W}Y@)%U#U&gR%`x|IBDeB(09~T&fkwxOo7~Aq4EDhT z38B+bNq*z0!uY{AWD26m!1gZi`tr=-*sd?XqI*r~?mzO)Y_7M)a&D z{%@LX;hyiBqK~m$ztGGg2MxSUVx@wQIZ|#2?b?rDC zLb3A)7c4kAxk#w=8a^b%qy}Sy490lq%<$2c4v}s@m_x?MK&V32yp~R(gZ|yUaq27% zC=>7#(_?&=X2yA2``k;eCS^DM_w;xsHM(x!}%$H+gcQVdJMVrOq!XXj18o+Ccvv^wY1 zeuIuJZXzsY9~*Jf5ehkPUb`0GZ*&V3ShE3p_1wIxjv}S(r}>kQ0)xgzjol|&JfQMR zm^i>6BvRtxHO1yPO7eyC6Kr$&2N2%jlJz;jjcjH=?(v?!U6l20Kc?nvW6sOX6Z9&MhFBm2iyD|ii8G`fLrTfz=coFMI`$wqtXKB{PF71(l zFcPZ5gWTRg;b0pa>z{~`G3ia19u%f6(D0@0jUQG+x+JJftz1uj%OK3gFgUl5gZe!< z&GM~bw{Z&!%9fb0b4dvFC7XMKn%yzqQ2lYXy5Z2kXPm3FU;Ide!x1)P(zT5AUE~%SC7?gd{@>9Ja-bZ{A0*X&1}A z1;vclEv@~gc??G&CjO!lm-pdGZ)*yXUtizJh6Q&@bx2sro(~Fy%9un!J!nz5jNi}T zqnPn*6+eJ1V(4(scbam&nRxLQIzT9-AWRWQxub5{jFSQlRUXx=rS2vXH!f}gj!`ea z(QJIGIB1~vJV$guS@O87`3B>v_xpm0NP*a%(k?*>I+@Uw(a zMSNIF*;q#d;TRuEpnZ5ahf%*X6xe7MPamj`+AMra|NJP$!ZWV0l)OJkti;?EtwGM+ zt#fzYs|4pO+_NZG>7PpD4h^Rzdk!MIjpyh^SdbXh6+5qP}kT3XM!(prvj>7cT6@G(7VCQVC&F-uv8x2WJv2%wzsl9OpQ4^xn4pd-U-tp8@( zpj-!p(PJ(K!YqDVSTSo>cZ6nt?e8$y2?+5n-GLalC+c3KF306z8n-J<-USZ>ZnI7Qei+)K=n0FgU`v05 z0HKG=|Jb*0jTN#R4eR13;nwBF!3i_$Ps^d+W*4t_nmWZAeV^4^rL!XO5!s9+xbJn*DLfvK;X;5LLE$*Z4teWawSui+ZOX= zK}jr}5W~T=+{A7YNCnN0U5Zd!##`!X!WLi%Ii!`YodOHFw;g| zNKotCKD^5fdw=Ip%bCpo!^7>ITX@FrQT&*jzn({!e+P@?#;Mc)fqbCfjL-E##E!@n z*XAD>L?D9gkPQ5vgFG$s%7V!n*m1{k9@9ao=HaJ}niaS^Py0(Usoq9)C|-6br^T395aXc*91~U|_D;!|5SQhe3Ayw9x9>v3ge@2XQ7tL?iB7fuSVDrFb74?UZekZws z^H)Z2Y08DQ`@NO>WdBOcr5*pA^#^=U-zDED0^hC32n}woEBGq;05eFl83>)O{>3>$ z{41G-A&~zM61owj{FOeI6XZ2*$GszTKSEi7_y$_fM zlzKr7rkiz9!@hR_?$FA)@g5BXMP!)qs08z*<7MG1f=kYPbxnnd zL}>o%v-Z$D*E)Oow};;KafgRvi!Sm9WBMBdBvv3Gqbqm(+e`da6P@25|sD z2t(jIcBUN)^@YE|f896MnWW};_Yj^KlZ3X-K_4pZy*9zPx-A9nWW?-Rk1JpL@({={ zel-!CW$^tKP#%L6-yUa^E-|@`1A-1DyrbK6m}=98BUw^hD!DiCt+|3Lj1!>sjpp(Zl8Nm;R4Yckullhr-;p9px+ z6g@r;xp`L^V~R&4>Dg=`y+!D%n!tOhRL&#=*}tvvoZ!&teJh{+2@@V@xbV4z8U0}o zlX{f->)rg6@2!Z2DPo&4ntk7p=!Em({MPIZOLUOq-*n(Le4`p_)b)HwT@?P$zH<}vK5sX^A7)%Hs?N{43eX)X0sPHLsf6&H!^<2*} zH2`R^&R>Oo789`-=Ey=H#muvNP)6WbI~~!dPjvXL+QxattQM#3!hbnB7nm-@7956~ zFE4Xz`=A`EI*g*?5M^6z(U#(Eh`{TfMy#fC$klA&FpEm^$tzeM@^#m-wU9FQJ>@`z zRS!%tKfu?yj_8w7 z&q*?bguScT#n}hcqezrYy?oi4Ok^{bD@S*6HfmPudOwi^(j-az=?+n$XXImC9f?+x zilcnW2uZ>t+RfoExcDxV|G^8@!8q3fp8ImxI>&3S0VyjrDlJQTEy%vK~87~+7 zrlcURMl1x*X5EE0KW;`&*yyWCG{({&q($-SXh=|3d;d-S|7->sKy$AUi)spo^pbm( zQFTtJ51D$K`P@aU+&y)l9gVJmy^ci@1h6rb(1K561OlWKxVCfmPC!8RZS?DA1&Z-= zX&nOyEk>|C`I*KIGUd2jEOpq|g-S z3GoZ;GD$AY{C>9raWw$0iF#o!rEZUhgLjOrzXw_2)~eyU>6hH2(%m=t=FQ%V&}6pG zt%)FPG7?&^RjaRSz;{+lacL`V{&@!;2LY;DrXH@|3=SlnZKyX@GG}I~2KD%?i~;Uc zhBewP6HXLlu|x?i7X}I{)WZ(~G<%nFi-u}T%Hb^q(vPwZlg;vNRIUpmGFfmij%W#J z(cE_G$NE1<<~idn8z(2-HIKE=fib@KQ1D`*;#))ENcYezg@j^4q-`pQAh%v6}I3Q}(T!n^(W9vbyt%^&M>oD|LUX42#x~T!e-x)+=MXGEos9XMS{QZ#~5Z7s3b}D)X3C4S6?A-EK8XcRgxcxcHPJeiQ`}AJZPRajO%OO7W ztJN3f1U|om>W#Azx~Urr<06|I$tn-I@CEyj_ za6ZW;hdKGSlM~rzqiWBNm&l99XN?y2E8=%olUYMACMX6;&h+8`ua=+4TuO>Oi(tw zF~xJRHm0ef(TEqubK`CVw+pu?J3xNWa~B*2Bv4}B&9X4_M6@`a*yQXKrONTeBX4lh zrjD1(GEISyfr4ajnXB>NiV-+c_rK{a#l;@OqK{X-V?vfHOImFS9we%_V5yiS;i2@0 zuzCjV)#-1G_7)AL`$+9iMsq6?bDIe<)PW1Kspa{@LXNhz81e=->&B`a?AHjujZ3Dz zr2baI4qL8TKx!$yVmzbk0hHfky-w$+;Qjo+j{qfq|(N&*b%z5^&ED@+wD*+=x| z&+4N|!tVw~{SKR5mlF8x6zGX-2b__dFY#n;;MLf-XXWpC4+1#3*Oe^St!*#}_W$k`N`fkMBt<64twu6@@pQ>(FV( zOVeDlgk+-jQOqC$4yIHLx}fzH@$#i9NKm0&nC4q$o5<6Syo=gz(egM<&~qzga5LqP zj8Orde<)vmQa}R_PrO3L-*EV%Y#UNlN84F_GqXvKA7WY%Eh9KHXkMD?R~(5s2Xriw4GKC#}DC1y2W=zBz)>U;+N;& zmbi`!Wn-PGiFm#GaRXI^i*beBmP&P^)BMus#hrfFr+er_H+lfqUw_~_AKpTa_zv=c zVZJpS7WipBXUj&_aKo@jF6Sb5I}HG0=M%L3`yZ4)_={!_zf2DtNf0k#jbMx?an3i? zhNC&PKUp>VynGMwxW~!3X~K{&sD=+z`+7MeTGW#MeR$v!$=Ph+eQK;2ziR7~&ULdh z2BgaYlvEQffAdG>e|%q}D#c4OgmBl_n<+y+C{Dy|JTqZ=h99+WJJ9Ai+!o~R5kLm? z4lV5ly_ok^y<1)>(UK|!vGtF$TSHdlaiFWO#Hn(VQoAQkJX~$IjPw8<=EWX{0WOOw zV#XQ9RmE^Po5GHd?-ek_f4&^3XiQ4^fsBb0&E|N5O}3lkm2X^4bas_%AW=_D45QRL zY(d47eMfs(L})78msMhon}|unL&&N56CCQBNwRscD>u)9BxxZ$GO=gp1D(Vp!|vN` zZWmUbrbhG^6fc%`$0CC+)ZO7o}egOJe z0ugyiG?R0DOOOfBGsSXZtX;)c0P^PSMgJ`pg+gB z%^r&uX`C@^+D!^YT6^sy5J1dbgxf{<0X5uEudc#h0X0+ic-AlX?BRashj$*{(-CNI z2jLK^zhDNQleTfq;*QoA-&4E}j z=F?HiKaf9=dd>Px>18huT9xeYM1dSq07ka&Zb*A6yqTQ$Umb&(47>hDRquVe4pXx%{r+|wU)7l)iPtcC7Z+0P>x<+-*Kyp3L+#XB zs*cps`bnVpNU`FgZ^uiKVRyZLtdHI(v^Ha=1(~D#zS4|POZouxNu*A-Exfn;LV`(% zF3tZvZCWk2e@x2IDl3fB(JytbCtWXOu;GP7m8I@5OUr;S-`4G-(--?7OKqD?aCu11 zTR1+huNt3|X0du>cBT6{LqFoDpi)&#(y!jFG^y|;?vNt(H`6hCoKG3~=zK+i7`L$% zLpzOUmB$FvH2}tCOy7m+an$l_`8Hg-na_x0s*%%X;}h#D#Cr(T4UQh@lCqGm;BM;C z;3QwStF;Js!v;;FD*u8kBjQZ?bJEd9UpgMo+Kq_O@~5ze;|*C0sa+;{XAYZ<{p8ce z9_F7hZ4FjVas&RGmozlyLWVKVzEb?gkx{2kzl}Q*L*4X+5;(h$Ev1dYf9-adKs2xC zYTjYdBu$Ta$XMInjhSTHEdlDw3(CuUtrLZoe|4E2ed2{IP7KHL&Pr+Y&*tmeQQlg8 zYF8}cjbw5M(-S-mf^E0n$ri4M36jnC8vm|D(ctuKHB&2=Zzv(RmJ=L898 z^TV2c6z4pPF-W~I6YeeJAR(F^Achnp>@ZA?yTVg|V#`$6?5gy9L- zwf@bH)r-HaQ<+}bu@aW`ef3nDRl{5GGVFlr${PC!fRO)6M#TkpkU1rzx*Aj8_6;e-wDmnDGCih}zryPJW#X(27;Hz_UCDSE$ zYZl__WOLBhd-AY9+q<{>_b1xs{)d%ggGOJZyXu!8fldJAeC=p-n=IbF1qM6;OmT-sT zr`q2A?^tX|_~xR?XtNBOlY{Pdt_;_`i(@PHBRIouEuonPYSu)H1a zrj&?Ght-B(5(LJm{YO(9#Xslo>Nz< z1wn&;lvio;UQE&VU1A|TsjZYW?N)b`*~V8aXDn1#n@VRiuEu+U*eFhEL642|u;7z2 zXrAd!WNp%smxToW*wJ6K!UJ@_c3kzLf#++R`NK4Y_9cw5*Zp&)xw+j!sq%b@i2Dp7 zFRxj3Eb=YI{O;$^i{+!Z)-~8!G=jJDrOaue|DS*2gfh-b*A)X)n<4JWjS7$+Cp{N(}B9JxqWzEwTxQRE&07Nl3b%3 z>Y{w4J3@2_x8ZUNXHFM1`cdxtJ}qXqey`GZzJUQWVU@di{`tHeYoV>7&B;^yu1FQv74Wv}iX<%v$d`UgXG@q&qxDK0KnIh&y$g70Ix207xQ~& z*3W$FN6`8l#wY`|nvH3C?UZM1H+Ei1MT^c+Iw|7;tsUvS!$;Y|C?PeGmEExc>x-Y& z-&J{ghi+eU>ldvB)GN~aL(xXDx163UzD-h7K;Oe?_4qqNeOkuF0s^Rg9GxSqG=~n7 zxF-O>s3XsF>pVP%c$Rws^|sPXG^X#q%zXM$3h_q^rVTeYSX)80-=!yQ&a>J_62p?j8}BsTc<)T)?@ z#@L6uh`I$G$efgL-up^?(`o%Tf!oAum27QUIn#~M)v)i=AET7rU$>f}1B%R_@R}gcjJanjqRg z!@p5$)&w$@u0KUuYtw#O{4|~*ts-Hg-nZaX;DbCLTY^mv9bn1Yy)4;>97z^DG&*@I zT;OL!3Fer?sx|Qm>7BkPdY{0 z=_}p8Ep_R3DD_Fkv7DK*@8yF3Aoqt%jyz>gb5?lK&*PQN4L3>cCiP2ExBu*lIq7ex zm+~__3(~^>SpA;fgHD`z^E+C`QQ2_YZe1t1T!#x4 z@4Oxu{TEv+Sd&ZQtl;!3p_sEq8a~Cvz-3d#3O+|GNZ1eUZN}~Kr)`}j zvPu|!m8&ysYE$<*MQp5z31p#kLI#l!J=;^$h$H07epS`deAnqk*#Gbi?r<450Ag3? zRkQLgAt^(fSc{8|Pkewm6t>6G4^jl4L|_o<(*^G1Vh$^ZpO{aCYvBd1 z)ytISV$C7cG=73OSbi{6=0hzhL}zzSsL_*I`t>Uo^5`kW*?g#+%vtN~#Ej3sz?PQA zETcuM2)_ZdBi>SH0ljU6CKNyZIAa_DwYUsrSFv_!UCrO68;;rP{sQOlEND26b`O94 zH@{ZI&uhL2$>pX7x%LYEU^DTpxwv3(<(--moY%#$9J1&H-lxWBkr>^UP;mnyy5>1_ zI}3u%{vrAvte1u@aaCg|j4xux#o6;BE)OsnhX54elP){4VM$)r z^aBvIR8`_kBlK_U%8729jL_VOmrBXtQjM!sDoUY=YOTty?w zq@hfKB!)2b6%y`bK-Qfi`+iew+{R*|7a9&TW#oA0Qc~-lgu8eBA^E2mSVSpM<2mLu zz)OBG8n#EBL9viT1dz^NMj7wB11S=O_hFuOBy%FOmeswIteNm|BRfQ{5PpO zQoZSsYBITC98~1sTP)4mt>dfEYq8K^Rk_CgCH$HSy_iEw&F($c0()U$K%q2C-QSvm zeKr7Kq+g&3spo9Yg1?q@M#Y>Qwa!2rbN=6(3tec2L5Y z)skAZD&iua2?cpraE@7`r{bQwU&s_L1CXJrzRmZD_Y4iC_WPSOwkw+-lA@aXGI|+= zzn}v3^05h&8e65@=5pu*FSAkcFV`tIZPv|ZWkdCTR7i1DUJ~#*R-Mxb|7ml(7FLcQ zq)bAR|L8kX$}$JaCzMNq_*Nx>=J5rn0y5EvYj`=DC@B_%;h)Jp>?H@g8c9uKsPOD< zBep_LGE5EnBrqQkVIh9XVK&b%56^hF@ba;R8k(s&QP5DGxi<^g$ z&}J6q4xx2+&|Db*~~#vjT`sf~QBK%=5(^YUo2+$Oy5z_1e|yu@Cikls*6M$0KyI zDy_5n(rtREk=Gc-zKZWg;_FUt7Rx|}l8<8{5!;{(7}?v|%-zaUug#{V>3~v>LznNh zwxm?e$f5b|cK;o<*~ACAnLI`sC!_jN+`GwE z%;Norm+sKzNQtHQFD7jcd%yZJnU<|aSWAjhs2uNhl2<|mZ~9X@9OYTN=ah%8qK175 zy!-GcrISTmYwiUj4ZFeI(o`v1qVzNOkj}m&@=L;1USV>5*LMeCULz7f=A)>pKtNSX z$q*t?#b8j-i9mMQf7Vfd+k=wsJ++Mi+{rf}LIcW|v%2Gj5u#%nC)3^t0H{--+*DWx z%wkeRUGD9PUF5ITr^ln5wtk(Y`CZQqod^4Me|JDD#(PJ^uz?qp#&EkY-Nr#AUwvNp z+wk^0a8(5Ic+A=2D9U-v8M~DM7Zj2lyVvow@ID-rGocPnms>O)T|9t)dd%9o->ecj)>1OHj;mBX&Pwi{0Hb^LWH~J?8 z!rlyOwNi}G0Q@7qnsjR`lQr!Y#qsttfe9H0(oOGBCCl^z3ty@$-i67!3s?TX_~w3sNMx`gj)a zp>Q#gd1^A-Gnta0C_bd?uf>P;2n=%QoNh(s zJ=Npl@&thF9;Z@#K;);+&+iruo)Gdl{u`d?iwGxiCry!}3#vi!Xap|0bWLs2Pw^YWyRb_OJil z@e_8KdPU|zE1MbZf1YM;u6Su5)-Fqs^!xsvXZ>N|K}Wt`0wwk?D2FZU+Xw|a>(F1N z)%Bp9=8g|a2xKX;jjwGxbL+@2C*1w3uOztu5Hg-!&O>-i+Ed^^M8eOr33rMrW?A^f z{LS`vS$_mGa$qy-3(S`%yW>3Sz`SU3dw(`S#hg>8LkDO)W3-Kh_NYX39R{5rWcAgh z(LE_V3a-=pOx^B{3g(m{cT7ajso+Hclg zJ#&GUtuCUP&uO?8{aduWMSNK66mOG>K{XX#e1=>&e#mQ4-}DqiUE_SaCn?Cq1Qy5W z>H~h>eB*_Q@KWnWPLxq@%fnQ>wji&U%!3ghog3ju(=OK}-(ZGtn)N>UmbY^$e}#K? zq1>13sM&sy@!(8oEsjE(`Ow;7r&cnnRrdXf8E~$zZCf-I`d~%JNI!cT^S;rwKMM^V z@i5x=XwCHO!v<$ZO}B}va8_K*pXeV-{-;Idj950_#1Me=&r?4s`s9sWNtA%E<3e&C zE*m0L&B#Xne`WIt3}fZ7@=Oi0ueW zX!32Wp)x*1ciq6hm$forr@-}>2h1N!+Yu}tm*s`AF6%-(IE78Z~aK= zguh25*>N`M_kq-0?sWZtpOb1L5co7A&P0ufDxgxoFRw-+2oEE&YpFIg7fckua>zR8 z0s7SpYntU@_RQ5`0m_@T!WX0vDr<3<&gChjI9%h#99+vVXm z-S$?az#@nrO5Wo{V@Bcn$M`CebE$g51Bdmq35!4g)6aHL2> zKsLcXzpGI;G5HsSM(nr7+7ja@q2rzj(QjAbm`2TYZMSK3yzpbd;sF=pu4!OA6`jkW z#2L1y*In|IKaaSPu&w6rXxu}t4hnfLob=&9htOp>mW zpX8cQ^dyhbrz4u2hQ@|jZ+JjaRa1vH9Eygoc{#CRTq2N>vgOLDEZ8|D1yNXG1Wp4W zIcob7^F4t8nT(i!xv78Gq78=>_r(}%z`0V`5RBaArYo0fx9u3F(L)QRRr`)-FYdqq zbb95oSz?GMilUEgE!B$X4dx;BaR9V)CtbBq|(#}36Vv4tNAYait zyft;trB1)avl+B{OgISyd8kDU!1SM3e+uhcGxNXmb$E`^mhtl1S#qT%YdvqWD`V?( zyoSIEaOD%C3PVnxC)inO8sxA?&9{g`FswzAJ2%l?u#{-m&Ax^076}AXugh%or6@O3 zu>hz}e7Y33O*ly(yU~e8)$%`pE;C}G%tufNcfNsHzMtkhUR=%0%p4u7`;708*rOOe z?Tv-SVPrXR&s#gshoM`&^S~Iz4y)yCS+_ZU8lBXI00KlzY#ByBFz3+{Ngz^a*+@+C z@i<;Q7csPO%R=|y+be}hty^Afx0LGf6@3WKuX2NC1LcNof_jUizKfUr;U ziG!-m&%*m)+|UF~>YD8;`*Au;Ncc6)pyPU{-G2%*%en^X@6Zj`xh0?1$pOmKSMn_h zrum~XcNAulO%*ycjqip3*dTzfg%6{HNJ^Q-cNuI}1R}|QaBmO6TU!wr%0y=j(vrEgDsX@fO}U#WJF3b z%r~m9`Nmx6=6YZohH__^{Xq$y6axx&5yXUYJhyAdg=#e!u)@vmFSf^p9&Nq6_{^2k zv9#@)3N!cn1={7kRSPq0VI-O)K95xg$&S&#vP9bq4bnlT6zUeH*vIwKWoQlQB|t0z>ZZ|c#v)^?@Y8;Ol5+7S%+7-dPDq)PhF+nS zJS};{bGFyImDqIW=d$pm&%cJ*ZL4dH-t0;RJE20Nv}uMdPFoG)eG=%UF}=^H9csqK zy|cKGnbX*?Q$_-l6|2mI_3RssZ8>Y!zhlZ~UAXsr!5!`y0#ettZ*L{(@ZeN1H$q`#V~q{!TD3#@8 zyx~L2Y^U`nrQqU2O)4gBy(7I;z9j|aJa4|_E|2p^po-=F&$CU<^78gx_r28vG~2wc zn_UmpD>K(kMBqs|xQVJDZndO#?f+n>&%t%0+AdLzU!Eupt0XFOS9&qm;UFhAkR*J5 ziIbIxtIg>{6w$q268AY?X9~r(`$;eBvy;)%?x1`ZFE&8QP= zx6A0T;_Q(#8p%ns!_eY}UDN*4ccX^+%{tuc_rz$$5%mRC)7iJ*frki({$2GZlOeW~#$OpUFCxIx+TwA+gKwmdo6h%MJ2qhRk)|PgdXgk{sBs?x7%n%rAM` zynTzKkO`8XH|tmd!3PCJl=cRNjB9A$xa-HUNR#S~JELDsNj|U~# z%6oTePUrD~cJ7DSjT&vPI~!XLMALeMW#>WCoyGdzL&|rA1$Uto2bB!d(+78*d%s5@ zfnJ%gXjOWi9*6jRrKA~`D*2Qh)soA6MXK`-k>ry(6l5J`~YCZ2D%;77JhTm3ERb2TG^oG>Z(7<%XES@=4`T(U6t7YdLbsTBArY!s35$K#T) zTwH4tv9_Yr&J}+QOR)qxyXq{6_3Zdbd{+xVx11!l#;qTo2{buPLco)cd2Qnr8eclX zBFDfY=3RPu;?fD|6iNFR+3>lKtVDHIX44xc6r=3VzvU66pv9YqQO|1V{vNkVYyk&qnQSU%0oe@PW=Y1RwF_UGaPib zFzf3_waa@4Oi~VN7Mx%Z_7FrRlj!q%J~R-1*vor!BO2{j^Db?X-uw%QOaD&ao5>oe zu}ho7XbwC=?6wi$D^EKKrNTpcv$P6o1`OF;${O*Cnw5b2_pdxTnp6f}6~BIWAp)J_ z^unEj7J;z|vzEVjk^Kxa9PG+spKDYF5|-DYJ@1*@7K8JUvAiEC9Res-2@I;(*bjNH zZ6rKP9RKF!kuPzJeR$_85r&4fGzy!yX>waY|3V@cAVtmeA#7@U+*TEPM|Q7dJ+R1H zzMLM3Q%cy@QNOvnN@UV!lCI?GUd--a@SrXhU*lYJRuTWdFK}Y28y~FL9MK2txpudT$Yy z>O##)qJ8J_AVQjm>udkQpd~%hn0>I)@W-it2jz|TT3o8y{G9Le*5;0EUuW!yS;;gVju-y z?aKw`#w>1_ZX{ir^95x>snBBS#8QN0TF>H3Nfxdl!bh)2(@3%B8ts&aPN9~ssLgR$ zPp7Xhr@D<0Z_$>s663L}%Ihye#|NSZji1yK^gEmW3e% z%|5^0n6b~#OTP=bf$`BoVh9mqV`DqJV_ojusNY~=otxuj^2%3(ZIndc<3sj^p^|8Z zqEv?IRcmdilMdcndhtzfpvn|M&v|PB2`_Yl=WFow{&EI1jiaZ9&3^op#2RnbOUrJS z&3j4xERWX#6v3;Bqm$PRCWe8sjmH-N@Lc!%e7|zZ?m+4F^XWu({H1X% zqP0SB>8y|0?|h8VCfa_W{woA#5L{yMzuIJljx@Xn7m z3I82od5cj&e3$40|1fpt8e1~OG<-PaLjZb*!r$%kpu3HC6BNOZdTXk_g|q$-+y3vv z2_(T6DR;v2nSDGakgqd@b68RCHy`EeuS;F$;f|k#X zP9W6Do;|5hp1Fz|K12ZYwtdEhK0Wpg@oM`IB5jtI#|R3yc7@B|#W-TlC*%Gvm;Nq_ z{7L(k{&zhLD|d#US%Xl$Sd3U~@r3TT;)tL3q?}jZy^VY90j$0Pn%{lKp%|Dw7rF3) zJTHeGFE+3+@TdH*rNXT93P2}>yUUNeBjnwOuPmz;k-=EZ5CD3*hJ8lieEz`sH#=)^gE^WG5^9wLE6UMr7b<+D1)=D2IxiG$n+bS{C*Ulew(-FeY- z1S`VxqoVMm?Gn)fWHLH!|59w9LpMS31K|!)5XCGq1m9<-@6Dn`makid&R1|)k@K^& zoZ%^>ZyMg~`e3$<6&nuxxlv00wc`&l!{gGtMOB;%vDPO} zE%P#&6vgtmHxp%Z2y2w;peZit^>9nK(OC9ndo}KV%jYty4CTfDbyASN1rNJe5`OfZ z-;~CB@$d5G#Mix>*;#_r@|$0>at4p8So+~;pjdzHdJ}ID-wgSfD~)5zid8NOpTkc@ zsfK~@&FDMJRe;X#pQ+b|3%`y~p=RM%c@eP~G=KkW&JYxM@+WG4HupI`9Of2?i<~zG z1!&@b!ta$$NkJj-cvM@aQTbM)ZMT^bG<_W+$LhG|?L^@nJ4HCfF4v}lg6b8`%!KOS zSN6e^UK#$6_Hjjm$AmzI3J*^6+cQRmoIxj!IK`5dYxqnE!T*<=q1u2osIavFbp2cI3)g{DLNL;MGzIN~|04y$O) z)f+_D{}81f!jimAH>ry-qBpay>25O`*uA$ef>6W23IE@RRoKGoIC|$**#F&XV6*tN z(1VC2+-i8PG1G7s-|)pY)ZpnXun&dV!#4c+J@2I!~T(ouKfp1CjqzS$LvQjpe=uvEpk>dO7C9P5TfRl%a3YA-(=+j2w6aeK?kI zjp2FHCb2WYd;j+ zjc_kf9R*o&s~v@4@u zyz;pU*XDb==JIUfzMLH-&$>-{0OOa?lU$}4fXpU!iZmwFobVz4_@A`V#p(Gg%#lrN?o|W@L`Vap#-8ytgN!J&* zI0p)k9%#NJWJ0&vyd^(b>P$@(>rPM0>78$kFRcG!AUYg6Px&3VXJ(7nxQOOt_d-XF zk1&~S-Z%C4SBTkG4GOrqEKH1l#9kyY7d2QFuft9f2 z^9irf3M2k4rxGIeTbK`3%%}h9DdVQ|Oq2cGd+bio;#U!q_ShVqRm1TFq9 zA)7{%?c5D9U$kBN87IU!Zlj%--YG85G#T5|b;T^9e}^_H&Z{T3g#L=5OtP!mwgcZD zQWTPZZP&0}!>}FKx9Wwhm8{Y8$}rSa|Ap}KRcI3Xie=CS)6-o20IC=_<)Dexfd8r7 zQJtCYz2})or6eOMtqizc{Ca#4qNPRuZTUKJgoFz8zs%|Ts+agryTwJL)4rS4D)FJ) zx=rUy8NWjS4(XN`f9^71MJ;k3uH4#w%J=~Q6d@S*o?2z<@QKPtY7XADYd-yoV)~bd z7bK3_F0riKu12>x4!gwG)BxZprsbzUNB5bm4PNZ|tK66hR!j8v>@wLl+WjM1yMsLg zYl!EQlg@Hdq8dJ?(V@m3Pc02YC}Fa37gfpIBMY zf0Ql-feLhImaSYhXJ}C|tJ3xj(-=PQ`js|%Y62TJG`#Wj=vjkhU#bJ^VVcIxn4-TO z3YIIF$NhjH(eF8_SwW`8G#M!Ieel_K^JYN;;tlQe?cK~}ozMx1kaV3=BdJiJx-L0k z#%l`=(p4j(@;-xaeYb7WZsJH_uQiioXmmWO@WRRvD(Q$gHRCI)$e>rl?+&erV zpt7_vA7xFzKuzf%1)$noac;MbP6RNZ3phT$!oue?NigZ{rTfG(i|xGx%nG744;WEP zz^`KdFD^9UgN4wfE3Bi&ifUkq#~D*Befx}j5TPO8#Zpy4=b9~CC2zv#%BI0mS5QIW zE~lNjh9V*$T>lW}T0-t^M(E8gMP?MQY4fmGY`i#FBUWzz<8z#emm2_|{A z`Nw~6>Ghxh5ri2jMiZ(6OpN_M1pEmw$oA+?#7oMF&ocEcR~C_V!Yi)E4u{BE_0#zu zQ2Oe^!e)PDj{UNvM!msv+hI7Os%gyV7sM4Gm^-=C*M8xa(ANL z1*foclm7hzez?@=h>BI1YibxMvV7y{S$@O%X1kA`)zQ9qve5mKKXYL^I4C z-+xMZTBJjPfY(Hdvi=?h3s|RoY(NT_m6{L3u2>{dOdp$%Ky7ya{+y+op6rK3>O$Oo zkO{xK`Jcjj_kRlS-iD@I6!PVc?D=0c?KS#kV;c?v9$H7Gl%~tpo-_p#5TNd3K)wS3 z{5%;unXIq$dH5zN42YyZjS@$Og2Znip>%E@8vz0kvpapM^}Xs1)Q43skW+^75pB00 z2wDlBkzIXXj|z~C)bVIbF&Z&>g2faCa>Uq~-V&%69KKK5k(sA+zMS4WtYwWexQ@l#W#2*mCrGF-M7=VE{0A9Nk zSx}eQr;}KEf-CB6FiJLZVR?&aTH}46Dj3nk-0{vi)sFuR%liumDd(}iZC-T}Y^e{W zQ)HCr+njzC3eQa9i*wk)viL$ZhWi?^>Mx@YfycTq*voQL#9CE%F_@DZ{-i2hw@oc}=XU8dIgoyL#SuUPRMzsW$d4D5F9e_Q8ZnD4Rf@=bjTiaotj zVSzAF2Zy#Wr*`!$XU@c7U8#4CkarJ$8sdw6-=E3>WZ6}h43ZU_aMfaF&O^ijoj+Tk+g*$F37AbkwFBv7OdyrP@IORkNsb)1d{BRs&Y zx|gTJ;zacSFncV*w+iM-ZOiCir%kdNV|hpJSu01D(BNy%%%cecQClvsQ<;AAN!z?% z8RDH-BkkZ$O10AO?0ENpq;9$XXy;p7nszVk}1 zO-{xI?y^z4j?)N+O@i1D>X={!FU%Y=5XL{EgM5ElIBr;`K!JX*JEBcbi2;yLq&QZ= zT^o|4!1(iPws7i6PSipMGv)*ueA(RZv%8?BtOn5ycH;$0_Ex3sU0fEBxCVI#GgRbc zUU}K%u57K_H}e&Ou>v7tpo(A3WmD3{>(bL~=&l2wuol_zjq=)_ zd`N*Fk?tBM=nbxJW$lc8i2~~%OUKz`SHttTrtvKyD6w=hgadp_M3a148X*^`TFN94 zuSi)?OQ0-QvzVTsCi!n0l$wQ+yOzgi6WSyV{KVqux@)%ud3Hau*Ioa((BJqtGxwtYQv4^%l+HMX@g;I-Lc?! zI%s*&=Zte94$2;7Ybs2RcR}#c$t1St0G4?*jOZ_z`K0zv=#+K}HW{5zz>*Krhg4gq z2b9^3A+@CQSw9Qz$={@knH2Wbv1)xs|0DeQ5AFt!4*D1XOP$Cm=8Eg1=n?<4h!l>u z)V66Ai4=&)4C#@1Cs`V0tYpFiHQ_ZbE67PKLOr<5$RzX{)Ir2e`2!!&C%Z=m?-$Np z*hEc?6$|I^ROL*hURCgwvS%;b4)x9@3_MX^@Ld?4ZA5KkJ+ zr}_XLw$t*cT&>GA*@JrL09^!YiEy36>gs_NxR(Mtuo3*8lz+k5lu(o|yNayRL>sk3gJ+=(8c(|ouKahJ(R-mgHsZLZnw z8(QOMed}vYE7x{8J+ueo#jy|@PT8bA@e#BnL_JU_9Dui&J1$aapWcM~7)Z?_o-&-@ zEpz>A8->>T<15n7OP3Suo#pb>=wjB=^VESn<|z`21*5toS=i`TQag?5cq6h42yweP zOmDxx&_rZ63(SkFvn@c)WNu*b5u}0h{wC*U=qD#uH<-E!^K1LtR_v>5v2zav4lk@~ zyN7rFnbUW;7G_=oU+v^|sy+pcoAE%L2O!f!6;{E536>Pu{WZA=Lnd(0J*M+X`T|wN z&u#(CmaU$$`~H1-rr7ccKZl+C`O6vbg21h&vL>SiW68oEAo0l(QOUezs=uFvPKQos#6f{cMT9T@#m7E#BvIx`KO{x;z8N%1isWy`jF>G$h z=#=jA?*8~_IXA9Uu3UJ8%WC0*_Xq<*-)xqRI~&gr5&CPKtWeusd^~X+p!ZuWTJtt| zo#`?B+o@{IwczX4bGM}Q#%|1ZZu2zRAhrcBu`i*QXsencJ?RIl(nhJWh8@%K%<~1M6KW?l$h&IchrzDHgVjnHnn>;Bd&1u@odCA?Y>yx3l z=-1$}3hT*bJM-GS51NxVwudw7gI0VnT_xqB$Cl$nuQK8!tEx6bbuN3YB-h`=e8rldf}M+Vz9m z=9xF4cLngwZ9eQgP46N?gA}T&x=Eq{8!kg6pf7wW-DF00d$CSH!e5CA6X|VeeXQ)T zFSSBECSk3bBkE`E_dAmMPw(!ZW2oPG|EwFq{FVV!;Y?B|aA=|yLit&-@UT(WpTk&L z=S_-^RY`k%5;;WgRb7%=O^tS7x&x8;}bjY}#uw2D}qoY|hg)2mbG z1m%leHooso(q+ggy%F1ivzFqIrk${uu#Gk8#3GaD;%{CSftrM` zf8BTnJ8$qr}N#ZCTvPN5oQ z4%7#w%r8YAVrJfmoMS+hGmuo4k~F89M&Uv<5lOk(H~aS1+UdvUmB%M5CevRt{+Q#H zmlf^xE`zdnvt|bXipEH`GU@)eW1ESg(HP$q)>zDS*zZMi== zF2Z*_Pb&Dk5lIAnF(Yltga_{dgdPy#-Q;>KMEBihhH@y!4I0hg029d z$niOvh9nf|w&q+ZC;DviiM+x%VX&t8tc~BLPzO{1un?T!w?8v32h@=dQ_{XSNb{itx0O42I%y_&+3kj8 zS0UL#n2QNlkyIx`}rsIH?5U8ffdZ-Lw-sVbGI$t2Wr73v}qc337h zSd&X5&Qq88yiI(Kh3nav9G$5FxwzW6JR~wyhT#7V=Y5b?Y-MP^OAmo5Md!Jiu=05T z;?dEvcc8JYZ4$>GVG?@NNz#Iqk>Nv8^Z30Rs|DfiUK54)#RpbVUd2I-N-Uu0kJv|F z(2oz3C?EXCQ!gqLQs1R%5NC8?oI|}k%z2aPf&CW!Z^TX(PCn+R%-2Xz1%En`AnT=U zqK(hRm3=Mm_i9w^7qDf%Tek$66yl)lAe%JHIbI8@iB;W9_n4>y-COKMaOLY*AXg`m z7Xn`)LmKSo{0jBT<^Cu{TaH_^XJ-yt-X*}# zg9AwOe=|}J$;47q5dz-uxxSw3G!xI+i0{#&A`T&f>zLEW-N}To6Iq>(eX@<R=*zBoOO)K5D7VQkh!Xn2XC>1f_-U{50h z=6^CVS{dEZKl~9;uwm=tKeg`!=451eRXPh`%PcOb&vEda+`T=aF3@JWnA)X>UisBoKMG8mZbN^+w0oowKZ&EpS7v100M0! z+kwk}Ray|#-xzHk1sjK+&h(6&Zw-V9@aadl-IuHK`30(bnsw41v&wWRBB#nj<$=WH z;cxr`&>wKxkq=z6t&Aj`Rp`Cy%(a*Kv-5+3SB@Ny*3!O<&3Aub4Crw@~|fh8i3D}DpsX2t%d3qz5>XKbuo&9N81i1 zF6un?{^HY%4Y=;Rq(Ym>>Dl*XY%&!I@CnTVU4?Z|%A+q#kB~;&UN1%Uf8hByzoM(W zoN-N_-F3{I^n{%L*orP(Q42n^*$)oU4W#eONW4~vG#9~ZCf?`%$$v4Srdm{wmf$G4 zo1s5Exsn|bqbrsKjfYBTclr9a4hQIk%67e@i{`SifUJZ^WFA)JwA1T^7n4#cNd=a{nHj;VgmbVA{?y%Z>2X#(!gq%UDbXW z`Hb_0u%xmI1e!{sy**j_GDt1C$sS`}ScdN+GP6`+Ui}pfAx{96;E}WFCqzvN1PXJ4 z45|Ks-cWy&Mzv5g`Hr+?Y}%QRUJapIQv`qhF4D%1-#5JCb0&e1wZ0SBAwfN%Tb zhIc|K)M10DH2B$w@8~FD3j77>95hUV(f+UPX?NYy_2AO0Ne_s6Rx7 z--ba>FkB5kzeK{|{(IDO$0!slHG32@0Z8lnasRuThF=krw^~X98voGTx^i{_SL#%* z^+s|S{R!yh_o`vclJ3HRx@E8neOI=nD=CwMCV=qN-$qU)&x^A)H=`saW_j3si- zrv#;k&tY2wV1)TMpvgbTLSY!NLN0w6G)j~w0ifXKM_$AMrte;&uqiv>vCY$6)pZP6y*l3aMPf*OCFh#3Ski+DEWHF#a}i&9&ZFHe*?711V6l!??&Hk(`}cF^^|igKIn3ZtzjO z1~}J*j~Lin$}P7?W>_CrO3kgL960&N>atN<{8mOVHy+PN?08(3ww(|a-{($(OS>Jc$GaS2P(x%sRH*HJHw_^0lpJq~!ldtxO~ zsgghqvA%9%K=w`8;Fcu7^6)iG@gl`1c)vjr&}WvysQx^ols>q5J`dy}VE>_mp6|jz z8T^5YXvZXl0cO=UYh0%qoDl*AZy2@8>kh`Adf?biPd9^o&f&Ql<$v9rBi#!$t_C@l zt+WDL;}UJ~QZYaAmQtj2qlCT&ff!TM2!G_-TkUXd^t@P9^7=_4FZN|7?%I%xb~CrP zoqfF+l`d7z2IVT0=sB!`n~kFJM)|}08Kt?N=315T!f7`d^$*$u`BVT-8x|b^W6v%- zJ&7l&Ab@rkwGOb| z>;QW@)OZ6$!j#CVPHT`&%6z|oq{ykyd(WwjF5m5R3Y&yxd6jnDPTH}l?zG-}=RQ{S z`2#k^ITeDhxFUSlRPA8bMD$4N({_FAVx;#9l}gc_(LuXQ((-sAy9A79(mDVJcTapl znd>Ypj!(O5kR?rP8@KH@JSM0mHic!m3XVUh6!Kb*=!ds1FyH z9;G)f!zHz|Hoczgixp*>x|;d)coMukl7IpOoO1OpUuEm$#Wncd*GhaapL{zDA&SS2 zNnq%kXAwe4h)tZ30MTyN%smj$-0VjtG%oLqJ6>?8`mCZ5w5#`TC3#&Qt-&%;G|QJ9 zQ2_~suR)-hIfb3=Cn}LexO6%9L;OV8g@XkqBIYK)o1)TvGr7yF{ZduyN>h4_^pDxr zCqUsjvS|xUrX9*?L;-fU26z84=66Z%Li89&t;yhc(IfKU1uJIuL7tz^~7YKQY8~pVLD6;UEZaugn0{o zwIiI*DLWXUrEbzUGa~^FV=^HAjOv@)z!If!LMz{4F32&wD)}8NK}Yr{QzAeJK4aSAN3U$F3rOwXtBa74+v%yn3XX2y{1!C{NInn$VO zdtBT!mUM#)9OxZv+8~{+(JV^8_;G-%h2wY!IvIeC zM9kA~TDw{&XGUgiyy2nW_J0X;33U8ZK;wnoJ+M=?)o5$gQYZvl0Dbr>tf6@M;ZVEdw(jmHwbuJ36uZeKD=y16>{@)Zr3FAi z0yo*{ws8Ni)`g4e@~uCF`pSQP#{f|Rjtq#$8YD#@uN}87{9Oh{SnAHP}aS_`Pr>v(OH?UBHj0g_@mnm z#q@Cf5P=s=Z@gF@41RGq+-80n9rOoO@)L-nNB4_%+tDBSi(-1Q>aW>9c2=%9CcQPo z1X6$qFzH}!P@1~)n?~F9en>&#;zefn@}DF&oNmtP;SM2g89>RN`i5r1(meZI9r0%j z*gq59m~x*HqBK!$Q%Z|zg?WCaq>`57R(8lCBcPibkN9{g-QNa3C&{Ju+BxEDoRqv& zTJ%@4AWhtAR`Eb<>OtC(OvUb;gb-%qD*V)w`whZ3KwD;9DR+2kxO!M#4QyG_fnZ)q z=vd4=WzYLFGNHK@t643d^uRRECiiROaq=6eENy>(vg4YcX2N)t8}_4L`_RXBcIqCV ze#CLZg%aiqoFAdo^q-a5{oDS^vPb1#ey_Uo_@k4Id6O{nKL;0hvt)_|Rl9cK-yPQ$ zj`5b9#Lw7H6nd{;$_THOsT0PaqlHWL&nGZmexm9|-Jrq0|1r37i3FKnQl?D4>n-c* zT2zG}SMD2xyJaRNHR$mRq$cN$t1xg_lZQx z^@E}N4Q{XcKG0JY*+m*l2c$lq={CDk^043(+7Qe!AANQ!Dev{QijL03a-qU!jY}5W zO;6i?Pb)JP6az5|vuk{QPcoBzv%~|JG8O)-wFGr`+_n{T>|MIOoq79)0fP`u38;+b z?qR^Id1<>>EnAVKB_5=ia|>4NkSq(Njp+-W1Xq=d^~>?nL*@RkP&ZTYVV;piFd=?D zaeeK3q=j~2Vh}3RQ<3Si3R|@?6&lw8ifM?(;wF3V^P0aZ3dgf@hf`32inWRbOMQ*L zi@aUNT_VTSNdBva)1EVUdD_(9%dOwam1IRo2`^_STnH`ipV~y)Li^%u%+}E8thi+S z{oa9^xQ3Ac)d)1-v@kyRl3+40`rs?$o9-{ZX@?rbF09ci>^bJRfHeU6ZAaPt_exO4 zy}@-ZLlO}t6O)mnV{hU1(dT>W4HgJmZ| zyYqjr0N0gQa1>}!t|ins-*JKPrQpuTzYi$Y$AP5Js;jG?C&Pf6`hPWLH$S<;?W!es z*9mjY+qQFHdc|E>H6>bm(rCw2nn})3QJ^tpvoc|PxgyBGkN$Cc{=9efp4BHAtNqMF zJ6c=bE3RSHiv=x8;c6DcLgro#|#4@E?VTkUAl)K5|| zL0T-km76=yhOU1+@M913lF6U<(ME(fHidh7;2rBT+8fof8q z43^Bl{h7J=vk;H3k|r=_iw@ca?~FDU9eF?AohHL%z^=pFZhG%d(YmgfIaHCYn6y4x zt4(@@$-0^<@55X)f|dxfHCnj(PIFAQIMfVE@A+jHuFa!8g2nlw?$+k}KeqI|tn76F zGvLaBw3L19A0A#-`-}Vz6AMz4K;~i8bRgVQ+~rE7gYzL%qI^thRpllfA*%*CQEt*% z!FC8GY?~L9`|HAe%+%XT1{VIoaW9XP-4LbX5xFo8>i6iZ7AgBt?Z0^0)dpQefM(;S?B=0ib@B0*99xcOpGdy4gUKN*?mJ+#~AAbRL5Cf%BK@bH2 zE-RPiGHGmvGyK;e?s3>=uk=$7n=o_zrLU2ZC>#YPC04FBupN9VYH2&K`T4zWWha=B zBNe=(K^L^KJGy;sE-N-(hZ{ISZ#jLIYipg4ms|N-TW*k{L8Zcf831y!>W5wplG*U0D&K%#*KhgsVJn6;|3F8$McFm%cY$@A&gVw1%_gdIH|jjxsAv zvzPh&P#JW11osBs(KTgH^(VIuoV}T)`|a9ySHpVNAP&qJePAqKke`5KLVCm2dK(w` zi;IfZIZ!~3q1C2io72+^7!+~@jGsa6ZoYWwVx4o&Uj%l><{Ccg+12wCFQcbW!tEwF z04@;+LzkkfFdXa6)lpRYJjjOn?;@$xSd*#cbob^Mm*y(0u8=Q{PQ`eo0Ap zrzO@d)Bdwx>5~f#$Wi+rl9EkxT@SgN+)6jG2GEqI-sd2}phwsK8a@|%j;r(YWHw8z zcDIbosO)czonOCsJ&;4~>QG40nvSKd^^$zUdlPRrq%@2l6{1u-~(Qq#4<_n7lHbPAutwn#_-ek8#(iBB!mqKZP` zi=a#fq{a0wY`x81Ha50B+kE|*SAz0J{CAW0$7Nf+;3zX7=?ba)1Rov`Pfz>mL`s9wmp7D0`!}{+1dM1 zZNI%pGcFjwiPxHqXMOa0efk~&ukoIc>)Lcrq{h&LzFi;0E$zhC%wvnqK{(BlA7Hot zeA3=?R=fo<@a_gV`sB+$yKVLnHJtXReK~{>ZHT{p{&F{_{1EunrYtXSTlrW*zXbE@lMYEa(Ra8{;5&5Lx>oqyYg5X@3uD_3c(!KjRUXlNV!~=4qiKo}SbB2t@>v^s<+g>iR zfunY};`P!P^sy$5yO*j{%cQWzB_A@BQ%u$>}X!GE3x> zW5S9RsG|``?TZYONhEqSJw+VzdKmA$%k_SZjCXN&P#%fH^lioUHv$n+x@2^|yNhNxZXI?SPW4R3);N$rHBmo~0TKZHCV_>4DbZ=P z2NKa1>TP$*3OPNT`_vnG+6Mnj=10=5(lgi+F#yfh79|s|T@lKLaC-VM01>;Wh#n9N zkwi32cWWdm& z{GO|&eBS9@%dH;rKCILmk1oNxz|6MY(3l&27)=FzM4!NxND`Sf4tPGoXxub$EXnZvejA?Y=~peD(-3l;Ueh;q%xo zt?|)oag7RYX=!=B>WTKGc;#Ey)t(0|%W9KE?gX};r`>dsDxg>hnPGe|;C_d{f%%px z9Av?o#AZ3u)7O^`f1ueLxFq1V&ua6qK|GnSnGDe9?@zHiW94#>@!e}5z$hq@&(f{~ zLkr2r3aP>$P=C@_b4#xI3C2;AP(R7c=hL}M>r%L#?KwT z3%2cEhqIOF@K0XLek1NW4p}{2sYWZc=Ldi`uN>>SY)}sU;&9h`vAJMQGnU5Jt?PMK z_`G9MED<7-cKRHj@Svr{HiSN26iZ`}uF1IFX6L!{YISZr{cV1^<_M5P>2dANuWz^F z{dn_s8qMqeQoCXI7v@mBZkuOglJSa!_hlk1qId+tHV^j6-k9=C{lwGb4i!YK#ewzw z2tMZgMJU2PM*u-O-%-{ts~y3?Z`zbWpa#EBt?s|*bS~zr$V|s#Fvh<=-Ve&hGw8(3 z*4sw%R=(kgB=X_BSZ=Ck_*Ak@&(FD)`MXm8L2MtvyMF0vxO%MAi>9`&Zf4K1Ext|6 zYrO|xZLBvip5oA}edW!HRbC-3X2B?38)+PQ!qjzB)c`i3YI1C@3gLSw}-- z>a==+TT`p#z;VG|=i!j&YjdpYgF^N4Pd<@eVq8xQo;yvSHoA#!JPuia2`A42(wyj$ z1>_!GLTe9E+8jEORaI3lPkjVr9@Xu=Fr0mEpex5{S2-|2j)KSPdS0=|FP1jYbo#=W%~r=*p}Vi@_u6$128YO-@%UH|vg9TI$IO}XO-(}}d zlZLJrdMxtv~uxa~DqRakEn zuFKL5=yxdruj@%q2!@E`{h#`vfX20V4`sf8T?`OtQ74kVJ6MA9T?AtD^Urgo(^JDm zwz|;JS8wIXCm!LLyppd4l`(oYe*F z1ms^DLsY&g1C(=#Z(4p{U9aL6_tjXsz_sNP!EbjY5+!*bqqCTxMSHo;j<5Cf9(2Y# z5#^2x{HB_4Xmixm&fcwFJCKDC%GI(=ulp;Ezx`XsInLCGyMNuT;I#H_3!+z4T%5e9 z|82iBh$t~c@)pF0_t(aHi45q^E?v`lZC!Rj-`76hPid*C`FOeA?wy@Y^1g=t0RAe7 z%FRxDRvvl#mZ0AS%e#Ou#U0=cy)Ey?jpD^X3MFaU_LBsJjAD2`Uh*PB&zq>kPoIu> zW#=~Hw5L$UTt8>+4~^At@3j}EzmXPESNB_$dq-@TMVL$iSggSDzh&6}?Fp&Tuvh4K zrT`HGcZHAMTIVZmQP`D`)jS{x&j`vT{Ox;uZfBk6C+M4q?rMIo1aa^)x9a0bW*0OZ z!qubWO`kOKXaaOYG{9hRua|hp9j*Ek6t2rU@y^c9ylLH!x+8~ac@@57eAXKuPp8*w z8+M`GMHhZB&KB-l=3qa}dqhM5UHkn@?HNI6Z(v+jNZRiS-7Xf}i3HRfhdrlk%8fMP zuG@#?C|004QnJ)WE3 zZJe=Yke~7U%Vrv=3(8kwJ&a)zr07gxW#*cHqx3Oth0K=OG!^BNgvb;yMhv}^R&rvb#1dqwjx ze9L{BAfN&SS?(_MyN*zHcwj+}m}Qt7z<*E;yt5Frm+52(R0=AxcK<`jQ;(XhQH zn$_B>|A$CHjtu`{k$*nyu!g^V3xs}vVu47)B1nGFc>i;81``lV+ZCF*L<8g>D_N^_ zJcEjl2Ed2}5uuCuIjJX(a)wzlA5Pu`j~)0^{1apS`|DLen)#M>W8opwt`N_c_I&P` zG5nv~uF?apz9Vk_oWkb~9+Bob1f;w)$m&0e=kHalD8@K~@s)UCzdTLN+J#7({tYp| zeEEe4&{L|4NlK)sZ(zWxO##9ECi5vdiRkEz3Z&>Eq%JU2rWAR{<`u7W8>uW4O@4v} z*GbTWNxkijr?MQq%q`15(@f+tgoGoYAe=-8^TL2b^n4AJroP3LKtnWUN1Y{->m)GH zu--8$fX`6hH1Jx;u4|>vEuVF#uq!)jt+%|%<$bxM>l+bt$&NS1JuN*oR?#DK7e{d% zjVOX2+_WHFELxNKUtG}4>)1Vs4c8f8*5pRSToarxdfg<(B?AV!sXQ?(o9mM z{r=QFE;x7z_m~2hhF4$3B_^Jggc?vji~QUxLirJFmCS|?N%cd&X1_ixp^x+6mQ;xg z50>B=yNr@^uTQjvK3Fb^2~dm{@_Tq4Dnj@wDzZl&D=P&p`NC#{p;Z~1N8tnN8}iax zR5UKSJ!<+OK~|n(i~}ZhLQ&sz5z-UXU{6vgk{C33@?6_`)_dy3Hp^FEKWsW-pv}EC z>M8bnAO%Os3qCkc0Ri#C^#8CAq5bVX6P=sAP_OvFey`nr z8%w|1K$WPu;v{-wy}XLrxKt!?mhyj^pa{S;noH&$aZU*{y}j1V-}^)@O(=~Gsx*-r zldHniz%xHlRfnfU0)~wJ$c(B9Mj*!4Guj%-=B;9?M~qe>QEYcbRd>J8@X9pML$@Ybqt@&b zRlxRYF^^Ug)}vGL6;>hic4}eiOcd^4{Q9_Lsj6AcJv6}vIr{rtXw;1|>#`AN%-`oS zhGvom2b@3XvPhSV$-ixG`f3RzXs{3ADMzy>X@Yyz$ir}}+eY^`a%LHN{n^lUp~tx4 zlG0Pfb^i)ER}6Y@hY5#1l?o4~thhZ*u!)S&HbSk2ga}wOqYIs0mZl0_yMSYU{Q)1M zDOb(EA|(>W(LJvjt!SH_Kpqg!HKwpl3KnD1oVNJ>Yd>D(mo00x$R?fgNSI2%pm7^G zsI|+23Ab*0H`K~#I$y-{;mqY1EINEFyta!d53MGmAxmhm|3rUmqFtwm2rFX_Mq5`2 z7oAdU!=#uLIVU^QRP*0POuxd$R z!gK5H$4YX+Ght-M$Xk}mRs9(rri+X?Z9VImk+ri+rlm!@EsC=lkW8D+ph-yoQNu`Q z;ht3%Q?h`*!BJ$NZowE|z)E7w2l1CA5n$XLwq+fm)VGtFU{xLb6em?XU>P<}Q-1OB zaP-0nP6M2^X2<1rFx3`L7~i6k&dNt^TprH%BQ5EDI?HuaJ{CN#0S-8>KT|K=_)Lv% zWc~-M@=SwY~kHVuDpa`ifUT9WN$Z}dDiZUHFcZXmgLQ% z-#z*R3zyP;)4-9O!{0-aME477_vR10P}CXyFpD~Y#8ilJh|F9@!%rEt5Qynqzezts z4p)&_B<=LU_YnW8eof{-VtkgYc(XW8+47wh{T!7dq(J@hI_~6Bo#Z2nuCBPFDT+wT z2Tfq+=~c{^*{ZkhHdUJvP^OSVwl-Alnekg28T|VhG;)(%-=_;1Zcj5w>R@aaOD!i= zJ9_#ZuQl4iBeJkg8q|{Y5K4X5BUEkJm+Bmxdaq_BDJRBHlU_}4sH!s?o;3WjMfq>z zdw+#=fVUM_wI+!>gwJ5W!Afq!?ShcbMnt7dJ0N4-!kcPkqcimx@+Yqw+2#wLvbtHR z95|EH-q<7?*a8ktSoI%{9akcbn#|LVwXv!o0BaitmCLF`Di@lH4)|k2?l|ZD*!G>3hT*sdWRn@Q zvcfiHvA|$k)w69eSsXMprn5#|{Ipm!w7KvDwY{>Epj}o|ubw~4zbLVC8LX8Mqf}a% zNvINLx1CS+5!S!NP9z8S1MxHb_5!+<&juklqCJa@jXw$&KXXpqbUORB`I3S0O4MNM z@0djc$a&DvF!Dld@8TLm^bXd^0}J!S#U%%cMQ}`fH>1xA5`U^hHE^V0v@P zgX0iFf`^lpYPXQH(c_ovl+|%kV$RW${uiT|!Nut7`YZC`lGt(|M?}$l)5-O(r#5*~ zopksAh+s3sV5*r|+Zm^En>cR(2IJvH&vp^eo|fRKN2!$zSu3P7Zp3eIV-r3$mJG+> z%`EZ?nur8jCRd_MYj)$OY|d8|X9Z*#4NvH7lmYb+ly)4iY_z)#(M{N^vE#USqKlPt zs?pb9C3}%(yK{>XlY*;kAo~XbT}r8K!Ogm8Y|`Vy8~&lYZiAy52bI=2)T)faA}U6V ztX5vZY@4_mV3P(Vw4#{rAt_j`;}g4;K}cfwXi<(?Qge4bqtZ^t?LV#C$}ZG$_mP|1 z`WGv7mZtxpCzp@ZqN7ErymxS-8d_pj#^~IlgzRirjx33me0t|Htq=H1|7pMRfXVSw zr0h;Aba?1-Qh%!&sKd7u+Vit%LGwxq_w%x01!qWbk3O}iw5+c}Ap$lAU_$i1vh>Je z2HUI};md{pgdNmn>1FTzWvZQ2O5PM~Rn^q!K2kKsfdQ-}`m((pW`UAj?q|2m%zmf$ z9t{;gJfJ6jRAkb%n7Pg(TWRjAaT+1J8~R1gn6I-Vog*p_whF6cBB5ChafJz6Du6@1L+q8`hYXvJF_w8%2d7-Vhqrv1W8(;>;xM+U3Q6*j z4Ei<7$7OkYOR2aK@1iBE&B9W@hy1$AJMcePfS{4M3FhSR*6p9Z!xue0r%gG0>{W>q zrf^#@#aUnyRSeZ4J7znGH-ypN&4DE-1?zk9PeTm{xtTmH{@13OxRa|-ok(bNQaa~{ z37yQE(rZDl2XNMBFk7JBVZ>H($YAA(2c=w8u8D{|L+eGoR53ryZG8u!7+?RysKj7eGGkiB$vWGL!$1nS|4x!GA&RjEwtm9Q*gQ)XJHud~T1;~&(?MO% ztTn`2FmZaOLZaf2?Dxd<96F1gO?t6PR-Qg4`RKaIL3B&L9BF|ZX$o*9Ev-&&5@BIt zVH^ibT!Jq!IQa0jFqE{2Oof!wpIGEyMX`;E zao!19};PziIQb$(VFL1&zQ9* z#o}@F1gN|X{>M8JGoq zHfazK|KGI){eBgrzeJ?Gf=U^OJyZ8p7+?4Ljb-moBQGvAG!|ZZh)O~=HL*z^wN;o9 zzs}L!Gh@3N;%hN}KK&)^0OR~21SfnYy(wd;6@m$@>Zucw7jtSSG97 zN?xQs1kouVO56)&)2#B=t||h*Rt$`W7NWYCr)QN}>8p)1nZYq1+|RJcrWgi@4p`wH zys$FsZW*`N-=ifcm1PxcHe$bJ$9q>Cm}&kh?_ES5+5l4w{wj+l)jY3@DX0jp5!PJ_ z3Ms46v9c_8+7f%+iv2&sb9@U7FMW0lGEF)wr(ScMIiq8p1~@~M-!-F)2p1Q<4(m+v zR&~OosPlf2mJBW$Qx{hp&Yxsy^`fFx!cDBJ<19?(a?bOOkBF}Kjl|o3(&VTL?^#BN zP-x7ZCD*FXa^sZv<*ZS232)ZmosEcyi0^YCDbFm4<`GbkfM?7ojY9e@W-ZA9ty$RX zxC)Cq$LTaI0NL7&REv2(qKkpu>y@^3m$Nf50(o@S`bFm>AyRVbXt`8a+Ev?(U)z=f z{-3c3CTAiYKpAy!>O?E38P(MtM3I>wLg<3Kr|4({&1fiD>s>gQd{l=Ab-LlA7GKM4 zTXW^z;T3uZbjOi{xJr#Fcvw*+DdSN#mcNbY7&Z2$;-BLm&U=Q^)oN&2w1kdq<7)>h zW&o~>h|!#71*+y*xXDf|ayRGMms}MIqv?Z4)VYhhS8>5T7}J9XI^&A8>H_tnKjMqf zF@UMEcNB$O`$IbVH_J5Ljem)2+jLvStuxz@5>YoteOCiEX8vuy_`7f;v=C)~jR*|Z2(K8(&xraXT#8Vk zRg$-ko3LzSv(GcW7(l-(Py_qTnea+W20m9|pk=3&Se=(p&6rp>dLT@R1Tu?=$Q9?7 zblYajZf?ZrI1S=m(s_5!T{bR~3TLwB*cAS6jd9@5Ttb0^jmZ@g9Bg%Wp_;dSKs6J? zJ1!4a7Ne8km^t<$J9Vff-!dL?2FHbm47jPM9S>TSts}{r`HFy}#7*lsu}41Dmt|;x z%Pi-6lmsC5u0gT^BQUiV>Lv-?^IQX_Vs_Rz%^ZBz9*E&mcJBT%>-oXKUdldXZW&U) z=+Fj|n5$(*cn9;OSEd#(Q-4X0(2ey|QWW)w7;#`?;ULMfBW>JJt9Ijp>wXt-{Gp@W z$cvDTVLvyL)fa<@D)!?pe{a-9lKl`8T%eO&S$Io5 z*~BH>=QZ+LTvWcN=YQEty9AWo?yvMU*4HH}e*|kxTF4HQOHU>Z*o?YrMLYW%ONZSV z{B(!t5*55zbH`|=H#Cg4&eS;Xoed7q8ejC6IN~qaGLu{ifBMKgV_-N?$0B(iSeeND z%Y2$nda_zXWc`b(gf4C`edUbsU6<5A?4SfrUSjs@k%1O|d`Rn|En3t_Lb5(y=G@kvXEaBR%8&JPn6qnX%%rd} z^w&sYaPiSfP!oG3ZdDL-Xj{@6hXi}7N*1phU7{GO*g0S(+9qfiTuQ4%%aQlWC`$yC z)Xrv%jSdc1|2}D0jJ3=A=~x;|mQQ79r}P_9$Tqrpccd+SVfMj|RpPZDJVo@$S)oa^@=N zls)>%lcN)9<$kwVl7a23ME+3o_3X#uqa%PP-d3t)g`*%&jE1NM!40$kpzQZ-`&Ct! zSb){eLQd>enYBiOi5P9jE@~8mIu}M2Ega^MHJ!=KG*=>ky=^m%CoS=0RYfhp^!Nr% zG3biba+Fc@$Bz=ZtckD$+;=RRd>uCxTHnSLa5!6BecX?N$KpH#k8g34qc6bqp+H^xP-_tzl+F;YZf*#$`_ARR{*Y^ z7`>#K0{_6~SA)T7^vYgLG)3d2A73LvnFU6QIAPTfW3l$H69D@Hjop;T+rK|;{zsE8 zZu5u~Aj1cU@3_XJ)`-1hsq^WH-OAZ<&|LpPpm4V#IgB58)c(y99R#?v@0%1b4SUa6Pya+=9EiyPj#jd+&elyv)6bohaZdN9y7sQ>UB9ZTP`!_}O=RO$bRe%jk()S@Goq@fISP$aSpD&co~Ql8o`HH1 zUB3@~c{(LI=O8~S1wP6^nV^+U@b-(G2CJ+>nx~D|ywpKQ!PHzht;Y>=2ZJK+SU&u5?t(@76mf= zykVh~)QeU_ZyqFjhvjA*>M?$DGLuurgeF&Fv&#PRn@pACR95ho`<+ox%7x?{gs2+C zqV1Jvb}T0P%c(kdUr@*AdT-b+IvISf4St$83zM+y?t1i zvZm}dn$%WdQbc8X*t0vh_JK+`HR6hh9ARm4_2%tvqE*IzUOTCK^>x1gu`$7w3{i;Ws|YKo5yQ|VO$tO z8!Xeif`tCFL5rYRX(U|s<;(0uH(0hmBCRdg-^D!e!(|rh0V~@t?oXn@>jvj}qL;Yv z2oA=0v!Ar;KdDycmlPNh36`u@UeUVFeMy;1`|yF)_!ol~_Pwo>dE53LuB>|7h(I)c z+z%TzQ>JzdIfjG~`55U@HZ1GSEx;GK2wgly4l24n*VT3`w{c z`HalW*T*E;v(!0!`&b9~?3}JVfMJCi^?brE*_WB0R%D_mY%RkkkGZcLw;h)AV^YB$ z_QehbFURS-}UuW4iC_lwJ}y{qg$r&>oUJBUm=)( zAIqdbpwBYK$?gD->O$SdT;~3jA^Feo#SYlE2DvD5T^iJk%y+^?gai*P*U}lw&Se+H zsfI{OJYEq0*XwaMG7#I~=r5N|{XMb3fAd-5Igs*}_SUvLnRP<8|BU#*uADtmDfeHl z9YCru0^t_RXm=L{Gmg~{{}}*qUi13zP~%=GqMNsP?|gW8O?@~*T3K#=VdAOSxIMs; zVMzN+Ltc!-#26CKh~Yp@F#i?845%+DH;*CVz1T!8Bo}^BQg%!PFw7J&GUf4BatRoE ziD;yg#R}3@M^N@u_P>Go*D*BKPsX+TCdT>xartrjeq5ahrN8sdBPz+9q8I>A777ZG zo4U}f=76#>|MRQ8&XUr3!-$Ai92Lj1gvYzSDRrA4tC2NO(U3GOzg=q*z>QuSP-0Qe zlg^2M>GG@kJv3laA0#UAdykqo``ohums^k@FV$@KGX}m7ct}^L{)@-o3j7+*i4PAE&;-K9;vh12G?gRsn#178Hbq?u;6HI~!&;Us8goj$6W{SIOP7a&gEE5N^lJ z%>cS5NJ7(|RN(;{r~L;u1^&A$0e~DM^=Bb|IUheKtC`y0;zwC(c?jzzmv|dPgiXZZ zL($CwC>IV8Dc5_tJnt4JdN_xh0;1U$#BkZNNCXtbtaKhdG`)g>PC4VxiYzA!_pUe8 zDaiio0C5_Lhfl=kw)AK1hmh~XSu!%8GC;wco9sM$M+Lzl9wj6!B~T_Bsz4GhlHf~t z{k^-oyT7e|2aOw@K$>5HY!Ij;xFo>4P@<8ynQ2~Zr{i9&IO za=uc}l}Sn5t2rL3s;Za1FDJ}GL%(<;1iyETWbl~@)@_zLxcO{vPH`LeYa*6bQN&J^We-SqGe>(4-fnXo4E^c{+D49gM<24=llG}>-d<|@_kp?X@O*>a+Ss$nqiJpK8i1H z8+G|fCRy5OL~N-5YBX;DFEIKtL(u!?UqBqM_s#F_bpTE880ngtauy-3(i(Or+A|Fn zyoU^Uv=y@349OdGIs4q{w>d!`0xql6n#mb?*?N3h zj=*Ub_#D8z3grOQ31Mzad$|EvQ{)Pw4Q9kvhb3R5K>)cs!$!)ENEh}m|Gc{L{21Ae z1JTpfl@-Ib7z3VM+xg=YEFvx-j0@sQ=O>jX=Y@7ny%wzzeI%r&+xfd)hn;~6?hgR7 z!p6s8>av$OLV9{9BPqsksCDb6bG1aRhN`g5PYkL>{bzmHg8{I0CMG7Xv=Q@~`@8ea z>FH?zb8MUkZm{A!Cg=nfprQG*x=N}VB=mlA66v zP6l~MZf6MSR|DynIIQ}`0oV|S=K(Oi{0c{2a~$*yO@&e~7KE4c5QTxKvCyD$m{ti_ zB*5W4x_U;c#$7h={6dA;NN@7&Jt~_NYI)gDy38lV=hH(2&~_sHYt%d-badY9bNAOM zsYt#Y{RY1rztwJ7<6hiK-9^T>#NMAr#<9>fk}b>vvt~9Tj?en14}Zlc?*1<8$;-=#_lvk+zwp}}rm;9U zoVEi+{7-8+*HPufFyAhRXffO`Vk(wvf$5H3zMK$vn{9`0525JQl@z7XK5oWrX(r8Z z8v$#nfzHEVF0P>j=3DNtMSIegH85@>qaiw;3$yzOt&R2ty)>{`+#|bX0KG>V&8O3D z24zk*0PYZ=3rSKd)AaV{D*YLJgMgiGHC^4ulZA%Cm%EHpCD1s^-3K7V4dr$Qh{ z>x5_{>uz#VI!?c|PhBI^5NzxT;Brre2bBPIcsseuBzRBg?)X6d6OhyvH--!5OLf2< zM7L);7tlb53a`s9SpHYbQU(}Gk(mB>_`x5@g2B8fduhkdH+qpj^bF~I3YIj@&CTuY z?c?Y}P@28BXnMz+Pj4SWz#aRlj%YS)X zhih2zI#g;X4Fy)Q_KcfTz}PJH{sPcv!SZ!(3{d;d(=og>1d3OeYj$P^=n})~J96OP zmN@AzGPcNm`Y5v(;O!c0c4t?2 zPj~vdPug}#r7LpbzhxTt{8{TsN(2la+Qjxy((G>qMq%GnfN5rUK33n}F6X|Uop&Dp z4uv-H=^!M_=K$ikIXHM}qfur$Pf~B)Hnsnxmo^dwx9Vtd1c}(>Ms@jA0#`Jnh{JJo zKdN&B2c*ViN4=sW#P#Erdq$86NioW|pHP>*hOOAJ=I&6SzNi)#7i-nq&Ub!;14oFW z#?YdQKY33t#uX`CUR>;O6M{I_ry3l3A|)XiH#de<#RuF?cPGuK2HwY<&BPH+E;jw) z!&#<&JyE{CaD5O%Q9vL%{_jK@*j(n8#~8F|fTW+|l7p_)X~ENU5BeEkm3m6HY2JVA zCiS3!X19mZ11K|p(?T0Mb*udW_t{o;UELvve7AcIh5um90KK+vLLfGD1l?g2^EzqoWiyNRI!#o1ZF_ z2;nlP%Uo#%gdVUHOT9pX)^Gjh#8s*B*bM$QKK~OUbaF2%G@x^nW9Zj!Pi1RV@R)An1Xq zCY;QPRH2~e2&tO7bwqs35O~0-bx_L;Vem3G&2kPJVf>V$NQrfueyjA`%tB)DYq4}V zs6CMEXNVLB%X=CDGB@qus@iF`9{Y*1=okdli?~o260!l}kAwJCwDW}uklExz=SFga zF%0x7{>|rCiwVG8(hr6*?{1+YrPw%cv%c1k5QH6$ehl+Y^LEp~9TLo-pc|49%g@+- zkfLr~9Bv47bDwfXq==VmP3^nkNd9HyAIod%K&!CBIP_m>D^<(FWD8%0oxFDdF)G*A&nwoGGt;@ZS|%=E(-ts? zr*eFKq@|1f^OZ`Rx^P!p_fd3#v8gVMppMNlIjcwV{lz)ryNrD8*c@i7q(x?MTz~R+xvW0+P>pv+`8V#6=W9pS-S~>@*WWvHX_;S&3mWd%Dl1J>0OQOGk z{JZ%wNbsqcozoqVP}VtayLcR@;1aDdEqe2h?bNWVxYByfYl&D7xC$s^!iN4B;O?*Pj1_SrbvJ%hpR;Q+ zLsvd+65_kz7~&)JDNQ_7-RY%raL|K`*B$m|*b!`soVJ>vXPe4W)w?zi4X-h_=rbh( zU+~OQS2D7jm|KsAa35fO`+rAWIcdJ+IIbc4wA-1nx1nQ$f3N45IurY*v0>KlsTR48 z4mHMGV(#`8aN2f;0WxzHmsl?R`?qM)Swnm%m870)laOEpA)~JXDlo%llGk;_-@xRpKJ_dhT{gBBwCZEojR;}v&VGOa9Y{e zH?_s5Bwg<;D){Lb7@lqx9l+=MpF&2`NQZ2QKzofvnNf;yu?&!DsZgO^_aQuo0Co$FcJyb{R++*6YnxTAL|!i)J15HCM`*Fc*DKaMFNl&X zM~zh#6PqasIq}Dc6Nh0^owkFKUEwu>I=H)%QetMWbnpOI(y}q`uV|G|Dixa^Q=E+0 zXn1v&eA7tE14bg_1m$S>Is1+n_fs5h5v^Gwl^wIJSR{v>AhjrEl61>}vVl1(q079E zD(^f>zKwa<_5Hv|x|99?0jV`_Oo{x51$YJ4>eqMPartg+0YOU!^q&=ag7hi{?_%%S zunWvL>m!FVaAxdBb@HpLAC_!Qqz>YRESb%GpU`P>4#LY z+*}j=g3*8uUYhdjmU;PbBq9}AZr}%E2m&JZ0h53GM(8%U+2H+Db83$*J^H||gBG`@ zgxJK-1Kv_k>4fQ#k3FRa2&*Lhmgtj(SGP{ zVJZsrzBmW|@y~1`TH)y04f3*!07jwDh`1CU%3l>jr27vjRBC^Q+b$qd9D|VY1LI8u z;n}bEPuQy|nP;89R86f)`zu>U96oQv{AisuusJ@dtG>CdX`Rmy&QS5^Ou>b26~!FA)y?xarVNdKRpp30s*R zMih;F)SpKL74qV4PO52aRrOwKQb7^`o0{Iw%zZfDbf7>a`M~$ zq-DZh+27}3pnV`s8T3R(>*)f-gK?MQzMS^(pZp+Ai}1fvW{niZ-&{HLe*u&kp=IDW*Sw*${%bE#Jz%T$yuF!W^mtg7(wtH+YTw0X6Q z_c1og?hXkG8pu(vb1^#iep&8XaSOYgdBh<7)H?Xg;AMduTteNf?UZKM>+lE1qTt-M zVKa=xp4&5xAqdr}*A-@DG`E#xYLrPZl&Il^UlR0LqkMBq=u?dQSxc^+&-%vE2H(&0 zn#7ixne#c}E!XP0D!=y~gbS@9Hpy*K4b|N5L`Bf5IJBW8}t0 zvs;Jsms~G@PoEPfdXxaaoA51xig6N@;kxv}%vK^yD$Q`X=-G6{jL7NNM_Vdtfe8>D z89ALzD;u#wrZ;N(y6K~=s18~TPe0_nwDFtl!##G=HsEIY%z5ifa3{!mL27L5!`462 z9^H%4SXege;gia-{zm-9X zi3%m4;^E#Il)-B*{-bV?eMlfF9@Kw{+^6F3E^u`lSIC;@?sMbfmP^hywu8s;$@a0L z`z=rPmi-_jms3!`cxYy>YeAnXECDRYGBKrYv4sTMX;Pa~i>$;bvmwI|9u$vi?*7ZS zJA>>kw|O4Rk<0|^h)h!1;WDGDJltxXHU|IUFyq{o4kz=_%sVN+M~5YGD?LqbQJ-}J zZFm!xF`jgOb&)?wn7{{)CYF%`Gg@`TJe$*TqpG zGkB}e#8(ZYQYmr?zl=eKns7x_Rpa_MC-x=2*r1u+!Mr?ADabDQkF7ljr-5sI8;e?F-eG`z#na7hLJ+>ma73OoTcFaBp zLiWh<3AQuO*3K9PDA{`LVYT4z+bEG-4Bg6B4G=@UrLRphU6H7 zC`3@)WnwHjs_UH^9X!;>IQPb8;I^UcSOVBM9X&OfA`RqSr!sa?ppJa(g(i9~^~O{m6b@a+sxx5L#OTSg(pSFx)#Z;=Ech>dLczNofYeckh}q5b)I74mXB zVTUTdV=P%8n|$h9afvFHvjqJ_#w-4E2JxMFB88ma?{S&W={=d;MN#sa-R#wW2UL#2 zs@nttG;v!6UZ?lC3jN#eHW2UMT%YD3W&RQd>%N@z;&T6OlE_h#0MP|6zsIvL5T9B+ zjh?Wy_>SDbn!X(-lt~|suQPweSXcXQS!E%;nm-K$f=_&+5z;zxlGT#3aZ-1U!%Tie zEK%Upd&w{8)y<9Ag8TC%Kxu1_`c|ij^aq*(WQxR$E=yHun^*bzrZZMjl5cT_L3XA3 zogeRu`wy61JUd{KfDn0Lsljr%+jV{wqW}8 zW$Ne!RD1TNKlw)7rS0E>)@QcF2L=1AySq^tM+Dg?k#Ql-D7-Ttn&*t8f4C)0q+Boz z$tO}fJD*0hQu)vJ@kd91vX#=Z*d*K(Wm$A_szC2y^-h7p3hIPO17j@ft7YLVmSenn z7aX~RTqCDmb0NawF4Tj`QGKCmgF?w!!qi>G>Z?Ujnjnysz16--5llb7k+{I*7Ltga zUYw23UsF%MB-PlnH(!W>WkwPxw*a&j1^MjquX^60Us`g9h~`A%#k}xIzKpM|_}v`M zPuL-e@5B(p&&AdK{i^^jNM?0T6h$`(d7fBgX^O%pG4^gA$1up6M6<>ke19*lqJ`9a zGp$)2F_*lJ$oj-ajCl#P(t%$0X`%#PRf0j#xP}vDi$4wJY|P`(s$;*wHf>t{ALhKUo>83cb{y& z-vNyn9TJ*$>(X2otErHUT`^^2tkU?17vQ1j*#t>^P&{YE0BN*azP~;(h&n3zG>Tp3 z`x94U%3{0l%KZlmfxX`r@l2It)w<%=f|S77*Tt#xo`YNtzr^je#hY&xr}Unkc=mC# z$BBp0n~l5^<--R%AvKM49<3Q0IbJEWN33p>+m?s=eVZ-=C>E(^=JrwzY=c-688jw0 ze0Ys2RA$N)@|YrewsVIOweHWvVT+8-cyt^Ok7PqS2a>Wx+c)1HWy47jEr?pGoKHRS zaz5BrrCwj=lgfjup!tGC!6_6=k2MObd6&CmG4>`jpjSUf*uBT{LEI@{Uk_`rQ9MU! z`01W`Ys{Y@t14f}?m_J3%c5NawY7OP@csDnE`8Oa>ZYBZKs=%L=X=z+Tnn2}SF1(x7ZehagW3%Y2(^(j_tZ`uDGs$n z`GwAV3d3|5Au!U_Zv%{$(}m;H^OKn8z#SarNbA2R)`J^QPmlURMdG0bhu!Q%1A6rn ze@1p2IXJydvIr#d!t&Ln0!6f9O+r_d{dflLe(2~V+wW4dgL*#CjYX%FXh_=lbRluR z;Voa27vVRo@S7+6AvQ+Koanl>Yq_yJ0@7L*VC>j)CGc6JBw3M{BUV0!dC5 zSyjfZIs&Vxv)ueFhH;;SQ@r{YKhXjo2fxu%=UQIz%9;IvUkc0G6^5GeUMWO^gRCnD z>&zd+@8oYuCmozqTDHiH<^>UNP@`nuX99m!~qN zN&1_eBE`xkuxLq#$BRPk#qew1IQb?>w3ddK6V6fw!#=Oyf6CD)eXHFoHQd^O0BoyH zC(vtdjV;V8yXpYTv%!F8_B9; zkQ)KSKEAcodp+9PfPsvR47uwU2FWF}d@#H5&08h{o?4fs>Iwgb2V4iRPriNoXfc}K zhLSgcyNvZ!+C`UdJJCcXr1z|1)A_MwZe^d-X^I<9g=RBFL9&!JQ%yRyi=Ts9F58;h ztkP$S@P(_Hfxn0=^aEsjd|B^6jhrS7cpu%Tt?rqQKd$C?~U?NU@3Hq z@zq#dSA1NNBXpC~f+EAckLJ+Php)Y=KFgavGy&1B@lK<|pE8`nLj{-%anmRg1uZnr z67$$Fd&N%C@Ha{JbXXO+UY5Y7-r=KS^QGC#ycn6Uz7}msmat^}4tl_>Ac!rgcF1QkX zy=iAfH$vpS0Nv^H{FU_It4}#gPD`Aw)_O~*+hZA<8EiT(O+$e2*Q5DQ@Rs|47eWP1 zhF?|3#28TuW0lFL%4Mmd_|S1wLBwT!`*TG~G+2XWP}fL=k1QGH4#)Mu!MMTkydsr$ zOdE@!fRu#8yU$rU4grljcYaYPk>-voZM~k4p=*NLy`;PP)SkDnfuMJ=cbb~}f-fbT zl*%f%ku>2b;vaK{pDWE)pK{`#9WuH;Ug;@efZb}0DWE}G_CGT{lc@7MofEZ4Oy7e& zW8S^@GnjKk_#HjPHX7G+d>%Shtli-~N&Ev8l=`@hM)HPhUhS;u7l=Zs|FU1dJWk;B zJObuND5Q16Hl}FHL*3vaN(0)#z`q|MLy_TKIdVN3dlk6~-F`#l-(O8vSh-r??my0W zYJLC1FN7xVlrPrBzlsPFiCk&A)LfVc`WjyVY0kEmL#C-9?3eg0Ro&<0|QLq7n`FSA~$0n;Qt;aw1YpyIZ8v z0lq{IQkcSrry*ttUlU`_t9Tpm5AeBej5asBaJ0{vKXE9&Qy+~3{H4E%t(52tqae|Z zY^3W*mB(yKhotB44F!TpjL87CoQa8Ysj zz_mxN%#YGob0cmGD0G8j*Mzp=0wOX1H6<=8zP7Rk^=#U|2f?^!kb*XN?0IOt@my0o zFS>-_{K2i;PSY!T89u^`cU`U;5Lb5#5qmFx$&5J<-ss}LlWcp`TwLYkJjQ@8^UN{H zR6i7Bqh~ut*l(!{=O{GX*NT-oS+VcLgk}QmtBh`DGDfFc;2lgy1i(r&n zJoQbWWw>VCs=sqD3x!iU0tnjm1cb)3eJ%^kb5oAXD;e1LXHViHTlY0EApX_tb_HQ3 z4HK<~F<-W$Ny$-Oy{K9D&Q6x_XJTxugJ^1;m%>h=szDgn7HE)^>U%Wb>{<@}L{zq0 zYx64?C*vK$nt0HA68A=qf*G;epaK)C`r8bmJ001u3KFnYi%IP z=sO=J&cH(0#>r!kgTwBAm4WE19w7ud$%^(?ItG|$3fYnhAC_20coD#dwU+f~SUDLR z=TTh4&!INwE(nCuT!Brg2e-`?>M^++YF++FVVW3si!Uya8{QaWlSaA?yck{cmFeX` zK4}UsK<`hPOR$sMPT~->$p4h}6yC}^Fy($1G{a&DAK>8`L*u2uc_oz%v{g8nDqsn~ zI`e?paP|HK!h0rr&hA#hP!6@9l;I#e1>PPppr1WHL}76Q9fT0f28nn<6z5r6$0eW&$_ zp{Y`9BTu<;`m=`@JJ!`Hr)fBZgr%(Wc@Lky^KBqh>jy4qnYH}p`x(=Uj7~tu|b z1=;Kpr2o;JWd!!a&0@0aCf1-I&@-Gkhe0b1fiM|1NxPS1 z=uBtGhJ9|*Gzb~@%G&JjS2Udw6>pD}{y6A^XJ&>g$w{8+&2t$rV-;Ioq%@q&Ns3~i z@^NmB_?fdUpc(O_3~*6JuGHoQ44^;b;PUpXFk=x!Rg0qq?p!<-{a$%j7uS&{UhfP8 zQuAV}DpmeXL@kX$$b`g5v>mY2@iI7T(G{byX55_|dLC~(U`R!;yD~{V%a`UQP_;48 zrM~C^Et10_WTg?(ZXT63GniX(W}mrTC)5eOc=tptYdRqgZv0}GZ)-g)P{XkPj#|Gy zuRH*T=I?xr6Z+eg%A(LiBQ-kMzlvMhre^e(x{vW?yFVyaG)Fv7!$BQRi3!9Qo0Yo; z|Fe$#dpTiC3?<47XPZ$HGOEkCNL@uj+hF$h3BIkIZ`9)cgdd?KyJq4(&99)y4i&&t z{zbFAsRplmTd1(E{fP4Ylev9o)+HmVbpiqz2l(E7@R<5da)NFh`z&ECA1w5M&7vC5 zCcXlG=}gi7MT2fS>f)2w8u#J!cJLA0^@4Xo)o_nZzW!a$;Y-JQ6CM{4u0592mF^fi{-!FCK5n0trO1>4vd)Mc`nvi9#yxm zHBRoC^rz`&1x2*fqKHP-`(a96g2 zvR}Z#L546rw-@04=lRq*8-J^;bG0y9$F*wiw*^+3R@2(fo@iUSjJiY4Ly=2koA{F( z!bAK*XM=4C2ipY&L(RN)l)Li=TVPyIWehzV74sI0Dux-GcqA$BH3kQWJ{Z^#q3SeU zwh2GtC>l>mvXU{p$r~_m(E{2sPw+5LY7xF*<&gN1G${YV5{b;Q^k;(nm{vsduuvb= zPIF}C-lVRwMCBlIZybe(3HZusyO>mZK*uo*PWrcIy`JJ7-Xw)zH;Ix$se#p#Zq1Zr z*#Up5dz{v~C7YwouM53lusRKwVnf)TUdaB?^)3I9+EpQ=yT7h#=HKe1x`S!&C?+7~b!W@={Ui*IE%s!K2-}cYqwniR;8@fW<18KZ zD}#U^Ac#3D#Qap^7cMS|fLiw9b}qWb+^vH2P_?Kg`^VF-kzU$iCe*unYVXjbOnbWC zlvFbgh2O2hgTBYrZ^VJ{mfd8b_$ZM$xedQf8DNm@#fi`_@en6<#b18^ftIawfP0M` zfm`Ml_uOie*gunKNFjFCv~nhKhuLQ-$A4T;?KO7>PQW=%>otH5_1irWr3TI9uO{&C zg+H!K+~9u3-A%@LXbq8V1z{Zsn1oru=m_Z*rrP$SKU$Vwr-v#92=HBe8GBCbqyFrGo9ROR-CACfo@F7ZW*m9KUgSGh>{~EL5C0VeN;RAR z`PB7AU$qDAq)V$93p6MG=s|5`pgoNE{-ff3X(maC$=|+Xltn)IG12ZcZ`%LumHhL} z2l2iJOA`sx{0+{aej?R8_MS17nxfgnqX7l0Q(1x~FJ)Hj-+3H^ogeU8Olm!uPQzNk zeUF?niGg2@60DEEC4T*6-)@nm3=2A-KEAP1_gO0;F|FulMXo{H*zWyHwJP>DWhM z`GfSWLN+DlEMxG8A^e9%mFqWgwpHG5khdv4WAK3+$|M?Lfx0W{qE0@lt|)kSQzsoO z+ISl}D*PPMHf=H-=>s8k1ET7E`03;c&UqF`(!2=F`<$Y&d|%AWmakXj=d{cMU+7EX z-|Z0Yl(f%5muLhER;IEqlGf|dEHG7( z)Ix1XT1CfcT6W3K%>QlOxr0Cd^1HCZq(a_Z6^ru~W0&xidS1m6PcANtm{F>A)I%t(P-~<7^OLQQKqMx< z?FWMD(cmg@IiI}V6ig%X5he7Y>J!gNagh11=cxvH@-Mxt!@V)SkQ&pFr~7Me|Hq8e z$eLqtvzvXp&puf|PztJ$v6pRannV|i?0;AQ_O~9ZK1o%2Fv&rWOwCS3OYwXTKR=Lr zazRAfi{Oldoc1&+x;HC^ZPMw^Y}q$R>0kc@^ws2<2&d6I#jS#26- z0we4g5G$|%^=-%C`CX4&au*4IEqIt8^A4`-PuIRMmj!zcqY$gyi?s|eQQ3iym_jSR zc_Ce#W^viA-sC=c-nPA2eO$S<*V7-{E`zj`A$JHvE`=c%N$o9;*vfsda41B@Wo58m zR()>;FNfLlmebFnkmIEO_1f@Xi}L2Tu-h-PFOohmta4YgGk4{DU#1 zV|T@pVr(Z%KG~(eHj48T(}ML-s?Xy0fwwk?f4EB{hPfAnA%}HikcE@l$exH7*QKsKc#YzNSs!DjkG#Rf%VOd zW!#PeOGZr0Kf^FSSUXvM+^TQ+B+U=)&5A@I(y2WSo@=!RFN)?~{`?^_iaUHCO`Y@K z&B`g@mq;vy(BEK|UAxX?Vi8^Kp(ATjzT7<*yiSSjLUP!Zk~PC&7Nk2HS?j?V7zfdB zz$U>Qb^1?w>m8PXX7!}%DLBw@1&ZH6?bQh5OiDS!IXL)|*~;;kRt5bPx=4bqtEZua zqAWZ71-9Atv;~1r6jY8p1wydd=BdJ8sxeN1bd%9NgiV@6{LR^xRkQEsb{VWz^q|ky z_S5axZ4AIvMndIFQlk0!4vc`Cl998HZH`m{SCZKh^tZC6_w6@%yiB}4%ZO1ftYLz6 zoMo7&$B~DmkY-=D4`av76BG9dzy-clVd04hoZkF2D#M}lUk0<1?<1$K-~L=N?Y3Hzvl`29suoTx69Qo5bJrY*c4V1=-FeQ>lk8WK%izcse1D;WXFDQA>_xc=RVun%9g9T*>}z5O4nwWO9@8$^VdJ)*9` z`$N?^tu$8$COdU#*%vbv2*~wu+43dzfkX~@Uu3f6$BYI213|1vZ?Z@94-Zv^w#v)M zL1_JEh1Z%tJ$j72R`4kTzRK%a&R<=$Jp*l2TdN!%6I-zHt>1#+)r1}NOp>TsZvq+B z)k!nwUWB{&hcKN{G<-dB54thcL!9IG%{hVHQBfs;rw9{^95~(*=|25E z1HzeH-hMNwW%Um`FMrc#9xgJ*OfB}!%$OGi;(uqS`y|~pBz`hEi*2x>~-8W7bfUEX;}u!0NcdNzK1Mw5UQd8TO=g$Wp>rg|N8{vwq*ap-4+7ItNmbvQz(2UQ&gJ(h0;OWY)G~&? z(Hoqo1;bBPyF_WNjxqE+JV^vq6RvAP>V^00<}Vy>7sQxU5E{Q7UqrdXaQabHW{lFg zyEfOuIPG*dK%VmHF8$x7g+nvA$SDu2o&-@G9H^Hbp5_55x-0^J_(ONtP`{Q5dtvB& z!Ccm9#2LX>f;P;VUjyn{K#;6lRn;ZFu|`)aX2-Q2_pe38D5j;?yF7z_j=XF3V{ufu zEo$)lp;)n3x<|zS&o~O1Y~&rm6{POx=*6`T{hC`UeyRPxa;lF=$Dww)@d)Y_4{q0E7rq%8c^Hq@U zzW!bLr~L|#K`XW8wbiVm8BXRi(hc&-Psuf>>z(EPG^;v=PWw|(AWZ>ZvhQ&Z1P$+4 ztad2j1F(uq4=)e*HxI=@pHFvH9uX%AXckYAWCFg9`1Jbrxqgu~u#cXvC8Ku#^l=~u zl{w3^J6{D9s|3!=H-HYHmDZDZo8&Sp27WrG^94Ts>@*vmR+?o6CW?xZH{-t?kwGbP zSh}nM1Cz@eDPf>^#Ju6^QH8LE-{+Y1-tHUZU!VMIY&PA?_3AdYvO|vZ7{}*uECn{{ z7FC-zC?Cu9>`o6c{O6mFM$BGF`ig%@iLT6KH@x^RjvCufeRxa^;&x&W2_I7GoPFnW z@XJObw!|HiIen*lBo5lO=#7;6ZQIwF3cEKTbCjeBNCqJypsMz~cvQAmWFNkA&F=K> z2tZZ9KMh@Q0^c6e%vyM`TF8mKs2;#<{f5053@ za{R@Z^mST1p3BPHr^B_FYol+Nu|$?Jc6IdAP9(RmuCNK`)V&<~3hH2Dn6GOZi^o9T z5Ipm^*&$ypod3d}ZU(6^gYZ*6CnP{mGynGTLS0?(y}%91rh)PGDJU~ljJ_VXSKU~{ zq(dk#i_vwPxvJF&?wO%-u!(CZ%ym(e=*(HgGILQd|CNX>JyW&|FZ#3?EuvswYXCsuKHgFz} zlabYEv0ZhT5W{~!dOw3}A*{3Hdw`}(D3}nHDbsA%Yu}$kG?LwJ`v1_29=BD~>k0EAYsbXogRR-f{dOuUs?~k4-hc4#t`_%3 z6hK;d<FSDQc$V&^{{mks8}22qvx6(WzSpIBju5Lh4fPM2g>jK#L! z)Pe%SjHE*E4m{CYFI~B38n@j~^I@0bUrr$-2h2eiWnaO90`JR%n3Bqvmo`65PA(NV zbE@KD2<&<_e?`R*`C{k2l4yXY1uk#-Ibph!JcXGcN3+JSY;dj|05XI^soCP7 zdx_V~C#0jDbFmLgKLic994WPbTU^R_PMVF+#k0?Aef-6;Mr`k%2n_A<;~fnzPV_Qc zYYe!kO4zHT_6JgFkHo&~e8s)XL($9&ok=ym9K6GnbjIw){VVWf^BjFC0QJkew1u_d zeYM!+)^7o3NIae~VcTfI4Xm)Du9M{}mH1)7q(S;oOi&4BpG%N%3EqsU zE|{TRXT>phl2JQ0A+^{P{|8s6d!O=on`XS&DpU<^^lpRLkFTHr^q8`t6%UGzQI6kt z*h%@u=m>hhTs4R;BQT^)?)#$jf~VNbOzDrEHG|s#6G8KDg7q+*RNw0QV}>=C(2w7l z7~f{7ZdpTWgrwewarP$KArjW#x`d#w8k(`po1!vtO;j2Oec)uxyk|lewksAit|-QR z??pf3NVcRPOW~^%SP`>b&ak74@7jl9(xhjV_b4R}Rs@N@gu9xXef54^f;#O)1E!$^ zt2AOGt%hzX#Y~nPdD>fVVi^Jrz*9`-26BW_p)K zy}p|7DwJCE4)NVT(n>F3fz+4Ze7jnJWzZ0Ae+57DmoD6I&D?4>x3+f58g#3(7*J)5 z`TD(p6olF+Z^;9=?IWdAENAngh*E# zS?00>|#{q#~m99%i=38^0c?Va1A{#8rW z7Ns7hNM|sHL@)P%CMBtTYac6*5rnpSnh`~K(Zo;{+in}8s?nv!i}Dghk~(v+dr>;; zSop?|40h0MF4HSp_hTi#?oC>1#@((iE6>zE9hud4W_8s>M%ZATg=uQlN+yFYr04P4|{qK+<#-NqtI=snI^X{OOA!;i+op%lB9%Xu}S1n zIV?y2bx^&4ZNUz8v|A_&JoIF*oM!Ah z=DAh`ow~-Z*r$N3Iy;1-_Z!-lFoQ_nEF?nEgLSH;}YBizVu(^^vV% za3$>OT<))B9FoOk2uXibr*tWE`R=*BbqtsEHuP4g z=7d(mZX;I!|KcI!;v`6Vd)nA00UXGyNYOk=s(y}qMghuG%<7{Y%>Rg!X_(e_ipj?3 zFC%ig3`7_Toe4@`puZ>;%pEexc9vTTKb>E%kr}oEuXTAy7EZHFGeN1aGR@7f2aR zF92kU1t>en*ZSaWMEH5oOx^@qRqCQ(koQ@tBMb%GVVqpZ4{;A0OVGF=|@v6$|?iW0`pH>!5&yA6GbH zUS76XIwMgzy>8q50-sFz27cm!tBu|W6u{j_E$dP3<2Z?R>_%z9T=MfZ zD_N&?Wp?N=Zo*@v(T@`jWLpUbS(i!(H$U4TNK`@Qe_R0*`C;hHrpoG$uU z6~3SCI}4^IUW>ha;5&nIU4H;bY}KL|AF!7HabLDr7U%crG(?jIcK5e+R3$O%m?>Jc zGZ3PIx$ZwIeO$c9PUYpaOP)&KR#*tidK>rVt;}ur)Aly_KKn{9QzS-gHu@h_IxXMY zvtAMT{cTlpI;=Hwmg2CMYm(4$w0+ydpOQfw%hOBT!)@`|2a)9uFVvmy-Ap=u$o=CN6Xvz2e%NP4lOjvJa-YWfExCYEW5C_D zC;I=qh-vTp0>6{X1R~F~%M}YyNOBp+o-Ign=qv2AnaW!0h^{3>Gh=$bw|D8~tCa;6v@yKRU+=V^LII8NK zT6)%m>}|f7>$^{^_eM>&r*?CDp%Xt9Cep|r4UcjGOf1h>U8!gc+T#1!cI%UEWzK^Ey_cN82lGOU0k5uMPmNC(RC*MJ7qvC4}Rlka+ATa;-$LgP35wW1K z!=LDs7p}KwXIz2|lA}1pICC9Tv4a%R4&7^#<8UX?qDW7(G>vgHQ0QFa==xN=rk>Iq z9Sp0k!cDgk&*T10ay64UxJ?3i;(QGPL9|N|KqcGIKGEuJUrLFrOwQyEY&qk}o=bn1 zGylo>m_?pyDJWH^vEs|<{mg00RQqKf#vMmK;EnAO#rv=C3`ltbN&i(_reEKOGCh3H zYVaXP)xQn*Xy~5Hej*(8Svx4MR*ZDgj_7ttCnfv2R$Z8y)u0KzxeKG5$7W7eDjXZ1 z9Mv_H>M|$`Zw|Vbh>fq*IQfgPi+5H)a>$!{*J=i`Inrh9&M&lb7++yGX!@c$XtC=b&0+B@V_Z;oi) z!@s&M&(8KidXdHy?QYkCeQqa)GY~_E39RQiH*ZMAzR31&*|(3uZxNn2lq{V6DpsJE z=+fnt4)ta_t?fdTXTK@*L7~6*%MZ9-!4RKpAdUPv+AA~kzosgeppqpgL)Pq@vzaC#aKVRc}KTg4+3RulTYV)3nWPFwc;9%uenPSB!^cTts$hL{i>ax_ROktIRXP43lKD{ow7X@4{kNqtrF9=> zw+6|+xt@}_&}CnL@)w6qX3DXCSdFJevbQ#0W??;+7|bVl2TP9Te@&@!um{HHjt{ zm?Xp|n{6S&xFNAbp+SD%t! z>z={N^{|Mt#Xc7RhY4BAYqQ#jv8LE+gQ<~xJGQZFj(3XVdNLTWmjcjs_u4NI&eq{cca(hl~HV8|XMFzz$@o33_-nP&azf4y7N~V8) z2THS?ER_CkhY`O-UmFklk6AHk4`;9T_f7Zg@enD#!vs0t3TSZp!63t0iab`RaWaXv zc3PKVQf>75OC%aKnCQ!4lxD!S;(mS(pb{M?b5)9K{{|2)!}Pr0^FoghTVHaJVWu zu`ZM+>+$Nmq0n$;G|<_{dq);CcpD+_nt4L1YAZ#kMXwa7Zp!eBUD88@@MtO~9T8vZ zbon9kY`vUGAf=?7-1Yhch86DLxzUlMfq3iC2?JCQbm%0=MzgAd|Q2bRvR#54u_D z!F6+E=b!kxmtu9|a<9JJBX+%*LBDkVMLFlj(q6)Nsb?L9jo@#T@MNAph|l4Gg}_Of z72ZkAxwJp=e`I`VSt5qZu4%8021$)`nj;^4^(eHcn@|LOj89>18|AWiOhgaPVcIyB zu^)#m_s2ev65$N^GMAI27-<>^Wxlc0=&YY?Mfe8npzne5T=}e(gy7kX^Ek~;b)lv} zBetXZPaKnX1H8BJy?Q0LZ~@`6Sv-q$p=2T>5`N3ZF7$o{OP=fRh0wJh2GM{ZT|5zx z4-Eub{soH&cmhjD2{C|li}W=r3}jXyS-0EU+Z(GaKB`q&gQaq_w^$j42mWzXu>EN% zi;2&DKlr(3`Ofy$%C@~z7A=_e)_I0N2=izcdo_s{E7-NuyKF{z4kVTF2n$0tJ94(} zsQYkiq{=<|FFN?VCFs>J3kr~4HjKy)gaKi^*1bmjeArs;_zcSuW+p2^3}}l}`-vQA zHH;f3Cc9{{QX;<`M5sIU9m;lH)AhdYZ>W&F@r?a-4pWfF z`T$pb(y^ouDBv>&>yeh{B})*g#d8cgV0^#7lJ|E8b(z#0U~W%3#~6>uzyJ$ zM@87;lCe@!`H>-6d=RgaS1@X$3x7)UTa zh!?#~4zBam5B|PJgOL3vM(}6Uv+1m!W|7?}S#DZapbYfpmUOZW%8U+DnQqDdNA8_z3DIf4O4CNpWC@KW5!(#->^t@p zmoCB4ScV9@fN*E(;vzo&pPimQD>mobbJE1&8*`_1C10#^ikTK<9MBu+nlPEivU9;y z+wE1$11*x!A8Te9uz`0p$Z!T_foRP_6|gD3JP0Gb5oE2h(E7hz04h*+=+y8pvClLI zl~9d&usKrJ(l!+cs3mYU_kA8V8lH^1sj>+^WHy=hTxO}8ra||aK^yWiScYNtw+-vl z#S^9Oc@t{M^vAavy#%w#Ji1<{ulP=zx}yGq)JP}ck}k-g5&x@DJfUa6i-Vc{3ve4o zdj+j3e{}g#^$WI^OpMHPXE9l>^nUXz33vaXq7LXP2~q08pqZssc-&5?fXf1AUeMhd zbGJ0VJ3;Z$Qs+jfWPstcf`GGf@NSI8V7r?1Rq zCm8_yO39OjfJO`+b&?d{bek~{k2Al`Q>ytUM0Sr>uBU@R%T05ha9aF!c)!rxWp4S< z%J*6s4kZ&vFOVSqpE5waz{~k}uz&r7=YnZ=?2He~c0RMpxsu;T9S`M!D z7D|c5zUjGM$cW$%`8ng`n@YM`**nLz$loa#>H7u8En5ww(+wg(<8S ztK(rr01?ukT$6X^PNM~+*y^(qGwX~dQ~$P^Gz0-ofL-c+k~w)$@|8iF8XVq9cpq0y znzO_Yb}Jiu1A>yo^=cXWS=e#|XT6#IvBJ|`T>&&wE0Q>Jp zZ&gg~X?(d)1P-d9tNxFv0r}3tHp|-D6e$$nAoqM$tu{FwPE%J{_>_*)jp-X-XLW8r zL>M1h)SA6AxGno?S7|+KB;GbceuupxB>D&A9T)KrxCCyU~Q zxJ$Kl>F9)C$O}zTxo*zs4<<}@ZG8Jj8cAgf&UWQwLO8%V^WGZm6G|uR@@&fmzo-@c zanD=xw>VWR-!Y0pXKi>CNW@;cKiHcNM0mI}gm*#By=Hi=eP>xBjf}T>KUMDuQI<7m zK8qNM?|-$Xbo$#=vNuF(2$MacR#WsO#SWrA!BDZ+q1nY1g7|rmzt6soEIan?RD#_? zrcXqsw*63+&frfb;w&4uO+MAQZ=3Psd4b{*%M*^SqZ5A7L5WE(Hz}mFs#l%FaTDX> zX^-&-F*2uZm=ew*_Bn-)I7{#CKZgAB8L+t4&!V$2G+)1TMzL7xY9oV0L=NIuE|G+P~bQPel9ott#HoLm(%4=)d>)p$n#kRUzS1J-n+|D8g*Nr&b#h2fr>X@s-??L z)Y?$iNbNZ3-GiRI>B2sHAI{?;xoc;1PE}Q90kUfv=6_+S=)+~xr7LWw=fd%gOMFWP zorGrq$(x7SCKLR1uuNd`fSE-qcbBJ*5R~8j^*RyGmzYZGSIhbDC&HNehr9PViw?iY zgQy*4WXs-uO0w5CxfW;XiZ#?yN@+jSEJ$KU9JXz_^ag>X+y4+58xAIiIU%7;?{r{} z{23eHRW<>Y6inLvh%YA!pk`$J5TI$GrhY~RGINT#^uIC&IPU$t!=CDiBb_s;Cv;9#cs5g<+9dR zUbo|UuasuJ;$^*UIB_di$fHB0Xuu&(+G_bnBLT-zj0|y`Q^Uc2(r{b)siT7pFRcKGo0w_ zHnP2>f*r8KykcaZ07~@c))5d|+fKe-mgM}*FOTC=TM5T9&io&%)(p9Bso{PmN-AF ztm`l&1&*3CA_5i&<~Vc$Lz1))-ESpzYn`xV*q!d%vB=o;i-vHY!E2=8iwnoy?~tM8 z7ff=03dnG^u7>9C&+qz7r%xALUryx}_fHH9AqnLDb(`9O$ZRautX|n za4-CfYpQy(>3%LPaaSJ4w|i6?DlE{(858OODzi+Bh$`<`l>T$^nIb57{WqNq5_y@_ z^|X65SLVDoPH+;un)|lWwy->np4KxA39s%tb3NeY;4?}l*f3ucyNkGr;~L))w>u-{VJFI@(OL0f2Rj_Or8uuze=@cO0|rR6*S*lymso%ndp)?|a=;25xtpfE zaR$!NDTNxG%ba#g*J0HY!fR7yFWuB*@VuYJ5r+UF-_AxJtUH*t~3P%#$RxU-HkBPsz&=ko14`Cq2PkgRPcT zH!E9jf~TtgpfyJD44qiL8W~^6x`#$DjS*+6OEm4ei>FB5!3{luN^15_Rrg+IGHOzT zmTAFVp1zh8FxW>p%t@v<)sO7bQ(78bQzz#b=Xt&S^coFDEEt2`4C5wp+;m(i zlq#yvn7Y{^jf3dFY&LG%Z=h61D+#m&VFLZUW;wetZ&oq~9W;44XV^ZP=Qxff430_u zxI1e$iFLa<-ihZ~j<^3k9Xj!eSt&7z1M!=%P>#M8Co3Y-i=`;l=S`66-`ehr)hs?=AYG>*1F6b>h3HlqbHh29F z%%@Xj?1>K|loni59e;-J8^{kcJ@&f9az^x?6FVMa--1||QM_f@C}a*JIcb<*hNDG9 zk-BJX7a>rs*z}MP*D6A1OKl3@oL=1|3XKZY=@&uP+2Xsg-(7O2x5O}{1&%MNywUMA> zu*Qkb`(oEt(g5HQE?9P_0Af2r$9p^`o0Z0i(NU|t@f1b=^FTRjEZ*Flf|^o8gE?FM zzTsz10&P3%>5Y#ly53@vUV6eurQc?Cs$xAP&K?Ylx=2Pue4DU~HFH}j!ruR&WUF&m z-xFsK?j_@~z(NRsNwQ(>i&G$`&UKZEw}x+KV$LL%pCMNBw@)kXJZfg4V)b3Ai%FBHh=(X(3teDtM&bu@bzAIMt z&-OM^lW214(4}wv1+;ZP2AdoG!)Q@4>}ebP->x}DQf<|T%rp_(HOLnI)jR7Sn`XNg zOj}vdibFX2oNC!*;TT@3Fjev+zwAeT(@I-E$5WKRq0(9erP zUSSzgm_S?|#BmaLTP0Go8)0|-qj@2#&sPS4is0fJIumh=U@5|e*QdrMcXZp0u0xV% zP#YHJYrdkOF)p+8d)-U*2dh^%L<1GsHI4T}p;u^P$IfA;kz#6( z25y+Q#T}z|8J%8_kLG{3ss{Sl?@>UYj_+(?04lO*|6G{{8VPT`+sSfraxwt&Y#?-w zo)fxea+5^5`hkRhZE0O|!^Cdqs3~H!bCrOB0vsz&cRLu=9F@cZmH<27rk&c@E#9~V z3FlwT@gx*vooJB|9Go1HVXyk25ld@$^IV! z4Lcot(lm8(F-jDzrje`kcY}hTd8WUHhN?Z=S{jRUMNln|EcogdER*1IuIQPWa}V*# zqlGQU`<6=)aHiDQmBcO1E*j-9#fWwn=0PBcO#{J*9(*e+tdwA5%A2^g=RRXDzb|fk zM38v%rYSRpm=y6+y_(IJO67NbS^cX(bJMQc2XE%-FmkZ;-<$L(B+?WT(a8RFwbL`s z$$mTBKti+TQEZIwUZ16=<`xXNWBm`9%Z%r{UX~q-9gm(R;a@kF85ySAXehEy@Q!&N zf}HdMSLLaV#QH<2*fg^K9ORF0C-BsK#sp)Iarsr#^loT@sWD|U%-*!P7P+14`OWa% z!?=ZHLEJ=m$Tj0G1?x>{IhdEY3r|Z+af{hQlCmW73)Lk-I82?HUxUc@+nz}7l zA6}!D#SadRS!{cFGjz=F(QdKwbgHm_ynB`<9NmRmRA{qZH6S=^6%-8=qCjA(1Avv0 zNd6VjUX2+Y9SsZ&jQ-Kq+&m6oQv%xZ-@@C^G9dio&r^c& z3HKi`mR45mH#+qW93BP+BJh$Jbq1SWQ~%zcqbVE=DBSp`cK92(;W2wS^!6Vr-rXzs z=PppCbuv7GP0m)tOl=vZ*K5k$`Cu&M(>TYRQ^F|*ZS}O2bel%SZ?a~J=+@{fj|#f{*+ydzvsisb zvstXaR&Z0(Q){_Cqqg&jyt6*XcAwIhd#8ujv{&RTh^aJ8nu(JBs(O|exViIK$3gUZ zgRlY6zU|e)@8?^6YvUw?@+ukt6CDUkr}I4DO0ay)FDSsl#l`$RTcV;-u1W5~{T*%; zIQ0)g)&h{_ffoSFo(X_l>+5T(B7?FGp6^6$p+R!h#rSW3(ECBN=%PdWFN)uOWjBI@ zu}X(U_B^Q^_;)2J^5?&r7x-J1`W+8v{;!Y!aG3xk<&O4t;J+Xtf6)*=WMo}&8JlGS zFgOLwdmIg2Mj_~PQDO}+LWl^50SWO*1q0F#84r(1m)qswSB_{1wL<#A{{H^qArG#e zAPDq~KypgVf z7QtqbfEU9C^GcNZue@ItWLp1dyZsdo*O7|2~@gznSs?@HgJQdnY3KoB8Fo>y=>T zHR&a>#nYZ{5ZHkSWgfpaQJ)7!CFrPaDOlZ5qi0|#5{D%3WrLze>bc^$(qgnWPA^w~ z2wsi&ec8s&&U$h>-@2*r?}`)9?O0ya=rL4c1qEy(j8uQPoAQ6TJZaiM`d42?$QzI8 zO8%7r7Y7c1&+qwqVRTd`C-1;rd*W6k#PC;5pWZ>J;V+ZDGoH(_4?siW=uA-{>gLVz zoLZaTbL%e*7-YMNiPe-DxH6N9>xSg*<`sKjF23W&8VP&>u-!5;7+tV|AD%0(bB(<^ z^bZ_Bpy1|nENcF{KX2p&VDOU}7#K;@S$@yY+wBa;hz!Ako*_?x?;5nDeklRN6BPNk zOd#HZIV=0sW^$k}hosPft$+X!Fc`drNoxbmYnxuwMdhs8J-LCHpif5`a8 zBG)z4Ip6+G6)^u$_^rp`X587InAKPeSjr)7+bkE;rc>gs%MO@;-^r}=Q^A7%G~UIP zrN?om`2LJHz~l9bEoGbmA{PN37*hAjzn9LzM_|5|%gW2;q@)hw^nh9uUY?%!_xIN$ z>prkRdGZ5KJ)K=ea0rR!}!fpea7^*I)f%SU|-f9_Kwd`uHPQ z(1G;{T?I^cz&A0DZihbyJL5$?4uG=_zwy5tyYu+?xV^o7Zz7EgS1kYpdLRU@Ms|== zg+umibaSiQAMa}bx_vtWVA=&36<^01{##>~+3ab;Zcqr&=TCDZOCH}rIo*iIApM4m zO)bm)Q2eZ@p$Oyjz-UBJ_R4?nBT-EWunR%q0*(L})G(`nO_1z2fH|1|xAoyat*`%D zzasx@HT=l%&duXDoMHh05C3lJNsC}LifQF(fRp?QHwMvvnPhPT1{Q?u_TLSt^%QH! zZax`5V*39dTnJT9aAfNhS<-;#CvS6zetpNU9#Hp}pnp@<{iToj-5?e(E+`-eAz>bb zz)e{S6U@)>j&sL>ri*DS6hCJhXhQkVqvw1#z#JbNd%ueg1A0i$i*vrZNGPsHU@^R( zOeVm6;s3W1EIMs9&A4d752aO#)gp*6AkmGtIsc?r03XEC^8V>^swh9de{k^O{+=8Q z!69j`0C6drtqw)50*e>(KqGpR>A;srf0FVcnzgP~Bc==w_%#y{O~A#}n=%5Xi%}#I z*5~N?^t^uR2SAn){(pJkuecG@%e@Jr2yG!yFUzbeOaOVXfRbvI36bH)?gYZ%lxYv( z%u<<>S!0*{JOE*iqZKBbdGR;h(8Su(%zFcXivE^pGpXdxidUu-msR`esfj7>w640g z-or39g5UIa;_-#u#5%7=dV{B>M|Q|QCD972nR+5_qGeE8^m1Br3JV6 zl)3x@cw!6;chkdsB{TKB@p1-%d5!uF*0M=iZ(pT5dp+GKQq!aIzmPDkg4R<%b`VQ@ z&VS22b(09`;RWP`@!h);cum0s!|Ik8H5)OEhlPe(?=W$wLl}^?TNIt4;e$u@RG!PR z?d4ZLqe$uVR(Tm_)#6%q&|(P8wQU_MOLuhDMqnU=-}1+s()s*N6f!=PcyOq!E$#_d z>gQE16#v+T2^97BqR`8?e}1L!%BxhTRgFb=~~r|`-(o@}#%O+Op;2;0RK zV0KhK^!K3EML@Z?>Urq1bm$&$GeK?YD^3H@EbEcLunagbcF#;Y)gG~TWBFe!$b4tP z=6ub1M!W4==kPB`inahoOo#dKx0cT6T1QMPV^=jQ#P}8}-pU#}Ysa7coi;1F@4CW1 zF>tKZ<=kr;-+AFk_InJTuAy5ng2C^XLP!8(o|Do*j!xUg!aEsV*sQY%)m)8{BIpUvQPc9WTH}^CL%<9s0AFV zg68nkq?tO&$6_yaaG-x?d310Q?^`45NKDMU&$unE||qeNdCGkQ*LDv>{Z__8f1QVe(mG2 z3Kv{TvCZ#m7E~oQPItIyIc659sTsvqM+m{FJT|R*NDsPA)%y1xEB?0^;*r<}K#zlS z94@8tN#>pk)zu^>+mBw3AsGiU@nQ5?S-ViS)34r)<%631EF_C7)pB556k;N7qvAcCPv<`lp8_=UXZdg;VOD*g9eAm3SLIxsUh=t zH=h2sPJS-PTyGJwL43tIbWH=|#qL_0{@U)W+yK;>acA&-maX$4Z3Ox;bFG@7bl>=k zGjh*i`%-sPT=^cf%Bs-8><9_10yfi&50t1_GfQb44O4^0>u(XCXYJr@Vd}TYJF2Pr z^g`_g^&^i92CZF7OEbu!G51d*_CCgmy9~qvw?$9IDNc}(SURM ze`^>}(UjWP*UA&h*kF0iN5>5YhfTGLLU>lT!M!5i@B$_KsZSW0rotQ-XjPo$KVUtS zMo#efP|M-Q=;@|+*y`D+ig{>?na-x>cNip^OYpFZa;SQ^pTSHpo&S42l6>!4%eVzix}V%0rI5V#w9Zn^UmeYMaOD`d2i`5EwjrnzEwSn)Z}sL| z3quriQj^qElM=Gxn*Q3SQtLyGqPX#AUChxa!-ebL=Z19WRK5{+s%4k(hNK362uTg2?tF<5f zj^EWruPbVDE|`V7tUT)fMPXramb!F$Hi5ZfRJrM%5V=4V)%;WnRrfN{slmUk>MQHM zY|{Zx^!DuNuU|Nx+9nfN3M!6bDvp%quVKe|D{xdc=ZWSb^Gy$}i_U8BT4C@lJXB|; zZj1+iIWUUUne^_gyu^LeLb`>temC!DRb8?piVjR@&uJ^>E;eBPrJ3Jdj^`V|V*QpRk(NcS55R zDl6ZCS7v0px~A*e8i88XAH3M)uT6-K2QAW#-;mO^)Zc8;EIMC%eEYB!Kf&Yb1&*Qg zh;!0=TtPBkHNLf@yY!%~Q<&N-%1;!d^vr7_0`Y#G`6qCZwIW+KUn)v!*i1ZqWZ+vE zL-kqKmNGZ%Y3^bP#ai3DIucLuinN*;R3^9)#Xdfz=gZ|4ZdsVkW1vX(^fmG@76v$cKO>7x z=c*E?0vO=%tw+<}A5pOv9MiR1KC1GcE(*dvl4($|QHF3==I{#mNzzL8OAY>rW3%-W zbSel7r`f(QP9C|a{w2gkgGk$VXcdkmsJfSF#ACbufbKcd6+SO-zI?3PkM1Z&tdm^* zcaDF}!&6K%d&MJIQ+|`?umy(!qewxgfogH-q~hl_e7TL6$6ud~FymHLm3n6SIuXf! zHAs0hT4o20&?>cqtCz)}+IC(64A$C1@*Zbj5}F@z2SoKWYFeY?NF;M4vZ(&y6HhjZ zLQsCfK74icKdGhcU=15}y;^59RFrGCSeekd%<;#MvIVx3Rt$<-oug-WnV@${?$B1C zo}bBOQc&gU5ZbL-`kq8E{5|h7hK`C>_hkD2w3JC3 z++CIWynLd%e20p90o(z9>&O*nsJ0F@zRs%=ERSJVq+D^yYI8`~LC;)$XuQ6h6id$y zmgqdqYaRj&*0hoBNWRnEB?QA{YX*Jm^6o+IJNn+N)IBgHwVvjpHl7EEHfKuOO~HC6 zG*k>ZrD+NKAG!C?GVpfKc6?0}*-X^c@5QiG8!8*wNC*v`+{IDH!ob+>B%599Hv`|A zzZ|r+s6ukz2J8J9Z11iVsd08BRJ^wWcN8`z7N?C=SH-t*h>3mTVUsX=_(u0GO82jq zS!!Z2^_hcsY?Jxz4Kke#3pvN&hS_> zf4ALG2DUVI#O;N1z0&4nXNKaZ7@NDLNn36z)tukc!}iULwhUe{Mr`kYP_$yNpJlnL zzo=LUPkoA0O<^q14$U>j*74hK>kOpuRT~T^yR@40|1Q%qShU-bm(+ED@z7uTO(NHM zsRf=7PTN;DUm@C;qe?;XpT$4ALNsG#rmtx#XS4Gl7-+{c=yY^7Pz9gZf#n3%+P=M4 z*;`)V_{1gMz%_p|KT~7FuP$R`t6o>wDwiB<4>#@EQ#lQ0mlX)Ugl8wQ zH+WToImqdc4Bz;Nq4Rk>^8HkxpeiK;eB_Ret6ggq&Q*Xg?@QxlS7(1zdE|HRrUT7q?vvo4ErLQhow_`t}w3;Y=f?WKqr&FjJSxkQcYTHjWp6ZsY zs2Yxq|7!=kP5gIZvbO1~N1VYc(b2H@f5cE>oaJ}xL#6gUi_1`HgF7TD_J$M4!KW@u z(l1VQ*Bq>?eEBK8kUOstrFN^AWbuFs=7vqRx`a0Xk9?$B}~ogFBbUTh%* z1?uZ%jE)3K4(8|s$kgz_s>NWdo-nQW%GOr)XeorrH?eDI`_mC&NHGbYJ)}1@loG~2 zeCMpW`Kb129^P~IFzwz>tL7={cG(nY40Tk_FOuLv$Kb$yy_{&DC#i4XP2D;?rHmUD zF-dYS?ig+!WYXY9$2fEixs1>j$m7%Maeu@2Myzox5CelXvu0&Wq`e3cA;e3H$+bgQ z>lS|_S0dpx&Sx8uZ^gVf^r#kdoz3)($*mj1)JK3m6b(*C&@oD8RBGia7_%2FiFToG zYoq_VI;~;A?oalc9?1S-P;${aok-}=*vhQ^CUnb zKRfxM&&HzgjR&(jDJ<)EKW)#3yyGe-cfNTCBiW$dD0>#+EcT1_YZyZPq}EEhaqXDF zTlCe})G#12;+Q%U^Iaq{R4mdzRmHj)r~I#r1=@Xc@t)l|GoC-uT83Nc2u9~f##S#% z!8`Bp7T$3-n%s$Vd3TgDY3P~UHQ4*r@XMwwjl3qzX`p0@>!>Wv+yag%IQIXnKE9!k ze(05@{{pp>yLTWtN7kfL`=5=?%E{kL(sKW#&CDED1EtOEl1%4#j<1DHyvk$L-R-3T z_F*EfK~7QYQ@RKfOEzS~?)T{T-+JP_yBOxdpNM}KXrsuQ9>;DXXE4j#P`F#mAFG=x zEtM8m-mJ=cDU^ny#JT#2G%?E#U}CWP$tE=#d z{%u5Jl`mDuJtmevj}=A<^B#v}U3cp)ls!&u9OKYsKP(*utUcq zyb}}K;O79QMyB@{EUXzvAFgc@f|Z(~bg8Yq!|`MKy-*jyL%CNjP{2zzGc*67`3yl< zbu`TzaE;=4796|&B>SBIDSG3hg{FqLyPJ1lj&gM9%$$W?hGOeHmpM_ureql%zbtS+ z@8sTD8=QqjjvPKwHaV1RVR+5}eROHcj7j;%n8-aMUD2`DG!&cfMux){(vLXYQTSo` zb*H8oR%7%e^QxT`#NNNF>ssN?Wl>lC;4-2I&|E+Y%L+j)`w%MR`q zC%Y!#GFRwnP05@Mz20UGo!=!byANN-Z>RXj%MO-nh=Il}nX<&HQ(x(Rs=WY%s|&Ft zpvmu6MvWJ<@R+vxhvxg$$@z{C=Eh<@E!w$v9cCngYqH4QO+!PQvBYWQkqb|E`05*D zE^ZgWX!gulQ!9&0f1~yW)o+(+)To~DC@wSREpw#IQUzb5b+5ymu(*!E`z>|yw_36~ z>+#Knoo#)H0V_uIbJ}3A@oJH0+Uay1n(|$k{AXwHJ>x!2r)cO+%o@$V$qP|QQoBU_ zen@I2)_)g-;F=DzA@Hp8H7XPtkkbg!D++3+49SydAGg726J92HyIupD$!Uwd%>^Zh zL=g*uB=wn7fvn2*;;W7Bs2`qk%ZuAev($IB`5|n;e{f3LIb2Ij3cj-6 z1f7GI2K4L=8BdeDR@{D6Je7qqva>IVx;rfAUll$_)bxR7_-&p?kPDy_#H!pubA1I6^ zXB?R|{-3Z54Kxb|i z&Y*Xv4OmD`8$Y>toX&=hW0SU=t+}V`j`|LPw@zsC`Kh1ZMS$VJx0chJ=U7}Kb2buj zJR+uZ5;a}VWj68UlUwJ`Q{$miiij1T^Q}sWy2hC=8-^Ao>@I`p!=T@U*p)fl9d)eI>LlX3N*P5eDDSPR%fGQPcef z+~%mv8Z!b1SmlNmbur86a~Lr%?We>_MeIMKKFw)&_GrrTwICg7Ro19&UUL#I(g#mO ziQ|LmA}Q0vjhJVPc<5RE0*Sz$~vNANs)L4pn&z> zGefFY<%838jO6Tn)`=Mf(4DO$r5ayj6Y=z*PUB;+gXk5zOTu8N> zu#br#u_`SR-FWxI=IxZFQgg$O7;_*F43 zmY;1N{N*E(Lj}2qWg_qYs$`p!qlq(JdcqNYKT~>l%9GNymGb5OlO$qER6gVzt;WS| zHMuC&AMj$%V9R-Q#+Q#5eXpy=gNW-=cGh$y&Ol07qsQq zC)Xcf5qM5~sSi$$rc!HC{Rv6LCYBc`ezVqUK{&)1F;Z*;6>$l)*M!$v;JEi|ha3%p z1bbErKHY!yr_Y09tXCBYD>CJ#{_yLlt(|xOwyrn7Hypfwbgu;!H6B2nGklX3k|A*{A0_4WXg4trz#qF0XPu{hRX-zM#qJaCOasSUsOfBk~ zKzi%gqyAuzAl--{U07Mw!-K`TxuhyQP&;m)8@%N*KtR7kRg~b_Ci-y0^xMUMPJj_D zqL1BQ9RV$Xb$SoE4~-aNc2+(fF<8OYjc(L#ep32=+2sePJA;ue;NAnW3c3s1$MJ8Y z_vtc5Mym9Bmk_d(B5@Wg-L+aKX5)&x5k#}ZKCpZr5g5mCy!Td~3vXsB!ghwIErEaP zF~-B@&x_mG@|rlW;@GjIQ!8W?96^ION+-$Cwi@DV;bv3q!8jbHvl`w|4cZ8&psNTo zU95DU$~hmWCWymWdTUgLa&7O{4B)02Bf)cLC1@^Cwe zi~%siP<{Vw9dC=Uk|r$N$g%1}*VfE-qt}>5Y>!RCMFa*YJd0^$BL0sP*^Cd%`>y-) z{Mt3lk`**y(W00J!!dVRc@)ZT) zjpZUHydXgYy|i|$=IXtojY0+nK?V@X7mIXvaS3Ri(eQirGYcw_P2g>#;<)~~YA}CM zoVS`~kQqlmHA=@-Ly(qK`02V?3e1{cGHLDq$GKpp52|WW++;j;+INkKDCyv={JY(Xo?z#oxkMuPH@A^?_lBX*?CA? zT|Jlp6_Lwjydjo@JQCBax6~JZGr@og4MjauYvfB^oSqF*9P$@n<+WlG70Wlbo@(sK zjbJRlXE2oabZxUq9Hyb>6a$07m0+ zlWf)WQCJzD|Hzk>pR7!IJx7yix_ml1*+&pXrtQuB0aKDasVdrWW@`T|1^uC#s6xBs z$M0!XO_W+XinGO|%zwV^yDNVTGU15{?5Q#g=rL};6nhsF9ZFBnGa{ansyg;TbuUfI zaxL}2ioB7v#lDj4IqxVlBoN?wRV;BC5U?^d%xX+=J}#|(TekV>m|xZKyOA8>(~o1@ zBv_3Pzc3t+e9t!@x2V|MC5r&5(O0wYdgRn8#H+YP(004c-Nf`_DT6citf~`h?&*W` zatzzDBDzhvFjdwy>CHtUIRR+IcE8hdmnoCia#-sU(^XGo)-1~en zQ_`4LXxT*&0bz96sMkn=NQnpC@Q}2XXw<&7A|A=)B<*Gw7T^6*#qZkB56u5xdv6^T z_47RrFQOQf0umyipaLQ#NT-yFfQXcoNQrbei=uQ$cPb#=os!bsv2-lWQcLVUv&;Ma z`Tf3sJbymte4leZb2zdt^P1P4JGbwh8IV0A!J1u={QxCPCTMSa#IG&BsrK-%u|s{{ zW{>0u--qTrB?>GlG->~mFc|&HsSugpW<-_rX+A*e`4|A3ji>C0|J$#3cI3C)c)$%7 zA!CgbJCqDGy}_(YSu7oLmnVKtgrvhabMV%t`o!u)U**2;fIs-I8g+Zksy@&t`Qv$A zVt48~q16YqAK^YP@;fI&vUr3S<5?ZMkG@e;u0&|t$?q)x|j3kp1@;^v8& z@v2rGap|;-zC$BBH>UZOl*y?5(TDG=3MXqT2aStp;O#fufj#g`)2$YHS?%Xz-q9gq zTswHs6Q$svm#7KoJ|6uJ?jSb5=J2`wv}j^4w8^P5X>pN`xh~>5so>>iL%MSz<_5{P zmA8c#%9&jjG>x@h8g`iYlZ%j&fsGv3{ zHjAWWBXi#;g{r4M9RK=YDP1fxI%&40|3G7s($CNUC@;%u%(r|b@dJFf`(ryV;Wq}#YiR4;ZQygC^>*JH z?`-{yDYSOE1<03SO+)3$`(w@3#;B+~h4w`*U6RoqGqeEZ!bFn=HN=bR0mgHLIR9m~ z4s84a(EL(^HfBWk?$eBJb>vjmrO52;HwmUCoFmIcM|+%4aNlIPX8+n$iGOr7-0+=B z?oWTn+52&z*3CL)9|ZIL2wL)Cc^RbXGWKpJQ@fO(-@86LVVRMah}bTE-hB1BNPPIf z7R~rx$#?&!wnRnpc;c`~x3Mf$O%M#!>gk{$k%dpzCvUwtYrGv}cQ>1jsqO*oXlMBv z&ZB$wx1plFx0~5rS@ZMUbSO1KbJU_$T82$t)d?u1`==jhQrKxhl8IkjYP|H2o<6l| z zqW$U)PYcForc1S2G#i_g(#;(9Z)36*Jm{ULMT`9FPDPBAdmwpoAbXD4{Lqz2lL7eGFhE^_~703P=yAYg2qQj3~k^z$N4PjC1X&0$B z5kGs9Nwwf*oxg=gOk&&ibjj)%xDiFwP&U9pB_AFat@n*r=C-w0^W`%P&Gd+j)1in6$zUTT5 z=z_68y6^;~G}V&tcpSu%nrR$EB7I7s9&#=pK2I&}$j#xu}mM2f2qLpEJ zIxrk4xe^X_>8|A;`=be;+a{}Jeos|V8L#KBlxY3;fcW|$BAU-VUQ$wX!D(|X^=zu< z291nlfW`*3p9ZevLvgV{sCzYASEg`zM*HGRiU-jB#=C1N$&BRA6=oiX-SK~giL z>9=6han3j?^sN2(tMfnGlM{8mvAQh=E&re4=!3GAn`BA zcs(e1w?`csz>xQNfy%*7O@GXkIP-R)k#Z$fhwHNyvNYGF)Q@RpZj5D5o;AHzhjM3ePJW7k^_L2d` z3lfsIB~P+SqP|ve=w$vDZ@XM~izVuZ7;wqOgLi{{@&AI;h7`aeJso5aeST|p>0S!n zrf*G7K>Q7rJ2isxu@y|Y=lTjj+0Dt!Z_wRZp|i@UHhx4OTJgPQ^M?QWA4B^sT`L!X z@#l9UM#(^KRhmcCe)4Rr=cx1V^Dyh@VXuW4?1RVLIX=3miocA%^pod`{oV)!Qtpkd zff4I{xk!z+dsC#}zl?h)Xpl_*0l9vO%N2$=x}*~o&B;avB2Gd3NTE`0)lNk>tJd|F zT%M2djfYGyqH?3Lf_uj1kwN>WFX5>_-dX#zu)JT{s=d!1M&=);Z09Vm@gwH#k8w^W z7xdV)3+Y77Pd>|qpw+Os%-ew=TmE&w`O<>Gn0Tl3-jM@xL)He1o zes*#0oL_VkCqH>^`CL3Q=(vjQie$5+g^#8jsD9bM6@q{}43sL!7{<@N$Y)V}6v-6W z%PH??yEM`OkCHQEB81gRDA#gmO}_x6vijSUO-=ON|KMqD5zaM8Stk~ms3I|>7Ewsg zE%6|50_r|#N+06V?7vs8@>`8Q?-4sIXRuFnWsgOP?e29;ptUaPhg2V_2p>JSzApPt zCoxVl(Ztoy>e@_ft!jS(Pk*z0*VM0}=vPwKoSmv41b?`$^JlsqXfJ(Mxb914&b)j3 zuFe-$@8rBsJ z_}LvZ;ZCdO7rzF4+03;?aQ=ko+RzBp{nX!*R}OKNd37=eI!#16#Ir#S`?Gx3-qO?P z{k9nxa#xJs3IVnH=a0A_vk0#z!`H(ihF5Ik6LlXf=m+)8pzilFk)gu2ty@T1UlwLC z-4jsF?CMsHh#y&ns|Qi~4*l7^b!3d=M?v;Q-Yq^h%xkk}VPoE5F{?x%sQGQoPnozX zHi+el{#IX(IpBGPH$A4(Ih8L$um7ly!sQEh8T3%yhYfqGWqA~F& z-^BJVLx`NMeca3mx62X8Oh|k=pZZm^@P#TfQ(eX{3t%>MtTR62_`CEOv%pxy{aX0Q zYCMm3F{X-oY=4NxB?8HqWqaU-pLgUc^-jNnS`{z#H3MG-yB2?b}EE^qq6KGsc!*pk#mV!GRDjGr(kE(C=0MaKbzZLpo_m} zDwKdM+VKylwIB^CEq&nB#+K4VB?(F;h**LxB|{5>d$zSalqK+f|Ihkfyz$4&|Ffpo z2|Slt0m@Lk4WE&4eyOe#rTp^vr^Itq3N9Tq`laN;7W6|?dhT=Y!Av_VaNO<@!>#XU zbK?z2h3hmuG;bI?>2#DEZ@px&sRO5{zcYuPpiH}4>udj%mv6tO7IwBp*N(=HErG*k zd{&WixYY_MD>0F+q1T<* z)x*rEk~c$9&sUl?ec}}_;I=f;g-H~f`@MkfC*l%(;CUBu`cnI)v9kEy0BhTreecMo zM(KlGKc5$iH_31L_+koh`@AiGf?t@18?CfYt=Q2Q4su(aI&*U|)FgLj*O^LFKti3= ziOwLqBoMglCi|_F4k>z9Jo3i8A2y%q^q=TG8O|Q*wGp|S6D`>7l=`j0Sx!nk zih|?=eA)M0)DIPKoI9CS?D$ny?}5V0yZ=GTy|7~ofeO`pwNRBVIKP>=;VW^&Q&q>d zEob(2I?|V*I{%wt*RiD8K{fANdr7qu_S?P_pMW1h6xlRn=_F}`1m&{^l zX!zV40&!^fxy6)9gd6eqzN1SBjE;+IrWdu5y_YqCuzMo&(f8c(su3?T{)(T^8;1vt z5WK6Iu3Fm4V_)_iiV-(nv6%F(jY$ImwkAnYZoD@uD(&SY`<>{P7xMyf3Mh@gMtz-t zp4VcAyG&-joV%gH3#P%b>^uVWP(acib!}UA**-xhQaLmA~^M0 zcLF=3*sfDwhwO*RMyb`^5BcyJRIow_l=NEF5QJ05Vnxx+hzT?C}@YOdL0 zO6w&!4SkkNdj@r!&iji?)ubO$MtcF@0pUuX5J7;q)>qM#S>!o-Bg@vNt7_1-?St|yL%h|y~= zenCM5jo7{9kt_CnlSC4|2IL@L=f$v))5nSHVmKyzG_|mCat$V8RUcm(H!EBKHaP3PD!)3U5H?zU?0J!CTRHZ=h?I2wH}1of;jgFD#oLD z5oN2ndb>tET->QZYTg?`?mguh6)w>+G1sYyAyc3j9jvt_wRNRyv(GKbp`oGu{HePs zO<-;aE0yJg^-r=-7M(`Dw=k?ggeB=&o{i1TC2M{dYJPR)fP(EBfOFrM?sI7?iI{>2@|W5Zavs`Q z;lpU%r(49O?_UdlNokITl~TJTy%Ufh`{2CE`70a8`S<>}xer!ui;C_Z(_)6k2Ddrb zeJqmrwD%T>OB-8paaC-%9Fh&p;(ySA8I}L7LUhc1JyAb*$w6xVX6A1Fr_SFRbco)@&9_T>Vanmz;mLJ*rdx z`0T4iHDQmju8`i-*V#yIgj*m6Bd%aB@mYNB<#f~!+E6+CHZ4FbY$}MHhyl82I1xhk zErFX{4!4t>z$_riaoEaOkIAqX4{TO?mL^NzcW)(F%v4xOjQxNlkM294AO5PRR&8`V zS<9gEy2bN=;|}M?=GV|B{i#OwAe8lPYQZkRTQAWHl_25yQave8wBX#ys@~DW#O`LW zXcrj|rNsn>v%J5C_Eg8H{eMKG;HG zcgNMTQA~$`7~+Vn4F~7YeESA&<@{oil*O0ndPJkUfa9SpD?6QnL_LAIFNVkfvx3o7 zs84=23|~6%4#-&5y6g0`0ZOvW$m8Lm?K!1@xlc_RO`RX%Q}-s^^p#Y=6YVaq&sIr7 zl|3JGgy0n=^_(Be`Rdx$R(?TrcVF%P8>e26AHDx01wLKv0u!-02`|`f@Yn-{2zxz~ zgNC7f{&u`NYxDX3T;?)l8e5AFvGuR4MCzdSD10Rw(dx%7{RzzN-QC@d(pMnD)(4*# z!2Y6+PWc_^tF!@8G_tqR>oQFst+4aRU4Y7YJ)J}}(g@6~LgFeqVsZ%Vjsyxw0c>JT zX{uDJ<1(Bvvgj=@7Dc@Qi-uPeEb?ZLuux5?dZ~(s3CN!`&ccxq68b8uh1M--jnh^e z-8Z5ec;8G^^Uc8)xmFg{W6`K5I`>1yu2GXfZ0Rnfr51_rB0Cg`FRJs!M?Nyb{A`li zRKl}B5l4*oyj;F~F0kUW-EDM6M8vR3eyt%!`MmouP}9KJP37fdK2sA@W^z^K^S3|Q z@3rg}izQqq9a>5Cwu>ov5(Rm!7yo9Ef7{!ngZ`dI8dn;82)uI9BWolhZAoY(BdT|WjGa$_A0I%y|BsBv zC4KbT@nBe$^~sZCQK-Pt!n%o$@NvFdG(8^253OqFgN2+fV6nm1*>{2isJNC(N42R1 z?Q;sgh#Ni0&Czz`47Er)-Svj1r%%;5DFGsPPLa=;L>iLRfBaD@xz|+;B@;-ko7?0% z=j3&$!)!2H<81>x_#v6!=41#^!}26i7;R{8B7><=Etlf*&Y7(Lu{~GYx!&mr;DYPa zB-ehw*DBT3nu4wqm~6=(9L7BRy)1YMa-lP1@4--q z`cA-J26CoP3F!NYIy+LGd%KA)TS%LYJ1m82tH~!`F)`yT{!tT?vPe;fZC6C~=hA}v zI0Sb^6Hcv0Ma!s*W=BE|pxO^fe7_N8MHvds9nGgQxx0^n%_O2Hv**9MeX9^mIzly? z)%Kg`0ktoo3bXm2B)QM8*GnnNeha(-an@bbL7%9m=mCl5Auj!dTy(dY^iJS%J^Gv- z{ldluk?9xaO^nLU+S^Z)-S`{AAVuGw%;J5CgS&u`Q1mSM91i=Qr0@140;#>Urqs$! zdCSSgCI5ZtE1`E)zp67cGuQg=OQi5XksF*NBaN+tay@y$@3L9gwR0F#fucVGHuiQ(_E?Uq-du~TS4++OWUu7)@gKu zW6Hv%n`%ojN|R;gpO^XQ@9L`y%}bHhbYQ%>119eY*I)4QzQrIdgvg=ak6F2l6t)M>GJOE|;UVy#8_D6ht{Nkb_wa8~8sHE*IG(zhcjP_Z_ zl=kBmKS_u~cLYn+I=kkosaxjhRyDhj(AjPqU45sbczz%yCzxu-fkn>w(nsN22|({d zQ{0gq%6hE?LHe`=8Zedkvz4B39q6<0H;KYVTkp2-kIC4;+zu7}qs|w)e}Q?x4^E)z zTi0@O-A;~rF&dlZjt9pcG0pLVbzD6yn9p~1g=i*H?$kO?BrkDWzQR$3B5gtQL3cWqYOxkdhRkjqA*$6F2*ad2@x z1ixU7-2KF)q@>{BUa*_+a2sZkb4Pc7J--_WIF=V5Abk_joO+4wCu`%yMhH9i4>t=* z{Lv)k=BFcaE4}E~lJC36c}Mby&YOz43{QSG(cmQmyVvzBrRaDps&!^(90!r;q;lW% z-T6u(^OkI6zN5*g=rJ>c(^c#2#|kn}T%CX&@r{UZHZN;%ZN_b76C>zWd~Pu`CPDih zT3_q_giGkP%^bC!G&3a8^#~RuCB-)JaJwc#R}p6tlKXuYv~}AeE`rsCWuTkOb}fU< z?8?YJn=o_jD%-XB@AwA?6hHvQpZ7Y@L^UUJ4noCO=^l_!i_>5B5YhFriv}e3d{m*^N^>HQCgZXE9XhM% z{XRMda`|xnYm~ReOnA+w-q0YQ91SWQn}5U-v#ft=I`=E@Sh62>stRDlu9|42bLpYMXu7#JA1fsgO|2|kp`qLOn{ApVc88jJ)N zY$Vj-DE747Z&E9zg)cuoXg}sQK8f5xKkOrntWir zp#Qe-4TLSFN$MN%j<`?p$;z_Gg2s~VB6)P}4l{w391tX0)g!l*m1x? zTuRd9aNhqU-bmU^X|jG?Z~lg+9ahhtvD*x1Sqt_qfDVkac5r)2bPoTaA~o@iaxrjB!Y$is6uV5J@GGC47EorVmu z&xxHk5N~+iFrf{~a&w7s-v$08{k0xg?Dr;itNR~5KqU1I4S5cBjqgJp?Z=2xqk4&= zQQu&5o>xT#T?-DJxy}MOJyKrT_6no+#(}+NX7G?)AhJ5J*Y7%J*R1V71s!0ctFQOy z!d9XZ8j*0)yc=3HV8L;X=9__`;WEeC{rt8JC*du(?b@>E-V7WzHjnrgk8r*q6e1J& zcIDb*lwc@geEdH*pII-yV5CsZ&zzyvR`S-p12(+k{U_LhN5#ce>`jwEXKzacMYU{a z4G$|v1O}?|<@usvc27pGog0T&R$kHjqo&3Y@I5y-cjcXhZ(v}bIN=k5rq_rB&Ta>3 z8!lD*`M4yg!06CWv(?>E@Q)nuBgq8BJhVCVo=|!f78DeGpu~5{9J0wO2g;&P5r_y| z3ap_9@aQ?#6eLe9D1e!J^at~vL}fjZV`{?Gp#eq30m|M}wo zy#s+2gY;C@Zl%?Nmq!S;|9)dPH7^p_5HY|#CwTkM$PG6gdWDZDCsp$_Z*h=dI(leV z*!nI}FE1}QN?+o5abf9z11Rn`akL%+cjIyZ#^He^X8>Zh2QsE^`Xq|=Upo}UhnsyR zQ$rYJ_BK2J*{J97=huNHTNeTD>c7kIVU_yXXEInr7pC?CLaE7CKJ?-Nro%;m0#mn4 z&1FdNe>%KJe=RL5Bj+IT_=Arv*Z@zRvOlx-cg$w+_1x0Z1y$g@JGbt}G4<6<+Q9yP_r#i5mQ$^Yp%iE$n>Em)4rii?Xej^yWm zF;Xx)H>YcE-cw%RQlyI+lw;OSRqFs~YgdaPP0BD`QS|;Gd%Y%b5<$;n^x@XCs*b&e(;d=lx+`MWC}Y)D zZ{EB-L~=j*E9)Cm{I5i;V<~<#G*%_b;C>|&qh{Tl31=~y_nGMyg+FO>CZ2ENWT_Za z-fo_|$AtHd*;wkDDQcORLCPL=%m0ua4{}RQUP( zgSbbHUh+%QCV;W!`JCdOj;^lP2~q4CceVj!d>&b>8ay>fL-=o1&?`{wd#3T5)zSJc0 zY&&%bIc3wk2~KUOak&S9p5v@LT|xEhcbr$h>Se^&hC1D zhVv#K7J7TO+WmncUhhqysz(-rTZO^?J$UW@{MY)kN_sny?HUA7_<9MrUv6TsXPBXs zAy24NyEFfF1+7`gHX{r!j+at2GuvDU?s=VHV{Hw1kb0Z;nim#snV&Mj=Ep{5qIKxH z1VM-9YB0F_p$=D8nd!>}cJN}revU_C9L<33llfmMDAX^;(@mi{{KBvdjPItd6H=h;(9(P7hc889O?Q+vDILs+| z{5=xRQtyby^YxXSuUgOZcObqjjYU4t`gIju5>xdiW|H?_Y}X-r%+Q?3 zh$D2F`kOZ#1|8v3Q&Wzr;tiOU^Ke$xvQw5I&VKm_>bR|?aE@}oKE`1(T7#N~qDKR% z*S94s_u3g1VxB%^XJ?;LzR80jzGQ8Ga@M+&;ryUG&mJFG_9hC~JMM=h331exmGR5~ zVf1aT_7h8%%Gt-5A=<404!Q=5YDrsGIm-H8#g@G;=>x5R@318fzu zUkmlxPO2ZqQ(`!;K_uR3Ii?)ueyZg#eb7p6A*onmrg6~a4HeiXR?ymClJ)D|pgs}+ z62J?1;KGN0dn4I3CU#z{sEpW+YB?;&7`0a1h^5A$<^yaGfv~7O81bfaKOQ$qk`pcl zikogmuvFtnsoolS9F!n(Yg-5cxl_D3S$^((n1g0^u|L|HCR8B5eOoS?<32E9TXp*g zu$i0FVIZ`27ut^2N4Ng~6}FyR{#GGR3vmK{jp}JoaC7d8V(T%R?<4}MKcJ{TZUH*H%yj%|t685AcGRninwml&)y0_TIA30WZU!2e6yP7H zxk|KpiKTe2c1F~`=z3S(IS6i$9=(P@=HF>(RPROHmW`^}-y2BVt}S=lj(YX#6|0s^qXD3C>JWjM^n0773EKpA36 zMNWui^j156Fg4)_u`fH(4Ds@F4 zfz1v*^)jEX!te`_Mk2eD*EEcc*UpfLpGmXOwv&sI3Q**U>^U(*P> z(K9kKZt+9f1^^UU+2!VwDq6L6CUyrSX2Y2h2Qud0D$3{Q=X>3@Y=Gzy4iPjKX)a)x z<-r^gCX-rFu+zbkUvswC2@V}9{P5@NL)l0Wp5Hk4ij9pe=do}%K`d90UxHXRg7b+E zR{Qm48@{Z>+XO+$A%TGy$!EDZFgSP$^i{b93|M!{@80DAjCIF8%dbbB0HrsdhzDud zjR3a+bueexZqERGYylxT*pS>$0u%-$=!;73`!sjrQ0EG}^$|j9o*bQe_a-kw5Woks z*LWH;RSCpff}p514ye5i)HF9Yrw{qt)z#J0vjvn|8_I&e1c&s&^$h1DGYqN zEQ?to(C(>WM#Z#0SfIg&Ymu1QgCdGGGbH!&7jxWDxWU-sq*3dw~nNupq&E z7yq*DzyWzHD)tx702cfG&&%48D@oAH&<+D#h*-@(-@Wt()~3UjYX!7}0%+si3o_(; z=j{@s`tl{_uR((VFp2vZRSkwB;`OS0LICkez*1>LN=Hu*8#6P1Gp~_>0U&R&jeo{% zn*HNRyqj=-a?sh+Ba){Ffe^jI68$X4{`x383(NXVm{Uy~z+m{rNOSz*9T7=M?BG3t zU;g=uO2qY89QG5OyC3-NpRbr7Kkn%572R>cBfMk#u@yWYeeoAvY9YrR9PQ1EdHYU) zdEdK0o%dz~g*yi5PeT6yr*SdqntD|?aFs`&<3DTZ3s!C$feZ}|1vrVH<%B>^87`*% z;LrgX)!7K~ke0fb#0z~Rqp0w3*Twdn91MSddUr8&P#>7L=-%sk_w%CSVm+|b1qv5X z$o#%oY8O#1u#y!3@{OP8kXI?*jm$P!|%QA%t4Q)v;;3{5zQbkAJ$d zV5hH;&$3xF?30SDz~ohnpB3UE_qn*vx?5#K1|zEqv@I zDgKUBfm;X&^t&Q^jS7b%h;0Fi7Qnh5%fG9f*ZrcRx?PsnFuuk?*Pw!EEl{f<8v;TN ztpbFXu+-k&1FWf1)A1rNZ%bZBG` zjbJL%d!V5l>JSOk7B#>=3$h~q_9$O!3M1>~e*^2MAmv->=VAEzsKQCd(n16f?;m-O zxmKoKCu!)m$CwWava;ZZn3D zC(1?FVCGfGlEK~=!mcX`4qJ7nTN4u#z&uuB#1L+G3#j%m>WU5#Fw)n5T{YL5%BF>V zln!XRv(|4G4(slp;d7wVN>>c&_JdDw3>7C=R-jR*>u`7~(<@oo>XQiz+mmKkOD#Bf z@$kN|@HqhgGYs`>s0o-~sZ~`1GcWsoVKkdqaRDGNU|(kRB+;HxIe-*qGAH1ED(Jzp zOdC15Zp`s?!08HmgoUj!-~Awa=zhrGv-xPKj|0$=ci#mk*7j^@gbIirO<~Lv;5%_^ zVaV)e9dI?mBO=mzDBN{zf&HSk0#xk%O2;WtjA7^pz^DQN?Ka`7v5zsr@fxfXxc?d& z)KZGT(Dxz`W(S50#PWrF$F`;P_WTesElS(Zf#Bc4!8wj;L>acCrFQGUUk9;;z6AGH zMkVhE7S*k>LWUX6K1u8ZkMDdOGtNl5wGEm`u-Y0#61koqw4Gp86Ci0P=5I+A#VN3}!lqeG(Aa z|6dG?(?a)?zf&a}0pO=g)=-6JGU^^TOgS>>Z&%NY&Yl;7 zYjm{ysVxw(PyZ@s&yImxT91Ungm&Uc_?^rU3T*I^l`b1^A`q=p>#ZT>B7!6{TN_}k zD>2frDecnCRM&p4;P4sOrPVsES9R7J>IPGBKvJ-%Vnsant2N)6#+ni6sjFF0dRA7} z+4{;#=%5)z(8s83r2PJ zupe&dy+`V$_Ty(6hA790fFeJAGAYHDjq4N&TW3>4_xTxZ7ZjN{xFm6LAwi<$FEJ6! zPu3(((|7?@hjsky-KU3@2Rf9In*8V0X-m63mmr_MVRehgBNmH>aJ0kvsjBBg3Sj{k zC$kz)@Ln3MHIU4_&a*`)dWus0o||~IH|bJa;=0$6bAe;~QK3q7(i_23zr)OO1EN}& zX>pOfGV6YcaxE_B4=+dU8JE%x$}L7qj~e>XLdX<~$HWefdxe~g2EPo9ei^JJs)Fk} z9o|KVDhnWEWqYW{s!iGsW5(6NT5VP(I#2Y~)A7y)$-uXXoy0QHZ0*W68Cs%-`sg9z zcA>Qet*h?tUEhptRLw-E+96_Li-K5$#g^10w$!FFMoNJQg?Wx6mtPQ!!b-U-(Q@~A z;GwdMuyUy}I7Ul_)%El8{=hC5ZKZ>4e<9LL$$Gf!rK+pR$zHkWnXTDyx?h&u?Ir(2 z*I)Z(Y!Y=&Fi$0EvW;!hK~lwVO%b!HhrHc0g7FVw+T}H-(|bkZ#1TPtD->Mpg2IJK zqQsEP&#@Z))5OH`0}{pX03h^6?w(m^GDK+ZSm@kQtrDV=^8Gsh#mK(BQ&vGGoL#G~ z=qVM5JPq#+Sm_O{2)S(c)%-;LmJ1G~L-Yo}`(=)dPE>t2P+p-CRTIyYHSxBx&b2>u zFH4{7;b_D(r=g^EPqD-1DJkiAKYUG3`fPnFYl2B}XeFMjicDWddA(Cd`)wWb0iDU_ z#`P%qtx8MyxHTo@vfMvlmepw;xL@k*6g(j*rOT#^-XGf2|Ffg9U2imBU`~i+Qr}(7 z9o4o2(PP?1;lBYlKndxMyTV7#7wA_ zmIkU1*CzY$oRnyMuM)wM3Rr4iTU9RMq@RRbN^#C38!E64^L_xn5ACFd+RlkUyV8p) z{jH^^5OMrUhitlvWOjE1mSn zM=7e(^q!vEQ41d`omQiD=L&S)X7Y7A$#aFOh&zmBy0cg5RII zhM1dzw>qncn6@`kT29f2$W+>lVW|CPm0zih!_Q_e@5F?p6UB&NH?!5-gDcA5xC}#I zT3mm`(doxYFE5oa+c-(cwMi8E1};WS20Ts=?uvEy*=D5_IS4tGp}5=j%(rK{>Mm1h z0=O^U`JFOQr|;A&ANmE&la$uWGhrh!7oe%k4{`x5X^dhHOAy8qrYG5fM@g+{D^)$&P z5oSMa{~9uiI!U1-78Wo;?R9wVMYvYiY!vPlwQZryGjQ}QDo$NgiTQ$b!tfxMv5^(X zr*MHl=uYXW7k8r0%w0aKhhc&+(J~R0IK*i{tRw8V@6p3i_Biy=6w(0EvCRHy^<(=1 zKHbSlAF{VM8ZjvAcc&K$?yuUl0_X=O@iJ?S&??Ql`Wm2K~dAk!lj+Ummzs`a4FHXO(ojA;#lG)4(E*lAf< zOgZmRQ$J!EQKely2wX>w9Ty6HU!b-}AVKOQ-p442I z{tZA}ikR7Xrro|cl6792{keT0ig<3IprZx<@gW+X6_G!T4%pWguBO?UYzgvBm90Z} zryS5Bpt4bP9cg9|F`J7>#pNtB?dlWu!B;9d)3DmhEYS15sdKNQ+6PfxCkJ3)HGcHC z!GU;|<*d3ek;St2kO~`gFJwUQk=*ghWCsynwwe2!qALNUFW|y6`|@~W_$R8mG<8X# zN2@O1<+^z+|L(F8QQCJYMeDheNkfZ?6&3>}sHO_6(N8)^WaSeZLAKU==kAK@ywh4I zeYvoNI#aZ&>q8w^cir>s1m^=GR8%SsL@o;JR^9x)|Hbp_%5YND>snNLW!zzqY-xnS zU~9nf1cQbGop8>|AE=t5Vw7BQtIk>O_-#72cgnKqI#$Ee2e63|a}*^t(QQ+~k8QVHWI~^2af|QS#m@ zGbdofW=S~&3z-=v*__xhe~NoiS8RSTZ;(ABFYSbzF2uoq5>=@n)efZO1aVXzG25d~ z!PC~vrY%}k0khZbUD_)IRAWE&wCP`|y2q+0KFJ4W}qxschlclxGIBq&?tX`uFs{K`d-|GLzVuY3|Efn1Bdz)g;1`{LDY zRyrHE^Civp4g-UFjl(~k-zDnLcXBMEOqsi13(G$ez0(vbsN}sbsomBOb8(g4o8KkQ zeZqcf;505H!dz?lmynCDrm&Z@LRYuPgSkE-?&x6GK}1FSwv=Mg=iyYRZ1VH&$pM64 z+l=#e?Py|x%|6|A$hX&6VR20@b>&!{J)Y~djkwEo4{4B%t||QN@-#$MZAfo+7Qa=? z{$O>!1|X*SR5;V{)LTzY?x{M|O0BwVGgY!z*1g2CK~#u)VU8aWS^r*JQ9a^yFAEdg zu4gvnXI_oHsg<^E&LZLQa<6u^>A*&tJHG=eG%b77Jjb=V=(7viLlUR&S^^I1c0J<^ zUV$`RIV**yl8}3v|B2={Se1YPW4_y_NhTst$$V|#Al&f?cqh7*yI#I=k9nmPZP(JG zf(Vunj|>tmg;2$Pf0>V^a!%9xQ7v=>31AAul%j9=KYTGsQ*< z0kXjRxVAB_6eX~6&Z{xohjor-t*xz}a&alGm`!Fa&;X6%ZK7d!uJdscgy6SH{`HQ) zE)@_w9?89MeTqQP7NqCWdz_q{{*Qm8`sU3KftpHGpkovUkC|#m8D7Pdcrw^DTI1-= zCT$Jms~QXt1>yCFpW%H~cI#f$v=DD>aHer|N5hlQqE20FQy#>kxvBDN-=ljgK{i&S zWQWC#j|7zjfcuuOkR-CUww8%FbLwps1R+-<#idq46K$OY0SXEVOp=ui>q+XEn`7d^ zN-K;jD0>hU#w7VXBzCiPMCy!s6Pf&qii+?EC~qF!{gj1up4BOzeSY`;{d+R0XV0G1 zCn4gnIa%=>=mNVed40Hmj^&>#zLNAa!hN#HHG*uf}p?0Q$tnR(CuPuHKMRECJX9i5a^EFG3LLfq1z6&doiat5xDP z&q1HUzf)+hg0%7-Y?wx~#B9LuQEQS#Tu?e6Yl8l@jwc{suua%A@t$s;Z-YR`35gwB2h(^mM#e z+p6U@Cy^&MdMjo#1ab=?ueStZE>KXgq10Pbwl_SgQWq;wZUPhGEzh-Jz6t@SE&-1l zoAwwc9R0GnnS@$P5;>~uO*mG*iH$aVN*Az$W42z2p3M=1E4VWA@@7ucShwq{m(E`R z%3_oTK?ppeyL=!$3X0Gw%EjJbNd@`p0SSe+Bd`#gv|V>w0GjLeI#^E6qAGzX(6j@w zIY6VhSBcKX+C<2Y$gg38fZPrsBaDf{aesP4CbhJ*M9pJ527+(ta&aIpL4L#y>;RBu z+${`t%Sld726>nvC57(xc3+oU7XtNIEML3U`2c?V=mrouK{4c3nEgqhc`RH6H!*1m z^Dq$Yfix7pQ&n{U(ks1(cgj-2%E}5P^gRrFB0yXM)Bc;sz+mCOi5d(R{!0v4Ec~w^ zhF8I$Y6vuOb`&u{2HDBK*mFXwxaRKPI#sHOYdcZ!di zmmoNkK*LXw#u8kFre@VX_oqt5@tDnP13v@ACABbryNH=t27oPD=5vkTq37#53$&LY zx*gr!!k}nM literal 0 HcmV?d00001 diff --git a/localization/autoware_ekf_localizer/media/ekf_smooth_update.png b/localization/autoware_ekf_localizer/media/ekf_smooth_update.png new file mode 100644 index 0000000000000000000000000000000000000000..7ac26fc604c6f38b2a4fb4a99af3541237666aae GIT binary patch literal 146470 zcmeFZg;!MF+dj_o=z{?WNJt3CAR#Rs0*W9A(%ni9F$_I4Dj^*zAT13;$Izt+f^;`S z*U&I@d^ewuKJV{8_^o%X_bivr;LJH^-}}0*`?~MF4?)U`G6c7&ZsXwK5WJL?QpLf! z$%un<-S_6-;3pmYZ+E~y*Bm8Zs^7eMb7EF$2E3(olGb)ogPS`c-Z+@ySlGg0W*m+t z4rXSyj!?MM*0n})9GnL@FQuNTyC$wr*}Hzi)?Z#C_=`pJSCUi;8C5?Q*F@3UW!(6z zE<8f7Up4SRl;M0%m@jq{YKN8|cgxzSDr6Xv(6%4R5_w(XUZnBh4UVG9`AaKxP0xI6g1FQxnsrnNUAk-L_cM zj0{EO{^5qFhQ9P3_1)StGDJ7uSg^d7)=2#z>6w~dId8HoR997M;I6^W%7q=&(RXVn zxZj_bqat%C0W$77;^}roIduKswRryn2q0djs4B^89A5e1%jY$ zHTe+of?ZgMRXd(X^Shao+K^x^!4|Ik^Pz|1!{pRkRCcN5Q?r^4&A;!fby_1zP|9e# zijLrgS{d1AO2sV`Y*Y~K+5=@KQF``+L?bkb895Bi}JJnP-0%Z#pr!T zv*?J*V{dg`R4!L??{}rx(_gx*76vCZTw1V#hulUqJHujqJB7dXrAcG*OxOC0)6M_hOB190;xfTT zt)AMoLZoBn&nL$7-ne?lB1JN1hwUSq)>p;G~oT()r)7P>`*ryJe z@-0y?Czy9X;`GWXTy2W%Gvw%B&tuioH${C36&8N+sYSDH|6(n`UCVG?uA zbIU4TO4X7ua>9D``nA&*{{e*;CW_&G&{A^pTCD;f;d~2J%8FV`>&5NRIiP~pYBc@L`LB2JEqo^o(=B%v=pW!hb+_D~rW&;QNo#6#=t=H*{| zc^b((W?Eeh-I*f87*((IP@@MHJe)LElcfDMLo7=lTS$i6m$n3SksPGTkdlHc@9 zS4>YIs>GhCq4V3+T5@ZnO`MKDOs(mKRPu|d8Q34rLG;$tlu)GIM*1~1B>r_=oOwW7D>ApMCD)LCHnLIA;FHfap|q7}#-M=rSep%zl^{^# zsAj-1G3s?-v(*r0R#w)am!vgKA-1(aF&)KBlj|K_nnj#Ii==_NE6qpxmMj~{t-WwH zk^q=y2$OIzt(OZP;-BkU3%g#oH<+J-C=?`G74u-_wu_b%xHF-*mD-A8T#gH4Fqd&_ z78X1&8;-ALsJHyWdq8V>Mi|SF$Ux*ecC0lsc)k1$RsF8QvvcY}eT|2lkdL9#5v|gk z&;Z{+tE437HrJUFufFo+oJ*NPWYxcBGb<16jLQt4%K7nKWwY}W@Dso`Z$Agq&QpsRViAlCId2hNiMCS@sjE8 zwR^I6Jv@`iVq%i4HNhejw9+Kwh_Wv$himPJq!T3HRT}6E?cU3;pfs1hyOZ7rjg1+_9Da7{i0O}#@8>Dfqw_WHuB0I7pCF?? z3TSC=@JQ;Df?|9tLSv9avkp2^nDFxTwUnYXQlVhD0QTOK5uO#(AUo6q%3G%OdVqcz zs>xVD7D5~5bkLYQI-y*WQLxccK&_?y&u@SQP;51sbha2eW!~_Q9$TD{xbH8ncgetC zkymAv?36%|*3Fq`X{FHhVMXjNvd1&c$bfS6M6DK*Mp`u@P~Lh%C$kmie{B&Dw{6&|J^KI2i+I+ z*Ft?gVI^YXJ(@*qQKrPv*fdmrMj~~lS zKG{$tYT&?rpMr1VX^F<>69i9tR2U%-uv(FougKB(UZOzj9A?8G*QU zkxrz2*(M8`g376^<`7oU$Yqi&S6Ft?YnS3~VRizU@E+$mi#}d&Yc*TyjJGy~g_(Ij zz5_!anS5}Y(GQQGT8@+c?b>Eooq!x#)KYisn!Ofsw$(ZB=He|+%EdnRsF7gQ`s@}x z(L>`FF(@*SH?V+2LVm697Az+VliOwA@F24|FLCTf+0In^V8i2M)S6>SJy15UkHpav zu8LymgFP*a1agIGfyN$R9}9H;Qm>C=#1_;!mAv49L+uFTbH9$(72Sy)^K>zt-+hqW+eTf%>JmwRU9$NKex)t&=KMIE-u`~Asmykd8xQg5;Kr|ks8I4C zsr~5?6_fg+2JcZuUwqB2fHkMCAR2ftqm72D$$1AYsBm_Fovpo*tOkm4&J_6a zKU<1-{>y@yH9N8e0?1PIML~}T?3!jcf1^Lu!u4`Rks_^}d6P_eC zyn3>|fGM{oeLhi>PWQq}&%WX=(uDfr%cnfVA;yI>BVfTp_qizV zrdBCq6@xSCvvJSuiQYqVCsjip)tQ-5yNpA1#JaKvrn>;kRtArWG}2E@u5~OI6OoJ< zTgT_4S-I?UQ9@a?-c-;yw2CO$(qu~i*2Q5oXY-r#g|D@wryrz^ZcdDjSD=Jevy|F5`$qk;Q3xLL2i9=n-MjgoKL`& ztHU`G=oV^{%Aw%|DdjSWyoBmmizLP^vUJC;t1o|?i>myo>7e2GuFLzwKum0X)HD7? z0{x~RE$G||n$(LRQd~#-_G6dzJf@aMK1exORuJ($#iR=e#Wv)}jaMZ9Gj)``jg>2RZhxp+De`^Z`P@twhs z>s>;3;Sxlc%f8pBuJ#z~jD_*rc>QcbC>h+C6H0*CcvWR+N2#3}dM8w=aMf_a$|=V& zxQy|+7dtPmOISE<*OzGGuq^UtcUyF!G$kZM=5*EH{8dN|k{;?FX6@ef9WobFntULa z%0Y&L(riR^n2KMO&)|65(aeJH=8a-GzH`_N{-DxY7-nN)3^-<|U>vhCvYx#wxh{MQ zMkKeNY!$k-8@c_wskD;7UcF46Nk&YpL6iE4y@=VQ&mhSo_njoj8Z3mCrUkuNhVKUN{~sGf*g~FJnOEV ze?Lrl$99_PcBS+k>GY%$ZAfa^5{nNzt-NzKYKSv#RTO$MlB3wv%W1sQbwX14ZhRW2WySs~Jv-_WkfglV;x= z2Yss{S-nM$JH*#7^-lcP(*#pQn#bU2H5ChT^~uY33-P#{i;oIKqXnU2*F1#3kj@{A zsC4i7%a$M0aTIw!x=&YYdA(ig@M*j5*-DEIPSjux$uj(Rf}2^hCtD`)&Hd+&*1KkB zBQuy1-~RU#B=Z@}i<+JJyECCC*OUR~=&sv4TVGmpiOYIbQeQ~_A#H)+{Md2d+OpN_ zCvf%GL@f{c5jr2QX}R?Jix|Z}Furg3D5LOo%STo8bm&A@PQ{q?@Txig2=ud{?;~}wk6hau9GwtM>cEPV(jI|&=1Y9c@_Uh zCIcUS{KIaP?o61UV5-U-;Vz-&znQ#8fIf60EdP?9WfBm&@hwwN)Ck%a?UjTS!}2Gn zIg;<{V?`@Q#JO!oza~86C$LHIrZ>X>J;Ju&I(oKKPY-u?0rH5j=l|g5IlCkMO!>y$ z8V=f_p0ACdn5Kr_^r0RzPGMukUjE{^y}S`+^|-y-E?z4f=dUL{oPTUEA*x+4FkoQNbnj0OrL?wmFTizz$!98FBNIX1 zRW~-^R1yKVz`wy}WL{};KKOlXSp9KHh1arPb|Z8Dc+`n-k2!VQEuc{yO0Dj%8Mc@s z1EosCwg_Qv4|sMP+Dp>=2IELEU6dq*S$YGF(7t?o$&|L~VVh%_ePyJNZ?$WxSBBvo zKgk-&zgui8v9XDvsP%>~=V`xl=<8xOQTWOoaUB)x=SE9Cz4G+-!+vRkY%31Y=G8Z5 z6J5i^)DdK-knFKYWVRco?b*8u6Ki>-v2$t}iwV0o$P$wjjtZ+OCP@sP^0L<}%k^iZ za9{{-zW#sY{F{~? zXDBRn;NyvLIX{2WRwEHdgM`DI0jb|}rSDw0UiVGY1#W*5wAV|Lw|1bvvXWmhQhBjB zxRUp6P2ZTh#9MhmQ{Wx2LbH`>;n*Op zKoBeAQfZd(Eo~#W0M;{cE#|N~^J%FCae?w|t>}t@I+DhNpXJ z6i;n{>+ZywSMw5!Oakj>o;8Vdb#D-r?ooSiO?~s7>7NO-26V3sMD`qtJbD*Z4A}Hn z-5$;okX^hfQhK6|{mS+6TwWW>C1)@%1y!>frH&re(5i9pN|>|bl-=qi4oMMBmsG($ zcpywglf~v+KS!+PWBw`hM9bs+Mrj7QK`PP%`CJSV1a*~{x7ocZO#0ucdz;rsmMkb+ zn7*_~l`V|5)*40lL@h2E_b_126W-5?MYZ+0*74GA1WFzF`6iq>M-=Lc{8U{rlqgQ? z4&_0Y8SZV@8{HnhVU@SFLN}qXuDhi>munqv{(>neJo1u0doOA*!%yGin0M&Fv2|D` zm##&mx&P9HXU->$b22w5FedOtc=*q2TgRM--vm@QnL~A9hV<=jGPEm<92+qoNuEXM}1O?Ta5h$iq zG`I^z=nhBN<+eKehL14Yz4;H&Rti(kV0tiYmMrAa$H6(8KBtr=k2UMq3_0QPa;sFw zA>MDYOI@#|B)QZ%k{ioywJ!69Ppy!xZ0~+6irtuq2iXd2LR;Xp!{#WTlLh`{(8Kma zK}4p@4nL@v&Bfq{A*(yk%=||lUeDlGt~&M?yKUSA;r#9&28(oIjx^zJ0(uvbZuk|Y zMua2HE7$?*{rC?FEU&%oJdo1qqJl$RA5XLodO*RAcnU# z$Gi-Ar_PEq7cMcRsuL+P^sAL#5LNjtsjwMqZ2j8IiU|ER-ePP6@BV?#(z5{ueDjgL zjpmWE+SbPleLlWv@m))Gp{#hnsM04oEHV^zO6|8b)?i+p;w!w1IvWU~B>Af^Iwe)y zpfY(5|6rVqapH9NESM>Qjv5yYI9+1vK7lTIjW!&Ff0L#r1!hcO!aOPUPTW0X&Rm!n z)@<_+64@rA#T%bVNqw%KZrVI3P;#d^z85c&Q>Gu?Qz7LtT#MK6O8N1x-6?8B#UR>3 zYk;9K2xR9!O2|ki(42mf#6givZFtb@o(mqR?*Q-BHuU4dm3R zXU@*M*~)$8r2+!mTxTO|6*bIrUL$!sI$!yE1BGwfs zfr~*)h00e}JK?gXJ`dgbqISN)Hl6kK4D+7&eE2Q1h2r;WGS0PR9lMs5BU_NRMdxzA14$D-Wy-Pv-~l$+ij`ifkoTb@eU&!Z2m0)+uOK^ z3Moh*R7+BxHQ1_zTzg|Lse92ZS$cSHB)^f)cj(kAWHr|cotHWs?kY*j-(!UuOA0An zzHcI5GF?{U{6=TyI3SCLqkyK*Rg%QlD)|kYgV5BWmh0w9ZFKNstyQBcS&TxUX~(Pb zj6h>HkBT8|I@4tlwXbON22F`;MAkxlL0NEcY*oF)uE?$ot89I`14bON!syc+qukLT z%a`1Xj}%7hLb+Tx4_&o{I&q0r6s(ZR(?5D~e!O;;m{6^QC|^3LaZgf-Q7P?DrR%t4 z=M6e4jXnJfcVb*YFIr~gG(j)j;Fd~(z=sZgiy2&Gh}H9n{2`?y-&t9{)JN6k^4_Ua zv#eA#k3S5ZFSr~sz!ZwEzZccjW$1%GiR$H(RvGfNPAzCF`LUrhTWZi7um0cgQ}DLi zMHf_Y8V--r*ctKr)*d0-ggp+{T}N<2c{id})pR~FLDGa$!fbuEdE%S?o4)PFj`vN7 zqlyd=L5hdj$heTTw3j8~ll=|f9#4KM)!p{S^vBMn30WNy|Jm%1){qoGnZO`JIm$vmItk7V?W?zu7?6F0fFwraRjj};U z!oR9M|GU~0x`OhF7Q0lETBw1`%_hxN$=pAbolW9dWFn68;`(LH_Os@C%dFE zV*qWCV8dOx1q=a(>d#jlrs?*jmP==uWIg`#?avg-&k2SOIXM$;c@*0o zD<AOQJhA|vUcc; zbW8WX{tstS$ssj1O^hw<48NH)c8-;H+u|UOf?xW2p3>nOrZ{}+tkVcT(-}94CD{Pc zdBwy zJIgm!j#Ez3K;8PL(BGzOGDDD(@k7<$G0CaWor)PIAMD}t4FZmLWL^q$1c&4v0*v_x zzynS`${Lf?=kJzTB_|+y&Dd_dMCDWpGGAGQUYGB?ZPVCg@lRgJz`%oStL0Mco33^3 z*@B9=8bbeg0gYIJ4_5J&g-Iio(9gpMj6F+|3_iJV&^XS@smT}Lx2i6H?_cyeq|{c;E$*%@c87JS6LVCh3Vc>h?6E~( zd_`>;46(5W>o;T(T(kwF1c-&lSI~F0$cNyB(RylPu@d!FD}66~9K#$J{r|axD=k%i z{w^l^-LQqh`BvZeA;LmJ>xy3^x>m9K^%WKFX3`}cT6@Jk^=17`5Ca8%>hD2MMp|j~ z>UpK47D|u-Jhc`HvYRbNPhYQ>B;WnbANHE@#m=7)h-0i7Y;VJdXdVlJY@LmK8BU9F zmES|f1Uzk>lkUsX(kmaM?Wv=$m6f^1g-e24d$^+xNE6(3TKtoBr&S@fK{_Ou_O=bo zD&HV3{H~P2g2Pgf%U7}fku>JMB+_<`SCj@5wA0fQ)Oh-@M(o`s zXZT2ejncnVh$`u!mb!l!GnUEG+dF({J&_j%3;0iu$t7shkEwsrNQB;k=u>vC%tP9( zP3tUaUx`EZ3Y}0AhftC+jHoLJsY7j0hk3@f_fzGt8BHc>|y)*gi zgvfZ|mk@G!Xqx{B>77EZ?3HC=;+H>6yyzsQUinTl8y9Q0QQK7;ZxTHC^{aI{dfwpr zf2P05Y$f2I-D$mRJ*O6q=VLFG|Lg@2p@;D7)I2V-D9m;;G{9y(bxoS0pKZz#aPDjE zr(EX4P-8nCUFn?SdxTk9AtBFHJ)Zp>ax;sjPLw_-XVg;p2y39z;Ag}gXD$1+*1WkU zmRivDZ3gpAxvbGWr14-371qUnug1s;nf;8BLQ2Y}gLTTWr^_L9_&Cea@D*lg|5X`I z>)rq1=~#nJg5AI3UTOK1rjSdgDzwG@@r6i!u}T9W(RS=>S-U9 zRz)=>@Sg%d&0NgvWC|GS&mC0b11ynWmaFUb^rwGHVen6BchzBqdG4(PC!@l9tS6!` zoeuHa?*;Jabq46!*hT2ZcUEQ}m z$~b4ksFttN-)DbBUK0!2*T0+Bg_K>BS|uzNB^5{8ki4#o{Ie&b4N|1MG|3Ec*d_>S zqmK>#%DkD*B+^uhI3mvxZyZ59b zH>RaWN=iyaf!z0D_=_96{)Nie_<%30A3>W30*Okwr?=iReJ?G}fElv!m{`6+nmFo7 z9=}os1F78B$yaGl%vs+aCtDd<0b&eVieH0K20hoxu}W<*&AWLJ7?^`+(5?T{X6JYy ziJ9Rd`|mzSk87NS{}a~Q3A$L2iGu>y#~uz({5XTfIeZFiliBJx-P-T*_#&i3K4ge| zuYUNe|ChqW*HPAv#4$|{9<-X?#AJn)n)J@uR|}nzmQm`dsln0vedf_xh2=qkLQghz zE^26o3QNEIeA6F}vh`won0JleEi+HR-_v^7nr(8CP~F4FV9h5d$4)-ix^T=iQd>r- zijlO(aj3{8Fpwg6ip{1WyLpH)L@!n}KfqPb(Ztj{8lj1TFLad=gs&MD5>$_zHW&@o ze6JrgUpp@rE3bYunJbdQj==h}94G&}u_mc>gN>ZLGM}Y_>Ml%_N{@qf%O<7q`NQ@Z zPEJuz#^1e+(3ObBDkrt*9t3_**MjfZ%(u{mQ^j3$n2e~QSwAh_m zHy_X1li*vch2&0#F(-?|d3os?agkV2(LI^2rMLOHxA;ahV4C@5Ayb(5Lx*G01{w-5 zRB9Kt;mHR?oX33k#sRbEJDA?N=-e%pK~KG%U-2jW(S`3XbQ6{Ma5IoDYVrfT9C8g) zZV^7G=?7Vi{2$k8+@=`7Vn#=IS`D+;JDQ7lh4=+sn>{g9Pay}_%dM5KLMiyLBwd|z zjPd~98x>eL8S0yJcP~$4U~6Gt75-wPn1@T9^>2@1H+G5v#`&JZ(qI!C33CU>VMkp` zsF4B=C&Rxxc{oS2={ka3fJba+``ms!Z$R+2jeok24Y zCue7xC$4sNc@&I#PqGpd<0AZ8Yr{i`>d>Eg-@AnwD$?VogOVH<= zh#Q2oPrOc?&};+QN-3gkYJj=$CmeDEj<^ls0+B5iO1pQ z`7EK2kk`q6NkP+Vm(Qen0d(Evql0+sjKuDR$gJ#PkBF(s!|xx*ho7U;)n?lcaIJ=q zllDN`Vf=U77WYT=*^*$YvaHlArh&tT!+L7ls#$9EQR~k9&%-TrqvLY7${zn~Aocsy@~#U9WHCWhu(6lBuFEcO~ry;zN47y%3k(qY|Ir?Sr@Z({9U24aIM! z>)fKFqxY73QUqY}eNc85mZNWk-rH>q5no{)e7>#Y#4q%>Gw@xsEwD6+Xd^;FPrgmmfE7ac4!M@@CjpzUL- zu+~-S%n01{mr;eqTQVVd*;HYl6nO6y?ru=kHK}QhUdmdQz-H>mdi>_R{(8=%{-&$s z32FaFdvubpuyAXCtlHLw)n3sfjtZSut@qO{&7-U}rYcq<2}#iv(`CiIJY!J4E_Mek zLFdroVp8tzFX-Qs{~)j7!E6Avt#-A;Vzo@RLc&4O2y7BLF$@{TG*+p zkVb847bEu<$uSN}$KSP~YR?CHFz^WZeu$;v|? zGo3wJH0K@}z0q`^o8|Zm{XA9K$r^*3ZOpQtpBEd8^b-AXY!`NF-XdZ|MjUj5Ee5oh zLY#xL>pHF0ZP7K4lo!XT+y%<9?=BuujEA!>A7UW537F(xbE~bJUSW%jQJI29-{o)X zqcArv2cp5!y8eWds^I2TWzW8hsnb9<)Faebb+PQ&RUJrMNo!T>(}WPcUnaI`%el~8{;?E&F2`}O%TJLAaIsE3Po ziIK?ZL?_b5D#vL_I>EcaYUh4PyK4FVh1F$vl}l8%s>9H;MrtVsGDdk5V&XnXk-7(Y zHy@>A=qH7&T=I~XIXAP6uq2cedkiV8gH^5jHK)&$M?tQjqa}qvsD9RWw&M?ev;~nM zw9Dmg{GHyLws-gTPQ8V^&yLD12TJ)xz0X|D=j}}mHEZiLL`u_3a)n8)?gSX>(s||< zZhm{ZqJtPFpmqv*QeW<>Aj>N%7NI4AmyblUr1__?7EDKBIf9>&636LjR(HB@s?2u@ z5cf&(5id>>PcE!P-w9>?ALev)bR>Y`2azyeoHky1VAqD4D^^!lM$0TB0zH>S(beTc zW^a^X@^#j+t|PXQKWKf9y~qf-)Q9rzhPbHggTKdS`L7B1-Nltr*gHU#-7r+B>*%@Rs4Y|l1d9;aNo zZT8LojJRA9Y$T34J3DI$xo5OC7qAi}b3mvo_7e0d^$hYKnnYb=D6q|thfrbeKC-JZ zH`Ba(J3vOi)l#!WOsl-YPQGVm1SJI#^ZI7R#urF#8D^>oU9q&ZtR4L)?XA4uzXhWv z`nVgBsF)qNK3(t896)e-xFzAXn-S>bT}|isNUJa ziBH1!i%>Gg@y{M7XhdBM8I}{0l&I)`WElY<-GTBY-G4Z*U~MHC4|!Qo%bfltV>n6n z99aW)MD$bUxbZN=%C;tG-qXn<*VwvC97UbcB zw1+MjT`U?gDa7yBg5-X*GtX7e=alsIky_T-_6Lde2_1KQOAZtw7Pl1Nf)y|C8sS9! zrOM`|w*fZod#^*RNr3dnsU5LztuSKeX9^lY5XeW1vc;EBAFt!{662vY_q2XtPoH}X zBda>LFxTAFx*wzNl~aQxmX=mFafT$?1I7DM%688+3}PqF-ws%@sXrXtceRurMRs!) z=~z07&F%$=U8D%(A>1bM3bJ~P3%bG-Jm!YU{@QxqPzYO$a6dzwQg3pF!|g?P85@{K zDNr6-QeFxBBLt!1|6*{t#Ad9t+HtwzWGxT4msgEKfR0yAqa%hRfzPu4i&kXlhe|#( z(Hx{9acyaiKzXxfSt@-MgYrEkXs{Iri-VY^!MSW)0elO$MW;Ho4omEFMCRiZGa@Wf zc3*vji&}6=a|m`j--txnVl;`(Gxg_G1+BH4S}i=HQIoy%deBe#sNy^Ai|BQFK=L(}HFU zwgr;nWW7!m)}horR%Y?D_RltRBg&uQG@`&G?XM1SNq6GRRMI!tU>fBFOG-tY)W7SHLDxpMQ{A7`HCsU}34+ ztig1{Tn^U9F3-`INrG@g9i6e+<_}zMaX2Se<^Fc`?BVHF4W_Wc$I55%zJzxj+@Tp( zIc3gA)dP!s#RTpcdu2LS*Vg8^uCDjmNkdC3_VZ_OK_gWenGb;!_yIO-kFFeIu-|zR2Y>*64HTsum(jhCm5bS~K|raY8)J``0i#bb&Z zlN*V^*>N&p6BQiH%rYvU_2Bi+qqrs7?017G@Nvt=o;a@!%Inj<<-5wg+)Lew!UMy@ z2YoVhQ=WTWptc5O=yJvJ(R>8jZJ8#$?+YyW3Nvr>l;Q9#y33=V)dU#Dn@TAJbUy$l0p~ zu~(kAN`GUz{&X-`jfCk{6{fH@0Ji<@2Hn{P+=nEJ8eX?EfxbA%EV$G3;Hu&Cx)X&$ zB?;L}O4&A^AAnD9PU5zkI!si+AjW)D@Y;}tu8|~0=bS%4?Hb(gv{E3opp+m08+_d1zEpf@%*yW892M4Z>c1gC}GeD|Y=-JyL#5%Kftqr2U=Q@jpz07pO2 zc^|birv$cP0gdLv1ecbUHm7PUYim9FGhTusRuN8q4)Aoizn@|4y4NKr{V?v;3$RI@ zj}>BcIzD1sy%_WI6I0lU44BobGe8*t_A>xDBhQ_dk%j|QrvxRRf~e<_osv?|a*B_* zWq$^6*L8JuJB5c<_JBc~o0|x<*C7~6J2=ih&4zF_0IL7+*s4c>QYkSp5$-up4QjaN zV$7xfOYxJHbin&Waj)^$+zZRg*_Xv~n2ilFr+>TJ+q$KA>yzYHHNa#yo=$BYpg_NB-{|sW1WZo()=0g_A+3_M_wk8| zQ$uwPX8_a@{pRN3CdR8r^Gq`H@-PLJ)9&D}E3yD>@IG11zB)tWVf|M0=g(mF>`xCi z-~cV)>Z1b#BoRO1fK5J^hdz~KHfJU)cdvL$2dH@^Nk9idsHByYz~0*G%ZpRcDMAko zVXrXQ^zK@=ViFi{1b~3^Pa4D|h{^Ir`f)G_PmtiWE5rReS7_R5IJGr2oL(EsyT`5_ zS)I8DK6cpqoX}q~wH64KR^!PKn2-+}Ygd>=S&t;Z8z@6sq)fp{s;jF3FYJWwN69V# zLR^gt&>!n`de6``wZ8rw%mq;tAiax|6F~OleboJ$KsyUF>bR0I8Z5 zmsk4Iea`0TfW{uqf{|YwFN=wZUG>+%-Aw<3N4~$m&nF;oaDKX$9w9FG@NVUlOTq}| z3azeMUK&ss%nQH|K-6_@FqaD`cV`^$RZmeXUt2|4*>0sb6@7Ve2*$eklg`HzFa?y2 z)6OFXz^JQfIM?OTvi*#p^VvX+9BiR4fvnJodme$b;RYnrqANby)(+snpw>l0Qa$eRWj)8Arp^@#Ti;Ig23JT911lNv2XZ<=JOx1fJwx;WO;?@NlkGo7F z#LR7NlcS<`K1iIUmY47MralKnE;#2{jdNaOX;QMi3#Fc#4sV3VoDpz=G{7CSD<- zqi4Q+;L9mK7uDI>%WOq;JeK_rbJb4(@vc%gxKGSTQBPaj*MU`_?#4WEz`%@^n8+9y zBvn=-Y;4veJKgeE*VoSu8!xA(r!QKm;YUYDHsj@%%iT#NN92^{8zkXeGnxl@~-QB$+&aY^;l9Cd5!|~FOAd;@m&O7&owt>WVCW*$@*noy~ zK&7jzt0zz`_4Z+Kc%2?xb^C!DBnZOq+`2{Yr>(6mBrHrnio?B21Rg=AaKG&j0l_}O zVyuVrQyYXC{rvp>yS_Z0A4gdOCxcSVo~U!%`|gj&!NGx8AGP0IcDO$rz zXDgX%cX@HnteDsf680o50&#A1#teh7j(z)%4;H0W?=C#u~Ph@PRLVRBfQf|=RkilWDLbxlq0gE0$fX=(NM z`Hv{@Tm5d42*9V$p6&$1#KeFUC@3y|0W2IZzcC!%2)J3)aKg&K@ciN3YM?tn=0VWF z*)P}fima@x_^863KH#>mFc}6*6?sS`n07p5Vl2>e-GZz;tdzyt`MtfpZ{NO+kEe>3 zla4mnc$qh3ZeekWF}kb)!>@712*AcobE^0E2b5xCV|}ngT7wZ{34&kZ;@sTbRjF@; zy?CBvnE+hMTuTTI4b6uQl50)p^dJRt@3XS9UM0Psv>u&AHeUf+xG6&AV>!hx&-T=^ z6;b8o5B;1Fh=jN}a624&75Q3yo&}nEAk%4RWUA)Y)YeW-P8yq-balR%m6&p1m!iD@nFgdf$B-8alpedNwwT{x1`M_5#SWMi&}2PH*!I`Xg!f zueb%~axmt3(FpjOwKWDLhVD4t>=7@Z5TM1Vr>mPIrvn5BA0Pid0#z&`B2rpf`rg+! zJuMA5Q+mH&zMH4dJUu;uSo%CU-yg6-)xa%hfD!uq`SZ0Kcfi8)6EL#+3sv);WEdQd zo|@WNU%yXEDs^7Ag#n%>YhX1%>}uhssc0Cq4Uau9@VM%FF?n`uY;06vE+BJpHJ*Kx zlODogr>3TWP&|0>b!6C=2=b{NM3Rb{I+qaxgppY(`3bAMW{^~xIxC2k!n)QyBBJe1 z-ku+=t?}N9A>;4;KYWnrt##R)w1mUqHwBbeoNE02rNM}&Y7u}7O8gGJKqQj7zkQ?U z;VFe*@&bL*)MSd11tHg99ok*&_&Kk&0N4nm+~@KXJ!T`oFNrn5VBwwp{XDF!YY5

DVKZ*K5)vBvIJ~Tu|LNZYK z{5en)C#U_zj#w`*FOP79vvblDHwO?zfLeh2jkx(&so!nftAt5oAVI6NE^74;ZoORZ1$VwZ%mJ}v_{H@A?G>&%B=rlmS%=9Cplz}{He*bG{s&S{E+Lqoxe$J*GsV$q0}mX^=u z`5~Yc@GE_NeO`!Ea4zGLFYX>br#T?OkVtlRcAjK?yn@0R^5*sTGcz-wYy}dXJP(PI zeRy}(sb+iIZtc1l{g2L0_QzL8-%0_{zF2mhv_2>ji7eMG2np$U&ZXloIlDTLZDL}= z{OSw$5#r^;k3h@t?s3|n8^qYz*Q2!zA3vVvu35uiv3e%6ll^( zcze#&j*X8iCJOB|L}!7z=&E#l-tZk5EVA4GgtX|EnJb_}z!fB)Ki6T`?C}}ZEfC=4 z-2-6ai39C*vx|!huRVC7VZ9tIikwq_6wN0mCwG&cmX;Qj7PPM2INX2#$7dM3xVYT9 zbqlbnz7?>mV|niuJ*adM_V$#W1yH_tUtizGMjtJ$dkJ01;$Ah6NG3oUi{a42rG!@j z7Xxfwi?O|hg~gjUZ$O$YQrno1s;oTR^11YAKIohQ3Nm=NqLG2u>oEmBXDnuBrgv%z z+_jDStp};ft}{*V_V=Aox?)XcU{W|^eL%9lCX@W-)e>+ySN)fFbX3H|&(iyHi~@BF zK<8m;?--KsYCPVen5Yq44>!Z_CY6aOw`}r4+j=c1yp!O6qArmt* zGb6sjLRwlHZZa=GLsNQK$D%k$IbLOwMFzE5>Z~s>(KQDxuem3urjnA9qUFr&?1~>@ zj)6n)ImZ}*`1pnjCW;~ob8>R>^5h{=`ZZ3u@b-%x7JyYy3Dx78@#v_i5Yzu?Z@1h& z<;TMdX=-{}pqV#h1u&z)t}A~tHzx;l#kg!Is~+2B<}NLnqjc-t_LkmlEp2R^_serl z2~J0T`LZ%MC#jJIdI;jK+YjjdIu@xEevM$T2L}iBa`HnXBPkL-4He**MofBwga9Ve z3+;NcZ)p`WXv9>m&E8-?k4yiftE&L6NrV&ng85L$Ycf}DwLFzenhOa!-6sCnt5!jtUruP5)u-!vn_nyd^|hz zM4A~DKEDIMTHBX)HT1OtE(Hst}_P$*<03+!OCSi zY>SNo#Zb(4bZ`g`3?vF^advhlJYOkE*P?$Q2cY`w*{C3pWpTL%eT4LlR$bp zywA?c3OGSd|B##84%EnAgd5HXgi*b_M&8iL@iFC;8Hr?us-?6vpzZF#fxrnAhvH2j zXjq0ug5n`7i;0>#0c6C6mYq|E*bew~-J{qJfJ2$m=TCvn)7GZIX6^yMB~eI{vV}Q2 z-czSuxFOdFv$4s~&Fx!t^7i)j(qoZe5lBc%Ote{{?W02~VOztf74XHe&KGBHv=K5l zL3_sAWPcu%U2AJ=M@O#BfrdqJ7_8p=T!j7yuxn5&NdQ$7lXSVv;Najju9#kcg#P|3 zPhx%gpCxNt0E659@4L*=hoXzgx_WxRXYo^orKF_v6?J@Q2NF&~LXum0s#Ro26U{Wl zke;5-AR&PU-HWNI^LG#t5VnGXff$k)gYWF5nL_vjX5kdd)sn~yzTt-t7{i+kk) zTIXP>-%`S;-bP1jfc)w+#f7^H5;-UsfwF+KLRj8g1n#+@0LjI}R@S+_ zV^CxO5zTT)^AL7i>I7{Icg=9sydm&W;355p?tC!e(*-t%hP8nC$`c-3TLd=HkBFDI ztbt?rDx7bLR6zzaGAinWW+|myJWY5HngW2M;D?;C)^coBH_V`#g5|)%0bLn#=-jUr z77^)==f}JgQQZgG2^1p$_MlA%95vmF+C4HduvY{Z7q@iGhLxMQQ008|$|myBGLeVm z<>loPT2rjAuan-q4y>?WWMm{!`YIkEQWj4i;H>$6wQBC?Uy*iT1KKWw4$ijSfAYdD zP*@Gl?i3dnH{1yMVQddN<*~6^Xn!VW!+O(^0Jw4Ba zbhUPl&%k6R2|Jq46t?-AT3gq;W35Q$2>^i9#d;gMs6k#;W_fs?p*S))sIH|YBPB(_ zI*U|CzJLE7jHtU?(Z}azidhagY?KZ^3N?E49YOx(!@#1E>PUWOACN{D|b` zyhV0SArn1 zAD94~ww|8YjzzynQ0f~p8#sw1DYF30c+pt6xZ?^&{)tIp4P{#IdFhltlk3&;^01MNDFW=M4(ce zUtP5Vh8EEB*p&{^Qr>qS7x^cm>H6J>EC9Q<4V zA%dia2HDWxZ?4oRK@jx%1yfT~LB^<8{ITLB^8eU-^KdNRwrluml8OvPB1AHlBtsb@ z^E@Y0rX)j|B2$J^NFgLsQpud55HgmK6iJ38b4Vc~W&GB8xu5rb-|zeT`|rKBXM48o z*Xp-MbwC z@JvkcDJj*Cor34ijUqxu4j+3KQa?1!MZbl^20sZI)$b7Rfdd9v2B;{cH-C4Rh^2dl zH4C<}5jMVXAy0p#PE(3CB&+Z>2 zPkO^*81OttMxE;xR!RE^LdN?0$27ko>QCQkAL@*aj-E4mrYA`WgiEe4cY@A&{aT@I zar3QPh#}xzub7l3M$}n@-$-!Vd|l4Uu2*)V(}(}SfeLUS2yTn@EPxr24fZOgq zFG}0C!!Q&Uwl&v~g^^K-^)$i;k|1DUFhR}u>gq;SR{DWkYB@g#luQT{_oa4EQv^nZ zkP&@3jut$A#U>NDJ6T(!K@R?z_yXDxAfc+Ns&c!Nh^Qzl&|_otem`|4zSy@c;!e2b z+e3CRG4aw;ViPhmGcz7Ec|G6~!6xkkz6fi9@?)Cb*~P`hsKD}Nrj$vVUK(=nxpSL0 zZOSz+3|{az5`Gb6W2814d$!T?OPZ)s~7s^K*}my&k&ThYZ`dF%F76O% z>FDU_P7@s)yFW^0)~E7e$UU{RZYV_{N^Sl|H4JUJ{_4Sl2j+FB51CgWanGOtqp2I+ z5V$#r*fu&J?Lb&GB|F#HIswQaYR9n7#kTO+A*=RY974M za$g!8bav;DV|%pn-??WQBmzs{xnomQrQ_$f4B`YO{qoY%+omS4;$>z|C}MBkM46n? z_8rik$ef4#o`WbUZZybg_ls%M*V8jIGg}b52-XL`27wGA(fP^~9A;RBzm{DLp&c9= zl26kt!V6XK=FKerM^H_FV)tS5bU@Yp?%nL%9BZ}#6Onseue6L3@fNiSA`y^k+8{M} z=f_no9&T>q9(RG57onvX71~mV)PDCZ!MD79t0ox7vU8^a*u{i|#&2#zLqpP1QXAK= zOV*0Kb&DttS|!9jG_5Qz%7C^C4h}|;*PW(F(720=`15D18R$IUWVUkuWgmV0wjJ71 zRAM)bX!yc`lu5nnJg^k3vo(Q4xU@CFKLlro&-Nv_dAg|oqbx3c^b0qk* znFrLDCb}Ww{2?fEJ35x@a#1NMz>gPfZJ#3`LAHSe5Yg??)!lu3?vp-<3pY>CsWN#G z9#eCa8!FBFa9fcx=l4?tSvfjNnn#FAW6dTF3=Cj<-?VX~&Z5Xeol<-kh%n*(`>&6; zS?-NeL6N3U5j6ctUwd~YOJqY%Ru-YG0vdo_0=@*ZqnbPom&{>0~JWk_grKTSaLNsHum%^;Rw??b*jX3 z$~?L^V-9&LI~ah*k47zYKhf!+=|Zs(g3l7ifqGhhYo?xRc+& z0@}V$1gD{I@%ds|&+5{s4D!d&{_DxK^eikW()Y$RHmAt2@7QsMDNcopP;^i?K#Gx0 z^=lp)9E3a@la%zOt1GkBj%s!1&9JblrI{v#3NV-IX?nH!oT8#AJ^lsLMj$X279N?~ zTw6bYBoIQwZd>>nH-%|e*$63;ja;PCCu`Ac-Rb}>at6tq>LJ!SyO$U%5X z_dP?5KmY?zoq92*(FV59YOiVQzBoG(6It0B;J42L+vao!M@JiM3o9!sR{oS!>+)0( zHWs)Fo|u*CanU0k5`6ceieFa^b1E-Qn5e034OdzOukTRgdtZaw(ZL~FEe$FZxR-%f z*UbbwZ?nF$6aol8`i#AqD4Y*f&VEEG4B{wVEBOVYfTX148Ubr)XjlaedO4X2suDPw z7q~-6TakN?J+pn!Tx^nz8Y>||m0?|1iL-^Hqd;T>SX@vMM+tAop~_E%pXFs`WzU~K z4^@)D#gDHG;YCM6vm?@7SoMNGbg5_K>0B;n@yTXUzoRG*D@{_8Vbg3n&g# z^|A>5RZq{{=lgyT7(g`$(*m(?p^?PBx1Fzy1=MqJc(k6$q1dPOk)m|m6L*Qqsc4V) ziJ~Z&q~)0@gcEMHjG}P%!~gkNq_ur-LWxo0l$?=~(O4aHm|s{J&@Tq4;2*^GOnF-i zzqxiC(%M?W%#T!{oh(rdyp3c5H3V?#*RNkV>MYCAP!KDhKGn@KxG&-Hwxz`x*|)d1 zH+cC$Lc(Y0O3Hs~6W&6%1Mf%(B)D?yltSF$?4uJ;&oqcIzfadpT4;KMJ+=V533jd5 z-(Oa!G2q(tba#iTVF9EWc$}LN5qViz#~?p~o@IopkE0nA^BZy{Q?HY~J&0389|N#f za2lY9!g@idK%M-=yt3Qwz69wODY12R-#SuYh@qL;5+sscyLN$)h9ClU?2t*(o4!5^ z?ii5s(~t;1arV~LorQ)49uXReh|f>CTtlMFz_~?QAY2NFav%fXR$2ge$i096?t?Dg z%g_Tm^P9f8rS4b+gMBwX-flKD9E5XZWD8(wxL{~C_7eDOq+`&Nez;XMe;1hqfU9k7 zN3a~g7RCpVPDTN!Mp{x@Yzy%d{gT zdVx@%ZQZ&xb1)ks8SDc3z8=3=Odwxssj4s|32%!-Hw;-li@VQ;tLjxn~dScO*v znsgh=7ua4R;UIyO>?2*0nQ7OVcbb8L0k{Yp$Bi2|up5V5j{5yz*iiFE7B*(fPK!k0y(VGy-jDx0#-JJD_mhoo$@3bl;tW{_fZ@n9oIF2lk(8Dmc6M8oUg1KS`YsnYz2x za!b)`h8#&!?|}6RzX%cp;hCInV26%KID%kZ+{eiYkE5-7W3~bRVn<&_4`{>$u#OPW z2w%tiNe7Rw7Sd_T`+8-4&hG|^4M+zrBrEbs+jj**#Q?5HTMnWjnCCzxCnBWc1EHKD zAFGQc9i+cu4oeuaGKlU!Ir&x09sgMX!<;mK8vfX@mzMa|u1EKzDjNIh=0HFxO-&8* z!C_1-EG&E|e8JH%hZun(f>ymRU&^Osjue}`AN?&UAu;PCUEK7;qhbq5iD{f~9f|5N z!EVJy@M>_!j8_REO-P7~cQ!W*a&y5 z<_pKq8vu&~x+2@Xs;$MY#S7BLUHDD_@kGVM^wc|QLuiy0761MHtE2qj2{cz*UHwRu zAsXDjJ1dgLoSS4b+K%msXubPY>1(O0`~gNVV@+VT0eIWn33?ea^b8a+l{yv(!qwoe zAYS`l_H%Bw6k>Basr^lG_DNZ{egOL2oRv8Y0}pSC#bm;IPGIH_ANKCt3Xo0Ba2q9` zd49>WXOHfd@yCuM2jGm3T@{Va9HGXM00SJHM`7^nL1m@1M}(?ioIb;~V5zPe>!(;P z9Xs+cX$o0UXVhoEW@dzE?H}BI0!Ar#{|}U*chvTG+})?jyYqQb5$r4oRPwW-3ps~( z>eJs)Ae20p;j2;~`0jG60!OSpBLK#ykf0?PpPs7Z8jcPRqx8m}mcOw3$dM!5G4_s* z>dCwL1Oxz62q#x&^X#b%VAp5QKBCe^!RONd2GTNiGvtgT`SK;Wvh`PF zAL@Xs5SNx-Ms8aDL`6yI;_12Th64EX zh9Tt2e50qkM< z$|dY0f4a^9fFkOm#g{18aJ-1vd*Om+YAehXmNYOclxqt=C5j#}fCH&%7>Ir_kKg!CN!!XpzqyED_U%Td!3r|`(gz5=US z6d}L^qJXbf4q|`ai}&e#uEA=;ZKa>nJ~1%?_yayxDRu5%dp>ncw`b?!Z;(vgd z0Kf>p4Dm$CmlJR8c!<#{HTl8bVeJV*}ozMA&xz`%0IS-v8hK zA_+095tsk@Crf_fJO9_K#(^>Qrmt0gi%=zC*91EhUs#}FV=~6Q%JG(JE z?cKyhSQgm%RQltmEEA4uh|<%jorDuKD1zWq1vFtToQU{}?xS@Jq{U@K1pf+p~QX zDV1=VDRSx}Ai>9=?At+J(xB@;YG+RQ`>$ZZ01VGEJ#4kxzI{7DEF>e&C_7Xj0HfD# zBV37!h=9!Y^qg-^Iz)c&><=IVn07!NiQYmU5=(k-Td1$EkI1kbSG@$E>UG-a`}YMI zZ^DxZI5zg4plwL~S2%iwl#mbzvo1jd<+~?BuC2Ja9SRlmnBI#>gvh&z}WuS9WTiy>s=I4wGt+NL6 z9vDbsyr~!tEC-69IQ6h5@smg~AC!I9Ti!zfh_*vOC*SQbj>Gs!FNd4%;_{1ElPr;t z*fhX)pq%e?)H%SY|1Ea?`t_(7l+KuwKSh4aKk74|V2@nb9#&_a%~}M;@joGIND)2g zeJ4Pco0zCkZlR?71upgbF>=hL5*-%5#lsmjhDsiC6hQjs2jtJI7d@U5@T21(L;@KZ z8RCxJC+Bq{mNAJVP=WzQ0S0j$L@yU0sGooN3NJ^6I(I)>! zucF-!X$ybcXMcKEs&Gm8%x0FA{c|~I)nxPR(Id{Q(Q4$c2}(E2p+P?l ziX~XA!U&ZW>j3>6c^XTB1(D8oc63}s4d+9>ee)Grke4BA?-epo%245@dIH4-tOca2 zyTHWYnom$hHGSJ9Xodt|QdkIE#5lt#w4RsZVvLNsTpC!g7*qi&Dk@AJ=g3PY#Vlx1 zMMz)Rr>KJQANOcEW7SX-?5Dp$R0pa1f?ke!FJn9HVr7+vb${T#k)a{uT*#|eudr@JE#;4fg4QiD z3LoS?IE#1h--mb@8ayu^P?rBmUKJ8W|HOo5MjOO}ii@LK$y#wxIT2~lHc|qZ{|qL4 z)OBQ=6*V+|j_haxN-U;0)1pU;x&#)(axT~(w+Tn6bksxFZnv2Y|=i+%EL_zn=S*+GPxi)de&BQSEjOH~GaxQf zX!jts5Uig^OPyOzDrlV3BkxL5{jLNJTahAg z>ud3Zqz~Xce@^5};#F#L1g`ljEc=z~z!Y&QH9JGaYnG`Ce(>`1(^GETcZ{4uNkVm` zX$k`k@}Vccz18A*@w#SN^3~tkwf@Qjr# zT!U&-BClEck595_!C!{ zw!xWbDadlAk@$z2)Xl`7_!Z{zZ4mb&{sje^IZvLP7y8_>^FM&J{@JTnatRt@Z*E2nlHWtKZkl4ObHl`8 z#0-jRUvE2mr>Ej=pTWDR@yS_l(>}Ic8-Yzz(@DHaMqy0U($?m=2EVM!(R=2d@SRizk(X)% z7_)`g+qXY>!qcmtYlw!!-%lIZSpI=8!K()1;$4^?^{0aoGT~2cjo(T9yOf^J|BTBZ z{`3C=`u{&m7-5!)HPA(@bWQ4$($e^bq4rOo&|T5rZ;6e7|Ic_+wEOq^K#pMIwAOU( zk846chnj}uj+#N)SAuvii9{3JFa#%fd0t+#ke;ET66Ju)Q4AFU$Gy8UYhBF;d7@0S zJOEQkPjx`G?B20sOgnZII(?Pcvz{EO0$n-8#XZq5^C@M+h7IuKa6Cp!(Tf)*dudU& zZbtcvSE__EiAjxI9^N_#+<`wwLi4kLfCB%d4?0R*Dc5S=`lI}XS7={-b3?hVyorT3 zJUkrIm-G4a;Ek!bZ?C7=+#hv?JdNT^Q{L(FOiOu7%YL*^J%jEE0c2%}eN{zG4gFH^ zn4mMff7&ZmdJS;~UeS3;fwqyi0{OF4Vzj`SlfbW;FHuqf%CshMlBh(<;iLXGI8#6y zITby+;tMHO z6<~8D)!OxMb%=UzBMf4ZqV$$eaaEQ7wRCdEAPu2GbrG^oX8y_+j`L!WJYPJ08bzxI z8<)9xl~rvpe2r1}=r!B3N(w}mGIe;BX1LGID!lK5@&L^DNb+l&1Psrf?dR;+(LSIdU6Pe`gH|q1)b#7WyRGK-+*w@L z?2OqY?kaosn}~WIXILWkZ1)yYjok_Io}ERd1f2?!eFUxE>C@7`>OO742ktve_^FYK zQqU=Qh?WwzZQ>@IXCy+kO-K93nTG98jVdrU4khV1mHU|n`~m1tg*Z@~uEa&}Vb(j) ze(7G`q=;GlZP6n(??*0N*Slo!Tbh-F3dS*x1UO_R$m^(NeB#7QG<&fhPjP0-%Fbqf zkj4C;;zUS@EfU5=WlB{I4Ut5-3AlGqLxM1>09jj5@Zoi~8g>H;N#LlH{IQ=xi;G2r zUj7YlI+&84g0?$*?TU0-9(Fm(sF@p?5x)c`>Q0qtmMoq6xbAoRccY`}`Fnr;Fb2+clawrPU8@FaysYiELj~;Y z6NN)A_|kitlIq)PX+*;uTFr)vGEgX-3 z-qUYWbvqQLVKghd0{~)5gMt0XuT8p*rO>nrF%{T~JWiIOl+>1F|#3Y6Lgj zDKoP@?W`tT^!RIhH?15BTJ*#m4P&<|#kGM(hLxr^6yz}FM*KIVGep>$?>xjd47{Q{ zk(i({QWN)e{%TdpdpL!fns(f*`xJWpdL2wQ@Kk~g(MWAw@ysf?{T4?L!|NOa~)StUrl=ha84q2V((>ed$B$YHH7(KiAUKjBWY` zhG)_v2Dv+&Mf~_Hi_)ntB~x&dU!xUEVr5`Zylx6_Cpc87o@k4N&JAYZ59R6_bE47k z%?*+umF_w@%GAnej;u#biK2p05_iiZzMY^%+Y8q<0E)$4Ar#QqQ%|0}6B?YFVrOBI z#3*%h`_I+1v2=2w2@Fp!F^yF@?NHsk8h3M@<r==wglAaE)V{yPQUo%C|3u<7aP z4WAgb_E|l;cI_I%3w$mps=%nw%Grr@!^8|rCzeRreS9A<;H|AuM76tpjS!I%icHBJ!6m7rl3A zv(eX;yLppK-@+uzw{S3r+!*{-EhZ{TCr8-b%1uE9q^ZZjVNd<90ZR>9EJ574*Dp-e zLyTT7wDN~vx}&WkCC96o6MkYOrr&Ep&>Z=qFJM*rWf{TMfB+2=kRTIPs=e3O#6wK5-uj}ggc7}oc1A&fU9(?WEt-l+|XMjx! zm2B+Go{K`Dyg_iw$Cot?O~Z=l2TNS`B>|3WXVcHx{IDa9AJFW>n9+cV`?4TSDG=T|T=yY?2L4}H9Xr=IJ!MWwXcQ?C)Ho z9o!>T8c9hy!%E(JwbQi>TH9nu2@woFx)7!UjrvN5^oX9$X zu@XS6kSNfXBvVs#Po9!PfrG1mb?!-|+)E22Zd*#X%U=*BcoV9(TqU0kTQslRI$>E_SWa84& zquCVDJo)+f8sEJ`_(Mn3XPhUBwi6Ez#j3@E@qyQ_dqJHdC@t+Q*n7ANb8-auG&!UW zb6nFf)~ZNfO7VQ5$)$Dt@h>L2cFj08?yrYbcfNq=*VAKmJVpETD;r@@8(7h-`wlek z_^ugs(VyhWdb=-X@%yHO+548>S_mRSkPUNi%%$mJj)H`=H2T|z|pE;uIU1pXV z>2e@|{lfYyfwaOd1pr~TgqLM?2Gi+md%)zcekaGjeab8+ zOYf>3WG8uCf!kK)9T`IRTVeOX(l7T0O)9<=EL6aS5VWf>$^_^PNDzDGWzX}fsuj3) zzzG*Br9M=;?B|D1$EvStn_h2LdNj^;?e>Fs|EaSRvK6lyD;+zw-q#ZU49K`9AJfF0 zw^I1aPC2#5UU2XJ49e=TjrB_(kDCZ`Eb;5bDt}V5wo)Hib+lvKOgckayPAGL%FWyN zz^MMfpD-O-Cd$#&=krvbNYkT}LwNq?_HVV>W=brZ6At2zV*%l7}KVOMK z0C)K6Kkn5i`fKX;XVXVBSrY+O$FozXE=V^n1uTF3zK+DUg$(24A7^FRqg5ZL{!=7$ zu$JSCKWW9TuYg(o^y$;jujQQubx=z+w6w&0&cfFJpQA3Q^EIi=Y?2gWPstHrLo$U`}s;NqO4L+yb(bRKF7_7$Y*tUFO?B>=@iiCz`lLm&b)sKN0E?( z0e2f5!k}F7s_Y&6`Ln`xsGj481)25`I*$%n8=idgtew?C2%jM!Ehwk?6eicOeWbBD_5mq!Le9-Ur%vbcCY>3OyGx5=q_$K2z6 z%XX$I@2fr^3S;015AyCWFwwB`-YRMoL^`!s`MRb1QJT>ycKJ}s_{~h)BNw4Om*xHN zIQ{$M7wUVC_d6Gt8R>XvTxV$MvJULFGyzo;@UH*iX)y>eq3(o_F0stmJ>7%Cg zFl&H$kTAqa{i?xJ-E3c&9p@`ketki2UVe|@z369`>7rD>YMSg~k7cVAE;zM=2;O&bd$RB)=ZFeP4n2xI4Ta0wHEr{BbNN&hmt# zlM}iNenGp0W6mOA44-bR8-6E&?sUj5BZ0HsTmMO%csnC6?auILWvb%07NGq12SGu# z=(mJN!0U%1v(LHwDCHHd?p=?w4YXc|*=A=dhXv(~sdumLh@$&LUpkT3yNM*h0U^Af z0%wdd3ZPriN3&{<>; zv}xkzFMs^he+j7r2rVu)_C}~)))L0T?cTZ5y~Qa7zb0_qUO;^qrrd)p6TLmYip1V~ zM=x-8F_HS~GsCc?k})@_pAPI^{a0}5uwR;Y{fh`s;AqnSQl)P9?^L4V#MztO0)xZ* znyUuOZrk4>^;{%|shOR7A)qSqMgv1S$w|(51mcc z;^FL^+W#vR;TGbu$l=3J)6)sEpp1PX9)pr-@5fWa1* zmOuO$7T}z46rO+dOhe&y!r1{56&>+aDp2*%%h(vx*{O}eB=9j$Jul76)5>WN3k^|j zIr4P7I{pIsBR~-&9Y%pb5q3kv6}q@aCJ8S{sW^;@#U>Z@^rBx{($e8Tp}v91^v&Dx zbmuM!&THE;Y?f-jTI4nFJ*BSTPsKyB{6);ir*edmAMsbxZCHgEYK-LQNx^|t5+8)`_{n=kKSrQ0fDBXW05l!9lTDRe#MnaQoB^9>Gf`z3 zqB%xm5UvN<6P`a8g9wbdIlewVy=EB6CakPJO*O^BBMEcRvuwp&_rpLV>%#Zwt6t-2e@Sq_r zM-V@~0;BaBUcUw!$^SBfN}r7l4zu1ec;B$wjJg)$N%=j<_Na(T?dgOf9V?xN0fSX&zMx5 zlusztxO@1>>&A>PH*URnR{?;?#K?GQbc45M>K=Z#B(*}*fTQPH&CX1SoxJC_yMtt@ z!bu!1KO|pRn$d2F{LMKCU;~G_GMl%;L!DXwN3g78m>!1KU=k2UKvau3!q={v9>oqn z_#>s%@0Z_THX*h>;ihqyApCg>7`8ynDZMY{{mk2k;C1~U1@pI7?X3%GXZ2M(&Oo<& zVDFXHgXY^LFO?J*!zOczu$m|;UJpejB!&Ht;(NZ|yykOBol}MG4jWYS7n}o1PHhOh zLOkY5=nfpH>FMcgQeFjBRptr?{Ot(NgfYnaHRZ(;v3>%ej6`nTzI~EjEFKCR8gMY$ z3pC*Iy?gsHRwx;DaCHe$oApG5nf+^^$m+NeYQ%T;aZaX^+Q|fiSk*JJOJ{;KOa$>O zIT6x8j|fW#oUyW+hDkmbu0+@=M=r3FD0UII{R6%aO_8m{d>7m>;%I^8St=+H@@3;5 zKhcoLn4F z$6unTlTl}*c#m))SZC z-5?hBF(!D}<1n*Ea-+Qq_(n5c=w-!eYEJ&x?D_Rj2KXlV`a}(9g_`!jaI#B|g zkC^#7-uAxTW2UI^a5c}u2ijG{A!`z8!&gLb%=t)8{@UXI=LqsrbIAXZsnpe*Fz8Y0 zzyaKpW{vmT4dK;Lj$}K@yAwf?Fh{hkE@>B=_+2zcCN|IC6&1qfliBA>WShyF++fM1 zkD>M1{&t&4!BWJIA)$a|VPW}l_VggQRLrj{D=iIugS-rf#i7$LY$OPa8%zh!cxNYs z&x#SJ19eL%nh7e+iDm&s1qF9=Nz4io6cxoVjW89IYiK7bV|Ut(g~HnU#_!)uN?!Kn2dL=u7h;Wxnox4ogDp^3y!zbH<~RXt&Ck@|t=NB0l; z8oheh$h+&J!sAA(M;-xln@I9Z#O|&6TT{9;fL!-~(2ieeJ~c4lia|^=vmfL&Qn3#LUvjyaE-$X*Km4|J{_ME5 zYm)o2PK@p|8a4Z>P_EcpUrx;=pOQ6{l@0uCLd>Zm|G)~kAvw{pClNx;`pLmVLE$yN z1&Gk$g7g6;Da1~XrPawpa~S?G`MGcuO;ViJ=gyTN2P3bU8X37~A?H(X-AW$?UpY=6 z<_TH94lTz{KxWpiJC(;h8X3^BXyI^J&G72c(i=fJnaV``yPKdSCQ>HlKJ&_p?zEGW zAZ}dGe)7JB&|``rlboPqq}y=|$@6?bFP>e{+9Oj3Dgvb*sC$LiXthR12T|%_{E{bO z5tX$7(rnCTT3!{EypY^ydD`D3TP-cSXvi+9`1JBHHFfWR{H!EcAT^#qZ;&_ag612%|a z%lJ$tLBIk9h5XJ=v>>@HTE3_jV%R{Mq_BXRP7#KF&8g3Y4YO#TE05!gEoC1|*2-A? zRZF88qzF4cjIW(fjL)F!V6qCI73h!V#luTN@k^~>X zB(#6tg9jPtFbsgGbEXID_9@*GTHEWZ_9zk5)fdrGF#h9*qRqSb!;s{#pm}KFfn^x} zXG}7}>+81zsJbw~w*w6zRID3nZWCK(%o&6~Og8W(h<~MsuVSa!vPG9aHvK9hEgE0% z+`)L5I54o^-0^0jZ^o#HM#R9_zueQuc(5o$-Rur^G%Y7l?tT!DaRo>CN%yklV9H0#r-n6+y~=~1D-e+<2Hh>5T~YvCK?(RmMCO( z)i{YrZwp^gq=Og#4Y2dyFjMzl{UyHa{k>!QI5{01nBMrlw)TvXRP9F6GC^B?&;~jJ zODhQc-A&j=&>e%__eCEAdYT}*fbfP-1OOHtaWV(2DPoosfLJ-L(*Q&izVYrmt!VLa z#lqj(V>)Y<$I<$Gu>{?23_Z_2nKROyoTJ10u7|*MA0ojMfu@9#je+upbO}=4Gbr*W zMn*cC_;5vNV>~mii?Rsibl`DMlndZIJm390f?V?EjS6fvDPAv3a?y0oreq~wtW~v8 z7#bRsv+)US@tH+`9vZr+Z5faEwp9%*rp@n8&Edf%!yx_S3_m}<-0~>qR!gHqM*XI# z86JuhX^UuulHozw;`+b=qL%s)f&qTV(Y*vGK+kLqETF&9c7j==?_>T}qOhswC$m%5 ze)_kCR;=ivdTKA84v2qY6O-EacEy>PsxOoZ&JYud%`m1)f#`=(7X^o!NDvALCl8!K z*|LG`#uR3yR9yw|XK1J;=Bm8;W@?ui-Nd7)Flo`H*<~rbV#U|A%kM_&z@4?n6$amg z8iE14P)eR1H%_g`Gcc z17cYv!aOvsaVm=DGVTQWia!kz73|x`wl?Tsio}#19K0cTx9V{T62s~r3AkxXx) z?}Bqe5lhfTV(>j65+7&>C}qTY_B+AUegT0LXcJ9`JLurZLq8be$JZV|YAvlQPEJjw ztRtb_PaB^31cincI?H$v71!*cN^?xH4p{o@N{0z6@iGA`xX(t}>qrzw@grp;Azb4_ z{ICNtbO#tN1;Y+tT>)Xjx(RhZC?OSfb;tAPchVu#V0tf3c+cCg0E@{xh55G%;_4mv zj`Gt8PFAHi?|rd{F6!`+g+fA^?4RUw5WK0!A+}wb0i#FvpmP~JA-$aHt^+CX#I>m) z66q@@k)cdH2itbTeMDG9d2}6Ooa#Z7qD(}aef#$D@xjcZrT~uvsyavzdf<$z@N#+KX&m3!zl9Hk6|`fYgFX0kpcj89vA+N$ib9_qIh-)aBZ zh1Y6n|7Iql{xsfMUotnNLr@_?IwA%){%qnqe!kWF+?iOj;~bl{-fYlTubFyXk2}5% z%nruw@1nz{nq*&zY9k4i{xW4DeQ1a248Rx^G-J!S}4a13l)+iM` zBOo!OmE-4)`C<0zyEtWW2Vb0jY8dubH(TvXWJE!n^2%!)!bi`vXZsUIzx$z~F(G#8 zp+QL^ENRVq6*C@ZYpnb`(KfG~Dj=`9?G?J@;Re81_K%>}di*w!oQTKo^-};JfUo78 z>ABc~8uS04$FoD9m=rr;y41*bw>O2ZxA*&UjRrk`BF+%r{?X=6I(u#K;kNxQNnMUU z(ga3hVnSI;!*Y4o+rJ_CQ=T)oUG>xU>Tea!71(xRwYVhr{W8cBi)#O67}(#nA0YJ$ z67`?c?K^k42=saSRq%GO1kh*DF)s3Px1ZhHw(yu&EQbQl*z@X?jGcW)^|bRg!H`&f z$m~$ABH`5%B@r~{cGuTDaiM8fx)gm+3-x-^WULxzjFEUyfAYuH-tvBJ*V(YxQjuf;Tt4e+?$QElU z*gXDmkX)P!ri`IzBl!`;ol7zh*Z1pM89&nC+tMNM)Iur|j4;WUax-0&#D5CCdzTk0 z*h#YN1Ya5&3V=X>D&i3Y8c94_vwzO(0`(E$4(KAeFh5kKou-60=RmnR6^ZE`Vyk5- zAyv5a*I+{FBJt=1a6w4*oR8Wa&<^$@S6fx}aJauwk)3X}7-77&beT5e<FtfL1eL{6sx)gXg{%I=nPD>>>uHNyqhJ>9Zh=wb#b(3gl2!O3tA z;URg8WF!U77F?!QywJncn*W`N1Pkv|Sv7RqBzHT!Oyyo5nHk+{>wi5p2h0)PiXx1cZY=i;&}?k11~2mpkx zIXDEI^H9~D#>s#W3z!D*9drK&z#M=SMPKgV;K!+OVplO;Mi~QCsdzr}#mcB3o5a}@ z_a0@X582)9uC)5tZJVJe`kBB==@}VE!k9@Ek~jiPjKD!?vO)glNNwdM5FtAKKx~!9 zo^)QN^+K5O@iD|uprRsVYB1j`;{+bBdC+;-&rwAsRQL5!@1RFdyFcDO#Cb3xrdz4& zW@yYCoF%RMQpRRx=j#noc5K9^r*g%$!h{JYDJCoIAjAT~!*TkBL9Ss^IoabPZ;YW* z1WynlePQ3vq^Tb-^n#R9iScHj&inG;uOlrGh=b}Zh#&Y9U~1Y)cU|raa77U$7M_ps6Wy{)%gbx!NZ^3tL!EeYSPh6-E&m_#$&Yx> zUGR1=SHJpSqL3n(D_3`SD(ns_sv>NBPe*(;DVV6zBk@QX(5>n3vAm#WE|mwH{cntt zh3Q7p>^kB;p<`+03@ZLOfD^1zkify^UgWV7Rrp0MN%ls$%T1<~%nxoVN7b zosbaaQD)f1h|w2#)Cn}atLTP1e;z#|e`aUz9XS^P`67XNGpWayhz0#SckN1g6%4N& z9suBeARFV6@sb9PCAwfU+E9;b5tN2up4l6-6MpFbQsKh{4yypxV@dL+rYqq7rDQq@pQh~ic` ziM*Hc0nrf#%ZrK(6i{*B#aJAAdWh~92%tWqfDEufi#WRnEUK193SPo8iuzX`_z9j$ zqDlh!1Z0nSHHX7X;0b}r7o%wBGIdkmp}MbGB7TV_tngx$ctl6#9nE`3(GW)%Zk4r( zH}3_N5fdN(_dlik8}w#EXaUeBa~>NAlAP*5dV;nh#!hF&2}85+(KR=3UQa$`3kHZZ zcvc(6z@So7umQ{?3VUha=O~fzK4P&8+}}Nfwa@p)9@OrdhbU2a08nTBZ)K0tEhaj8 zdf0=ZIkH@w-$Y_^A^+&_@k)5m*IcwXc9V>V$v8GUd<#do*9AZ z<)5N8p8x<<1c^-4qUE0X_DA^m>;W3S3hvHr`wne76pd)JjyH*)5FCPGxR{xP$>42z z)R5rNRgKnvf^rC4N8Yp7Fj6Hxo~do21w#}uwu(%__@Y2L&AA!%07_g=P^GBxN9@Tb zgti^i2-_WY(9(fCj2^dIdU_A1yzW*E*{B<$oqV;dg<@B9Cd#=B{0X(1Wnkt%sW`$2SA@_0DG z�-r#bfj|_Aw}7_6nZzvL;+cB%;F@W2aGfLA!)BmT(DV+v384l7fQJGvZrov}1o? zv8mi2ezLQg;^S!8@l!K9zFo-(r>P{kVFY-Lt|lZ$;+!L?|LfjFqB6u)e#l=_OR?M- zKhMvJasm(*T(V8czB`z+2^0g%u$i9Tqs||&4CA>T3zcVy8y}Q#sc@L*Mrfwe+tRGT ze*O+MRJit42C*{74e)2f0&ryubEofi*_j)R$S(63hor*BMOBuR4s(! z3Bm%G>)o^i=1RPn$b%gE|LkOSqG1uyA6~g`y*zYLON$Mn)K=lNy%+CgJ6!KfOSF*M z!N>@Y>-(+)Xp;xV3|w&m*2gX&RDcn9z|c)2e(9&t?@Qzz&+C{;Ke3IIQ;Th;KiX+) z#i&Y*ZkX0VmifvhVIAT`d4?d!E}--Ce^-Zgi#wUw*l=BZNC;PB7Z=RzpU~4KyeMs8 zo;s$NcxWy*I)!&#%bckrDse)vS_o^kBW7daD9g(Sh2l9uxn^Z<2yEE?J-NiaVxkaC zp#|t>C_WP@+M(v^60@L|)iGy^BlD2Z5-0K43`0PU_;}3w;p0Tt9Q+EPNXb;*T3QYd zGozzB*8db?2L@I|HHkKsE#yO>0MSx z3@_nzd~p&#Mur-j3?a?lI`%ItRAe_wsESc{3;o1CHkEj2YNgw- z?_5qHjuEy3_`Qg&Sw_e!=$<`8p-n-2tC0A)zLxxmfb+AP_}=U!Tw`M*i)B%mgEd#Ak!21n?E4-vYo8i_QQ1SJegIQXFFw=)I_LMDbGuL0`0fQ#p|?vO7F? zU+?>r{v*Q901+cjyHNm7r!kRc`G06O`lz=*HNK>#U~^5r(XXlZZ6>!*XEdJ#Fy4vHv*g(mGH_pmZkVJolzE!5vO+!Kn{jO=-18b ztaaEo)F_c;X^N5*Qv^5%=L)=9=p4^3u5hPbzNqtd#*bB?B){Y6#tRi+#Irk8;Xyfm zAm(o0L>h5H{mKa3oR2Wxia^+|GZamZ|Lz7~R@C>nIrMmBalOV_Olbb^cX)bvFjB#}yG__Z zFSRq8V(M2!!3hNoWli!A#}*vZ>PX_`%!{$<`82t$Vzj6w*CxAyd*Fi*IL4ki}ay*>h z?Mt7!KNTDKVg=EGN=*6-SZGVZ$2oWFll`bZ7t`=`uS(w%A}Qi|40DcgIL4uKETn#J zR(-BxrGE@Z`nfqj8treFc-q-B;Oo)MG!w(sUnW^WsFQ(KEp{T47(*&5TAY=os!$)n z%EHFBf{a4=)%WjDgXe;a%LeHO4*|+(V?e+oYX>*q1XHs(d0ar_)sqTmf^_oc1&#finKa_vS-s15?)01Z>4ox2A;FUPg z9_Q5cyM>0!|U;}D2&+mEd|HQx|`r}gXOz=%S!1hdf-#-=)wjN78cZKy+OFsA> zQgAFVcxh=V+1P@Se$O%K^Hir3cQ8^h@f14ZnO}>OlBhdixWwPhIv3)`L}IaC9I-D$ zs#MG%?4(ih_EmSjm7MBL2lQC9!IaxgJo^PsRE&mp){5^r_~y=44LZ7( zO`i9~ce3BD&vyDV$`ifDd8k6dCvYDM3E(~g>a=H{geM10)nusC1E?cQv%W-Cu0X`F zsU+l^bp#wqK94`0ge7B~nv?U-nJI_d>yMJS^@aJ4b5ftQ9&#ByMJ{m^Fw>tK010X_ zr!WLo)Ls~nDr5wSSr%(7OY>8dekILL949ghMv9Lt5yyYs*(l{Xng!A)%sEjbOMZGl zl3k35#g@Duzq^Bmwj%H|@6IqnuE7{h$TfsB(1o1T-_@UBtmKK)zH^TKz_A!7$M&U* z?A3H<*mkyDAN=Wi>eQsYOOR@F2qHgT8c@mrIEqXz5dJGXrw32ta)Wn{;Hv}kfLi+v z>)-K;AFZG><>CzRwOy?A4&;@2T9Qf}>Km0KY!!6)l)w`hGK}$B7vRUoJ?BK(g(0ko z5E$Z#D*J^pZpd;T=c!rmlFUZ!JO2+=e;pOo`u>l@qbME&6-7F9Kw3arKrlu?QV=QW zln{_c(f|fQ5NQyR7D15il5Xkl?(X_sdw74I?|SwhXPqUmXV1OwxZ)LV(|hr_s2Q&n zsw5)d8VW^bLQpCN#2xgbfhC6P32z{6_&xRI4-|bSU*S=Z0(;$@Cu{n_6L!3CcD1~# z*RNXvH4dp@+b^WoK*d!bGy?tZpGH|Q!0-PUzOh|k|KVx247263Z4i#_i6_<-p-6IB zP-Bt1%c1eo`JG6gd|{EV8fn9jW&l!EN|FbZ;}N}3a)Rf-PXky0+1fOpc*gIw$^JT+ zK6fqew;vRkpqI1FZ24sW{fyO}f`wA2N0+~Sahs+au@jA51r8GQvY|zX9s}tz2rZ$I z>}w0B?PDa$D|M+K!4HU`z19;F3AaJboa+?0_eYdG8H3?|t~a0nAm##zBtAIv0BF<| zabq{kb+5itivx=V*$F^ofaVaWsv1o-!wsd88~Ty|ikqpGya^(N3 z$%=?imq-cZeC^KfkhM$+fcw-j-lt%_^d#|Ha*NcTaO3bgwyJdshO zxj|#*nlj5!FG~l(40M=_-?#!Qq~bys*aFKIHq(2rr?{VbcVt>P0A@lu5EKUCR$ zB&|Dq)n*x%RW#qsB{)*i3nS#x5OkN(;|a6Ldt9{IF(HF z$t%K-&(1DucW27$g1hn2Wp&r>+h|K+oBjDZhe2Ls`CZc96Y_sKNr2{Tdx44TW2NbW zaWh0_6Lb_uy6&V^A%$b8$i7)4By0^Ch)F>}ts3n}X!S1y_j^tD2ln4v2XLE^!N>xO zWpYt;^G&E|5;6=Qy*dw_I;1IEA#XL5+)i|1e`O-PtwY4KWsN*OLoum(*HeflQpxJE z_N>2Bl!Hzmdv(4a_4qtZ!R_6m(J61TmMU`H;QY?37HDN(!ED@?4l@ZeN=h8ga~YO!QA-Za+(x5C z7pEK~bEZ|KRr8F;8>4zVo$R!9pJ~)qQm}6}ZG9V2OEjKd8DbGwFQm%V52U zY8vmCqx9h;caERa9QGwA-Efghd$QY`-(q>4@UBa~{?M3`AH|?SDzL)bele zpDdr>MojGI821m;kas*o5fDs~X~&XgAi4E0UC}o4OGU1ybS%x+4KBsdXb~vMA;1#S z?}0kEbsDiUL*iw+PKt|ewi&_tFV)^;t5#SCfuAY$rUou+bV(qM`8Tey^yi|8I7 z4gV~4Z``}`LHYCEsz7xIUyeR$;QG++LZ&O9J5h#ymHFWZJGxTB$lNh~8nM!Unss4z z8qz%WXOH)*pFI!M5-OP-*1T`F(Q7@@lXEs<+r^iK#=KEwgllDP?xpG=5;;*?{W%IGf znEcm(oZqW+J>#ULLM=x94@A_h@Zs><10LC9JEj=QPiSAQU&? z)hR^=GFJ0N6($*_u|aA~Y@AqeZ4J3hMw*rFB_U#&+2!pA)4RTbW~bKQhn(HN_X$f% zfRFgU(xGt-RXt0!Bl>?DT^lhFT>C%HZ z2!`(%Z#RoYs8RpA?36ZS4)iucfAGT|5>khK+>ZkpC|yM`2KSo`nIK*X zQ)DI#4}iKP0B|0(&Zp}>0eqwk0Ekbf$>>X2d?_kD$H;X9f~JThSnNwkyOxw$sMfBeN5v}soaj~OmP?|}Jl4dY(^KA89(E4+Q-fUo{J^ zZxU2o{Z!Jx#qHgFh9(|szq_OAb$40n;q)m2o*LiC;*yg0t2%OWnR!j$_%hcQo(}6# zvMm07o`!O@W6>R29ar~!&_SwPfE=TbMQv<0K|D%24fu?X%HlL zAUWl&iaT@ejO;9r=OjlXwr{8(kCpUVY#m>@;y9TnH=Dbb64DyoyX7j-aHp5gl`({-@RA%+e{%Z}wP5s7*W2{UKT!L6fDvErGl zeSSgAEdEn6c(l|6R}S4t+j7kAwau#DAd8@}p_yFo?;uB>7C-xhGGPr8%m8*uxDWN- zK~X493-j_SV!lO2PB(_Nry&zJ4Y$In>d*FnJ(4Fnke}OnHav6QPxAWdY z*he2KSNqO9wDq_SdzzQ;T2uPsd=yi7%7)6ZtwLGjo#S;&(V1ky;GHNHLh>=LUnN3( zx|(ZmBFBqLO)o7uL>nO!Wke7F%iwYhh{a)Vkb>9*&2)&9!89QS`hOQMLb+BLiaQ`j z4Oq>K7ePxNfi+D4=L$fGJa)^lt=vEslSH6PscfAiw@Z!S8>Sl2^|2gyH8~@!-POkv zJzDB@;k(89SYzx|F)_(eYw%*>kS_}xkHG%fW0&=u?k-!_Un6-7i!Eb=-}jgE*yV?W z^(Uv+U)fvtDW+XHu&d>XHTrscvhnx+*u<5W<83+SLx~&VLM$6W9d~4RnPg36gbVNJ z4)+UwGZekEb^fqDC)@qyS3l8Z#*O|gc}(S9i~01}qyFOzS{aIBo^nRpCE@nJxy9>i z)i)KbVGzo+pa^*bFcVM{M!Gx>Gtr)1X`0JpV}N=z(bk48Q7SYPz%+`@FsXCy|6#UJ z7P1gxe0Vw69{Wf~>@{eYFFqiwbF@h~4mO`E)(pHhY1{DpuHHTT6zAO!+3d%a#_>uk z-fzm;x18*&x(2y%&_YF)}dU6 zG9W5J3qjFiJO?}rc5VjG!jDyUDtn4a*4FE*uH5`{BD`q?77HQ5fxb%`8u((JvPX4n z_cLeK)0W&V>MK=W(v}2Ss9O8l71So8< zEBmd;1x*N!O4#hSeS^9i^|^}sTz~mglUD>4agn8`8PHWG7OkrcJU`@+^y#ji82Fqk zXI{HA9Ff~)>iua&mmdj!Py=iq%Kv~=3JAxC@dClE1cZTrnm5z}mVvg`3sIhJ5M?M$ z5R?_iZuA$iux)twpRO*t68p%7issm}>6Ujumq0{vCN+1|y{&9Hr^Z1fXhdD&h5j}i zXOLJSFeNbK1C{w%SOLRGo~0#2JY|L=?F$r^eeLS-PM(=l-k1CdhR%FnDo97c-neRY zF}fsHf%#Y@@^#v8eu_iSKPtjYu?iPDf36;tx0s5^cT8I9_btxTM2wlG$$utaMxsHd z5T2TrbsMWYyf3WA0?MEB#`46fW1tik9CiolZ`fUjFB`T5CRd znxXm{0QXv@kwxP2*o#v$kpMSo!8UK@N zT5pP_hV!VW#CpAk(w71KfAp8{}LshHcW| zr;~Rc3Q}<82$znhbQZl9d(JDZ2$fRv0Yahq-18ARn2#kiL`AKsjJw%8F>f+sj+|-d zaTS9H>;MA=zZGlnVnsT(NYgjXWs?Q!yGX~U4E5JZ;z1NA@om#ymrBO)KOI`?uTVc85OrEUu9aR=~ky07j3r7x9 zrk@#UHrGqFe;ch{T(Qd(aGWwt#YPZK1#x?~+0C&F9Ct7u9#TJ(NU~0ziBNl-*#_v^ z^%p^zd}a~OHLj14w@9i192CH;HGjX)f(F7b)RmxN0}j_X^y?)IvKZUd0tx$#+znac zW2;RRF$x{)5#7S}1v|0;MMXZG|64A|eA zWSpk%zZ)1r{zUZN7DxXzGchA0$6r=ZM+5%z^=UQtNu#fLH_4jm%BRSZwwRqO6p)%&-_&EFE3%V4w2E-^!#11oZYSc z%0&=g?*mvGQ2LClpk0fracEcI!zX6uAbZA-G$$x^0hbRn=5aWCFlz-(bta+Az$>R<+enFpPYjg;!*)<7VZ$BnBm)t8o*c{D8vMj^y|b127x7EPVas*(jZ+1AHf=KN}tw-0A%{ z{vycF!$bD!xc_2*mIyHqNmcQxZ3eGhV4|P6}?I%+E5icM=BUkl*s3psjt9vCwM{S2pqp0=*58J z2`?X?AV0rp&!16n!b3LIksOYaQ>6a|mZvRZ1*oYHryWWd{ywJJB=5AIlv0(qR7~pr zl=qV?fjr9ayC&hj!h%?7`14?Lf#}lspKvFIUfQ20#|+AX&;Z~wBU~< zw?EZ;ixOsgJ$fk~@rdyzVeLh_vRz&6PuN$lrR{fJj>4)km$LJ8#pvcErX8>c?vGrV z3%9hV(!$4gqT6yaz7{RNNv>mn<_#8JI)pbMbcHzbq zHS#dai2udD(1yNSqp4oVsoz72cpb)RTwef`>{9H$nK*Sk|}WZU9fwifp#k8b;ND}@y@ zRfg2+6xWw~n>$x7=hDUd927M*l}rwDRCUmt zC-hf%+d}FF{sIXJ*IK~|AhMennGPr+?oCH))=l3(@2~|M&nb>p$2xS;E{68@J2Xct zp2wS|Mvc>Se(4Tr)?1I3}i51 z45Y^iG1k3kB!L4HAMv?u@k3!kLOb&NVUN^=r6Zm$3K(~{@=fFMcP(JqjSl-K*ez^g z;aA5=r{LhaWXKy4_Mvqhzor*58L=S{q<~8(i?>Ou=O*^YN6qIWPT{-(*jo0`ztwkX)reNE}?}ph@jla2t0Yd;4Eh7>qEN(P-vG zIhjjvO=7K~7mSznrg`%c)SI`1+hz95@t*pwAUR1k>$nN

3>RLdLTE|`d3y~27El=5pk0fZ~@gB;2me*69!uV z{3tm!l^zUUCOX)VO%XN1U_^7U`Tg{?pJFv@Qb&UG1XT4b zoeY$-Gyp;b@M-Xu0SV$=5S)(QgzXmw8$(1%$r@0n_U~lOg?_Ld;svelU@*nV^PomX zktFr$Z}{b(KWCuTP3-NCg@_U4nVE^bp|t~6T9DxO_xFSDma{?dV-PEZ{=K?7Rc7-w zzncCM=fY%7+~cBrjOP}2>v`w@i{RrA{fxmpPY{TOk##$N0qUeu@{k!PDQFbgztPfi z!$RvGP%41sM?f8?!B_|YXdosJ#Jj#eRfAmobKndJ$SpTF6iF8H@<3?QOtEp~VWC;p z?I3}dSnNT%8Z)Fd6-e=NyQ8P4)@e>Nu^l8TKo1YlVBfz}8-N-XKnzX6b*S_85w~q& zaYhDU#sHYWNefMIopk^bkfE zoYs3xdC}qE%mqLc@K%3tGjBN?xhsleY1f-^FE`F5Y9qTNHFo6;tdAn2j^0O$0>4;j zSS1JM+mM-8eIL1X2SDn4!mA3BZi zgSi@D?j$8ILTh|T$O{Af5(Mk{e>bfI4is zdwO5tYp@3FgK22;@+>UxZb-{jnX;FUuY!I7 zkol@~RTa!RFy5&Kx8#M781AG`Af-$%ysw0f1i~&VLqZWT005A%kEHCO1h6!nH)6 zuuC9f8|Uxb1HdUjTBabamb-aXDoXeeEMlNB9xp#@T>xmk``~~jBvb@c70}X-j(*2< z8GwbrO@rniIPgUFa^Rl9=OJ{58XxNEO)%<1`vpv^9P;ig!H?X4)u^?W(Z2|25yN!l z?cd;Q4bmRVi;Fgolr9-Kzd(bQHYg;4jN9WD2)ZUFCkFxa4=YYTvln7QooW(R<(tIb zpuG{SdI& zU|g`iivY`E9?cCP>l2O(CyNOJu-pjrW1QW5i@tWjUB>t#{4@H|5Q;+uy6Ds*E(ZX4 z=8gD_1<^Dh*MkW-i1P!659{zD`7eGzU1dr*IWaM>gbD`pQ6ip`{PTaX^}{uy0X`0S zYN=H^(BTDrLF)8sQ(myTd^=KyV=pymg%m=MJZQTs9d z_uqe4F96olcIHLu1&UX-d%wWTA~x`zaCltnEAalJHHRmKtC|9^Z!iw+?T;~VLO=}( zm>hN?fE@$d5^6t&fVyu(w6OLokvESn1Zf3miGuf)BfHZ{dNb{p+qd$+1Q zTl>SHnW0NJLk!T*_EXd9$5&T^ai5GLg<=U{Wuf{4J|c~^@J0f@eg#cT=Ek zTp;jz_Vh#078(axbb5brwGPzOvK=`n(aK*QhOm%gIqU$w^6pK6D2HdKk#E zG87l%H7}Tj#IPSMEy-Zu>m|r13E3`$!bDMK_5E{;pWpsu>qs@GhMDyj_z4^jL4*wv zLC(wD0U8hn4glEc0Kc|9QpydUQ-47+8u+Y)whmWd;YUA1(=fN#9>+$7#1;O$81!E*dvevg!`ucCJV-$^y@qchg@(=yH?dyag4btM`SG}tM%1b%P49??#cS5W=OI@Hd zA`D*g+}s_I!>gzxWeSkILL^RLoB-!%TNp_OdU&wMfJ{=O#y|Km2QeJ^q;(Dgj6@*A#lmZM{d%=nx13Il5GSD+WotP*$#$A~Q%=h9>|JJH>wTc~G;6 z1hE!Cyo1XjnFGk+&|Ry8768c1sP&)hr+K2X4EvtsTUU(NHsX5ICm85j2)ClZ%8rqZ z4MHkF?lfW_+!O~!;xg`AjXXl85chAzLf2y#gJe835DsC|55gg%-rwmA+dWvRZ!M@q zG>KwNc?Id|MVW(q4}EYYUleuFcbQ*1_xG#sn%C4;Z3E*@o^h2*Y;FaV4gd(QR%Gw5 zg6$j}ybs~T?b~M^AHq2MI3pjJg@~`3^0I{#LUjg|QH7)6XmvhraFL@Am<78~2xSfd zFa->CLNYSM(w5Nf87WQ&2?F0D+eLCNFig*czXfLB!VoUH;Yi9h`e}dBX7*g^1|&-m z3t~EyAML&|iH0JcKSnTzN>U`G`fL8up|%xZfHLH&bHCBz{hRY?Zhyst7VH3@|ZZU&XbcD6r_ z5)mtotekpgf4b@A-guIE^Kj??8isiuu5Pt{c(VIR<`pVw%!zP zA0Ilj0dqQ6m{bC2zA44Fa%h5hJX?rKx-z&Y*6Hm5M;%zYAaJjftqM7pOr$`S-ZfTY z6F`n!^U?!7Ng14!6P$F6oxbINZrRdGM>y0ZIY=^be5)53^WWtA>mhM`jM&2C<{D`t z#2#g}5Ex(Q1-63eK%Rfi_}y`X%zNzY%Md1!f1Uzwy90O&p{yS(M!}LDTQvsQYo#qn zAmP%Li0~kn^uiLSQc?4A*gL7_1$T%=h4!shlHWoqGAPnqp#-W*z5Z*_s25{vivfU>nH1Bh+w|7F%EtRc z%)%fu?B0lFK13tU0&}=UkMc-=+eC{t?)LAsZ$U={ou`}Y8;tBEfe$`dLxzhAB#9ya z4bv^w5Rr%#I-MooB$di}yFOU$R zK0sA6NMaHcJ|L$L^#{5D#Eg!eN-tgz${`vtdnY^Ho1gI&F+Uwm3uo}N=f#}^(cNFq zP1m&ZvUEm92UB3I|16~|CL6+YfX+z+;Nl^iJOwA89vFrwsjGw6Ef|5C7*v8DC18L- z^9^=Ppl88lr}+Yme?f{C0|juI*U0yR2^j<#=;PPz4KEGo8V}xG;`^yC_Ff#RXuu-% zpwPQ}&3}kRbg&v6v;ISNv1)cCYg4kb+lJ!+He1|@AOvLiYhDwGNu`z5K5!<}I*mbF zz-*`}EHspV<8MX=r~9Lam`Bmi(EfQpY;Ye;$^h9Bc4p*rO~QR*idL(y`tu1MbJ1t< zsE2~jzC04^l(s&*o(Q8`&4YZR91vC>MT1zYsku2jVSZsDX#8-46Fih~eZxVy^9Zbf zxgwf?0s=rvXs?3RjX`F9Ny+!#{C73upg7X0pLX(=tBZVnFN3)a$e(q0Z@>FB-xPAp z*=`?v_#ymt(L;>wk<-4<%+SAV9?fixe9KS{S8~{jz9D;mKJfMPA$EWT*cdW2Gz4r5 zo%9~?98%VY+#VWVu0T!$p1|DZp0=YHsFc~m*#P!(GIJ;UfAx)G4PcY60+7$Zm7myK zKVA9g+x9Nlo1MLwbLls*J(?OCXwfI-fbJ|LHZDDbeECOEuZL|Aa?Iz?uXAylbg`x@ zfBW)iKC z8q09lBq8|(b8;{T1kX570RdbAEy&&@!6y`5)SaF0Yaby&)kolLYP~msF$c6B3k&Rk zjpC3cV9;c5NM_&=MvQ{}#oszQf>av^^0wew>H;%z&=mw69u!P`5X}pihR|#SPgX1- z9&K=`DNK8w1=YqVSRbLJu)2J%&<7-eiv=(bU}&${KZPfO^BQ9Au-yibxm3w94O3u_ z1ZjcT1>k1DMNg94sR|5u1qBcftMYQG229;&gpb$|x4zZ^x}9bp-{4V|SMp5WBK6G8);& zogWNu;653(tz~XSB*s{f_*QjphH#yOQz082;8}#ZUh#GVL0>@q}tvf zE-B!0umeZ)f~_DSsH3JTr=ww5Z{95HL|7Vb4aj$jg;NO1XkOTcNqYEm0A6@{0@WQN z1)#HWhJhvdbrA7w6f`q7mS+xvV%XyB>@74OUoL=c#p%96phoh)PYhLtiX4*Hy?iOi z!SMhC5Ml_pphZ<~Z46%sIhl#!I0TmnLjMOhd%$KQDvE{+fSkw$kkg%&QP|~+}TdS8j5V5)oy=%mVXQpw|i%Lo)}i&_6)5 z1;IVAd|zPR2Guzv9tCT-H{cui8bNJxBp_qv4HZ&Cunu>Weh&AALP85H!Whtwg(DUC zwD+=~oZM{&3T&`_Ln9|teNvgV3-a_Rhbgk?XESqM@EcmJNWwh@r4Il;pvj%L-GL1` zHKKVmsR^ruOWFDt<{??tlWQ@U&2!U#Ij?G18( zgkGnlY^3by?EK7G^$@99pE`A_`PKgt^fX=q=OfBZ+iQey=9leaFuW|;^FK4)$t7n( zMJaNgYsfdTE=gcusf38rfpYPf1%K*1?!35;%zU7dkwmrdk$-+$d{p9q=U0Q&Q;};s zy6+(pk^TFd{XzRf1>ba1>bHUoJpD9dZZtX^as$NTj)Y_ysw3fMFwM1`kWu#7*xZD0 z9;Ox9XHm2~BN3c#v}Rc+2+X;i2NrZ$=s!>*0p1|s^x=ds0HLZTopef&9?k_G#h>5gjRxzZ z6`ps9FZ$Iuj=GbmwX);Bf)9<-ktl}fJIAA*vj4uxa!o&P_&o9F)FXIDP)@$+fam57 z>lBy}-vQW|n;U`!Ljhi{P^FTj($;kE%f2 zr)Y6Q$-n;zW`aaWwfEb9#`zDWJDZIlo0W`UDJnzV6l(K;3IDRr-Dck z;VskQl0zsh;$lbho=G8US!C0`mdJZDNaHg5BS$UUbreo!vd*vCzmx)U2ZjW7oe024 zhMB6rp<)4wCcLDV8f#%I2WhNK%Sj1Hc(XVm!3V4pEEn)rhH#2(V%7dp^ol!)Mp@%Y zytZ@RRB>%&U_E8BYouJ^omC&QQF)z%Az6o}E6I%;;Ib%YfAg9b7+yiDq{7;T4Y7A{ zfYUk%3-kpL9Egh2gqC>3=hA%KD6D81R9&LB&hg=`DmSHz`F;uxMw-Md2!c@8uYOlO z&0hiCC|IOWz1-i2ZLrAz2#m0{VcQfQp@M3b(Ea-~`hK{3aonAi(kR!U|HYEn^Ld-q zm|qq%ye$yz|beCnRIeD}PQ- zy^+yZ+~oN(4=_;jHgEP*+t5F6lXJCIljog`DFMobtndCCHK^_p2Cjy^nYiFMdHI$% z)K@_56rY-gdRV7B$^)w zEu5^Z4XE^pj*p0J!Q;XEggm>#_@u}+A~lyYJGV94>caQ*`6E6XqWrCz&y=Q$@-*=f z2G`kGSr2MJX*IUA_mo?D{f`|5ZMBf*()o{@K1CxeB;4HPDlC?oE%_TJMh57ws%|u+ z`3z;wwUd_lYQokNpzvjxFC-v<6q6yeshHb*>kO$G2#+=y(4vXGvq4GO3zMN$etMec zWP$;m32K4Z%Y*g@bqXxG;}^)xzKr7Up84v@5N7VLzk( zv5g@VZF~f-d#``-p(Cs0(fs4j=lSM{LZg z!EYo;0uV?>?;bqB7-#Q6o@-`ms`u#}K0fIF$;dRDq!oigwoydW)a-27*RL7o!zIv( zxq;I=gxumx08Qw^Qle8%cx(o~P>~l_fS@B)_pisPE6Yne&bx~&Sm?kNWGJC_$cS$z zc&Ik`Qobg2i78yDH6%EwjLR!zOV?oOIsD7qN~y^fGEYILy7_nM{d@)WkCzm_%Pvg% ztwkudh7a?CVp+`h_iM8SO*VkIcAtlh72BZyCULL%<=4G7!A~Cjx4UHZ)rciGR41uI z)S5LW%EuC@$Sw)_8SZ4{y>ZMU5X-G{-?Mbq&y`iC2;A5B$`(#i25;x#U;bVbF=G!l zvUn%2{D1a$>|TCie8n6xFUZd3Y^OruKlm(%ftIZU>RkBem0s^FI~ulc=UYvhpo43Q z0FZ>=SrYOUQ}R52An9RD;Ol(jgj&@v&H7IkQ`4U}Et5bgaJcD{|>3fgdift5~QPg1|K+fa~! zIRgx1IKcrG*|Y32ecYJ2R86r!!Cot-sU*s$^o^ilT8l5KJC z1Yc`({2vw|KVR%Z*0Dbi_dV|5sfPZYHk+s4>hT^o{5H%C=vqq6!ml>#3B0qh_>-N5 zKm5+~;7P`d!&quH%ip8pK6y=N@sE2prZd`h^@>uz&ELJ9XO)Q4Kl3wg9!Fk!G8_M>bBNBMm66x8B8R-Rp+(Iu?iTNzalS5(wuASwnOux3 z4{F~vw!D|;)2q&YK}>l^@Q+IM`NAwavh{)`SHsJmk2_jZ>iu0TDwWVpKBJ@^pAOpa z*wq(Tio>I(TD;z_Ruq53>!s;l=`QiVbAC)HeP;By;*=CC@0H-Sflv;3ffzJ6{v<_E&|krAW^N6kO;aE#0g4HB*47-fuy3u5 zR^VDHF^gO=R6+1opc_RW1IE-)bkm_~NN;NNkfOKcwRZq@t;6JlzA)BXguN_Rie6}GiA^%H zm<@9{wm0YH4YO<==5t!PvJ#R7<>z<*mNRE&Tl`euJijoI_475zLsf4yemS@B{V|3> z?BYk74h7R9DtR@LFZr2`SHH3;O(velU;dWP#WcIUpHqChy@+Z)FYnf}c*ig^Gw+#e zgxOX4|8e)*&lkM~#VGki7cy|j;|Q;Mnh$HwoFqZhZAWo7tyBc7dud@^`zv zN_hnZcWV~ock6n?yeN|eN=L}KZVp)IJ#(S6YxkQy%P^;6#268tW`f^+gOl8g|69_x zTicfhHv9}EO-AuN336Yq$@Z@f_;I0)h3kGVOwk=0HZO|1VfoYhbK`ddwtf~h3Qzp4 zX}3!$bdGkFS0nOVAj)+RTUZRCED&M}ly2H9fAXFBpxLR;cY(AfN>)pL4SiXKf_zyu z{Q}CP>;T`*|1Jv?2;uq2UneAtmQTXYTyfp0fcj=+$B7kgnK+2)h=BPpkn*>Yvaxp+ z6rjYVrS-Q0podxqX4&9x7;1O-F|-0;L%$FC&{>dHWM>qhrG2Zp)q0Q-nf{a#jjmXI zpJAqL@b;Q#y$3O`T8UnkRZK8ubvaL%gH0e%B0D5i)##LGkCS$cwS^IVVJDJJD`s5t zl-A4TY+1s)9xpefA5^H9;hWO9(UEud9p&5Fn$O=7iO;(h{j-?0#7lo18~kxduF_9^ ze?sQjv$yd+ar(M;n;TIG(?9#qctiak&G(54qHI0GkD=CggO`zcmzvf;H6Yg2TfF zpd26;2FYutp)4fKplDNyw6j!)%-%ZJ>QQ*VxbTz<^ruU^O=oV~mxZ)=tLZe|OQ!k6zj zb-8MFlUjJ=s@;_1aRK4T1zhzKJD0Y?z%fVv}y z(G00CgI!EO9pu!yx&5F~J7zx)QJLtB$3|SYCi8)Uc3|9UDRXUFT#veuoGE&rN?(na z(BI;_lnR0H|Usjv`k56wYi1ote^!h!@JTwx8vwu zCVwSiY^V?Xl;LN`B0QA4%(tuWD&zR?Fow)dIBw#PSI@hrr9(vXu1fKq<^!^Y*#S$J zP#>W*f`J$a02QXZAXrsH=TQj7w!7y*TdmpnB=~Uy5p788B_t)G=N;w`;w6&tZP392 zY4AK~omj*_Q1Q_7d=!?(k?@47DNVa(aquQ(G&AFu$4v*5VfWHJhMa?2S7u8F=DYrp ztg{>iZ;dy8Xb9@H3(461J0WdOXZ}`Kgsd|^jNMFdt()o|MH~(Nkgm&v+)n$b5W>nU zH_^jCNh~czU(W2^5-JeHLlJIy6nzFI7X7!q4py_a5;&$dj5@g|U7zc!(q^WgH zS{zOrtz!K-ub~+#)$>QI{C&5E<6@-U5O`r?dQcp*tL?n?r$6hv*Vn&4edl&U!y{3~ z3!gQJDszlkSUg3xmw5$KlG4&G^v*gABi ztQkrvHlst2Szv$0_H%ATaI5`%Rbo|AHJGN;dhJ#(1v9g!d9x|cQRCuu>cPlUZoq{s zdj@^MHvJ_#dbMVHt*c=_=TN%B@VX7DAQpS+T-&23=|=k_u8TVLIuyZ^9?x)PMzZ4K{R?atyl81-`W}fTrS$6^*FZ| zU|(rxaGj7WOyoQ&k6@nZ)Kx+dD?`vy5ORZOF9Q9`v0v4JVhyOUxIbD&L{?#AeB8}@ zhm}=D)(C) z_Z=7SyGZ=e%@nbZWqrN<&X7dC?@KWAMs}8Qy)etqj`e_{=D@et3D0-yV~Srq-?bGr z7W1&a%%gcn(6WejF#s<*LjPRqq`~rpVchG!jl#wO!)<+rPxW0-bsxX49nyZrG7+!p zBGr8PyeIb6J67G%64T9+tV)C4wP!N9ISZMeejGRY^k=8(Y$&Z_rrxPvm^BgO41P69 z5$F9rk7`r@tXKm%fUpntWe3Q{S_i_eGhfmV;5GO3`TG9!*Novno%wSps0RdmYcfDI zwB+RcHAF~_t?~z;bpVCJGiT0(N+sY}6es<43UCjZp6(tRO6{J9Jf09aGoUgYpN1PX zRCPpxaZ5r2>q`=oUm|B&f2ha~C;v%I6pNQ<3aST<69YO94ya(KfO!GnsG5yQP}NaA zB%CorO}wf7m2~H5#~7v*zNus_FXHX~8u%8gxOVv(TV2ooG#}^fTsv!fbn*yISBiT6 zr&7I;biBv9`YKWShHMu*mZaDniyy3p;FZYg$Gz@(nQ(1tK_uqcD z14DCJ5>7|HKe0pn%(+Fu&X^Y#Bb*E?UU@#b4VGP9dJE_b)umoapxe#`{r$vndEw}} zOK;*n(O~6yBDTISnRbqfeeWGjFRuP@i53(y@836`%qb1LaghBmPlo?*4lyd=n)fa@ zUl|^_bOluDfD59JpP${49n@?P0L|ulHysc8XK26z7zSVh21ubUA4+Zj9kS%NJD3M& z3&=rwO{s0qL76U~&c%S@N@{6oluATre}6=i?L+xjyb&OS1$APz43#H<2v<@fA(W03 zfEMK7E&-qk`WLrAo9j~K)EI#1B6mgRplPkl8oW+10}fX6^XnTM(3NUFUIO{CM$HEx z+m@D@nF*gzF?wl#bc7OcI)Evx(gD5YrrqI4EF7IY92{j(EL(e40b&%t6`}P6a<0>^ zc2Mtu9UBqk!fb#(*9CXl1^T@isUb}>3JLK|=1tq7yZlw2F`5Zj5>H>KFvZKOC@LCo zhJ_MBNj*pc^i((2U2j#g=k81fH%vm2QQ)|+@F3*nRMLAB*L*O>1GV*E>!pGyH!Cd{ zJShQ4wl$qrpFq&8sY%0y{=agE*nz$h+8=|6Iu)dq?16zj=yV`{HsDAPVN5X_4UkIO-p zG)#+L3%e&|Y7v?nsA~4C(CqQ6=T6nG_YXJj+kHW5QKStkwKwP!0QCtKGUy2yh*_W1 zDv}hC=50X%0Bzt3)eHZH#Xbu0RlNTFL6C!0p1KvWfX%WQ{K!r7>KZ<&?0}$IURbz_ z@F{LSm&*6hsQ~#%$a6sx$eiZ2K;@o;7GuxU%!>gUMoQ)@T{ z*isLJDxtMhjaF$Gr`DE9mK$YcjJw&A2zYXCx0_ z72`2?_V6KzXaca?bSDrlY3o@$n01sz(TP4IHwvU`p|se>W*Ssr^~J z+O%ga+v1r`dp2_5NSr;7tzBx?6;`zHq?AaXC=s6OL@)aCa_u zm1WOY|FIIc1R6Jrj$>N6%Sp3)qjRcP)LduC4}|d=fq+Y+QK;1(xbR3C3u2=}4E>kN9nIIW=6{E;BXt!ne)aJ!8op+CfNl7h&~wYP`$ zm@+p@DMb3_c6_1DERFg}$r>dRRHXy$y#4**<7TH_^@cm`8HaS{)1TL5Ge0mOEwm3%iPa0jkeZR9H2C-dEts!;zZej>)LF9S^aoZ^KUByG#zK(#$&LWRFU@ zlozryF%#VQ#TUa*6vXE3%uu){?$VTePww$|_AaN?e|`7b2r|mVcE6s|YJ`wPH?$NR z{wqmc%nH4%(w<5o6nbO)TLSJKqD1vLNC6>Y13Nu*u>|lDYZ?)eQaI%R)(xnD&``pm zd{94x(kl9EonEsE35p);fmbT>Bil29CaG4lX2Es0Izc49`Y_SIrzF?J=TkQyRh}qB zclAR)I$i$uy8HeK`n8L8^i2OT%$E4=L|eLO}&)ud$xr1l^%8LLYH`mmKTK zK6}iVDUe#g%AO~4pcmG09OC#6#gPiv09geE z1etXdM=PnIz(VEf)bK7gYFtpy<6URZfGNZLYKW5x`=B$PZ@Jd(u>l@4h3Tmxn;#G2 zUvsD~mwdw3YKGq$C7}$O4p|CH9Sk&y z0skS`%*jRZ=($=4CGLr(&;SMn>?AaQLF6@C_aC5IKot*w7Z4}pEmP@ns({5KYzV+J zh4n+ss(h84oE-e$u3lYXq&Nq$gM=PD*5SvNqw!mw(v)b`(C^v28%u%~6{0=teX2o` zfklNLkK);t;D0F1?e_kGZ3+{OsA| z=&+XCgZE#YM$un^7()hADup>-r8yoQTwlyMHn9Rh` zW&GE6{f*qveil#Ajlqbx#|$*epGA42ME8D2CH#Narw5>GQE@UuZZ*$7QXX3m%_8W zbcf?|(x@a?*IDXaev#=#>8FJ{=kQJyMvn}Sa|(|eGOGvC zZ{^L@ki=y|vd>hHC3T_B>e~0)-h`sm|6^Lc&T0ywmSsf?Zk9sac!vBWbAV{(Y(R_D z+Q`4(#BOM$cG_-1M1HHc+WlW?gy9GU%sSzHDq(Tk*ZYY0_E)YckENlJ|(@Lllg`9wVI?M-~3&72$ISk zurqUt{H{IZ60u%fEPD5G_Lw{(HZ{&Y!^geZp$f%e`~RL-CR>-oRNUUn-fk&)t~{FI zITlOa-0;41zra=Fm9;VK3(&4sZ({`D-|+Yw#GB4fJ+Di5xL4fb|u_GkI59uhP6ncV-n`X zhOPh^Kzd4H?{yIpvqsJaZO6w3)_} zu6=e7dMN|H-DYo+u9(0_-9!Ut6nD9uZ`Q-N~X|yjUTj*0U3VSo`=BkJRk$yAsyu0!x57stMcVJWG7X#C1kI za8eX~;qql$qf+GijNkZwF9He)|AvN|4Ki&8H4+Vr3o06`qEJ+AC z`6?3npA=C|9B~Gg3wggr-$gfKOWOb5Q)?7SIojYgO&W3G8$uBa)K* zM23ZR-_W?0)GehxTcDFd5>Dtd11t`Al~uO(^}Pj<2p|W+7LRmeYb!_f_eoa{LdYri zW}3HNy`}(F`E$}9$~Cij+kpJ(^)rCtz+I%inNG<{)1IXRY z4Gqa@X~O`N07k*t(*Q+*sw$v$paa!NoB%+FDjf;rK35O{UfkuQq?o)3ASgiL0JIR; z%)0o!rnY)|dLU&V^TazrD(vqi3A$_OuMLy`!=5;Yh7kZ@zS)!-Xnc(ZTz)lHHY6yH z^8Z`YC_}5|yiv0htIX`ytbFbl4>G?WJq>}nP(uj2l7a#lYbF7HhDZ($yzdXfD0H(qKA``wadlnb1yO8O9;6o4-9qkKZknbjB0OOuFw1N^=z3+*JxJLee z)5U9VLJ%07k*dUUSJNARC*edSJ7n;w=g&(TpQp&{J9*=QcT-=Q#36XlNqhw0IAG>M z(el0D-`gmNw+9?-O>cS^&EX)AL;wG8I=n>!2r}CLcFr`O;S&2}2cvrn*Wd*IUIwJO zJ21=-AKtkG;{Fj80B%mv`E1DJy1h|73q-z}Dk?-u3q*}x78T=>;B(Yrd2`QADeZk@q-abAX0DZ8z*8HD#T{}R7S!>e*zEpeSYyJ@^Ap`YsnnYMsdVF|d z;w>;+U%!5Q^UcH2|Jq=ZLGORGVi5HWd~@1DHadLON5QQFI5lQkBz0}=?P;iGpukp+ zDhz;VMB3}uDvD5m14<1vn^Eu@hw#?O}l!vu#z2?(dMu|c%wAz;t?q;{$|RYW2&JQD(8V1h?RK4<-RSF`UY zm*e%jM>ke|1J6puPTxw!%OcTkBh3?7i|mNW)LjZ#_p7e&oZ45KG*wm}GF2X$4;VIk z)w<7*_&AbOPH|<;I$xix3%Y(aq@2166PJY>kA)?E;oUo{AMYF&54&i~NfLwpyo+ym zA9$o{E$zDK|I6j(al_JXz*ey~X3%Qlh!Q@XV7kh&2ZFVvRrduPLNcg5vdkPK2>2&L z3-O7G=vq0%x~1k#!6&>z`h9mGc(P9CJZnZW69xlY?+_ZaLmTmJxy{}+41EF zAd=%Oswj~TzzBkBqCtd)qT94Dc(V?p4+9eRlVR~{CluYGwSOa5xpBu!e z&~;AwGG#eifIGt~j!4$Uq715klQYJUQ*_f@wxB}{SP?KtpTS`UnItN8 zoJs*|*M2lqBy2js2^cP8U9t}i4Jd1O5Xy1{OOARlTx0>iX8vFATOxgVrON8+sDnBz zV5}pTR{c8Mrz9zJ)sN?J|{5u&(>M9oMVr%S6#uq z#~UoK0bB|-5VSE+(gklp!xO>JtWm#U%!y=+B>`Cvmp~53HxSt!77T5lw;6w*n0V8D z73>glfj|Qy1MZzKKvR$EHT}%k7_cXm5p=5o#3Tf?Kmm|W2Mf=SAHKQu{Tv;A{pwX^ zQYsM4FTi7Stm6p&QgE4QKA5lvD9I#LYMT6gt*xyA0B`8{E6UQ^8hj%F-CFJT9GQg{ z4KI8R5^0ol69BovT@KDvLSMjs?shZBxv7eQK_LoUy0rU%J6U}c8=PZdp1XCIKfHIZ z3d#$=ep%!Vjh927;}7j5$ZqMxp0XfHM}5IM5OkpS51JIdW!BaCpvGvrN@7@Sx(jp)!V>`sAO9l*&;b$cGc|e1_tZX~k z$jSUyuuTihDjz$Tc;K1!f#o*B1PFs*x+Hq*mMdUO@1Juil6ABLXi3_y2EdbGjOge& z?ob6EIu?9qn3;bAY?WAP2S9`G1s*AbXVcTC<$X(_xIYV8>3vHWWzc#pIbvplE9&Nh z1yv^)ELgN~Sqj3~Z+QwnbhZ5)`rV8IP@-*fW5{(WJWN+Hyc4!nAD z|MwC0@A0(Kz6l~k#09}jEu}H0FS}K&IBrBcP;_Cf0Fl_~!CP+JHn1xNU2|dB1bOMP zVYfLs47~KL^iWX`$y5UVF09S5l$c2DSoo*Qv%bqaT*wbOIp5z)o!%(N8vQ1sK?ENp zxlY55R4MJI#g#WU8L-sqbWKe!;d_3(dIA{F_i$(?C1GY{Wm%w@HKm@g+JJ8ZScdgq zO7N|-7b!u8Xz}pWsOoA6KTH?Yp9;e(A~I^m|Io()b{lQ6YGPm3lJhh9kv%uCc1`i({4l-c80)C?p_!UOq{BcA0 z!O#}&q?s-)1@eLH?Dy?G8!j(S;iJGv^Hd)KUJF1=OB+)Et;C*z-_(sd#MxJmj(&W>Cq0WI%BQTg0aGt$;2Snq=BBSb(oE%G7 zGPSj}bT_xP@+xw26pK@atD?AqfW7zRcV~e*6@*|uq{JVq@z2tQ+DNhw$1oa!VyBf8H?Bma7}~d zfvQx)BKD|1zma87<1!DS7-5Tb#fsZmMN%X-ZRuzs8x1#k4}cUNRpw@j7!=>z|1(B0f>4!5zoz?B4Lujg=H^sH z18KWvRYn?G`i+QaMay6=W8e_x^GqSY1_2Koeo}=UVR1F^urr;ofq=sR-%A1>pou}+ zg7TT&n5@pr%_YBny+a(Brbsb!4 ztV-_{HqM9B3_ra+K0eOFLxp<1NREj!UWaoqtf7x7ICP&X6fs}*AFCvcxqG3_U{n|Q zv7M&&6C}cbuY3n~HE`N#vgvnWJda$y;s{5IV|Rn)*TjG~4mwiM_sZgM0{A{`iaZ<~ zW*w4QXd$pQN1dGVfum@&08atf`d-qecUdFF>(Hv} z&um0w zmp<~RS&cG$1^yBRYv%AI#Af|g6Rf;j;{YXBR2-&AnPIBc0!z5 zPnAnp=2`LO4TK(To7445x|ljTI>c)RS&yOci2y8fL6axb>THU0MoIoFOyFNnD1Dm; z^bL;LCj$ssvni7jY&RtG# z1yrMA1c*g2HeR!$UUR_Rx*H$=4Iv^zI%Ij>GHCfrW*h=(Prpk5uRMi{JNU58q*fuj zMF4B%6Jc1SPa5wCnvN-S6|13+4M?KstQr7UsN;N3mub$==Qs)e_va71Iv$}eYNkRH zY4XDm!=e-@b{{Qh%pZ%*zzn5xHF;qisi=590vj?K1XV;WKEtag;n4Jia3Hmpd=2nl z6aurd(>;BCsQd!hVvP`@R84{^2&!xj^r6C*e{*d43gvH?zRQk?S(TO;=JfgQ$C2t7 zyax^lGlnSV;$Q*ZZ~;=1eP=jwKM^uw8!pBIe)MN0q2jP9++GUk*{E(CLgs9q=se&O zj5B?g(mVs(Hap4|UgagRP;t#TRLo zzd>~#0n^P2{t2$-I?EUBXF}WcId9L?8!iNc&V1>6-#zTsz<}9Iszf3SuGK{t&sp~) zWEIaTQC}K$VZ;e&X{AVPxOLeYUdhgpd59OTa?nuSq z`V?p6zsZ4`AI6|zP{DE=EJ{X#zjR6+PF=&rbQ9N7BHed=Yk-4VBf|`mAQJ*-NJ&xA z3;2E1wWkRbl1FfC{@#!pcx9oNfO>IiVx=e0$AWkeG%sL_feWy;G44A5e#K1)VnEoU z0Em+dwvDg^wcp%)R(+@_)#`^zZ3Zgun3^_2yM_bkx;1>6=vo0|B=m=7L}qzkh(n%#mQ3t@9|`J|Mw5W&Sk9_x<(;c9G_x?Eee2&2qvqM?qpK?AQ6k! z0-W_Oh}oCZ&%trE@pr6*);rNpaAq&3Pg_?=0sanQ;;vn+D`wEt%HmL#2{JwV zMFGB9WAMpU82ri3E1(3ilb}M67ttjZ5IBpQGd1@H#ng;)2p0uO8~LUE|)1V0f5 z!JM$k&?oCaRW@e~aOD5Z@>yKxb=#odC*i?bi8)+81{aVCY@eRP*02Q$mJi>@9;%y` zxIvwr%FVM3=M_LG8wc>%?CjVW<#~m@;9F4fL;ym+)r|iH4TKn=O_JWXQ;TXfbAf_*wZzF|2o69u zAu0=K&8X4DCZNt4S^;eIqo+MKpA4XB*fzfnyy$G044@TC9n(4Qa^%2f`wd3I?RFN7FSediSzHcn3W$beEui60K{kjQd75!5XpklE`C_^{c0 zc|jiwUsd-i2c$at)-dwZknTZk6nh&)lol2jm3N05Y8QHWyj*F9QjIFc9R#UiGN#N< zeXO|hsj)WZXAx`>c2NTNUfx*6DTU~J+yU0_-I~G4)3!EwX(dI>gJ?F`_M!-*I}!tR zi!6W>y$hoRaAS}CPZs}eh~ldo{vZknpm7a!+-LGo?}aG8dd8=)&gn%yAB0&jLt%^C zi;muCTZID#oZGv%4#BXlkVtY{7N40Bb(^|?g6cy^L}DE&0m27DE}y2IP)GeCn0-l9 zwGvnU?>_hUDi84C5hbOi)srZ!0xA@OYgv3~bmEpDAgdrNg^9*Jq~?F+zf);cFWs?k z8@2$9e!I$-Y?@K--2c|dXoU3Sd%4EOY6EUam}B6l#s8g1b;83x@dX_E`YR!WLBPS} zsv!={8n}#AEN0$k8o`8wwF}BR;&kj@1w``;s3M0OLBqw#n!lyFd!EPo*!_Z)@&keTE;)yUPDxjOTymp|J>_b2cjug z*NQBT)oMu339v&E4#GyjEk+dIOHEGh>=;!X&U>bGWDoZWGrQJ*^Xnw#an&>FXRsua z4NIg7u**w(KX`queB5gV!hr^dd3x z7#qegD_{lm=={N2T#}v$aXS&pw{7z-kR?NURYC~%pax)XYHDw%sfZEPT5USH&1%VD zxh3LX9KFk@C}sXM&^lixqznhwZ)lWs?E3SPAYPXVj?EBBtg4-ULkl`WV{H@fg;$5O zfu@Np2q+BY=7I(wCOX>w0W2^u7%MWa7ls)zk}xRS<%eOc?I27OWbnZb{7LX>9P9+C z_c!b-CsHuYprwKxio_KV^X-|8`+4bKFRy5Oeukh|{KoL6B2n8hTwes}gKVakg zvNSQoo6w0nVw{ zK+@u-1sxj+feqTOWyK{jC)|G9uxiSFn@P~@sJNQ4(YI8t9BrhcZj_-G+wx;D1H~|cW14t z(E612x4k9cGz7W5(ZwG$_TD&q;ERVG$7}$8AN_81pfQ*R!=>MRv78+@45(TPK68)S;X^j)um}(5r-BTf^#B@&4OME&AyEJF-%VDJf%#S}@c+2+#>@-12vZ zYMVezbUyQc0nABlY4gRz(k|2#1R(kGkA1?ScV(cg;H5D&vmkjGZLv`jq75yKkBW0y z^tQ_V8xB1Y&N5%FrL7McFyi9+8di5pw?vc`{#I46;|o_kf7SV-^{Q@tll#?cL~hTT zKtB(m5RPwN9(;oQ-}5Sf;S84P&*U>fmAeD-i>x0kGf|6DxWZ`EvQE>yr;Mj)E#l;z zjQnvym)tI&tlTDTEq3#5I@QlrPB27|HP|PAhBHy$a`5KQX%)r1unY62xHK9PziF%G z#`NKWEdcxNp{yiY3>D`yVy-z(tO*u+?(s6sAb-idq7H33lm)XR@$_IyOuja%&I+5M z49d~BX94{Z$(SXrZZ8K<+4YqT&xjz!#LUpVe7r^C6^EcmKcn;E`b-{qU3B-f8}T6Q zkp#CGe{Kgdpe|tLC0~65cF=mLJp;n#dzm&&9Bc|S*>iTAGr^n6l6bAS_JnRvbf2f3 zB*-b{pYd2SglKkqVVaY?C#_LudXDo6-2#i(AxHpYXXuSrMirFg$nmk!wx2MqrvA4D zuJ*y~&R(QJ=})W~L`L$qClXA0d8whHAud3qvBgMlGm+Kfo(yWPI zWtO|+uB%aX4QzkHIIrnlCk`=-++)1I@+(t-S!cBF*Sub^IOgiy6d@vazRa@yCUtT` zKV|j~`Lg&=Jm%A_~%iV?gghZNhl}n|H-f zDKo8cVI;c(Itd`3V-TUB=;m!_m3oz-C6N4fb@qxY2dNt;u8<;jSmSn@d|PinYu0@B zrYZke&?2_r7Ut2qn0tYhx8@w|3iHyqto_!t7{qqrY(amHaee2`KAuwCp_mdp$LMc) zNAbs@1&=$b|nRT#FnB@r&KGY%ZPr4gzRh(mP>`tqUvP+I!h>KG{I zPDPIxS7`$$|D8`pDzUUr#M2N?jr;fD{qsxJ--a$qZI8AzGOR@F)YE5Tr>H282t zm9x3Dwf+(AM*WSo<8{!8G;wj?`>Xtf&xBO6d&Bt2=5UzNYQ{tj59AU^WaxT*iJ!K; zBQRC63|d$Coky3a^F4b`V!UKjm8zXjW;_waKc&JBr09I1Zc<{! zWDsN)>9BJ@+cvr&!13%^ph(&!#;QzsHSN>w#7DNs0mFDbT*Q0QFWM1SWQe01#4;7< zHC47eXu0#|vcPWw^a9$q2S| zArZ9hmL4wI@(ZeG8T=_3;L{~UEVvE+qU}q&P`^hBGi)57OyogzD(>zbMaTbTm(B&p zD9!!OuC8haGNm0jcGiM1a4aY(NpzRE$5k7yBdCQLKkz3$-A-zIi(zcB6j5_9|9xvt zA|_KteuOVUwBElXCz>GN=-ZBcQNIBKH@-6Xmd%;OkEW0)(_i1YY>p)S@-oAGS9*2R zlLc`)GZ8wc!h`gYe$x$CpJQzd8W)p^R?V&V=*Uwx;Zw;3`|F)X-CnJvX!6>?>z~LJ zKqDr*y(JTVmBz(~RZH^uTbb5cjNp?QKi}bqf}ej7UTR>dGezT|xG{+^qm7cgnoUQu zFJ;$c4zzmENwRvRpwJF^l)=4wGJsm|iomi-4N+SyjfM9bDUKWtD?Uej<0|$8eg*r1ZYE2HB;=Q; zkqb5mLFE*c*0%)egfA2x99ko82O?fIE0y7uNKsx;{y3w*pcbuSe!@#@Bu;oQRlO%b zFaWztnB|A^#9{DO>s|aMr=!BjhrT`>aOCkZK1vjK?V{}QKYp^5 z55sOXtCZmp&=^U`n;s!9><~I3E_AYgHw5tGPeLHcI5`hM!18h$H@JWQa1<&TP|Tsb zWv#I;&urHLk>mX~rZXXjSjA6_cNOfzrNu^`^tUkI+jfmB`2msvKX0m0Yp%7U!k81N z64XKuU<~@L!)ZrUHZvGIn0B+_3sgBWK`)zwxvOZhD;f7C5=;|TqT~H=sAUv(O*j}u zo8@<%zVyj{^UEP)@|ON`1wQF1G6~s6kGO(gE-a_xM?Fr^L3H_GU&;Ji$dA}EqCqMS zv~DKJh&eG#M4hO?@bN6|%(Vj}y5v#IGfMXKjhc_j{AOQXBFyN6=i}sxWZT&yugCk_ z9AU;fs@4%auSRb8Qtr`tsqykwCXjfb=?IcPcr+T8ilrn!mTeN>Pig)myfdnd1|B1a zxi()E;i{tk($zq@{V9fE8o6iITDqZT3G4I+ZRMd6)xWpxRmNgYn&rf!_mui6E$Fy9 zzC+0euunnBoep5(5F;`p3JD4HKORw2>vCuu;A(aJj&fHX|zdntZ2hNvOP&0+HO@^a4D^u38KADog z{E!*{=icX4<(BO`SV_c5#Fh+Gr$(Msw}?ID@MM$CXei$J3>liI2i5q6N#YKp-ORb= z;`h7^cZfJ8ye)v4^lC<&O82uebyP9lOxVz0O2DYGNrsB_rC{1K9tz)jSQ`9%P;#IME<(fs=Y=$KyM2|*n8xRBui86 z44Hq8-4nZyP8`=>dkyjZ4L^axnIIf9BOzwYmgyOoLgf^=S3Ax5tq?b1OX3gF#2scF z#^1#q>ui-o4Qu0?~v;^>6kn`J&(#--iK;8wsuB%`#ca9 zaOEclcL!K*lOh^TW^WqPXafC@?24`6+aFtBzCUo;3?dC_#y(+rcj}BNi&0r@M)n8E z@}O64(+2Yp8SehX>i^qH^Rk)&9~+7p%Gm;xDK~4?ppOQ33R-;y z(BGH2*oiwU(3@rCh#EZS$ddl`y@yyEd0Jg$s4Adyf%$pSqeJj{7IG}|Wgo1`w5*wI_wVB@jZ%&9Eo@@{hYYZSuMWY>tmTa^yDs|cxpTG z*C=g@x9?WL)EnJj|Lhu;eC=229fwjUQ^LveCW5%E^tiI0y$9-RFKSy???HE<^qXVS9$NDuZch zQw+O()sy=^9!k1UlS4Bo9!dE_t)z>Oi7uXof{4nz<=p}|B`AEDl#bd}0^xWTnuw?x zHXXDMPBOLX&{R#sj;N;b+3KncoleUG@bs07vNMAf)9eOP5_bKH6rjvgXYG^ZjBxoo z3aM96=L?$mX#IvJKPwq3ofYup`yXw4Ch!;j{zO+!NX<<8nE6TUTX$k5fjJ7z*57O^ zvh`Jib(mx93h9VhPOl#1sgbG9qhLqwqHHuCzdXid2;VP~c-)>(_;M!)fK<_ebLsh zAPkmmS+eavRpSm;*dWF4#2<4G%LqLb{c`0q3kzcTmpKhi4<#=8mutj5^QDfj5A7VE zN>g_-8jFZMZbI`Hn+=Ly;YCp23YQt#?9+A@`*DtE&WA)E8>v1B;yR}I0$m0roHfpY z{cLZd1}g+oJu;mhDmy{86ZnAy2wb1BzZP@^1T64P4&?CU(!V^UfbtQ|^r*hxo107v zJ+~Ml7^$fJ?SthWi97tBlZq;%c;AjIZrn=J=QXo_!x~`9(9ll$4R(k9|(&>e^WMtMOY!d5Vg6_hl(tmEoK6gg(L5YYsiK?Vlh%K(1q1!tpAGzeE^D%m0{hUyEfH`w=xJ zMw=5yuqqes?CqL^EZeJJo?@mEe@1QL{ImU|y95aCahsV?bD7}G3VOqExw2{89m+N* zueg>#`l?TKT+~!J%=2t16OZX0o|46gAz2jCTt+)ug$bWmm}{sQ$d}>8ljMi`%A7qm zrweU8Y!%+L7*r1-mCqpG40Q>3R)*U{pn5KxxY!~{Mt!Z#q?Xm^`pQe4jdTrQA4y@h%{e_ z4_Dv5G%Z_nlhzZD4%eRNynA(^n_9hFdXoRBD)w1in{>@VTW$TL;?yvz$Q~7guv22m z58G)@_xqL8(I>sey4nRvTX(mU6}Th3nErO(xf(;Vs9Wxxbf1cJct(M$RyVoa$)2HB}UPH|>ZA9|jYG~PN_p>a)@s=F+hLX`{{T>LSN*{MaU zg{RSpMf?0Pl=_|#IBp)H#k@bpj!K-U&I~hb{@LNKhfG10x`&7M31kmH$cv9ub3)a~ z%95SgeJ7!ku$2vy29q^^KRw8m9g%X=kU?v7+5Ct6uU@D|Whj)PsS%q~G^orUp);}< zd8;-;PRE~vCfkqJ9j~PN3S!qTk1#3z$4ti_EP+?6cKCB-iHV=0nOAPcAn8R;q6mID z#azBXt-tlpo0?nmC*hl;A{jWN@0E#8$z+4KSlW1Nn!;_p*w+{_(K_8&rtp6gAK8-} z*pQ{SnqnU^+Bov(R3^_kKd^g5kH#8ihJj=r!#!jaZ3-g=11miWWB@rnr;a5iT@Wef zmp@ZzOHSR=DJn=?-bAMeeJsu^Uw#`#hFf_iOS~&bik7=3xrTt}5r0e*@!cx_L1+us@Fl_E zgB-q)+zL*fA%6VR=YK?V-TiWj?jYCY&S&SwqTuxBub5`c#ZPI9mOE^7rTk&MO&>}c za*CM3$5Ls}pzBtfQ17v02YE9+5;D{nr!S(xS~FyM-ekgr8&K zp3ZST%M%=&l>8I)NP>1UQ=t7VMeRYN(=#RoaSSLfiha=!A?*+U(e6%P!iPqn(auEi z-rI8N(lWpAW}NKEwfq1KJyu$y`O?;SoXqInwgj}Lxs&UCO=2RKJ6O;I56jMf$FwiLTP2(bZ=U16Yj*Ib zkrgIvd?)A_bjn-l!op2!_GT*nJNatUiA6@`CIR<&zyI$nE;6jDC*3~iKkesAQG+Y-d=JOyg!MDCjiql>K2`Q>wW41h zZ~&Al@7pI7g*ra0Z#CpXMLNPccA}mwl|nieDN||=R;>8xf-tC^_&}mj^P=hoL5I^ z;eVqa_(X@buUY41c|l7d9r6gymOIjMnMAI)-N=Uh8`s?OPt6rE^zp^@NsI-wA75*t zyC+G!PufM1=HM_xv%znZffv1<M4)sNn5NftH!7-4d<4^)E!(O*1jJXIJv>|2o62Q738ogT}q8zjwR);gwTM1cV$vqqozW*UjXv32J}oHf7wv z>1Rccw50oZuhqBc6cr86EI@y8(qb>z3xWZRYB zc~f0){xS}M1Wt|}$5XzuhUEzoH_9_Q{9{H;DS6&^$No7QQ!Nz>pAtd>{%BW=_skf1 zEamJeR+wqgih0lfCDKxLjJVA%ZE&Gop`81+_uxxHHMftGYnt1Nz0kUktL;G1lv~9E z{>f`9T8+DTr49x9*YGoWWat=kWU7>|{A~1zK;kZDx&Me(q4U~(p7o%XLc4Kp{i6ljC5wV*LaD)S-&U)5l|lMyoyxd2(b54`*flO$^p0E0L#jyyjH?tHyfn z^*;!BzFd*E)@m#qk}RzAchPnG7r>Xex& zAeEm(e=9vI>`$Nf2|Fg6Q6pT6;(*4ynFJxv3p<`KzJ-{)mTd4P?b#BOc1ub)^dX?t zkZo|7%Qr~LzZYRc8+$@TQWNx%BH3lRH#= zYDQ-w!^`mGcw<7%v~IZb9iA(j-j;kB=iuZ+Nxbgu`|YMN;W5IF^8KQQEiwFmlz6QX z)Q|Ap(XVr7kQ6LkPFoGTJ?p)f zdHZ?O#Q7S-J6|`GQ#SnfJUxrk$AfZz$a#JCngn0wIgP5Unfg2QBoC#pn+lEQ^cd}} z2bypEySLQQSVws{YWy4#1=PLu^EZ^oXvUeA z&C?^p-tfoS^}2Qkc=gQj1~1`Se%g1DBU+;z>ueWpG9F!S!Sd>1Ojan89UIzwv9UU1 zY21;N)%6?inLKuAtHpCU?Q$Is&}&9~>FVmrG5tKbK^V~vEn{ zMU2wTd2)@N7&kHt7s;5}dzM8S@(Aaxv_kjwaf`3YtJB8UJ9Wvt;xfG{BtPizl6wpo zlDv*PqS}Zeics<*tgiC585mrI`1-BzMs&MLsPH3N~eTYwu0LBcEK z_67~DU;>`fXQKS*Eh-6TDZXc4eW+FNxr{<6FvI|wOx*bA=96!qMr8?#h+qKlL}2B5 zX~6cXn|NyP$hi$76QfTvt>J7e=ep_E<d{wYTlr6BYR5!+|h>To} zO1g)+{*HUP^>FRo@%j%QZOte_h0=h>1K*XlRIko*OmFK@>m08-*2+wa?Ka0cd4FDD z@E8xA5kCH!ef9EA)dh}*sLrK8nO>Tk@oJV6>EwZ)^V+Y!u6_W#+fO$8ZS|4>A^C6u zm@C5=cK)do`z~8?!_`!OnNz|&T$5O7+AA3E&9z0u-ykVc*$@{Dh)t3ob6%HR>%VQZ zVwPj&mQ%c^v3xB0+Le&;u}txYUWE+Xbgdgh-J2uAL?ML9v@m(4 z(dtBPiWBUwQ;bgKzcwu^@Xt>8Gcpy*TS5^K>$dRu9==oJFU9<<#w zW0`7PA5bkvlbvYm+U)Z`tQ|_NPLh(~6uDFN#Fa|p7K4wabq}uoMR_`TQ{9@><2A1D z4=%n&5Hb47*<&LeE}F2uMe6UTm-`G&fsMk>@A9_*adT2-#{A`)F@f2n$*NSE@C|1YRP>v> zFw9lAsr{R`6`4?Q4|)rm?nTbKq=O90ADc9Ft?53b(prd1WkR<}M!Rs^bX@L^$q&%DW}1 z6tj$%riaFULgA_-t)J*LFJ;FtwsgJX+TKPC*PBs~9P6Uq!>Im)a0p?QE2u)h4MCbEO#Dzu#|f+`IDPYmZQ7QTe(XZf$0H zHao(|WHY~tnUqcQn^0qQ;XZ4*^^e{tKOXOQutzYqSfcw4E?DEL9WrdUxb@_G&GkrS zU(nVXq8kgG#!6Hw#Q%2SK?F6l!+)NA2=$IYHQ{LTXnuK^j( z^O`GTHp`m`xHMdKKSa8v|0O0RvVR@<38IIq#j44h)bQ)7Rd5WuTEuf7jkKl&4@;P@ z6@89SbL2{sWU#<`>)Gy4tj2%yP2ou0?Har~xrElv%rblxHO3GvsBG{)Ge8StJcY*e zp&SBw<-+s_G*Ds7cz$O|`#m(+Os#U}n(kn+Vvc)0DZtFARC+6Apwb?HLJ%0{CWJ{h zxD_FGb!k?i4DWG3TPPV}EB<`@vgyfNyicf0cM(;i+WaIvl-$fKhdY4}&@L$8bh1OyU zdC8Y6-Aw52xWlcrbp0)Y+~v!yl8G_O7Hm#8UnuBSU^OqSeCdR#kNfRJBlxAkZ7H=el<`pBB@Rm*(hudrjPU0)a@Zs1n9p z$&R@8EP`*^{$t@w#7o=7sKc40fTN?-wPZfSYT7E2my6$d>b3?V0{A&&Dk_GXx1(~K zHlBXiH7axD+fVEfy5U^tO(bzRSm{~IyWm*+28E5TBYizwO+vbb;Um1CYfU%x!Dftd zrN-!-`a5%cIbuZMwbVyPBiq9OQBQ@B4h8Pn0#?-c*Ftljv~*B!o?x<&BR?U`8PF+E z$r|Q`Ap(lWuz}+6TenD~RRI9k1e1`CMcG?S#3$@2+RR2#y($(y1Fe}Z; zmmWopMrL#J7c2SR7>xIGqMh~n292p7v8?rf#?mxmJcXu|HXe+Y&tuCSxg{KrfqN(V z23^beBG~wjSJo-@68t0*omILq`pmu5n1otG2wWVVJ>n81AM0$BMjM%eeX>)Kawy&a zp%mVXZ6VfheLF2^J?Q9 zME8AHeF#;`37dvQPj6^EpmZbR9yg}T7lMKv%M@lH&pV0Xs=<&uRtX=;4wXARq3m7h zi&ZRE9>TcKi&rwmw5)I5J760g;r<4ZE){oW7uQlMcvS>>H_Q9AmN@$tf9-*TBIB~o$Rv4| zAK{OT>WdVnEOVyDd%s=x*Rw3poU9t0$tK^@eQB1k@iM_pzkXptoQBjIX^#B|@C@^u z5R;`$4CLOf{PS?qD!*W5Mf@GTu;+LM zk^5^={tpX$UL1j~3fgiXXZBYgMJJyxe6T9z)-$?$ZJ!7@B@81QLkl;mHa^VsxA(-Q z`L4WOtBQTt!ym8*7!uajw1KiMIN%;Tjy!c3!U zPSwb^Q8Z{3Z@h~02;i0H&O zqKC7r*OBLKsSp%w4t5Yw$0~{(Zp0hGkS(MC;d9M{l9A)2wJau>6(?D@sCKsAZKwN8 zjMopdi#(?J+su)Qz(u_*k>T^Hm))KJhXu(0oE-ZA=YJ@M#I0qvwf+Z2wlPe04^3P5 z??SVLM=-pbHK%*~uJXM}x9LU3r@TDe%;r>h-y>+lw)Q%v6z-~LlVD^}XfP^}w>>iN z4GxY`_IZOu?rWvoda@aa`Jh~U^t8CT?djv9_SMYK532uI>;`MkOfEP0nn!s1trUuk zG9<+ddv1R5NR10E6>Q@sHzdmJ^OiEPs;cHi)9S)h)5GKMc&-a}{;9g7 zebef@-`RM?NZ{v&qR$%goBNdqVfk18jb}TaDGaB5$)xfE&)Y+@etD105B9lhu!9P1 zp`fdg%XTc^Lj;Tq0*rC%V`7PrqmZPPWDKgSkF@$D2vUjjLk)s&T`#j_-rwA$LBA?K z#{MmNhyHO)YjqzB9htl)?nw59!f+t1Etg~Z*bYbW!cC(0g}Xma5j=qLi;M8LSPNZ3 zxOsfhjQ!kAD9%eh#i!EEDN7RK?lRoE)6wzvbi6Fqy7zpBX?d8pNo`}2dfd_djL1#% z{zykP>stRFk!Y3NLAJNZ+e0Q47$sACb#ohLnD*}{jn!kwSGeV4-bO1UDMATn!4r$E zl??CoR3F#b?q&=wGqZLex&w~13ig}GR*EuIeJ%waief)>5QO&88YS<{h7#1G9_GF? z;ySX|m??hhD0GuPWQ2OHtWIR5t7r4FJJR+|3C|aNUi% z-|X;Gy^NJDC8%yFPbyOIJ>gIP?JrS0iFk}(=MxO=^`5ar?Eb38yGriQzL8eBc3<+c zf9mmLW#zC{>7%bjN`be%{Dv;B-_ogidT*v8kK!!glKrxNU*uWEx(!eK`-C5s82jx1 z5nA$ZZITW*%nY?YuP%QfZLF?o^khEtJ)xHA7qt_&-aDnw_q^7h7n$DtsRr~f&IifH zycCGk-rS*%IRVl1dab~D9^-9pL`pf752m$8P1F+Rr76FP=R-;S&8*`HBP}6N77!lw z#%nTIOC>NEuSQ~zY*lLt3YSJCB)w+Tmd{#u4;p@`$rbU3-EhCq$Mv1qu)psbsOSu9 z`k6d^9F8pbWD`d}o}B()L)h9C|DHSM^s9+F5g~JS#27oX|G-ZcFL`>=D&=xQ1SZ|D z$4m=G{T-gZ`8^AXR^twXG#FM1Rf9F6e8ZW=ZcBL{t@>9yIluhYnMi8i`rO;jdM5oi zzgB}n)Di!FYhcN=wEy5`-%Mkdko)W7O`4cQp{Sf*8Gfo9l0kKg~bL&(LX&V zdUA`;OAJqqpLnGGm=#{3Kfk+i;Amg}V7$qF@Z4u$Ki9ajqpD;q>w4imLmgdR<{5;N zDw2i$>+K&~ahR$#rsxTO1EdeSB*ny*F#IyMz0>+m3GOyjf30Wm-0V_%ru|4kw~`R@n7)YWB~QYAb7=2W4~5-5P}Lr@l$P=r!<( zlY9NP_F@Syf2`JF@z*sZAo1vc4 z$p6S9>AlkNc*xYWx3XsE;(5AtEa6^WYW!S+^x>3iD?J8daly>h(^o&lSOp-qCy+4D5K7&*kSK=ExxhDe{v^lDAjx;SAul zVnz~wFMA(sEAw4tt|&YVtI+vgIpoq>wu17BRtc`eH%b1g@^goYN21S#>k!y;exJ>< zW++;kzZse!M@^bvC*o8+xjXMlOOe#jI`0yh)m>hs!M1iA+9_Gi_x82q$F*XF9>#cPWfh0nw^W`DY!8wg8A2vMdIiha93AsxY;c?|NWSCe> z1T~H>lV&_hy`yEuL5kSkHM7ZBTgBJs!WAT_%x|?4V6?Z{hAf9Ihn?S8y`r0jlS<+w zVOf{l8rsu4mg)Lr=izW#zb1|dt)9?B$*Fraj%B9d3pjU{GOLIW)FQRY7=x!>ey{Lz zzxmQSWUn6ZrZ@(_z{$YOhbMTk*-={=m_rJb;?c}poTfNYA7O797U#0GjSj(Gf)5ZNAt7jj2Mrb=K!A_{!3pl}G9*|6!67&V zcXu5mxVz6laCc{h?_uq|-o4NH-gVCWc&>T4fbOpDs=BMXyYBazZZBLny7g!{{FYnr zZEbXgnGE9dmqNZ~qIZ{sYu6dQk@(znJkjPSgBwOu`u?3}lK}gJME@(XBq6-DY?*quJC2Kbg1ei81c1$f%RJ&dmH< zyepM-1pcbY$JqI~HW3h!Aog+FpxzkL-$gH~)eZn8GprNsr}&^vQ;E4h(-((7L@6n* zjvQfT*w)>FD0n<_-{R-DHB;fpK$DPEQS0nxnI|~@Pb8BtKFTZ>qvNuPRUIu|q4__N z5E-g;0@#ev!~uO_iB-~39>qsS)h@N12}=dRJDFJW{`?9HVxbFWK5YfT;Y)S`MQW^4 zwL?d|7RR91?F{QL&7L})PVr%xEL@W0pu*U>e&981QSvkv<8?Gb#q&?Kj>)B=HDh$| zc_p4nx>{n&k7a;s9P?NMvnhvI(kQ51=KXVcY^KWR_xO@R4JeDJ#3CH0ej#IAud%Cr zC{*x{-U&}`y12Y^8uNw0>4QxwseA+L`*c0~ZzSJ{J@ngfP0!ILbh3p=Zn&TGv(1^$ zpO3@pgc-6bnQiG2effGQts~DG?+Pgy7CZFX11M1RCmPQAC?1m7@nR}p(P_}WDaAck z#$xb~@U8!Tj8RQ}OQt>hz?2u{pGCiIx@eoaz~zjk*!HV2iG8{zj^C~H@vjofb;&$2 z^txtD5$o(~)i#%^_ggiYEojctWy!wtb56;T;v(dUPjC&1q@+)p(q}n<|pp)!`F0G?r`0c-Odvn1biDmM^8{>rGfI>dQ7wNKT zTBAU#ISi)0s*1G{>Cg;>t?tEf**tfxnMz2K1>c{0Z|$_InJg)O;8zSS81 zh2$y9_IXH2!fe>=sATS&B{Z+fYzz9OR%o2pvBnN7AX&h|)0s;6tSur1M60N1ld6n} zU{^@Ts@gd}(O4n%1;2lGZ3Xm81gwL9-&U6J-x9+15n;+5UvrSleqXOmz(+dwe2KH& z9W~5B!^hXcDsE@q?FEUQwo%6R6xL)+>~`ICfck*|sIty!wf z^?B{4TCD@-adyl<9H2t5e>9zG^22H?m8BR~$^8ev3eu5~X_MC#`+~zP%Sij#Zj8?> zf0#x0ITv62Fn$sdAWnw4_`yG0l9#%OJOfvPmcHFO2*JYEnRkV=-chC(Fi)U1-fKFH z=^?@t*AHA*ToND%HZ!yNaz?6sR+bWgAeq2kWP9{v`BwsHkM!GvU3CUQ10l?Dl)Am8 zz$=bH{t4BnYPvJIRpl^WB%fJSYnh#zyS($Ku*`K<0Tzaj)f8Oi49cN_Hq=hF5~7qD zSm_vc9Ulqj-Qx-6EODQ-JA)i1m-rg}%BYzQi4(t;eHu~l6{f*MO(!R!kJlFpn(N3L z@;l>6=JiFhGE0Kvvg2)fynVewsGF~Vx<`uT4A@tFi9Ho&8Ht>ON#Ghx>iZ4%?dMFQ z$<;5?`8kxZw%Gc>vQPe@lu^^Nr9!H1? zQexLFk0=Exz+(g_c7rOZgUw_oX*cjgvuHkK61fP)WTNoXOrucHOe2FkM=DSB8tLO!>y&2U`JK?!zX|Be!?qs?qG@MOQhdq4bo2Jae(lH?eY;t zKO{lkn=kkQ^VsUNzBUsJxlQTMZ9%OTM1tsH4gw`@_V~`-zk-3n1V;H|NrH9mGo=!w z`hd{+iF9DPxU}o|p)<;6T@1Sf%o$66mWwd7fqA^riVv4?dd-*D4E^CXFU z)E8pfB4v(^5S3;^FRBHCvTHt5+>X~deio!vsxQpQCkz?DXe$1N7s< z^1ueXt<3SjnXit)=;j;gByDz zydA6zA+gaK?(a{ ziV_9( zk*pKf&A)qo@zm9gs^Qu923k0K^nnvA)&FdZHS2hNJo@&DB%Y(?++pFe>7}!syu?Do zC#%a-oAcn;jn>(c&#K3JJEHk{&O%%g^`A@Vye!K0E!-0BR0eQBG?tA9#T%xHHqGrl z$Njxo*lY6jUb+E^7-szRru5iBkqqD93j+=iupK!Xjs_IjJjRf~!1}+{g&%7geC$1%en`$;Fo-eaV+bR55|A3-h{RJ88i` z8M}Ze2VZ(dX9PYc&Qx-K6lWmnKbL7Y=^0+tIGN)P8|g7V`Kew(+NKM0N}iOA{uUvX z_r}#ad5C%<&4TyBp`2K`Q(m%5;#EP4MhXAIgu7qR7CnoY|0WtGUITcUYO(bB^n<^Y zB!)l22apvB8}LOxz3B@Opp+IYd`T>&Mz+0viB>SG+$qUhp^7a8om9!r8P9@-Yd2j|r;5eeppxoJ(BqHT}p19}?Oa>i)%kMKCUoc)s4`zB2 zc^-;}O>)%qe)Oz7^?OW__Knv!(R8u96zCJ)gyRev!#p2(j;*S(70(c;1%pj(ah257 z-TKc12WOmkZ4*kR0Q6Tgpgyj{Y5+7j&hEg85o~5V$TVpt>*+0e>Ic+LhM=q0xZ!4+ zKc)AO`z6X9!%xKZS{Z6KRth{w*d{m=0rL^^6hO9xPq<`BiD>Z=K9+5IuNPhOkc8X8 z%X$9HzWCOq-z{qwejqZmm>%H`vX`a!6%yQ{PoxE!2tN@)SOYf*f+X#F4cGj}nTn{- z@1e)v&fNL#A;-8lH_G)qLwH~k;QTUZ`5r6W7(7Rj>UrE&2JC(Bxd6m$=TkJ?Bd{oeYYN(4~ByNN{4Q0rbHrzS{JWFBL`+d0*tnI~Q}?Qq#|i??w76ekfzs zF$gZ_Ng?Fo&pS@>FZ=Cg=|4KVf2w!1Y48~>ejn=ZKnhq+>!3A(uep4IC?C+j;f1g`B>#pe-8YHtq2(u-%5-O z)G!>4VC59d9jZDj{pu7QOjBOvE=C@7gUam}V}k@yZ;gL65@akPrb=!ICiU7K9)#`q zVyVr`<44;YF!Q?3d2rB2ZV(yR4E)%0@YmO5z~gJc`Ta6Q z-~)m5b)Yil{42oAum?1^mu|2;Sqk*P<#;ZGu_`|8QweQ*JaT4zzfN^%eE|ZK{0}&_ zw7ge&Lnk?+BuwpN#C(-0jF%~EMS*}1C*(b|`^iicWfcqm6G5=250RA5z&*<~c>Z-w z0IhNu_kG?Uq9`oI_ohA{&vz);amuKgrERT@6?K?}jr^#u0is|1#Ux}ow5{V)Xunp| z9?gS^&f1!qsXZ6g*tY=^C`rU0)6$Vy7rdX)+7HAxvr>Q7S~M0{NhW-D4sa=hrZd%| z-nSOG=B66%641dMj;PN}NQTQMvUb5S?OY(JqsQI6_B}4q*uK zyRhOf@&1u042rP(cI`fF**A*(2eWtJ?pgA)T@yzp`_58y*3ZJJmg4u#C)m=m7Tn}e zV$*i#d@%`7J{zHe6XoV%EgZQ5AgK7&Sban54gSu!Ew3-S+IYDWMc`omevO#Bp)!m! zc!{&-y~U$cK4>Z*q2#MXQ;at>CscA;wJLf&kXUuio!2GruxCb~|K$j~E zwgkZ2_;eG7bK#hY#~5&#-Nhk3N6t3{ld^e#(t}a?n}XyNAbntAi}3VYT3gD@wC`;f z7pvT_{|X+~@U!#)!-j^thW|tZfKdKKB-#?}MW*vZbb*p&n9ejYj~lC;W;jnUKxd|Q zXZW^y3lXGJocp?zBOb6N@4?`0PL&hh1(#pxnWY@;pnO!2y2yZx!MV<@b!o9vu0Wy6 z1u9!-S?Y;aw(%K^maw4C1UJTd9e*&;f?eACd6B7CqCWqR1Te-&nhC>SG_#?@3S#|W zVFgT;D-Q=-7>l!eC{shZI8a z_4G5q!p#%xywXsrjq;R>!KbzPlm2bL%QWY14IgyLT6c{>GYxu87S0gv+So|=4+g$x zP%`gqimp60;H2TsvSqd-k08$X#uDb+I#CN)>_Z~9x^jvf1gtw)B;OA?^?K5|TrDk9 zGpy%|F{j+s#?m^wvCBAM4UJ7YkMk&y2?&LF9s=s&{PkJP_6OLKe4aGI{Gf6pG$37= zl6(OxZzVl=$7?akCxIVSMrCiz>aPjHk`td8Zm1p31Wb13A^=sq_VbQ1Z5BPZ@IhnUC)l$UsFh=y^+>>(D;(R3h z1Ox3?i()t6FZH`Zh0`X)!w+ALAhR}7tk}sz=&>9Uq}Bv6PZ$6%JD1oR>TAOy@yr$K z>CgNNslaMYM@e4r5=)M>&YnC~d; zM0Se~iXiNYSW}jAIisds#iyHkuRXukObp6KS*B7B-#hlzD!WfRDE{FKYEWu*!je!N zw@lq5*nYWKI?7> z==y(w90TGjdZ+OQK~NtUi;Dg}4}tS<)wqu?fK)@0-U?T8byaouFt`#E^$Cou1epRj z|3ce`e1#{S9|e>6-R`ph1dd-W+N^D5;4!IL1pk7E;x^Q=uF(5d&(PGcwKi=0RI5DbOvz;lHIJ1D-p;dg6zf^ zb&RM{_?_~P*sZ8lZCB_8ia<$+2L@nT+0Sa+ZJ&f30s^V~Da3be4_h*L6;^25K8Whe zhp$5DY(7r*585JITA|~+xj&ldzzt024V|V5As4fZTLosVmqu}Cpic^aE3_pPh$G^h zDq0k$0o!KETX5d$HPcAkmL#aK4U1kHJPCX=>K$_+X7TZ5;R86Qm!+O-P9to#W~;y+SLy3LSD4QhC?@k)QgB2}Dj(-EXUF>= z4UF*ANyf*96Nb%6bTf2C-XV-MYl;Eu)R=@-bE{2oU=ns?>nb{v=p7!vSfxlQeJ=A4 z_H(R|1A%|Wq+dPqgz*V>!DZ_7w)r1+Z&e)2=V;Lftc;Hxdjkd6FcMs73aQBQYS2jM>Rs{CPl7+wy=mojEj}O z;hbu7iPO=Z0}S+<)Zo>AoM2uzgV#I$_d!#@MA%@mNxz`|diH}qE{d605PL3Pxy$8D zckq>B8R;v_u<|fmJZ*d#DqxD|g-?xS&_O`L@jcjacz$((fm@?fHeX>9uo55+Fbhn2 z@#QZ|-ZemjjC_AJ0m0_KG4#Ew0RW1}M@o3~n(9`mpwHvLqJYa#aS75$y zV8+MijSIX`JSQq^LSf&YmqO5_Ki`99-T<~|MX*3rdhg}I*P`6aQV*{U)gS`E?ST_o zzFfV~c7{C`v1MJH;nZ}pn04rSkJtY_X9rc^NI5*l>`9eUG%o+QhAJ*DcmPIn?g1&jS;qTn? z3ig1hUljsT{7J2%7{}`9h@!Na1tC-e*dwyheN6ocX>i~w{&6}T|~VE0A1ndr zh+t|wPweqr>5G=Lc6=4Jzs~~vZu+WIEEr3V@++!KnegL*>;oHDNj^hzZz>q8^FiieXG56 zg5i|jqNsn2aiGYVzI~E2A#VQK4P(M^9-=yZ9QZ~erMB2!S2-0aQg2#&wsvqijoe$;SYig10+ig*hBV?$^Yg_k*dw zGhT+kM*4x+cA;_pDRJVFzGS0QrrOcjWJ!Z6SFXx_)5xj!Dg!Vg>TLl40aA{Q~$kO z-)|tYW8JuY48K^46Tv&UdaGT!if^U@f4UCUWVd_N17x(I{yS;E092m_WUEsNKWb~` zx^ml^88w0cd_ZTp9kyf6N}D*Bpcgye4^Dhn5Rgsj48X+mLciY@=?Nf3l8K{5j^?## zPR%^O>Ip5!-bN>wuR&X=uOMB40J98Q!I=7elcSxkn_OkZoST?W0cfU^hZy1nGXCP1 z3ocx~Hb7F+io$@ythm_8;aTlmRVx3bgPNyj(hUM+)QW#`&Zqv{$#fNzcosr#0j5?= z`*IQpcPAnHV6WUQNk%CBq1JX<0chl}M8rvrBM?Qn7ZsC%{|Ok-J4|*s&^SxyiLFiF zRCOb=wSdh3cSagAYg59vd2ie;Ih-$^FTwi2BSkIvK>V&XRSV3@k^%RhYa0#u=DQD_ z44-uizsTILhFVl-=@&Ou=K*LyayDB$dS>YN<_Fk_6NS*Wys|o4KXzTQVmA{`-osyV zUrmIwbZ(e|xIu4-+V)UiWc+O$@uaNnBG^VliKG;04^(Hx48i@m0%{HX+*6?jz5X(A zukpYZ<~BDLz@Ul^Bwja5)Kr5~*MS%Za~sEi#mvGSwpGk`pJ>)rvpv>?;IuRk8ZVD1 zyp|;ays_ZJznTLp&iXAu$3yVX-U&Mc!Cr$?qlpJAu&`hGS_;wQfc(T=9}8z1vnl?A zb~0%+Q2jAUK zP;)itWO+Sb@=_!s;3}0Yz9~I&MQ{M_l3(mZ0hj|oU`ic;pRtF+)=6S(2PJcXi{=UZ zmlb-}@t&qhHTG^j?bH=PFBkI;CK`b@l8Du7JWfak(WJ!2igIZF0a*1YN;}=hitBBS z1z5lO5!sCq{5*|~%}sl|;^>o`fx8Sjh+w7WRDRG>>C!g1c&c`55r`I$JO!fns4&-q zhH>9|cN4tS)Fw#^BmwF{&SE?wcrZ<^EkG|?F8j+!GfS|}`+d5}B%7lnz;i>5Lb3cj zB+@heKn;sp?Yq6}%8h0K%W8zJY$w572-q7g&(&Z{3^;jL7?XN#6e(2Xb3Fd=MS&~S zWPUf>?KeOU1xNoCOc^B~IL%sTqGjC>&3_5|#(84nakytaRHoeN>FQk#Ms;GbJ#1Xe z4y<>D*+x@=+)06~U$;2fv|3^O`t;5o;DhzM){0?Gs^ozT{cZT>UXlNltemD1uv-Eu zy#|eM?OskyQD)4_8Lmcm_XQE!Xbw4sFgHJ;5!n;)=u`Q$f-@qk)%Jptxbx}nzOGRH zZi2Xc0jTlLoJV=qfcx>+6C;4?EtXXSa>hcYu&%`W{Kx^s>%0#|%saHt3=X?oJn8O# zRHtM9%>?BeV_2$76Li>P&4bfN2b3r9)Vk@<`S;*a$tF3H10uo{JFl~5#6UI(a%sR2 z1*Em2yLujeHZB@2aEP5nEK+s5=F%`xpvST5>-l^~3uJal7U%Qvw;HfhV>n52p0-$c z#v!0YodP@+$z8Q5w!ou)S*(w+zK6yW@$84Zf;nIb$FJ5#(N` z9qgvjRGppYGJRmLXIHWBmg*b{eDu~N#1m4E=s(zvokU4Jk2Dy|Us(nEBhy(HnxDY@ z$E*Hu(H!UyZCnZZaad6dm54vBZA2)ztqcDwY0rk3f;Hgbo8{l=8~I$%4zP|{9Vl( ztSk!eJj1l6g|h!bjptHpIdq9NMW15-GlG31b7Sp&m`_Ql8l>x)BvkABLDv`dhye@? zpRT2hoa;Y4c6I0og?9MeV`|w9*hby`Z$Ti#H zBR<}<PMD{U)q3JD4R+o9teV74zI|pAHD1-WNrti{zYtW?wo7eh zn@JJZI!a0yKrl+~UA6Rx{IaX?nfQJq%IL_MQrvSeXON6P1Ceay}QXcAbSA~D5S#;g-j7Q;bX z3}4F|POBx1iitk5;<;qH2G3NnYuY=+XG9oCsr&{OhfqsRiT0I~9>MDerdfX!s&2Cs zK4UJC%;I#<^xyt&sdtXweeZv3#k^DOy-G3*9-7$+8zom?dSnv!dZe%9ufCA|H228R zBO-fhsu22OfK96LH%JNed<82~cf5iu-74U{#WCV&o1BSU-R-^`QkvStD0jL$5pOhk zHLKw#)^6>a1IQk(o&7Wd+Bx0gO3}>s`NET{Ky_y!5KyrWLy~oHl7d~6l$iJ>P-__| z_&b7uB_SAoj4@Vv3U6AT=rZpu#Lczk^NE~Y3;eulGD3I~xX^v(2%j?bvG+L{&?gKy z{Tr+5`XGQ;FxwA|06@w$3j81&A% zpJ|P`f+C%NzC=zAFGdkL{v2hR>7funm6C=LciFa(*s*!0&9=auVlsf25JM`NUO`k`-KW`2J+0k9d|g&XRThoe90cpsachGbl2V01#=u00V?cn zcb16x-)fvXH_7!3KD9OG>0sVKW@b#PE8Zm+8pUtMx_b+=ga@lKMy%X|KZu=?7VZ!qQE z6?0@Hik&=gP_$<-a5_N5{tpSJzL|hTpbWaG3MAuVeu z?2QjUssoHB2>N(riptF%Rj@v5%<==hu&W%B@4GIQv_L-J2=QFmFD6-iyn}&o{h0FL z_1h-lDvywf*=snoSvF&d*L5OL%usc>%6xx!C8=>%ye6V?aJi6uE-2;Lt*k&Hzslcp?&7U6(8A0CPo`@p?7S46j7DdVcP8%dZcXI*Mj&}p9 zj)&2SQ131iIjHVr3ZxK?Ip;J%OLcAC-M2D(tC+r?;;-zVed3e?r+$ifeP>V4kDvGx z*!hBE2akUJ%=6nbyPfQn9%E&ktj@fO(>znsn z0~LsJc1SWEo>qXoVvCjfY)VU!68zFz1OwzN$@_}=;*4mu{Ht&c=K=Fu$-M%eMwU?f zd82b~uAAqtcl}InrN7VhD%v?b1ij#>9I#JyrZf&aA#p9He>6Jpda?F%+l7XfxRgCH zAtR!p;7JLX;}a3GkCf@H?!zXXk{`c&Lk}9$UV%VyY;)0`fcDlmOPPo<^;~ECiqI-> zWj-S?#sPh|(^-E}5q474fz{f1z89AosohaL??U6|(4xuV*uT3$(B?g;Hh7+@` zJ+m!#dvUgA5Z7$F0tUVP$HweyQ99ox6XenNwOz91(V(##x51QFum>V5j^%mv@Zg)7 zS*%72U_i?FIkicfRT)eE2#eUA3;C5r;*)FSesg+Dizq;00DKr3KLZ?H0Lj=d3_^dN z43D?|PAGS6pP4chu2jEo-6WH_hK3NRaJ@zJY=!Xep25Q`o)26NF2opkWWT3Md0{zg ziJtRwnuO(8SL-FebC#&TK}_FfojEQfT6M-ww-avq+_?v$+Hf=GuAZakc6NugZzu@?~);^!!Qr8NA>el1p{^HsSp%HsgI;hqr7# z&(wAo%iON(Hi@#|i*Xr?PYqQTE8rq8&x@EUyYR-D!XTZa zeftIbX9{jCUS@L5k=070i_Kw^eEx(?cv7`d$B^oWHB0@>d$*Bgx?qJ?nyO1tv(U?g z;mOu!zg}TBD)!(F_3oF5B|G_!ug*K(0Zr^qHf8(oz77pySntPv#9=zC^vpDWYo`PC z@dk)nlmKF$dm;dUl?EWV3WH1bgwyWX(r4ic5YV`_Jn`IuyHG}NaNHVWa6DQ#YCA8w z3gE5B)JxrZE@m;{!)(}@8l0CO!W9=jKL5iVq7`BPWD&wNP~~`4)p^I`@Q{KHxyDG_ z55BOSzuK-?_!{hYGxgMQL{abT_(WxP*p`#3*$mNVE~xYN0j@8nm$OY*ViS(e@mCpj z_R!bvZ9~?a>_dy5yW`%RxfkJdU0ER-c5ImGj0c2N^XHq~CY&ibFJpISBX71V40A92 z>JujMg?tp~GZKDOwt^VdzymJbC$ z8jVkFrRR#Q=oI_)b1U?aagmRbuC|baTht)mh=i1vHk~bTday=|dEv06h{*hx`(6f( z_A^!4(19NoZtClgPFUWs&6V5EKd|lXF6x9RDCyPOcjDqIwZu=EreTZ)36z1-;wm{$ z#vdm&=Z`(2C{7i%T!Ec|FE|#3lTd%m?o`O5b!6;e)*>bxyXLY>2UBXs&}!_H_|k6r z`rV&$AZ!693;AJ-7Zr5ckx`M&C$Y&$f-Wex zJ}a7YK3toHv6>>hI;(!{o(&su&On3vyzxK$Wt-NW0n!RuAr~}H(kxWIBzAxqbtaP@ zm2^;qgbnU9uhm>(%MyxD2QZtp0Gv1l-^@`B0HnGf;+`0{N1EL)J$3 zO!pcxUmOXXP66Uqcgl&E| zO~v)&!26z;*=?~-bDC{)c4i|?I=@0GtnTz>V7TU6r}&7>PDM|aLUY^@4v~|is$Dqg z>i+ZJyFA)MgX~K$Keq+DD<)}^q-s=Ob}m?@N$5Rit@XZE74^tTKl)~4^2Wo>Whg(I zNti^_lQ|h4SGh;(BsSQWxaefOxLY)k@QU@^cHZ4n_BrNA3oPA>C`&_q%jq2mMs|H|XRR=ZC@7|vd;QTO#W%Wis8z;x)(jPs3!l2W|q$Gc&gTC@U>Y>0c zKQ$+4nXF57O&=c{+h;8lueW#9O4oe_>Wsa0!Q+q9)N6#oc_T|_q3rZrhMT%Gk}Rq_R(CImK>y;dhC6s7a`@-tj(FP$GC4EjyYvBy+P5=$lX*! z93-Fg@gNlbh#Onm!J-0EUXo`XjX$I1P!!*d zR-nV}JNlP;jseVhl@%3$dIE&3-J{`yqSZk8^{A+*h=>S)YizoW4wp&;sO@=Ab`Sbh zFLQmb&nLrTg!;?v0Y^tiZFKKg0n!2m1%>{V5OVhIG3U>Qh9a>sd9FNEOF;0J)$gRD zg51$g*2VnQ^#Su&P6mO#^XOp1^UYI1@-Qi}q!qyL}kA25C6P5Z+Y?njpOHHi3SPzzFadZz~ zm56Kg^(zWre&t<>=VjMhRUlgfiNx{$HBuq~k^1AgEiW&prs4xEH(2KySoP0=W2@gt zUR)JBUM;!99N%n|pn}X+-nVpLNq*X@gK&US~yp-q+1dh&!mFpYm|HUR&_r5 zu=$iz^X#oh--y|}4toiM^W#Y&MQhzpy$@cuH+{r?TH|%BVlF#bDU9VdT+7eB$FuUT==yWT%0J#Gun&`Ki*hxn9Dsg&3Yu6&igm zYQ@+6n|Xa^MGtt8T1NiV(Y=tnx1sqMzVAv=1yXdo+l{z@%c}edeT7~_Vh!#H8M62? z7FT$`d8kqt?#%4IY-UELK+H~#X~`YC$P1*Q%)Q3l4?#kZfq|hdnkR2^TR%J?B8iw6 z^D%15a*a6#Ia8zS>L<-6wQBB-$B#8SsB2*kds~0EccjWIHhnrGd3cK~E4GwxRb8kGzSTELG zv=VEZwN4T<(QjT6{u=sllfz#JdVW@vc3jAH5i507%#5t#iz<^>CYs*Y&KeMBK0d;pD9V+gP*8~>7=(95?iwo`V?3HuQuOyg&ik7O^_}Ual214ujtH?C9|dzT!cxG6qkdzH&^80mYH| zlC*&vGt)L>o$HVUDr?tMCIs_aVQtZE0r>%n-IqjT<{v#l^iEu>eyHxV zBmO_`Jlx(qvCMDwO0O#`>v7ZhCR>MSxf|+pM|5_6Zz)tabwv!oyR3 z2YU<7rwyV2!2elWVPngz!tp)z<=r_}bor_VKtv>NZ~c3Z)d6;^C=1hb{rSdJ_-ck! z zUuA+^W_~nw9Z`f3?k`q54vS~<{wd*oReEQk+4n+yc{(VZMnsL;WqPdfAqffN4|L3M znnlQJMTFg5^j1e3)!3s(emQd%kqS=N>C~pLs!tK@7sbf_B#1jt*zvY#yPgyRTUNk7 z`{FpoOp`>S$Jel2L*u89%XvOPI;{TjBS8OtdJ02w3NiQuhlBtm^l19~3-y0_c7WO! zD35Lly5~veF;gxJ8pjbQl8}(lq)QWacL2OPJUl1@8AdGqa>kH8Yy2Go2NWoZJ?OuL zr$5Z){U!{Vz&Q++fY9N+xMk9IBL=-G_EVT1okcNP5b$2u&fL-pP2+=`Nn(6UM9uRe zEF#F9M)zb6{i~PZQhy;1LsoB#ll4I+CMJ(&AH?<9{{wLJ3=I*SYxK0f|McnV_GB2< z4Ir5WIGOxJlGSFc`1;7Ou<5tqz|E7ttjoV15vdvXN1XrrXCn6->;L|hG00)#BQV|1 zGC{GK6?#;%!PmgAT4(;}Pp%?aV0J;v<%?d!oWBoz7VNsyf<1f~#snE4gTGgKZ@!BB z@Xe%}(Yw_!rDw<*E^ng)F(CRxv@CxYx6z?dDdQEM&#R$(68T^L%kG_mV*{j3wZClQ zaHRS89Q}P3fCdH`2&)5Wf3GSz?OC?GjnNNhTr$Hr2a5qzEm&KgRnY$##8&NP#Udv= z6k_p};VD~JL`2Qu)-ECz1UeB4`Ap)|99O&R!}gSIeLpl;WJ7Oo7&(bB{~j3M_A;>7 zRjg*eWBg~1Ws1+iZ1?^DduLf6V;)XQlnF=$^lECd@&V;Jw&-BDOeSHJ8IFzgz(M^$=l-(tz6 zrqGaAu1a!)KG^6`J_NGBkJCgvT|X-fEY8wGB+g6a=#mdlO>@Nt8pPN+?nj<{bSlKu zbhSB^%YEOEm)PcnrSn=_+*KLYFeUu~J9w$|%3@^*4*Zj&UZR1U#t(+&FedQ1F1l~U z^nO^qvm~)zy|aOa#z4ox!sY-4GDn;{!i1i|{}PCN{$4U$xdWaM*E>T_T9t)bn|{wU z=*?Wg^BkRF4tK5_JkVZ~7^KGB;7Q%=PRpeQ93B^nqFjHobtN`$CuM(dP~(++v!AnO z$O_Z+xm(fdM+3cpoI`xh3tjt2xcHl|_Mx@bnnE&>ce!aIx9^Fc7F|LPir=oiSU=*2 zUawa=*H%-a_lpMy4sf%Zuq>&um<>Mahx zJ$)KGKoFyjVSwgpBOaN=ez5OxF$jm}3zsdI%ka}2O{~^m5A~&$&RVCnY)`u0HLnaR zDk;`NTGrFowE6{++V;t$UX#zjx+2_bwMn{nizzC!VNyAufuOt7Zq7F)h>Ovvs1(-E z@^IY~xR|Gvj{Ww@9kL~BX^|=YMo;Ui-841wNV-(i3C?}+;R)M()!s@tT-&vj5z^6d zA=Ws&+uZoTYZepgy)Qdfd51)1l`n*bN;S^XoG|5Uskn=T4y_K+^l+}2K(988PlV5G zO@`hD55tDr2c*NO9_FL%`hAWj>8cVWV#0LKE!aG3oNy zcbyb9-nnyw6{gg0e@~e0zc>&Z5PRXNY;|kL4q7bB%JLubIkLs!K{dx9k@zMCoVfp6 z#HUJDV--;71n#A674kl3w_009H3b-^>H3du z9Chcs=d=_9BC$K*PbNS&#nxdWx&pgrca^db;9hei#vLN3^ zCf@30{Dq|#>@$~HF@Z_=V-}y{2cCj%({FD*thZBCNkgY4{_Jj*do3^LaEbcm48+d} zDBBz^$xb8iDXP?2QGRn=r71p3yWO)4&u;FLe)l~5skZtDZd7>eQLc@2`Vp25s?Xr7G^YJ!sqdxMGB9JgiCj_kh z3H#u1GF=cJrvXZFXF=w?`S-~F%k6EYvAC8t9h56&RdPe_{^+a(2C?||5vq$emDikA zlHrhRTdXI6*LM<|iO2~-3-Or9TZVg8UxbvNZ`_%#^wsj2aJnPl zkOT^<%}6KgXXrCM?hqeK>8Ly0v61DDM&Sw{zkjRv{Q=a!T{GuLALP)p*vN~Pv-P=G z_~8ok1{8AwNufV}EW2^%CdDVtoqq;VMDuvskL`9A>Wfw^Z(La4I=Ub`IES#7ehE=x zq}?Ggb7yChYKlCw46bU93(3*-c*^rHIOLmMXEoCuY^M-}&~p2oF?Y)#Kh&k0W!xN1 z$CFwYk0&~rp;Sdg1d_CAg23+Cd^VLVcLb3{Vmk8vnCHKi3-tGii*LvT@097wgTbpZ zSe8OC6yFAq<5jr zXKr24VY*5TZ)VShxoWP9Nwq(+c%IhzINieYg6Ed>WD0~OkGr)fDzrEHA-CnORHtM{~JBT zeO6U9jJ#Wx2j|>gmoR&NLV6}azj-Zv=?P7vnXSIrT%w9LboQ%SB7_`X5Rze+tL`f* zY9fPV#C*7JzNanMCRF0%+;k!ini8Aiyp6gJP^4G}g5d7F(A~G|k83+E4WKT!(SrxE zov@o*JOZpxnxfX_yVa&>uZ=?$Zj&dcn<(2ZL2cRZQrf*MTu-hEt1r6$^exktLVRBl zhCO$0ysRV)|B*~Ptmad`Rx9@5Cwn8Oa~=75h>WP$-b2rYv8#tD9M5?bZ_XhOeEag6 zkr~{vUWa{Y1gxJMM4~vToem0O^RFNt=gWGD>TC)$Y`heZrmM9*Q=3oFD(*Bk4uxE4 zW90en;@MGoer0rnZsId$GmJ4jAUS=XRQY>)uX9&FmO{PuYLjY2>tATS6t+MAQ*Dc| zxb75}Ifo`zI-tXZ%WS$j3h5A5gP5Gf!Zfv~gRk-!92IB0pwx6k@q67E;P134V3^b4#hY{#^Z}3dB>Hrt#{gr_i?4Ydge! zM{H-=f^!ax@%ho+&JIPI&vJ9@1vLGeV*F8SAHVwG8vJ=L{1DlCPHhYTXxqX?~99sd>Y>#8Dvwo)mfk`o%}pjXZ!>vcbeyOpS@&!uX$Sgd0IIN zd%5AJyQ8Hz{+8;q+Hm!`^iYNPirs3(LOPpFR|jr$`Ds|=-E4T8_wnoPf{UAB3(mpU ziC_GQ{)GQuQ2?-C|NjF1{%G$8Q9iU_ss)Yid=()DG)IhYZEcO_;%>GPI>T2YtaK_i z7;}@Fm}6StlAZEd4{V1$RPxr2L)#xe-v3M=r%y-Ku8c(jg$-u3oMT0w^Cv+n_=}Vi z-NJ_lPol|pf$WH4iBXz{08b6iBLp6Gr z6H(wB6$B1A0=8xT=QG3nga3bCK%mw)2Ea-8|9tpxR`CDx z1}an0ZvJ;$zJixQkjtRbmh0_YF~k-exd$g11?XMX55A>(-4iptk#aqNA=Wq{pAIzi zEw2EsI=x#=2SU0^fFJLB~Y^zJ4Nv1@upfV0&5 z<=-9kE#53eZkO)EngL?(MJGX>1C5%WUZM~ndh?J$(IRyq+%~qcDSbn$Z3Bw| z1QNyxf&8+*D~E}87V4`S^{du$*ekTjD zEOn(RJM+3BLv-qmp5Nud>_M$7zE?5-o^QI4MrgL}T>|-?@_~T9{PlU7`EuLFEuh+J+J)`5w6v5$8z^oq zP~6>VA;sOD;_e=-v;~5@TXAZnR-p9ZB>q1|D7%pGv|4~h2&hiTecI{0UKtiVa6{uW&VE}Wcw1WE z{qR8;%DKy=}5X1Jv#tz(=0f#$=19X+*70!gv{ z=Js*%u>MN((xGHq_H&Ox*CdUf#>1Ki|J)swUUL=adfwU!ifibhyN;4!bx3BiZ##? zUhCRJNbIjHTGMzrwlWZ;l zfL^PEcfG8RxJ(8~pwvhD^z#Q_EYx_U)~F}{-2O@HZTuFlP#lgiL=|G+i7m`|1gE#E zRGj-Ot57ql|L_~Lc#!((pH@Ce=zY2W0dY-@-1S(C>*d_Cp9YIOuz^3cx}Ikwu7jx9 zB*Ouh{=4K3i}i!eEeE)EcH`<5caaX#LDoO;A0ZF)qKrL*&nt{|cxaANHEe&O09x7qjEg zlzv-caQ(J_>l~sCk;J|O-(LW+e=dOQ=t-Rh@7%M#v-ZrI5y4v-~ z^#=!J-w>xJDL<)l*&O+y17rFm2@w$_J{rv0Awss~2kGw?NBr6Y`6GgHS&q|brrwl} zYn8cr-hCk(jnTup)0#CGHdxMUkQc>A5nHrv6Cpj|OWut)c4T-#$ylFtA3Z{ew`2Co zS0X0WtLM{Ov5#XKPQ#&>Zst{)^AY!fyl5hCs_8U*`#Qq81 zXTL*-8d^8OA^@CfZ8bU0caWXhxL8vtlDct`LUFZ|ZkTE+u+2X-Kizpe)3sis15=$U z;NMtj9&rxRe|>?hW63cE63vOCrI{!VtJ5{LnWH|M!9UMgA2$K{=R_*cC4*Q_RBRfi z>8v*hT<6cDvyY=WwG!9XYHCw#7H32Xwg>#LoH^KV-G#ek3Q_zgTQ%n;$a}8nDt-o? zm9H_K?zE*Z54q{E)zq{wy>67ZJ18oRvRO|u1zkY#uG^+cQYt1x~O6g6eJV#2$$$NF+r~H*3iTuJ#ZW$h3V{+41 z0y0WZn?we(d3pF*hb^qIYLBm-4R%;Pn`yg*KxO_ma{kM1fp_hrzka<*eKt0$BOC7D za%1tc$%E(GOLybe*v?(}u-w?Y3#Zh}!?@)Ljn5?Cm4jz?Wz7#gjg5m1+@z@7K)zsu zsGPnA$*_)1+5xng#HY$sgg2xsmZl|+- z{#UEWEBR%qvhHbSrlyN~X(|&hf43>8t})&Rt{6<+V3zz}pKnIMvun21+3hO^ZMC~o zIiIcCx3Xmr`&{b2yvX(NoFmuewZQ~~sff0B%G^t%W|wSFe|i`@+s_JqN_ye_DwVH< zPTA8b>-g7uwYcIr87rKTk;7jZfqhFQ!%(o;-LMru%j>as4z(l2;Dn^5#UC>QSZ7kw z==%mhAR&}1LrVX|H@&=3nYYBa)bCocxj9pcudqQkAYW3I3>Vb1^vWP&B5)(SXJM}@ z1wHqPvU~Hw6focP*Ig(X8&Og+o=#wbLGVar{-=edC9vg0sOCwXm?|ssEUs;<5Vj$hzXeq`@*-$slAG<%(lZa_%~su9~il_`5X-^ zA0-AKe_63^V0b6sf_-ef*ZoeyYqu=-Bn&z=IU!&9TB;k zi<>r1aLOD*pU0v3?=8@?*FnBQfhL^7?7wwa31|3D+Pp5#2JVb@3}=bg#;d zZ*1w#<@?<(`LLgSMhi-j4*-kT3?)fw+T&=mh#G!^9QO7P*Nk2;_=wqhrP97e>;q|h z6c6m|H!-MF__%QH?)-|~d_z%kOiF+ez`XOcR^lVe{eSL$HmNyxu^)wiiSX&;s9qaG z)$yW0-7IU5p8C_GzQ$&(bABa0*xMz9*q2kwQJj$Z!?=KWOy4T$jXOAg*qd2#I<{_8 zflL3Xe_UuPswpyQ_h=jgJx)FQbQ>5qs;FZkc90H-NC|O3EL`G65*o0<{n3IF;cjpO zfVxy9mgBWBi`ckBW%iE4PI3%Dyob^uW@DaN18{;JO`~JG6rLL`-i7rfK0V_DOoqn= zfM>Y@LzHbA--UU&B?+9L>Y6Xc;4ESUJnEAih{hYijQ~-o;6X1K0@$ZTqI`wY!wE(T z604~M^6We7uO)kQ*l)%o$nBvvu`Z1(Ff;Pyc-v1*_AX{K#SZI`c#C|utx#*Wmm-oA zlxr{yaQs>CaO^D2MspY6?4GXV{yRQnk{dV*j+YBw)Z8GUMk)gq{B>Z(# zLmiLoB9D)yx9mX(<=-x)&I(-k{ zr1fyGo40Gl&dhxt&@7ZudT;~VL3GXe(BoxMi17?mTO8oSEeTWR#z42Ri$JT3J;mN> zWBn{j8$GheM@8s^!%DrjBDB1C3*+IGg~4o)w29j zr*w8~nNRyNTBxRq8dz`pW1-q)tAA1;C_Cb$&X7hH`1-CBNBh&bBC(ZdKC-b_wyZ@~ zr|TOn=4x|_e;iU$7=m`-Pnt7R;vIvNVTU5zn zg=X+2C6a-_#{7}|sEHMeX#V~CeQs0<47Os-Wr|q6mZotr8LqbQq%0%7uk!|XGJ7BW!LNqt$pc`vp__jHnGwKJU>dtKe;4UfnWSiG@UM& zXTdgxgkQ?8c{iMz2=}Gx;AK^_$t}oSWdHYQ_gW0mDJI6s$tzwfDb*K@PgkDOW_bHN z7;Fy;MQr&<*Zh9hY^<}uTppf4E)&*e5>zdARaC=}MDq%ZcXD{kF)`kUs%4h5ddA#J z?{f6>DI(M-0G*L6aLaNFbI2uhLX3{3rb<=9G{j;(S+)Wus{;qii3;-dw+Y)?ahWg7 zvX}dTZSS*ocmVP|&g|mJMf;2|GhP8uj1^Hc9r@(TyB{dhD{K2d!mJy{`u1FkLz!dL z`2)GWgwfaMUwmSwzvpzXJzfi!-cfi*3fY;uu;fXR+3DoU@F>TRM4wXnO3ZIj+p>?U zE6cdnDJ*TNoZ_`3hLLVAN`VjNQkSP0?0@r|Fd|jc)9M(L${8MJrz4v`CiXl@r{29OH7|&Gto3?T< z3j>yO6`QLOks;IV>$(}vC@-+}(DsR@YUHf@wiH{@?8z&3ROD4nv~icKiA47)+UAD? zqjX1TjcWZ(&iUgRjv<8|nvR15bMx5?xrMh4aAd`L?GArw`^+~? zInWTaTPI}z&i zfi*WL&lDF6=I7Et@&ZOzzNf@yU2>Hg_?#D0V3;2R$+4)wFoYV!zTI3)MM*_8*oMBb z$PLjstP4F2xdF9~SP}3$roGVoHKE~Sa2)w~OVxyZRfofMkU;m9C5Z?{Se*O%h;HfG zz_&M=VP}XhOe4${>kSl}gDT$1HO5@a(>R?=q4iXn0=!@mBtW%!sk>#^8Nt_qLcHI7 z4KF69G>lR4ppWd~#9<=X1+_aQIeQIL$t%aSxVihsY_s$sIFOyKodC#G)FisY zoq8^0E5HIJCDxdCs4}78>x%@xKQ2HvQAzhQZK(T8x3u1$TLGqyMiU1@&IVCn)EvaR zEm0AhkZRdeG?f?Zh1qt91&(E;_?1p0r0gk@^Q5wT9hX64yW;Hv8$ZQS`*JZjD}caY zfV^?Kc~{8lnwWXWMKcGZc(|97itv7RqD{|F}y}AaZwg*4tDJRmgM$MT`xh-#U|_c9Hqv;ufTa50tAc(d~$FU zXWM``64ArG*GAf+C=8-{Z?FIWOdy%))J*TudArA?Cy4IdtF=?9STNOLY*(H}a!biJ z-vEWNBCwlCLfr2 z3M677di)&1!00n``$BbsI)$;9d`V(kgi+)^;CQ+|!t9o3F_j+H{Wp3Z0}n{lBQ13X z2m$gO4dYiwW$n{-loHaw3&$g4YO|Boo{}Z1%;6_cnREbv zctyWhm{eSlVeVW9t3@b{_*o{$+q8q!QwoUD>1rvFL{$0BO=m~id1f(psR@(NZ}fZ6 z@%1A5yH5O`bSdlh!A<-0WsI;zR9BahCC#hG$k>LP!DT5%WB>7Gf&{x6kOF#To;POF zHJudYO{$1H%yrToBnBJT>X{pq-ECIP8AoZbDkZm%zU0AAe3naKl}R}O1SWsnQE7yU z%=yn4Xd5R;_T)YaxIr4ku65b>d1!A8cmJwq_4BHTdc4?)Mt^_M@?40Chf;09d1}9b z*al5QYrgXB%ocOcE%5t{G0V~Yc*>QlH{q#liOKMt$VaoRgH!nls3P`ubMA8+Uc$DfG8+~Q3zcO1!o^DrNp5iw zM+qk}a-VqK5+1xDGzJ3QcSD=V_G!tc)1#ZDjZp&*e8Gp&efG}eM~lx$lp`%Q2BcIB zLow3OCwt8;E9#+>WhcVYXmkC$VWsc^{+>m!oyD;`X)-GIU#G1By7qQj3I`J?5?Aleo+pQ{_C^iqa5Dy<5Kf= zZ1GQ>FCsnO@7yga6zIpz4!rk{qd^Ide*>#L^?u#=`gvVmPmSg$WO26(1q5KvVhCxj zQbJ*-*j2IW;g8~^{n9&dsauoJ`?#A~FHW5o^G8eryGMA$FH9=poearkF)jf&SpFJf z{XeK?4ACQlV0Os1-iGa_O5L{Bd)8Nbc)`k@9y`eifJ(3Mf*<%1w{yUd!Cw3F+2UVi z$7M8}EZy;ClGVh=k4uz08_mUfZnuFoITei=1=N@h$X ztzy~0muK4R4 zdJ#jI{vop>Or72}ASxXrJA%zjcYY83$G^ju+ zxzJQuteR8=P?_j&l3Gn3nI>fljn7g`gG+fSQoUC2St&65)NXBcVw^7bbKusvELS*& z0MD-Tu{d|$sW)!EWu=tskB#qixVU)a*&W>Y1FJ$ZKJga=Q~Ey21oa3Eh^-hm?_l=S zu(uVAGE8g%wb(FlfwTx-v$k|6A~uk8A?whVIP}K0+%Q%}%x-ybfaG!&=L^(ba>3aq zdTJ?t$0H|pg4Nulg&_VxLyCyMyd6?Kzl9@+`~zZtKg6ID_VzcB`Aolfcl{FLDSelo zay#N(=t5O?dJR+Eg7Vz#wv6b)?w^S9NXuD8?Bab)a1xaR5=AWEfWGs;$~OH&Q}3Jf z|9hgVHB4LoXFumbO7jT?$woKW7s34wtOP_j9VP?DgOJL6N z81Kf&lFJp(n6Vu%l#^XE)gerKKm{v4>`G>aK2Uy@z_onJaEB;CM&(*dr{zQ1mc@L{ zGzRL__ssnCw#{esukXhH19TRKiKE&r(5B?1kV20|vYX&Hn}G{UPsy0|*AYMAm%Lho7KGhk4qhU(08->ZTJdos#P@bWyNy4_E_DZ%i($+>cz8u%V#BKWVyU@v}# zgzQW1X^oH>Hw0le+h3e;J^EcQtvsIu-nl-G_W>9wwB61_Ss;MiJ?aF?3=jLF+&S)4 zLwC#2xMUFqtfT{XSqFSv6$Di!sh4@H2{ z=%-GTO%vk#wm(3I0<65;`y^%3euB?riB(nnhH}gr8p(!!8BVW7LuM*Re17qX_YkQd z0k#fZc&&0f%sz~z!dy7yY4A^4R-Q@sP?-1?3)zKb!MQaTlr(sLt?&%dtVb@rWScRf zz4Y)7$6X0HnmSO=h2>cC8pmMy%hR$J+lBJX|ymjY)eXd;UL_r*nSIv$A z*wU>p7WK=hH{5rw$6|J1B_wp2$!$-~?``v>jkA=i-`!3+1X9Iwv8qKRf>wp75^$=l z8-UewueZKeb_j4#=4mtJ(yS{m-=U6Aq3cC4k`eGu8}+KnI|!&ag7Tt zyGS=$)caHlA81fi@C8^ zoVfg?w(CR(K_W~T>NLP$wH{NWu>+)V{Jl?|D8uP(Kj((KHCQMyU3Exhh6U=YwMcPz zGg(O2s?`wS?q9U71iq}`HHdxJ>@eRA-aGEce%_aFO5Cgtm|K1~VVxl|;GHX%x0eHM z%6S!WWS^zAdh~tjJuoXZWo~oqizpS&uNS~C-Mgu*U34y zAVX5E)W?Qz3F8Nc8Is1k!Bn>ajP13Ml^|t7J;jKq=o5H{%<(kE>s*@3NfM zQ1=cxA||9ouL4t!fYnAa9II(!BMd#Q$4B-kIjJYEI(sgB*(L!ecxiXYD5A6bfi|e$ z&}(;Ijg+2$oq(YU4Y9>+9kv3y2-$VN3Dt^k+D_u<=OmG)J(H#cC!|pJuaRCMU!t#E z`H|3Qm#0<4B<1?ej+k^`>qgmju1!~JeN#-falO=aF3^fKcb8I*;Hef4Zbp~Zp|_Eg zdW_*_yj9az{qdtix|~w3w#Gul(G*qB710{*?{@xR9FbFYRf-oc-s~M-Dc|8iq3E06 z7P_LR$=t10BbCkSF|bQ{K~bGu0WL}*I!oS?#~rFx^YED*DafzS)txhmYpz$pqq6jd-bw-6(O{&XQu5rr2R4 z)db?SXEDfx8JKP4;x*Pu?-7yXqH}iw=%-@jVg&f0jP=6h<~>TWxskzGxO;D5l2d9L3p1K5}CAUh}&=X3du+JNt93sD0735&_SC*RFZ*bT6P-8QkUrR0?hh4@&?DPaXf2^`D_5AVV3}|wjayB z_8(p|%^!U2Lec-|J{HaGf>?lr`NNL|f24dR6-s_kz0*gcoLUTEv~;e@lu51eLeEKG z+b==@U@g-pfSlc#hX+^QinB`y@g`AdZJw7OdbyyCYC0K=MY>P%nx%*}!lFuJdq(-? z3GLLL1j>F}?kXj*evCBXv=nX}XC4w*ksy^Cuh&J?*4Z7ROZL0;lQh44o`=0C?9W+l zAs86MDIRY6=oS^B$>0E+eS?L?LOMM&;tgzutKR0v?0m$@Pt0j#eVzDhXAWQU*^`{g z(PjJH!e^0DMLj9&?z}@a0oYqUZ|4M+&OhW+I|Lf-FXZrv0<#FWCeG%syf_(Qy496x z<7`1!ePX6Gdprz7sy>TWk)d$4AWZ%-d&OB!c$vnjmAQAjmkj*4m36z{i1 z;2TE+xjEqg)F>3~GNNi!cF}CiEn4E0kFI~<>-zzO5|PyLi47l|r|dpw(6C@hh@AQ9 zO`>e}5xlpPA~Pa$Rc5DEeS^oibircc>;;;%e>-ZT6VIzu%F`@u?Scg=Hb6vP^Wq`l zkA>TeHyCS`36`hpy!m4~rv4;Z8Z4r0frQ!Xie?$gS2pi5JE`7P)$x^<41aVNw2w1( z<0njwmm+bY_}WI^TVmZeOe8lV{gx$^DhZL>mC0towLQ1XdkcSz_`ev5T(AngLZ5+o zjE0rAiXI;ucMR^Va2s?5l(|ktexeDW*L79G$Y*u3chGs}y=`h%?Vew6KIGSx2meJv<|!x>ZiE*VhGXbLTL!(#~LNQf)9n3B%xE8g=QDKEE~ybyfNzM9%NL2e5o#m`U16~D9pc`Ma$bK`0imaqKGpQuKJ zUjR#H{+YDSSa!$R5zBb>ETCc-5|IjiM?>O>8X-m~to{2M$k7IKwo*jwidqQ?Eb;G1 zN4poE{6Q4@8~K)k=2%B4cQf;=_Agb>Bw+_V=|8nIhsDSz3AHf>F8FOk`VNf>7#bFv1?u>TsytFW~bJ6W>q~LN#uNztHEnHoZ0-cBRkVLmw%oy+*1&PeU;c^ zgs?$8jTkRg-Fnqy*xQ+iKm2dSat^YVhP*DD)(i_)z z^e$H^FXPP&!;BYp?7VrBH9o~EYK&QO(KEoN!uL+%4ZKNzS+U|>^bgqD@+GhKf2FKm zZsci?@bN)<3y-rd>|(;<@fJ4)v&g2w((j5`lV{j~e~y4> zqc4)>N0r>gku3Y{>v6@eHBgW+Y?_{Px26d}M_x)BTJ~7=!iAF@%NHXG-ooR@Zfa;x zk`WVn6<5Inqj{7jkJ5M4>t+O9zX8Th;x$4(?bM*Gv@OBK;|MiG*Rr$`4K#4a$sfkO zFbSpKLK$fMI;<+>leN7o1M1=2Ge-;xEI)in@Ve9m>-GevJP7OezV^-!&%N8ZD?#{j zUDw$@_`Ct&+oRmS2E{>-TK&2P^MF!Ut?7sAEKCSu&@+8JeKDD`%~Gf7 zQ^`M$9bngqZ{*<8BB-McO_{tD$?O^W4H##kI;BqWXrga&d!7cYp zo!Sl`B)R8dPYr0%Rr9uTes)3OB=SZ+0L)b+{!}>{9D4~u>e8-pcc)L7YmX9r@{E}5 zZD=RL-4izRcEIi(GYVog#xW*+TC3~*x@YrltOpXu`uUFA`y#^132uPEYmQs(vVzyJR$yZ*QM zVYFi+J)-tYfJaluXL@S>J)%ptk_p}ylc0*BF#kr@ErhpKrv8uS_rNJU`QXRGi9zGT z?Y9KCW1lxh#A*-;|(W7xMg(3aR_t1YD{RG0qPfh)qpD;FA|1^6Jxz_?Ws8BH_N!Gj_9b;dp){ z&`>w^BW0sDXyA(X-nl7t)$|tFcJH#559V7aQ(C{Vb;9F6OqkKLva((#s5#6iA3K`; z41*kLPF(!B+VVqgb|~6rxAffQZr0N*yplM4)hyHO<2@eNyzj8fdDK{LQ}1~416DPc zf%~!92Pa9oW@y@DtIi3Dg$ zq@Ag=c7^nJtLDgq5U4;_eb?q&WS2vWfZ=pEZ+B(YtEyu(v__-V9jB_vC~{DJwVo!T zy9PS?GE;)@mb&4RxLfKU>6USk2M4-a{EZMmO}ff0K`kOHh{5kf&uo|R^mr>Ld#%6- zFI!9zM2{a2R9LHRgw1XNtS?3}t_ZRwd~a}iPU)cqXUi7GYsoKXr54Q)9< zu6W?d!AcuKv-LD9?TE*KFWf?Yb7&-DYTOZR4CT_7=A$Sx)fn}ld?4_e)sMfo+vW_wO za$iTsb{IbvIwhsSMo};ri~)1e&_UU0C=T6VSI?4SA+Bc{=EahM0+He6iOVK@D_|Bo zXwdDZbJ9wD9tQxCB_Ey8gX>V%bu4X1T=eg*{_t+)z`K3J=ce_Rl=T1OJq6`%y?Rm7 zN$pZFuXia7{?)XjQ>Q48y+-Lb85;O;o7-X=={{u) znhhz_3^}2_&XQwO_hoeSEHvs>jjbfJeu9&!%Nqcrvjqo-wes-8<*oraF1G^4JM z3UhUf#UsUoo0-@UyT0^{?T&?eLnd7A_r-y0sSbnk{*GBQP0K;0;5>nbeOz@O_g`<6GN$k-o!^2Px7Dr?OR<>>Tv_4 zI1}AN&*0CZn*h&)UvlTHBy46`Z~_2E!k$FVu!%3zMlkO-u{tGtibcUWZajET56IjT zmnqc_#Id#G&iLNS*(8(H0hsmQ+ij3-fA{qXx#QtIzLoMOP730hI`p!Wm~iju8FzXz zonwm-DSi%~{>J^VmG+1aa6K{$X8ww^$LC8_zniP25so&7X#X4dHAQvRT4+md1lXY6 z2LWQTt!f7o@FK45v(8O^t3HG4u{*s3p~TqWsN^)0*uF{J2uC)A8A7`@K~DO0&*M-o zsJx9I7?OA=!=0?u`naW$CoT5O;n@^oWED8qTMGmB2Tq0_8XlBA>gc)s5*!P3|AVfrpUkk#-g{W zOYF{?GzYYtjZrs=SABGm@Ly|RxDiL@Sv0HX-ywh<4KG4$0*yRy4PvWdzX9ZoIes4- zh-g?cv+CHH9Q0blT&F&TVBqVJf>+M9_9MWEfckW#=GyGTR4Rm0^*cJ9%<&^>_mz%u zXdr+HpSsM8cr?kGRgS`bdGivkCDGwKd8)qrK~61+EwaZsT)NIbqtS!?gA{F_`OikB zJ-xP>gxCa1ax^4Fq>9l=lSKD2yt2!XJA8-4yBIJxFb9Ha%uJwVW6JI3(x9`E9BCuK zQSOFvwH7oq)d!Pi!2b(o%t$8Fj-6_LIOrFtT^8&Yawvl?+SjfEmSM$SZc+P+l1b204kNq3-Wz;fDo25LVDlDS7k zGIuSJHZB%$`2NT8Qstn@Esr@i`pX|LqmL9ToL}3_$Bd*rW2M5r*BaKey^ZBmXYyTOi;KhvO#pd{6A=pQFbto8*&G=~oi<{~l! zh=99=xZ2B7HNqI#o`W4tWGh4Vs++?7`=nI`4Yaq7*g=f1+%?#h!!+`)q%aU4ij`O& z`Y5WG*=kWq0g5!Ges6GbBT8^YHA=cG+;VnR3wg8N^$8@L0CzRIEH^?Z9E`-spFfgM zb)<`_$50#{w-;vaW+fFaRIob@6jqRQQ&e1GF-sd8H=?bHN*ypB`Qw5;Xeb`X&XGk^ z)5XP45;x>zL07uBt|ITPud{!*zT_ayPNV%wK^kr(C{n8s7h*c~jXhn(eY-FAKXaV& zF#v0)yB-|c9!GY-i)`~OVUDryqR{ER(yR7~5y^owgrQPiAnNkl8jCA@{>K?(9U9z4)TUP^_b#G9%WQvr-v)l*F8C+dpR12>;ByviO) z$hHS9v({!7tFIEA?`2FHvf+n>LTPl%uq|P}B5A6pr5;F7^~9vkbq@Ch-nLHR#;^3x zVr=qvrj%%8FM*|MM4!G6#0@HPq?Bx4V!-&1m)Ta0ux>v81I)U912f1+v_~xx-!~mK zpRg*y(;R@v&Mhys%&oK#{j$EH65I+Tf0i4PF*JJNP-{bR^Gf!q%I=_Ur1-*H2&G6r?Xm^&xk9c7jWY9m*EyiFMo1@1Pa$-TOyUmA9rXZla46JM1j$+wIlXCMUpB#1UKVz6>peCKqo{E?l~D{ zADlcf98yF4C@6$S(t8uW!~4F&`DYG*-@Re=JjDgiSwnFFdwW}gqzjtS-V${#1|hBp z!<>7#v>1b!5rzYsdKRW;6{4wy%0s`qvn6Q4zQ@FZWN`5V-ub>vpDn2RBv^zU9&@m& zMCHi*I`ycI(xZdq1#%8wbqP+BmZI{Dq*!vXmdgTa_`0yC|L#12)Rr?E2}f_pm)3Xz zP7d34Rqo7iN5k`BJr{k7SIN))bA^_|{Dnxuf*UtqdVeprIXvGkk?scAMV|f`nRS)z zwOSS#&t7Oue3;7g&yY!t^6QZ4n+%mbr?94FCsT2;n;yji-Y=6Wo}0_~icrcT3O0 zgy}=vjYb{bO1obQvvy=(Y*HgOcMU|`i35oB$M}RVwMN|`%(i-li=Lvp{hr9#M^pXn z_`0Z;I+1T~wu}5`CA~P78`ArFt|P*#>=O_>tu=k*{;*|>?#%TRDt{ITbtMv-QPW*ZUuB&rh*Ol41geI&KV&(kX5mp zs0Lku&xtErg}$K>)Y>%Bi}W8et7kz7oAn((1v^{Gtu#vlWv?Z>>flQUcEWruYQECk zQc4;VS$*FA8--4rGw@_n+#d?Kiqzl-x-3CiVT3!>UsEP(mJ78?b@lm;D5plA0^-gZYY(>2iQOe`^Qw|ZyR8iz|mPdwRZZGj1veqgG-u~n5y4*Tqi zT%9!OEXPps$oD|0SfkKkU8P{?U`U-{a4FvRf7xS!1*I>XAo>nawaZ&xf#yVR(hN(E zN)_(UB((jxkN<8*W!C=#>nnH#z$*%6aNAvBp3oCGOQvBUCvAIgnA_tGDmsp_-JEUx z*_cBFBjF?5yctcWuuQQEq*I`Xd8YfU%c*VyD_00eJ{f90>|6ee+QMWsheP2~g2`5t zfGg42TjKI-y+p!)?}LT(KW$H#gQ59VzlBxisMU_=gX?%Jmr&a_lRtUR7&XAm3*qBr zeX=Ny>?}t@Huf(Sb#R^bXWlDmN}`2WIGfTpN8r^KQ?4-uU2>N9LfajOVP;iu#ON{C z|HOL0X?E|rbD!79Jf&>rOoCK2zce#Fz_xyf12ilJ>{PF^?z*xb_58sJG9Q`re%H~Xy6Jrd!!g-%s8~t>^^~6flq+4%B zJl|reJRtZiKve)SaD>+_ydq2-xk&7T?}D%7EPnJE&l_cVPhrBtBohVjakXN{!7YC}gZj$_0h=`m!5;TRM`9WK^|q)T zEj)b(bK?q9hv;+1Rv8t8s4>rOzig64amC-UViLkoPac|u!>DWtId8zVE7;KJs_86C z0PxxiC{9-#8u_w838A7rc1tV1%T&ve`}vW-X6_NI7^E-G z{yueWc9NYf0cO^#HRs(=XjBJCS&!dUNYA}x3Pow?pH65ko-JPb8vHHw{h=CMwk0vr z5c;V|zejVUKREvMYv8qR@Cl5<+);*MTM+HsdYF-S0mrJYuORd)m3+z)T zvssu0i{d1R`1VYf6|V4B7W%O6yzqY^jDi14VXW`v(%*WPeXUT(U`N61PuzPH3+l)G zp<*ZV@}^(6a6NnGBC5ax5@L3*7bw*8MU|=>`G8R%L&q^t&}T~F`w8Ok@ZSRcU+w7n zhu+Qq%T)ei-mcSz^7w(Y#HmL6d-{Q6Mp_=^^+@%yJQw@U#? zi2VMCw#QEytPiw#^lAt!2hRM{#@kegJjVBtG#lDPcqhfaiIYhs-Y$tDhXUpB_4L1? zps4+9d(O`k4kL-nx|mvzoZde3C=)ccZ)$|ycrEPcz}y%9Qq4ABum8!0+`rN9it#r0 zKM{{f_Cv`gil`}<8}7UQuZ1#|z1P!HXWVz_jYlD~AErKK9fx!qf@_2MF@|$x_0=xZp!p8q zBSF~Drw7ol!uJ#I5s%iA2th543)@=Mhj$A4ZyGTs_k>zo0I*c)I+q5-ym+leH;KQG z{OkKK>i*x_TWiY@}v(CmN`)~fp~V0pN;LP#g(Jw@TU8UV6@C8 zt+xt_Q*slq+izh!lIl~wAR*``$am3w=%ZR>TsdVZC`W>~|1e>nUGt8mJ) zM!bj71Fuy3T_e+S97x(7)Z^7BBFHn}0JZe8qA2z*SB6qE9C!T;pS75?;DGHorJ^v* z7F%zRtV1gIcw5@%8-Dg9YeFm=?%7C!SW4S{@tW> zh)%iOZd7TU4&$&;ewF{yBAy9Mpwg|h8lGo!q@qIhVAAYQd-&|lX>6RFld~bh;I|px z<2_Do56pVkf@|L_z~SP*>X6wcE5ct|Fa-4+G%y$nsm#^577V_|7;Wbg-r2cXxn;StFbQJH|P z(%BMPlw=ooW@c0}4d^#fMvu5Cznfcwj0BAx?u*g>ouflZ2b7==xJs+HLjQd736aAS zZ$@?}4i@`JK3_s66 zUyT{+UpG3~!3hCJ<|h^2%d$gG^RP(QjPc9)l_zP!bq7XLGlH*OITs_UChr)idPGRG zsr|9rN0GOpMUA5azZG6(V>b|sZ@5jEh5gdcuh6?gfv%pu_NIGvZQ4(3aco1C*;i*( z%JpDU=y%p;abb7jb1PuwBVtvUke7;z=&15(oF}RmnWvLI=py7zB(z?(HbTao=)v8$ z4D?46jhb(^?V%?3a?){e5+#OTuIhN-j#`31FDB)=ckdQS=R9UWJf{{SjkTj!+8SZ& zRo>`|(6cI6=KcaaxzQ;!9>mHCzyb8 z%n>ZjXN=!EdsqM~4cdzNA;vb@8-~r!hrs2FF8ic)(yr8lJVd6H3f4Ni~@6 z@w{~g1Kje^Muh^MRiEJ|4W#PmsW~NTpI*slr@uIHDwLj`@@NjW7Lg#(243+sSRnuu zWjDv6reK0GXBPx$7$eTrjDf@c#eVtiBkDK^Ygs>Aj_OpnXEY5f+r8%XCK;mOf>z~9 zzMcLU0C89s2X-Cne%UKPZ=5Pm3Bv@o z7~Bw~An2drMw+qO?xA1+;WfCVrYFs?wmE=oZfeSSg@A{T7etg~&b%?g)!c|8@A%Wi zrhY+(E>S(FP!{BHjBI>qoBJ5%!Dh+3++>&$HGG_RpU;;*9X!_6`638-L1-{da=df} z1ePZaS*B9ks9aN(1~+FieZh$p>ACi~wa2U;b{IYu6j7$QVyuHS#R_us94>8cT5w2{ zX@vA^Llwfjmp$Dww;GxZZ2GG3Q5H;XzlN*?Yc5w!h6K7}jc255(wzR76~(KrQT%?@ zWO$T#v-?xzu|+m4KjMNwefuyZ1+!1`CrnDJQE=N`Sy2;Jag4lH(^!MWF>_f@x0WoT zr!(!Ku3m#ySpcgphIIX)Wp7e#b#d~ic5qCY*hFZxCrr(D5fVs{-tu0y|Wgk~C;pfLhL( z*}magEV=8zDun3d$I}4tunVSns<{8^wxa2m7T}PfL{Xm;xS8Y?>&pY!G=!>J`K~ zLdaO@-N+PDZNUrAa>Z>^oDb<^Y0@;@#0>GmFKKX=jMUq;a9YtjJpLq5nNv%-cw_qn z-a&Fpc%;SIq z$z8V_V(S>vYh8-iz$_uSAOidD)At;;Gg(DomN6@^Zg&AlXj4dyWwU124u8_^y3;MF zvBiDKq8;O{@==jBfzOPSLCxYa(1Ia}l6_{AzdpIcMS_&Q-c>Tq_7~{{8IAZpD>|vU zQ|^1Xd)+9oOyzQZM2bQelc})kRnGQF9skn=XG%ghAt3O=byFm<-p_+ltuR}oFCQPE z+aRjekhn+s;Gpr%{O`h!hKAvZcA`Kuy+l>#BHfE*^j2gOo1dxb>cw^3c?Zhf6;I6{ z1llugIP=RaGy&H=Yi$7wDNx2Hc7wOuLyM> z6jiWR4Lh6|CDu}}fB{1fVVh-Ycf}XV`AfRJ*0m=WhN~hpWK6Z)8A3wrNH|U8Oa4nF1Lhol| zv70wDqIj)Ph7!zjJ=EHHg(gFa35e*{M0_U56yKhkgD9F zu7nz|P~8NwI8WIuK0JHMx8K&=s~NGGs9A>aVt*uibh-Eu}P2 z+*;Bi#oeJT!QEYoyE_5eQXqJ74+RPoclRPG8Z5Y52<{T>o_^)M_s9DOylZ8_I*>DG z&dlt+XZC*fv*Xi$hwh#^1H!6prxD3fn9QUcP^Xd0pqu{0g*(7m$UcL@F#ApfW9|h)GllM`)V8{sRQjN#? zd4m?bnI2lL(16mml7-C`>msIUMF-OI^l5TvqD@cD`5L<8M&XCj!UsR*x~=j(o7P=f zisQrHN(l?CjrORaXz~|K-m$RxYXg&%v^tBlWG21LcK&kwTTl$4Z?dGG<(Fssnwd1J z7*%3Y32*D6s+B7YTbi*xmf-5^fvY-W8a4j4d(mU`br>q~D2A9#sDMpMRuBtt+1i)6 zWSE1xD2^TXHz^Up_PP0p9YLKGT}!K|7dcc})$wB;y$>tO7gQhI5yUzAFOOFB>ZnMt zc-Sp(-M;CH*iKZ>>*47w{Xd(1X$L(3aS}I(g*6t}u({?%v)I>8*aM_Cafaf69$eZk z&3trZ;ryp>&59w9Fitmxy(Vu?qL>S>Ns71=o~E7{bPT;qcd`!I*XYV`LTyYcr>c{M z6oEifitmK-#9QIg3I4}DzdI+S^;RzrEpyN?c;!=|X@8zrmh@gt|I}nG3;yK{tsCfo zWr5)fyk8MYw4fy^LhgsKpRvHZnLn;wQ>99-C{N{FT4NI2IC`!DMg3OzvU?U|leq`n zQ}%x9B80Vfpy2JThugY2R|g(!OeM+sYBVp+mbvC!o*w)Crz+KB%>z_I&a&y+Hz^(H z?v~|+CQ6rpvv&C8jyoCrzg`ffJW)0m{$;FDy9Yg?z)rZBj0^C zK7ph8tgX?93z=~?lUCVs+Y)^By^IsNSNA~Cj`r4@=7+zL;6X9aLfNRff#SjwU~;N% z+BT-T@rHmPLg-~2-_ctCm~Xu3(vg}-#W$A+w}Mn|ii1t|ifQh6(&Hz2jKfH%6 zQanK(V&6I1&wgX|9w?1e!pM13=ddf<+qNfiraX*gimfAkdK*osh`dY{c@bhcw8PH^ zy8864vOA4eF8ZF;zWu=6SYOxI5FbPZxS!Ba5kBr-J;h9pNHL!nS?*_t172 ztOeji+qk@wUg@fht2KD1!V=l&*Yx7z_X>2;iE^=;uIEog+7`1Ww(rkT0n;7JU;jCl z>^q#=ykCR?amL-S6Uk_XTWRfW<8byCNsU3pZ@a~stg*6C(M=JiLn33M4+6{S|A-do zENh!%TJN5HQZ8dNZesi8DVioPGjC9h}g*TB+bl9i z=>E(8@pm*A&4SPV->jzhd29>+8RdWdO8@;o7WeP9>(l>H1%EI9@7eJ0)t&#n`OcmH z9kBmhB>yWI|9{G0Uon#wJ*3J|C@0*t6_e5wIoi=S$(}iuUL5Ab zToh19C%zCf$0CiD7+Tq=-sMj2AD`#_{Vp0i_kBt$y*%f?SO8OwofD>_9rq>oXISR8 z)~Rdh#wpWjlSW4yIzQ%1dHrx-M^t^l!&lxR0q|3!Pup&d1J*pr0~%ILDZC9|$5vlg z_Lx@ahl@ll-)(cZ=I7yo6$Uj`y)J)Zw-i1F^ujQ;XV+c%&P_g`CnIu1+*0IeV=vD8 zW9L|8WXJZ!CjxK9Rkh_!!qHW3cD1q(_M@`r^pmcTs6QQZERWk18bmStoTN9x#U0}na|dDA%65A3@#^5{ ziBls8@$3R^%BRES+3Rs4!BJ=(ejumH>!1wrndE1MQk*~Tk!VdzyJ9KXb?3iXG6-jh zV0+HW)X&={`jrT0t{*?z(fV|FRF5_`iLYr!{N6c2nnmsbt74$XwYAG<%D9I5q!Cz> z5Rje=H|G%bx=3gK>~6twF73FkVgA^kld^^AnZc8{jEbsGF?%}n$EudSjJrnCcNXhM z$H%riOpm)~QFzcnP4UZA&I43Kp!clmLhwf%&M((?*WcRtx-&@9Zy8=<-Q_;*TE!z_r>e)EEbgx} zE+%AXH<2QHo_g14pVtjszxkTl9R2TKWwQlMJ^G9Wx8frL3HDjzCSdLd8(Flm`RVfq zRBvK#;b$s$u5g?*7?DT%SpTm>bUk!UU!wAe_i~Ig>cu6dJNEzNmv7VvhnVm#C%wM? z^~@q22J2_0ta`EY3Ei~sv`GENS2VeO)D7PF@A1KTc7$7IR}~zcEDK+`^eOfk$Q3r< zV!S^%!76u?G)q$aa)En7@KkpoqX5UEh&Hyz)LlX3*TuU+QS0$jg(@d5e<7DyTaKN^ z7sD_q9G?N;8&wuY+h>Qe5&dEd`Ed~n@bZ}=^CL!ZbZB;|H{hp@L@-Ph0bi^{(eek+ zCqEOlyi%Rg)nu*PZocdX9$sik?R{x|TrN@QB4!Re?_`di`ApK$NU>w!O>eNT2Jk15 z8?!mERmDM|BFi(%P3D&Qo%p-xELlx|%7Qlu4#``4w^<|+(<&^I~Eq3xxi%J`~B&qw_XKpmAHm9kIRsPI8f*vg(2%D?Bh~ zA{1fPJdxZFG#~1)ooZP#Tx05=fz!gTX1%LIeEm9KgT=P&;wIEV#W@x91P=%a`TZL%Eg(GagT4floEP~Nkb zI2Q%J8^&uZFI8fLf#F7=Dn<;0eM)KpWc$Ko%G)ltWSC9Amc%Xyu5 zhg~qq^0VE)O8al84xNxWh0(#3Iq6et^^4?)ozm$db5-`x2Fa57qOki5aVwt_u%A}z zOu18w5v`LO3DX^aR%Z|=ET%QM6laf!cWoe;LP=nOSuF-k`%WpnDXKci%|PI`DjKQ- z(T<*?e%qHUrL_J@O+U^;g>#pY&BCPiOVeq`#0tW*L0gye4kpb$a=F5%i*qTgIy01H zAuT4H$#M$K#(Rp>XGy@kU!2r;=Pgc$UZp;=2sPN`PA+Q6;HHuBwO-(BsMaL3es_g| zp*Pwj@`PPyHB||x>H#C*YRM5#r-O5Os$uJVboRj9pYc=|SaBS>cBRw7^Unsa4I1-m zJ+AJ3PVaaUc_s$bvcD%e9grN&co5NC(Q}zq+h4>JVv=gAq}w#%$}Qs2vl3_9b;o&( z`0BMbVKS~M&H!iH`Ui)t*HJgJGbG2yVtIZ1MwKalhqM?N(uK#I!=Yz(mZILk5MWLo z#>1*MV0BhCHPThA>;xdI{EUE>?EBvMX1>*4rzK|D3*i?Am1omM>%v&j0FYwd^y#BP zX+=rZB~Cl%;JhyoKC$&dVJ_(Pit?++e$%zA#0=Q-q@JBj&zZRRa|yg6e<#f-*?kzQ zE6spwUZ5KV)|pM~EfUFy@N-%^_e(|D0xy0#Az|*vNW|VK#Ch1z?2!RPU#3r~&wR%_mk4jv&@$f;aH{_|5EORsiK4Qqw)|B(o#`FERkxzVM##q^|@0t+xT<*x&1wz;Gj~)08 zHdvXN>T>;)9oc9U{<+f8IUcO*1UW5l>@yn`TQGsv#_FXosQ|GO-1-vi}sf<7A}1qJm|FCbw<#ri|{8O%6JspU|X z1a82<3MkKnd3+cw9Ug^ge5QU~{AJ+6M&}do(3`E1jk_AU%GY0V^z1SEA)sjS7vCa? z&TiE78MhdZ&^gN!L7g=S2_&Kbo~1rP%iGW#(&_mrdkRKLqL0-z zJRaWm>T*(AJxQT*<%{H_prbQJ@@(M;wi1kX(`qs$FhJ+R7yWB1Er!PBtHupq@ zUMMW$6d*aGrhVrx>Rw+}n9yj+u+AqEsa{e=^0?uCSZibgnNPOD_zHoHrk5BbU(tvH z#2R(ez~%QDCUsMH=n*0QTgP945RcH%jLff)t>EeQ79-F{9rLCky3mjLflMlki3RaY zaC8WaGWFe_LsSVriF(k%(^^UKNLVZ)HlBRqaCb;*nKN+(CbkPCMG+~BEIU#-(eJUA z5I?PV&<}?(?OwFX%92N3={`nxa@VfFiq6Ew!44F2)4xKGn`&DdMiboK#?k55l~t3Y zLmTYD*%=dpa92;0*wmAmoHNRR_SZwd~%%LHHqu-wga3yHJS(Sr61Gcr&6|4 z%TodjvikE%UeqnTuQ_QH_7g|v#yJY*mnUgS)z-HfNK#Wqj_hu0UtfPv?Ej6Uzea6( z*ce8B7xBJkNT|b#;#i0LaD%W){{t&=Dxb1~(gQ0c7V17&qNHr_;E5q39{e2fsbY1-kIG7hKjpy=cIKj-cgPWDCdJTlO3(UDHMYl zPt__Z97<=%34@t@RqB<1eXGpuUnma&L(8A{iDR7QZ?&6g#NJvR{Q1TEF^nOnUC!;u z>D!lqsXv=0nMX8*7+WGlXZlJ1S4~szn$~D%sXZ2TIn;$iVbtSClNXI8=7Tg5ZUTNSLNL|X*1{J`*n@dEptOP$EGIy2K+pm?fe2I6i!mu zM~B|K1?R2Emw@UsHcFK6fAa9yH?zS<4T0)@Jv_A796fu*AOYE4we`gzQj~UkoY1TO z=~q7xh^*!EE*taIUrUGe>;>g2a?%*n+Tc50x|6n&c!tHqy90-%* z<7qj!VE8T6*I9yLkCfiSXp>LjYQ=WO>D0_U0{mB zKp+=ZHMoL)G9Mt7BItPLtgY**F2lqGKlu&GIK4?$XGmwC!vJkBBeF9WDIE@+K&VQ! z)V+0c)Qc3PP0H2fqr9NtZ z8IzyW3NS->F0=zm^4vea$l|`b@*n2SQMGNOAI3}lBZR)@Fn*Cjt#hPRS61Gu%y?(C zF0!-bq>qTkxK}fWh+Saehr{`k(%N9@Ji2wTtZXX_Vd3=9y6N%7qjo2`>B%Vgnz80_ zwunobdzgOYa7JhsaxV4c^aZHALzU1*+t6EauPx@RwOlUW+NI~B?E@V43)vd|RaiHf zPYUveQnizXf8WmP;zTmcduy!!7WK1I_Yd<;#;-ic7YBkaZVUWMhn{d4AG?wWgTpUM z+=yivlV>d)EQI6K;&~@aIZFH->_b{xve?{{y4395N(Ps74q+qS@y9-_8d<>=mtdhpC=-vSFeev2>XV}mI zG$48|vwqTt1~k0rxrV79M3d`09SmHjYYJBv&*j6+=Y&gA#Uoxv`H`YL-26OiDlW)u z^z*XX&6h#@Q&d!gcy<5%7$MAls4D#A?M6y-!lWRANZM!7mkDbVws_m6uJt>ua5!V+MbzI{|mO4_Y5mv}? zpDm6kLDE0;75!eYOkZg!(@WjpQogHrjBJO;+_9xyDH&%=c25QZ zkvsNFr%!ZP%ln)y`{D#-+4Z7($g#*OaX#p~rBT_`n{e`(L}KIt1R@;MiBr-S*5!A} zlz3jl*E$#}pLnUlE@q@2{PXuHL`w8Mn^)H1SGsecFZa33OW?@k9|PB!YclKQUwD;aYd z)1Pr^SoJd)mXNcqef(k)y0vXd-)yzUC8HQdSA7vWJ|>**;em=23w8QzQq)@0w$*z6 zFcP*hw=glwSo4zJ{b%UKBcSG9X20fBFpcbW`||J@NCI+&IpiUn(54=l@WQGoh*aCiz<7B`z6rtV&Yv; zL6LwsUhAYg&@VL7CPvk`9pOF#b_r;5GBc$CWEf`3v%nm){Ka`CD+kTJU}W@1mEKl$ zXw(L-6;PDz${%-bARbiadxRTt)Zs@%qY+I_v=?jd`sL$p-m?4%u0v*tN&(}|sx9iS zS@s+yYR5o8(#sSq&8C4bCfPl%+FP?uPPY5-5o67)^@wGacc)v6=Rv(^i+}}FMp#sw z2zwGyf`q@Ce=KAp?LA~n)hT6i2pW+2U}gSWKM1sUozDXxB3KE-lpFNQ(w#iAp^f=F z8$E);3uRt<%y|d6IzvXjJmcd~u`sj20UzKz&{<1lgGe^SELB>!v`;z~P2p0f2SdOC z1GLhO<-Xc`Y~JFiXL9(|y%2T%5>HKy0NDYm0k{i&$9xF$-bt`OZd2=Bff^#*Ih7D8 zp&ek>polo$S$xSVq6nr!NGG*=8c`NXYunF@l)E8qjBj|!k>5;0(YQQ#t+b+ih9M%! z^&=?XH>HcvQ?>xR5p}WeOQUeCfB2MJ)+OdvJ`j}O7d;YoI5NEU62u-nGojhcR(h@| zJNAUR!BJSgbCp+8A3ES6=QT>lnYC?PxBR4`t91U!pQ26hhXi2j$&oCF$rk+>9SliZ zEvSTh)aUnQD3p1)JhC@G1#K29na2Og@>HxHzt@iu)Kq_c<=3nx zcZ#Kqe`p@V#7@&|D%-`aMQH0OQriNTMbJj7Yd#1$4WI#8DUPgJ#8_i*S1Xen(B-{* zfyS*t>kBSr(+)b>3qnb?^{f|#Sd~;}+2#DrYgp_y){Rx49pzVO84_4jgZM!Es|S&n}Oe2DD?$ z?crEwH3oC!etjR1wC_OTFwzV@CXy9PnW`1e5(J!OypO6;TGq6xGoDR80u5DlY-_vh zdK!po$-q{ZWFME^lzXoHY1iSfk*F>B*A%*oi0OND4w98#H1lhM>T|h7Z#|XscUHS; zKAHSxC^deq6DDqNUfAOK;`wzZh^}rhp;nqKs&Js|hHWy5b1((`-aByp)G3Qizsj{zStr0H4mMSwZ6GoPM}a z(M3u13h|xoEPLfun3QVjUhK?wZSKAwJY5;bmzRa2__HkpLco$3o^W||@tlqb-o&H+TMC~?>vEoP9q%a8M%^69DQ)1#IFR9CBjeO*mu-R4njL2U=O$?bDPy_F)>m zMP1p-@h}2?3;pVq{z|``68Ra@NYwP;_sJWh%4Xl>*yg>l=W?c{lID;LwJUe0A9=*m zJ}LP=boCpzA~nZ-SLf0uJ~&qa0B%d*^i{N42&^YK4Y!4|3fSz8#PqxbMgO3GOtLn5 z;E8z?MHIF${HqTm^hy9P^yk~`1C>?XF!4Rh&XC^n$UzLJwv$eQNYA`h$bK4nDT8@F;)megw?+TIJeNO5lyhOC{<~d_ds0ACuXcv~~;K@mXwHpfGQS?Qu_~k0uj0S~Mdw-p)T_#b6f2DnTUc7rXB;$HO&TH}k0c4{6n}~% zf`ns5yDM=GMJEB+r&k#^_EaY!>CH@`=#m!>m}Z>!mAZ!s$B{WrZ=#J-*n+e*q{wgq zW6h>r!%4GaP_h0nP|m%#+U?IVb&gwc@iS#v+E_BsRwdBa-#u;TK6h`m5fX}4^^_49 zjW|DvpFyk)#4Z2O@sb{pSTiZ8M20}(Zn{NXooK!NX9lBU1Bn|h8hlax{SZi8-Zbu_ z?O+G@Lyb{9PDm$qySh10if^faf8i4oJ`dP)7U4<5?Co3b{5#V#6hd;C{tK(#ttq5b z*KdpxZ1eW>9i_I>|0`5%FVbppR~~-&Rr(aC5&-5#A1K>n?cc@H8M~u1AJGwZ-H(yq z6Fn;^toxTF(MDqOK1`(U#mppVqb!tCKe-2IvwUTrXAr!3f+SpHERR~}Lg zv)OXuBk%9ouVCV!@lMm3YBBw3ymMN7)B&YQ9)n2Gm`&p^lQV`#^BGPUa1L$$d(~?@ww{95cqzq19zbYwN`!p!!3cA~EZn zwyKK_;ND3sZtp#tD%#OUX7!nldeNw$^&(^{(C2yyfDSiA5kGg)XbDtRPHyEO135KS zpVAb0$DHBPfkzUE*QpalRKZ8JYRjGzQwgk?#p094e$8!NO)izoWTl}^DOXO;tNl)w zHwH5zE?!e#6gOE&H=gwSttB%3oWpzEtS}?8^?8}}!j$$3!4pC9AhkG`ylSEX0`(OK zxJmnTw?s+}syySe@`;A$pR! zENnptmujReNph45?2wL-qBwnr0(%x_C^IN_;)4 z>AB${hR(QL4ZSZNu%1^f_{S`F?lPFZ@Qk`-_XWU)_W-a(+tzM`weEmte6A{Yvz9f9 zc|Et!R?}QPKIyJ!N~TH>P=JZkHpa^vwm8hqPMz<5ikJ6Ii4Fk z^I2Qx58gy5Z{1H3Hy(jW9p4FVnk>17YR*XW@t-A|k|fn;Hid7Bss0{^W>j1Mnh6a! zHkDxQO+cs4O*&XF%GX(g8l(seXtR7*wyCv&I zJa8C&Wx=L;TSkk(SxLW(4t9O@Va`ND=>(?b#g+5x8xmsN55)=!ara(;th#WBNo<7P zeCjHqGko^`kX`(WE53z5cD4DbWd2OK9K1)85Dt6JzirEcA4Pk_@>nu|!5AZSfOu(P zf%v46;enZOa+KSs;ii^i=d^-^SGiSBd8hbISB#iZH@(tHErp?{>z6Y<>z{Jgs(d`C z(!6*>29N-X=1Pdh!K9i=Lrd`8e4xw=1c+Y&Ka8v1jmK!tm6Yph)6j&yI_bGzq3-Z( z2dQ=ZVP{xNNHCRe6@F=Lf8)({qb1KAtlGDfd>g+1xY;DJG%~~XTH{7SOFw$Xe(IFK zwfNleJ`Ss^cB;E=B+B4V(>3DD$XkKpW8r`u%YVq9eT$JfPff1R_&6+DG1WL62z*!r zz;n+R9&6^!GwTzZRF!)o&Py34ker+g1FZ83X4G`xsMu)gl1OdHTJb@?;?<5`@{Q3T zrx3p1FA!)8Kj*`gbu|aD!1~iIE1a_IOTt8QE(7Z%oTRC(3)I85aB5#ZNnL?HLoNOn z3!sSA(_aciS)QAZmx|J!`|-INf)!kS3hm30H_-Nzbv>1g_8m}H!2O!$aG=}>trKH? zF>g$5qu};GV(ngnzlNjq;K&tgIDnA%Q%;a^X;V}kUZ`#2Z7M%G)Zhw#y(Ur@rn!Ch zy$@CCPc9nctU7J?D&b^x-$&J$krPRgES253iSY~zDPDoqsYhP&eGcAD^f#udn$ZrK z@mFQXeMPcmb{vA$iOMbUgzjtw9D4XBlHD4ry{BB%k|ZUQ^6$L*unwHewk@`e&*(^m zsm_MWH;QeKy&-~Y=8(9kAp4&oNh{$FD?I5uk`@u!gSi5NqGh8=^}}voiYPQw0~66+ zR3?nf@m{`_(A4BDA5FoIa_bpFd_fA^nrc?gZn7PxlVF~9H|A((q`ZIgixyJ(;@p)9 z^zsCnmi1u7(P&v_Xl}n7bgl`Yz+6MwIl&_-^AEHdBrBmrC*Nh4EY{(j%Xm_x{oVF- z+zPH#sDlRE0k4b;@pYO(fjOKD69>^Uga(Btg|dQEnGA ze>w~f)qL#xjMw>lV>WdE`hiXetG{7_KiTQqyzL?ux`{Q3rbewQ9`&5jnJPr+MHN7n z^QZe_Gl)&pGsQ&@BIbJW=^9v&gUxwr2G$AKsOF`dgCZnh-TG6#(Xq?&Kh9jGnozEj#`8)@YV!d8OI(#Cky(Tyc3KmLVAu+)^@F@K1B_`dT zJa%K2JqRyzWluS;tMr)Ov6Y_Y=ctKMvG0~zn289TtEnn8=_YvA?xI85NZ2zU3YnN? z!Lh3CSVBPLPSskhoronYSc8L{s`;jR*j*}B?+Pks$e*QX^fnDglQ9*J`!z6kl-td^ z2m)cbdRAUPSh>dh!n=t#6bFjHXB9QJHw=tER+j!ylE=+=gg|j{-r)F*TMKlB0|2mx z*i(&04RuoOT;EnC^q7XgI_-7YKWeA-Dob3bF~ONzGBf+~UuGn|;iu#oi7Bs>u_>RV zj7S=Fv%Sn{GV0vm0Y)vW%GcsY+mTgf*`?KQ2=s>!T3}x?Z`(?NUjev|#xHKB>(Q*?KhL z!pn6VEYYc_xlX5m5;~^Ovv1Hx6?OScqvQfay<-$KGlqDHp73_)8tXkV&ey1!# z`kXFAN@OJ;dhCLg;A@cSTwU}SRgcAmR821rn$cPd?c}X-)E6KP)8;ZiY_O4}ky|&v z8~cM?vW5Qw!jWz#41_fD18dX8)Sr%SRH0E6l}|jO_-(S{VMr+X1mJ^SvpN}gx?`@< zjgwcx1LI3Jeq=;gK%FuyQBy{mEe5w!f(jW|nrLIDviDqEcq07-^ z)V4LXtTt16+4toY)I)ls_6pk%MnE2mE102lIqZa!B(X9NhZpnoO{d6Jr4g`$9WQOg z*O2Wdz@_P%(^3J`v@CNAH#z_AkqVoO%=gH0sy;t_lnxzhPi)lz^ZcS0o-s6C`YyH# ztAZT6<48)#v>}wtF-*%r&#WP6fc* ziN^!sU0XayOTUvQ&_|K|bEWj>?5(B2^chcsS1?;gpm@t6H0M5k>mW(NQ|`Y-{BXxw zO9iQ;X01=G^~cfhx>aMyFF=E0U4T}u9(ivQ_>Uj zA@s?`d>z@uw58;A?^F50j8Fi?Ld8{p!O~Vr-7ww_1X+bF3sTNl7GY7&O)Je${6#_e z`96KTnou;~~^R>4A`!vh(VRwTM z$jit~HD+|0I@7UWH_VR-X55#tPgbTrGCsre5cq_6g(}>_8@BSf#SvX@<38TRGM~X%xPF z#`?6M_dS9s)IsZ2)-lp$XVg?0#c4)%`;nr*47kYQ z^#;US58Jyz(J6JhzNUS7=$2^w~(sEHKi51Iq8L zYW-EgTT#40%)rluZ?cfM6hV_(?P9S7E!d1xLXbw5>!G#-D zZy+BP3#z9pB7ND^i`vJjzB+jDdC}-Z1SJ+~Rug4l9rR1t0Hvy4B*yK{nbK6A)Jx#v z*@QZJD(5c_Pv{v})90aRQnAjJr&dDXd~}+0EcGt8^(-hc5nY(egl7(YqUTHWXnrbD zkTr(f>Mq`NW;@TGZ;F5u*YyzixCIOEE^G8pbZan+ocZd3jV0$w;PRUH?yyEed9Xd- zFOPmobW-Cev{v_Y#D$w`jPXTQ)A?lE*JUom$iAUa4b?7;w#_W?OeG#V|DNYElCSdd zM1PKembxFwYy)|N=OZ99Q5$}mx}=|{F9Z@!N^LOkkB~MsZM9qEUg)P5babCk`s;zi z{TU~5Ie%(9$TQVlRhBuv@?P-CqdkGG<&!=edr2Bam}g>3hy7&4ur~R#oW@jbhZ9nR zDe|MGlwuYH3fPSfSxyD&^2_RsF*>JG^yCyP1hzz#8gqM|nmt$Iq) z#@s8>JV7S74aYp&^*hgaY<_$CTviaJ-qxJHkGh|0#80?}HM&?w4@-MmDSjn~EQMb3%mQ=F#nUTH{FB z4-RV)p4XuxV#jO(E?{v$P&OLUWJHHMHfC8FA_(FL)Dsc*DcrBRI&EfZMRw*wzU8!P2y-WQo*&f;D$B&KK8S|I1pxN?T1c2W*8 z`Plvo*p7e0%ZJ544qkb1djZXO%WXVz!R~RAVpfW5hfy&xG1-_pVHNgPW3?jG0>#~_ zj3IGXpNvbO#otr(&W-+@OnEN~6N9s=)v`Qa#cf~zEU;d^j|_BJCPWKVA0MLH;$aeR z(vDwdked}<)L6OH$Y%IoF^7P1ZqVe|H%(6ZpLj&hY8dxj1TJ3`fk)lO zbXklQ4v3A&D@@jenNOhsKDV7Q3bFIZ`JpE@av21mtQB(5P#Ld+P6*4jJ?JPv7g@l zOTVX#puhx>H%+cP=A$fI8E#x1xBtn8x-U_l{lV)wJi3o+#4+h;Nq#(~7HTUj=#-rr z9YZ3>K?cACPn&n9((EeItv+4%Ms$9u!GCu14S^Cr=Hoardy`Ig^AoAw$hq6S(a&ds zu?J(1)TNA6CinUYp?UkgwCs{@I+^xX=FZd+))FniRV0tlP&|-c}cKd`eKNrwE*Y3g~wo>hI=utGvC>-yfEX|4v;>Gx6EiLlo*!O#c7qNg zLuSfD?gPle2`cpxVE}m+7uhNIBIiTC-piZC4dYzn;j%;!NHzDiVCIKt9z{6JbB|Sh z%K$s1%*2n-B1VSlws!)otKM@mPm?hOIXWcpfieGu&Jh4e@i%*n+wf;DMNy64@z;Up z09MFCEI!Aw`JMBy@{~%E@xc!3puqv(Y;i?cB`P{d3qeKz?3H9}OjD zBnlvi>nop?ASAUy0Htu?Zi%WSfd2_c2)z7YLNlbxL!8DqZ(WwLbmOY?++KN`xT|D@ z)|J0IyT13ZW?n1V@jZ(h)%aW3b%=(ty4R0^XnA|wCZXNcXi=_&jJ&wG+M=JE?Y2Hx#ljDz3 zu0!DGLgMW&&wj&*!}-{{zAzX}Ml_a*KQ6H^o3UrTLf|%`+M7{0m2*bf&1KO~Bh42r zq2;pP?a|NTB$7xz1w5eTV#|E|EbTVzja^Kx-N;5m{T@1<4uQTJJQCs;Mqi{0MOj`- z#DvLKmTs;!EMRcbWCi+!{cp8UYt9T8HR?w@+bT3!?&9X7D}Ha6c_a%O&2S8Zx!=kz z9HfI$3kO|__hcXfUscupf9f*~k^X`usJuDixWA-<471r@9CyBJ_M=ns~7NZbeagkVgK}5FHLT z_w4dQ>7g&IptBli~SU~IYI)?3h;0aQ!XqC7Ryo37rmH7VesR3D|O zZ_;;{q+?Vy)8MUr&YAW&ix}X1gQ8=&iPMO7iPE|~_##-ni-iuWprb88hAJj~{=$vV zY--I;HExtV9(UWLZWtP=Mr0lj@F+WX6#Dj^1xFs4FjW+C#K-5R3d(0Ua+H-^W-pZN zDi+3VS)&HTatN&*^eGTdyN3G=AWTTV`h?d}bk%8MdAx2fkerD{f{N8_>rvsHC&e1| zCQrIHpC5Sg%mSs1{c{>dbnBS)=+3*4U)LU8dzr0}opIV&tv$-dhpw5cbQTAf^0xH( za3JSwyf}pG<9(VAE8S6DQ%(uXOKZe5@%V10#^pczu@Y-USy3WtP;)T!~+~i7Rhb`1SIWagK~2SM~&# z_i=noRPEtD%!2ab5!X0?S8z(p*`7U5{_dZcX(KZ$vsHeD2u3)}I-KYEVZxLyVth@r zc0(KaDD}3ox$S5d7WpD8li;B(MEfW4_7CF6O|Vh8Q3&$xrYbf9Txu@O!QJZesiKvi zRjzH?G3JE}Ud|Vf5LONEC@c&R!!T&cXP$v~3Mf?le5IyYO;m;3S+f?0sz6 zT`~kQk5Dx@1sd#;+E|n!zlg+*qT57fSG&8WGA3ipWQpia? zA1`9JPsQ5u)lCcu#?j}TU3|6ZM$3Eb0hoM(cXAR;rw2^T6fz5Cvm2^sAl5BGfWCTDwDMFel$+yTE`WiAarObPNjjg zF3y<@4NQ}^oFB!LxEU!-bIalkLB2RbJMEvipsbc+QBxN{gK%d!IO?<>^13QTh zU+h9WbK`QR1J_ct$5NFl1K%S;i~OTACo`MnI(oJ{I|4uu$s_;v_z4#4x<-V`OuZBX z8;;SsjkmnvxxG`JYeRRsx4DQC?=In$d$1hUx5hUpk==V|{Pf!L7Jg*KPQ$w!wYRWo1poFs zQOw*@pfuQmli*8a#M$HhOQmo;VSmqtAJ9aiUXzW#IpH^-cMT}Y1_y~x9EEtD918=i zM)ug(7n;ru1@ZiKlr9lO_#Hwt%TJ5}Iyh8C>@B>9xJwB1dg{)Vf$+PR8pttk*4S!s z2| z5jfIq>~~}BxshGPY)nB;wK+fi;$LJuZJd402P}8scB1mnTewpGpk)clEFWj9qCIa( z&(k@6YqHQi56s&eGjtJo1M#nmzd!sI&VBz&i*v`4_`iHBKo&B~;eUxc?)=bS{U0W}_l%s2lP`Kh*V_K>&bi3plWGf$5q1h3zCx={Mp3G7Uo{Sn_5Y9NCxH!rf zB=$>RtoiLw557(?x&K+CzE^vrxAR( z{bx{*jPhEmt8WoVcWp^nII0ye>o$Uz~%FeFVT~iit3zm-M zd98V_4S^gzz)Zokak2j`{H@SPs0Umqo=mV*5Md9+4ph)$ZQO@kf_a;eaZVV!_F zU1&e6c68;?)%)@mx_Ri|r&@=0Fc3L$zCA??Qz_=1b=?=E?yf|EW4byS9OPdI7w`O^ z_P#T!sjcl6^*wry3K~&Rio6D;9zdii)e;0jK)RF=8=-^rnxLW>nuriWXb~_VHDG`M z5dwz}(n2pGw15Fa3oVr7i~8Ps|J*U|xcBe<{_U}|ch(-ye%4y^nRD&AGREyo$lV;Z z#C*|PX)MFMPTJzWp?&lynj|(ky%|)w84tIv(7U9>j5m)^V5|m&*!Ki$_IOd($W!_8 zGnTYDNyrxWeWFyxf*7>7{Sg`5{21iGH;)$vY%Rq&L2i^be%}bP=k`HHC?6&)T>YT* z)*&wY_Kv-|`hw1wnD-9W%m^P-TwQNxV)9N1pKOM9udG#NYFtGNO3zDje)v?|mn@jH z6mn2@N&3^oc6`H2hC}?qjrdj~Yzm1_q^hJ|rFKh}WQy+kass^axW6p07zg1O)kFQY zsr!i4ocsGZ<`HZ*qbJm$^A9fq-^n_EML14E+>EQCw9(n(O>G;)eglJyuVUF)bxHWzCW?KFnD=<12&W}vX6+PLIeN?h+*eWDzjvGSk`!w^`ArRz_hqG7 zfus^N)y#cunk5S|t-B^6G?8d}pCFjqqxv|bzz>}5L)<_22|mg$YYFKaj?|PN-csYQ zM8KFowjwo%y6a37_4PVyP=rD{A)7IjR~?(S^Pp|DEDIRl(g$m z1fmL=yJYJ)7WO#50U*0<@^x{Wp;~UXqXDafX;ZVD*UM(F zcTZfn0~(n8K5@TkQEK=@ou*;vTZPmTx!u;$=~~)7bP_a$TU?Np$LbQQF~c59AMF4B ziZ=^Q_1qAWjVrWiTx&-9X7b4Z`WnmZp0ecu1hRiEc_LdZo(8{nciY8m@scg}eM$Y! zDV1aHUsy7Xq}YoCvTNVxjoqqELHJ1ALI?3cM0j$Ax#^p3f_$|ZKq?(w(ABCY5u zv9uSIR8GWP$U)%@TX4E#pKY+DQk((Bic8P71r^vg{nPXp$qQpif0yfp=^^xpvHu>f z>TN=VV|xBpK|mi4YV^ELLVT`o+6R5MzDIfUPw^kxbr8EDvqen9`n?+Dq+2QsxjgVV zQrpIP=B%CUGeyNOUngFZd2<4>HkJ@)nWgL9HKKHBu&`*WjqQ0IGx{8IzU1tayQ%cK z_{7FqAaI_TKeYE^)&fR!@gOk_N-dJ>ydsetGHe0SMLlKFPQrhU5^Qn%Z=eKzpfj+5e5;eEjja8&O z+%j6dvh=IBG;05{yFUW44jFZJmsgrEEL+$Q8HBuZ%Y- ze#UcA0kn-Q0G^JcLh_^0K9=A0@`lctElnV5W^!}n|&o+ekyYI?hsiQIMh>d+LXQSDPdpVs3o;-nbxk5s&9c)D$o zJEWtjHK z?WGzH}i7Je@U^l&a8Oimg41%J!Mfx(dKA(T_=BLg}hxzz2|%A zX3TE@Rj=f+nUab>O(_O}Cgz`K&x>+Ktvgrdgm6};5I4H_5p)6Ws2AjD=y?79L`W%n zkiPeH&#=)|wlM*#2r=!ru5L=&K1VtOAY8aN5D%Aw1IQGhr%j@%bv!+!jw;|dD+-LRoDvax=O}AuaHIn` zmKBxya-Lj`(0}Xox4C)KfT?BLfJ;70rq}gqDD-?ab{h3Wa$~)Um7DsJ z*y?_0aNAxhEzU%q`tR%jJ@X1=f^3E1rb1i?>7;YgnNWMayBcO33U1i!(x^A-jJI$C z2&QNll~B*Vxw;ueD+J+Lk&-?hMHY2qIu4v8?}Zc0RIh}=u&cRDUb(H8{;4ao224r- z&s5aY-#*hjIb$kk;rSsqY#i&V?nEKR|IGZ;c`$T&;;~G^lS?Rw$|!96(OilHvHiUI zvNiC7iNvy1B~s#|bV!8P8@KK5R@@a2K!uys7ZTjVj?vcp82l;4Bn(-q3o5TKd$BA~ z&7W3nXV+n^6!l8~t&U%jW>tEvDl+Uc`CRN*=uqo~(pl~7s1Z7j9~-sEAa5)+hj|Xx z@C~6KuHSWEjKyhJB}+kej7V0*_VNHJfb^UUb6fBUCrS`Bz;4U0Ei9OE4*IP3DJ2Sm z!}Qc<-Ill3(IEd!2^zN-W#!L!%RfOxrBU8r$Hdji@W!%N(EJzeMDA;!;#$XW#6I8C^~E`&s#^=#o^ zIyPc^sS=^@t+;It%W@6(Q&kiuo>8TIx#s~E?n+=`vCZ~dG0(e(4L}U(!L$rmZ-}AC zms3(4Vcyi9=P~;7ghjiI!k|8j5Z@D}2Zs3HX zhK>4{1f-#Ooq=WQwD1U+=%$FQ^N2xIwi0CI{++!GQ;-2jKOV~|e$&Kl<~cGw7NH;S^|9fCYqFyhAo#tF zv+Gr>%@rHUrltYE%Ydow3L#{XP%-+iuE4aH5pas!`ayF8N>9=Ys%HB#3`xxQy9G+B zaQfJgr(u{eA#c5si2Vk4vy}goV_sdjXmmMTHbXADs+gU@+aY!8`8axjaug%)R{Y+R zL^6pw3!PlY>^nCmWIfREDGIIir=9hw zeuY2`FL_veogBr2n!2qWPOhxJefJ$0Fu(h)qskT@FrN$F-Mn)pWxbHN72e|+s8V`R z{8|ne-=T-fY->W6j$YczK=<{&*k*N$vK!1-AepS?zv7;#7P$s8D)nf?b4p@-%EzmH zzo*IpKXjJtnSEKuq(v_eV^d7_mj+%6YG~c%Oq0@UcY>cVly!q+>uwEXY>EwFbltiL z4_(jFR2GRZ5r`n-S0J$2UYlg~xuU_DcgBI~B$YZ;9r85IsMn9s_YRz{>EYt3vA4-e zWHT~)yu|*@6ge2)*pHaswU)=oMpxB3)b_EeYbQ(A9ZVkcRO3xmhC7qtCQo}#`l}XH zYb_}0COio^5L~pAZSvp^*B1C;x_(uQHS~ysQLi0(nWffa0?+WgkH$L@t+uWArh+q< za_{sL)rH?kalz&lWY)de9gwTZ^YxCofr_U6h}-k?_vh!o(Ks4d2499&p!eK^h;52p z8T3zC8HJcadCGXHm0_i{bjkS5RIj6`G6qZ0a%0E=WzUr*2sFZFeg*mn$_zaG4z&Jgq! zQM(cuR15XFz}{m#H$nelR>sOgCWQb1JA>fJik23uD%m6CxD#i_+X*LcN4PeI|^HA;<6BBm^k@a$<589K-A#`!+>eyYjCB69d+$c zr3{W|$Oet|hCXL;aP6Fl?b|$M#TXV8xaklv8f7~*R5UBj->Nrf8o-7E*NnopmUi}Q z-Dh$V*>U% zD`(XBqn65c0$JZGm=R2Rl$X=eaQ0{I*Xv0#-JY7fCfHqyouxOj&-2{Zbo6mg)#$FX z+2{sBYlK()xDJ+|d$-rj8jc^0nU|z)NaFGBhHSZ@YEA=fRXCBZ$DQ&ebmAfdtlm6G zzpywlXCeaMgYobf{AY)}(%_g=!ba0(QpJ)*<#!Y1276E5;hNr**5eTR+9*MQ=^(#i zH7r8U2%rJe$~>2Vd7{Lutcq)x9V|Q)$_tJ{WZ2c-UWrVq>=#oP%|PURAv{e08$^%N zPqp-Wn2^8pJ>Fc8m5M8TVy=FYny}iY^R)fGeDI}@MC>ZH?0bbIq2Re&mvyGUOYzya%UT_e6}K3m5V(x@)Hxb;4B=gQT*H z`b=8gKJWt9pL;WXwGQU@czBZD|29!~ces?%Q6zM$liEEO4eS_s?5?~;n|y3z09q%^ zTcgC|WjX$Yzoy)K>4~I-@Yfre7`P*GSUqf! zNe+4jT}Q&boED}Fd5_MZBw3@6kP+m*m`Zo}?nXz*aG+#sNwHA8LX%1DcgosARwuPM zkY_Kg@1>x+mO`eHa@)HkV_lc=%&8N-#VVNKjZ!Svlw&TBzWZU>7^(ij|5*Bf_A(a6xSRY9%D^6xRawKjV|C$&y3r?s#uA$LeT(G^=S( zQqOA)*s)D0#YO2J*__S6wmZplQ!8Mr5Z@3u^CsK*m|o&iQFu6%ro!CcpQ9d5P{6Z@HiO{Z!PlcyNv<;qyL+m=kZGCo zI$&$Qx$T&@9Y{y{J0v{Gp&h| z^d23r7b#Eea=JFduuQq0vXN!C$6x2|Eq z3tEp6BlHt@?qG6Jv$7Lt?cgv!c7nc%^F|jk*CI6+^eH7eJmZ{=Tg7|He58bP&G`4^ zYB}p5Wic&PzqPa<2Cbz`rgdWuL;zI&Qk?BCnLs|glD_E%WYMQdu`OaFomVbviyRNn zJZD-*xO)ejrnzKXY!3QCT-yQLStTEKelxBfD*vpinGNx~>Ze$C=CSHp-_#V9pLL8r zq53o;>Wi&((}d&5DaL*{kjr}KF=Y=4F1P4WMKA>2ki#!2v^Ww}@7gxsdC!E~Vf(kU z$>BeKbj92`*7z4yzlyu6;(iF0sU|w!&p5J9#cOcMKi|wo>+zH`CwM?jzaW=pqo)B^}h$5ku0VqB)U?%%*)jFvDPr3i66 zZO0I`a}HWIJi*`EweDb`w0j?KtswX3-yMIll`76mDddxFe)4#ePg80m9c*B>iA~z|cmO{ho))3sb!cG!m12kV?l82q&yP^^R!o7BS z$kn&4WmhPo=ZO^-cwbMMhZl4#4enV7ZI#W=NpP1sSbUEe%Mfi1P8Xr`b0c*bMbK)N zaIPEQzY5@P4-?PV^<5?IVy(|uho-haX?i=`%2VPA^02qtu5ss>qt!dC4X)MI@F8N^ z5|~YL;D~xTOJ5w4&A){OiJ~9+B@^F<@3&fVrr(kYCMUo+X$gPn2bs6JiZ>kke<)dX zuYt@LMhq^+_^#|K2V%2ocyoFl*0J?bUYAV=&3H9_^04aLlF6Y#1Q$ldH&4r5`OAVR zC`1nSX(OYqzIraTOb+shYGf%^{6@Ril?l^uuhIqmp*^|t+ zcogsmIAF^`Vo#q=+@C&yZ%6Apej@z^o6fh(A9n+_BAxdy?9tKNK1%_jLxXEI{c$F66a)w z(QVWVgA!!8U+H6fDxtf4Z@5wxcE0t9Fz%82-4f%wTd0=1NJ7swH8tG5z~^DwDuIsI z%c<)%C(uN+{VlElJ-wa#fv|9Q%ftRN+)opoDXPQ2zH+Vn$)!MrL|H^&p3Y8)-=YSRl$?sQ80_y`1z@rSl&E?5Q^+#4)7omt8ZC{lL{)VyKUQKwy)n32HwkK+yB&3m zWXm+_4I|LOCBV+_?)@2PpLCDfJ_b(a z?5ys@S*#nBqR$Lv^TiouocJl=0#jWW6VEBgmga{}P;;hv-|*o&hc32sVl|4NvLPmX zF<#-5w%ekJoivCU{=RJ@<@^o6>ZXfXo8t=2Cma1+;3p*Z9aze376x1v-`Bmi<( literal 0 HcmV?d00001 diff --git a/localization/autoware_ekf_localizer/package.xml b/localization/autoware_ekf_localizer/package.xml new file mode 100644 index 0000000000000..e0e37f59d1acb --- /dev/null +++ b/localization/autoware_ekf_localizer/package.xml @@ -0,0 +1,47 @@ + + + + autoware_ekf_localizer + 0.40.0 + The autoware_ekf_localizer package + Takamasa Horibe + Yamato Ando + Takeshi Ishita + Masahiro Sakamoto + Kento Yabuuchi + NGUYEN Viet Anh + Taiki Yamada + Shintaro Sakoda + Ryu Yamamoto + Apache License 2.0 + Takamasa Horibe + + ament_cmake_auto + autoware_cmake + eigen3_cmake_module + + eigen + + autoware_internal_debug_msgs + autoware_kalman_filter + autoware_localization_util + autoware_universe_utils + diagnostic_msgs + fmt + geometry_msgs + nav_msgs + rclcpp + rclcpp_components + std_srvs + tf2 + tf2_ros + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + ros_testing + + + ament_cmake + + diff --git a/localization/autoware_ekf_localizer/schema/ekf_localizer.schema.json b/localization/autoware_ekf_localizer/schema/ekf_localizer.schema.json new file mode 100644 index 0000000000000..61fbcc2973aae --- /dev/null +++ b/localization/autoware_ekf_localizer/schema/ekf_localizer.schema.json @@ -0,0 +1,52 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "EKF Localizer Configuration", + "type": "object", + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "type": "object", + "properties": { + "node": { + "$ref": "sub/node.sub_schema.json#/definitions/node" + }, + "pose_measurement": { + "$ref": "sub/pose_measurement.sub_schema.json#/definitions/pose_measurement" + }, + "twist_measurement": { + "$ref": "sub/twist_measurement.sub_schema.json#/definitions/twist_measurement" + }, + "process_noise": { + "$ref": "sub/process_noise.sub_schema.json#/definitions/process_noise" + }, + "simple_1d_filter_parameters": { + "$ref": "sub/simple_1d_filter_parameters.sub_schema.json#/definitions/simple_1d_filter_parameters" + }, + "diagnostics": { + "$ref": "sub/diagnostics.sub_schema.json#/definitions/diagnostics" + }, + "misc": { + "$ref": "sub/misc.sub_schema.json#/definitions/misc" + } + }, + "required": [ + "node", + "pose_measurement", + "twist_measurement", + "process_noise", + "simple_1d_filter_parameters", + "diagnostics", + "misc" + ], + "additionalProperties": false + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/localization/autoware_ekf_localizer/schema/sub/diagnostics.sub_schema.json b/localization/autoware_ekf_localizer/schema/sub/diagnostics.sub_schema.json new file mode 100644 index 0000000000000..eda9e7d06f6f4 --- /dev/null +++ b/localization/autoware_ekf_localizer/schema/sub/diagnostics.sub_schema.json @@ -0,0 +1,63 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "EKF Localizer Configuration for Diagnostics", + "definitions": { + "diagnostics": { + "type": "object", + "properties": { + "pose_no_update_count_threshold_warn": { + "type": "integer", + "description": "The threshold at which a WARN state is triggered due to the Pose Topic update not happening continuously for a certain number of times", + "default": 50 + }, + "pose_no_update_count_threshold_error": { + "type": "integer", + "description": "The threshold at which an ERROR state is triggered due to the Pose Topic update not happening continuously for a certain number of times", + "default": 100 + }, + "twist_no_update_count_threshold_warn": { + "type": "integer", + "description": "The threshold at which a WARN state is triggered due to the Twist Topic update not happening continuously for a certain number of times", + "default": 50 + }, + "twist_no_update_count_threshold_error": { + "type": "integer", + "description": "The threshold at which an ERROR state is triggered due to the Twist Topic update not happening continuously for a certain number of times", + "default": 100 + }, + "ellipse_scale": { + "type": "number", + "description": "The scale factor to apply the error ellipse size", + "default": 3.0 + }, + "error_ellipse_size": { + "type": "number", + "description": "The long axis size of the error ellipse to trigger a ERROR state", + "default": 1.5 + }, + "warn_ellipse_size": { + "type": "number", + "description": "The long axis size of the error ellipse to trigger a WARN state", + "default": 1.2 + }, + "error_ellipse_size_lateral_direction": { + "type": "number", + "description": "The lateral direction size of the error ellipse to trigger a ERROR state", + "default": 0.3 + }, + "warn_ellipse_size_lateral_direction": { + "type": "number", + "description": "The lateral direction size of the error ellipse to trigger a WARN state", + "default": 0.25 + } + }, + "required": [ + "pose_no_update_count_threshold_warn", + "pose_no_update_count_threshold_error", + "twist_no_update_count_threshold_warn", + "twist_no_update_count_threshold_error" + ], + "additionalProperties": false + } + } +} diff --git a/localization/autoware_ekf_localizer/schema/sub/misc.sub_schema.json b/localization/autoware_ekf_localizer/schema/sub/misc.sub_schema.json new file mode 100644 index 0000000000000..cc36a5bf41ec6 --- /dev/null +++ b/localization/autoware_ekf_localizer/schema/sub/misc.sub_schema.json @@ -0,0 +1,23 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "EKF Localizer Configuration for MISC", + "definitions": { + "misc": { + "type": "object", + "properties": { + "threshold_observable_velocity_mps": { + "type": "number", + "description": "Minimum value for velocity that will be used for EKF. Mainly used for dead zone in velocity sensor [m/s] (0.0 means disabled)", + "default": 0.0 + }, + "pose_frame_id": { + "type": "string", + "description": "Parent frame_id of EKF output pose", + "default": "map" + } + }, + "required": ["threshold_observable_velocity_mps", "pose_frame_id"], + "additionalProperties": false + } + } +} diff --git a/localization/autoware_ekf_localizer/schema/sub/node.sub_schema.json b/localization/autoware_ekf_localizer/schema/sub/node.sub_schema.json new file mode 100644 index 0000000000000..cbaf34de6eaa7 --- /dev/null +++ b/localization/autoware_ekf_localizer/schema/sub/node.sub_schema.json @@ -0,0 +1,44 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "EKF Localizer Configuration for node", + "definitions": { + "node": { + "type": "object", + "properties": { + "show_debug_info": { + "type": "boolean", + "description": "Flag to display debug info", + "default": false + }, + "predict_frequency": { + "type": "number", + "description": "Frequency for filtering and publishing [Hz]", + "default": 50.0 + }, + "tf_rate": { + "type": "number", + "description": "Frequency for tf broadcasting [Hz]", + "default": 50.0 + }, + "extend_state_step": { + "type": "integer", + "description": "Max delay step which can be dealt with in EKF. Large number increases computational cost.", + "default": 50 + }, + "enable_yaw_bias_estimation": { + "type": "boolean", + "description": "Flag to enable yaw bias estimation", + "default": true + } + }, + "required": [ + "show_debug_info", + "predict_frequency", + "tf_rate", + "extend_state_step", + "enable_yaw_bias_estimation" + ], + "additionalProperties": false + } + } +} diff --git a/localization/autoware_ekf_localizer/schema/sub/pose_measurement.sub_schema.json b/localization/autoware_ekf_localizer/schema/sub/pose_measurement.sub_schema.json new file mode 100644 index 0000000000000..d2bc313d4dc75 --- /dev/null +++ b/localization/autoware_ekf_localizer/schema/sub/pose_measurement.sub_schema.json @@ -0,0 +1,38 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "EKF Localizer Configuration for Pose Measurement", + "definitions": { + "pose_measurement": { + "type": "object", + "properties": { + "pose_additional_delay": { + "type": "number", + "description": "Additional delay time for pose measurement [s]", + "default": 0.0 + }, + "pose_measure_uncertainty_time": { + "type": "number", + "description": "Measured time uncertainty used for covariance calculation [s]", + "default": 0.01 + }, + "pose_smoothing_steps": { + "type": "integer", + "description": "A value for smoothing steps", + "default": 5 + }, + "pose_gate_dist": { + "type": "number", + "description": "Limit of Mahalanobis distance used for outliers detection", + "default": 49.5 + } + }, + "required": [ + "pose_additional_delay", + "pose_measure_uncertainty_time", + "pose_smoothing_steps", + "pose_gate_dist" + ], + "additionalProperties": false + } + } +} diff --git a/localization/autoware_ekf_localizer/schema/sub/process_noise.sub_schema.json b/localization/autoware_ekf_localizer/schema/sub/process_noise.sub_schema.json new file mode 100644 index 0000000000000..37a8c248edd2c --- /dev/null +++ b/localization/autoware_ekf_localizer/schema/sub/process_noise.sub_schema.json @@ -0,0 +1,28 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "EKF Localizer Configuration for Process Noise", + "definitions": { + "process_noise": { + "type": "object", + "properties": { + "proc_stddev_vx_c": { + "type": "number", + "description": "Standard deviation of process noise in time differentiation expression of linear velocity x, noise for d_vx = 0", + "default": 10.0 + }, + "proc_stddev_wz_c": { + "type": "number", + "description": "Standard deviation of process noise in time differentiation expression of angular velocity z, noise for d_wz = 0", + "default": 5.0 + }, + "proc_stddev_yaw_c": { + "type": "number", + "description": "Standard deviation of process noise in time differentiation expression of yaw, noise for d_yaw = omega", + "default": 0.005 + } + }, + "required": ["proc_stddev_yaw_c", "proc_stddev_vx_c", "proc_stddev_wz_c"], + "additionalProperties": false + } + } +} diff --git a/localization/autoware_ekf_localizer/schema/sub/simple_1d_filter_parameters.sub_schema.json b/localization/autoware_ekf_localizer/schema/sub/simple_1d_filter_parameters.sub_schema.json new file mode 100644 index 0000000000000..00679ee92ad24 --- /dev/null +++ b/localization/autoware_ekf_localizer/schema/sub/simple_1d_filter_parameters.sub_schema.json @@ -0,0 +1,28 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "EKF Localizer Configuration of Simple 1D Filter Parameters", + "definitions": { + "simple_1d_filter_parameters": { + "type": "object", + "properties": { + "z_filter_proc_dev": { + "type": "number", + "description": "Simple1DFilter - Z filter process deviation", + "default": 1.0 + }, + "roll_filter_proc_dev": { + "type": "number", + "description": "Simple1DFilter - Roll filter process deviation", + "default": 0.1 + }, + "pitch_filter_proc_dev": { + "type": "number", + "description": "Simple1DFilter - Pitch filter process deviation", + "default": 0.1 + } + }, + "required": ["z_filter_proc_dev", "roll_filter_proc_dev", "pitch_filter_proc_dev"], + "additionalProperties": false + } + } +} diff --git a/localization/autoware_ekf_localizer/schema/sub/twist_measurement.sub_schema.json b/localization/autoware_ekf_localizer/schema/sub/twist_measurement.sub_schema.json new file mode 100644 index 0000000000000..7b80133cb38aa --- /dev/null +++ b/localization/autoware_ekf_localizer/schema/sub/twist_measurement.sub_schema.json @@ -0,0 +1,28 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "EKF Localizer Configuration for Twist Measurement", + "definitions": { + "twist_measurement": { + "type": "object", + "properties": { + "twist_additional_delay": { + "type": "number", + "description": "Additional delay time for twist [s]", + "default": 0.0 + }, + "twist_smoothing_steps": { + "type": "integer", + "description": "A value for smoothing steps", + "default": 2 + }, + "twist_gate_dist": { + "type": "number", + "description": "Limit of Mahalanobis distance used for outliers detection", + "default": 46.1 + } + }, + "required": ["twist_additional_delay", "twist_smoothing_steps", "twist_gate_dist"], + "additionalProperties": false + } + } +} diff --git a/localization/autoware_ekf_localizer/src/covariance.cpp b/localization/autoware_ekf_localizer/src/covariance.cpp new file mode 100644 index 0000000000000..9ed3a83fbf705 --- /dev/null +++ b/localization/autoware_ekf_localizer/src/covariance.cpp @@ -0,0 +1,56 @@ +// Copyright 2022 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/ekf_localizer/covariance.hpp" + +#include "autoware/ekf_localizer/state_index.hpp" +#include "autoware/universe_utils/ros/msg_covariance.hpp" + +namespace autoware::ekf_localizer +{ + +using COV_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; + +std::array ekf_covariance_to_pose_message_covariance(const Matrix6d & P) +{ + std::array covariance{}; + covariance.fill(0.); + + covariance[COV_IDX::X_X] = P(IDX::X, IDX::X); + covariance[COV_IDX::X_Y] = P(IDX::X, IDX::Y); + covariance[COV_IDX::X_YAW] = P(IDX::X, IDX::YAW); + covariance[COV_IDX::Y_X] = P(IDX::Y, IDX::X); + covariance[COV_IDX::Y_Y] = P(IDX::Y, IDX::Y); + covariance[COV_IDX::Y_YAW] = P(IDX::Y, IDX::YAW); + covariance[COV_IDX::YAW_X] = P(IDX::YAW, IDX::X); + covariance[COV_IDX::YAW_Y] = P(IDX::YAW, IDX::Y); + covariance[COV_IDX::YAW_YAW] = P(IDX::YAW, IDX::YAW); + + return covariance; +} + +std::array ekf_covariance_to_twist_message_covariance(const Matrix6d & P) +{ + std::array covariance{}; + covariance.fill(0.); + + covariance[COV_IDX::X_X] = P(IDX::VX, IDX::VX); + covariance[COV_IDX::X_YAW] = P(IDX::VX, IDX::WZ); + covariance[COV_IDX::YAW_X] = P(IDX::WZ, IDX::VX); + covariance[COV_IDX::YAW_YAW] = P(IDX::WZ, IDX::WZ); + + return covariance; +} + +} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/src/diagnostics.cpp b/localization/autoware_ekf_localizer/src/diagnostics.cpp new file mode 100644 index 0000000000000..45468abf72d6c --- /dev/null +++ b/localization/autoware_ekf_localizer/src/diagnostics.cpp @@ -0,0 +1,226 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/ekf_localizer/diagnostics.hpp" + +#include + +#include +#include + +namespace autoware::ekf_localizer +{ + +diagnostic_msgs::msg::DiagnosticStatus check_process_activated(const bool is_activated) +{ + diagnostic_msgs::msg::DiagnosticStatus stat; + + diagnostic_msgs::msg::KeyValue key_value; + key_value.key = "is_activated"; + key_value.value = is_activated ? "True" : "False"; + stat.values.push_back(key_value); + + stat.level = diagnostic_msgs::msg::DiagnosticStatus::OK; + stat.message = "OK"; + if (!is_activated) { + stat.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + stat.message = "[WARN]process is not activated"; + } + + return stat; +} + +diagnostic_msgs::msg::DiagnosticStatus check_set_initialpose(const bool is_set_initialpose) +{ + diagnostic_msgs::msg::DiagnosticStatus stat; + + diagnostic_msgs::msg::KeyValue key_value; + key_value.key = "is_set_initialpose"; + key_value.value = is_set_initialpose ? "True" : "False"; + stat.values.push_back(key_value); + + stat.level = diagnostic_msgs::msg::DiagnosticStatus::OK; + stat.message = "OK"; + if (!is_set_initialpose) { + stat.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + stat.message = "[WARN]initial pose is not set"; + } + + return stat; +} + +diagnostic_msgs::msg::DiagnosticStatus check_measurement_updated( + const std::string & measurement_type, const size_t no_update_count, + const size_t no_update_count_threshold_warn, const size_t no_update_count_threshold_error) +{ + diagnostic_msgs::msg::DiagnosticStatus stat; + + diagnostic_msgs::msg::KeyValue key_value; + key_value.key = measurement_type + "_no_update_count"; + key_value.value = std::to_string(no_update_count); + stat.values.push_back(key_value); + key_value.key = measurement_type + "_no_update_count_threshold_warn"; + key_value.value = std::to_string(no_update_count_threshold_warn); + stat.values.push_back(key_value); + key_value.key = measurement_type + "_no_update_count_threshold_error"; + key_value.value = std::to_string(no_update_count_threshold_error); + stat.values.push_back(key_value); + + stat.level = diagnostic_msgs::msg::DiagnosticStatus::OK; + stat.message = "OK"; + if (no_update_count >= no_update_count_threshold_warn) { + stat.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + stat.message = "[WARN]" + measurement_type + " is not updated"; + } + if (no_update_count >= no_update_count_threshold_error) { + stat.level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + stat.message = "[ERROR]" + measurement_type + " is not updated"; + } + + return stat; +} + +diagnostic_msgs::msg::DiagnosticStatus check_measurement_queue_size( + const std::string & measurement_type, const size_t queue_size) +{ + diagnostic_msgs::msg::DiagnosticStatus stat; + + diagnostic_msgs::msg::KeyValue key_value; + key_value.key = measurement_type + "_queue_size"; + key_value.value = std::to_string(queue_size); + stat.values.push_back(key_value); + + stat.level = diagnostic_msgs::msg::DiagnosticStatus::OK; + stat.message = "OK"; + + return stat; +} + +diagnostic_msgs::msg::DiagnosticStatus check_measurement_delay_gate( + const std::string & measurement_type, const bool is_passed_delay_gate, const double delay_time, + const double delay_time_threshold) +{ + diagnostic_msgs::msg::DiagnosticStatus stat; + + diagnostic_msgs::msg::KeyValue key_value; + key_value.key = measurement_type + "_is_passed_delay_gate"; + key_value.value = is_passed_delay_gate ? "True" : "False"; + stat.values.push_back(key_value); + key_value.key = measurement_type + "_delay_time"; + key_value.value = std::to_string(delay_time); + stat.values.push_back(key_value); + key_value.key = measurement_type + "_delay_time_threshold"; + key_value.value = std::to_string(delay_time_threshold); + stat.values.push_back(key_value); + + stat.level = diagnostic_msgs::msg::DiagnosticStatus::OK; + stat.message = "OK"; + if (!is_passed_delay_gate) { + stat.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + stat.message = "[WARN]" + measurement_type + " topic is delay"; + } + + return stat; +} + +diagnostic_msgs::msg::DiagnosticStatus check_measurement_mahalanobis_gate( + const std::string & measurement_type, const bool is_passed_mahalanobis_gate, + const double mahalanobis_distance, const double mahalanobis_distance_threshold) +{ + diagnostic_msgs::msg::DiagnosticStatus stat; + + diagnostic_msgs::msg::KeyValue key_value; + key_value.key = measurement_type + "_is_passed_mahalanobis_gate"; + key_value.value = is_passed_mahalanobis_gate ? "True" : "False"; + stat.values.push_back(key_value); + key_value.key = measurement_type + "_mahalanobis_distance"; + key_value.value = std::to_string(mahalanobis_distance); + stat.values.push_back(key_value); + key_value.key = measurement_type + "_mahalanobis_distance_threshold"; + key_value.value = std::to_string(mahalanobis_distance_threshold); + stat.values.push_back(key_value); + + stat.level = diagnostic_msgs::msg::DiagnosticStatus::OK; + stat.message = "OK"; + if (!is_passed_mahalanobis_gate) { + stat.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + stat.message = "[WARN]mahalanobis distance of " + measurement_type + " topic is large"; + } + + return stat; +} + +diagnostic_msgs::msg::DiagnosticStatus check_covariance_ellipse( + const std::string & name, const double curr_size, const double warn_threshold, + const double error_threshold) +{ + diagnostic_msgs::msg::DiagnosticStatus stat; + + diagnostic_msgs::msg::KeyValue key_value; + key_value.key = name + "_size"; + key_value.value = std::to_string(curr_size); + stat.values.push_back(key_value); + + key_value.key = name + "_warn_threshold"; + key_value.value = std::to_string(warn_threshold); + stat.values.push_back(key_value); + + key_value.key = name + "_error_threshold"; + key_value.value = std::to_string(error_threshold); + stat.values.push_back(key_value); + + stat.level = diagnostic_msgs::msg::DiagnosticStatus::OK; + stat.message = "OK"; + if (curr_size >= warn_threshold) { + stat.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + stat.message = "[WARN]" + name + " is large"; + } + if (curr_size >= error_threshold) { + stat.level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + stat.message = "[ERROR]" + name + " is large"; + } + + return stat; +} + +// The highest level within the stat_array will be reflected in the merged_stat. +// When all stat_array entries are 'OK,' the message of merged_stat will be "OK" +diagnostic_msgs::msg::DiagnosticStatus merge_diagnostic_status( + const std::vector & stat_array) +{ + diagnostic_msgs::msg::DiagnosticStatus merged_stat; + + for (const auto & stat : stat_array) { + if ((stat.level > diagnostic_msgs::msg::DiagnosticStatus::OK)) { + if (!merged_stat.message.empty()) { + merged_stat.message += "; "; + } + merged_stat.message += stat.message; + } + if (stat.level > merged_stat.level) { + merged_stat.level = stat.level; + } + for (const auto & value : stat.values) { + merged_stat.values.push_back(value); + } + } + + if (merged_stat.level == diagnostic_msgs::msg::DiagnosticStatus::OK) { + merged_stat.message = "OK"; + } + + return merged_stat; +} + +} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/src/ekf_localizer.cpp b/localization/autoware_ekf_localizer/src/ekf_localizer.cpp new file mode 100644 index 0000000000000..5638a5416e6ab --- /dev/null +++ b/localization/autoware_ekf_localizer/src/ekf_localizer.cpp @@ -0,0 +1,463 @@ +// Copyright 2018-2019 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/ekf_localizer/ekf_localizer.hpp" + +#include "autoware/ekf_localizer/diagnostics.hpp" +#include "autoware/ekf_localizer/string.hpp" +#include "autoware/ekf_localizer/warning_message.hpp" +#include "autoware/localization_util/covariance_ellipse.hpp" + +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include +#include +#include +#include + +namespace autoware::ekf_localizer +{ + +// clang-format off +#define PRINT_MAT(X) std::cout << #X << ":\n" << X << std::endl << std::endl // NOLINT +#define DEBUG_INFO(...) {if (params_.show_debug_info) {RCLCPP_INFO(__VA_ARGS__);}} // NOLINT +// clang-format on + +using std::placeholders::_1; + +EKFLocalizer::EKFLocalizer(const rclcpp::NodeOptions & node_options) +: rclcpp::Node("ekf_localizer", node_options), + warning_(std::make_shared(this)), + tf2_buffer_(this->get_clock()), + tf2_listener_(tf2_buffer_), + params_(this), + ekf_dt_(params_.ekf_dt), + pose_queue_(params_.pose_smoothing_steps), + twist_queue_(params_.twist_smoothing_steps) +{ + is_activated_ = false; + is_set_initialpose_ = false; + + /* initialize ros system */ + timer_control_ = rclcpp::create_timer( + this, get_clock(), rclcpp::Duration::from_seconds(ekf_dt_), + std::bind(&EKFLocalizer::timer_callback, this)); + + pub_pose_ = create_publisher("ekf_pose", 1); + pub_pose_cov_ = + create_publisher("ekf_pose_with_covariance", 1); + pub_odom_ = create_publisher("ekf_odom", 1); + pub_twist_ = create_publisher("ekf_twist", 1); + pub_twist_cov_ = create_publisher( + "ekf_twist_with_covariance", 1); + pub_yaw_bias_ = + create_publisher("estimated_yaw_bias", 1); + pub_biased_pose_ = create_publisher("ekf_biased_pose", 1); + pub_biased_pose_cov_ = create_publisher( + "ekf_biased_pose_with_covariance", 1); + pub_diag_ = this->create_publisher("/diagnostics", 10); + pub_processing_time_ = create_publisher( + "debug/processing_time_ms", 1); + sub_initialpose_ = create_subscription( + "initialpose", 1, std::bind(&EKFLocalizer::callback_initial_pose, this, _1)); + sub_pose_with_cov_ = create_subscription( + "in_pose_with_covariance", 1, + std::bind(&EKFLocalizer::callback_pose_with_covariance, this, _1)); + sub_twist_with_cov_ = create_subscription( + "in_twist_with_covariance", 1, + std::bind(&EKFLocalizer::callback_twist_with_covariance, this, _1)); + service_trigger_node_ = create_service( + "trigger_node_srv", + std::bind( + &EKFLocalizer::service_trigger_node, this, std::placeholders::_1, std::placeholders::_2), + rclcpp::ServicesQoS().get_rmw_qos_profile()); + + tf_br_ = std::make_shared( + std::shared_ptr(this, [](auto) {})); + + ekf_module_ = std::make_unique(warning_, params_); + logger_configure_ = std::make_unique(this); +} + +/* + * update_predict_frequency + */ +void EKFLocalizer::update_predict_frequency(const rclcpp::Time & current_time) +{ + if (last_predict_time_) { + if (current_time < *last_predict_time_) { + warning_->warn("Detected jump back in time"); + } else { + /* Measure dt */ + ekf_dt_ = (current_time - *last_predict_time_).seconds(); + DEBUG_INFO( + get_logger(), "[EKF] update ekf_dt_ to %f seconds (= %f hz)", ekf_dt_, 1 / ekf_dt_); + + if (ekf_dt_ > 10.0) { + ekf_dt_ = 10.0; + RCLCPP_WARN( + get_logger(), "Large ekf_dt_ detected!! (%f sec) Capped to 10.0 seconds", ekf_dt_); + } else if (ekf_dt_ > static_cast(params_.pose_smoothing_steps) / params_.ekf_rate) { + RCLCPP_WARN( + get_logger(), "EKF period may be too slow to finish pose smoothing!! (%f sec) ", ekf_dt_); + } + + /* Register dt and accumulate time delay */ + ekf_module_->accumulate_delay_time(ekf_dt_); + } + } + last_predict_time_ = std::make_shared(current_time); +} + +/* + * timer_callback + */ +void EKFLocalizer::timer_callback() +{ + stop_watch_timer_cb_.tic(); + + const rclcpp::Time current_time = this->now(); + + if (!is_activated_) { + warning_->warn_throttle( + "The node is not activated. Provide initial pose to pose_initializer", 2000); + publish_diagnostics(geometry_msgs::msg::PoseStamped{}, current_time); + return; + } + + if (!is_set_initialpose_) { + warning_->warn_throttle( + "Initial pose is not set. Provide initial pose to pose_initializer", 2000); + publish_diagnostics(geometry_msgs::msg::PoseStamped{}, current_time); + return; + } + + DEBUG_INFO(get_logger(), "========================= timer called ========================="); + + /* update predict frequency with measured timer rate */ + update_predict_frequency(current_time); + + /* predict model in EKF */ + stop_watch_.tic(); + DEBUG_INFO(get_logger(), "------------------------- start prediction -------------------------"); + ekf_module_->predict_with_delay(ekf_dt_); + DEBUG_INFO(get_logger(), "[EKF] predictKinematicsModel calc time = %f [ms]", stop_watch_.toc()); + DEBUG_INFO(get_logger(), "------------------------- end prediction -------------------------\n"); + + /* pose measurement update */ + pose_diag_info_.queue_size = pose_queue_.size(); + pose_diag_info_.is_passed_delay_gate = true; + pose_diag_info_.delay_time = 0.0; + pose_diag_info_.delay_time_threshold = 0.0; + pose_diag_info_.is_passed_mahalanobis_gate = true; + pose_diag_info_.mahalanobis_distance = 0.0; + + bool pose_is_updated = false; + + if (!pose_queue_.empty()) { + DEBUG_INFO(get_logger(), "------------------------- start Pose -------------------------"); + stop_watch_.tic(); + + // save the initial size because the queue size can change in the loop + const size_t n = pose_queue_.size(); + for (size_t i = 0; i < n; ++i) { + const auto pose = pose_queue_.pop_increment_age(); + bool is_updated = ekf_module_->measurement_update_pose(*pose, current_time, pose_diag_info_); + if (is_updated) { + pose_is_updated = true; + } + } + DEBUG_INFO( + get_logger(), "[EKF] measurement_update_pose calc time = %f [ms]", stop_watch_.toc()); + DEBUG_INFO(get_logger(), "------------------------- end Pose -------------------------\n"); + } + pose_diag_info_.no_update_count = pose_is_updated ? 0 : (pose_diag_info_.no_update_count + 1); + + /* twist measurement update */ + twist_diag_info_.queue_size = twist_queue_.size(); + twist_diag_info_.is_passed_delay_gate = true; + twist_diag_info_.delay_time = 0.0; + twist_diag_info_.delay_time_threshold = 0.0; + twist_diag_info_.is_passed_mahalanobis_gate = true; + twist_diag_info_.mahalanobis_distance = 0.0; + + bool twist_is_updated = false; + + if (!twist_queue_.empty()) { + DEBUG_INFO(get_logger(), "------------------------- start Twist -------------------------"); + stop_watch_.tic(); + + // save the initial size because the queue size can change in the loop + const size_t n = twist_queue_.size(); + for (size_t i = 0; i < n; ++i) { + const auto twist = twist_queue_.pop_increment_age(); + bool is_updated = + ekf_module_->measurement_update_twist(*twist, current_time, twist_diag_info_); + if (is_updated) { + twist_is_updated = true; + } + } + DEBUG_INFO( + get_logger(), "[EKF] measurement_update_twist calc time = %f [ms]", stop_watch_.toc()); + DEBUG_INFO(get_logger(), "------------------------- end Twist -------------------------\n"); + } + twist_diag_info_.no_update_count = twist_is_updated ? 0 : (twist_diag_info_.no_update_count + 1); + + const geometry_msgs::msg::PoseStamped current_ekf_pose = + ekf_module_->get_current_pose(current_time, false); + const geometry_msgs::msg::PoseStamped current_biased_ekf_pose = + ekf_module_->get_current_pose(current_time, true); + const geometry_msgs::msg::TwistStamped current_ekf_twist = + ekf_module_->get_current_twist(current_time); + + /* publish ekf result */ + publish_estimate_result(current_ekf_pose, current_biased_ekf_pose, current_ekf_twist); + publish_diagnostics(current_ekf_pose, current_time); + + /* publish processing time */ + const double elapsed_time = stop_watch_timer_cb_.toc(); + pub_processing_time_->publish( + autoware_internal_debug_msgs::build() + .stamp(current_time) + .data(elapsed_time)); +} + +/* + * get_transform_from_tf + */ +bool EKFLocalizer::get_transform_from_tf( + std::string parent_frame, std::string child_frame, + geometry_msgs::msg::TransformStamped & transform) +{ + parent_frame = erase_leading_slash(parent_frame); + child_frame = erase_leading_slash(child_frame); + + try { + transform = tf2_buffer_.lookupTransform(parent_frame, child_frame, tf2::TimePointZero); + return true; + } catch (tf2::TransformException & ex) { + warning_->warn(ex.what()); + } + return false; +} + +/* + * callback_initial_pose + */ +void EKFLocalizer::callback_initial_pose( + geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg) +{ + geometry_msgs::msg::TransformStamped transform; + if (!get_transform_from_tf(params_.pose_frame_id, msg->header.frame_id, transform)) { + RCLCPP_ERROR( + get_logger(), "[EKF] TF transform failed. parent = %s, child = %s", + params_.pose_frame_id.c_str(), msg->header.frame_id.c_str()); + } + ekf_module_->initialize(*msg, transform); + + is_set_initialpose_ = true; +} + +/* + * callback_pose_with_covariance + */ +void EKFLocalizer::callback_pose_with_covariance( + geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg) +{ + if (!is_activated_ && !is_set_initialpose_) { + return; + } + + pose_queue_.push(msg); + + publish_callback_return_diagnostics("pose", msg->header.stamp); +} + +/* + * callback_twist_with_covariance + */ +void EKFLocalizer::callback_twist_with_covariance( + geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg) +{ + // Ignore twist if velocity is too small. + // Note that this inequality must not include "equal". + if (std::abs(msg->twist.twist.linear.x) < params_.threshold_observable_velocity_mps) { + msg->twist.covariance[0 * 6 + 0] = 10000.0; + } + twist_queue_.push(msg); + + publish_callback_return_diagnostics("twist", msg->header.stamp); +} + +/* + * publish_estimate_result + */ +void EKFLocalizer::publish_estimate_result( + const geometry_msgs::msg::PoseStamped & current_ekf_pose, + const geometry_msgs::msg::PoseStamped & current_biased_ekf_pose, + const geometry_msgs::msg::TwistStamped & current_ekf_twist) +{ + /* publish latest pose */ + pub_pose_->publish(current_ekf_pose); + pub_biased_pose_->publish(current_biased_ekf_pose); + + /* publish latest pose with covariance */ + geometry_msgs::msg::PoseWithCovarianceStamped pose_cov; + pose_cov.header.stamp = current_ekf_pose.header.stamp; + pose_cov.header.frame_id = current_ekf_pose.header.frame_id; + pose_cov.pose.pose = current_ekf_pose.pose; + pose_cov.pose.covariance = ekf_module_->get_current_pose_covariance(); + pub_pose_cov_->publish(pose_cov); + + geometry_msgs::msg::PoseWithCovarianceStamped biased_pose_cov = pose_cov; + biased_pose_cov.pose.pose = current_biased_ekf_pose.pose; + pub_biased_pose_cov_->publish(biased_pose_cov); + + /* publish latest twist */ + pub_twist_->publish(current_ekf_twist); + + /* publish latest twist with covariance */ + geometry_msgs::msg::TwistWithCovarianceStamped twist_cov; + twist_cov.header.stamp = current_ekf_twist.header.stamp; + twist_cov.header.frame_id = current_ekf_twist.header.frame_id; + twist_cov.twist.twist = current_ekf_twist.twist; + twist_cov.twist.covariance = ekf_module_->get_current_twist_covariance(); + pub_twist_cov_->publish(twist_cov); + + /* publish yaw bias */ + autoware_internal_debug_msgs::msg::Float64Stamped yawb; + yawb.stamp = current_ekf_twist.header.stamp; + yawb.data = ekf_module_->get_yaw_bias(); + pub_yaw_bias_->publish(yawb); + + /* publish latest odometry */ + nav_msgs::msg::Odometry odometry; + odometry.header.stamp = current_ekf_pose.header.stamp; + odometry.header.frame_id = current_ekf_pose.header.frame_id; + odometry.child_frame_id = "base_link"; + odometry.pose = pose_cov.pose; + odometry.twist = twist_cov.twist; + pub_odom_->publish(odometry); + + /* publish tf */ + const geometry_msgs::msg::TransformStamped transform_stamped = + autoware::universe_utils::pose2transform(current_ekf_pose, "base_link"); + tf_br_->sendTransform(transform_stamped); +} + +void EKFLocalizer::publish_diagnostics( + const geometry_msgs::msg::PoseStamped & current_ekf_pose, const rclcpp::Time & current_time) +{ + std::vector diag_status_array; + + diag_status_array.push_back(check_process_activated(is_activated_)); + diag_status_array.push_back(check_set_initialpose(is_set_initialpose_)); + + if (is_activated_ && is_set_initialpose_) { + diag_status_array.push_back(check_measurement_updated( + "pose", pose_diag_info_.no_update_count, params_.pose_no_update_count_threshold_warn, + params_.pose_no_update_count_threshold_error)); + diag_status_array.push_back(check_measurement_queue_size("pose", pose_diag_info_.queue_size)); + diag_status_array.push_back(check_measurement_delay_gate( + "pose", pose_diag_info_.is_passed_delay_gate, pose_diag_info_.delay_time, + pose_diag_info_.delay_time_threshold)); + diag_status_array.push_back(check_measurement_mahalanobis_gate( + "pose", pose_diag_info_.is_passed_mahalanobis_gate, pose_diag_info_.mahalanobis_distance, + params_.pose_gate_dist)); + + diag_status_array.push_back(check_measurement_updated( + "twist", twist_diag_info_.no_update_count, params_.twist_no_update_count_threshold_warn, + params_.twist_no_update_count_threshold_error)); + diag_status_array.push_back(check_measurement_queue_size("twist", twist_diag_info_.queue_size)); + diag_status_array.push_back(check_measurement_delay_gate( + "twist", twist_diag_info_.is_passed_delay_gate, twist_diag_info_.delay_time, + twist_diag_info_.delay_time_threshold)); + diag_status_array.push_back(check_measurement_mahalanobis_gate( + "twist", twist_diag_info_.is_passed_mahalanobis_gate, twist_diag_info_.mahalanobis_distance, + params_.twist_gate_dist)); + + geometry_msgs::msg::PoseWithCovariance pose_cov; + pose_cov.pose = current_ekf_pose.pose; + pose_cov.covariance = ekf_module_->get_current_pose_covariance(); + const autoware::localization_util::Ellipse ellipse = + autoware::localization_util::calculate_xy_ellipse(pose_cov, params_.ellipse_scale); + diag_status_array.push_back(check_covariance_ellipse( + "cov_ellipse_long_axis", ellipse.long_radius, params_.warn_ellipse_size, + params_.error_ellipse_size)); + diag_status_array.push_back(check_covariance_ellipse( + "cov_ellipse_lateral_direction", ellipse.size_lateral_direction, + params_.warn_ellipse_size_lateral_direction, params_.error_ellipse_size_lateral_direction)); + } + + diagnostic_msgs::msg::DiagnosticStatus diag_merged_status; + diag_merged_status = merge_diagnostic_status(diag_status_array); + diag_merged_status.name = "localization: " + std::string(this->get_name()); + diag_merged_status.hardware_id = this->get_name(); + + diagnostic_msgs::msg::DiagnosticArray diag_msg; + diag_msg.header.stamp = current_time; + diag_msg.status.push_back(diag_merged_status); + pub_diag_->publish(diag_msg); +} + +void EKFLocalizer::publish_callback_return_diagnostics( + const std::string & callback_name, const rclcpp::Time & current_time) +{ + diagnostic_msgs::msg::KeyValue key_value; + key_value.key = "topic_time_stamp"; + key_value.value = std::to_string(current_time.nanoseconds()); + diagnostic_msgs::msg::DiagnosticStatus diag_status; + diag_status.level = diagnostic_msgs::msg::DiagnosticStatus::OK; + diag_status.name = + "localization: " + std::string(this->get_name()) + ": callback_" + callback_name; + diag_status.hardware_id = this->get_name(); + diag_status.message = "OK"; + diag_status.values.push_back(key_value); + diagnostic_msgs::msg::DiagnosticArray diag_msg; + diag_msg.header.stamp = current_time; + diag_msg.status.push_back(diag_status); + pub_diag_->publish(diag_msg); +} + +/** + * @brief trigger node + */ +void EKFLocalizer::service_trigger_node( + const std_srvs::srv::SetBool::Request::SharedPtr req, + std_srvs::srv::SetBool::Response::SharedPtr res) +{ + if (req->data) { + pose_queue_.clear(); + twist_queue_.clear(); + is_activated_ = true; + } else { + is_activated_ = false; + is_set_initialpose_ = false; + } + res->success = true; +} + +} // namespace autoware::ekf_localizer + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::ekf_localizer::EKFLocalizer) diff --git a/localization/autoware_ekf_localizer/src/ekf_module.cpp b/localization/autoware_ekf_localizer/src/ekf_module.cpp new file mode 100644 index 0000000000000..02c9f8ee30e08 --- /dev/null +++ b/localization/autoware_ekf_localizer/src/ekf_module.cpp @@ -0,0 +1,459 @@ +// Copyright 2018-2019 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/ekf_localizer/ekf_module.hpp" + +#include "autoware/ekf_localizer/covariance.hpp" +#include "autoware/ekf_localizer/mahalanobis.hpp" +#include "autoware/ekf_localizer/matrix_types.hpp" +#include "autoware/ekf_localizer/measurement.hpp" +#include "autoware/ekf_localizer/numeric.hpp" +#include "autoware/ekf_localizer/state_transition.hpp" +#include "autoware/ekf_localizer/warning_message.hpp" + +#include +#include + +#include +#include +#include + +#include +#include + +namespace autoware::ekf_localizer +{ + +// clang-format off +#define DEBUG_PRINT_MAT(X) {if (params_.show_debug_info) {std::cout << #X << ": " << X << std::endl;}} // NOLINT +// clang-format on + +EKFModule::EKFModule(std::shared_ptr warning, const HyperParameters & params) +: warning_(std::move(warning)), + dim_x_(6), // x, y, yaw, yaw_bias, vx, wz + accumulated_delay_times_(params.extend_state_step, 1.0E15), + params_(params), + last_angular_velocity_(0.0, 0.0, 0.0) +{ + Eigen::MatrixXd x = Eigen::MatrixXd::Zero(dim_x_, 1); + Eigen::MatrixXd p = Eigen::MatrixXd::Identity(dim_x_, dim_x_) * 1.0E15; // for x & y + p(IDX::YAW, IDX::YAW) = 50.0; // for yaw + if (params_.enable_yaw_bias_estimation) { + p(IDX::YAWB, IDX::YAWB) = 50.0; // for yaw bias + } + p(IDX::VX, IDX::VX) = 1000.0; // for vx + p(IDX::WZ, IDX::WZ) = 50.0; // for wz + + kalman_filter_.init(x, p, static_cast(params_.extend_state_step)); + z_filter_.set_proc_var(params_.z_filter_proc_dev * params_.z_filter_proc_dev); + roll_filter_.set_proc_var(params_.roll_filter_proc_dev * params_.roll_filter_proc_dev); + pitch_filter_.set_proc_var(params_.pitch_filter_proc_dev * params_.pitch_filter_proc_dev); +} + +void EKFModule::initialize( + const PoseWithCovariance & initial_pose, const geometry_msgs::msg::TransformStamped & transform) +{ + Eigen::MatrixXd x(dim_x_, 1); + Eigen::MatrixXd p = Eigen::MatrixXd::Zero(dim_x_, dim_x_); + + x(IDX::X) = initial_pose.pose.pose.position.x + transform.transform.translation.x; + x(IDX::Y) = initial_pose.pose.pose.position.y + transform.transform.translation.y; + x(IDX::YAW) = + tf2::getYaw(initial_pose.pose.pose.orientation) + tf2::getYaw(transform.transform.rotation); + x(IDX::YAWB) = 0.0; + x(IDX::VX) = 0.0; + x(IDX::WZ) = 0.0; + + using COV_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; + p(IDX::X, IDX::X) = initial_pose.pose.covariance[COV_IDX::X_X]; + p(IDX::Y, IDX::Y) = initial_pose.pose.covariance[COV_IDX::Y_Y]; + p(IDX::YAW, IDX::YAW) = initial_pose.pose.covariance[COV_IDX::YAW_YAW]; + + if (params_.enable_yaw_bias_estimation) { + p(IDX::YAWB, IDX::YAWB) = 0.0001; + } + p(IDX::VX, IDX::VX) = 0.01; + p(IDX::WZ, IDX::WZ) = 0.01; + + kalman_filter_.init(x, p, static_cast(params_.extend_state_step)); + + const double z = initial_pose.pose.pose.position.z; + + const auto rpy = autoware::universe_utils::getRPY(initial_pose.pose.pose.orientation); + + const double z_var = initial_pose.pose.covariance[COV_IDX::Z_Z]; + const double roll_var = initial_pose.pose.covariance[COV_IDX::ROLL_ROLL]; + const double pitch_var = initial_pose.pose.covariance[COV_IDX::PITCH_PITCH]; + + z_filter_.init(z, z_var); + roll_filter_.init(rpy.x, roll_var); + pitch_filter_.init(rpy.y, pitch_var); +} + +geometry_msgs::msg::PoseStamped EKFModule::get_current_pose( + const rclcpp::Time & current_time, bool get_biased_yaw) const +{ + const double z = z_filter_.get_x(); + const double roll = roll_filter_.get_x(); + const double pitch = pitch_filter_.get_x(); + + const double x = kalman_filter_.getXelement(IDX::X); + const double y = kalman_filter_.getXelement(IDX::Y); + /* + getXelement(IDX::YAW) is surely `biased_yaw`. + Please note how `yaw` and `yaw_bias` are used in the state transition model and + how the observed pose is handled in the measurement pose update. + */ + const double biased_yaw = kalman_filter_.getXelement(IDX::YAW); + const double yaw_bias = kalman_filter_.getXelement(IDX::YAWB); + const double yaw = biased_yaw + yaw_bias; + + Pose current_ekf_pose; + current_ekf_pose.header.frame_id = params_.pose_frame_id; + current_ekf_pose.header.stamp = current_time; + current_ekf_pose.pose.position = autoware::universe_utils::createPoint(x, y, z); + if (get_biased_yaw) { + current_ekf_pose.pose.orientation = + autoware::universe_utils::createQuaternionFromRPY(roll, pitch, biased_yaw); + } else { + current_ekf_pose.pose.orientation = + autoware::universe_utils::createQuaternionFromRPY(roll, pitch, yaw); + } + return current_ekf_pose; +} + +geometry_msgs::msg::TwistStamped EKFModule::get_current_twist( + const rclcpp::Time & current_time) const +{ + const double vx = kalman_filter_.getXelement(IDX::VX); + const double wz = kalman_filter_.getXelement(IDX::WZ); + + Twist current_ekf_twist; + current_ekf_twist.header.frame_id = "base_link"; + current_ekf_twist.header.stamp = current_time; + current_ekf_twist.twist.linear.x = vx; + current_ekf_twist.twist.angular.z = wz; + return current_ekf_twist; +} + +std::array EKFModule::get_current_pose_covariance() const +{ + std::array cov = + ekf_covariance_to_pose_message_covariance(kalman_filter_.getLatestP()); + + using COV_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; + cov[COV_IDX::Z_Z] = z_filter_.get_var(); + cov[COV_IDX::ROLL_ROLL] = roll_filter_.get_var(); + cov[COV_IDX::PITCH_PITCH] = pitch_filter_.get_var(); + + return cov; +} + +std::array EKFModule::get_current_twist_covariance() const +{ + return ekf_covariance_to_twist_message_covariance(kalman_filter_.getLatestP()); +} + +double EKFModule::get_yaw_bias() const +{ + return kalman_filter_.getLatestX()(IDX::YAWB); +} + +size_t EKFModule::find_closest_delay_time_index(double target_value) const +{ + // If target_value is too large, return last index + 1 + if (target_value > accumulated_delay_times_.back()) { + return accumulated_delay_times_.size(); + } + + auto lower = std::lower_bound( + accumulated_delay_times_.begin(), accumulated_delay_times_.end(), target_value); + + // If the lower bound is the first element, return its index. + // If the lower bound is beyond the last element, return the last index. + // If else, take the closest element. + if (lower == accumulated_delay_times_.begin()) { + return 0; + } + if (lower == accumulated_delay_times_.end()) { + return accumulated_delay_times_.size() - 1; + } + // Compare the target with the lower bound and the previous element. + auto prev = lower - 1; + bool is_closer_to_prev = (target_value - *prev) < (*lower - target_value); + + // Return the index of the closer element. + return is_closer_to_prev ? std::distance(accumulated_delay_times_.begin(), prev) + : std::distance(accumulated_delay_times_.begin(), lower); +} + +void EKFModule::accumulate_delay_time(const double dt) +{ + // Shift the delay times to the right. + std::copy_backward( + accumulated_delay_times_.begin(), accumulated_delay_times_.end() - 1, + accumulated_delay_times_.end()); + + // Add a new element (=0) and, and add delay time to the previous elements. + accumulated_delay_times_.front() = 0.0; + for (size_t i = 1; i < accumulated_delay_times_.size(); ++i) { + accumulated_delay_times_[i] += dt; + } +} + +void EKFModule::predict_with_delay(const double dt) +{ + const Eigen::MatrixXd x_curr = kalman_filter_.getLatestX(); + const Eigen::MatrixXd p_curr = kalman_filter_.getLatestP(); + + const double proc_cov_vx_d = std::pow(params_.proc_stddev_vx_c * dt, 2.0); + const double proc_cov_wz_d = std::pow(params_.proc_stddev_wz_c * dt, 2.0); + const double proc_cov_yaw_d = std::pow(params_.proc_stddev_yaw_c * dt, 2.0); + + const Vector6d x_next = predict_next_state(x_curr, dt); + const Matrix6d a = create_state_transition_matrix(x_curr, dt); + const Matrix6d q = process_noise_covariance(proc_cov_yaw_d, proc_cov_vx_d, proc_cov_wz_d); + kalman_filter_.predictWithDelay(x_next, a, q); + ekf_dt_ = dt; +} + +bool EKFModule::measurement_update_pose( + const PoseWithCovariance & pose, const rclcpp::Time & t_curr, EKFDiagnosticInfo & pose_diag_info) +{ + if (pose.header.frame_id != params_.pose_frame_id) { + warning_->warn_throttle( + fmt::format( + "pose frame_id is %s, but pose_frame is set as %s. They must be same.", + pose.header.frame_id.c_str(), params_.pose_frame_id.c_str()), + 2000); + } + const Eigen::MatrixXd x_curr = kalman_filter_.getLatestX(); + DEBUG_PRINT_MAT(x_curr.transpose()); + + constexpr int dim_y = 3; // pos_x, pos_y, yaw, depending on Pose output + + /* Calculate delay step */ + double delay_time = (t_curr - pose.header.stamp).seconds() + params_.pose_additional_delay; + if (delay_time < 0.0) { + warning_->warn_throttle(pose_delay_time_warning_message(delay_time), 1000); + } + + delay_time = std::max(delay_time, 0.0); + + const size_t delay_step = find_closest_delay_time_index(delay_time); + + pose_diag_info.delay_time = std::max(delay_time, pose_diag_info.delay_time); + pose_diag_info.delay_time_threshold = accumulated_delay_times_.back(); + if (delay_step >= params_.extend_state_step) { + pose_diag_info.is_passed_delay_gate = false; + warning_->warn_throttle( + pose_delay_step_warning_message( + pose_diag_info.delay_time, pose_diag_info.delay_time_threshold), + 2000); + return false; + } + + /* Since the kalman filter cannot handle the rotation angle directly, + offset the yaw angle so that the difference from the yaw angle that ekf holds internally + is less than 2 pi. */ + double yaw = tf2::getYaw(pose.pose.pose.orientation); + const double ekf_yaw = kalman_filter_.getXelement(delay_step * dim_x_ + IDX::YAW); + const double yaw_error = normalize_yaw(yaw - ekf_yaw); // normalize the error not to exceed 2 pi + yaw = yaw_error + ekf_yaw; + + /* Set measurement matrix */ + Eigen::MatrixXd y(dim_y, 1); + y << pose.pose.pose.position.x, pose.pose.pose.position.y, yaw; + + if (has_nan(y) || has_inf(y)) { + warning_->warn( + "[EKF] pose measurement matrix includes NaN of Inf. ignore update. check pose message."); + return false; + } + + /* Gate */ + const Eigen::Vector3d y_ekf( + kalman_filter_.getXelement(delay_step * dim_x_ + IDX::X), + kalman_filter_.getXelement(delay_step * dim_x_ + IDX::Y), ekf_yaw); + const Eigen::MatrixXd p_curr = kalman_filter_.getLatestP(); + const Eigen::MatrixXd p_y = p_curr.block(0, 0, dim_y, dim_y); + + const double distance = mahalanobis(y_ekf, y, p_y); + pose_diag_info.mahalanobis_distance = std::max(distance, pose_diag_info.mahalanobis_distance); + if (distance > params_.pose_gate_dist) { + pose_diag_info.is_passed_mahalanobis_gate = false; + warning_->warn_throttle(mahalanobis_warning_message(distance, params_.pose_gate_dist), 2000); + warning_->warn_throttle("Ignore the measurement data.", 2000); + return false; + } + + DEBUG_PRINT_MAT(y.transpose()); + DEBUG_PRINT_MAT(y_ekf.transpose()); + DEBUG_PRINT_MAT((y - y_ekf).transpose()); + + const Eigen::Matrix c = pose_measurement_matrix(); + const Eigen::Matrix3d r = + pose_measurement_covariance(pose.pose.covariance, params_.pose_smoothing_steps); + + kalman_filter_.updateWithDelay(y, c, r, static_cast(delay_step)); + + // Update Simple 1D filter with considering change of roll, pitch and height (position z) + // values due to measurement pose delay + auto pose_with_rph_delay_compensation = + compensate_rph_with_delay(pose, last_angular_velocity_, delay_time); + update_simple_1d_filters(pose_with_rph_delay_compensation, params_.pose_smoothing_steps); + + // debug + const Eigen::MatrixXd x_result = kalman_filter_.getLatestX(); + DEBUG_PRINT_MAT(x_result.transpose()); + DEBUG_PRINT_MAT((x_result - x_curr).transpose()); + + return true; +} + +geometry_msgs::msg::PoseWithCovarianceStamped EKFModule::compensate_rph_with_delay( + const PoseWithCovariance & pose, tf2::Vector3 last_angular_velocity, const double delay_time) +{ + tf2::Quaternion delta_orientation; + if (last_angular_velocity.length() > 0.0) { + delta_orientation.setRotation( + last_angular_velocity.normalized(), last_angular_velocity.length() * delay_time); + } else { + delta_orientation.setValue(0.0, 0.0, 0.0, 1.0); + } + + tf2::Quaternion prev_orientation = tf2::Quaternion( + pose.pose.pose.orientation.x, pose.pose.pose.orientation.y, pose.pose.pose.orientation.z, + pose.pose.pose.orientation.w); + + tf2::Quaternion curr_orientation; + curr_orientation = prev_orientation * delta_orientation; + curr_orientation.normalize(); + + PoseWithCovariance pose_with_delay; + pose_with_delay = pose; + pose_with_delay.header.stamp = + rclcpp::Time(pose.header.stamp) + rclcpp::Duration::from_seconds(delay_time); + pose_with_delay.pose.pose.orientation.x = curr_orientation.x(); + pose_with_delay.pose.pose.orientation.y = curr_orientation.y(); + pose_with_delay.pose.pose.orientation.z = curr_orientation.z(); + pose_with_delay.pose.pose.orientation.w = curr_orientation.w(); + + const auto rpy = autoware::universe_utils::getRPY(pose_with_delay.pose.pose.orientation); + const double delta_z = kalman_filter_.getXelement(IDX::VX) * delay_time * std::sin(-rpy.y); + pose_with_delay.pose.pose.position.z += delta_z; + + return pose_with_delay; +} + +bool EKFModule::measurement_update_twist( + const TwistWithCovariance & twist, const rclcpp::Time & t_curr, + EKFDiagnosticInfo & twist_diag_info) +{ + if (twist.header.frame_id != "base_link") { + warning_->warn_throttle("twist frame_id must be base_link", 2000); + } + + last_angular_velocity_ = tf2::Vector3(0.0, 0.0, 0.0); + + const Eigen::MatrixXd x_curr = kalman_filter_.getLatestX(); + DEBUG_PRINT_MAT(x_curr.transpose()); + + constexpr int dim_y = 2; // vx, wz + + /* Calculate delay step */ + double delay_time = (t_curr - twist.header.stamp).seconds() + params_.twist_additional_delay; + if (delay_time < 0.0) { + warning_->warn_throttle(twist_delay_time_warning_message(delay_time), 1000); + } + delay_time = std::max(delay_time, 0.0); + + const size_t delay_step = find_closest_delay_time_index(delay_time); + + twist_diag_info.delay_time = std::max(delay_time, twist_diag_info.delay_time); + twist_diag_info.delay_time_threshold = accumulated_delay_times_.back(); + if (delay_step >= params_.extend_state_step) { + twist_diag_info.is_passed_delay_gate = false; + warning_->warn_throttle( + twist_delay_step_warning_message( + twist_diag_info.delay_time, twist_diag_info.delay_time_threshold), + 2000); + return false; + } + + /* Set measurement matrix */ + Eigen::MatrixXd y(dim_y, 1); + y << twist.twist.twist.linear.x, twist.twist.twist.angular.z; + + if (has_nan(y) || has_inf(y)) { + warning_->warn( + "[EKF] twist measurement matrix includes NaN of Inf. ignore update. check twist message."); + return false; + } + + const Eigen::Vector2d y_ekf( + kalman_filter_.getXelement(delay_step * dim_x_ + IDX::VX), + kalman_filter_.getXelement(delay_step * dim_x_ + IDX::WZ)); + const Eigen::MatrixXd p_curr = kalman_filter_.getLatestP(); + const Eigen::MatrixXd p_y = p_curr.block(4, 4, dim_y, dim_y); + + const double distance = mahalanobis(y_ekf, y, p_y); + twist_diag_info.mahalanobis_distance = std::max(distance, twist_diag_info.mahalanobis_distance); + if (distance > params_.twist_gate_dist) { + twist_diag_info.is_passed_mahalanobis_gate = false; + warning_->warn_throttle(mahalanobis_warning_message(distance, params_.twist_gate_dist), 2000); + warning_->warn_throttle("Ignore the measurement data.", 2000); + return false; + } + + DEBUG_PRINT_MAT(y.transpose()); + DEBUG_PRINT_MAT(y_ekf.transpose()); + DEBUG_PRINT_MAT((y - y_ekf).transpose()); + + const Eigen::Matrix c = twist_measurement_matrix(); + const Eigen::Matrix2d r = + twist_measurement_covariance(twist.twist.covariance, params_.twist_smoothing_steps); + + kalman_filter_.updateWithDelay(y, c, r, static_cast(delay_step)); + + last_angular_velocity_ = tf2::Vector3( + twist.twist.twist.angular.x, twist.twist.twist.angular.y, twist.twist.twist.angular.z); + + // debug + const Eigen::MatrixXd x_result = kalman_filter_.getLatestX(); + DEBUG_PRINT_MAT(x_result.transpose()); + DEBUG_PRINT_MAT((x_result - x_curr).transpose()); + + return true; +} + +void EKFModule::update_simple_1d_filters( + const geometry_msgs::msg::PoseWithCovarianceStamped & pose, const size_t smoothing_step) +{ + double z = pose.pose.pose.position.z; + + const auto rpy = autoware::universe_utils::getRPY(pose.pose.pose.orientation); + + using COV_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; + double z_var = pose.pose.covariance[COV_IDX::Z_Z] * static_cast(smoothing_step); + double roll_var = pose.pose.covariance[COV_IDX::ROLL_ROLL] * static_cast(smoothing_step); + double pitch_var = + pose.pose.covariance[COV_IDX::PITCH_PITCH] * static_cast(smoothing_step); + + z_filter_.update(z, z_var, ekf_dt_); + roll_filter_.update(rpy.x, roll_var, ekf_dt_); + pitch_filter_.update(rpy.y, pitch_var, ekf_dt_); +} + +} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/src/mahalanobis.cpp b/localization/autoware_ekf_localizer/src/mahalanobis.cpp new file mode 100644 index 0000000000000..f7e56674b16bd --- /dev/null +++ b/localization/autoware_ekf_localizer/src/mahalanobis.cpp @@ -0,0 +1,32 @@ +// Copyright 2022 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/ekf_localizer/mahalanobis.hpp" + +namespace autoware::ekf_localizer +{ + +double squared_mahalanobis( + const Eigen::VectorXd & x, const Eigen::VectorXd & y, const Eigen::MatrixXd & C) +{ + const Eigen::VectorXd d = x - y; + return d.dot(C.inverse() * d); +} + +double mahalanobis(const Eigen::VectorXd & x, const Eigen::VectorXd & y, const Eigen::MatrixXd & C) +{ + return std::sqrt(squared_mahalanobis(x, y, C)); +} + +} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/src/measurement.cpp b/localization/autoware_ekf_localizer/src/measurement.cpp new file mode 100644 index 0000000000000..63db7d250f8d5 --- /dev/null +++ b/localization/autoware_ekf_localizer/src/measurement.cpp @@ -0,0 +1,61 @@ +// Copyright 2022 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/ekf_localizer/measurement.hpp" + +#include "autoware/ekf_localizer/state_index.hpp" +#include "autoware/universe_utils/ros/msg_covariance.hpp" + +namespace autoware::ekf_localizer +{ + +Eigen::Matrix pose_measurement_matrix() +{ + Eigen::Matrix c = Eigen::Matrix::Zero(); + c(0, IDX::X) = 1.0; // for pos x + c(1, IDX::Y) = 1.0; // for pos y + c(2, IDX::YAW) = 1.0; // for yaw + return c; +} + +Eigen::Matrix twist_measurement_matrix() +{ + Eigen::Matrix c = Eigen::Matrix::Zero(); + c(0, IDX::VX) = 1.0; // for vx + c(1, IDX::WZ) = 1.0; // for wz + return c; +} + +Eigen::Matrix3d pose_measurement_covariance( + const std::array & covariance, const size_t smoothing_step) +{ + Eigen::Matrix3d r; + using COV_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; + r << covariance.at(COV_IDX::X_X), covariance.at(COV_IDX::X_Y), covariance.at(COV_IDX::X_YAW), + covariance.at(COV_IDX::Y_X), covariance.at(COV_IDX::Y_Y), covariance.at(COV_IDX::Y_YAW), + covariance.at(COV_IDX::YAW_X), covariance.at(COV_IDX::YAW_Y), covariance.at(COV_IDX::YAW_YAW); + return r * static_cast(smoothing_step); +} + +Eigen::Matrix2d twist_measurement_covariance( + const std::array & covariance, const size_t smoothing_step) +{ + Eigen::Matrix2d r; + using COV_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; + r << covariance.at(COV_IDX::X_X), covariance.at(COV_IDX::X_YAW), covariance.at(COV_IDX::YAW_X), + covariance.at(COV_IDX::YAW_YAW); + return r * static_cast(smoothing_step); +} + +} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/src/state_transition.cpp b/localization/autoware_ekf_localizer/src/state_transition.cpp new file mode 100644 index 0000000000000..f6a50b5839ec4 --- /dev/null +++ b/localization/autoware_ekf_localizer/src/state_transition.cpp @@ -0,0 +1,102 @@ +// Copyright 2022 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/ekf_localizer/state_transition.hpp" + +#include "autoware/ekf_localizer/matrix_types.hpp" +#include "autoware/ekf_localizer/state_index.hpp" + +#include + +namespace autoware::ekf_localizer +{ + +double normalize_yaw(const double & yaw) +{ + // FIXME(IshitaTakeshi) I think the computation here can be simplified + // FIXME(IshitaTakeshi) Rename the function. This is not normalization + return std::atan2(std::sin(yaw), std::cos(yaw)); +} + +/* == Nonlinear model == + * + * x_{k+1} = x_k + vx_k * cos(yaw_k + b_k) * dt + * y_{k+1} = y_k + vx_k * sin(yaw_k + b_k) * dt + * yaw_{k+1} = yaw_k + (wz_k) * dt + * b_{k+1} = b_k + * vx_{k+1} = vx_k + * wz_{k+1} = wz_k + * + * (b_k : yaw_bias_k) + */ + +Vector6d predict_next_state(const Vector6d & X_curr, const double dt) +{ + const double x = X_curr(IDX::X); + const double y = X_curr(IDX::Y); + const double yaw = X_curr(IDX::YAW); + const double yaw_bias = X_curr(IDX::YAWB); + const double vx = X_curr(IDX::VX); + const double wz = X_curr(IDX::WZ); + + Vector6d x_next; + x_next(IDX::X) = x + vx * std::cos(yaw + yaw_bias) * dt; // dx = v * cos(yaw) + x_next(IDX::Y) = y + vx * std::sin(yaw + yaw_bias) * dt; // dy = v * sin(yaw) + x_next(IDX::YAW) = normalize_yaw(yaw + wz * dt); // dyaw = omega + omega_bias + x_next(IDX::YAWB) = yaw_bias; + x_next(IDX::VX) = vx; + x_next(IDX::WZ) = wz; + return x_next; +} + +/* == Linearized model == + * + * A = [ 1, 0, -vx*sin(yaw+b)*dt, -vx*sin(yaw+b)*dt, cos(yaw+b)*dt, 0] + * [ 0, 1, vx*cos(yaw+b)*dt, vx*cos(yaw+b)*dt, sin(yaw+b)*dt, 0] + * [ 0, 0, 1, 0, 0, dt] + * [ 0, 0, 0, 1, 0, 0] + * [ 0, 0, 0, 0, 1, 0] + * [ 0, 0, 0, 0, 0, 1] + */ +Matrix6d create_state_transition_matrix(const Vector6d & X_curr, const double dt) +{ + const double yaw = X_curr(IDX::YAW); + const double yaw_bias = X_curr(IDX::YAWB); + const double vx = X_curr(IDX::VX); + + Matrix6d a = Matrix6d::Identity(); + a(IDX::X, IDX::YAW) = -vx * sin(yaw + yaw_bias) * dt; + a(IDX::X, IDX::YAWB) = -vx * sin(yaw + yaw_bias) * dt; + a(IDX::X, IDX::VX) = cos(yaw + yaw_bias) * dt; + a(IDX::Y, IDX::YAW) = vx * cos(yaw + yaw_bias) * dt; + a(IDX::Y, IDX::YAWB) = vx * cos(yaw + yaw_bias) * dt; + a(IDX::Y, IDX::VX) = sin(yaw + yaw_bias) * dt; + a(IDX::YAW, IDX::WZ) = dt; + return a; +} + +Matrix6d process_noise_covariance( + const double proc_cov_yaw_d, const double proc_cov_vx_d, const double proc_cov_wz_d) +{ + Matrix6d q = Matrix6d::Zero(); + q(IDX::X, IDX::X) = 0.0; + q(IDX::Y, IDX::Y) = 0.0; + q(IDX::YAW, IDX::YAW) = proc_cov_yaw_d; // for yaw + q(IDX::YAWB, IDX::YAWB) = 0.0; + q(IDX::VX, IDX::VX) = proc_cov_vx_d; // for vx + q(IDX::WZ, IDX::WZ) = proc_cov_wz_d; // for wz + return q; +} + +} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/src/warning_message.cpp b/localization/autoware_ekf_localizer/src/warning_message.cpp new file mode 100644 index 0000000000000..0c1e127747365 --- /dev/null +++ b/localization/autoware_ekf_localizer/src/warning_message.cpp @@ -0,0 +1,60 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/ekf_localizer/warning_message.hpp" + +#include + +#include + +namespace autoware::ekf_localizer +{ + +std::string pose_delay_step_warning_message( + const double delay_time, const double delay_time_threshold) +{ + const std::string s = + "Pose delay exceeds the compensation limit, ignored. " + "delay: {:.3f}[s], limit: {:.3f}[s]"; + return fmt::format(s, delay_time, delay_time_threshold); +} + +std::string twist_delay_step_warning_message( + const double delay_time, const double delay_time_threshold) +{ + const std::string s = + "Twist delay exceeds the compensation limit, ignored. " + "delay: {:.3f}[s], limit: {:.3f}[s]"; + return fmt::format(s, delay_time, delay_time_threshold); +} + +std::string pose_delay_time_warning_message(const double delay_time) +{ + const std::string s = "Pose time stamp is inappropriate, set delay to 0[s]. delay = {:.3f}"; + return fmt::format(s, delay_time); +} + +std::string twist_delay_time_warning_message(const double delay_time) +{ + const std::string s = "Twist time stamp is inappropriate, set delay to 0[s]. delay = {:.3f}"; + return fmt::format(s, delay_time); +} + +std::string mahalanobis_warning_message(const double distance, const double max_distance) +{ + const std::string s = "The Mahalanobis distance {:.4f} is over the limit {:.4f}."; + return fmt::format(s, distance, max_distance); +} + +} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/test/test_aged_object_queue.cpp b/localization/autoware_ekf_localizer/test/test_aged_object_queue.cpp new file mode 100644 index 0000000000000..dc9ef008335ed --- /dev/null +++ b/localization/autoware_ekf_localizer/test/test_aged_object_queue.cpp @@ -0,0 +1,108 @@ +// Copyright 2023 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/ekf_localizer/aged_object_queue.hpp" + +#include + +#include + +namespace autoware::ekf_localizer +{ + +TEST(AgedObjectQueue, DiscardsObjectWhenAgeReachesMaximum) +{ + AgedObjectQueue queue(3); + + queue.push("a"); + EXPECT_EQ(queue.size(), 1U); + + queue.pop_increment_age(); // age = 1 + EXPECT_EQ(queue.size(), 1U); + + queue.pop_increment_age(); // age = 2 + EXPECT_EQ(queue.size(), 1U); + + queue.pop_increment_age(); // age = 3 + EXPECT_EQ(queue.size(), 0U); +} + +TEST(AgedObjectQueue, MultipleObjects) +{ + AgedObjectQueue queue(3); + + queue.push("a"); + EXPECT_EQ(queue.size(), 1U); + EXPECT_EQ(queue.pop_increment_age(), std::string{"a"}); // age of a = 1 + EXPECT_EQ(queue.size(), 1U); + EXPECT_EQ(queue.pop_increment_age(), std::string{"a"}); // age of a = 2 + + queue.push("b"); + + EXPECT_EQ(queue.pop_increment_age(), std::string{"a"}); // age of a = 3 + EXPECT_EQ(queue.size(), 1U); + + EXPECT_EQ(queue.pop_increment_age(), std::string{"b"}); // age of b = 1 + EXPECT_EQ(queue.size(), 1U); + + EXPECT_EQ(queue.pop_increment_age(), std::string{"b"}); // age of b = 2 + EXPECT_EQ(queue.size(), 1U); + + EXPECT_EQ(queue.pop_increment_age(), std::string{"b"}); // age of b = 3 + EXPECT_EQ(queue.size(), 0U); +} + +TEST(AgedObjectQueue, Empty) +{ + AgedObjectQueue queue(2); + + EXPECT_TRUE(queue.empty()); + + queue.push("a"); + + EXPECT_FALSE(queue.empty()); + + queue.pop_increment_age(); + queue.pop_increment_age(); + + EXPECT_TRUE(queue.empty()); +} + +TEST(AgedObjectQueue, Clear) +{ + AgedObjectQueue queue(3); + + queue.push("a"); + queue.push("b"); + + EXPECT_EQ(queue.size(), 2U); + + queue.clear(); + + EXPECT_EQ(queue.size(), 0U); +} + +TEST(AgedObjectQueue, Back) +{ + AgedObjectQueue queue(3); + + queue.push("a"); + + EXPECT_EQ(queue.back(), std::string{"a"}); + queue.push("b"); + + EXPECT_EQ(queue.back(), std::string{"b"}); +} + +} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/test/test_covariance.cpp b/localization/autoware_ekf_localizer/test/test_covariance.cpp new file mode 100644 index 0000000000000..cab09367d6340 --- /dev/null +++ b/localization/autoware_ekf_localizer/test/test_covariance.cpp @@ -0,0 +1,84 @@ +// Copyright 2022 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/ekf_localizer/covariance.hpp" + +#include + +namespace autoware::ekf_localizer +{ + +TEST(EKFCovarianceToPoseMessageCovariance, SmokeTest) +{ + { + Matrix6d p = Matrix6d::Zero(); + p(0, 0) = 1.; + p(0, 1) = 2.; + p(0, 2) = 3.; + p(1, 0) = 4.; + p(1, 1) = 5.; + p(1, 2) = 6.; + p(2, 0) = 7.; + p(2, 1) = 8.; + p(2, 2) = 9.; + + std::array covariance = ekf_covariance_to_pose_message_covariance(p); + EXPECT_EQ(covariance[0], 1.); + EXPECT_EQ(covariance[1], 2.); + EXPECT_EQ(covariance[5], 3.); + EXPECT_EQ(covariance[6], 4.); + EXPECT_EQ(covariance[7], 5.); + EXPECT_EQ(covariance[11], 6.); + EXPECT_EQ(covariance[30], 7.); + EXPECT_EQ(covariance[31], 8.); + EXPECT_EQ(covariance[35], 9.); + } + + // ensure other elements are zero + { + Matrix6d p = Matrix6d::Zero(); + std::array covariance = ekf_covariance_to_pose_message_covariance(p); + for (double e : covariance) { + EXPECT_EQ(e, 0.); + } + } +} + +TEST(EKFCovarianceToTwistMessageCovariance, SmokeTest) +{ + { + Matrix6d p = Matrix6d::Zero(); + p(4, 4) = 1.; + p(4, 5) = 2.; + p(5, 4) = 3.; + p(5, 5) = 4.; + + std::array covariance = ekf_covariance_to_twist_message_covariance(p); + EXPECT_EQ(covariance[0], 1.); + EXPECT_EQ(covariance[5], 2.); + EXPECT_EQ(covariance[30], 3.); + EXPECT_EQ(covariance[35], 4.); + } + + // ensure other elements are zero + { + Matrix6d p = Matrix6d::Zero(); + std::array covariance = ekf_covariance_to_twist_message_covariance(p); + for (double e : covariance) { + EXPECT_EQ(e, 0.); + } + } +} + +} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/test/test_diagnostics.cpp b/localization/autoware_ekf_localizer/test/test_diagnostics.cpp new file mode 100644 index 0000000000000..5ce39df484e98 --- /dev/null +++ b/localization/autoware_ekf_localizer/test/test_diagnostics.cpp @@ -0,0 +1,213 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/ekf_localizer/diagnostics.hpp" + +#include + +#include +#include + +namespace autoware::ekf_localizer +{ + +TEST(TestEkfDiagnostics, check_process_activated) +{ + diagnostic_msgs::msg::DiagnosticStatus stat; + + bool is_activated = true; + stat = check_process_activated(is_activated); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); + + is_activated = false; + stat = check_process_activated(is_activated); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); +} + +TEST(TestEkfDiagnostics, check_set_initialpose) +{ + diagnostic_msgs::msg::DiagnosticStatus stat; + + bool is_set_initialpose = true; + stat = check_set_initialpose(is_set_initialpose); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); + + is_set_initialpose = false; + stat = check_set_initialpose(is_set_initialpose); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); +} + +TEST(TestEkfDiagnostics, check_measurement_updated) +{ + diagnostic_msgs::msg::DiagnosticStatus stat; + + const std::string measurement_type = "pose"; // not effect for stat.level + const size_t no_update_count_threshold_warn = 50; + const size_t no_update_count_threshold_error = 250; + + size_t no_update_count = 0; + stat = check_measurement_updated( + measurement_type, no_update_count, no_update_count_threshold_warn, + no_update_count_threshold_error); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); + + no_update_count = 1; + stat = check_measurement_updated( + measurement_type, no_update_count, no_update_count_threshold_warn, + no_update_count_threshold_error); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); + + no_update_count = 49; + stat = check_measurement_updated( + measurement_type, no_update_count, no_update_count_threshold_warn, + no_update_count_threshold_error); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); + + no_update_count = 50; + stat = check_measurement_updated( + measurement_type, no_update_count, no_update_count_threshold_warn, + no_update_count_threshold_error); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); + + no_update_count = 249; + stat = check_measurement_updated( + measurement_type, no_update_count, no_update_count_threshold_warn, + no_update_count_threshold_error); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); + + no_update_count = 250; + stat = check_measurement_updated( + measurement_type, no_update_count, no_update_count_threshold_warn, + no_update_count_threshold_error); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR); +} + +TEST(TestEkfDiagnostics, check_measurement_queue_size) +{ + diagnostic_msgs::msg::DiagnosticStatus stat; + + const std::string measurement_type = "pose"; // not effect for stat.level + + size_t queue_size = 0; // not effect for stat.level + stat = check_measurement_queue_size(measurement_type, queue_size); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); + + queue_size = 1; // not effect for stat.level + stat = check_measurement_queue_size(measurement_type, queue_size); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); +} + +TEST(TestEkfDiagnostics, check_measurement_delay_gate) +{ + diagnostic_msgs::msg::DiagnosticStatus stat; + + const std::string measurement_type = "pose"; // not effect for stat.level + const double delay_time = 0.1; // not effect for stat.level + const double delay_time_threshold = 1.0; // not effect for stat.level + + bool is_passed_delay_gate = true; + stat = check_measurement_delay_gate( + measurement_type, is_passed_delay_gate, delay_time, delay_time_threshold); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); + + is_passed_delay_gate = false; + stat = check_measurement_delay_gate( + measurement_type, is_passed_delay_gate, delay_time, delay_time_threshold); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); +} + +TEST(TestEkfDiagnostics, check_measurement_mahalanobis_gate) +{ + diagnostic_msgs::msg::DiagnosticStatus stat; + + const std::string measurement_type = "pose"; // not effect for stat.level + const double mahalanobis_distance = 0.1; // not effect for stat.level + const double mahalanobis_distance_threshold = 1.0; // not effect for stat.level + + bool is_passed_mahalanobis_gate = true; + stat = check_measurement_mahalanobis_gate( + measurement_type, is_passed_mahalanobis_gate, mahalanobis_distance, + mahalanobis_distance_threshold); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); + + is_passed_mahalanobis_gate = false; + stat = check_measurement_mahalanobis_gate( + measurement_type, is_passed_mahalanobis_gate, mahalanobis_distance, + mahalanobis_distance_threshold); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); +} + +TEST(TestLocalizationErrorMonitorDiagnostics, merge_diagnostic_status) +{ + diagnostic_msgs::msg::DiagnosticStatus merged_stat; + std::vector stat_array(2); + + stat_array.at(0).level = diagnostic_msgs::msg::DiagnosticStatus::OK; + stat_array.at(0).message = "OK"; + stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::OK; + stat_array.at(1).message = "OK"; + merged_stat = merge_diagnostic_status(stat_array); + EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); + EXPECT_EQ(merged_stat.message, "OK"); + + stat_array.at(0).level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + stat_array.at(0).message = "WARN0"; + stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::OK; + stat_array.at(1).message = "OK"; + merged_stat = merge_diagnostic_status(stat_array); + EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); + EXPECT_EQ(merged_stat.message, "WARN0"); + + stat_array.at(0).level = diagnostic_msgs::msg::DiagnosticStatus::OK; + stat_array.at(0).message = "OK"; + stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + stat_array.at(1).message = "WARN1"; + merged_stat = merge_diagnostic_status(stat_array); + EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); + EXPECT_EQ(merged_stat.message, "WARN1"); + + stat_array.at(0).level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + stat_array.at(0).message = "WARN0"; + stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + stat_array.at(1).message = "WARN1"; + merged_stat = merge_diagnostic_status(stat_array); + EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); + EXPECT_EQ(merged_stat.message, "WARN0; WARN1"); + + stat_array.at(0).level = diagnostic_msgs::msg::DiagnosticStatus::OK; + stat_array.at(0).message = "OK"; + stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + stat_array.at(1).message = "ERROR1"; + merged_stat = merge_diagnostic_status(stat_array); + EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR); + EXPECT_EQ(merged_stat.message, "ERROR1"); + + stat_array.at(0).level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + stat_array.at(0).message = "WARN0"; + stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + stat_array.at(1).message = "ERROR1"; + merged_stat = merge_diagnostic_status(stat_array); + EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR); + EXPECT_EQ(merged_stat.message, "WARN0; ERROR1"); + + stat_array.at(0).level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + stat_array.at(0).message = "ERROR0"; + stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + stat_array.at(1).message = "ERROR1"; + merged_stat = merge_diagnostic_status(stat_array); + EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR); + EXPECT_EQ(merged_stat.message, "ERROR0; ERROR1"); +} + +} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/test/test_ekf_localizer_launch.py b/localization/autoware_ekf_localizer/test/test_ekf_localizer_launch.py new file mode 100644 index 0000000000000..1db0863636b04 --- /dev/null +++ b/localization/autoware_ekf_localizer/test/test_ekf_localizer_launch.py @@ -0,0 +1,170 @@ +#!/usr/bin/env python3 + +# Copyright 2023 TIER IV, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os +import time +import unittest + +from ament_index_python import get_package_share_directory +from geometry_msgs.msg import PoseWithCovarianceStamped +import launch +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import AnyLaunchDescriptionSource +from launch.logging import get_logger +import launch_testing +from nav_msgs.msg import Odometry +import pytest +import rclpy +from std_srvs.srv import SetBool + +logger = get_logger(__name__) + + +@pytest.mark.launch_test +def generate_test_description(): + test_ekf_localizer_launch_file = os.path.join( + get_package_share_directory("autoware_ekf_localizer"), + "launch", + "ekf_localizer.launch.xml", + ) + ekf_localizer = IncludeLaunchDescription( + AnyLaunchDescriptionSource(test_ekf_localizer_launch_file), + ) + + return launch.LaunchDescription( + [ + ekf_localizer, + # Start tests right away - no need to wait for anything + launch_testing.actions.ReadyToTest(), + ] + ) + + +class TestEKFLocalizer(unittest.TestCase): + @classmethod + def setUpClass(cls): + # Initialize the ROS context for the test node + rclpy.init() + + @classmethod + def tearDownClass(cls): + # Shutdown the ROS context + rclpy.shutdown() + + def setUp(self): + # Create a ROS node for tests + self.test_node = rclpy.create_node("test_node") + self.evaluation_time = 0.2 # 200ms + + def tearDown(self): + self.test_node.destroy_node() + + @staticmethod + def print_message(stat): + logger.debug("===========================") + logger.debug(stat) + + def test_node_link(self): + # Trigger ekf_localizer to activate the node + cli_trigger = self.test_node.create_client(SetBool, "/trigger_node") + while not cli_trigger.wait_for_service(timeout_sec=1.0): + continue + + request = SetBool.Request() + request.data = True + future = cli_trigger.call_async(request) + rclpy.spin_until_future_complete(self.test_node, future) + + if future.result() is not None: + self.test_node.get_logger().info("Result of bool service: %s" % future.result().message) + else: + self.test_node.get_logger().error( + "Exception while calling service: %r" % future.exception() + ) + + # Send initial pose + pub_init_pose = self.test_node.create_publisher( + PoseWithCovarianceStamped, "/initialpose3d", 10 + ) + init_pose = PoseWithCovarianceStamped() + init_pose.header.frame_id = "map" + init_pose.pose.pose.position.x = 0.0 + init_pose.pose.pose.position.y = 0.0 + init_pose.pose.pose.position.z = 0.0 + init_pose.pose.pose.orientation.x = 0.0 + init_pose.pose.pose.orientation.y = 0.0 + init_pose.pose.pose.orientation.z = 0.0 + init_pose.pose.pose.orientation.w = 1.0 + init_pose.pose.covariance = [ + 0.01, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.01, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.01, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.01, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.01, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.01, + ] + pub_init_pose.publish(init_pose) + + # Receive Odometry + msg_buffer = [] + self.test_node.create_subscription( + Odometry, "/ekf_odom", lambda msg: msg_buffer.append(msg), 10 + ) + + # Wait until the node publishes some topic + end_time = time.time() + self.evaluation_time + while time.time() < end_time: + rclpy.spin_once(self.test_node, timeout_sec=0.1) + + # Check if the EKF outputs some Odometry + self.assertTrue(len(msg_buffer) > 0) + + +@launch_testing.post_shutdown_test() +class TestProcessOutput(unittest.TestCase): + def test_exit_code(self, proc_info): + # Check that process exits with code 0: no error + launch_testing.asserts.assertExitCodes(proc_info) diff --git a/localization/autoware_ekf_localizer/test/test_ekf_localizer_mahalanobis.py b/localization/autoware_ekf_localizer/test/test_ekf_localizer_mahalanobis.py new file mode 100644 index 0000000000000..29afd4953520e --- /dev/null +++ b/localization/autoware_ekf_localizer/test/test_ekf_localizer_mahalanobis.py @@ -0,0 +1,229 @@ +#!/usr/bin/env python3 + +# Copyright 2023 TIER IV, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os +import time +import unittest + +from ament_index_python import get_package_share_directory +from geometry_msgs.msg import PoseWithCovarianceStamped +import launch +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import AnyLaunchDescriptionSource +from launch.logging import get_logger +import launch_testing +from nav_msgs.msg import Odometry +import pytest +import rclpy +from std_srvs.srv import SetBool + +logger = get_logger(__name__) + + +@pytest.mark.launch_test +def generate_test_description(): + test_ekf_localizer_launch_file = os.path.join( + get_package_share_directory("autoware_ekf_localizer"), + "launch", + "ekf_localizer.launch.xml", + ) + ekf_localizer = IncludeLaunchDescription( + AnyLaunchDescriptionSource(test_ekf_localizer_launch_file), + ) + + return launch.LaunchDescription( + [ + ekf_localizer, + # Start tests right away - no need to wait for anything + launch_testing.actions.ReadyToTest(), + ] + ) + + +class TestEKFLocalizer(unittest.TestCase): + @classmethod + def setUpClass(cls): + # Initialize the ROS context for the test node + rclpy.init() + + @classmethod + def tearDownClass(cls): + # Shutdown the ROS context + rclpy.shutdown() + + def setUp(self): + # Create a ROS node for tests + self.test_node = rclpy.create_node("test_node") + self.evaluation_time = 0.2 # 200ms + + def tearDown(self): + self.test_node.destroy_node() + + @staticmethod + def print_message(stat): + logger.debug("===========================") + logger.debug(stat) + + def test_node_link(self): + # Trigger ekf_localizer to activate the node + cli_trigger = self.test_node.create_client(SetBool, "/trigger_node") + while not cli_trigger.wait_for_service(timeout_sec=1.0): + continue + + request = SetBool.Request() + request.data = True + future = cli_trigger.call_async(request) + rclpy.spin_until_future_complete(self.test_node, future) + + if future.result() is not None: + self.test_node.get_logger().info("Result of bool service: %s" % future.result().message) + else: + self.test_node.get_logger().error( + "Exception while calling service: %r" % future.exception() + ) + + # Send initial pose + pub_init_pose = self.test_node.create_publisher( + PoseWithCovarianceStamped, "/initialpose3d", 10 + ) + init_pose = PoseWithCovarianceStamped() + init_pose.header.frame_id = "map" + init_pose.pose.pose.position.x = 0.0 + init_pose.pose.pose.position.y = 0.0 + init_pose.pose.pose.position.z = 0.0 + init_pose.pose.pose.orientation.x = 0.0 + init_pose.pose.pose.orientation.y = 0.0 + init_pose.pose.pose.orientation.z = 0.0 + init_pose.pose.pose.orientation.w = 1.0 + init_pose.pose.covariance = [ + 0.01, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.01, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.01, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.01, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.01, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.01, + ] + pub_init_pose.publish(init_pose) + rclpy.spin_once(self.test_node, timeout_sec=0.1) + + # Send pose that should be ignored by mahalanobis gate in ekf_localizer + pub_pose = self.test_node.create_publisher( + PoseWithCovarianceStamped, "/in_pose_with_covariance", 10 + ) + pose = PoseWithCovarianceStamped() + pose.header.frame_id = "map" + pose.pose.pose.position.x = 1000000.0 + pose.pose.pose.position.y = 1000000.0 + pose.pose.pose.position.z = 10.0 + pose.pose.pose.orientation.x = 0.0 + pose.pose.pose.orientation.y = 0.0 + pose.pose.pose.orientation.z = 0.0 + pose.pose.pose.orientation.w = 1.0 + pose.pose.covariance = [ + 0.01, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.01, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.01, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.01, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.01, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.01, + ] + pub_pose.publish(pose) + + # Receive Odometry + msg_buffer = [] + self.test_node.create_subscription( + Odometry, "/ekf_odom", lambda msg: msg_buffer.append(msg), 10 + ) + + # Wait until the node publishes some topic + end_time = time.time() + self.evaluation_time + while time.time() < end_time: + rclpy.spin_once(self.test_node, timeout_sec=0.1) + + # Check if the EKF outputs some Odometry + self.assertTrue(len(msg_buffer) > 0) + + # Assert msg to be at the origin + self.assertEqual(msg_buffer[-1].pose.pose.position.x, 0.0) + self.assertEqual(msg_buffer[-1].pose.pose.position.y, 0.0) + self.assertEqual(msg_buffer[-1].pose.pose.position.z, 0.0) + + +@launch_testing.post_shutdown_test() +class TestProcessOutput(unittest.TestCase): + def test_exit_code(self, proc_info): + # Check that process exits with code 0: no error + launch_testing.asserts.assertExitCodes(proc_info) diff --git a/localization/autoware_ekf_localizer/test/test_mahalanobis.cpp b/localization/autoware_ekf_localizer/test/test_mahalanobis.cpp new file mode 100644 index 0000000000000..3f867470a3c63 --- /dev/null +++ b/localization/autoware_ekf_localizer/test/test_mahalanobis.cpp @@ -0,0 +1,66 @@ +// Copyright 2022 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/ekf_localizer/mahalanobis.hpp" + +#include + +namespace autoware::ekf_localizer +{ + +constexpr double tolerance = 1e-8; + +TEST(squared_mahalanobis, SmokeTest) +{ + { + Eigen::Vector2d x(0, 1); + Eigen::Vector2d y(3, 2); + Eigen::Matrix2d c; + c << 10, 0, 0, 10; + + EXPECT_NEAR(squared_mahalanobis(x, y, c), 1.0, tolerance); + } + + { + Eigen::Vector2d x(4, 1); + Eigen::Vector2d y(1, 5); + Eigen::Matrix2d c; + c << 5, 0, 0, 5; + + EXPECT_NEAR(squared_mahalanobis(x, y, c), 5.0, tolerance); + } +} + +TEST(mahalanobis, SmokeTest) +{ + { + Eigen::Vector2d x(0, 1); + Eigen::Vector2d y(3, 2); + Eigen::Matrix2d c; + c << 10, 0, 0, 10; + + EXPECT_NEAR(mahalanobis(x, y, c), 1.0, tolerance); + } + + { + Eigen::Vector2d x(4, 1); + Eigen::Vector2d y(1, 5); + Eigen::Matrix2d c; + c << 5, 0, 0, 5; + + EXPECT_NEAR(mahalanobis(x, y, c), std::sqrt(5.0), tolerance); + } +} + +} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/test/test_measurement.cpp b/localization/autoware_ekf_localizer/test/test_measurement.cpp new file mode 100644 index 0000000000000..99dcc1744c33d --- /dev/null +++ b/localization/autoware_ekf_localizer/test/test_measurement.cpp @@ -0,0 +1,86 @@ +// Copyright 2022 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/ekf_localizer/measurement.hpp" + +#include + +namespace autoware::ekf_localizer +{ + +TEST(Measurement, pose_measurement_matrix) +{ + const Eigen::Matrix m = pose_measurement_matrix(); + Eigen::Matrix expected; + expected << 1, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0; + EXPECT_EQ((m - expected).norm(), 0); +} + +TEST(Measurement, twist_measurement_matrix) +{ + const Eigen::Matrix m = twist_measurement_matrix(); + Eigen::Matrix expected; + expected << 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 1; + EXPECT_EQ((m - expected).norm(), 0); +} + +TEST(Measurement, pose_measurement_covariance) +{ + { + const std::array covariance = {1, 2, 0, 0, 0, 3, 4, 5, 0, 0, 0, 6, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 7, 8, 0, 0, 0, 9}; + + const Eigen::Matrix3d m = pose_measurement_covariance(covariance, 2); + + Eigen::Matrix3d expected; + expected << 2, 4, 6, 8, 10, 12, 14, 16, 18; + + EXPECT_EQ((m - expected).norm(), 0.); + } + + { + // Make sure that other elements are not changed + std::array covariance{}; + covariance.fill(0); + const Eigen::Matrix3d m = pose_measurement_covariance(covariance, 2.); + EXPECT_EQ(m.norm(), 0); + } +} + +TEST(Measurement, twist_measurement_covariance) +{ + { + const std::array covariance = {1, 0, 0, 0, 0, 2, 0, 0, 0, 0, 0, 6, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 3, 0, 0, 0, 0, 4}; + + const Eigen::Matrix2d m = twist_measurement_covariance(covariance, 2); + + Eigen::Matrix2d expected; + expected << 2, 4, 6, 8; + + EXPECT_EQ((m - expected).norm(), 0.); + } + + { + // Make sure that other elements are not changed + std::array covariance{}; + covariance.fill(0); + const Eigen::Matrix2d m = twist_measurement_covariance(covariance, 2.); + EXPECT_EQ(m.norm(), 0); + } +} + +} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/test/test_numeric.cpp b/localization/autoware_ekf_localizer/test/test_numeric.cpp new file mode 100644 index 0000000000000..080ce01f31770 --- /dev/null +++ b/localization/autoware_ekf_localizer/test/test_numeric.cpp @@ -0,0 +1,54 @@ +// Copyright 2022 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/ekf_localizer/numeric.hpp" + +#include + +#include + +#include + +namespace autoware::ekf_localizer +{ + +TEST(Numeric, has_nan) +{ + const Eigen::VectorXd empty(0); + const double inf = std::numeric_limits::infinity(); + const double nan = std::nan(""); + + EXPECT_FALSE(has_nan(empty)); + EXPECT_FALSE(has_nan(Eigen::Vector3d(0., 0., 1.))); + EXPECT_FALSE(has_nan(Eigen::Vector3d(1e16, 0., 1.))); + EXPECT_FALSE(has_nan(Eigen::Vector3d(0., 1., inf))); + + EXPECT_TRUE(has_nan(Eigen::Vector3d(nan, 1., 0.))); +} + +TEST(Numeric, has_inf) +{ + const Eigen::VectorXd empty(0); + const double inf = std::numeric_limits::infinity(); + const double nan = std::nan(""); + + EXPECT_FALSE(has_inf(empty)); + EXPECT_FALSE(has_inf(Eigen::Vector3d(0., 0., 1.))); + EXPECT_FALSE(has_inf(Eigen::Vector3d(1e16, 0., 1.))); + EXPECT_FALSE(has_inf(Eigen::Vector3d(nan, 1., 0.))); + + EXPECT_TRUE(has_inf(Eigen::Vector3d(0., 1., inf))); +} + +} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/test/test_state_transition.cpp b/localization/autoware_ekf_localizer/test/test_state_transition.cpp new file mode 100644 index 0000000000000..667c6b5ef2df8 --- /dev/null +++ b/localization/autoware_ekf_localizer/test/test_state_transition.cpp @@ -0,0 +1,101 @@ +// Copyright 2018-2019 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#define _USE_MATH_DEFINES +#include "autoware/ekf_localizer/state_index.hpp" +#include "autoware/ekf_localizer/state_transition.hpp" + +#include + +#include + +namespace autoware::ekf_localizer +{ + +TEST(StateTransition, normalize_yaw) +{ + const double tolerance = 1e-6; + EXPECT_NEAR(normalize_yaw(M_PI * 4 / 3), -M_PI * 2 / 3, tolerance); + EXPECT_NEAR(normalize_yaw(-M_PI * 4 / 3), M_PI * 2 / 3, tolerance); + EXPECT_NEAR(normalize_yaw(M_PI * 9 / 2), M_PI * 1 / 2, tolerance); + EXPECT_NEAR(normalize_yaw(M_PI * 4), M_PI * 0, tolerance); +} + +TEST(predict_next_state, predict_next_state) +{ + // This function is the definition of state transition so we just check + // if the calculation is done according to the formula + Vector6d x_curr; + x_curr(0) = 2.; + x_curr(1) = 3.; + x_curr(2) = M_PI / 2.; + x_curr(3) = M_PI / 4.; + x_curr(4) = 10.; + x_curr(5) = 2. * M_PI / 3.; + + const double dt = 0.5; + + const Vector6d x_next = predict_next_state(x_curr, dt); + + const double tolerance = 1e-10; + EXPECT_NEAR(x_next(0), 2. + 10. * std::cos(M_PI / 2. + M_PI / 4.) * 0.5, tolerance); + EXPECT_NEAR(x_next(1), 3. + 10. * std::sin(M_PI / 2. + M_PI / 4.) * 0.5, tolerance); + EXPECT_NEAR(x_next(2), normalize_yaw(M_PI / 2. + M_PI / 3.), tolerance); + EXPECT_NEAR(x_next(3), x_curr(3), tolerance); + EXPECT_NEAR(x_next(4), x_curr(4), tolerance); + EXPECT_NEAR(x_next(5), x_curr(5), tolerance); +} + +TEST(create_state_transition_matrix, NumericalApproximation) +{ + // The transition matrix A = df / dx + // We check if df = A * dx approximates f(x + dx) - f(x) + + { + // check around x = 0 + const double dt = 0.1; + const Vector6d dx = 0.1 * Vector6d::Ones(); + const Vector6d x = Vector6d::Zero(); + + const Matrix6d a = create_state_transition_matrix(x, dt); + const Vector6d df = predict_next_state(x + dx, dt) - predict_next_state(x, dt); + + EXPECT_LT((df - a * dx).norm(), 2e-3); + } + + { + // check around random x + const double dt = 0.1; + const Vector6d dx = 0.1 * Vector6d::Ones(); + const Vector6d x = (Vector6d() << 0.1, 0.2, 0.1, 0.4, 0.1, 0.3).finished(); + + const Matrix6d a = create_state_transition_matrix(x, dt); + const Vector6d df = predict_next_state(x + dx, dt) - predict_next_state(x, dt); + + EXPECT_LT((df - a * dx).norm(), 5e-3); + } +} + +TEST(process_noise_covariance, process_noise_covariance) +{ + const Matrix6d q = process_noise_covariance(1., 2., 3.); + EXPECT_EQ(q(2, 2), 1.); // for yaw + EXPECT_EQ(q(4, 4), 2.); // for vx + EXPECT_EQ(q(5, 5), 3.); // for wz + + // Make sure other elements are zero + EXPECT_EQ(process_noise_covariance(0, 0, 0).norm(), 0.); +} + +} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/test/test_string.cpp b/localization/autoware_ekf_localizer/test/test_string.cpp new file mode 100644 index 0000000000000..b1fae1f88b74b --- /dev/null +++ b/localization/autoware_ekf_localizer/test/test_string.cpp @@ -0,0 +1,31 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/ekf_localizer/string.hpp" + +#include + +namespace autoware::ekf_localizer +{ + +TEST(erase_leading_slash, SmokeTest) +{ + EXPECT_EQ(erase_leading_slash("/topic"), "topic"); + EXPECT_EQ(erase_leading_slash("topic"), "topic"); // do nothing + + EXPECT_EQ(erase_leading_slash(""), ""); + EXPECT_EQ(erase_leading_slash("/"), ""); +} + +} // namespace autoware::ekf_localizer diff --git a/localization/autoware_ekf_localizer/test/test_warning_message.cpp b/localization/autoware_ekf_localizer/test/test_warning_message.cpp new file mode 100644 index 0000000000000..791e86c050352 --- /dev/null +++ b/localization/autoware_ekf_localizer/test/test_warning_message.cpp @@ -0,0 +1,67 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/ekf_localizer/warning_message.hpp" + +#include + +#include + +namespace autoware::ekf_localizer +{ + +TEST(pose_delay_step_warning_message, SmokeTest) +{ + EXPECT_STREQ( + pose_delay_step_warning_message(6.0, 4.0).c_str(), + "Pose delay exceeds the compensation limit, ignored. " + "delay: 6.000[s], limit: 4.000[s]"); +} + +TEST(twist_delay_step_warning_message, SmokeTest) +{ + EXPECT_STREQ( + twist_delay_step_warning_message(10.0, 6.0).c_str(), + "Twist delay exceeds the compensation limit, ignored. " + "delay: 10.000[s], limit: 6.000[s]"); +} + +TEST(pose_delay_time_warning_message, SmokeTest) +{ + EXPECT_STREQ( + pose_delay_time_warning_message(-1.0).c_str(), + "Pose time stamp is inappropriate, set delay to 0[s]. delay = -1.000"); + EXPECT_STREQ( + pose_delay_time_warning_message(-0.4).c_str(), + "Pose time stamp is inappropriate, set delay to 0[s]. delay = -0.400"); +} + +TEST(twist_delay_time_warning_message, SmokeTest) +{ + EXPECT_STREQ( + twist_delay_time_warning_message(-1.0).c_str(), + "Twist time stamp is inappropriate, set delay to 0[s]. delay = -1.000"); + EXPECT_STREQ( + twist_delay_time_warning_message(-0.4).c_str(), + "Twist time stamp is inappropriate, set delay to 0[s]. delay = -0.400"); +} + +TEST(mahalanobis_warning_message, SmokeTest) +{ + EXPECT_STREQ( + mahalanobis_warning_message(1.0, 0.5).c_str(), + "The Mahalanobis distance 1.0000 is over the limit 0.5000."); +} + +} // namespace autoware::ekf_localizer diff --git a/localization/autoware_pose_covariance_modifier/README.md b/localization/autoware_pose_covariance_modifier/README.md index 53cddbfa981c2..201fb8bb37103 100644 --- a/localization/autoware_pose_covariance_modifier/README.md +++ b/localization/autoware_pose_covariance_modifier/README.md @@ -118,7 +118,7 @@ the [pose_twist_estimator.launch.xml](../../launch/tier4_localization_launch/lau ### Without this condition (default) - The output of the [ndt_scan_matcher](../../localization/autoware_ndt_scan_matcher) is directly sent - to [ekf_localizer](https://github.com/autowarefoundation/autoware.core/tree/main/localization/autoware_ekf_localizer). + to [ekf_localizer](../../localization/autoware_ekf_localizer). - It has a preset covariance value. - **topic name:** `/localization/pose_estimator/pose_with_covariance` - The GNSS pose does not enter the ekf_localizer. @@ -130,7 +130,7 @@ the [pose_twist_estimator.launch.xml](../../launch/tier4_localization_launch/lau - **from:** `/localization/pose_estimator/pose_with_covariance`. - **to:** `/localization/pose_estimator/ndt_scan_matcher/pose_with_covariance`. - The `ndt_scan_matcher` output enters the `autoware_pose_covariance_modifier`. -- The output of this package goes to [ekf_localizer](https://github.com/autowarefoundation/autoware.core/tree/main/localization/autoware_ekf_localizer) with: +- The output of this package goes to [ekf_localizer](../../localization/autoware_ekf_localizer) with: - **topic name:** `/localization/pose_estimator/pose_with_covariance`. ## Node From d03152b5030a1fb5fe3562202cadff26d77149dd Mon Sep 17 00:00:00 2001 From: Junya Sasaki Date: Wed, 22 Jan 2025 16:35:10 +0900 Subject: [PATCH 283/334] feat: apply `autoware_` prefix for `bluetooth_monitor` (#9960) * feat(bluetooth_monitor): apply `autoware_` prefix (see below): * In this commit, I did not organize a folder structure. The folder structure will be organized in the next some commits. * The changes will follow the Autoware's guideline as below: - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder Signed-off-by: Junya Sasaki * rename(bluetooth_monitor): move headers under `include/autoware`: * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit Signed-off-by: Junya Sasaki * fix(bluetooth_monitor): fix include paths * To follow the previous commit Signed-off-by: Junya Sasaki * bug(bluetooth_monitor): fix a missing prefix bug Signed-off-by: Junya Sasaki * rename: `bluetooth_monitor` => `autoware_bluetooth_monitor` Signed-off-by: Junya Sasaki * style(pre-commit): autofix * bug(autoware_bluetooth_monitor): revert wrongly updated copyrights Signed-off-by: Junya Sasaki * bug(autoware_bluetooth_monitor): `autoware_` prefix is not needed here Signed-off-by: Junya Sasaki * update: `CODEOWNERS` Signed-off-by: Junya Sasaki * update(autoware_bluetooth_monitor): `README.md` Signed-off-by: Junya Sasaki --------- Signed-off-by: Junya Sasaki Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .github/CODEOWNERS | 2 +- .../CHANGELOG.rst | 0 .../CMakeLists.txt | 12 ++++++------ .../README.md | 4 ++-- .../config/bluetooth_monitor.param.yaml | 0 .../docs/block_diagram.drawio.svg | 0 .../bluetooth_monitor/bluetooth_monitor.hpp | 13 +++++++++---- .../bluetooth_monitor/service/l2ping.hpp | 13 +++++++++---- .../service/l2ping_interface.hpp | 11 ++++++++--- .../bluetooth_monitor/service/l2ping_service.hpp | 15 ++++++++++----- .../launch/bluetooth_monitor.launch.xml | 6 ++++++ .../package.xml | 3 ++- .../schema/bluetooth_monitor.schema.json | 0 .../service/l2ping.cpp | 7 ++++++- .../service/l2ping_service.cpp | 7 ++++++- .../service/main.cpp | 8 ++++---- .../src/bluetooth_monitor.cpp | 9 +++++++-- .../launch/bluetooth_monitor.launch.xml | 6 ------ 18 files changed, 76 insertions(+), 40 deletions(-) rename system/{bluetooth_monitor => autoware_bluetooth_monitor}/CHANGELOG.rst (100%) rename system/{bluetooth_monitor => autoware_bluetooth_monitor}/CMakeLists.txt (65%) rename system/{bluetooth_monitor => autoware_bluetooth_monitor}/README.md (94%) rename system/{bluetooth_monitor => autoware_bluetooth_monitor}/config/bluetooth_monitor.param.yaml (100%) rename system/{bluetooth_monitor => autoware_bluetooth_monitor}/docs/block_diagram.drawio.svg (100%) rename system/{bluetooth_monitor/include => autoware_bluetooth_monitor/include/autoware}/bluetooth_monitor/bluetooth_monitor.hpp (92%) rename system/{bluetooth_monitor/include => autoware_bluetooth_monitor/include/autoware}/bluetooth_monitor/service/l2ping.hpp (87%) rename system/{bluetooth_monitor/include => autoware_bluetooth_monitor/include/autoware}/bluetooth_monitor/service/l2ping_interface.hpp (94%) rename system/{bluetooth_monitor/include => autoware_bluetooth_monitor/include/autoware}/bluetooth_monitor/service/l2ping_service.hpp (85%) create mode 100644 system/autoware_bluetooth_monitor/launch/bluetooth_monitor.launch.xml rename system/{bluetooth_monitor => autoware_bluetooth_monitor}/package.xml (89%) rename system/{bluetooth_monitor => autoware_bluetooth_monitor}/schema/bluetooth_monitor.schema.json (100%) rename system/{bluetooth_monitor => autoware_bluetooth_monitor}/service/l2ping.cpp (96%) rename system/{bluetooth_monitor => autoware_bluetooth_monitor}/service/l2ping_service.cpp (97%) rename system/{bluetooth_monitor => autoware_bluetooth_monitor}/service/main.cpp (90%) rename system/{bluetooth_monitor => autoware_bluetooth_monitor}/src/bluetooth_monitor.cpp (96%) delete mode 100644 system/bluetooth_monitor/launch/bluetooth_monitor.launch.xml diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 7ee7e376111cc..0a7a3920b5f51 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -210,7 +210,7 @@ simulator/vehicle_door_simulator/** isamu.takagi@tier4.jp system/autoware_component_monitor/** baris@leodrive.ai memin@leodrive.ai yavuz@leodrive.ai system/autoware_default_adapi/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp system/autoware_processing_time_checker/** kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp -system/bluetooth_monitor/** fumihito.ito@tier4.jp +system/autoware_bluetooth_monitor/** fumihito.ito@tier4.jp junya.sasaki@tier4.jp system/component_state_monitor/** isamu.takagi@tier4.jp system/default_ad_api_helpers/ad_api_adaptors/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp system/default_ad_api_helpers/ad_api_visualizers/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp diff --git a/system/bluetooth_monitor/CHANGELOG.rst b/system/autoware_bluetooth_monitor/CHANGELOG.rst similarity index 100% rename from system/bluetooth_monitor/CHANGELOG.rst rename to system/autoware_bluetooth_monitor/CHANGELOG.rst diff --git a/system/bluetooth_monitor/CMakeLists.txt b/system/autoware_bluetooth_monitor/CMakeLists.txt similarity index 65% rename from system/bluetooth_monitor/CMakeLists.txt rename to system/autoware_bluetooth_monitor/CMakeLists.txt index ea91d77abeeb8..042f0ab9ada1b 100644 --- a/system/bluetooth_monitor/CMakeLists.txt +++ b/system/autoware_bluetooth_monitor/CMakeLists.txt @@ -1,11 +1,11 @@ cmake_minimum_required(VERSION 3.5) -project(bluetooth_monitor) +project(autoware_bluetooth_monitor) ### Dependencies find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_library(bluetooth_monitor_lib SHARED +ament_auto_add_library(${PROJECT_NAME} SHARED src/bluetooth_monitor.cpp ) @@ -21,12 +21,12 @@ find_package(Boost REQUIRED COMPONENTS ) ## Specify libraries to link a library or executable target against -target_link_libraries(bluetooth_monitor_lib ${Boost_LIBRARIES}) +target_link_libraries(${PROJECT_NAME} ${Boost_LIBRARIES}) target_link_libraries(l2ping_service ${Boost_LIBRARIES}) -rclcpp_components_register_node(bluetooth_monitor_lib - PLUGIN "BluetoothMonitor" - EXECUTABLE bluetooth_monitor +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "autoware::bluetooth_monitor::BluetoothMonitor" + EXECUTABLE ${PROJECT_NAME}_node ) ament_auto_package(INSTALL_TO_SHARE diff --git a/system/bluetooth_monitor/README.md b/system/autoware_bluetooth_monitor/README.md similarity index 94% rename from system/bluetooth_monitor/README.md rename to system/autoware_bluetooth_monitor/README.md index c0f9c3aecca98..a32069624e113 100644 --- a/system/bluetooth_monitor/README.md +++ b/system/autoware_bluetooth_monitor/README.md @@ -46,7 +46,7 @@ L2ping is only allowed for root by default, so this package provides the followi ## Parameters -{{ json_to_markdown("system/bluetooth_monitor/schema/bluetooth_monitor.schema.json") }} +{{ json_to_markdown("system/autoware_bluetooth_monitor/schema/bluetooth_monitor.schema.json") }} - `rtt_warn` @@ -71,7 +71,7 @@ L2ping is only allowed for root by default, so this package provides the followi ```sh ./build/bluetooth_monitor/l2ping_service - ros2 launch bluetooth_monitor bluetooth_monitor.launch.xml + ros2 launch autoware_bluetooth_monitor bluetooth_monitor.launch.xml ``` ## Known limitations and issues diff --git a/system/bluetooth_monitor/config/bluetooth_monitor.param.yaml b/system/autoware_bluetooth_monitor/config/bluetooth_monitor.param.yaml similarity index 100% rename from system/bluetooth_monitor/config/bluetooth_monitor.param.yaml rename to system/autoware_bluetooth_monitor/config/bluetooth_monitor.param.yaml diff --git a/system/bluetooth_monitor/docs/block_diagram.drawio.svg b/system/autoware_bluetooth_monitor/docs/block_diagram.drawio.svg similarity index 100% rename from system/bluetooth_monitor/docs/block_diagram.drawio.svg rename to system/autoware_bluetooth_monitor/docs/block_diagram.drawio.svg diff --git a/system/bluetooth_monitor/include/bluetooth_monitor/bluetooth_monitor.hpp b/system/autoware_bluetooth_monitor/include/autoware/bluetooth_monitor/bluetooth_monitor.hpp similarity index 92% rename from system/bluetooth_monitor/include/bluetooth_monitor/bluetooth_monitor.hpp rename to system/autoware_bluetooth_monitor/include/autoware/bluetooth_monitor/bluetooth_monitor.hpp index 6ebca9b4189d5..60f6ec1adc648 100644 --- a/system/bluetooth_monitor/include/bluetooth_monitor/bluetooth_monitor.hpp +++ b/system/autoware_bluetooth_monitor/include/autoware/bluetooth_monitor/bluetooth_monitor.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BLUETOOTH_MONITOR__BLUETOOTH_MONITOR_HPP_ -#define BLUETOOTH_MONITOR__BLUETOOTH_MONITOR_HPP_ +#ifndef AUTOWARE__BLUETOOTH_MONITOR__BLUETOOTH_MONITOR_HPP_ +#define AUTOWARE__BLUETOOTH_MONITOR__BLUETOOTH_MONITOR_HPP_ -#include "bluetooth_monitor/service/l2ping_interface.hpp" +#include "autoware/bluetooth_monitor/service/l2ping_interface.hpp" #include #include @@ -24,6 +24,9 @@ #include #include +namespace autoware::bluetooth_monitor +{ + class BluetoothMonitor : public rclcpp::Node { public: @@ -109,4 +112,6 @@ class BluetoothMonitor : public rclcpp::Node {StatusCode::FUNCTION_ERROR, DiagStatus::ERROR}}; }; -#endif // BLUETOOTH_MONITOR__BLUETOOTH_MONITOR_HPP_ +} // namespace autoware::bluetooth_monitor + +#endif // AUTOWARE__BLUETOOTH_MONITOR__BLUETOOTH_MONITOR_HPP_ diff --git a/system/bluetooth_monitor/include/bluetooth_monitor/service/l2ping.hpp b/system/autoware_bluetooth_monitor/include/autoware/bluetooth_monitor/service/l2ping.hpp similarity index 87% rename from system/bluetooth_monitor/include/bluetooth_monitor/service/l2ping.hpp rename to system/autoware_bluetooth_monitor/include/autoware/bluetooth_monitor/service/l2ping.hpp index 8d7777f78f743..5ff24f687f465 100644 --- a/system/bluetooth_monitor/include/bluetooth_monitor/service/l2ping.hpp +++ b/system/autoware_bluetooth_monitor/include/autoware/bluetooth_monitor/service/l2ping.hpp @@ -12,16 +12,19 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BLUETOOTH_MONITOR__SERVICE__L2PING_HPP_ -#define BLUETOOTH_MONITOR__SERVICE__L2PING_HPP_ +#ifndef AUTOWARE__BLUETOOTH_MONITOR__SERVICE__L2PING_HPP_ +#define AUTOWARE__BLUETOOTH_MONITOR__SERVICE__L2PING_HPP_ -#include "bluetooth_monitor/service/l2ping_interface.hpp" +#include "autoware/bluetooth_monitor/service/l2ping_interface.hpp" #include #include #include #include +namespace autoware::bluetooth_monitor +{ + class L2ping { public: @@ -92,4 +95,6 @@ class L2ping bool stop_; //!< @brief Flag to stop thread }; -#endif // BLUETOOTH_MONITOR__SERVICE__L2PING_HPP_ +} // namespace autoware::bluetooth_monitor + +#endif // AUTOWARE__BLUETOOTH_MONITOR__SERVICE__L2PING_HPP_ diff --git a/system/bluetooth_monitor/include/bluetooth_monitor/service/l2ping_interface.hpp b/system/autoware_bluetooth_monitor/include/autoware/bluetooth_monitor/service/l2ping_interface.hpp similarity index 94% rename from system/bluetooth_monitor/include/bluetooth_monitor/service/l2ping_interface.hpp rename to system/autoware_bluetooth_monitor/include/autoware/bluetooth_monitor/service/l2ping_interface.hpp index 26abc5c4b2ac4..f02f2cec12d27 100644 --- a/system/bluetooth_monitor/include/bluetooth_monitor/service/l2ping_interface.hpp +++ b/system/autoware_bluetooth_monitor/include/autoware/bluetooth_monitor/service/l2ping_interface.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BLUETOOTH_MONITOR__SERVICE__L2PING_INTERFACE_HPP_ -#define BLUETOOTH_MONITOR__SERVICE__L2PING_INTERFACE_HPP_ +#ifndef AUTOWARE__BLUETOOTH_MONITOR__SERVICE__L2PING_INTERFACE_HPP_ +#define AUTOWARE__BLUETOOTH_MONITOR__SERVICE__L2PING_INTERFACE_HPP_ #include #include @@ -23,6 +23,9 @@ #include #include +namespace autoware::bluetooth_monitor +{ + // 7634-7647 Unassigned static constexpr int DEFAULT_PORT = 7640; static constexpr int DEFAULT_DELAY = 1; @@ -171,4 +174,6 @@ struct L2pingStatus */ typedef std::vector L2pingStatusList; -#endif // BLUETOOTH_MONITOR__SERVICE__L2PING_INTERFACE_HPP_ +} // namespace autoware::bluetooth_monitor + +#endif // AUTOWARE__BLUETOOTH_MONITOR__SERVICE__L2PING_INTERFACE_HPP_ diff --git a/system/bluetooth_monitor/include/bluetooth_monitor/service/l2ping_service.hpp b/system/autoware_bluetooth_monitor/include/autoware/bluetooth_monitor/service/l2ping_service.hpp similarity index 85% rename from system/bluetooth_monitor/include/bluetooth_monitor/service/l2ping_service.hpp rename to system/autoware_bluetooth_monitor/include/autoware/bluetooth_monitor/service/l2ping_service.hpp index 2511311e8ba52..21a42718093b2 100644 --- a/system/bluetooth_monitor/include/bluetooth_monitor/service/l2ping_service.hpp +++ b/system/autoware_bluetooth_monitor/include/autoware/bluetooth_monitor/service/l2ping_service.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BLUETOOTH_MONITOR__SERVICE__L2PING_SERVICE_HPP_ -#define BLUETOOTH_MONITOR__SERVICE__L2PING_SERVICE_HPP_ +#ifndef AUTOWARE__BLUETOOTH_MONITOR__SERVICE__L2PING_SERVICE_HPP_ +#define AUTOWARE__BLUETOOTH_MONITOR__SERVICE__L2PING_SERVICE_HPP_ -#include "bluetooth_monitor/service/l2ping.hpp" -#include "bluetooth_monitor/service/l2ping_interface.hpp" +#include "autoware/bluetooth_monitor/service/l2ping.hpp" +#include "autoware/bluetooth_monitor/service/l2ping_interface.hpp" #include #include @@ -24,6 +24,9 @@ #include #include +namespace autoware::bluetooth_monitor +{ + class L2pingService { public: @@ -85,4 +88,6 @@ class L2pingService L2pingStatusList status_list_; //!< @brief List of l2ping status }; -#endif // BLUETOOTH_MONITOR__SERVICE__L2PING_SERVICE_HPP_ +} // namespace autoware::bluetooth_monitor + +#endif // AUTOWARE__BLUETOOTH_MONITOR__SERVICE__L2PING_SERVICE_HPP_ diff --git a/system/autoware_bluetooth_monitor/launch/bluetooth_monitor.launch.xml b/system/autoware_bluetooth_monitor/launch/bluetooth_monitor.launch.xml new file mode 100644 index 0000000000000..d23e7b44d3a32 --- /dev/null +++ b/system/autoware_bluetooth_monitor/launch/bluetooth_monitor.launch.xml @@ -0,0 +1,6 @@ + + + + + + diff --git a/system/bluetooth_monitor/package.xml b/system/autoware_bluetooth_monitor/package.xml similarity index 89% rename from system/bluetooth_monitor/package.xml rename to system/autoware_bluetooth_monitor/package.xml index f43db39e987b7..8f5c8d2d6ab77 100644 --- a/system/bluetooth_monitor/package.xml +++ b/system/autoware_bluetooth_monitor/package.xml @@ -1,10 +1,11 @@ - bluetooth_monitor + autoware_bluetooth_monitor 0.40.0 Bluetooth alive monitoring Fumihito Ito + Junya Sasaki Apache License 2.0 ament_cmake_auto diff --git a/system/bluetooth_monitor/schema/bluetooth_monitor.schema.json b/system/autoware_bluetooth_monitor/schema/bluetooth_monitor.schema.json similarity index 100% rename from system/bluetooth_monitor/schema/bluetooth_monitor.schema.json rename to system/autoware_bluetooth_monitor/schema/bluetooth_monitor.schema.json diff --git a/system/bluetooth_monitor/service/l2ping.cpp b/system/autoware_bluetooth_monitor/service/l2ping.cpp similarity index 96% rename from system/bluetooth_monitor/service/l2ping.cpp rename to system/autoware_bluetooth_monitor/service/l2ping.cpp index 6499f3a2b9612..4911825e5bf04 100644 --- a/system/bluetooth_monitor/service/l2ping.cpp +++ b/system/autoware_bluetooth_monitor/service/l2ping.cpp @@ -13,7 +13,7 @@ // limitations under the License. // -#include "bluetooth_monitor/service/l2ping.hpp" +#include "autoware/bluetooth_monitor/service/l2ping.hpp" #include @@ -25,6 +25,9 @@ #define FMT_HEADER_ONLY #include +namespace autoware::bluetooth_monitor +{ + namespace bp = boost::process; L2ping::L2ping(const std::string & address, const L2pingConfig & config) @@ -189,3 +192,5 @@ const std::string & L2ping::getAddress() const { return status_.address; } + +} // namespace autoware::bluetooth_monitor diff --git a/system/bluetooth_monitor/service/l2ping_service.cpp b/system/autoware_bluetooth_monitor/service/l2ping_service.cpp similarity index 97% rename from system/bluetooth_monitor/service/l2ping_service.cpp rename to system/autoware_bluetooth_monitor/service/l2ping_service.cpp index 827a7e3060acc..20bb6104692af 100644 --- a/system/bluetooth_monitor/service/l2ping_service.cpp +++ b/system/autoware_bluetooth_monitor/service/l2ping_service.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "bluetooth_monitor/service/l2ping_service.hpp" +#include "autoware/bluetooth_monitor/service/l2ping_service.hpp" #include #include @@ -30,6 +30,9 @@ #define FMT_HEADER_ONLY #include +namespace autoware::bluetooth_monitor +{ + namespace bp = boost::process; L2pingService::L2pingService(const int port) : port_(port), socket_(-1) @@ -252,3 +255,5 @@ bool L2pingService::buildDeviceList() return true; } + +} // namespace autoware::bluetooth_monitor diff --git a/system/bluetooth_monitor/service/main.cpp b/system/autoware_bluetooth_monitor/service/main.cpp similarity index 90% rename from system/bluetooth_monitor/service/main.cpp rename to system/autoware_bluetooth_monitor/service/main.cpp index d3aef2c0696dd..eb2bd5f3d5cc0 100644 --- a/system/bluetooth_monitor/service/main.cpp +++ b/system/autoware_bluetooth_monitor/service/main.cpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "bluetooth_monitor/service/l2ping_interface.hpp" -#include "bluetooth_monitor/service/l2ping_service.hpp" +#include "autoware/bluetooth_monitor/service/l2ping_interface.hpp" +#include "autoware/bluetooth_monitor/service/l2ping_service.hpp" #include @@ -47,7 +47,7 @@ int main(int argc, char ** argv) // Parse command-line options int c = 0; int option_index = 0; - int port = DEFAULT_PORT; + int port = autoware::bluetooth_monitor::DEFAULT_PORT; while ((c = getopt_long(argc, argv, "hp:", long_options, &option_index)) != -1) { switch (c) { case 'h': @@ -78,7 +78,7 @@ int main(int argc, char ** argv) openlog(nullptr, LOG_PID, LOG_DAEMON); // Initialize l2ping service - L2pingService service(port); + autoware::bluetooth_monitor::L2pingService service(port); if (!service.initialize()) { service.shutdown(); diff --git a/system/bluetooth_monitor/src/bluetooth_monitor.cpp b/system/autoware_bluetooth_monitor/src/bluetooth_monitor.cpp similarity index 96% rename from system/bluetooth_monitor/src/bluetooth_monitor.cpp rename to system/autoware_bluetooth_monitor/src/bluetooth_monitor.cpp index b9c74870c558d..e9fcb56d41622 100644 --- a/system/bluetooth_monitor/src/bluetooth_monitor.cpp +++ b/system/autoware_bluetooth_monitor/src/bluetooth_monitor.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "bluetooth_monitor/bluetooth_monitor.hpp" +#include "autoware/bluetooth_monitor/bluetooth_monitor.hpp" #include #include @@ -28,6 +28,9 @@ #define FMT_HEADER_ONLY #include +namespace autoware::bluetooth_monitor +{ + BluetoothMonitor::BluetoothMonitor(const rclcpp::NodeOptions & options) : Node("bluetooth_monitor", options), updater_(this), @@ -199,5 +202,7 @@ void BluetoothMonitor::checkConnection(diagnostic_updater::DiagnosticStatusWrapp setErrorLevel(stat); } +} // namespace autoware::bluetooth_monitor + #include -RCLCPP_COMPONENTS_REGISTER_NODE(BluetoothMonitor) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::bluetooth_monitor::BluetoothMonitor) diff --git a/system/bluetooth_monitor/launch/bluetooth_monitor.launch.xml b/system/bluetooth_monitor/launch/bluetooth_monitor.launch.xml deleted file mode 100644 index 7dd98572e544b..0000000000000 --- a/system/bluetooth_monitor/launch/bluetooth_monitor.launch.xml +++ /dev/null @@ -1,6 +0,0 @@ - - - - - - From 8418ae94321955b6f4069e3de10f6073dccdb088 Mon Sep 17 00:00:00 2001 From: Junya Sasaki Date: Wed, 22 Jan 2025 16:56:49 +0900 Subject: [PATCH 284/334] feat: apply `autoware_` prefix for `perception_online_evaluator` (#9956) * feat(perception_online_evaluator): apply `autoware_` prefix (see below): * In this commit, I did not organize a folder structure. The folder structure will be organized in the next some commits. * The changes will follow the Autoware's guideline as below: - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder Signed-off-by: Junya Sasaki * bug(perception_online_evaluator): remove duplicated properties * It seems the `motion_evaluator` is defined and used in the `autoware_planning_evaluator` Signed-off-by: Junya Sasaki * rename(perception_online_evaluator): move headers under `include/autoware`: * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit Signed-off-by: Junya Sasaki * fix(perception_online_evaluator): fix include paths * To follow the previous commit Signed-off-by: Junya Sasaki * rename: `perception_online_evaluator` => `autoware_perception_online_evaluator` Signed-off-by: Junya Sasaki * style(pre-commit): autofix * bug(autoware_perception_online_evaluator): revert wrongly updated copyright Signed-off-by: Junya Sasaki * bug(autoware_perception_online_evaluator): `autoware_` prefix is not needed here Signed-off-by: Junya Sasaki * update: `CODEOWNERS` Signed-off-by: Junya Sasaki * bug(autoware_perception_online_evaluator): fix a wrong package name Signed-off-by: Junya Sasaki --------- Signed-off-by: Junya Sasaki Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .github/CODEOWNERS | 2 +- .../CHANGELOG.rst | 0 .../CMakeLists.txt | 39 ++++++++++++++++ .../README.md | 0 .../images/detection_counts.drawio.svg | 0 .../images/lateral_deviation.drawio.svg | 0 .../images/path_deviation.drawio.svg | 0 .../path_deviation_each_object.drawio.svg | 0 .../images/yaw_deviation.drawio.svg | 0 .../images/yaw_rate.drawio.svg | 0 .../metrics/detection_count.hpp | 12 ++--- .../metrics/deviation_metrics.hpp | 10 ++--- .../metrics/metric.hpp | 10 ++--- .../metrics_calculator.hpp | 22 +++++----- .../parameters.hpp | 12 ++--- .../perception_online_evaluator_node.hpp | 14 +++--- .../utils/marker_utils.hpp | 10 ++--- .../utils/objects_filtering.hpp | 12 ++--- .../perception_online_evaluator.launch.xml | 4 +- .../package.xml | 3 +- .../perception_online_evaluator.defaults.yaml | 0 .../src/metrics/detection_count.cpp | 8 ++-- .../src/metrics/deviation_metrics.cpp | 6 +-- .../src/metrics_calculator.cpp | 6 +-- .../src/perception_online_evaluator_node.cpp | 10 ++--- .../src/utils/marker_utils.cpp | 6 +-- .../src/utils/objects_filtering.cpp | 6 +-- .../test_perception_online_evaluator_node.cpp | 10 ++--- .../CMakeLists.txt | 44 ------------------- .../launch/motion_evaluator.launch.xml | 7 --- 30 files changed, 121 insertions(+), 132 deletions(-) rename evaluator/{perception_online_evaluator => autoware_perception_online_evaluator}/CHANGELOG.rst (100%) create mode 100644 evaluator/autoware_perception_online_evaluator/CMakeLists.txt rename evaluator/{perception_online_evaluator => autoware_perception_online_evaluator}/README.md (100%) rename evaluator/{perception_online_evaluator => autoware_perception_online_evaluator}/images/detection_counts.drawio.svg (100%) rename evaluator/{perception_online_evaluator => autoware_perception_online_evaluator}/images/lateral_deviation.drawio.svg (100%) rename evaluator/{perception_online_evaluator => autoware_perception_online_evaluator}/images/path_deviation.drawio.svg (100%) rename evaluator/{perception_online_evaluator => autoware_perception_online_evaluator}/images/path_deviation_each_object.drawio.svg (100%) rename evaluator/{perception_online_evaluator => autoware_perception_online_evaluator}/images/yaw_deviation.drawio.svg (100%) rename evaluator/{perception_online_evaluator => autoware_perception_online_evaluator}/images/yaw_rate.drawio.svg (100%) rename evaluator/{perception_online_evaluator/include => autoware_perception_online_evaluator/include/autoware}/perception_online_evaluator/metrics/detection_count.hpp (92%) rename evaluator/{perception_online_evaluator/include => autoware_perception_online_evaluator/include/autoware}/perception_online_evaluator/metrics/deviation_metrics.hpp (81%) rename evaluator/{perception_online_evaluator/include => autoware_perception_online_evaluator/include/autoware}/perception_online_evaluator/metrics/metric.hpp (90%) rename evaluator/{perception_online_evaluator/include => autoware_perception_online_evaluator/include/autoware}/perception_online_evaluator/metrics_calculator.hpp (89%) rename evaluator/{perception_online_evaluator/include => autoware_perception_online_evaluator/include/autoware}/perception_online_evaluator/parameters.hpp (84%) rename evaluator/{perception_online_evaluator/include => autoware_perception_online_evaluator/include/autoware}/perception_online_evaluator/perception_online_evaluator_node.hpp (87%) rename evaluator/{perception_online_evaluator/include => autoware_perception_online_evaluator/include/autoware}/perception_online_evaluator/utils/marker_utils.hpp (89%) rename evaluator/{perception_online_evaluator/include => autoware_perception_online_evaluator/include/autoware}/perception_online_evaluator/utils/objects_filtering.hpp (94%) rename evaluator/{perception_online_evaluator => autoware_perception_online_evaluator}/launch/perception_online_evaluator.launch.xml (63%) rename evaluator/{perception_online_evaluator => autoware_perception_online_evaluator}/package.xml (93%) rename evaluator/{perception_online_evaluator => autoware_perception_online_evaluator}/param/perception_online_evaluator.defaults.yaml (100%) rename evaluator/{perception_online_evaluator => autoware_perception_online_evaluator}/src/metrics/detection_count.cpp (97%) rename evaluator/{perception_online_evaluator => autoware_perception_online_evaluator}/src/metrics/deviation_metrics.cpp (90%) rename evaluator/{perception_online_evaluator => autoware_perception_online_evaluator}/src/metrics_calculator.cpp (99%) rename evaluator/{perception_online_evaluator => autoware_perception_online_evaluator}/src/perception_online_evaluator_node.cpp (97%) rename evaluator/{perception_online_evaluator => autoware_perception_online_evaluator}/src/utils/marker_utils.cpp (97%) rename evaluator/{perception_online_evaluator => autoware_perception_online_evaluator}/src/utils/objects_filtering.cpp (95%) rename evaluator/{perception_online_evaluator => autoware_perception_online_evaluator}/test/test_perception_online_evaluator_node.cpp (99%) delete mode 100644 evaluator/perception_online_evaluator/CMakeLists.txt delete mode 100644 evaluator/perception_online_evaluator/launch/motion_evaluator.launch.xml diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 0a7a3920b5f51..26d86e98018c3 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -51,7 +51,7 @@ evaluator/autoware_control_evaluator/** daniel.sanchez@tier4.jp kosuke.takeuchi@ evaluator/autoware_planning_evaluator/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp temkei.kem@tier4.jp evaluator/kinematic_evaluator/** dominik.jargot@robotec.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp evaluator/localization_evaluator/** anh.nguyen.2@tier4.jp dominik.jargot@robotec.ai koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp -evaluator/perception_online_evaluator/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp kotaro.uetake@tier4.jp kyoichi.sugahara@tier4.jp shunsuke.miura@tier4.jp yoshi.ri@tier4.jp +evaluator/autoware_perception_online_evaluator/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp kotaro.uetake@tier4.jp kyoichi.sugahara@tier4.jp shunsuke.miura@tier4.jp yoshi.ri@tier4.jp junya.sasaki@tier4.jp evaluator/scenario_simulator_v2_adapter/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp takamasa.horibe@tier4.jp temkei.kem@tier4.jp launch/tier4_autoware_api_launch/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp launch/tier4_control_launch/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp diff --git a/evaluator/perception_online_evaluator/CHANGELOG.rst b/evaluator/autoware_perception_online_evaluator/CHANGELOG.rst similarity index 100% rename from evaluator/perception_online_evaluator/CHANGELOG.rst rename to evaluator/autoware_perception_online_evaluator/CHANGELOG.rst diff --git a/evaluator/autoware_perception_online_evaluator/CMakeLists.txt b/evaluator/autoware_perception_online_evaluator/CMakeLists.txt new file mode 100644 index 0000000000000..cddc59e1a91c6 --- /dev/null +++ b/evaluator/autoware_perception_online_evaluator/CMakeLists.txt @@ -0,0 +1,39 @@ +cmake_minimum_required(VERSION 3.14) +project(autoware_perception_online_evaluator) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +find_package(pluginlib REQUIRED) + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/metrics_calculator.cpp + src/perception_online_evaluator_node.cpp + src/metrics/deviation_metrics.cpp + src/metrics/detection_count.cpp + src/utils/marker_utils.cpp + src/utils/objects_filtering.cpp +) + +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "autoware::perception_diagnostics::PerceptionOnlineEvaluatorNode" + EXECUTABLE ${PROJECT_NAME}_node +) + +target_link_libraries(${PROJECT_NAME} glog::glog) + +if(BUILD_TESTING) + ament_add_ros_isolated_gtest(test_perception_online_evaluator_node + test/test_perception_online_evaluator_node.cpp + TIMEOUT 300 + ) + target_link_libraries(test_perception_online_evaluator_node + ${PROJECT_NAME} + ) +endif() + +ament_auto_package( + INSTALL_TO_SHARE + param + launch +) diff --git a/evaluator/perception_online_evaluator/README.md b/evaluator/autoware_perception_online_evaluator/README.md similarity index 100% rename from evaluator/perception_online_evaluator/README.md rename to evaluator/autoware_perception_online_evaluator/README.md diff --git a/evaluator/perception_online_evaluator/images/detection_counts.drawio.svg b/evaluator/autoware_perception_online_evaluator/images/detection_counts.drawio.svg similarity index 100% rename from evaluator/perception_online_evaluator/images/detection_counts.drawio.svg rename to evaluator/autoware_perception_online_evaluator/images/detection_counts.drawio.svg diff --git a/evaluator/perception_online_evaluator/images/lateral_deviation.drawio.svg b/evaluator/autoware_perception_online_evaluator/images/lateral_deviation.drawio.svg similarity index 100% rename from evaluator/perception_online_evaluator/images/lateral_deviation.drawio.svg rename to evaluator/autoware_perception_online_evaluator/images/lateral_deviation.drawio.svg diff --git a/evaluator/perception_online_evaluator/images/path_deviation.drawio.svg b/evaluator/autoware_perception_online_evaluator/images/path_deviation.drawio.svg similarity index 100% rename from evaluator/perception_online_evaluator/images/path_deviation.drawio.svg rename to evaluator/autoware_perception_online_evaluator/images/path_deviation.drawio.svg diff --git a/evaluator/perception_online_evaluator/images/path_deviation_each_object.drawio.svg b/evaluator/autoware_perception_online_evaluator/images/path_deviation_each_object.drawio.svg similarity index 100% rename from evaluator/perception_online_evaluator/images/path_deviation_each_object.drawio.svg rename to evaluator/autoware_perception_online_evaluator/images/path_deviation_each_object.drawio.svg diff --git a/evaluator/perception_online_evaluator/images/yaw_deviation.drawio.svg b/evaluator/autoware_perception_online_evaluator/images/yaw_deviation.drawio.svg similarity index 100% rename from evaluator/perception_online_evaluator/images/yaw_deviation.drawio.svg rename to evaluator/autoware_perception_online_evaluator/images/yaw_deviation.drawio.svg diff --git a/evaluator/perception_online_evaluator/images/yaw_rate.drawio.svg b/evaluator/autoware_perception_online_evaluator/images/yaw_rate.drawio.svg similarity index 100% rename from evaluator/perception_online_evaluator/images/yaw_rate.drawio.svg rename to evaluator/autoware_perception_online_evaluator/images/yaw_rate.drawio.svg diff --git a/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/detection_count.hpp b/evaluator/autoware_perception_online_evaluator/include/autoware/perception_online_evaluator/metrics/detection_count.hpp similarity index 92% rename from evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/detection_count.hpp rename to evaluator/autoware_perception_online_evaluator/include/autoware/perception_online_evaluator/metrics/detection_count.hpp index c111a725a2ea0..33a4353fc5c4a 100644 --- a/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/detection_count.hpp +++ b/evaluator/autoware_perception_online_evaluator/include/autoware/perception_online_evaluator/metrics/detection_count.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PERCEPTION_ONLINE_EVALUATOR__METRICS__DETECTION_COUNT_HPP_ -#define PERCEPTION_ONLINE_EVALUATOR__METRICS__DETECTION_COUNT_HPP_ +#ifndef AUTOWARE__PERCEPTION_ONLINE_EVALUATOR__METRICS__DETECTION_COUNT_HPP_ +#define AUTOWARE__PERCEPTION_ONLINE_EVALUATOR__METRICS__DETECTION_COUNT_HPP_ -#include "perception_online_evaluator/parameters.hpp" +#include "autoware/perception_online_evaluator/parameters.hpp" #include "tf2_ros/buffer.h" #include @@ -32,7 +32,7 @@ #include #include -namespace perception_diagnostics +namespace autoware::perception_diagnostics { namespace metrics { @@ -143,6 +143,6 @@ class DetectionCounter seen_uuids_; }; } // namespace metrics -} // namespace perception_diagnostics +} // namespace autoware::perception_diagnostics -#endif // PERCEPTION_ONLINE_EVALUATOR__METRICS__DETECTION_COUNT_HPP_ +#endif // AUTOWARE__PERCEPTION_ONLINE_EVALUATOR__METRICS__DETECTION_COUNT_HPP_ diff --git a/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/deviation_metrics.hpp b/evaluator/autoware_perception_online_evaluator/include/autoware/perception_online_evaluator/metrics/deviation_metrics.hpp similarity index 81% rename from evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/deviation_metrics.hpp rename to evaluator/autoware_perception_online_evaluator/include/autoware/perception_online_evaluator/metrics/deviation_metrics.hpp index 0f3379b3f055e..90256ce18110f 100644 --- a/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/deviation_metrics.hpp +++ b/evaluator/autoware_perception_online_evaluator/include/autoware/perception_online_evaluator/metrics/deviation_metrics.hpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PERCEPTION_ONLINE_EVALUATOR__METRICS__DEVIATION_METRICS_HPP_ -#define PERCEPTION_ONLINE_EVALUATOR__METRICS__DEVIATION_METRICS_HPP_ +#ifndef AUTOWARE__PERCEPTION_ONLINE_EVALUATOR__METRICS__DEVIATION_METRICS_HPP_ +#define AUTOWARE__PERCEPTION_ONLINE_EVALUATOR__METRICS__DEVIATION_METRICS_HPP_ #include #include #include -namespace perception_diagnostics +namespace autoware::perception_diagnostics { namespace metrics { @@ -44,6 +44,6 @@ double calcLateralDeviation(const std::vector & ref_path, const Pose & tar double calcYawDeviation(const std::vector & ref_path, const Pose & target_pose); } // namespace metrics -} // namespace perception_diagnostics +} // namespace autoware::perception_diagnostics -#endif // PERCEPTION_ONLINE_EVALUATOR__METRICS__DEVIATION_METRICS_HPP_ +#endif // AUTOWARE__PERCEPTION_ONLINE_EVALUATOR__METRICS__DEVIATION_METRICS_HPP_ diff --git a/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/metric.hpp b/evaluator/autoware_perception_online_evaluator/include/autoware/perception_online_evaluator/metrics/metric.hpp similarity index 90% rename from evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/metric.hpp rename to evaluator/autoware_perception_online_evaluator/include/autoware/perception_online_evaluator/metrics/metric.hpp index 4caf932919e61..c190af8162ebf 100644 --- a/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/metric.hpp +++ b/evaluator/autoware_perception_online_evaluator/include/autoware/perception_online_evaluator/metrics/metric.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PERCEPTION_ONLINE_EVALUATOR__METRICS__METRIC_HPP_ -#define PERCEPTION_ONLINE_EVALUATOR__METRICS__METRIC_HPP_ +#ifndef AUTOWARE__PERCEPTION_ONLINE_EVALUATOR__METRICS__METRIC_HPP_ +#define AUTOWARE__PERCEPTION_ONLINE_EVALUATOR__METRICS__METRIC_HPP_ #include "autoware/universe_utils/math/accumulator.hpp" @@ -23,7 +23,7 @@ #include #include -namespace perception_diagnostics +namespace autoware::perception_diagnostics { /** * @brief Enumeration of trajectory metrics @@ -90,6 +90,6 @@ static struct CheckCorrectMaps } check; } // namespace details -} // namespace perception_diagnostics +} // namespace autoware::perception_diagnostics -#endif // PERCEPTION_ONLINE_EVALUATOR__METRICS__METRIC_HPP_ +#endif // AUTOWARE__PERCEPTION_ONLINE_EVALUATOR__METRICS__METRIC_HPP_ diff --git a/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics_calculator.hpp b/evaluator/autoware_perception_online_evaluator/include/autoware/perception_online_evaluator/metrics_calculator.hpp similarity index 89% rename from evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics_calculator.hpp rename to evaluator/autoware_perception_online_evaluator/include/autoware/perception_online_evaluator/metrics_calculator.hpp index c17051d2a30a7..b59f0a6c32b3d 100644 --- a/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics_calculator.hpp +++ b/evaluator/autoware_perception_online_evaluator/include/autoware/perception_online_evaluator/metrics_calculator.hpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PERCEPTION_ONLINE_EVALUATOR__METRICS_CALCULATOR_HPP_ -#define PERCEPTION_ONLINE_EVALUATOR__METRICS_CALCULATOR_HPP_ - -#include "perception_online_evaluator/metrics/detection_count.hpp" -#include "perception_online_evaluator/metrics/deviation_metrics.hpp" -#include "perception_online_evaluator/metrics/metric.hpp" -#include "perception_online_evaluator/parameters.hpp" -#include "perception_online_evaluator/utils/objects_filtering.hpp" +#ifndef AUTOWARE__PERCEPTION_ONLINE_EVALUATOR__METRICS_CALCULATOR_HPP_ +#define AUTOWARE__PERCEPTION_ONLINE_EVALUATOR__METRICS_CALCULATOR_HPP_ + +#include "autoware/perception_online_evaluator/metrics/detection_count.hpp" +#include "autoware/perception_online_evaluator/metrics/deviation_metrics.hpp" +#include "autoware/perception_online_evaluator/metrics/metric.hpp" +#include "autoware/perception_online_evaluator/parameters.hpp" +#include "autoware/perception_online_evaluator/utils/objects_filtering.hpp" #include "tf2_ros/buffer.h" #include @@ -38,7 +38,7 @@ #include #include -namespace perception_diagnostics +namespace autoware::perception_diagnostics { using autoware_perception_msgs::msg::PredictedObject; using autoware_perception_msgs::msg::PredictedObjects; @@ -160,6 +160,6 @@ class MetricsCalculator }; // class MetricsCalculator -} // namespace perception_diagnostics +} // namespace autoware::perception_diagnostics -#endif // PERCEPTION_ONLINE_EVALUATOR__METRICS_CALCULATOR_HPP_ +#endif // AUTOWARE__PERCEPTION_ONLINE_EVALUATOR__METRICS_CALCULATOR_HPP_ diff --git a/evaluator/perception_online_evaluator/include/perception_online_evaluator/parameters.hpp b/evaluator/autoware_perception_online_evaluator/include/autoware/perception_online_evaluator/parameters.hpp similarity index 84% rename from evaluator/perception_online_evaluator/include/perception_online_evaluator/parameters.hpp rename to evaluator/autoware_perception_online_evaluator/include/autoware/perception_online_evaluator/parameters.hpp index b4cf23b85effb..5c53332b0a003 100644 --- a/evaluator/perception_online_evaluator/include/perception_online_evaluator/parameters.hpp +++ b/evaluator/autoware_perception_online_evaluator/include/autoware/perception_online_evaluator/parameters.hpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PERCEPTION_ONLINE_EVALUATOR__PARAMETERS_HPP_ -#define PERCEPTION_ONLINE_EVALUATOR__PARAMETERS_HPP_ +#ifndef AUTOWARE__PERCEPTION_ONLINE_EVALUATOR__PARAMETERS_HPP_ +#define AUTOWARE__PERCEPTION_ONLINE_EVALUATOR__PARAMETERS_HPP_ -#include "perception_online_evaluator/metrics/metric.hpp" +#include "autoware/perception_online_evaluator/metrics/metric.hpp" #include #include -namespace perception_diagnostics +namespace autoware::perception_diagnostics { /** * @brief Enumeration of perception metrics @@ -64,6 +64,6 @@ struct Parameters std::unordered_map object_parameters; }; -} // namespace perception_diagnostics +} // namespace autoware::perception_diagnostics -#endif // PERCEPTION_ONLINE_EVALUATOR__PARAMETERS_HPP_ +#endif // AUTOWARE__PERCEPTION_ONLINE_EVALUATOR__PARAMETERS_HPP_ diff --git a/evaluator/perception_online_evaluator/include/perception_online_evaluator/perception_online_evaluator_node.hpp b/evaluator/autoware_perception_online_evaluator/include/autoware/perception_online_evaluator/perception_online_evaluator_node.hpp similarity index 87% rename from evaluator/perception_online_evaluator/include/perception_online_evaluator/perception_online_evaluator_node.hpp rename to evaluator/autoware_perception_online_evaluator/include/autoware/perception_online_evaluator/perception_online_evaluator_node.hpp index 61c1ba40134df..62e4d14af63e0 100644 --- a/evaluator/perception_online_evaluator/include/perception_online_evaluator/perception_online_evaluator_node.hpp +++ b/evaluator/autoware_perception_online_evaluator/include/autoware/perception_online_evaluator/perception_online_evaluator_node.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PERCEPTION_ONLINE_EVALUATOR__PERCEPTION_ONLINE_EVALUATOR_NODE_HPP_ -#define PERCEPTION_ONLINE_EVALUATOR__PERCEPTION_ONLINE_EVALUATOR_NODE_HPP_ +#ifndef AUTOWARE__PERCEPTION_ONLINE_EVALUATOR__PERCEPTION_ONLINE_EVALUATOR_NODE_HPP_ +#define AUTOWARE__PERCEPTION_ONLINE_EVALUATOR__PERCEPTION_ONLINE_EVALUATOR_NODE_HPP_ +#include "autoware/perception_online_evaluator/metrics_calculator.hpp" +#include "autoware/perception_online_evaluator/parameters.hpp" #include "autoware/universe_utils/math/accumulator.hpp" -#include "perception_online_evaluator/metrics_calculator.hpp" -#include "perception_online_evaluator/parameters.hpp" #include "rclcpp/rclcpp.hpp" #include "tf2_ros/buffer.h" #include "tf2_ros/transform_listener.h" @@ -34,7 +34,7 @@ #include #include -namespace perception_diagnostics +namespace autoware::perception_diagnostics { using autoware::universe_utils::Accumulator; using autoware_perception_msgs::msg::ObjectClassification; @@ -108,6 +108,6 @@ class PerceptionOnlineEvaluatorNode : public rclcpp::Node // Debug void publishDebugMarker(); }; -} // namespace perception_diagnostics +} // namespace autoware::perception_diagnostics -#endif // PERCEPTION_ONLINE_EVALUATOR__PERCEPTION_ONLINE_EVALUATOR_NODE_HPP_ +#endif // AUTOWARE__PERCEPTION_ONLINE_EVALUATOR__PERCEPTION_ONLINE_EVALUATOR_NODE_HPP_ diff --git a/evaluator/perception_online_evaluator/include/perception_online_evaluator/utils/marker_utils.hpp b/evaluator/autoware_perception_online_evaluator/include/autoware/perception_online_evaluator/utils/marker_utils.hpp similarity index 89% rename from evaluator/perception_online_evaluator/include/perception_online_evaluator/utils/marker_utils.hpp rename to evaluator/autoware_perception_online_evaluator/include/autoware/perception_online_evaluator/utils/marker_utils.hpp index 0ad0872723d55..ad849acd23956 100644 --- a/evaluator/perception_online_evaluator/include/perception_online_evaluator/utils/marker_utils.hpp +++ b/evaluator/autoware_perception_online_evaluator/include/autoware/perception_online_evaluator/utils/marker_utils.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PERCEPTION_ONLINE_EVALUATOR__UTILS__MARKER_UTILS_HPP_ -#define PERCEPTION_ONLINE_EVALUATOR__UTILS__MARKER_UTILS_HPP_ +#ifndef AUTOWARE__PERCEPTION_ONLINE_EVALUATOR__UTILS__MARKER_UTILS_HPP_ +#define AUTOWARE__PERCEPTION_ONLINE_EVALUATOR__UTILS__MARKER_UTILS_HPP_ #include @@ -27,7 +27,7 @@ #include #include -namespace marker_utils +namespace autoware::perception_diagnostics::marker_utils { using autoware::universe_utils::Polygon2d; @@ -77,6 +77,6 @@ MarkerArray createDeviationLines( const std::vector & poses1, const std::vector & poses2, const std::string & ns, const int32_t & first_id, const float r, const float g, const float b); -} // namespace marker_utils +} // namespace autoware::perception_diagnostics::marker_utils -#endif // PERCEPTION_ONLINE_EVALUATOR__UTILS__MARKER_UTILS_HPP_ +#endif // AUTOWARE__PERCEPTION_ONLINE_EVALUATOR__UTILS__MARKER_UTILS_HPP_ diff --git a/evaluator/perception_online_evaluator/include/perception_online_evaluator/utils/objects_filtering.hpp b/evaluator/autoware_perception_online_evaluator/include/autoware/perception_online_evaluator/utils/objects_filtering.hpp similarity index 94% rename from evaluator/perception_online_evaluator/include/perception_online_evaluator/utils/objects_filtering.hpp rename to evaluator/autoware_perception_online_evaluator/include/autoware/perception_online_evaluator/utils/objects_filtering.hpp index 7adab46f42d2f..4220284b243f9 100644 --- a/evaluator/perception_online_evaluator/include/perception_online_evaluator/utils/objects_filtering.hpp +++ b/evaluator/autoware_perception_online_evaluator/include/autoware/perception_online_evaluator/utils/objects_filtering.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PERCEPTION_ONLINE_EVALUATOR__UTILS__OBJECTS_FILTERING_HPP_ -#define PERCEPTION_ONLINE_EVALUATOR__UTILS__OBJECTS_FILTERING_HPP_ +#ifndef AUTOWARE__PERCEPTION_ONLINE_EVALUATOR__UTILS__OBJECTS_FILTERING_HPP_ +#define AUTOWARE__PERCEPTION_ONLINE_EVALUATOR__UTILS__OBJECTS_FILTERING_HPP_ -#include "perception_online_evaluator/parameters.hpp" +#include "autoware/perception_online_evaluator/parameters.hpp" #include #include @@ -31,7 +31,7 @@ * most of this file is copied from objects_filtering.hpp in safety_check of behavior_path_planner */ -namespace perception_diagnostics +namespace autoware::perception_diagnostics { using autoware_perception_msgs::msg::ObjectClassification; @@ -170,6 +170,6 @@ PredictedObjects filterObjectsByVelocity( PredictedObjects filterObjectsByVelocity( const PredictedObjects & objects, double velocity_threshold, double max_velocity); -} // namespace perception_diagnostics +} // namespace autoware::perception_diagnostics -#endif // PERCEPTION_ONLINE_EVALUATOR__UTILS__OBJECTS_FILTERING_HPP_ +#endif // AUTOWARE__PERCEPTION_ONLINE_EVALUATOR__UTILS__OBJECTS_FILTERING_HPP_ diff --git a/evaluator/perception_online_evaluator/launch/perception_online_evaluator.launch.xml b/evaluator/autoware_perception_online_evaluator/launch/perception_online_evaluator.launch.xml similarity index 63% rename from evaluator/perception_online_evaluator/launch/perception_online_evaluator.launch.xml rename to evaluator/autoware_perception_online_evaluator/launch/perception_online_evaluator.launch.xml index fc045da0302b7..5fedb030c62eb 100644 --- a/evaluator/perception_online_evaluator/launch/perception_online_evaluator.launch.xml +++ b/evaluator/autoware_perception_online_evaluator/launch/perception_online_evaluator.launch.xml @@ -3,8 +3,8 @@ - - + + diff --git a/evaluator/perception_online_evaluator/package.xml b/evaluator/autoware_perception_online_evaluator/package.xml similarity index 93% rename from evaluator/perception_online_evaluator/package.xml rename to evaluator/autoware_perception_online_evaluator/package.xml index 94575a0adbb4c..198ef5fae247c 100644 --- a/evaluator/perception_online_evaluator/package.xml +++ b/evaluator/autoware_perception_online_evaluator/package.xml @@ -1,7 +1,7 @@ - perception_online_evaluator + autoware_perception_online_evaluator 0.40.0 ROS 2 node for evaluating perception Fumiya Watanabe @@ -10,6 +10,7 @@ Kyoichi Sugahara Shunsuke Miura Yoshi Ri + Junya Sasaki Apache License 2.0 Kosuke Takeuchi diff --git a/evaluator/perception_online_evaluator/param/perception_online_evaluator.defaults.yaml b/evaluator/autoware_perception_online_evaluator/param/perception_online_evaluator.defaults.yaml similarity index 100% rename from evaluator/perception_online_evaluator/param/perception_online_evaluator.defaults.yaml rename to evaluator/autoware_perception_online_evaluator/param/perception_online_evaluator.defaults.yaml diff --git a/evaluator/perception_online_evaluator/src/metrics/detection_count.cpp b/evaluator/autoware_perception_online_evaluator/src/metrics/detection_count.cpp similarity index 97% rename from evaluator/perception_online_evaluator/src/metrics/detection_count.cpp rename to evaluator/autoware_perception_online_evaluator/src/metrics/detection_count.cpp index 1bbfb9e3ee963..3245a80dd7ff5 100644 --- a/evaluator/perception_online_evaluator/src/metrics/detection_count.cpp +++ b/evaluator/autoware_perception_online_evaluator/src/metrics/detection_count.cpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "perception_online_evaluator/metrics/detection_count.hpp" +#include "autoware/perception_online_evaluator/metrics/detection_count.hpp" #include "autoware/object_recognition_utils/object_recognition_utils.hpp" +#include "autoware/perception_online_evaluator/utils/objects_filtering.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" -#include "perception_online_evaluator/utils/objects_filtering.hpp" #include @@ -25,7 +25,7 @@ #include #include -namespace perception_diagnostics +namespace autoware::perception_diagnostics { namespace metrics { @@ -236,4 +236,4 @@ void DetectionCounter::purgeOldRecords(rclcpp::Time current_time) } } } // namespace metrics -} // namespace perception_diagnostics +} // namespace autoware::perception_diagnostics diff --git a/evaluator/perception_online_evaluator/src/metrics/deviation_metrics.cpp b/evaluator/autoware_perception_online_evaluator/src/metrics/deviation_metrics.cpp similarity index 90% rename from evaluator/perception_online_evaluator/src/metrics/deviation_metrics.cpp rename to evaluator/autoware_perception_online_evaluator/src/metrics/deviation_metrics.cpp index 292fc9cd65a17..9aa8632ec7f51 100644 --- a/evaluator/perception_online_evaluator/src/metrics/deviation_metrics.cpp +++ b/evaluator/autoware_perception_online_evaluator/src/metrics/deviation_metrics.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "perception_online_evaluator/metrics/deviation_metrics.hpp" +#include "autoware/perception_online_evaluator/metrics/deviation_metrics.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" #include "autoware/universe_utils/geometry/pose_deviation.hpp" @@ -21,7 +21,7 @@ #include -namespace perception_diagnostics +namespace autoware::perception_diagnostics { namespace metrics { @@ -50,4 +50,4 @@ double calcYawDeviation(const std::vector & ref_path, const Pose & target_ } } // namespace metrics -} // namespace perception_diagnostics +} // namespace autoware::perception_diagnostics diff --git a/evaluator/perception_online_evaluator/src/metrics_calculator.cpp b/evaluator/autoware_perception_online_evaluator/src/metrics_calculator.cpp similarity index 99% rename from evaluator/perception_online_evaluator/src/metrics_calculator.cpp rename to evaluator/autoware_perception_online_evaluator/src/metrics_calculator.cpp index 0ced0b9d6c8a8..0243e0c7edbbb 100644 --- a/evaluator/perception_online_evaluator/src/metrics_calculator.cpp +++ b/evaluator/autoware_perception_online_evaluator/src/metrics_calculator.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "perception_online_evaluator/metrics_calculator.hpp" +#include "autoware/perception_online_evaluator/metrics_calculator.hpp" #include "autoware/motion_utils/trajectory/trajectory.hpp" #include "autoware/object_recognition_utils/object_classification.hpp" @@ -21,7 +21,7 @@ #include -namespace perception_diagnostics +namespace autoware::perception_diagnostics { using autoware::object_recognition_utils::convertLabelToString; using autoware::universe_utils::inverseTransformPoint; @@ -686,4 +686,4 @@ std::vector MetricsCalculator::averageFilterPath( return filtered_path; } -} // namespace perception_diagnostics +} // namespace autoware::perception_diagnostics diff --git a/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp b/evaluator/autoware_perception_online_evaluator/src/perception_online_evaluator_node.cpp similarity index 97% rename from evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp rename to evaluator/autoware_perception_online_evaluator/src/perception_online_evaluator_node.cpp index 7d8344c24819c..4a02745b6ad99 100644 --- a/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp +++ b/evaluator/autoware_perception_online_evaluator/src/perception_online_evaluator_node.cpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "perception_online_evaluator/perception_online_evaluator_node.hpp" +#include "autoware/perception_online_evaluator/perception_online_evaluator_node.hpp" +#include "autoware/perception_online_evaluator/utils/marker_utils.hpp" #include "autoware/universe_utils/ros/marker_helper.hpp" #include "autoware/universe_utils/ros/parameter.hpp" #include "autoware/universe_utils/ros/update_param.hpp" -#include "perception_online_evaluator/utils/marker_utils.hpp" #include @@ -33,7 +33,7 @@ #include #include -namespace perception_diagnostics +namespace autoware::perception_diagnostics { PerceptionOnlineEvaluatorNode::PerceptionOnlineEvaluatorNode( const rclcpp::NodeOptions & node_options) @@ -382,7 +382,7 @@ void PerceptionOnlineEvaluatorNode::initParameter() getOrDeclareParameter(*this, ns + "object_polygon"); } } -} // namespace perception_diagnostics +} // namespace autoware::perception_diagnostics #include "rclcpp_components/register_node_macro.hpp" -RCLCPP_COMPONENTS_REGISTER_NODE(perception_diagnostics::PerceptionOnlineEvaluatorNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::perception_diagnostics::PerceptionOnlineEvaluatorNode) diff --git a/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp b/evaluator/autoware_perception_online_evaluator/src/utils/marker_utils.cpp similarity index 97% rename from evaluator/perception_online_evaluator/src/utils/marker_utils.cpp rename to evaluator/autoware_perception_online_evaluator/src/utils/marker_utils.cpp index 7489447ccb47e..154ca23e9c0cf 100644 --- a/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp +++ b/evaluator/autoware_perception_online_evaluator/src/utils/marker_utils.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "perception_online_evaluator/utils/marker_utils.hpp" +#include "autoware/perception_online_evaluator/utils/marker_utils.hpp" #include "autoware/universe_utils/geometry/boost_polygon_utils.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" @@ -29,7 +29,7 @@ #include #include -namespace marker_utils +namespace autoware::perception_diagnostics::marker_utils { using autoware::universe_utils::calcOffsetPose; using autoware::universe_utils::createDefaultMarker; @@ -197,4 +197,4 @@ MarkerArray createObjectPolygonMarkerArray( return msg; } -} // namespace marker_utils +} // namespace autoware::perception_diagnostics::marker_utils diff --git a/evaluator/perception_online_evaluator/src/utils/objects_filtering.cpp b/evaluator/autoware_perception_online_evaluator/src/utils/objects_filtering.cpp similarity index 95% rename from evaluator/perception_online_evaluator/src/utils/objects_filtering.cpp rename to evaluator/autoware_perception_online_evaluator/src/utils/objects_filtering.cpp index 13bd820f18cec..10ad8915da061 100644 --- a/evaluator/perception_online_evaluator/src/utils/objects_filtering.cpp +++ b/evaluator/autoware_perception_online_evaluator/src/utils/objects_filtering.cpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "perception_online_evaluator/utils/objects_filtering.hpp" +#include "autoware/perception_online_evaluator/utils/objects_filtering.hpp" #include #include -namespace perception_diagnostics +namespace autoware::perception_diagnostics { namespace filter { @@ -102,4 +102,4 @@ PredictedObjects filterObjectsByVelocity( filterObjects(filtered, filter); return filtered; } -} // namespace perception_diagnostics +} // namespace autoware::perception_diagnostics diff --git a/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp b/evaluator/autoware_perception_online_evaluator/test/test_perception_online_evaluator_node.cpp similarity index 99% rename from evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp rename to evaluator/autoware_perception_online_evaluator/test/test_perception_online_evaluator_node.cpp index ffefee835f933..9faf680767db8 100644 --- a/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp +++ b/evaluator/autoware_perception_online_evaluator/test/test_perception_online_evaluator_node.cpp @@ -16,8 +16,8 @@ #include "rclcpp/time.hpp" #include +#include #include -#include #include #include @@ -36,7 +36,7 @@ #include #include -using EvalNode = perception_diagnostics::PerceptionOnlineEvaluatorNode; +using EvalNode = autoware::perception_diagnostics::PerceptionOnlineEvaluatorNode; using PredictedObjects = autoware_perception_msgs::msg::PredictedObjects; using PredictedObject = autoware_perception_msgs::msg::PredictedObject; using MarkerArray = visualization_msgs::msg::MarkerArray; @@ -57,7 +57,7 @@ class EvalTest : public ::testing::Test rclcpp::NodeOptions options; const auto share_dir = - ament_index_cpp::get_package_share_directory("perception_online_evaluator"); + ament_index_cpp::get_package_share_directory("autoware_perception_online_evaluator"); options.arguments( {"--ros-args", "--params-file", share_dir + "/param/perception_online_evaluator.defaults.yaml"}); @@ -126,9 +126,9 @@ class EvalTest : public ::testing::Test tf_pub_->publish(tf_msg); } - void setTargetMetric(const perception_diagnostics::Metric & metric) + void setTargetMetric(const autoware::perception_diagnostics::Metric & metric) { - const auto metric_str = perception_diagnostics::metric_to_str.at(metric); + const auto metric_str = autoware::perception_diagnostics::metric_to_str.at(metric); setTargetMetric(metric_str); } diff --git a/evaluator/perception_online_evaluator/CMakeLists.txt b/evaluator/perception_online_evaluator/CMakeLists.txt deleted file mode 100644 index b323d07a882e8..0000000000000 --- a/evaluator/perception_online_evaluator/CMakeLists.txt +++ /dev/null @@ -1,44 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(perception_online_evaluator) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -find_package(pluginlib REQUIRED) - -ament_auto_add_library(${PROJECT_NAME}_node SHARED - src/metrics_calculator.cpp - src/${PROJECT_NAME}_node.cpp - src/metrics/deviation_metrics.cpp - src/metrics/detection_count.cpp - src/utils/marker_utils.cpp - src/utils/objects_filtering.cpp -) - -rclcpp_components_register_node(${PROJECT_NAME}_node - PLUGIN "perception_diagnostics::PerceptionOnlineEvaluatorNode" - EXECUTABLE ${PROJECT_NAME} -) - -rclcpp_components_register_node(${PROJECT_NAME}_node - PLUGIN "perception_diagnostics::MotionEvaluatorNode" - EXECUTABLE motion_evaluator -) - -target_link_libraries(${PROJECT_NAME}_node glog::glog) - -if(BUILD_TESTING) - ament_add_ros_isolated_gtest(test_${PROJECT_NAME} - test/test_perception_online_evaluator_node.cpp - TIMEOUT 300 - ) - target_link_libraries(test_${PROJECT_NAME} - ${PROJECT_NAME}_node - ) -endif() - -ament_auto_package( - INSTALL_TO_SHARE - param - launch -) diff --git a/evaluator/perception_online_evaluator/launch/motion_evaluator.launch.xml b/evaluator/perception_online_evaluator/launch/motion_evaluator.launch.xml deleted file mode 100644 index 08c4e11126ec1..0000000000000 --- a/evaluator/perception_online_evaluator/launch/motion_evaluator.launch.xml +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - From 56f29fea5f9090ed33fb9fe20ca4c7ec2bcf3863 Mon Sep 17 00:00:00 2001 From: Junya Sasaki Date: Wed, 22 Jan 2025 17:22:43 +0900 Subject: [PATCH 285/334] feat: apply `autoware_` prefix for `duplicated_node_checker` (#9970) * feat(duplicated_node_checker): apply `autoware_` prefix (see below): Note: * In this commit, I did not organize a folder structure. The folder structure will be organized in the next some commits. * The changes will follow the Autoware's guideline as below: - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder Signed-off-by: Junya Sasaki * rename(duplicated_node_checker): move a header under `include/autoware`: * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit Signed-off-by: Junya Sasaki * fix(duplicated_node_checker): fix include header path * To follow the previous commit Signed-off-by: Junya Sasaki * rename: `duplicated_node_checker` => `autoware_duplicated_node_checker` Signed-off-by: Junya Sasaki * style(pre-commit): autofix * bug(autoware_duplicated_node_checker): revert wrongly updated copyrights Signed-off-by: Junya Sasaki * update(autoware_duplicated_node_checker): `README.md` Signed-off-by: Junya Sasaki * update: `CODEOWNERS` Signed-off-by: Junya Sasaki --------- Signed-off-by: Junya Sasaki Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .github/CODEOWNERS | 2 +- .../CHANGELOG.rst | 0 .../CMakeLists.txt | 6 +++--- .../README.md | 4 ++-- .../config/duplicated_node_checker.param.yaml | 0 .../duplicated_node_checker_core.hpp | 10 +++++----- .../launch/duplicated_node_checker.launch.xml | 7 +++++++ .../package.xml | 3 ++- .../schema/duplicated_node_checker.schema.json | 0 .../src/duplicated_node_checker_core.cpp | 8 ++++---- .../launch/duplicated_node_checker.launch.xml | 7 ------- 11 files changed, 24 insertions(+), 23 deletions(-) rename system/{duplicated_node_checker => autoware_duplicated_node_checker}/CHANGELOG.rst (100%) rename system/{duplicated_node_checker => autoware_duplicated_node_checker}/CMakeLists.txt (69%) rename system/{duplicated_node_checker => autoware_duplicated_node_checker}/README.md (83%) rename system/{duplicated_node_checker => autoware_duplicated_node_checker}/config/duplicated_node_checker.param.yaml (100%) rename system/{duplicated_node_checker/include => autoware_duplicated_node_checker/include/autoware}/duplicated_node_checker/duplicated_node_checker_core.hpp (83%) create mode 100644 system/autoware_duplicated_node_checker/launch/duplicated_node_checker.launch.xml rename system/{duplicated_node_checker => autoware_duplicated_node_checker}/package.xml (88%) rename system/{duplicated_node_checker => autoware_duplicated_node_checker}/schema/duplicated_node_checker.schema.json (100%) rename system/{duplicated_node_checker => autoware_duplicated_node_checker}/src/duplicated_node_checker_core.cpp (91%) delete mode 100644 system/duplicated_node_checker/launch/duplicated_node_checker.launch.xml diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 26d86e98018c3..3d92cd900e3b2 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -219,7 +219,7 @@ system/diagnostic_graph_aggregator/** isamu.takagi@tier4.jp system/diagnostic_graph_utils/** isamu.takagi@tier4.jp system/autoware_dummy_diag_publisher/** fumihito.ito@tier4.jp tetsuhiro.kawaguchi@tier4.jp system/dummy_infrastructure/** ryohsuke.mitsudome@tier4.jp -system/duplicated_node_checker/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp uken.ryu@tier4.jp +system/autoware_duplicated_node_checker/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp uken.ryu@tier4.jp junya.sasaki@tier4.jp system/hazard_status_converter/** isamu.takagi@tier4.jp system/mrm_comfortable_stop_operator/** makoto.kurihara@tier4.jp tomohito.ando@tier4.jp system/mrm_emergency_stop_operator/** makoto.kurihara@tier4.jp tomohito.ando@tier4.jp diff --git a/system/duplicated_node_checker/CHANGELOG.rst b/system/autoware_duplicated_node_checker/CHANGELOG.rst similarity index 100% rename from system/duplicated_node_checker/CHANGELOG.rst rename to system/autoware_duplicated_node_checker/CHANGELOG.rst diff --git a/system/duplicated_node_checker/CMakeLists.txt b/system/autoware_duplicated_node_checker/CMakeLists.txt similarity index 69% rename from system/duplicated_node_checker/CMakeLists.txt rename to system/autoware_duplicated_node_checker/CMakeLists.txt index 6a8089fa85c96..25f7e8bd16d92 100644 --- a/system/duplicated_node_checker/CMakeLists.txt +++ b/system/autoware_duplicated_node_checker/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(duplicated_node_checker) +project(autoware_duplicated_node_checker) find_package(autoware_cmake REQUIRED) autoware_package() @@ -10,8 +10,8 @@ ament_auto_add_library(${PROJECT_NAME} SHARED ) rclcpp_components_register_node(${PROJECT_NAME} - PLUGIN "duplicated_node_checker::DuplicatedNodeChecker" - EXECUTABLE duplicated_node_checker_node + PLUGIN "autoware::duplicated_node_checker::DuplicatedNodeChecker" + EXECUTABLE ${PROJECT_NAME}_node ) ament_auto_package(INSTALL_TO_SHARE diff --git a/system/duplicated_node_checker/README.md b/system/autoware_duplicated_node_checker/README.md similarity index 83% rename from system/duplicated_node_checker/README.md rename to system/autoware_duplicated_node_checker/README.md index 81b53e36c9f6d..42cbf8f7633ac 100644 --- a/system/duplicated_node_checker/README.md +++ b/system/autoware_duplicated_node_checker/README.md @@ -8,7 +8,7 @@ The result is published as diagnostics. ### Standalone Startup ```bash -ros2 launch duplicated_node_checker duplicated_node_checker.launch.xml +ros2 launch autoware_duplicated_node_checker duplicated_node_checker.launch.xml ``` ## Inner-workings / Algorithms @@ -30,7 +30,7 @@ The types of topic status and corresponding diagnostic status are following. ## Parameters -{{ json_to_markdown("system/duplicated_node_checker/schema/duplicated_node_checker.schema.json") }} +{{ json_to_markdown("system/autoware_duplicated_node_checker/schema/duplicated_node_checker.schema.json") }} ## Assumptions / Known limits diff --git a/system/duplicated_node_checker/config/duplicated_node_checker.param.yaml b/system/autoware_duplicated_node_checker/config/duplicated_node_checker.param.yaml similarity index 100% rename from system/duplicated_node_checker/config/duplicated_node_checker.param.yaml rename to system/autoware_duplicated_node_checker/config/duplicated_node_checker.param.yaml diff --git a/system/duplicated_node_checker/include/duplicated_node_checker/duplicated_node_checker_core.hpp b/system/autoware_duplicated_node_checker/include/autoware/duplicated_node_checker/duplicated_node_checker_core.hpp similarity index 83% rename from system/duplicated_node_checker/include/duplicated_node_checker/duplicated_node_checker_core.hpp rename to system/autoware_duplicated_node_checker/include/autoware/duplicated_node_checker/duplicated_node_checker_core.hpp index 66e125de666b7..91683ff46c265 100644 --- a/system/duplicated_node_checker/include/duplicated_node_checker/duplicated_node_checker_core.hpp +++ b/system/autoware_duplicated_node_checker/include/autoware/duplicated_node_checker/duplicated_node_checker_core.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef DUPLICATED_NODE_CHECKER__DUPLICATED_NODE_CHECKER_CORE_HPP_ -#define DUPLICATED_NODE_CHECKER__DUPLICATED_NODE_CHECKER_CORE_HPP_ +#ifndef AUTOWARE__DUPLICATED_NODE_CHECKER__DUPLICATED_NODE_CHECKER_CORE_HPP_ +#define AUTOWARE__DUPLICATED_NODE_CHECKER__DUPLICATED_NODE_CHECKER_CORE_HPP_ #include #include @@ -22,7 +22,7 @@ #include #include -namespace duplicated_node_checker +namespace autoware::duplicated_node_checker { class DuplicatedNodeChecker : public rclcpp::Node { @@ -54,6 +54,6 @@ class DuplicatedNodeChecker : public rclcpp::Node bool add_duplicated_node_names_to_msg_; std::unordered_set nodes_to_ignore_; }; -} // namespace duplicated_node_checker +} // namespace autoware::duplicated_node_checker -#endif // DUPLICATED_NODE_CHECKER__DUPLICATED_NODE_CHECKER_CORE_HPP_ +#endif // AUTOWARE__DUPLICATED_NODE_CHECKER__DUPLICATED_NODE_CHECKER_CORE_HPP_ diff --git a/system/autoware_duplicated_node_checker/launch/duplicated_node_checker.launch.xml b/system/autoware_duplicated_node_checker/launch/duplicated_node_checker.launch.xml new file mode 100644 index 0000000000000..ec7c417f671c1 --- /dev/null +++ b/system/autoware_duplicated_node_checker/launch/duplicated_node_checker.launch.xml @@ -0,0 +1,7 @@ + + + + + + + diff --git a/system/duplicated_node_checker/package.xml b/system/autoware_duplicated_node_checker/package.xml similarity index 88% rename from system/duplicated_node_checker/package.xml rename to system/autoware_duplicated_node_checker/package.xml index ee2f938cfb442..c49d8304f1968 100644 --- a/system/duplicated_node_checker/package.xml +++ b/system/autoware_duplicated_node_checker/package.xml @@ -1,12 +1,13 @@ - duplicated_node_checker + autoware_duplicated_node_checker 0.40.0 A package to find out nodes with common names Shumpei Wakabayashi yliuhb Mamoru Sobue + Junya Sasaki Apache 2.0 ament_cmake diff --git a/system/duplicated_node_checker/schema/duplicated_node_checker.schema.json b/system/autoware_duplicated_node_checker/schema/duplicated_node_checker.schema.json similarity index 100% rename from system/duplicated_node_checker/schema/duplicated_node_checker.schema.json rename to system/autoware_duplicated_node_checker/schema/duplicated_node_checker.schema.json diff --git a/system/duplicated_node_checker/src/duplicated_node_checker_core.cpp b/system/autoware_duplicated_node_checker/src/duplicated_node_checker_core.cpp similarity index 91% rename from system/duplicated_node_checker/src/duplicated_node_checker_core.cpp rename to system/autoware_duplicated_node_checker/src/duplicated_node_checker_core.cpp index 40ced8f886005..d68b893b075c1 100644 --- a/system/duplicated_node_checker/src/duplicated_node_checker_core.cpp +++ b/system/autoware_duplicated_node_checker/src/duplicated_node_checker_core.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "duplicated_node_checker/duplicated_node_checker_core.hpp" +#include "autoware/duplicated_node_checker/duplicated_node_checker_core.hpp" #include #include @@ -22,7 +22,7 @@ #include #include -namespace duplicated_node_checker +namespace autoware::duplicated_node_checker { DuplicatedNodeChecker::DuplicatedNodeChecker(const rclcpp::NodeOptions & node_options) @@ -77,7 +77,7 @@ void DuplicatedNodeChecker::produceDiagnostics(diagnostic_updater::DiagnosticSta stat.summary(level, msg); } -} // namespace duplicated_node_checker +} // namespace autoware::duplicated_node_checker #include -RCLCPP_COMPONENTS_REGISTER_NODE(duplicated_node_checker::DuplicatedNodeChecker) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::duplicated_node_checker::DuplicatedNodeChecker) diff --git a/system/duplicated_node_checker/launch/duplicated_node_checker.launch.xml b/system/duplicated_node_checker/launch/duplicated_node_checker.launch.xml deleted file mode 100644 index 87f41f045545d..0000000000000 --- a/system/duplicated_node_checker/launch/duplicated_node_checker.launch.xml +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - From 58d303c657c6063cd8027510c56cc5fc6cfbe3bb Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Wed, 22 Jan 2025 18:03:57 +0900 Subject: [PATCH 286/334] feat(autoware_crosswalk_traffic_light_estimator)!: tier4_debug_msgs changes to autoware_internal_debug_msgs in autoware_crosswalk_traffic_light_estimator (#9870) Signed-off-by: vish0012 --- .../autoware_crosswalk_traffic_light_estimator/README.md | 7 ++++--- .../autoware_crosswalk_traffic_light_estimator/node.hpp | 4 ++-- .../autoware_crosswalk_traffic_light_estimator/package.xml | 1 + 3 files changed, 7 insertions(+), 5 deletions(-) diff --git a/perception/autoware_crosswalk_traffic_light_estimator/README.md b/perception/autoware_crosswalk_traffic_light_estimator/README.md index 1b24b115f5812..068b588adfc62 100644 --- a/perception/autoware_crosswalk_traffic_light_estimator/README.md +++ b/perception/autoware_crosswalk_traffic_light_estimator/README.md @@ -21,9 +21,10 @@ This module works without `~/input/route`, but its behavior is outputting the su ### Output -| Name | Type | Description | -| -------------------------- | ----------------------------------------------------- | --------------------------------------------------------- | -| `~/output/traffic_signals` | autoware_perception_msgs::msg::TrafficLightGroupArray | output that contains estimated pedestrian traffic signals | +| Name | Type | Description | +| ---------------------------- | ----------------------------------------------------- | --------------------------------------------------------- | +| `~/output/traffic_signals` | autoware_perception_msgs::msg::TrafficLightGroupArray | output that contains estimated pedestrian traffic signals | +| `~/debug/processing_time_ms` | autoware_internal_debug_msgs::msg::Float64Stamped | pipeline latency time (ms) | ## Parameters diff --git a/perception/autoware_crosswalk_traffic_light_estimator/include/autoware_crosswalk_traffic_light_estimator/node.hpp b/perception/autoware_crosswalk_traffic_light_estimator/include/autoware_crosswalk_traffic_light_estimator/node.hpp index 085e423db38ba..e41ede2f574ed 100644 --- a/perception/autoware_crosswalk_traffic_light_estimator/include/autoware_crosswalk_traffic_light_estimator/node.hpp +++ b/perception/autoware_crosswalk_traffic_light_estimator/include/autoware_crosswalk_traffic_light_estimator/node.hpp @@ -19,10 +19,10 @@ #include #include +#include #include #include #include -#include #include #include @@ -41,9 +41,9 @@ namespace autoware::crosswalk_traffic_light_estimator using autoware::universe_utils::DebugPublisher; using autoware::universe_utils::StopWatch; +using autoware_internal_debug_msgs::msg::Float64Stamped; using autoware_map_msgs::msg::LaneletMapBin; using autoware_planning_msgs::msg::LaneletRoute; -using tier4_debug_msgs::msg::Float64Stamped; using TrafficSignal = autoware_perception_msgs::msg::TrafficLightGroup; using TrafficSignalArray = autoware_perception_msgs::msg::TrafficLightGroupArray; using TrafficSignalElement = autoware_perception_msgs::msg::TrafficLightElement; diff --git a/perception/autoware_crosswalk_traffic_light_estimator/package.xml b/perception/autoware_crosswalk_traffic_light_estimator/package.xml index a760c3bd950e3..c96ad1e2135c1 100644 --- a/perception/autoware_crosswalk_traffic_light_estimator/package.xml +++ b/perception/autoware_crosswalk_traffic_light_estimator/package.xml @@ -13,6 +13,7 @@ ament_cmake_auto autoware_cmake + autoware_internal_debug_msgs autoware_lanelet2_extension autoware_map_msgs autoware_perception_msgs From 174a09e2dbd57f296ea1c3743873cdaf93a60295 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Wed, 22 Jan 2025 18:12:19 +0900 Subject: [PATCH 287/334] feat(diagnostic_graph_utils): remove unnecessary dependency in diagnostic_graph_utils (#9922) Signed-off-by: vish0012 --- system/diagnostic_graph_utils/package.xml | 1 - 1 file changed, 1 deletion(-) diff --git a/system/diagnostic_graph_utils/package.xml b/system/diagnostic_graph_utils/package.xml index b777ee530ecc9..9c860d62a7928 100644 --- a/system/diagnostic_graph_utils/package.xml +++ b/system/diagnostic_graph_utils/package.xml @@ -14,7 +14,6 @@ diagnostic_msgs rclcpp rclcpp_components - tier4_debug_msgs tier4_system_msgs ament_lint_auto From 8ee41bebc1c7df6176b837db4a0059964cfb6ff8 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 22 Jan 2025 18:21:12 +0900 Subject: [PATCH 288/334] feat(intersection): add wall marker for too late detect objects (#10006) Signed-off-by: Mamoru Sobue --- .../src/debug.cpp | 8 ++++++++ .../src/scene_intersection.cpp | 1 + .../src/scene_intersection.hpp | 1 + 3 files changed, 10 insertions(+) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/debug.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/debug.cpp index e50bc041cbc89..2c9a2c30b11b8 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/debug.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/debug.cpp @@ -446,6 +446,14 @@ autoware::motion_utils::VirtualWalls IntersectionModule::createVirtualWalls() wall.pose = debug_data_.absence_traffic_light_creep_wall.value(); virtual_walls.push_back(wall); } + if (debug_data_.too_late_stop_wall_pose) { + wall.style = autoware::motion_utils::VirtualWallType::pass; + wall.text = "intersection"; + wall.detail = "too late to stop"; + wall.ns = "intersection" + std::to_string(module_id_) + "_"; + wall.pose = debug_data_.too_late_stop_wall_pose.value(); + virtual_walls.push_back(wall); + } return virtual_walls; } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp index daebfbed3d12a..b4e1f313a6936 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -273,6 +273,7 @@ DecisionResult IntersectionModule::modifyPathVelocityDetail(PathWithLaneId * pat const auto closest_idx = intersection_stoplines.closest_idx; const std::string evasive_diag = generateEgoRiskEvasiveDiagnosis( *path, closest_idx, time_distance_array, too_late_detect_objects, misjudge_objects); + debug_data_.too_late_stop_wall_pose = path->points.at(default_stopline_idx).point.pose; return OverPassJudge{safety_diag, evasive_diag}; } return OverPassJudge{ diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp index 39a56977b301e..afba73ad45922 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -214,6 +214,7 @@ class IntersectionModule : public SceneModuleInterfaceWithRTC bool passed_first_pass_judge{false}; bool passed_second_pass_judge{false}; std::optional absence_traffic_light_creep_wall{std::nullopt}; + std::optional too_late_stop_wall_pose{std::nullopt}; std::optional> attention_area{std::nullopt}; std::optional> occlusion_attention_area{std::nullopt}; From 30ab90ecf4055f8ed971ed63cac16a5c69d7abd2 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Wed, 22 Jan 2025 23:11:19 +0900 Subject: [PATCH 289/334] feat(autoware_detected_object_validation): add height filter in lanelet filtering (#10003) * feat: add height filter param Signed-off-by: yoshiri * feat: use ego base height Signed-off-by: yoshiri * fix: build error Signed-off-by: yoshiri * feat: add lanelet filter test Signed-off-by: yoshiri * feat: add height filter test Signed-off-by: yoshiri * docs: update README and lanelet filter Signed-off-by: yoshiri * fix: do not getTransform when flag is off Signed-off-by: yoshiri --------- Signed-off-by: yoshiri --- .../CMakeLists.txt | 4 + .../config/object_lanelet_filter.param.yaml | 3 + .../object-lanelet-filter.md | 17 +- .../schema/object_lanelet_filter.schema.json | 35 +- .../src/lanelet_filter/lanelet_filter.cpp | 29 ++ .../src/lanelet_filter/lanelet_filter.hpp | 5 + .../lanelet_filter/test_lanelet_filter.cpp | 302 ++++++++++++++++++ .../test/test_lanelet_utils.hpp | 71 ++++ 8 files changed, 461 insertions(+), 5 deletions(-) create mode 100644 perception/autoware_detected_object_validation/test/lanelet_filter/test_lanelet_filter.cpp create mode 100644 perception/autoware_detected_object_validation/test/test_lanelet_utils.hpp diff --git a/perception/autoware_detected_object_validation/CMakeLists.txt b/perception/autoware_detected_object_validation/CMakeLists.txt index bf205fb32bb1d..dd8d3616c362e 100644 --- a/perception/autoware_detected_object_validation/CMakeLists.txt +++ b/perception/autoware_detected_object_validation/CMakeLists.txt @@ -83,6 +83,10 @@ if(BUILD_TESTING) test/test_utils.cpp test/object_position_filter/test_object_position_filter.cpp ) + ament_auto_add_gtest(object_lanelet_filter_tests + test/test_utils.cpp + test/lanelet_filter/test_lanelet_filter.cpp + ) endif() ament_auto_package(INSTALL_TO_SHARE diff --git a/perception/autoware_detected_object_validation/config/object_lanelet_filter.param.yaml b/perception/autoware_detected_object_validation/config/object_lanelet_filter.param.yaml index d15b2c81cf6db..c6b3b5538fc44 100644 --- a/perception/autoware_detected_object_validation/config/object_lanelet_filter.param.yaml +++ b/perception/autoware_detected_object_validation/config/object_lanelet_filter.param.yaml @@ -21,3 +21,6 @@ object_speed_threshold: 3.0 # [m/s] debug: false lanelet_extra_margin: 0.0 + use_height_threshold: false + max_height_threshold: 10.0 # [m] from the base_link height in map frame + min_height_threshold: -1.0 # [m] from the base_link height in map frame diff --git a/perception/autoware_detected_object_validation/object-lanelet-filter.md b/perception/autoware_detected_object_validation/object-lanelet-filter.md index b748885c188b4..4da7b7fdea3de 100644 --- a/perception/autoware_detected_object_validation/object-lanelet-filter.md +++ b/perception/autoware_detected_object_validation/object-lanelet-filter.md @@ -24,10 +24,19 @@ The objects only inside of the vector map will be published. ## Parameters -| Name | Type | Description | -| ---------------------- | -------- | ------------------------------------------------------------------------------------ | -| `debug` | `bool` | if true, publish debug markers | -| `lanelet_extra_margin` | `double` | `if > 0` lanelet polygons are expanded by extra margin, `if <= 0` margin is disabled | +Description of the `filter_settings` in the parameters of the `object_lanelet_filter` node. + +| Name | Type | Description | +| ------------------------------------------------- | -------- | ------------------------------------------------------------------------------------------------------------------------------------- | +| `debug` | `bool` | If `true`, publishes additional debug information, including visualization markers on the `~/debug/marker` topic for tools like RViz. | +| `lanelet_extra_margin` | `double` | If `> 0`, expands the lanelet polygons used for overlap checks by this margin (in meters). If `<= 0`, polygon expansion is disabled. | +| `polygon_overlap_filter.enabled` | `bool` | If `true`, enables filtering of objects based on their overlap with lanelet polygons. | +| `lanelet_direction_filter.enabled` | `bool` | If `true`, enables filtering of objects based on their velocity direction relative to the lanelet. | +| `lanelet_direction_filter.velocity_yaw_threshold` | `double` | The yaw angle difference threshold (in radians) between the object’s velocity vector and the lanelet direction. | +| `lanelet_direction_filter.object_speed_threshold` | `double` | The minimum speed (in m/s) of an object required for the direction filter to be applied. | +| `use_height_threshold` | `bool` | If `true`, enables filtering of objects based on their height relative to the base_link frame. | +| `max_height_threshold` | `double` | The maximum allowable height (in meters) of an object relative to the base_link in the map frame. | +| `min_height_threshold` | `double` | The minimum allowable height (in meters) of an object relative to the base_link in the map frame. | ### Core Parameters diff --git a/perception/autoware_detected_object_validation/schema/object_lanelet_filter.schema.json b/perception/autoware_detected_object_validation/schema/object_lanelet_filter.schema.json index fd4e39f0ca02e..8e1b641eebbf8 100644 --- a/perception/autoware_detected_object_validation/schema/object_lanelet_filter.schema.json +++ b/perception/autoware_detected_object_validation/schema/object_lanelet_filter.schema.json @@ -95,9 +95,42 @@ } }, "required": ["enabled", "velocity_yaw_threshold", "object_speed_threshold"] + }, + "debug": { + "type": "boolean", + "default": false, + "description": "If true, debug information is enabled." + }, + "lanelet_extra_margin": { + "type": "number", + "default": 0.0, + "description": "Extra margin added to the lanelet boundaries." + }, + "use_height_threshold": { + "type": "boolean", + "default": false, + "description": "If true, height thresholds are used to filter objects." + }, + "max_height_threshold": { + "type": "number", + "default": 10.0, + "description": "Maximum height threshold for filtering objects (in meters)." + }, + "min_height_threshold": { + "type": "number", + "default": -1.0, + "description": "Minimum height threshold for filtering objects (in meters)." } }, - "required": ["polygon_overlap_filter", "lanelet_direction_filter"] + "required": [ + "polygon_overlap_filter", + "lanelet_direction_filter", + "debug", + "lanelet_extra_margin", + "use_height_threshold", + "max_height_threshold", + "min_height_threshold" + ] } }, "required": ["filter_target_label", "filter_settings"], diff --git a/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp b/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp index f1c25e8573e85..85add97e20078 100644 --- a/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp +++ b/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp @@ -66,6 +66,12 @@ ObjectLaneletFilterNode::ObjectLaneletFilterNode(const rclcpp::NodeOptions & nod filter_settings_.debug = declare_parameter("filter_settings.debug"); filter_settings_.lanelet_extra_margin = declare_parameter("filter_settings.lanelet_extra_margin"); + filter_settings_.use_height_threshold = + declare_parameter("filter_settings.use_height_threshold"); + filter_settings_.max_height_threshold = + declare_parameter("filter_settings.max_height_threshold"); + filter_settings_.min_height_threshold = + declare_parameter("filter_settings.min_height_threshold"); // Set publisher/subscriber map_sub_ = this->create_subscription( @@ -146,6 +152,19 @@ void ObjectLaneletFilterNode::objectCallback( RCLCPP_ERROR(get_logger(), "Failed transform to %s.", lanelet_frame_id_.c_str()); return; } + // vehicle base pose :map -> base_link + if (filter_settings_.use_height_threshold) { + try { + ego_base_height_ = tf_buffer_ + .lookupTransform( + lanelet_frame_id_, "base_link", transformed_objects.header.stamp, + rclcpp::Duration::from_seconds(0.5)) + .transform.translation.z; + } catch (const tf2::TransformException & ex) { + RCLCPP_ERROR_STREAM(get_logger(), "Failed to get transform: " << ex.what()); + return; + } + } if (!transformed_objects.objects.empty()) { // calculate convex hull @@ -199,6 +218,16 @@ bool ObjectLaneletFilterNode::filterObject( return false; } + // 0. check height threshold + if (filter_settings_.use_height_threshold) { + const double object_height = transformed_object.shape.dimensions.z; + if ( + object_height > ego_base_height_ + filter_settings_.max_height_threshold || + object_height < ego_base_height_ + filter_settings_.min_height_threshold) { + return false; + } + } + bool filter_pass = true; // 1. is polygon overlap with road lanelets or shoulder lanelets if (filter_settings_.polygon_overlap_filter) { diff --git a/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.hpp b/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.hpp index 724e60df27e49..bbb0f7c0d43ce 100644 --- a/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.hpp +++ b/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.hpp @@ -35,6 +35,7 @@ #include #include +#include #include #include #include @@ -88,6 +89,7 @@ class ObjectLaneletFilterNode : public rclcpp::Node tf2_ros::TransformListener tf_listener_; utils::FilterTargetLabel filter_target_; + double ego_base_height_ = 0.0; struct FilterSettings { bool polygon_overlap_filter; @@ -96,6 +98,9 @@ class ObjectLaneletFilterNode : public rclcpp::Node double lanelet_direction_filter_object_speed_threshold; bool debug; double lanelet_extra_margin; + bool use_height_threshold; + double max_height_threshold = std::numeric_limits::infinity(); + double min_height_threshold = -std::numeric_limits::infinity(); } filter_settings_; bool filterObject( diff --git a/perception/autoware_detected_object_validation/test/lanelet_filter/test_lanelet_filter.cpp b/perception/autoware_detected_object_validation/test/lanelet_filter/test_lanelet_filter.cpp new file mode 100644 index 0000000000000..b1e061261f8b6 --- /dev/null +++ b/perception/autoware_detected_object_validation/test/lanelet_filter/test_lanelet_filter.cpp @@ -0,0 +1,302 @@ +// Copyright 2025 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include + +#include +#include + +#include +#include + +#include +#include +#include +#include + +// Include the filter node header with include guard + +#include "../../src/lanelet_filter/lanelet_filter.hpp" +#include "../test_lanelet_utils.hpp" + +using autoware::detected_object_validation::lanelet_filter::ObjectLaneletFilterNode; +using autoware_map_msgs::msg::LaneletMapBin; +using autoware_perception_msgs::msg::DetectedObject; +using autoware_perception_msgs::msg::DetectedObjects; +using autoware_perception_msgs::msg::ObjectClassification; + +namespace +{ +/// @brief Create a test manager (custom utility for Autoware tests) +std::shared_ptr generateTestManager() +{ + return std::make_shared(); +} + +/// @brief Create an instance of ObjectLaneletFilterNode with a parameter file +std::shared_ptr generateNode() +{ + auto node_options = rclcpp::NodeOptions{}; + // Example parameter file path + const auto detected_object_validation_dir = + ament_index_cpp::get_package_share_directory("autoware_detected_object_validation"); + node_options.arguments( + {"--ros-args", "--params-file", + detected_object_validation_dir + "/config/object_lanelet_filter.param.yaml"}); + + return std::make_shared(node_options); +} + +std::shared_ptr createStaticTfBroadcasterNode( + const std::string & parent_frame_id, const std::string & child_frame_id, + const geometry_msgs::msg::Vector3 & translation, const geometry_msgs::msg::Quaternion & rotation, + const std::string & node_name = "test_tf_broadcaster") +{ + // Create a dedicated node for broadcasting the static transform + auto broadcaster_node = std::make_shared(node_name); + + // Create the static transform broadcaster + auto static_broadcaster = std::make_shared(broadcaster_node); + + // Prepare the transform message + geometry_msgs::msg::TransformStamped transform_stamped; + transform_stamped.header.stamp = broadcaster_node->now(); + transform_stamped.header.frame_id = parent_frame_id; + transform_stamped.child_frame_id = child_frame_id; + transform_stamped.transform.translation = translation; + transform_stamped.transform.rotation = rotation; + + // Broadcast the transform + static_broadcaster->sendTransform(transform_stamped); + + return broadcaster_node; +} + +// publish sample LaneletMapBin message +void publishLaneletMapBin( + const std::shared_ptr & test_manager, + const std::shared_ptr & test_target_node, + const std::string & input_map_topic = "input/vector_map") +{ + auto qos = rclcpp::QoS(1).transient_local(); + LaneletMapBin map_msg = createSimpleLaneletMapMsg(); + test_manager->test_pub_msg(test_target_node, input_map_topic, map_msg, qos); +} +} // namespace + +/// @brief Test LaneletMapBin publishing + object filtering +TEST(DetectedObjectValidationTest, testObjectLaneletFilterWithMap) +{ + rclcpp::init(0, nullptr); + + // Create the test node (lanelet_filter_node) + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + + // Create and add a TF broadcaster node + auto tf_node = createStaticTfBroadcasterNode( + "map", "base_link", geometry_msgs::build().x(0.0).y(0.0).z(0.0), + geometry_msgs::build().x(0.0).y(0.0).z(0.0).w(1.0), + "my_test_tf_broadcaster"); + + // Subscribe to the output topic + const std::string output_topic = "output/object"; + DetectedObjects latest_msg; + auto output_callback = [&latest_msg](const DetectedObjects::ConstSharedPtr msg) { + latest_msg = *msg; + }; + test_manager->set_subscriber(output_topic, output_callback); + + // 1) Publish a LaneletMapBin + // In a real test, you'd have an actual map message. + publishLaneletMapBin(test_manager, test_target_node); + + // 2) Publish DetectedObjects + const std::string input_object_topic = "input/object"; + DetectedObjects input_objects; + input_objects.header.frame_id = "base_link"; + + // Prepare two unknown objects + { // Object 1: not in the lanelet + DetectedObject obj; + obj.kinematics.pose_with_covariance.pose.position.x = 100.0; + obj.kinematics.pose_with_covariance.pose.position.y = 5.0; + obj.classification.resize(1); + obj.classification[0].label = ObjectClassification::UNKNOWN; + obj.shape.footprint.points.push_back( + geometry_msgs::build().x(1.0).y(1.0).z(0.0)); + obj.shape.footprint.points.push_back( + geometry_msgs::build().x(1.0).y(-1.0).z(0.0)); + obj.shape.footprint.points.push_back( + geometry_msgs::build().x(-1.0).y(-1.0).z(0.0)); + obj.shape.footprint.points.push_back( + geometry_msgs::build().x(-1.0).y(1.0).z(0.0)); + input_objects.objects.push_back(obj); + } + { // Object 2: in the lanelet. To be filtered out. + DetectedObject obj; + obj.kinematics.pose_with_covariance.pose.position.x = 0.0; + obj.kinematics.pose_with_covariance.pose.position.y = 0.0; + obj.classification.resize(1); + obj.classification[0].label = ObjectClassification::UNKNOWN; + obj.shape.footprint.points.push_back( + geometry_msgs::build().x(1.0).y(1.0).z(0.0)); + obj.shape.footprint.points.push_back( + geometry_msgs::build().x(1.0).y(-1.0).z(0.0)); + obj.shape.footprint.points.push_back( + geometry_msgs::build().x(-1.0).y(-1.0).z(0.0)); + obj.shape.footprint.points.push_back( + geometry_msgs::build().x(-1.0).y(1.0).z(0.0)); + input_objects.objects.push_back(obj); + } + + // Publish the DetectedObjects + test_manager->test_pub_msg(test_target_node, input_object_topic, input_objects); + + EXPECT_EQ(latest_msg.objects.size(), 1) + << "Expected one object to pass through (or receive something)."; + + rclcpp::shutdown(); +} + +/// @brief Test with an empty object list +TEST(DetectedObjectValidationTest, testObjectLaneletFilterEmptyObjects) +{ + rclcpp::init(0, nullptr); + + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + + // Create and add a TF broadcaster node + auto tf_node = createStaticTfBroadcasterNode( + "map", "base_link", geometry_msgs::build().x(0.0).y(0.0).z(0.0), + geometry_msgs::build().x(0.0).y(0.0).z(0.0).w(1.0), + "my_test_tf_broadcaster"); + + // Publish simple LaneletMapBin + publishLaneletMapBin(test_manager, test_target_node); + + // Subscribe to the output topic + const std::string output_topic = "output/object"; + int callback_counter = 0; + auto output_callback = [&callback_counter](const DetectedObjects::ConstSharedPtr msg) { + (void)msg; + ++callback_counter; + }; + test_manager->set_subscriber(output_topic, output_callback); + + // Publish empty objects (not publishing map) + DetectedObjects input_objects; + input_objects.header.frame_id = "base_link"; + + test_manager->test_pub_msg(test_target_node, "input/object", input_objects); + + // The callback should still be called at least once + EXPECT_GE(callback_counter, 1); + + rclcpp::shutdown(); +} + +TEST(DetectedObjectValidationTest, testObjectLaneletFilterHeightThreshold) +{ + rclcpp::init(0, nullptr); + + // 1) Setup test manager and node with a custom param override (height filter enabled) + auto test_manager = generateTestManager(); + + auto node_options = rclcpp::NodeOptions{}; + const auto detected_object_validation_dir = + ament_index_cpp::get_package_share_directory("autoware_detected_object_validation"); + node_options.arguments( + {"--ros-args", "--params-file", + detected_object_validation_dir + "/config/object_lanelet_filter.param.yaml"}); + node_options.append_parameter_override("filter_settings.use_height_threshold", true); + node_options.append_parameter_override("filter_settings.max_height_threshold", 2.0); + node_options.append_parameter_override("filter_settings.min_height_threshold", 0.0); + + auto test_target_node = std::make_shared(node_options); + + // 2) Create a TF broadcaster node (map->base_link at z=0.0) + auto tf_node = createStaticTfBroadcasterNode( + "map", "base_link", geometry_msgs::build().x(0.0).y(0.0).z(0.0), + geometry_msgs::build().x(0.0).y(0.0).z(0.0).w(1.0), + "my_test_tf_broadcaster_1"); + + // Subscribe to the output topic + const std::string output_topic = "output/object"; + DetectedObjects latest_msg; + auto output_callback = [&latest_msg](const DetectedObjects::ConstSharedPtr msg) { + latest_msg = *msg; + }; + test_manager->set_subscriber(output_topic, output_callback); + + // 3) Publish a simple LaneletMapBin (50m straight lane) + publishLaneletMapBin(test_manager, test_target_node); + + // 4) Publish DetectedObjects + const std::string input_object_topic = "input/object"; + DetectedObjects input_objects; + input_objects.header.frame_id = "base_link"; + + // (A) Object in-lane, height=1.5 => expected to remain + { + DetectedObject obj; + obj.classification.resize(1); + obj.classification[0].label = ObjectClassification::UNKNOWN; + obj.kinematics.pose_with_covariance.pose.position.x = 0.0; + obj.kinematics.pose_with_covariance.pose.position.y = 0.0; + obj.shape.type = autoware_perception_msgs::msg::Shape::BOUNDING_BOX; + obj.shape.dimensions.x = 2.0; + obj.shape.dimensions.y = 2.0; + obj.shape.dimensions.z = 1.5; + input_objects.objects.push_back(obj); + } + + // (B) Object in-lane, height=3.0 => expected to be filtered out + { + DetectedObject obj; + obj.classification.resize(1); + obj.classification[0].label = ObjectClassification::UNKNOWN; + obj.kinematics.pose_with_covariance.pose.position.x = 5.0; + obj.kinematics.pose_with_covariance.pose.position.y = 0.0; + obj.shape.type = autoware_perception_msgs::msg::Shape::BOUNDING_BOX; + obj.shape.dimensions.x = 2.0; + obj.shape.dimensions.y = 2.0; + obj.shape.dimensions.z = 3.0; + input_objects.objects.push_back(obj); + } + + // Publish the objects (Round 1) + test_manager->test_pub_msg(test_target_node, input_object_topic, input_objects); + + // 5) Check result => only the first object remains + EXPECT_EQ(latest_msg.objects.size(), 1U) + << "Height filter is enabled => only the shorter object (1.5m) should remain."; + + // 6) Second scenario: place ego at z=1.3, effectively lowering object's relative height + auto tf_node_after = createStaticTfBroadcasterNode( + "map", "base_link", geometry_msgs::build().x(0.0).y(0.0).z(1.3), + geometry_msgs::build().x(0.0).y(0.0).z(0.0).w(1.0), + "my_test_tf_broadcaster_2"); + + // Publish the same objects (Round 2) + test_manager->test_pub_msg(test_target_node, input_object_topic, input_objects); + + // 7) Check result => now both objects remain because each one's height above base_link is < 2.0 + EXPECT_EQ(latest_msg.objects.size(), 2U) + << "With ego at z=1.3, the 3.0m object is effectively only ~1.7m above ego => remain."; + + rclcpp::shutdown(); +} diff --git a/perception/autoware_detected_object_validation/test/test_lanelet_utils.hpp b/perception/autoware_detected_object_validation/test/test_lanelet_utils.hpp new file mode 100644 index 0000000000000..3e9ff5372044a --- /dev/null +++ b/perception/autoware_detected_object_validation/test/test_lanelet_utils.hpp @@ -0,0 +1,71 @@ +// Copyright 2025 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +#ifndef TEST_LANELET_UTILS_HPP_ +#define TEST_LANELET_UTILS_HPP_ + +#include + +#include +#include +#include +#include +#include + +#include + +/** + * @brief Create a simple LaneletMapBin message containing a single 50[m] straight lanelet. + * + * The lanelet has left boundary at y=+1.5 and right boundary at y=-1.5, + * forming a lane of width 3.0[m] and length 50.0[m]. + * + * @return autoware_map_msgs::msg::LaneletMapBin The generated map message. + */ +inline autoware_map_msgs::msg::LaneletMapBin createSimpleLaneletMapMsg() +{ + // 1) Create left boundary (y = +1.5). + // This is a straight line from (0, +1.5, 0) to (50, +1.5, 0). + lanelet::Point3d p1_left(lanelet::utils::getId(), 0.0, 1.5, 0.0); + lanelet::Point3d p2_left(lanelet::utils::getId(), 50.0, 1.5, 0.0); + lanelet::LineString3d ls_left(lanelet::utils::getId(), {p1_left, p2_left}); + ls_left.attributes()[lanelet::AttributeName::Type] = lanelet::AttributeValueString::RoadBorder; + + // 2) Create right boundary (y = -1.5). + // This is a straight line from (0, -1.5, 0) to (50, -1.5, 0). + lanelet::Point3d p1_right(lanelet::utils::getId(), 0.0, -1.5, 0.0); + lanelet::Point3d p2_right(lanelet::utils::getId(), 50.0, -1.5, 0.0); + lanelet::LineString3d ls_right(lanelet::utils::getId(), {p1_right, p2_right}); + ls_right.attributes()[lanelet::AttributeName::Type] = lanelet::AttributeValueString::RoadBorder; + + // 3) Create a lanelet by specifying the left and right boundaries, + // then set the subtype to "Road". + lanelet::Lanelet lanelet_section(lanelet::utils::getId(), ls_left, ls_right); + lanelet_section.attributes()[lanelet::AttributeName::Subtype] = + lanelet::AttributeValueString::Road; + + // 4) Create a LaneletMap and add the lanelet to it. + auto lanelet_map = std::make_shared(); + lanelet_map->add(lanelet_section); + + // 5) Convert the LaneletMap to a LaneletMapBin message. + autoware_map_msgs::msg::LaneletMapBin map_bin_msg; + lanelet::utils::conversion::toBinMsg(lanelet_map, &map_bin_msg); + + // 6) Set the frame_id in the header. + map_bin_msg.header.frame_id = "map"; + + return map_bin_msg; +} + +#endif // TEST_LANELET_UTILS_HPP_ From 0c118baf512593f29a95259cc430cd743882751f Mon Sep 17 00:00:00 2001 From: TetsuKawa <70682030+TetsuKawa@users.noreply.github.com> Date: Wed, 22 Jan 2025 23:56:15 +0900 Subject: [PATCH 290/334] feat(autoware_topic_relay_controller): add topic relay controller node (#9964) * feat: add node base Signed-off-by: TetsuKawa * modify: include guard Signed-off-by: TetsuKawa * feat: delete schema Signed-off-by: TetsuKawa * feat: delete config Signed-off-by: TetsuKawa * feat: add subscriber Signed-off-by: TetsuKawa * modify: add include Signed-off-by: TetsuKawa * feat: add publisher Signed-off-by: TetsuKawa * feat: add service Signed-off-by: TetsuKawa * modify: typo Signed-off-by: TetsuKawa * style(pre-commit): autofix Signed-off-by: TetsuKawa * modify: add include memory Signed-off-by: TetsuKawa * modify: add qos setting Signed-off-by: TetsuKawa * style(pre-commit): autofix Signed-off-by: TetsuKawa * feat: add enable_keep_publishing Signed-off-by: TetsuKawa * style(pre-commit): autofix Signed-off-by: TetsuKawa * feat: add readme Signed-off-by: TetsuKawa * style(pre-commit): autofix Signed-off-by: TetsuKawa * feat: change qos name and add parameter type Signed-off-by: TetsuKawa * feat: add config and delete arg from launch Signed-off-by: TetsuKawa * modify: typo Signed-off-by: TetsuKawa * style(pre-commit): autofix * modify: add comment Signed-off-by: TetsuKawa * modify: modify comment Signed-off-by: TetsuKawa * feat: add maintainer Signed-off-by: TetsuKawa * modift: change readme param format Signed-off-by: TetsuKawa * style(pre-commit): autofix --------- Signed-off-by: TetsuKawa Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../CMakeLists.txt | 20 +++ .../autoware_topic_relay_controller/README.md | 45 ++++++ .../config/topic_relay_controller.param.yaml | 14 ++ .../launch/topic_relay_controller.launch.xml | 8 ++ .../package.xml | 25 ++++ .../src/topic_relay_controller_node.cpp | 129 ++++++++++++++++++ .../src/topic_relay_controller_node.hpp | 77 +++++++++++ 7 files changed, 318 insertions(+) create mode 100644 system/autoware_topic_relay_controller/CMakeLists.txt create mode 100644 system/autoware_topic_relay_controller/README.md create mode 100644 system/autoware_topic_relay_controller/config/topic_relay_controller.param.yaml create mode 100644 system/autoware_topic_relay_controller/launch/topic_relay_controller.launch.xml create mode 100644 system/autoware_topic_relay_controller/package.xml create mode 100644 system/autoware_topic_relay_controller/src/topic_relay_controller_node.cpp create mode 100644 system/autoware_topic_relay_controller/src/topic_relay_controller_node.hpp diff --git a/system/autoware_topic_relay_controller/CMakeLists.txt b/system/autoware_topic_relay_controller/CMakeLists.txt new file mode 100644 index 0000000000000..768affd7fd121 --- /dev/null +++ b/system/autoware_topic_relay_controller/CMakeLists.txt @@ -0,0 +1,20 @@ +cmake_minimum_required(VERSION 3.14) +project(autoware_topic_relay_controller) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/topic_relay_controller_node.cpp +) + +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "autoware::topic_relay_controller::TopicRelayController" + EXECUTABLE ${PROJECT_NAME}_node + EXECUTOR MultiThreadedExecutor +) + +ament_auto_package(INSTALL_TO_SHARE + config + launch +) diff --git a/system/autoware_topic_relay_controller/README.md b/system/autoware_topic_relay_controller/README.md new file mode 100644 index 0000000000000..a5651ff32fbd2 --- /dev/null +++ b/system/autoware_topic_relay_controller/README.md @@ -0,0 +1,45 @@ +# topic_relay_controller + +## Purpose + +The node subscribes to a specified topic, remaps it, and republishes it. Additionally, it has the capability to continue publishing the last received value if the subscription stops. + +## Inputs / Outputs + +### Input + +| Name | Type | Description | +| ------------ | -------------------------- | -------------------------------------------------------------------- | +| `/` | `` | Topic to be subscribed, as defined by the `topic` parameter. | +| `/tf` | `tf2_msgs::msg::TFMessage` | (Optional) If the topic is `/tf`, used for transform message relay. | +| `/tf_static` | `tf2_msgs::msg::TFMessage` | (Optional) If the topic is `/tf_static`, used for static transforms. | + +### Output + +| Name | Type | Description | +| ---------------- | -------------------------- | ----------------------------------------------------------------------------- | +| `/` | `` | Republished topic after remapping, as defined by the `remap_topic` parameter. | + +## Parameters + +| Variable | Type | Description | +| ---------------------- | ------- | ---------------------------------------------------------------------------------------------------- | +| topic | string | The name of the input topic to subscribe to | +| remap_topic | string | The name of the output topic to publish to | +| topic_type | string | The type of messages being relayed | +| qos | integer | QoS profile to use for subscriptions and publications (default: `1`) | +| transient_local | boolean | Enables transient local QoS for subscribers (default: `false`) | +| best_effort | boolean | Enables best-effort QoS for subscribers (default: `false`) | +| enable_relay_control | boolean | Allows dynamic relay control via a service (default: `true`) | +| srv_name | string | The service name for relay control when `enable_relay_control` is `true` | +| enable_keep_publishing | boolean | Keeps publishing the last received topic value when not subscribed (default: `false`) | +| update_rate | integer | The rate (Hz) for publishing the last topic value when `enable_keep_publishing` is `true` (optional) | +| frame_id | string | Frame ID for transform messages when subscribing to `/tf` or `/tf_static` (optional) | +| child_frame_id | string | Child frame ID for transform messages when subscribing to `/tf` or `/tf_static` (optional) | + +## Assumptions / Known limits + +- The node assumes that the specified `topic` and `remap_topic` are valid and accessible within the ROS 2 environment. +- If `enable_keep_publishing` is `true`, the node continuously republishes the last received value even if no new messages are being received. +- For `/tf` and `/tf_static`, additional parameters like `frame_id` and `child_frame_id` are required for selective transformation relays. +- QoS settings must be carefully chosen to match the requirements of the subscribed and published topics. diff --git a/system/autoware_topic_relay_controller/config/topic_relay_controller.param.yaml b/system/autoware_topic_relay_controller/config/topic_relay_controller.param.yaml new file mode 100644 index 0000000000000..204679e4be11a --- /dev/null +++ b/system/autoware_topic_relay_controller/config/topic_relay_controller.param.yaml @@ -0,0 +1,14 @@ +/**: + ros__parameters: + topic: "/default" + topic_type: "std_msgs/msg/String" # unneccessary for /tf or /tf_static + remap_topic: "/remap_default" + #frame_id: neccessary for /tf or /tf_static + #child_frame_id: neccessary for /tf or /tf_static + qos_depth: 1 + transient_local: false # Change qos to transient_local. Default is volatile. + best_effort: false # Change qos to best_effort. Default is reliable. + enable_relay_control: true + srv_name: "/system/topic_relay_controller_default/operate" # neccessary for enable_relay_control is true + enable_keep_publishing: false + #update_rate: #neccessary for enable_keep_publishing is true diff --git a/system/autoware_topic_relay_controller/launch/topic_relay_controller.launch.xml b/system/autoware_topic_relay_controller/launch/topic_relay_controller.launch.xml new file mode 100644 index 0000000000000..f4c6fa43a8d61 --- /dev/null +++ b/system/autoware_topic_relay_controller/launch/topic_relay_controller.launch.xml @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/system/autoware_topic_relay_controller/package.xml b/system/autoware_topic_relay_controller/package.xml new file mode 100644 index 0000000000000..771c7e632f49a --- /dev/null +++ b/system/autoware_topic_relay_controller/package.xml @@ -0,0 +1,25 @@ + + + + autoware_topic_relay_controller + 0.1.0 + The topic_relay_controller ROS 2 package + Makoto Kurihara + Tetsuhiro Kawaguchi + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + + rclcpp + rclcpp_components + tf2_msgs + tier4_system_msgs + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/system/autoware_topic_relay_controller/src/topic_relay_controller_node.cpp b/system/autoware_topic_relay_controller/src/topic_relay_controller_node.cpp new file mode 100644 index 0000000000000..88056c271cb40 --- /dev/null +++ b/system/autoware_topic_relay_controller/src/topic_relay_controller_node.cpp @@ -0,0 +1,129 @@ +// Copyright 2025 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR +// CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language +// governing permissions and limitations under the License. + +#include "topic_relay_controller_node.hpp" + +#include +#include + +namespace autoware::topic_relay_controller +{ +TopicRelayController::TopicRelayController(const rclcpp::NodeOptions & options) +: Node("topic_relay_controller", options), is_relaying_(true) +{ + // Parameter + node_param_.topic = declare_parameter("topic"); + node_param_.remap_topic = declare_parameter("remap_topic"); + node_param_.qos_depth = declare_parameter("qos_depth", 1); + node_param_.transient_local = declare_parameter("transient_local", false); + node_param_.best_effort = declare_parameter("best_effort", false); + node_param_.is_transform = (node_param_.topic == "/tf" || node_param_.topic == "/tf_static"); + node_param_.enable_relay_control = declare_parameter("enable_relay_control"); + if (node_param_.enable_relay_control) + node_param_.srv_name = declare_parameter("srv_name"); + node_param_.enable_keep_publishing = declare_parameter("enable_keep_publishing"); + if (node_param_.enable_keep_publishing) + node_param_.update_rate = declare_parameter("update_rate"); + + if (node_param_.is_transform) { + node_param_.frame_id = declare_parameter("frame_id"); + node_param_.child_frame_id = declare_parameter("child_frame_id"); + } else { + node_param_.topic_type = declare_parameter("topic_type"); + } + + // Service + if (node_param_.enable_relay_control) { + srv_change_relay_control_ = create_service( + node_param_.srv_name, + [this]( + const tier4_system_msgs::srv::ChangeTopicRelayControl::Request::SharedPtr request, + tier4_system_msgs::srv::ChangeTopicRelayControl::Response::SharedPtr response) { + is_relaying_ = request->relay_on; + RCLCPP_INFO(get_logger(), "relay control: %s", is_relaying_ ? "ON" : "OFF"); + response->status.success = true; + }); + } + + // Subscriber + rclcpp::QoS qos = rclcpp::SystemDefaultsQoS(); + if (node_param_.qos_depth > 0) { + size_t qos_depth = static_cast(node_param_.qos_depth); + qos.keep_last(qos_depth); + } else { + RCLCPP_ERROR(get_logger(), "qos_depth must be greater than 0"); + return; + } + + if (node_param_.transient_local) { + qos.transient_local(); + } + if (node_param_.best_effort) { + qos.best_effort(); + } + + if (node_param_.is_transform) { + // Publisher + pub_transform_ = this->create_publisher(node_param_.remap_topic, qos); + + sub_transform_ = this->create_subscription( + node_param_.topic, qos, [this](tf2_msgs::msg::TFMessage::SharedPtr msg) { + for (const auto & transform : msg->transforms) { + if ( + transform.header.frame_id != node_param_.frame_id || + transform.child_frame_id != node_param_.child_frame_id || !is_relaying_) + return; + + if (node_param_.enable_keep_publishing) { + last_tf_topic_ = msg; + } else { + pub_transform_->publish(*msg); + } + } + }); + } else { + // Publisher + pub_topic_ = + this->create_generic_publisher(node_param_.remap_topic, node_param_.topic_type, qos); + + sub_topic_ = this->create_generic_subscription( + node_param_.topic, node_param_.topic_type, qos, + [this]([[maybe_unused]] std::shared_ptr msg) { + if (!is_relaying_) return; + + if (node_param_.enable_keep_publishing) { + last_topic_ = msg; + } else { + pub_topic_->publish(*msg); + } + }); + } + + // Timer + if (node_param_.enable_keep_publishing) { + const auto update_period_ns = rclcpp::Rate(node_param_.update_rate).period(); + timer_ = rclcpp::create_timer(this, get_clock(), update_period_ns, [this]() { + if (!is_relaying_) return; + + if (node_param_.is_transform) { + if (last_tf_topic_) pub_transform_->publish(*last_tf_topic_); + } else { + if (last_topic_) pub_topic_->publish(*last_topic_); + } + }); + } +} +} // namespace autoware::topic_relay_controller + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::topic_relay_controller::TopicRelayController) diff --git a/system/autoware_topic_relay_controller/src/topic_relay_controller_node.hpp b/system/autoware_topic_relay_controller/src/topic_relay_controller_node.hpp new file mode 100644 index 0000000000000..446b9f156456a --- /dev/null +++ b/system/autoware_topic_relay_controller/src/topic_relay_controller_node.hpp @@ -0,0 +1,77 @@ +// Copyright 2025 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef TOPIC_RELAY_CONTROLLER_NODE_HPP_ +#define TOPIC_RELAY_CONTROLLER_NODE_HPP_ + +// ROS 2 core +#include + +#include +#include + +#include +#include + +namespace autoware::topic_relay_controller +{ +struct NodeParam +{ + std::string topic; + std::string remap_topic; + std::string topic_type; + int qos_depth; + std::string frame_id; + std::string child_frame_id; + bool transient_local; + bool best_effort; + bool is_transform; + bool enable_relay_control; + std::string srv_name; + bool enable_keep_publishing; + int update_rate; +}; + +class TopicRelayController : public rclcpp::Node +{ +public: + explicit TopicRelayController(const rclcpp::NodeOptions & options); + +private: + // Parameter + NodeParam node_param_; + + // Subscriber + rclcpp::GenericSubscription::SharedPtr sub_topic_; + rclcpp::Subscription::SharedPtr sub_transform_; + + // Publisher + rclcpp::GenericPublisher::SharedPtr pub_topic_; + rclcpp::Publisher::SharedPtr pub_transform_; + + // Service + rclcpp::Service::SharedPtr + srv_change_relay_control_; + + // Timer + rclcpp::TimerBase::SharedPtr timer_; + + // State + bool is_relaying_; + tf2_msgs::msg::TFMessage::SharedPtr last_tf_topic_; + std::shared_ptr last_topic_; +}; +} // namespace autoware::topic_relay_controller + +#endif // TOPIC_RELAY_CONTROLLER_NODE_HPP_ From d4e488a48b895221b0a76f95aee4dda43a03bb28 Mon Sep 17 00:00:00 2001 From: Junya Sasaki Date: Thu, 23 Jan 2025 09:17:05 +0900 Subject: [PATCH 291/334] fix(launch): fix missing changes for launch (#10007) bug(launch): fix missing changes for following PRs: * https://github.com/autowarefoundation/autoware.universe/pull/9956 * https://github.com/autowarefoundation/autoware.universe/pull/9970 Signed-off-by: Junya Sasaki --- launch/tier4_perception_launch/launch/perception.launch.xml | 2 +- launch/tier4_simulator_launch/launch/simulator.launch.xml | 2 +- launch/tier4_system_launch/launch/system.launch.xml | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index 02a34eab8fe9a..9f325466ed107 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -311,6 +311,6 @@ - + diff --git a/launch/tier4_simulator_launch/launch/simulator.launch.xml b/launch/tier4_simulator_launch/launch/simulator.launch.xml index 73b00adf923be..67c05a2b4d069 100644 --- a/launch/tier4_simulator_launch/launch/simulator.launch.xml +++ b/launch/tier4_simulator_launch/launch/simulator.launch.xml @@ -105,7 +105,7 @@ - + diff --git a/launch/tier4_system_launch/launch/system.launch.xml b/launch/tier4_system_launch/launch/system.launch.xml index 0e0e0e78c1dba..c37db6bca4ffe 100644 --- a/launch/tier4_system_launch/launch/system.launch.xml +++ b/launch/tier4_system_launch/launch/system.launch.xml @@ -53,7 +53,7 @@ - + From ba4b755a1931433c1f8bdc48f0bd54654c345115 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 23 Jan 2025 10:52:03 +0900 Subject: [PATCH 292/334] feat(static_obstacle_avoidance): output safety factor (#10000) * feat(safety_check): convert to SafetyFactor Signed-off-by: satoshi-ota * feat(static_obstacle_avoidance): use safety factor Signed-off-by: satoshi-ota * fix(bpp): output detail Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../interface/scene_module_interface.hpp | 4 ++-- .../utils/path_safety_checker/safety_check.hpp | 4 ++++ .../src/utils/path_safety_checker/safety_check.cpp | 14 ++++++++++++++ .../scene.hpp | 7 +++++-- .../src/scene.cpp | 5 ++++- 5 files changed, 29 insertions(+), 5 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp index 741d4552d8558..c5c0972972773 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp @@ -549,7 +549,7 @@ class SceneModuleInterface if (stop_pose_.has_value()) { planning_factor_interface_->add( path.points, getEgoPose(), stop_pose_.value().pose, PlanningFactor::STOP, - SafetyFactorArray{}); + SafetyFactorArray{}, true, 0.0, 0.0, stop_pose_.value().detail); return; } @@ -559,7 +559,7 @@ class SceneModuleInterface planning_factor_interface_->add( path.points, getEgoPose(), slow_pose_.value().pose, PlanningFactor::SLOW_DOWN, - SafetyFactorArray{}); + SafetyFactorArray{}, true, 0.0, 0.0, slow_pose_.value().detail); } void setDrivableLanes(const std::vector & drivable_lanes); diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp index ab62c369c41e4..23ff10a2a0abf 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp @@ -25,6 +25,7 @@ #include #include #include +#include #include #include @@ -283,6 +284,9 @@ double calculateRoughDistanceToObjects( CollisionCheckDebugPair createObjectDebug(const ExtendedPredictedObject & obj); void updateCollisionCheckDebugMap( CollisionCheckDebugMap & debug_map, CollisionCheckDebugPair & object_debug, bool is_safe); + +tier4_planning_msgs::msg::SafetyFactorArray to_safety_factor_array( + const CollisionCheckDebugMap & debug_map); } // namespace autoware::behavior_path_planner::utils::path_safety_checker #endif // AUTOWARE__BEHAVIOR_PATH_PLANNER_COMMON__UTILS__PATH_SAFETY_CHECKER__SAFETY_CHECK_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp index 5ae62f51bdb52..b448ae50492ac 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp @@ -883,4 +883,18 @@ double calculateRoughDistanceToObjects( return min_distance; } +tier4_planning_msgs::msg::SafetyFactorArray to_safety_factor_array( + const CollisionCheckDebugMap & debug_map) +{ + tier4_planning_msgs::msg::SafetyFactorArray safety_factors; + for (const auto & [uuid, data] : debug_map) { + tier4_planning_msgs::msg::SafetyFactor safety_factor; + safety_factor.type = tier4_planning_msgs::msg::SafetyFactor::OBJECT; + safety_factor.is_safe = data.is_safe; + safety_factor.object_id = autoware::universe_utils::toUUIDMsg(uuid); + safety_factor.points.push_back(data.current_obj_pose.position); + safety_factors.factors.push_back(safety_factor); + } + return safety_factors; +} } // namespace autoware::behavior_path_planner::utils::path_safety_checker diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp index 247e22e1aedad..46b6388fd5119 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp @@ -17,6 +17,7 @@ #include "autoware/behavior_path_planner_common/interface/scene_module_interface.hpp" #include "autoware/behavior_path_planner_common/interface/scene_module_visitor.hpp" +#include "autoware/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp" #include "autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp" #include "autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp" #include "autoware/behavior_path_static_obstacle_avoidance_module/shift_line_generator.hpp" @@ -134,7 +135,8 @@ class StaticObstacleAvoidanceModule : public SceneModuleInterface if (finish_distance > -1.0e-03) { planning_factor_interface_->add( start_distance, finish_distance, left_shift.start_pose, left_shift.finish_pose, - PlanningFactor::SHIFT_LEFT, SafetyFactorArray{}); + PlanningFactor::SHIFT_LEFT, + utils::path_safety_checker::to_safety_factor_array(debug_data_.collision_check)); } } @@ -154,7 +156,8 @@ class StaticObstacleAvoidanceModule : public SceneModuleInterface if (finish_distance > -1.0e-03) { planning_factor_interface_->add( start_distance, finish_distance, right_shift.start_pose, right_shift.finish_pose, - PlanningFactor::SHIFT_RIGHT, SafetyFactorArray{}); + PlanningFactor::SHIFT_RIGHT, + utils::path_safety_checker::to_safety_factor_array(debug_data_.collision_check)); } } } diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp index 739b5b21f59dc..e0f96c3ab2ed1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp @@ -1211,9 +1211,12 @@ CandidateOutput StaticObstacleAvoidanceModule::planCandidate() const const uint16_t planning_factor_direction = std::invoke([&output]() { return output.lateral_shift > 0.0 ? PlanningFactor::SHIFT_LEFT : PlanningFactor::SHIFT_RIGHT; }); + planning_factor_interface_->add( output.start_distance_to_path_change, output.finish_distance_to_path_change, sl_front.start, - sl_back.end, planning_factor_direction, SafetyFactorArray{}, true, 0.0, output.lateral_shift); + sl_back.end, planning_factor_direction, + utils::path_safety_checker::to_safety_factor_array(debug_data_.collision_check), true, 0.0, + output.lateral_shift); output.path_candidate = shifted_path.path; return output; From fa4f02359fbcaf548ff54dbd39b8d7ee9e825a01 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Thu, 23 Jan 2025 13:41:53 +0900 Subject: [PATCH 293/334] feat(autoware_tracking_object_merger)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_tracking_object_merger (#9899) Signed-off-by: vish0012 --- .../src/decorative_tracker_merger_node.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/autoware_tracking_object_merger/src/decorative_tracker_merger_node.cpp b/perception/autoware_tracking_object_merger/src/decorative_tracker_merger_node.cpp index 44912e2242eb2..91345c2d10685 100644 --- a/perception/autoware_tracking_object_merger/src/decorative_tracker_merger_node.cpp +++ b/perception/autoware_tracking_object_merger/src/decorative_tracker_merger_node.cpp @@ -247,9 +247,9 @@ void DecorativeTrackerMergerNode::mainObjectsCallback( published_time_publisher_->publish_if_subscribed( merged_object_pub_, tracked_objects.header.stamp); - processing_time_publisher_->publish( + processing_time_publisher_->publish( "debug/cyclic_time_ms", stop_watch_ptr_->toc("cyclic_time", true)); - processing_time_publisher_->publish( + processing_time_publisher_->publish( "debug/processing_time_ms", stop_watch_ptr_->toc("processing_time", true)); } From 231f027371c61525360172cd9ec935018193e25b Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Thu, 23 Jan 2025 14:36:29 +0900 Subject: [PATCH 294/334] feat(traffic_light_fine_detector)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in traffic_light_fine_detector (#9900) Signed-off-by: vish0012 --- perception/autoware_traffic_light_fine_detector/README.md | 8 ++++---- .../autoware_traffic_light_fine_detector/package.xml | 2 +- .../src/traffic_light_fine_detector_node.cpp | 6 +++--- .../src/traffic_light_fine_detector_node.hpp | 4 ++-- 4 files changed, 10 insertions(+), 10 deletions(-) diff --git a/perception/autoware_traffic_light_fine_detector/README.md b/perception/autoware_traffic_light_fine_detector/README.md index df9f297422fce..05a3da5d82e64 100644 --- a/perception/autoware_traffic_light_fine_detector/README.md +++ b/perception/autoware_traffic_light_fine_detector/README.md @@ -36,10 +36,10 @@ ROIs detected from YOLOX will be selected by a combination of `expect/rois`. At ### Output -| Name | Type | Description | -| --------------------- | -------------------------------------------------- | ---------------------------- | -| `~/output/rois` | `tier4_perception_msgs::msg::TrafficLightRoiArray` | The detected accurate rois | -| `~/debug/exe_time_ms` | `tier4_debug_msgs::msg::Float32Stamped` | The time taken for inference | +| Name | Type | Description | +| --------------------- | --------------------------------------------------- | ---------------------------- | +| `~/output/rois` | `tier4_perception_msgs::msg::TrafficLightRoiArray` | The detected accurate rois | +| `~/debug/exe_time_ms` | `autoware_internal_debug_msgs::msg::Float32Stamped` | The time taken for inference | ## Parameters diff --git a/perception/autoware_traffic_light_fine_detector/package.xml b/perception/autoware_traffic_light_fine_detector/package.xml index c9db06669ea99..2b639fb98bebf 100644 --- a/perception/autoware_traffic_light_fine_detector/package.xml +++ b/perception/autoware_traffic_light_fine_detector/package.xml @@ -14,6 +14,7 @@ autoware_cmake + autoware_internal_debug_msgs autoware_tensorrt_yolox cv_bridge image_transport @@ -21,7 +22,6 @@ rclcpp rclcpp_components sensor_msgs - tier4_debug_msgs tier4_perception_msgs autoware_lint_common diff --git a/perception/autoware_traffic_light_fine_detector/src/traffic_light_fine_detector_node.cpp b/perception/autoware_traffic_light_fine_detector/src/traffic_light_fine_detector_node.cpp index bc3d29ce456a8..8e2b2d5b3cfbb 100644 --- a/perception/autoware_traffic_light_fine_detector/src/traffic_light_fine_detector_node.cpp +++ b/perception/autoware_traffic_light_fine_detector/src/traffic_light_fine_detector_node.cpp @@ -101,8 +101,8 @@ TrafficLightFineDetectorNode::TrafficLightFineDetectorNode(const rclcpp::NodeOpt std::lock_guard lock(connect_mutex_); output_roi_pub_ = this->create_publisher("~/output/rois", 1); - exe_time_pub_ = - this->create_publisher("~/debug/exe_time_ms", 1); + exe_time_pub_ = this->create_publisher( + "~/debug/exe_time_ms", 1); if (is_approximate_sync_) { approximate_sync_.reset( new ApproximateSync(ApproximateSyncPolicy(10), image_sub_, rough_roi_sub_, expect_roi_sub_)); @@ -208,7 +208,7 @@ void TrafficLightFineDetectorNode::callback( const auto exe_end_time = high_resolution_clock::now(); const double exe_time = std::chrono::duration_cast(exe_end_time - exe_start_time).count(); - tier4_debug_msgs::msg::Float32Stamped exe_time_msg; + autoware_internal_debug_msgs::msg::Float32Stamped exe_time_msg; exe_time_msg.data = exe_time; exe_time_msg.stamp = this->now(); exe_time_pub_->publish(exe_time_msg); diff --git a/perception/autoware_traffic_light_fine_detector/src/traffic_light_fine_detector_node.hpp b/perception/autoware_traffic_light_fine_detector/src/traffic_light_fine_detector_node.hpp index ada6be3844d77..a1450c0c5230a 100644 --- a/perception/autoware_traffic_light_fine_detector/src/traffic_light_fine_detector_node.hpp +++ b/perception/autoware_traffic_light_fine_detector/src/traffic_light_fine_detector_node.hpp @@ -22,9 +22,9 @@ #include #include +#include #include #include -#include #include #if __has_include() @@ -148,7 +148,7 @@ class TrafficLightFineDetectorNode : public rclcpp::Node message_filters::Subscriber expect_roi_sub_; std::mutex connect_mutex_; rclcpp::Publisher::SharedPtr output_roi_pub_; - rclcpp::Publisher::SharedPtr exe_time_pub_; + rclcpp::Publisher::SharedPtr exe_time_pub_; rclcpp::TimerBase::SharedPtr timer_; typedef message_filters::sync_policies::ExactTime< From 789d5c05634bdc7b5da7721b8066203782f055ba Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Thu, 23 Jan 2025 14:38:52 +0900 Subject: [PATCH 295/334] feat(autoware_euclidean_cluster)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_euclidean_cluster (#9873) feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files perception/autoware_euclidean_cluster Signed-off-by: vish0012 Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> --- .../src/euclidean_cluster_node.cpp | 6 +++--- .../src/voxel_grid_based_euclidean_cluster_node.cpp | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/perception/autoware_euclidean_cluster/src/euclidean_cluster_node.cpp b/perception/autoware_euclidean_cluster/src/euclidean_cluster_node.cpp index cccb05160942c..1a72a813d581b 100644 --- a/perception/autoware_euclidean_cluster/src/euclidean_cluster_node.cpp +++ b/perception/autoware_euclidean_cluster/src/euclidean_cluster_node.cpp @@ -78,11 +78,11 @@ void EuclideanClusterNode::onPointCloud( std::chrono::duration( std::chrono::nanoseconds((this->get_clock()->now() - output.header.stamp).nanoseconds())) .count(); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/pipeline_latency_ms", pipeline_latency_ms); } } diff --git a/perception/autoware_euclidean_cluster/src/voxel_grid_based_euclidean_cluster_node.cpp b/perception/autoware_euclidean_cluster/src/voxel_grid_based_euclidean_cluster_node.cpp index 019001c54ba49..18898fae3bfa0 100644 --- a/perception/autoware_euclidean_cluster/src/voxel_grid_based_euclidean_cluster_node.cpp +++ b/perception/autoware_euclidean_cluster/src/voxel_grid_based_euclidean_cluster_node.cpp @@ -81,11 +81,11 @@ void VoxelGridBasedEuclideanClusterNode::onPointCloud( std::chrono::duration( std::chrono::nanoseconds((this->get_clock()->now() - output.header.stamp).nanoseconds())) .count(); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/pipeline_latency_ms", pipeline_latency_ms); } } From 82c947075b87b5db5256a7d1982357d83a7e7db9 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Thu, 23 Jan 2025 15:15:02 +0900 Subject: [PATCH 296/334] feat(autoware_tensorrt_yolox)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_tensorrt_yolox (#9898) Signed-off-by: vish0012 --- perception/autoware_tensorrt_yolox/package.xml | 1 + .../autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp | 6 +++--- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/perception/autoware_tensorrt_yolox/package.xml b/perception/autoware_tensorrt_yolox/package.xml index e04d839282fd8..40da8422a7b93 100644 --- a/perception/autoware_tensorrt_yolox/package.xml +++ b/perception/autoware_tensorrt_yolox/package.xml @@ -20,6 +20,7 @@ tensorrt_cmake_module autoware_cuda_utils + autoware_internal_debug_msgs autoware_object_recognition_utils autoware_perception_msgs autoware_tensorrt_common diff --git a/perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp b/perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp index 2048279dcf3f1..c8a6b676e6c32 100644 --- a/perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp +++ b/perception/autoware_tensorrt_yolox/src/tensorrt_yolox_node.cpp @@ -212,11 +212,11 @@ void TrtYoloXNode::onImage(const sensor_msgs::msg::Image::ConstSharedPtr msg) std::chrono::nanoseconds( (this->get_clock()->now() - out_objects.header.stamp).nanoseconds())) .count(); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/pipeline_latency_ms", pipeline_latency_ms); } From 24f2656e25b3cbb7337e68654b7a1b3fd7a53684 Mon Sep 17 00:00:00 2001 From: Junya Sasaki Date: Thu, 23 Jan 2025 15:24:12 +0900 Subject: [PATCH 297/334] feat: apply `autoware_` prefix for `dummy_infrastructure` (#9969) * feat(dummy_infrastructure): apply `autoware_` prefix (see below): Note: * In this commit, I did not organize a folder structure. The folder structure will be organized in the next some commits. * The changes will follow the Autoware's guideline as below: - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder Signed-off-by: Junya Sasaki * rename(dummy_infrastructure): move a header under `include/autoware` * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit Signed-off-by: Junya Sasaki * fix(dummy_infrastructure): fix include header path * To follow the previous commit Signed-off-by: Junya Sasaki * rename: `dummy_infrastructure` => `autoware_dummy_infrastructure` Signed-off-by: Junya Sasaki * bug(autoware_dummy_infrastructure): revert wrongly updated copyrights Signed-off-by: Junya Sasaki * update(autoware_dummy_infrastructure): `README.md` Signed-off-by: Junya Sasaki * update: `CODEOWNERS` Signed-off-by: Junya Sasaki * fix(autoware_dummy_infrastructure): fix package name in CHANGELOG.rst Signed-off-by: Ryohsuke Mitsudome * docs(autoware_dummy_infrastructure): fix package name in README and package description Signed-off-by: Ryohsuke Mitsudome --------- Signed-off-by: Junya Sasaki Signed-off-by: Ryohsuke Mitsudome Co-authored-by: Ryohsuke Mitsudome Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> --- .github/CODEOWNERS | 2 +- .../CHANGELOG.rst | 6 +++--- .../CMakeLists.txt | 20 +++++++++++++++++++ .../README.md | 4 ++-- .../config/dummy_infrastructure.param.yaml | 0 .../dummy_infrastructure_node.hpp | 10 +++++----- .../launch/dummy_infrastructure.launch.xml | 4 ++-- .../package.xml | 5 +++-- .../schema/dummy_infrastructure.schema.json | 0 .../dummy_infrastructure_node.cpp | 8 ++++---- system/dummy_infrastructure/CMakeLists.txt | 20 ------------------- 11 files changed, 40 insertions(+), 39 deletions(-) rename system/{dummy_infrastructure => autoware_dummy_infrastructure}/CHANGELOG.rst (97%) create mode 100644 system/autoware_dummy_infrastructure/CMakeLists.txt rename system/{dummy_infrastructure => autoware_dummy_infrastructure}/README.md (94%) rename system/{dummy_infrastructure => autoware_dummy_infrastructure}/config/dummy_infrastructure.param.yaml (100%) rename system/{dummy_infrastructure/include => autoware_dummy_infrastructure/include/autoware}/dummy_infrastructure/dummy_infrastructure_node.hpp (87%) rename system/{dummy_infrastructure => autoware_dummy_infrastructure}/launch/dummy_infrastructure.launch.xml (69%) rename system/{dummy_infrastructure => autoware_dummy_infrastructure}/package.xml (80%) rename system/{dummy_infrastructure => autoware_dummy_infrastructure}/schema/dummy_infrastructure.schema.json (100%) rename system/{dummy_infrastructure => autoware_dummy_infrastructure}/src/dummy_infrastructure_node/dummy_infrastructure_node.cpp (95%) delete mode 100644 system/dummy_infrastructure/CMakeLists.txt diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 3d92cd900e3b2..21674649e67fd 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -218,7 +218,7 @@ system/default_ad_api_helpers/automatic_pose_initializer/** isamu.takagi@tier4.j system/diagnostic_graph_aggregator/** isamu.takagi@tier4.jp system/diagnostic_graph_utils/** isamu.takagi@tier4.jp system/autoware_dummy_diag_publisher/** fumihito.ito@tier4.jp tetsuhiro.kawaguchi@tier4.jp -system/dummy_infrastructure/** ryohsuke.mitsudome@tier4.jp +system/autoware_dummy_infrastructure/** ryohsuke.mitsudome@tier4.jp system/autoware_duplicated_node_checker/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp uken.ryu@tier4.jp junya.sasaki@tier4.jp system/hazard_status_converter/** isamu.takagi@tier4.jp system/mrm_comfortable_stop_operator/** makoto.kurihara@tier4.jp tomohito.ando@tier4.jp diff --git a/system/dummy_infrastructure/CHANGELOG.rst b/system/autoware_dummy_infrastructure/CHANGELOG.rst similarity index 97% rename from system/dummy_infrastructure/CHANGELOG.rst rename to system/autoware_dummy_infrastructure/CHANGELOG.rst index 50ecdd8d7fa96..f42190ddc4b82 100644 --- a/system/dummy_infrastructure/CHANGELOG.rst +++ b/system/autoware_dummy_infrastructure/CHANGELOG.rst @@ -1,6 +1,6 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package dummy_infrastructure -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_dummy_infrastructure +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.40.0 (2024-12-12) ------------------- diff --git a/system/autoware_dummy_infrastructure/CMakeLists.txt b/system/autoware_dummy_infrastructure/CMakeLists.txt new file mode 100644 index 0000000000000..dc025c8d643f1 --- /dev/null +++ b/system/autoware_dummy_infrastructure/CMakeLists.txt @@ -0,0 +1,20 @@ +cmake_minimum_required(VERSION 3.14) +project(autoware_dummy_infrastructure) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_library(autoware_dummy_infrastructure_node_component SHARED + src/dummy_infrastructure_node/dummy_infrastructure_node.cpp +) + +rclcpp_components_register_node(autoware_dummy_infrastructure_node_component + PLUGIN "autoware::dummy_infrastructure::DummyInfrastructureNode" + EXECUTABLE ${PROJECT_NAME}_node +) + +ament_auto_package( + INSTALL_TO_SHARE + launch + config +) diff --git a/system/dummy_infrastructure/README.md b/system/autoware_dummy_infrastructure/README.md similarity index 94% rename from system/dummy_infrastructure/README.md rename to system/autoware_dummy_infrastructure/README.md index d032bfa1a7e3d..a070489ec0513 100644 --- a/system/dummy_infrastructure/README.md +++ b/system/autoware_dummy_infrastructure/README.md @@ -1,11 +1,11 @@ -# dummy_infrastructure +# autoware_dummy_infrastructure This is a debug node for infrastructure communication. ## Usage ```sh -ros2 launch dummy_infrastructure dummy_infrastructure.launch.xml +ros2 launch autoware_dummy_infrastructure dummy_infrastructure.launch.xml ros2 run rqt_reconfigure rqt_reconfigure ``` diff --git a/system/dummy_infrastructure/config/dummy_infrastructure.param.yaml b/system/autoware_dummy_infrastructure/config/dummy_infrastructure.param.yaml similarity index 100% rename from system/dummy_infrastructure/config/dummy_infrastructure.param.yaml rename to system/autoware_dummy_infrastructure/config/dummy_infrastructure.param.yaml diff --git a/system/dummy_infrastructure/include/dummy_infrastructure/dummy_infrastructure_node.hpp b/system/autoware_dummy_infrastructure/include/autoware/dummy_infrastructure/dummy_infrastructure_node.hpp similarity index 87% rename from system/dummy_infrastructure/include/dummy_infrastructure/dummy_infrastructure_node.hpp rename to system/autoware_dummy_infrastructure/include/autoware/dummy_infrastructure/dummy_infrastructure_node.hpp index 38d41750610b1..10f7f81f4e7ff 100644 --- a/system/dummy_infrastructure/include/dummy_infrastructure/dummy_infrastructure_node.hpp +++ b/system/autoware_dummy_infrastructure/include/autoware/dummy_infrastructure/dummy_infrastructure_node.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef DUMMY_INFRASTRUCTURE__DUMMY_INFRASTRUCTURE_NODE_HPP_ -#define DUMMY_INFRASTRUCTURE__DUMMY_INFRASTRUCTURE_NODE_HPP_ +#ifndef AUTOWARE__DUMMY_INFRASTRUCTURE__DUMMY_INFRASTRUCTURE_NODE_HPP_ +#define AUTOWARE__DUMMY_INFRASTRUCTURE__DUMMY_INFRASTRUCTURE_NODE_HPP_ #include @@ -25,7 +25,7 @@ #include #include -namespace dummy_infrastructure +namespace autoware::dummy_infrastructure { using tier4_v2x_msgs::msg::InfrastructureCommand; using tier4_v2x_msgs::msg::InfrastructureCommandArray; @@ -75,6 +75,6 @@ class DummyInfrastructureNode : public rclcpp::Node NodeParam node_param_{}; }; -} // namespace dummy_infrastructure +} // namespace autoware::dummy_infrastructure -#endif // DUMMY_INFRASTRUCTURE__DUMMY_INFRASTRUCTURE_NODE_HPP_ +#endif // AUTOWARE__DUMMY_INFRASTRUCTURE__DUMMY_INFRASTRUCTURE_NODE_HPP_ diff --git a/system/dummy_infrastructure/launch/dummy_infrastructure.launch.xml b/system/autoware_dummy_infrastructure/launch/dummy_infrastructure.launch.xml similarity index 69% rename from system/dummy_infrastructure/launch/dummy_infrastructure.launch.xml rename to system/autoware_dummy_infrastructure/launch/dummy_infrastructure.launch.xml index bc45abdebec70..8dea215e4a546 100644 --- a/system/dummy_infrastructure/launch/dummy_infrastructure.launch.xml +++ b/system/autoware_dummy_infrastructure/launch/dummy_infrastructure.launch.xml @@ -7,10 +7,10 @@ - + - + diff --git a/system/dummy_infrastructure/package.xml b/system/autoware_dummy_infrastructure/package.xml similarity index 80% rename from system/dummy_infrastructure/package.xml rename to system/autoware_dummy_infrastructure/package.xml index 49c1b00757094..fd710eb1efeb0 100644 --- a/system/dummy_infrastructure/package.xml +++ b/system/autoware_dummy_infrastructure/package.xml @@ -1,10 +1,11 @@ - dummy_infrastructure + autoware_dummy_infrastructure 0.40.0 - dummy_infrastructure + autoware_dummy_infrastructure Ryohsuke Mitsudome + Junya Sasaki Apache License 2.0 ament_cmake_auto diff --git a/system/dummy_infrastructure/schema/dummy_infrastructure.schema.json b/system/autoware_dummy_infrastructure/schema/dummy_infrastructure.schema.json similarity index 100% rename from system/dummy_infrastructure/schema/dummy_infrastructure.schema.json rename to system/autoware_dummy_infrastructure/schema/dummy_infrastructure.schema.json diff --git a/system/dummy_infrastructure/src/dummy_infrastructure_node/dummy_infrastructure_node.cpp b/system/autoware_dummy_infrastructure/src/dummy_infrastructure_node/dummy_infrastructure_node.cpp similarity index 95% rename from system/dummy_infrastructure/src/dummy_infrastructure_node/dummy_infrastructure_node.cpp rename to system/autoware_dummy_infrastructure/src/dummy_infrastructure_node/dummy_infrastructure_node.cpp index 4760c9366da46..2f1500e7db1e0 100644 --- a/system/dummy_infrastructure/src/dummy_infrastructure_node/dummy_infrastructure_node.cpp +++ b/system/autoware_dummy_infrastructure/src/dummy_infrastructure_node/dummy_infrastructure_node.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "dummy_infrastructure/dummy_infrastructure_node.hpp" +#include "autoware/dummy_infrastructure/dummy_infrastructure_node.hpp" #include @@ -25,7 +25,7 @@ using std::chrono::duration; using std::chrono::duration_cast; using std::chrono::nanoseconds; -namespace dummy_infrastructure +namespace autoware::dummy_infrastructure { namespace { @@ -192,7 +192,7 @@ void DummyInfrastructureNode::onTimer() pub_state_array_->publish(state_array); } -} // namespace dummy_infrastructure +} // namespace autoware::dummy_infrastructure #include -RCLCPP_COMPONENTS_REGISTER_NODE(dummy_infrastructure::DummyInfrastructureNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::dummy_infrastructure::DummyInfrastructureNode) diff --git a/system/dummy_infrastructure/CMakeLists.txt b/system/dummy_infrastructure/CMakeLists.txt deleted file mode 100644 index 5d3d39d02365d..0000000000000 --- a/system/dummy_infrastructure/CMakeLists.txt +++ /dev/null @@ -1,20 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(dummy_infrastructure) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -ament_auto_add_library(dummy_infrastructure_node_component SHARED - src/dummy_infrastructure_node/dummy_infrastructure_node.cpp -) - -rclcpp_components_register_node(dummy_infrastructure_node_component - PLUGIN "dummy_infrastructure::DummyInfrastructureNode" - EXECUTABLE dummy_infrastructure_node -) - -ament_auto_package( - INSTALL_TO_SHARE - launch - config -) From 8eed7e9782c71e078b121cbdec94d73dfce25723 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Thu, 23 Jan 2025 15:33:57 +0900 Subject: [PATCH 298/334] feat(autoware_image_projection_based_fusion)!: tier4_debug-msgs changed to autoware_internal_debug_msgs in autoware_image_projection_based_fusion (#9877) Signed-off-by: vish0012 --- .../package.xml | 1 + .../src/fusion_node.cpp | 15 ++++++++------- 2 files changed, 9 insertions(+), 7 deletions(-) diff --git a/perception/autoware_image_projection_based_fusion/package.xml b/perception/autoware_image_projection_based_fusion/package.xml index 025ed5377fa72..fa6217f589627 100644 --- a/perception/autoware_image_projection_based_fusion/package.xml +++ b/perception/autoware_image_projection_based_fusion/package.xml @@ -17,6 +17,7 @@ autoware_cmake autoware_euclidean_cluster + autoware_internal_debug_msgs autoware_lidar_centerpoint autoware_object_recognition_utils autoware_perception_msgs diff --git a/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp b/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp index f7861d91b6712..53b18e20883bc 100644 --- a/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp @@ -20,6 +20,7 @@ #include #include +#include #include #include @@ -253,12 +254,12 @@ void FusionNode::exportProcess() std::chrono::nanoseconds( (this->get_clock()->now() - cached_det3d_msg_ptr_->header.stamp).nanoseconds())) .count(); - debug_publisher_->publish( + debug_publisher_->publish( "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( + debug_publisher_->publish( "debug/processing_time_ms", processing_time_ms + stop_watch_ptr_->toc("processing_time", true)); - debug_publisher_->publish( + debug_publisher_->publish( "debug/pipeline_latency_ms", pipeline_latency_ms); processing_time_ms = 0; } @@ -353,9 +354,9 @@ void FusionNode::subCallback( // add timestamp interval for debug if (debug_internal_pub_) { double timestamp_interval_ms = (matched_stamp - timestamp_nsec) / 1e6; - debug_internal_pub_->publish( + debug_internal_pub_->publish( "debug/roi" + std::to_string(roi_i) + "/timestamp_interval_ms", timestamp_interval_ms); - debug_internal_pub_->publish( + debug_internal_pub_->publish( "debug/roi" + std::to_string(roi_i) + "/timestamp_interval_offset_ms", timestamp_interval_ms - det2d.input_offset_ms); } @@ -418,9 +419,9 @@ void FusionNode::roiCallback( if (debug_internal_pub_) { double timestamp_interval_ms = (timestamp_nsec - cached_det3d_msg_timestamp_) / 1e6; - debug_internal_pub_->publish( + debug_internal_pub_->publish( "debug/roi" + std::to_string(roi_i) + "/timestamp_interval_ms", timestamp_interval_ms); - debug_internal_pub_->publish( + debug_internal_pub_->publish( "debug/roi" + std::to_string(roi_i) + "/timestamp_interval_offset_ms", timestamp_interval_ms - det2d.input_offset_ms); } From 4b6a342b03d818c47de4f46111dcbbcf33506797 Mon Sep 17 00:00:00 2001 From: Junya Sasaki Date: Thu, 23 Jan 2025 16:52:55 +0900 Subject: [PATCH 299/334] feat: apply `autoware_` prefix for `fault_injection` (#9989) * feat(fault_injection): apply `autoware_` prefix (see below): Note: * In this commit, I did not organize a folder structure. The folder structure will be organized in the next some commits. * The changes will follow the Autoware's guideline as below: - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder Signed-off-by: Junya Sasaki * rename(fault_injection): move headers under `include/autoware`: * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit Signed-off-by: Junya Sasaki * fix(fault_injection): fix include header paths * To follow the previous commit Signed-off-by: Junya Sasaki * rename: `fault_injection` => `autoware_fault_injection` Signed-off-by: Junya Sasaki * Fixed exec_depend Signed-off-by: Shintaro Sakoda --------- Signed-off-by: Junya Sasaki Signed-off-by: Shintaro Sakoda Co-authored-by: SakodaShintaro --- launch/tier4_simulator_launch/package.xml | 2 +- .../CHANGELOG.rst | 0 .../CMakeLists.txt | 12 ++++++------ .../README.md | 0 .../config/fault_injection.param.yaml | 0 .../img/component.drawio.svg | 0 .../fault_injection/diagnostic_storage.hpp | 12 ++++++------ .../fault_injection_diag_updater.hpp | 12 ++++++------ .../fault_injection/fault_injection_node.hpp | 16 ++++++++-------- .../launch/fault_injection.launch.xml | 10 ++++++++++ .../package.xml | 5 +++-- .../fault_injection_node.cpp | 11 ++++------- .../test/config/test_event_diag.param.yaml | 0 .../test/launch/test_fault_injection.launch.xml | 6 ++++++ .../test/src/main.cpp | 2 +- .../test/src/test_diagnostic_storage.cpp | 13 +++++++++---- .../test/test_fault_injection_node.test.py | 4 ++-- .../launch/fault_injection.launch.xml | 10 ---------- .../test/launch/test_fault_injection.launch.xml | 6 ------ 19 files changed, 62 insertions(+), 59 deletions(-) rename simulator/{fault_injection => autoware_fault_injection}/CHANGELOG.rst (100%) rename simulator/{fault_injection => autoware_fault_injection}/CMakeLists.txt (74%) rename simulator/{fault_injection => autoware_fault_injection}/README.md (100%) rename simulator/{fault_injection => autoware_fault_injection}/config/fault_injection.param.yaml (100%) rename simulator/{fault_injection => autoware_fault_injection}/img/component.drawio.svg (100%) rename simulator/{fault_injection/include => autoware_fault_injection/include/autoware}/fault_injection/diagnostic_storage.hpp (85%) rename simulator/{fault_injection/include => autoware_fault_injection/include/autoware}/fault_injection/fault_injection_diag_updater.hpp (95%) rename simulator/{fault_injection/include => autoware_fault_injection/include/autoware}/fault_injection/fault_injection_node.hpp (74%) create mode 100644 simulator/autoware_fault_injection/launch/fault_injection.launch.xml rename simulator/{fault_injection => autoware_fault_injection}/package.xml (87%) rename simulator/{fault_injection => autoware_fault_injection}/src/fault_injection_node/fault_injection_node.cpp (93%) rename simulator/{fault_injection => autoware_fault_injection}/test/config/test_event_diag.param.yaml (100%) create mode 100644 simulator/autoware_fault_injection/test/launch/test_fault_injection.launch.xml rename simulator/{fault_injection => autoware_fault_injection}/test/src/main.cpp (95%) rename simulator/{fault_injection => autoware_fault_injection}/test/src/test_diagnostic_storage.cpp (82%) rename simulator/{fault_injection => autoware_fault_injection}/test/test_fault_injection_node.test.py (98%) delete mode 100644 simulator/fault_injection/launch/fault_injection.launch.xml delete mode 100644 simulator/fault_injection/test/launch/test_fault_injection.launch.xml diff --git a/launch/tier4_simulator_launch/package.xml b/launch/tier4_simulator_launch/package.xml index 19bc81b056b60..fba24d0a5d525 100644 --- a/launch/tier4_simulator_launch/package.xml +++ b/launch/tier4_simulator_launch/package.xml @@ -14,8 +14,8 @@ ament_cmake_auto autoware_cmake + autoware_fault_injection dummy_perception_publisher - fault_injection simple_planning_simulator ament_lint_auto diff --git a/simulator/fault_injection/CHANGELOG.rst b/simulator/autoware_fault_injection/CHANGELOG.rst similarity index 100% rename from simulator/fault_injection/CHANGELOG.rst rename to simulator/autoware_fault_injection/CHANGELOG.rst diff --git a/simulator/fault_injection/CMakeLists.txt b/simulator/autoware_fault_injection/CMakeLists.txt similarity index 74% rename from simulator/fault_injection/CMakeLists.txt rename to simulator/autoware_fault_injection/CMakeLists.txt index 11bf03facd67f..16f8518609f82 100644 --- a/simulator/fault_injection/CMakeLists.txt +++ b/simulator/autoware_fault_injection/CMakeLists.txt @@ -1,18 +1,18 @@ cmake_minimum_required(VERSION 3.14) -project(fault_injection) +project(autoware_fault_injection) find_package(autoware_cmake REQUIRED) autoware_package() find_package(pluginlib REQUIRED) -ament_auto_add_library(fault_injection_node_component SHARED +ament_auto_add_library(${PROJECT_NAME}_node_component SHARED src/fault_injection_node/fault_injection_node.cpp ) -rclcpp_components_register_node(fault_injection_node_component - PLUGIN "fault_injection::FaultInjectionNode" - EXECUTABLE fault_injection_node +rclcpp_components_register_node(${PROJECT_NAME}_node_component + PLUGIN "autoware::simulator::fault_injection::FaultInjectionNode" + EXECUTABLE ${PROJECT_NAME}_node ) if(BUILD_TESTING) @@ -23,7 +23,7 @@ if(BUILD_TESTING) ) target_link_libraries(test_fault_injection_node_component - fault_injection_node_component + ${PROJECT_NAME}_node_component ) # launch_testing diff --git a/simulator/fault_injection/README.md b/simulator/autoware_fault_injection/README.md similarity index 100% rename from simulator/fault_injection/README.md rename to simulator/autoware_fault_injection/README.md diff --git a/simulator/fault_injection/config/fault_injection.param.yaml b/simulator/autoware_fault_injection/config/fault_injection.param.yaml similarity index 100% rename from simulator/fault_injection/config/fault_injection.param.yaml rename to simulator/autoware_fault_injection/config/fault_injection.param.yaml diff --git a/simulator/fault_injection/img/component.drawio.svg b/simulator/autoware_fault_injection/img/component.drawio.svg similarity index 100% rename from simulator/fault_injection/img/component.drawio.svg rename to simulator/autoware_fault_injection/img/component.drawio.svg diff --git a/simulator/fault_injection/include/fault_injection/diagnostic_storage.hpp b/simulator/autoware_fault_injection/include/autoware/fault_injection/diagnostic_storage.hpp similarity index 85% rename from simulator/fault_injection/include/fault_injection/diagnostic_storage.hpp rename to simulator/autoware_fault_injection/include/autoware/fault_injection/diagnostic_storage.hpp index a6c6b816c99f7..e6522188b71df 100644 --- a/simulator/fault_injection/include/fault_injection/diagnostic_storage.hpp +++ b/simulator/autoware_fault_injection/include/autoware/fault_injection/diagnostic_storage.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2025 Tier IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef FAULT_INJECTION__DIAGNOSTIC_STORAGE_HPP_ -#define FAULT_INJECTION__DIAGNOSTIC_STORAGE_HPP_ +#ifndef AUTOWARE__FAULT_INJECTION__DIAGNOSTIC_STORAGE_HPP_ +#define AUTOWARE__FAULT_INJECTION__DIAGNOSTIC_STORAGE_HPP_ #include @@ -22,7 +22,7 @@ #include #include -namespace fault_injection +namespace autoware::simulator::fault_injection { using diagnostic_msgs::msg::DiagnosticStatus; @@ -65,6 +65,6 @@ class DiagnosticStorage std::unordered_map event_diag_map_; }; -} // namespace fault_injection +} // namespace autoware::simulator::fault_injection -#endif // FAULT_INJECTION__DIAGNOSTIC_STORAGE_HPP_ +#endif // AUTOWARE__FAULT_INJECTION__DIAGNOSTIC_STORAGE_HPP_ diff --git a/simulator/fault_injection/include/fault_injection/fault_injection_diag_updater.hpp b/simulator/autoware_fault_injection/include/autoware/fault_injection/fault_injection_diag_updater.hpp similarity index 95% rename from simulator/fault_injection/include/fault_injection/fault_injection_diag_updater.hpp rename to simulator/autoware_fault_injection/include/autoware/fault_injection/fault_injection_diag_updater.hpp index 0a71c1681d1d3..7d6b553c35999 100644 --- a/simulator/fault_injection/include/fault_injection/fault_injection_diag_updater.hpp +++ b/simulator/autoware_fault_injection/include/autoware/fault_injection/fault_injection_diag_updater.hpp @@ -1,4 +1,4 @@ -// Copyright 2024 TIER IV, Inc. +// Copyright 2025 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -46,8 +46,8 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#ifndef FAULT_INJECTION__FAULT_INJECTION_DIAG_UPDATER_HPP_ -#define FAULT_INJECTION__FAULT_INJECTION_DIAG_UPDATER_HPP_ +#ifndef AUTOWARE__FAULT_INJECTION__FAULT_INJECTION_DIAG_UPDATER_HPP_ +#define AUTOWARE__FAULT_INJECTION__FAULT_INJECTION_DIAG_UPDATER_HPP_ #include @@ -57,7 +57,7 @@ #include #include -namespace fault_injection +namespace autoware::simulator::fault_injection { class FaultInjectionDiagUpdater : public diagnostic_updater::DiagnosticTaskVector { @@ -240,6 +240,6 @@ class FaultInjectionDiagUpdater : public diagnostic_updater::DiagnosticTaskVecto std::string hardware_id_; std::string node_name_; }; -} // namespace fault_injection +} // namespace autoware::simulator::fault_injection -#endif // FAULT_INJECTION__FAULT_INJECTION_DIAG_UPDATER_HPP_ +#endif // AUTOWARE__FAULT_INJECTION__FAULT_INJECTION_DIAG_UPDATER_HPP_ diff --git a/simulator/fault_injection/include/fault_injection/fault_injection_node.hpp b/simulator/autoware_fault_injection/include/autoware/fault_injection/fault_injection_node.hpp similarity index 74% rename from simulator/fault_injection/include/fault_injection/fault_injection_node.hpp rename to simulator/autoware_fault_injection/include/autoware/fault_injection/fault_injection_node.hpp index 999d18b38c7b0..b423c9e5e56df 100644 --- a/simulator/fault_injection/include/fault_injection/fault_injection_node.hpp +++ b/simulator/autoware_fault_injection/include/autoware/fault_injection/fault_injection_node.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2025 Tier IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef FAULT_INJECTION__FAULT_INJECTION_NODE_HPP_ -#define FAULT_INJECTION__FAULT_INJECTION_NODE_HPP_ +#ifndef AUTOWARE__FAULT_INJECTION__FAULT_INJECTION_NODE_HPP_ +#define AUTOWARE__FAULT_INJECTION__FAULT_INJECTION_NODE_HPP_ -#include "fault_injection/diagnostic_storage.hpp" -#include "fault_injection/fault_injection_diag_updater.hpp" +#include "autoware/fault_injection/diagnostic_storage.hpp" +#include "autoware/fault_injection/fault_injection_diag_updater.hpp" #include @@ -25,7 +25,7 @@ #include #include -namespace fault_injection +namespace autoware::simulator::fault_injection { using tier4_simulation_msgs::msg::SimulationEvents; @@ -49,6 +49,6 @@ class FaultInjectionNode : public rclcpp::Node DiagnosticStorage diagnostic_storage_; }; -} // namespace fault_injection +} // namespace autoware::simulator::fault_injection -#endif // FAULT_INJECTION__FAULT_INJECTION_NODE_HPP_ +#endif // AUTOWARE__FAULT_INJECTION__FAULT_INJECTION_NODE_HPP_ diff --git a/simulator/autoware_fault_injection/launch/fault_injection.launch.xml b/simulator/autoware_fault_injection/launch/fault_injection.launch.xml new file mode 100644 index 0000000000000..9c521acc52794 --- /dev/null +++ b/simulator/autoware_fault_injection/launch/fault_injection.launch.xml @@ -0,0 +1,10 @@ + + + + + + + + + + diff --git a/simulator/fault_injection/package.xml b/simulator/autoware_fault_injection/package.xml similarity index 87% rename from simulator/fault_injection/package.xml rename to simulator/autoware_fault_injection/package.xml index feedcf3333f7f..15391feced80f 100644 --- a/simulator/fault_injection/package.xml +++ b/simulator/autoware_fault_injection/package.xml @@ -1,10 +1,11 @@ - fault_injection + autoware_fault_injection 0.40.0 - fault_injection + The fault_injection package Keisuke Shima + Junya Sasaki Apache License 2.0 ament_cmake_auto diff --git a/simulator/fault_injection/src/fault_injection_node/fault_injection_node.cpp b/simulator/autoware_fault_injection/src/fault_injection_node/fault_injection_node.cpp similarity index 93% rename from simulator/fault_injection/src/fault_injection_node/fault_injection_node.cpp rename to simulator/autoware_fault_injection/src/fault_injection_node/fault_injection_node.cpp index 467054dcda8fe..5e65b4bdcc327 100644 --- a/simulator/fault_injection/src/fault_injection_node/fault_injection_node.cpp +++ b/simulator/autoware_fault_injection/src/fault_injection_node/fault_injection_node.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "fault_injection/fault_injection_node.hpp" +#include "autoware/fault_injection/fault_injection_node.hpp" #include @@ -21,7 +21,7 @@ #include #include -namespace +namespace autoware::simulator::fault_injection { std::vector split(const std::string & str, const char delim) { @@ -33,10 +33,7 @@ std::vector split(const std::string & str, const char delim) } return elems; } -} // namespace -namespace fault_injection -{ #ifdef ROS_DISTRO_GALACTIC using rosidl_generator_traits::to_yaml; #endif @@ -101,7 +98,7 @@ std::vector FaultInjectionNode::read_event_diag_list() return diag_configs; } -} // namespace fault_injection +} // namespace autoware::simulator::fault_injection #include -RCLCPP_COMPONENTS_REGISTER_NODE(fault_injection::FaultInjectionNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::simulator::fault_injection::FaultInjectionNode) diff --git a/simulator/fault_injection/test/config/test_event_diag.param.yaml b/simulator/autoware_fault_injection/test/config/test_event_diag.param.yaml similarity index 100% rename from simulator/fault_injection/test/config/test_event_diag.param.yaml rename to simulator/autoware_fault_injection/test/config/test_event_diag.param.yaml diff --git a/simulator/autoware_fault_injection/test/launch/test_fault_injection.launch.xml b/simulator/autoware_fault_injection/test/launch/test_fault_injection.launch.xml new file mode 100644 index 0000000000000..76488d625dbe4 --- /dev/null +++ b/simulator/autoware_fault_injection/test/launch/test_fault_injection.launch.xml @@ -0,0 +1,6 @@ + + + + + + diff --git a/simulator/fault_injection/test/src/main.cpp b/simulator/autoware_fault_injection/test/src/main.cpp similarity index 95% rename from simulator/fault_injection/test/src/main.cpp rename to simulator/autoware_fault_injection/test/src/main.cpp index bc077b74c48f5..dbd4824169399 100644 --- a/simulator/fault_injection/test/src/main.cpp +++ b/simulator/autoware_fault_injection/test/src/main.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2025 Tier IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. diff --git a/simulator/fault_injection/test/src/test_diagnostic_storage.cpp b/simulator/autoware_fault_injection/test/src/test_diagnostic_storage.cpp similarity index 82% rename from simulator/fault_injection/test/src/test_diagnostic_storage.cpp rename to simulator/autoware_fault_injection/test/src/test_diagnostic_storage.cpp index 311401df37e59..7d9ea6145bcc8 100644 --- a/simulator/fault_injection/test/src/test_diagnostic_storage.cpp +++ b/simulator/autoware_fault_injection/test/src/test_diagnostic_storage.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2025 Tier IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "fault_injection/diagnostic_storage.hpp" +#include "autoware/fault_injection/diagnostic_storage.hpp" #include @@ -20,6 +20,9 @@ #include #include +namespace autoware::simulator::fault_injection +{ + class TestDiagnosticStorage : public ::testing::Test { protected: @@ -30,8 +33,8 @@ class TestDiagnosticStorage : public ::testing::Test } } - fault_injection::DiagnosticStorage storage_; - const std::vector diag_config{ + DiagnosticStorage storage_; + const std::vector diag_config{ {"foo", "foo_diag"}, }; }; @@ -52,3 +55,5 @@ TEST_F(TestDiagnosticStorage, raise_exception_with_wrong_key) { EXPECT_ANY_THROW(storage_.getDiag("invalid_name")); } + +} // namespace autoware::simulator::fault_injection diff --git a/simulator/fault_injection/test/test_fault_injection_node.test.py b/simulator/autoware_fault_injection/test/test_fault_injection_node.test.py similarity index 98% rename from simulator/fault_injection/test/test_fault_injection_node.test.py rename to simulator/autoware_fault_injection/test/test_fault_injection_node.test.py index 1437d69b1c91b..a9516a531479f 100644 --- a/simulator/fault_injection/test/test_fault_injection_node.test.py +++ b/simulator/autoware_fault_injection/test/test_fault_injection_node.test.py @@ -1,4 +1,4 @@ -# Copyright 2021 Tier IV, Inc. +# Copyright 2025 Tier IV, Inc. # # Licensed under the Apache License, Version 2.0 (the "License"); # you may not use this file except in compliance with the License. @@ -35,7 +35,7 @@ @pytest.mark.launch_test def generate_test_description(): test_fault_injection_launch_file = os.path.join( - get_package_share_directory("fault_injection"), + get_package_share_directory("autoware_fault_injection"), "launch", "test_fault_injection.launch.xml", ) diff --git a/simulator/fault_injection/launch/fault_injection.launch.xml b/simulator/fault_injection/launch/fault_injection.launch.xml deleted file mode 100644 index 94b1fe8a62e6b..0000000000000 --- a/simulator/fault_injection/launch/fault_injection.launch.xml +++ /dev/null @@ -1,10 +0,0 @@ - - - - - - - - - - diff --git a/simulator/fault_injection/test/launch/test_fault_injection.launch.xml b/simulator/fault_injection/test/launch/test_fault_injection.launch.xml deleted file mode 100644 index 1d4bcd7c96d9b..0000000000000 --- a/simulator/fault_injection/test/launch/test_fault_injection.launch.xml +++ /dev/null @@ -1,6 +0,0 @@ - - - - - - From 9c39d3f58ffb9c7a8315dd62b70237f64896cf52 Mon Sep 17 00:00:00 2001 From: Junya Sasaki Date: Thu, 23 Jan 2025 17:16:34 +0900 Subject: [PATCH 300/334] feat: apply `autoware_` prefix for `vehicle_door_simulator` (#9997) Signed-off-by: Junya Sasaki Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .github/CODEOWNERS | 2 +- launch/tier4_simulator_launch/launch/simulator.launch.xml | 2 +- .../CHANGELOG.rst | 0 .../CMakeLists.txt | 4 ++-- .../README.md | 2 +- .../launch/vehicle_door_simulator.launch.xml | 2 +- .../package.xml | 3 ++- .../src/dummy_doors.cpp | 8 ++++---- .../src/dummy_doors.hpp | 4 ++-- 9 files changed, 14 insertions(+), 13 deletions(-) rename simulator/{vehicle_door_simulator => autoware_vehicle_door_simulator}/CHANGELOG.rst (100%) rename simulator/{vehicle_door_simulator => autoware_vehicle_door_simulator}/CMakeLists.txt (65%) rename simulator/{vehicle_door_simulator => autoware_vehicle_door_simulator}/README.md (68%) rename simulator/{vehicle_door_simulator => autoware_vehicle_door_simulator}/launch/vehicle_door_simulator.launch.xml (70%) rename simulator/{vehicle_door_simulator => autoware_vehicle_door_simulator}/package.xml (85%) rename simulator/{vehicle_door_simulator => autoware_vehicle_door_simulator}/src/dummy_doors.cpp (93%) rename simulator/{vehicle_door_simulator => autoware_vehicle_door_simulator}/src/dummy_doors.hpp (95%) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 21674649e67fd..096a610d7873e 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -206,7 +206,7 @@ simulator/fault_injection/** keisuke.shima@tier4.jp simulator/learning_based_vehicle_model/** maxime.clement@tier4.jp nagy.tomas@tier4.jp simulator/simple_planning_simulator/** mamoru.sobue@tier4.jp maxime.clement@tier4.jp takamasa.horibe@tier4.jp temkei.kem@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp kotaro.yoshimoto@tier4.jp simulator/tier4_dummy_object_rviz_plugin/** yukihiro.saito@tier4.jp -simulator/vehicle_door_simulator/** isamu.takagi@tier4.jp +simulator/autoware_vehicle_door_simulator/** isamu.takagi@tier4.jp junya.sasaki@tier4.jp system/autoware_component_monitor/** baris@leodrive.ai memin@leodrive.ai yavuz@leodrive.ai system/autoware_default_adapi/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp system/autoware_processing_time_checker/** kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp diff --git a/launch/tier4_simulator_launch/launch/simulator.launch.xml b/launch/tier4_simulator_launch/launch/simulator.launch.xml index 67c05a2b4d069..fa457a31f8c43 100644 --- a/launch/tier4_simulator_launch/launch/simulator.launch.xml +++ b/launch/tier4_simulator_launch/launch/simulator.launch.xml @@ -203,7 +203,7 @@ - + diff --git a/simulator/vehicle_door_simulator/CHANGELOG.rst b/simulator/autoware_vehicle_door_simulator/CHANGELOG.rst similarity index 100% rename from simulator/vehicle_door_simulator/CHANGELOG.rst rename to simulator/autoware_vehicle_door_simulator/CHANGELOG.rst diff --git a/simulator/vehicle_door_simulator/CMakeLists.txt b/simulator/autoware_vehicle_door_simulator/CMakeLists.txt similarity index 65% rename from simulator/vehicle_door_simulator/CMakeLists.txt rename to simulator/autoware_vehicle_door_simulator/CMakeLists.txt index fbe989555c4ba..d715608a5d122 100644 --- a/simulator/vehicle_door_simulator/CMakeLists.txt +++ b/simulator/autoware_vehicle_door_simulator/CMakeLists.txt @@ -1,10 +1,10 @@ cmake_minimum_required(VERSION 3.14) -project(vehicle_door_simulator) +project(autoware_vehicle_door_simulator) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_executable(dummy_doors +ament_auto_add_executable(${PROJECT_NAME}_node src/dummy_doors.cpp ) diff --git a/simulator/vehicle_door_simulator/README.md b/simulator/autoware_vehicle_door_simulator/README.md similarity index 68% rename from simulator/vehicle_door_simulator/README.md rename to simulator/autoware_vehicle_door_simulator/README.md index f312216622a5b..d3fe0a30993ab 100644 --- a/simulator/vehicle_door_simulator/README.md +++ b/simulator/autoware_vehicle_door_simulator/README.md @@ -1,3 +1,3 @@ -# vehicle_door_simulator +# autoware_vehicle_door_simulator This package is for testing operations on vehicle devices such as doors. diff --git a/simulator/vehicle_door_simulator/launch/vehicle_door_simulator.launch.xml b/simulator/autoware_vehicle_door_simulator/launch/vehicle_door_simulator.launch.xml similarity index 70% rename from simulator/vehicle_door_simulator/launch/vehicle_door_simulator.launch.xml rename to simulator/autoware_vehicle_door_simulator/launch/vehicle_door_simulator.launch.xml index 66857130a4932..e550a460e8807 100644 --- a/simulator/vehicle_door_simulator/launch/vehicle_door_simulator.launch.xml +++ b/simulator/autoware_vehicle_door_simulator/launch/vehicle_door_simulator.launch.xml @@ -1,5 +1,5 @@ - + diff --git a/simulator/vehicle_door_simulator/package.xml b/simulator/autoware_vehicle_door_simulator/package.xml similarity index 85% rename from simulator/vehicle_door_simulator/package.xml rename to simulator/autoware_vehicle_door_simulator/package.xml index ca9d7c98e691a..2a92e6240eba3 100644 --- a/simulator/vehicle_door_simulator/package.xml +++ b/simulator/autoware_vehicle_door_simulator/package.xml @@ -1,10 +1,11 @@ - vehicle_door_simulator + autoware_vehicle_door_simulator 0.40.0 The vehicle_door_simulator package Takagi, Isamu + Junya Sasaki Apache License 2.0 ament_cmake_auto diff --git a/simulator/vehicle_door_simulator/src/dummy_doors.cpp b/simulator/autoware_vehicle_door_simulator/src/dummy_doors.cpp similarity index 93% rename from simulator/vehicle_door_simulator/src/dummy_doors.cpp rename to simulator/autoware_vehicle_door_simulator/src/dummy_doors.cpp index cad0aa721dc73..001213918c900 100644 --- a/simulator/vehicle_door_simulator/src/dummy_doors.cpp +++ b/simulator/autoware_vehicle_door_simulator/src/dummy_doors.cpp @@ -16,10 +16,10 @@ #include -namespace vehicle_door_simulator +namespace autoware::vehicle_door_simulator { -DummyDoors::DummyDoors() : Node("dummy_doors") +DummyDoors::DummyDoors() : Node("vehicle_door_simulator_node") { using std::placeholders::_1; using std::placeholders::_2; @@ -112,13 +112,13 @@ void DummyDoors::on_timer() pub_status_->publish(message); } -} // namespace vehicle_door_simulator +} // namespace autoware::vehicle_door_simulator int main(int argc, char ** argv) { rclcpp::init(argc, argv); rclcpp::executors::SingleThreadedExecutor executor; - auto node = std::make_shared(); + auto node = std::make_shared(); executor.add_node(node); executor.spin(); executor.remove_node(node); diff --git a/simulator/vehicle_door_simulator/src/dummy_doors.hpp b/simulator/autoware_vehicle_door_simulator/src/dummy_doors.hpp similarity index 95% rename from simulator/vehicle_door_simulator/src/dummy_doors.hpp rename to simulator/autoware_vehicle_door_simulator/src/dummy_doors.hpp index 485586fa8724e..452d11c5414e3 100644 --- a/simulator/vehicle_door_simulator/src/dummy_doors.hpp +++ b/simulator/autoware_vehicle_door_simulator/src/dummy_doors.hpp @@ -23,7 +23,7 @@ #include -namespace vehicle_door_simulator +namespace autoware::vehicle_door_simulator { class DummyDoors : public rclcpp::Node @@ -57,6 +57,6 @@ class DummyDoors : public rclcpp::Node std::array statuses_; }; -} // namespace vehicle_door_simulator +} // namespace autoware::vehicle_door_simulator #endif // DUMMY_DOORS_HPP_ From cacab80001ab479be1ad37252a84ea15b030d73d Mon Sep 17 00:00:00 2001 From: Junya Sasaki Date: Thu, 23 Jan 2025 17:26:22 +0900 Subject: [PATCH 301/334] feat: apply `autoware_` prefix for `default_ad_api_helpers` (#9965) Signed-off-by: Junya Sasaki Signed-off-by: Takagi, Isamu Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Takagi, Isamu --- .github/CODEOWNERS | 6 +++--- .../launch/autoware_api.launch.xml | 2 +- launch/tier4_autoware_api_launch/package.xml | 2 +- .../pose_twist_estimator/pose_twist_estimator.launch.xml | 2 +- launch/tier4_localization_launch/package.xml | 2 +- localization/autoware_pose_initializer/README.md | 2 +- system/autoware_default_adapi/script/web_server.py | 2 +- .../autoware_adapi_adaptors}/CHANGELOG.rst | 0 .../autoware_adapi_adaptors}/CMakeLists.txt | 6 +++--- .../autoware_adapi_adaptors}/README.md | 4 ++-- .../config/initial_pose.param.yaml | 0 .../launch/rviz_adaptors.launch.xml | 8 ++++---- .../autoware_adapi_adaptors}/package.xml | 5 +++-- .../schema/adapi_adaptors.schema.json} | 4 ++-- .../autoware_adapi_adaptors}/src/initial_pose_adaptor.cpp | 8 ++++---- .../autoware_adapi_adaptors}/src/initial_pose_adaptor.hpp | 4 ++-- .../autoware_adapi_adaptors}/src/routing_adaptor.cpp | 8 ++++---- .../autoware_adapi_adaptors}/src/routing_adaptor.hpp | 4 ++-- .../autoware_adapi_visualizers}/CHANGELOG.rst | 0 .../autoware_adapi_visualizers}/__init__.py | 0 .../autoware_adapi_visualizers}/planning_factors.py | 2 +- .../launch/autoware_adapi_visualizers.launch.xml | 5 +++++ .../autoware_adapi_visualizers}/package.xml | 5 +++-- .../resource/autoware_adapi_visualizers} | 0 .../autoware_adapi_visualizers/setup.cfg | 4 ++++ .../autoware_adapi_visualizers}/setup.py | 6 +++--- .../autoware_adapi_visualizers}/test/test_copyright.py | 0 .../autoware_adapi_visualizers}/test/test_pep257.py | 0 .../autoware_automatic_pose_initializer}/CHANGELOG.rst | 0 .../autoware_automatic_pose_initializer}/CMakeLists.txt | 4 ++-- .../autoware_automatic_pose_initializer}/README.md | 0 .../launch/automatic_pose_initializer.launch.xml | 6 ++++++ .../autoware_automatic_pose_initializer}/package.xml | 3 ++- .../src/automatic_pose_initializer.cpp | 8 ++++---- .../src/automatic_pose_initializer.hpp | 4 ++-- .../launch/ad_api_visualizers.launch.xml | 5 ----- .../default_ad_api_helpers/ad_api_visualizers/setup.cfg | 4 ---- .../launch/automatic_pose_initializer.launch.xml | 6 ------ 38 files changed, 67 insertions(+), 64 deletions(-) rename system/{default_ad_api_helpers/ad_api_adaptors => autoware_default_adapi_helpers/autoware_adapi_adaptors}/CHANGELOG.rst (100%) rename system/{default_ad_api_helpers/ad_api_adaptors => autoware_default_adapi_helpers/autoware_adapi_adaptors}/CMakeLists.txt (77%) rename system/{default_ad_api_helpers/ad_api_adaptors => autoware_default_adapi_helpers/autoware_adapi_adaptors}/README.md (94%) rename system/{default_ad_api_helpers/ad_api_adaptors => autoware_default_adapi_helpers/autoware_adapi_adaptors}/config/initial_pose.param.yaml (100%) rename system/{default_ad_api_helpers/ad_api_adaptors => autoware_default_adapi_helpers/autoware_adapi_adaptors}/launch/rviz_adaptors.launch.xml (74%) rename system/{default_ad_api_helpers/ad_api_adaptors => autoware_default_adapi_helpers/autoware_adapi_adaptors}/package.xml (85%) rename system/{default_ad_api_helpers/ad_api_adaptors/schema/ad_api_adaptors.schema.json => autoware_default_adapi_helpers/autoware_adapi_adaptors/schema/adapi_adaptors.schema.json} (93%) rename system/{default_ad_api_helpers/ad_api_adaptors => autoware_default_adapi_helpers/autoware_adapi_adaptors}/src/initial_pose_adaptor.cpp (90%) rename system/{default_ad_api_helpers/ad_api_adaptors => autoware_default_adapi_helpers/autoware_adapi_adaptors}/src/initial_pose_adaptor.hpp (95%) rename system/{default_ad_api_helpers/ad_api_adaptors => autoware_default_adapi_helpers/autoware_adapi_adaptors}/src/routing_adaptor.cpp (95%) rename system/{default_ad_api_helpers/ad_api_adaptors => autoware_default_adapi_helpers/autoware_adapi_adaptors}/src/routing_adaptor.hpp (96%) rename system/{default_ad_api_helpers/ad_api_visualizers => autoware_default_adapi_helpers/autoware_adapi_visualizers}/CHANGELOG.rst (100%) rename system/{default_ad_api_helpers/ad_api_visualizers/ad_api_visualizers => autoware_default_adapi_helpers/autoware_adapi_visualizers/autoware_adapi_visualizers}/__init__.py (100%) rename system/{default_ad_api_helpers/ad_api_visualizers/ad_api_visualizers => autoware_default_adapi_helpers/autoware_adapi_visualizers/autoware_adapi_visualizers}/planning_factors.py (98%) create mode 100644 system/autoware_default_adapi_helpers/autoware_adapi_visualizers/launch/autoware_adapi_visualizers.launch.xml rename system/{default_ad_api_helpers/ad_api_visualizers => autoware_default_adapi_helpers/autoware_adapi_visualizers}/package.xml (83%) rename system/{default_ad_api_helpers/ad_api_visualizers/resource/ad_api_visualizers => autoware_default_adapi_helpers/autoware_adapi_visualizers/resource/autoware_adapi_visualizers} (100%) create mode 100644 system/autoware_default_adapi_helpers/autoware_adapi_visualizers/setup.cfg rename system/{default_ad_api_helpers/ad_api_visualizers => autoware_default_adapi_helpers/autoware_adapi_visualizers}/setup.py (81%) rename system/{default_ad_api_helpers/ad_api_visualizers => autoware_default_adapi_helpers/autoware_adapi_visualizers}/test/test_copyright.py (100%) rename system/{default_ad_api_helpers/ad_api_visualizers => autoware_default_adapi_helpers/autoware_adapi_visualizers}/test/test_pep257.py (100%) rename system/{default_ad_api_helpers/automatic_pose_initializer => autoware_default_adapi_helpers/autoware_automatic_pose_initializer}/CHANGELOG.rst (100%) rename system/{default_ad_api_helpers/automatic_pose_initializer => autoware_default_adapi_helpers/autoware_automatic_pose_initializer}/CMakeLists.txt (74%) rename system/{default_ad_api_helpers/automatic_pose_initializer => autoware_default_adapi_helpers/autoware_automatic_pose_initializer}/README.md (100%) create mode 100644 system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/launch/automatic_pose_initializer.launch.xml rename system/{default_ad_api_helpers/automatic_pose_initializer => autoware_default_adapi_helpers/autoware_automatic_pose_initializer}/package.xml (89%) rename system/{default_ad_api_helpers/automatic_pose_initializer => autoware_default_adapi_helpers/autoware_automatic_pose_initializer}/src/automatic_pose_initializer.cpp (86%) rename system/{default_ad_api_helpers/automatic_pose_initializer => autoware_default_adapi_helpers/autoware_automatic_pose_initializer}/src/automatic_pose_initializer.hpp (93%) delete mode 100644 system/default_ad_api_helpers/ad_api_visualizers/launch/ad_api_visualizers.launch.xml delete mode 100644 system/default_ad_api_helpers/ad_api_visualizers/setup.cfg delete mode 100644 system/default_ad_api_helpers/automatic_pose_initializer/launch/automatic_pose_initializer.launch.xml diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 096a610d7873e..42627e0671475 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -212,9 +212,9 @@ system/autoware_default_adapi/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4. system/autoware_processing_time_checker/** kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp system/autoware_bluetooth_monitor/** fumihito.ito@tier4.jp junya.sasaki@tier4.jp system/component_state_monitor/** isamu.takagi@tier4.jp -system/default_ad_api_helpers/ad_api_adaptors/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp -system/default_ad_api_helpers/ad_api_visualizers/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp -system/default_ad_api_helpers/automatic_pose_initializer/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp +system/autoware_default_adapi_helpers/autoware_adapi_adaptors/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp +system/autoware_default_adapi_helpers/autoware_adapi_visualizers/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp +system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp system/diagnostic_graph_aggregator/** isamu.takagi@tier4.jp system/diagnostic_graph_utils/** isamu.takagi@tier4.jp system/autoware_dummy_diag_publisher/** fumihito.ito@tier4.jp tetsuhiro.kawaguchi@tier4.jp diff --git a/launch/tier4_autoware_api_launch/launch/autoware_api.launch.xml b/launch/tier4_autoware_api_launch/launch/autoware_api.launch.xml index 143fbc9be5bfb..4c204fe2795e8 100644 --- a/launch/tier4_autoware_api_launch/launch/autoware_api.launch.xml +++ b/launch/tier4_autoware_api_launch/launch/autoware_api.launch.xml @@ -17,7 +17,7 @@ - + diff --git a/launch/tier4_autoware_api_launch/package.xml b/launch/tier4_autoware_api_launch/package.xml index 45df577f28f29..290aa80bcdad7 100644 --- a/launch/tier4_autoware_api_launch/package.xml +++ b/launch/tier4_autoware_api_launch/package.xml @@ -11,7 +11,7 @@ ament_cmake_auto autoware_cmake - ad_api_adaptors + autoware_adapi_adaptors autoware_default_adapi autoware_iv_external_api_adaptor autoware_iv_internal_api_adaptor diff --git a/launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml b/launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml index 02d4f169cbc0d..9ec7ed2d62886 100644 --- a/launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml +++ b/launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml @@ -134,7 +134,7 @@ - + diff --git a/launch/tier4_localization_launch/package.xml b/launch/tier4_localization_launch/package.xml index 55c9c59a2b000..e686bf627be5c 100644 --- a/launch/tier4_localization_launch/package.xml +++ b/launch/tier4_localization_launch/package.xml @@ -17,8 +17,8 @@ ament_cmake_auto autoware_cmake - automatic_pose_initializer autoware_ar_tag_based_localizer + autoware_automatic_pose_initializer autoware_ekf_localizer autoware_geo_pose_projector autoware_gyro_odometer diff --git a/localization/autoware_pose_initializer/README.md b/localization/autoware_pose_initializer/README.md index 2d8f0343f3493..d48520fa7ea30 100644 --- a/localization/autoware_pose_initializer/README.md +++ b/localization/autoware_pose_initializer/README.md @@ -137,4 +137,4 @@ pose: ``` It behaves the same as "initialpose (from rviz)". -The position.z and the covariance will be overwritten by [ad_api_adaptors](https://github.com/autowarefoundation/autoware.universe/tree/main/system/default_ad_api_helpers/ad_api_adaptors), so there is no need to input them. +The position.z and the covariance will be overwritten by [autoware_adapi_adaptors](https://github.com/autowarefoundation/autoware.universe/tree/main/system/autoware_default_adapi_helpers/autoware_adapi_adaptors), so there is no need to input them. diff --git a/system/autoware_default_adapi/script/web_server.py b/system/autoware_default_adapi/script/web_server.py index 1cbf30133c46b..bbd3d72bd0e06 100755 --- a/system/autoware_default_adapi/script/web_server.py +++ b/system/autoware_default_adapi/script/web_server.py @@ -49,7 +49,7 @@ def convert_dict(msg): def spin_ros_node(): global cli - node = Node("ad_api_default_web_server") + node = Node("adapi_default_web_server") cli = create_service(node, InterfaceVersion, "/api/interface/version") rclpy.spin(node) diff --git a/system/default_ad_api_helpers/ad_api_adaptors/CHANGELOG.rst b/system/autoware_default_adapi_helpers/autoware_adapi_adaptors/CHANGELOG.rst similarity index 100% rename from system/default_ad_api_helpers/ad_api_adaptors/CHANGELOG.rst rename to system/autoware_default_adapi_helpers/autoware_adapi_adaptors/CHANGELOG.rst diff --git a/system/default_ad_api_helpers/ad_api_adaptors/CMakeLists.txt b/system/autoware_default_adapi_helpers/autoware_adapi_adaptors/CMakeLists.txt similarity index 77% rename from system/default_ad_api_helpers/ad_api_adaptors/CMakeLists.txt rename to system/autoware_default_adapi_helpers/autoware_adapi_adaptors/CMakeLists.txt index c14f71571d272..a9f443e919411 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/CMakeLists.txt +++ b/system/autoware_default_adapi_helpers/autoware_adapi_adaptors/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(ad_api_adaptors) +project(autoware_adapi_adaptors) find_package(autoware_cmake REQUIRED) autoware_package() @@ -10,13 +10,13 @@ ament_auto_add_library(${PROJECT_NAME} SHARED ) rclcpp_components_register_node(${PROJECT_NAME} - PLUGIN "ad_api_adaptors::InitialPoseAdaptor" + PLUGIN "autoware::adapi_adaptors::InitialPoseAdaptor" EXECUTABLE initial_pose_adaptor_node EXECUTOR MultiThreadedExecutor ) rclcpp_components_register_node(${PROJECT_NAME} - PLUGIN "ad_api_adaptors::RoutingAdaptor" + PLUGIN "autoware::adapi_adaptors::RoutingAdaptor" EXECUTABLE routing_adaptor_node EXECUTOR SingleThreadedExecutor ) diff --git a/system/default_ad_api_helpers/ad_api_adaptors/README.md b/system/autoware_default_adapi_helpers/autoware_adapi_adaptors/README.md similarity index 94% rename from system/default_ad_api_helpers/ad_api_adaptors/README.md rename to system/autoware_default_adapi_helpers/autoware_adapi_adaptors/README.md index 74c5e6f84e80b..24f2de82e564f 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/README.md +++ b/system/autoware_default_adapi_helpers/autoware_adapi_adaptors/README.md @@ -1,4 +1,4 @@ -# ad_api_adaptors +# adapi_adaptors ## initial_pose_adaptor @@ -32,4 +32,4 @@ The clear API is called automatically before setting the route. ## parameters -{{ json_to_markdown("/system/default_ad_api_helpers/ad_api_adaptors/schema/ad_api_adaptors.schema.json") }} +{{ json_to_markdown("/system/autoware_default_adapi_helpers/adapi_adaptors/schema/adapi_adaptors.schema.json") }} diff --git a/system/default_ad_api_helpers/ad_api_adaptors/config/initial_pose.param.yaml b/system/autoware_default_adapi_helpers/autoware_adapi_adaptors/config/initial_pose.param.yaml similarity index 100% rename from system/default_ad_api_helpers/ad_api_adaptors/config/initial_pose.param.yaml rename to system/autoware_default_adapi_helpers/autoware_adapi_adaptors/config/initial_pose.param.yaml diff --git a/system/default_ad_api_helpers/ad_api_adaptors/launch/rviz_adaptors.launch.xml b/system/autoware_default_adapi_helpers/autoware_adapi_adaptors/launch/rviz_adaptors.launch.xml similarity index 74% rename from system/default_ad_api_helpers/ad_api_adaptors/launch/rviz_adaptors.launch.xml rename to system/autoware_default_adapi_helpers/autoware_adapi_adaptors/launch/rviz_adaptors.launch.xml index 855f57345ed15..253d786cd59e7 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/launch/rviz_adaptors.launch.xml +++ b/system/autoware_default_adapi_helpers/autoware_adapi_adaptors/launch/rviz_adaptors.launch.xml @@ -2,9 +2,9 @@ - - - + + + @@ -12,7 +12,7 @@ - + diff --git a/system/default_ad_api_helpers/ad_api_adaptors/package.xml b/system/autoware_default_adapi_helpers/autoware_adapi_adaptors/package.xml similarity index 85% rename from system/default_ad_api_helpers/ad_api_adaptors/package.xml rename to system/autoware_default_adapi_helpers/autoware_adapi_adaptors/package.xml index 4fe6390df77e0..fa2f632f445a7 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/package.xml +++ b/system/autoware_default_adapi_helpers/autoware_adapi_adaptors/package.xml @@ -1,12 +1,13 @@ - ad_api_adaptors + autoware_adapi_adaptors 0.40.0 - The ad_api_adaptors package + The adapi_adaptors package Takagi, Isamu Ryohsuke Mitsudome Yukihiro Saito + Junya Sasaki Apache License 2.0 ament_cmake_auto diff --git a/system/default_ad_api_helpers/ad_api_adaptors/schema/ad_api_adaptors.schema.json b/system/autoware_default_adapi_helpers/autoware_adapi_adaptors/schema/adapi_adaptors.schema.json similarity index 93% rename from system/default_ad_api_helpers/ad_api_adaptors/schema/ad_api_adaptors.schema.json rename to system/autoware_default_adapi_helpers/autoware_adapi_adaptors/schema/adapi_adaptors.schema.json index bdc921e31dd23..dd3bb2b4a25ed 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/schema/ad_api_adaptors.schema.json +++ b/system/autoware_default_adapi_helpers/autoware_adapi_adaptors/schema/adapi_adaptors.schema.json @@ -1,9 +1,9 @@ { "$schema": "http://json-schema.org/draft-07/schema#", - "title": "ad_api_adaptors parameter", + "title": "adapi_adaptors parameter", "type": "object", "definitions": { - "ad_api_adaptors": { + "adapi_adaptors": { "type": "object", "properties": { "initial_pose_particle_covariance": { diff --git a/system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.cpp b/system/autoware_default_adapi_helpers/autoware_adapi_adaptors/src/initial_pose_adaptor.cpp similarity index 90% rename from system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.cpp rename to system/autoware_default_adapi_helpers/autoware_adapi_adaptors/src/initial_pose_adaptor.cpp index 18235d966aa5e..f4aaada70b4a6 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.cpp +++ b/system/autoware_default_adapi_helpers/autoware_adapi_adaptors/src/initial_pose_adaptor.cpp @@ -18,7 +18,7 @@ #include #include -namespace ad_api_adaptors +namespace autoware::adapi_adaptors { template using Future = typename rclcpp::Client::SharedFuture; @@ -35,7 +35,7 @@ std::array get_covariance_parameter(rclcpp::Node * node, const std:: } InitialPoseAdaptor::InitialPoseAdaptor(const rclcpp::NodeOptions & options) -: Node("initial_pose_adaptor", options), fitter_(this) +: Node("autoware_initial_pose_adaptor", options), fitter_(this) { rviz_particle_covariance_ = get_covariance_parameter(this, "initial_pose_particle_covariance"); sub_initial_pose_ = create_subscription( @@ -60,7 +60,7 @@ void InitialPoseAdaptor::on_initial_pose(const PoseWithCovarianceStamped::ConstS cli_initialize_->async_send_request(req); } -} // namespace ad_api_adaptors +} // namespace autoware::adapi_adaptors #include -RCLCPP_COMPONENTS_REGISTER_NODE(ad_api_adaptors::InitialPoseAdaptor) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::adapi_adaptors::InitialPoseAdaptor) diff --git a/system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.hpp b/system/autoware_default_adapi_helpers/autoware_adapi_adaptors/src/initial_pose_adaptor.hpp similarity index 95% rename from system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.hpp rename to system/autoware_default_adapi_helpers/autoware_adapi_adaptors/src/initial_pose_adaptor.hpp index 922c4c30b6254..1ea99394f25fc 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.hpp +++ b/system/autoware_default_adapi_helpers/autoware_adapi_adaptors/src/initial_pose_adaptor.hpp @@ -22,7 +22,7 @@ #include -namespace ad_api_adaptors +namespace autoware::adapi_adaptors { class InitialPoseAdaptor : public rclcpp::Node @@ -41,6 +41,6 @@ class InitialPoseAdaptor : public rclcpp::Node void on_initial_pose(const PoseWithCovarianceStamped::ConstSharedPtr msg); }; -} // namespace ad_api_adaptors +} // namespace autoware::adapi_adaptors #endif // INITIAL_POSE_ADAPTOR_HPP_ diff --git a/system/default_ad_api_helpers/ad_api_adaptors/src/routing_adaptor.cpp b/system/autoware_default_adapi_helpers/autoware_adapi_adaptors/src/routing_adaptor.cpp similarity index 95% rename from system/default_ad_api_helpers/ad_api_adaptors/src/routing_adaptor.cpp rename to system/autoware_default_adapi_helpers/autoware_adapi_adaptors/src/routing_adaptor.cpp index 1de86a621a9e4..a84d8604f7ce6 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/src/routing_adaptor.cpp +++ b/system/autoware_default_adapi_helpers/autoware_adapi_adaptors/src/routing_adaptor.cpp @@ -16,11 +16,11 @@ #include -namespace ad_api_adaptors +namespace autoware::adapi_adaptors { RoutingAdaptor::RoutingAdaptor(const rclcpp::NodeOptions & options) -: Node("routing_adaptor", options) +: Node("autoware_routing_adaptor", options) { using std::placeholders::_1; @@ -109,7 +109,7 @@ void RoutingAdaptor::on_reroute(const PoseStamped::ConstSharedPtr pose) cli_reroute_->async_send_request(route); } -} // namespace ad_api_adaptors +} // namespace autoware::adapi_adaptors #include -RCLCPP_COMPONENTS_REGISTER_NODE(ad_api_adaptors::RoutingAdaptor) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::adapi_adaptors::RoutingAdaptor) diff --git a/system/default_ad_api_helpers/ad_api_adaptors/src/routing_adaptor.hpp b/system/autoware_default_adapi_helpers/autoware_adapi_adaptors/src/routing_adaptor.hpp similarity index 96% rename from system/default_ad_api_helpers/ad_api_adaptors/src/routing_adaptor.hpp rename to system/autoware_default_adapi_helpers/autoware_adapi_adaptors/src/routing_adaptor.hpp index b4577573b665b..4f8a18af5c066 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/src/routing_adaptor.hpp +++ b/system/autoware_default_adapi_helpers/autoware_adapi_adaptors/src/routing_adaptor.hpp @@ -23,7 +23,7 @@ #include -namespace ad_api_adaptors +namespace autoware::adapi_adaptors { class RoutingAdaptor : public rclcpp::Node @@ -59,6 +59,6 @@ class RoutingAdaptor : public rclcpp::Node void on_reroute(const PoseStamped::ConstSharedPtr pose); }; -} // namespace ad_api_adaptors +} // namespace autoware::adapi_adaptors #endif // ROUTING_ADAPTOR_HPP_ diff --git a/system/default_ad_api_helpers/ad_api_visualizers/CHANGELOG.rst b/system/autoware_default_adapi_helpers/autoware_adapi_visualizers/CHANGELOG.rst similarity index 100% rename from system/default_ad_api_helpers/ad_api_visualizers/CHANGELOG.rst rename to system/autoware_default_adapi_helpers/autoware_adapi_visualizers/CHANGELOG.rst diff --git a/system/default_ad_api_helpers/ad_api_visualizers/ad_api_visualizers/__init__.py b/system/autoware_default_adapi_helpers/autoware_adapi_visualizers/autoware_adapi_visualizers/__init__.py similarity index 100% rename from system/default_ad_api_helpers/ad_api_visualizers/ad_api_visualizers/__init__.py rename to system/autoware_default_adapi_helpers/autoware_adapi_visualizers/autoware_adapi_visualizers/__init__.py diff --git a/system/default_ad_api_helpers/ad_api_visualizers/ad_api_visualizers/planning_factors.py b/system/autoware_default_adapi_helpers/autoware_adapi_visualizers/autoware_adapi_visualizers/planning_factors.py similarity index 98% rename from system/default_ad_api_helpers/ad_api_visualizers/ad_api_visualizers/planning_factors.py rename to system/autoware_default_adapi_helpers/autoware_adapi_visualizers/autoware_adapi_visualizers/planning_factors.py index b60fa5365f2a2..27ff45276b9ef 100755 --- a/system/default_ad_api_helpers/ad_api_visualizers/ad_api_visualizers/planning_factors.py +++ b/system/autoware_default_adapi_helpers/autoware_adapi_visualizers/autoware_adapi_visualizers/planning_factors.py @@ -60,7 +60,7 @@ class PlanningFactorVisualizer(rclpy.node.Node): def __init__(self): - super().__init__("planning_factor_visualizer") + super().__init__("autoware_planning_factor_visualizer") self.front_offset = self.declare_parameter("front_offset", 0.0).value self.pub_velocity = self.create_publisher(MarkerArray, "/visualizer/velocity_factors", 1) self.pub_steering = self.create_publisher(MarkerArray, "/visualizer/steering_factors", 1) diff --git a/system/autoware_default_adapi_helpers/autoware_adapi_visualizers/launch/autoware_adapi_visualizers.launch.xml b/system/autoware_default_adapi_helpers/autoware_adapi_visualizers/launch/autoware_adapi_visualizers.launch.xml new file mode 100644 index 0000000000000..90559864b9469 --- /dev/null +++ b/system/autoware_default_adapi_helpers/autoware_adapi_visualizers/launch/autoware_adapi_visualizers.launch.xml @@ -0,0 +1,5 @@ + + + + + diff --git a/system/default_ad_api_helpers/ad_api_visualizers/package.xml b/system/autoware_default_adapi_helpers/autoware_adapi_visualizers/package.xml similarity index 83% rename from system/default_ad_api_helpers/ad_api_visualizers/package.xml rename to system/autoware_default_adapi_helpers/autoware_adapi_visualizers/package.xml index 2392cfaaface1..a51e5b0b80b32 100644 --- a/system/default_ad_api_helpers/ad_api_visualizers/package.xml +++ b/system/autoware_default_adapi_helpers/autoware_adapi_visualizers/package.xml @@ -1,12 +1,13 @@ - ad_api_visualizers + autoware_adapi_visualizers 0.40.0 - The ad_api_visualizers package + The adapi_visualizers package Takagi, Isamu Ryohsuke Mitsudome Yukihiro Saito + Junya Sasaki Apache License 2.0 autoware_adapi_v1_msgs diff --git a/system/default_ad_api_helpers/ad_api_visualizers/resource/ad_api_visualizers b/system/autoware_default_adapi_helpers/autoware_adapi_visualizers/resource/autoware_adapi_visualizers similarity index 100% rename from system/default_ad_api_helpers/ad_api_visualizers/resource/ad_api_visualizers rename to system/autoware_default_adapi_helpers/autoware_adapi_visualizers/resource/autoware_adapi_visualizers diff --git a/system/autoware_default_adapi_helpers/autoware_adapi_visualizers/setup.cfg b/system/autoware_default_adapi_helpers/autoware_adapi_visualizers/setup.cfg new file mode 100644 index 0000000000000..0eed433d69c43 --- /dev/null +++ b/system/autoware_default_adapi_helpers/autoware_adapi_visualizers/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script_dir=$base/lib/adapi_visualizers +[install] +install_scripts=$base/lib/adapi_visualizers diff --git a/system/default_ad_api_helpers/ad_api_visualizers/setup.py b/system/autoware_default_adapi_helpers/autoware_adapi_visualizers/setup.py similarity index 81% rename from system/default_ad_api_helpers/ad_api_visualizers/setup.py rename to system/autoware_default_adapi_helpers/autoware_adapi_visualizers/setup.py index ee4cf253b5288..ee38c2feb0670 100644 --- a/system/default_ad_api_helpers/ad_api_visualizers/setup.py +++ b/system/autoware_default_adapi_helpers/autoware_adapi_visualizers/setup.py @@ -7,7 +7,7 @@ simplefilter("ignore", category=SetuptoolsDeprecationWarning) simplefilter("ignore", category=PkgResourcesDeprecationWarning) -package_name = "ad_api_visualizers" +package_name = "autoware_adapi_visualizers" setup( name=package_name, @@ -22,10 +22,10 @@ zip_safe=True, maintainer="Takagi, Isamu", maintainer_email="isamu.takagi@tier4.jp", - description="The ad_api_visualizers package", + description="The adapi_visualizers package", license="Apache License 2.0", tests_require=["pytest"], entry_points={ - "console_scripts": ["planning_factors = ad_api_visualizers.planning_factors:main"], + "console_scripts": ["planning_factors = autoware_adapi_visualizers.planning_factors:main"], }, ) diff --git a/system/default_ad_api_helpers/ad_api_visualizers/test/test_copyright.py b/system/autoware_default_adapi_helpers/autoware_adapi_visualizers/test/test_copyright.py similarity index 100% rename from system/default_ad_api_helpers/ad_api_visualizers/test/test_copyright.py rename to system/autoware_default_adapi_helpers/autoware_adapi_visualizers/test/test_copyright.py diff --git a/system/default_ad_api_helpers/ad_api_visualizers/test/test_pep257.py b/system/autoware_default_adapi_helpers/autoware_adapi_visualizers/test/test_pep257.py similarity index 100% rename from system/default_ad_api_helpers/ad_api_visualizers/test/test_pep257.py rename to system/autoware_default_adapi_helpers/autoware_adapi_visualizers/test/test_pep257.py diff --git a/system/default_ad_api_helpers/automatic_pose_initializer/CHANGELOG.rst b/system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/CHANGELOG.rst similarity index 100% rename from system/default_ad_api_helpers/automatic_pose_initializer/CHANGELOG.rst rename to system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/CHANGELOG.rst diff --git a/system/default_ad_api_helpers/automatic_pose_initializer/CMakeLists.txt b/system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/CMakeLists.txt similarity index 74% rename from system/default_ad_api_helpers/automatic_pose_initializer/CMakeLists.txt rename to system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/CMakeLists.txt index b777df8675bef..0e0b604d57935 100644 --- a/system/default_ad_api_helpers/automatic_pose_initializer/CMakeLists.txt +++ b/system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(automatic_pose_initializer) +project(autoware_automatic_pose_initializer) find_package(autoware_cmake REQUIRED) autoware_package() @@ -9,7 +9,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED ) rclcpp_components_register_node(${PROJECT_NAME} - PLUGIN "automatic_pose_initializer::AutomaticPoseInitializer" + PLUGIN "autoware::automatic_pose_initializer::AutomaticPoseInitializer" EXECUTABLE ${PROJECT_NAME}_node EXECUTOR MultiThreadedExecutor ) diff --git a/system/default_ad_api_helpers/automatic_pose_initializer/README.md b/system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/README.md similarity index 100% rename from system/default_ad_api_helpers/automatic_pose_initializer/README.md rename to system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/README.md diff --git a/system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/launch/automatic_pose_initializer.launch.xml b/system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/launch/automatic_pose_initializer.launch.xml new file mode 100644 index 0000000000000..0c4f62891c67a --- /dev/null +++ b/system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/launch/automatic_pose_initializer.launch.xml @@ -0,0 +1,6 @@ + + + + + + diff --git a/system/default_ad_api_helpers/automatic_pose_initializer/package.xml b/system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/package.xml similarity index 89% rename from system/default_ad_api_helpers/automatic_pose_initializer/package.xml rename to system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/package.xml index 13f15d7dc63fd..606d0237b2d5d 100644 --- a/system/default_ad_api_helpers/automatic_pose_initializer/package.xml +++ b/system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/package.xml @@ -1,12 +1,13 @@ - automatic_pose_initializer + autoware_automatic_pose_initializer 0.40.0 The automatic_pose_initializer package Takagi, Isamu Ryohsuke Mitsudome Yukihiro Saito + Junya Sasaki Apache License 2.0 ament_cmake_auto diff --git a/system/default_ad_api_helpers/automatic_pose_initializer/src/automatic_pose_initializer.cpp b/system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/src/automatic_pose_initializer.cpp similarity index 86% rename from system/default_ad_api_helpers/automatic_pose_initializer/src/automatic_pose_initializer.cpp rename to system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/src/automatic_pose_initializer.cpp index 53943af1a3f31..192eeae356e51 100644 --- a/system/default_ad_api_helpers/automatic_pose_initializer/src/automatic_pose_initializer.cpp +++ b/system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/src/automatic_pose_initializer.cpp @@ -16,11 +16,11 @@ #include -namespace automatic_pose_initializer +namespace autoware::automatic_pose_initializer { AutomaticPoseInitializer::AutomaticPoseInitializer(const rclcpp::NodeOptions & options) -: Node("automatic_pose_initializer", options) +: Node("autoware_automatic_pose_initializer", options) { const auto adaptor = autoware::component_interface_utils::NodeAdaptor(this); group_cli_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); @@ -47,7 +47,7 @@ void AutomaticPoseInitializer::on_timer() timer_->reset(); } -} // namespace automatic_pose_initializer +} // namespace autoware::automatic_pose_initializer #include -RCLCPP_COMPONENTS_REGISTER_NODE(automatic_pose_initializer::AutomaticPoseInitializer) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::automatic_pose_initializer::AutomaticPoseInitializer) diff --git a/system/default_ad_api_helpers/automatic_pose_initializer/src/automatic_pose_initializer.hpp b/system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/src/automatic_pose_initializer.hpp similarity index 93% rename from system/default_ad_api_helpers/automatic_pose_initializer/src/automatic_pose_initializer.hpp rename to system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/src/automatic_pose_initializer.hpp index a22a19cc592d2..407a23a6d01e5 100644 --- a/system/default_ad_api_helpers/automatic_pose_initializer/src/automatic_pose_initializer.hpp +++ b/system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/src/automatic_pose_initializer.hpp @@ -19,7 +19,7 @@ #include #include -namespace automatic_pose_initializer +namespace autoware::automatic_pose_initializer { class AutomaticPoseInitializer : public rclcpp::Node @@ -38,6 +38,6 @@ class AutomaticPoseInitializer : public rclcpp::Node State::Message state_; }; -} // namespace automatic_pose_initializer +} // namespace autoware::automatic_pose_initializer #endif // AUTOMATIC_POSE_INITIALIZER_HPP_ diff --git a/system/default_ad_api_helpers/ad_api_visualizers/launch/ad_api_visualizers.launch.xml b/system/default_ad_api_helpers/ad_api_visualizers/launch/ad_api_visualizers.launch.xml deleted file mode 100644 index 26fb4720ca435..0000000000000 --- a/system/default_ad_api_helpers/ad_api_visualizers/launch/ad_api_visualizers.launch.xml +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/system/default_ad_api_helpers/ad_api_visualizers/setup.cfg b/system/default_ad_api_helpers/ad_api_visualizers/setup.cfg deleted file mode 100644 index b0af17360079d..0000000000000 --- a/system/default_ad_api_helpers/ad_api_visualizers/setup.cfg +++ /dev/null @@ -1,4 +0,0 @@ -[develop] -script_dir=$base/lib/ad_api_visualizers -[install] -install_scripts=$base/lib/ad_api_visualizers diff --git a/system/default_ad_api_helpers/automatic_pose_initializer/launch/automatic_pose_initializer.launch.xml b/system/default_ad_api_helpers/automatic_pose_initializer/launch/automatic_pose_initializer.launch.xml deleted file mode 100644 index e9a94efd6be7b..0000000000000 --- a/system/default_ad_api_helpers/automatic_pose_initializer/launch/automatic_pose_initializer.launch.xml +++ /dev/null @@ -1,6 +0,0 @@ - - - - - - From 1a1a18afc0dd659c8c28558d0ed0d2467aafd2c1 Mon Sep 17 00:00:00 2001 From: Junya Sasaki Date: Thu, 23 Jan 2025 17:35:33 +0900 Subject: [PATCH 302/334] feat: apply `autoware_` prefix for `simple_planning_simulator` (#9995) * feat(simple_planning_simulator): apply `autoware_` prefix (see below): Note: * In this commit, I did not organize a folder structure. The folder structure will be organized in the next some commits. * The changes will follow the Autoware's guideline as below: - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder Signed-off-by: Junya Sasaki * rename(simple_planning_simulator): move headers under `include/autoware`: * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit Signed-off-by: Junya Sasaki * fix(simple_planning_simulator): fix include header paths * To follow the previous commit Signed-off-by: Junya Sasaki * rename: `simple_planning_simulator` => `autoware_simple_planning_simulator` Signed-off-by: Junya Sasaki * bug(autoware_simple_planning_simulator): fix missing changes Signed-off-by: Junya Sasaki * style(pre-commit): autofix * bug(autoware_simple_planning_simulator): fix errors in build and tests * I had to run after `rm -rf install build`, ... sorry Signed-off-by: Junya Sasaki * style(pre-commit): autofix * Fixed NOLINT Signed-off-by: Shintaro Sakoda * Added NOLINT Signed-off-by: Shintaro Sakoda * Fixed to autoware_simple_planning_simulator Signed-off-by: Shintaro Sakoda --------- Signed-off-by: Junya Sasaki Signed-off-by: Shintaro Sakoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Shintaro Sakoda --- .github/CODEOWNERS | 2 +- .../launch/simulator.launch.xml | 2 +- launch/tier4_simulator_launch/package.xml | 2 +- .../CHANGELOG.rst | 0 .../CMakeLists.txt | 10 +++--- .../README.md | 2 +- .../data/actuation_cmd_map/accel_map.csv | 0 .../data/actuation_cmd_map/brake_map.csv | 0 .../data/actuation_cmd_map/steer_map.csv | 0 .../docs/actuation_cmd_sim.md | 0 .../simple_planning_simulator_core.hpp | 19 +++++------ .../utils/csv_loader.hpp | 13 +++++--- .../utils/mechanical_controller.hpp | 12 +++---- .../vehicle_model/sim_model.hpp | 30 ++++++++++++++++++ .../vehicle_model/sim_model_actuation_cmd.hpp | 23 ++++++++------ .../sim_model_delay_steer_acc.hpp | 15 ++++++--- .../sim_model_delay_steer_acc_geared.hpp | 16 +++++++--- ...l_delay_steer_acc_geared_wo_fall_guard.hpp | 18 +++++++---- .../sim_model_delay_steer_map_acc_geared.hpp | 18 +++++++---- .../sim_model_delay_steer_vel.hpp | 16 +++++++--- .../sim_model_ideal_steer_acc.hpp | 15 ++++++--- .../sim_model_ideal_steer_acc_geared.hpp | 15 ++++++--- .../sim_model_ideal_steer_vel.hpp | 16 +++++++--- .../vehicle_model/sim_model_interface.hpp | 13 +++++--- .../sim_model_learned_steer_vel.hpp | 15 ++++++--- .../visibility_control.hpp | 8 ++--- .../simple_planning_simulator.launch.py | 13 ++++---- .../media/acceleration_map.svg | 0 .../media/mechanical_controller.drawio.svg | 0 ...nical_controller_system_identification.png | Bin .../media/pitch-calculation.drawio.svg | 0 .../media/vgr_sim.drawio.svg | 0 .../package.xml | 3 +- .../param/acceleration_map.csv | 0 ...mple_planning_simulator_default.param.yaml | 0 ...ing_simulator_mechanical_sample.param.yaml | 0 .../param/vehicle_characteristics.param.yaml | 0 .../simple_planning_simulator_core.cpp | 22 +++++-------- .../utils/csv_loader.cpp | 9 ++++-- .../utils/mechanical_controller.cpp | 8 ++--- .../vehicle_model/sim_model_actuation_cmd.cpp | 8 +++-- .../sim_model_delay_steer_acc.cpp | 9 ++++-- .../sim_model_delay_steer_acc_geared.cpp | 9 ++++-- ...l_delay_steer_acc_geared_wo_fall_guard.cpp | 9 ++++-- .../sim_model_delay_steer_map_acc_geared.cpp | 9 ++++-- .../sim_model_delay_steer_vel.cpp | 9 ++++-- .../sim_model_ideal_steer_acc.cpp | 9 ++++-- .../sim_model_ideal_steer_acc_geared.cpp | 9 ++++-- .../sim_model_ideal_steer_vel.cpp | 9 ++++-- .../vehicle_model/sim_model_interface.cpp | 9 ++++-- .../sim_model_learned_steer_vel.cpp | 9 ++++-- .../test/actuation_cmd_map/accel_map.csv | 0 .../test/actuation_cmd_map/brake_map.csv | 0 .../test/actuation_cmd_map/steer_map.csv | 0 .../test/test_simple_planning_simulator.cpp | 15 +++++---- .../vehicle_model/sim_model.hpp | 30 ------------------ 56 files changed, 297 insertions(+), 181 deletions(-) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/CHANGELOG.rst (100%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/CMakeLists.txt (85%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/README.md (99%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/data/actuation_cmd_map/accel_map.csv (100%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/data/actuation_cmd_map/brake_map.csv (100%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/data/actuation_cmd_map/steer_map.csv (100%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/docs/actuation_cmd_sim.md (100%) rename simulator/{simple_planning_simulator/include => autoware_simple_planning_simulator/include/autoware}/simple_planning_simulator/simple_planning_simulator_core.hpp (96%) rename simulator/{simple_planning_simulator/include => autoware_simple_planning_simulator/include/autoware}/simple_planning_simulator/utils/csv_loader.hpp (78%) rename simulator/{simple_planning_simulator/include => autoware_simple_planning_simulator/include/autoware}/simple_planning_simulator/utils/mechanical_controller.hpp (92%) create mode 100644 simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model.hpp rename simulator/{simple_planning_simulator/include => autoware_simple_planning_simulator/include/autoware}/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.hpp (94%) rename simulator/{simple_planning_simulator/include => autoware_simple_planning_simulator/include/autoware}/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.hpp (90%) rename simulator/{simple_planning_simulator/include => autoware_simple_planning_simulator/include/autoware}/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp (89%) rename simulator/{simple_planning_simulator/include => autoware_simple_planning_simulator/include/autoware}/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.hpp (88%) rename simulator/{simple_planning_simulator/include => autoware_simple_planning_simulator/include/autoware}/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.hpp (90%) rename simulator/{simple_planning_simulator/include => autoware_simple_planning_simulator/include/autoware}/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.hpp (89%) rename simulator/{simple_planning_simulator/include => autoware_simple_planning_simulator/include/autoware}/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc.hpp (80%) rename simulator/{simple_planning_simulator/include => autoware_simple_planning_simulator/include/autoware}/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.hpp (83%) rename simulator/{simple_planning_simulator/include => autoware_simple_planning_simulator/include/autoware}/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_vel.hpp (80%) rename simulator/{simple_planning_simulator/include => autoware_simple_planning_simulator/include/autoware}/simple_planning_simulator/vehicle_model/sim_model_interface.hpp (91%) rename simulator/{simple_planning_simulator/include => autoware_simple_planning_simulator/include/autoware}/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.hpp (86%) rename simulator/{simple_planning_simulator/include => autoware_simple_planning_simulator/include/autoware}/simple_planning_simulator/visibility_control.hpp (85%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/launch/simple_planning_simulator.launch.py (95%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/media/acceleration_map.svg (100%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/media/mechanical_controller.drawio.svg (100%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/media/mechanical_controller_system_identification.png (100%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/media/pitch-calculation.drawio.svg (100%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/media/vgr_sim.drawio.svg (100%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/package.xml (94%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/param/acceleration_map.csv (100%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/param/simple_planning_simulator_default.param.yaml (100%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/param/simple_planning_simulator_mechanical_sample.param.yaml (100%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/param/vehicle_characteristics.param.yaml (100%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/src/simple_planning_simulator/simple_planning_simulator_core.cpp (98%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/src/simple_planning_simulator/utils/csv_loader.cpp (94%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/src/simple_planning_simulator/utils/mechanical_controller.cpp (97%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/src/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.cpp (98%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.cpp (94%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp (96%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.cpp (96%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.cpp (95%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.cpp (94%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc.cpp (88%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.cpp (93%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_vel.cpp (88%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/src/simple_planning_simulator/vehicle_model/sim_model_interface.cpp (87%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/src/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.cpp (90%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/test/actuation_cmd_map/accel_map.csv (100%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/test/actuation_cmd_map/brake_map.csv (100%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/test/actuation_cmd_map/steer_map.csv (100%) rename simulator/{simple_planning_simulator => autoware_simple_planning_simulator}/test/test_simple_planning_simulator.cpp (98%) delete mode 100644 simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model.hpp diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 42627e0671475..7e76a883c36e9 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -204,7 +204,7 @@ simulator/autoware_carla_interface/** maxime.clement@tier4.jp mradityagio@gmail. simulator/dummy_perception_publisher/** yukihiro.saito@tier4.jp simulator/fault_injection/** keisuke.shima@tier4.jp simulator/learning_based_vehicle_model/** maxime.clement@tier4.jp nagy.tomas@tier4.jp -simulator/simple_planning_simulator/** mamoru.sobue@tier4.jp maxime.clement@tier4.jp takamasa.horibe@tier4.jp temkei.kem@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp kotaro.yoshimoto@tier4.jp +simulator/autoware_simple_planning_simulator/** mamoru.sobue@tier4.jp maxime.clement@tier4.jp takamasa.horibe@tier4.jp temkei.kem@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp kotaro.yoshimoto@tier4.jp junya.sasaki@tier4.jp simulator/tier4_dummy_object_rviz_plugin/** yukihiro.saito@tier4.jp simulator/autoware_vehicle_door_simulator/** isamu.takagi@tier4.jp junya.sasaki@tier4.jp system/autoware_component_monitor/** baris@leodrive.ai memin@leodrive.ai yavuz@leodrive.ai diff --git a/launch/tier4_simulator_launch/launch/simulator.launch.xml b/launch/tier4_simulator_launch/launch/simulator.launch.xml index fa457a31f8c43..1255061a474db 100644 --- a/launch/tier4_simulator_launch/launch/simulator.launch.xml +++ b/launch/tier4_simulator_launch/launch/simulator.launch.xml @@ -219,7 +219,7 @@ - + diff --git a/launch/tier4_simulator_launch/package.xml b/launch/tier4_simulator_launch/package.xml index fba24d0a5d525..f12209f4ab3ef 100644 --- a/launch/tier4_simulator_launch/package.xml +++ b/launch/tier4_simulator_launch/package.xml @@ -15,8 +15,8 @@ autoware_cmake autoware_fault_injection + autoware_simple_planning_simulator dummy_perception_publisher - simple_planning_simulator ament_lint_auto autoware_lint_common diff --git a/simulator/simple_planning_simulator/CHANGELOG.rst b/simulator/autoware_simple_planning_simulator/CHANGELOG.rst similarity index 100% rename from simulator/simple_planning_simulator/CHANGELOG.rst rename to simulator/autoware_simple_planning_simulator/CHANGELOG.rst diff --git a/simulator/simple_planning_simulator/CMakeLists.txt b/simulator/autoware_simple_planning_simulator/CMakeLists.txt similarity index 85% rename from simulator/simple_planning_simulator/CMakeLists.txt rename to simulator/autoware_simple_planning_simulator/CMakeLists.txt index 6acb74342c90f..ab4ac8218e193 100644 --- a/simulator/simple_planning_simulator/CMakeLists.txt +++ b/simulator/autoware_simple_planning_simulator/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(simple_planning_simulator) +project(autoware_simple_planning_simulator) find_package(autoware_cmake REQUIRED) find_package(Python3 COMPONENTS Interpreter Development) @@ -8,8 +8,8 @@ autoware_package() # Component ament_auto_add_library(${PROJECT_NAME} SHARED - include/simple_planning_simulator/simple_planning_simulator_core.hpp - include/simple_planning_simulator/visibility_control.hpp + include/autoware/simple_planning_simulator/simple_planning_simulator_core.hpp + include/autoware/simple_planning_simulator/visibility_control.hpp src/simple_planning_simulator/simple_planning_simulator_core.cpp src/simple_planning_simulator/vehicle_model/sim_model_interface.cpp src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_vel.cpp @@ -28,8 +28,8 @@ ament_auto_add_library(${PROJECT_NAME} SHARED target_include_directories(${PROJECT_NAME} PUBLIC ${Python3_INCLUDE_DIRS} ${learning_based_vehicle_model_INCLUDE_DIRS}) # Node executable rclcpp_components_register_node(${PROJECT_NAME} - PLUGIN "simulation::simple_planning_simulator::SimplePlanningSimulator" - EXECUTABLE ${PROJECT_NAME}_exe + PLUGIN "autoware::simulator::simple_planning_simulator::SimplePlanningSimulator" + EXECUTABLE ${PROJECT_NAME}_node ) if(BUILD_TESTING) diff --git a/simulator/simple_planning_simulator/README.md b/simulator/autoware_simple_planning_simulator/README.md similarity index 99% rename from simulator/simple_planning_simulator/README.md rename to simulator/autoware_simple_planning_simulator/README.md index cd362c0115358..385f4aa1c7eab 100644 --- a/simulator/simple_planning_simulator/README.md +++ b/simulator/autoware_simple_planning_simulator/README.md @@ -1,4 +1,4 @@ -# simple_planning_simulator +# autoware_simple_planning_simulator ## Purpose / Use cases diff --git a/simulator/simple_planning_simulator/data/actuation_cmd_map/accel_map.csv b/simulator/autoware_simple_planning_simulator/data/actuation_cmd_map/accel_map.csv similarity index 100% rename from simulator/simple_planning_simulator/data/actuation_cmd_map/accel_map.csv rename to simulator/autoware_simple_planning_simulator/data/actuation_cmd_map/accel_map.csv diff --git a/simulator/simple_planning_simulator/data/actuation_cmd_map/brake_map.csv b/simulator/autoware_simple_planning_simulator/data/actuation_cmd_map/brake_map.csv similarity index 100% rename from simulator/simple_planning_simulator/data/actuation_cmd_map/brake_map.csv rename to simulator/autoware_simple_planning_simulator/data/actuation_cmd_map/brake_map.csv diff --git a/simulator/simple_planning_simulator/data/actuation_cmd_map/steer_map.csv b/simulator/autoware_simple_planning_simulator/data/actuation_cmd_map/steer_map.csv similarity index 100% rename from simulator/simple_planning_simulator/data/actuation_cmd_map/steer_map.csv rename to simulator/autoware_simple_planning_simulator/data/actuation_cmd_map/steer_map.csv diff --git a/simulator/simple_planning_simulator/docs/actuation_cmd_sim.md b/simulator/autoware_simple_planning_simulator/docs/actuation_cmd_sim.md similarity index 100% rename from simulator/simple_planning_simulator/docs/actuation_cmd_sim.md rename to simulator/autoware_simple_planning_simulator/docs/actuation_cmd_sim.md diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/simple_planning_simulator_core.hpp similarity index 96% rename from simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp rename to simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/simple_planning_simulator_core.hpp index 3e54bca245f82..26a849dddc278 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp +++ b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/simple_planning_simulator_core.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 The Autoware Foundation. +// Copyright 2025 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. @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SIMPLE_PLANNING_SIMULATOR__SIMPLE_PLANNING_SIMULATOR_CORE_HPP_ -#define SIMPLE_PLANNING_SIMULATOR__SIMPLE_PLANNING_SIMULATOR_CORE_HPP_ +#ifndef AUTOWARE__SIMPLE_PLANNING_SIMULATOR__SIMPLE_PLANNING_SIMULATOR_CORE_HPP_ +#define AUTOWARE__SIMPLE_PLANNING_SIMULATOR__SIMPLE_PLANNING_SIMULATOR_CORE_HPP_ +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_interface.hpp" +#include "autoware/simple_planning_simulator/visibility_control.hpp" #include "rclcpp/rclcpp.hpp" -#include "simple_planning_simulator/vehicle_model/sim_model_interface.hpp" -#include "simple_planning_simulator/visibility_control.hpp" #include "tier4_api_utils/tier4_api_utils.hpp" #include "autoware_control_msgs/msg/control.hpp" @@ -57,9 +57,7 @@ #include #include -namespace simulation -{ -namespace simple_planning_simulator +namespace autoware::simulator::simple_planning_simulator { using autoware_control_msgs::msg::Control; @@ -406,7 +404,6 @@ class PLANNING_SIMULATOR_PUBLIC SimplePlanningSimulator : public rclcpp::Node */ void publish_tf(const Odometry & odometry); }; -} // namespace simple_planning_simulator -} // namespace simulation +} // namespace autoware::simulator::simple_planning_simulator -#endif // SIMPLE_PLANNING_SIMULATOR__SIMPLE_PLANNING_SIMULATOR_CORE_HPP_ +#endif // AUTOWARE__SIMPLE_PLANNING_SIMULATOR__SIMPLE_PLANNING_SIMULATOR_CORE_HPP_ diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/utils/csv_loader.hpp b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/utils/csv_loader.hpp similarity index 78% rename from simulator/simple_planning_simulator/include/simple_planning_simulator/utils/csv_loader.hpp rename to simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/utils/csv_loader.hpp index a8851640fb62b..2965327beaacc 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/utils/csv_loader.hpp +++ b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/utils/csv_loader.hpp @@ -1,4 +1,4 @@ -// Copyright 2023 Autoware Foundation +// Copyright 2025 Autoware Foundation // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SIMPLE_PLANNING_SIMULATOR__UTILS__CSV_LOADER_HPP_ -#define SIMPLE_PLANNING_SIMULATOR__UTILS__CSV_LOADER_HPP_ +#ifndef AUTOWARE__SIMPLE_PLANNING_SIMULATOR__UTILS__CSV_LOADER_HPP_ +#define AUTOWARE__SIMPLE_PLANNING_SIMULATOR__UTILS__CSV_LOADER_HPP_ #include #include @@ -21,6 +21,9 @@ #include #include +namespace autoware::simulator::simple_planning_simulator +{ + using Table = std::vector>; using Map = std::vector>; class CSVLoader @@ -40,4 +43,6 @@ class CSVLoader std::string csv_path_; }; -#endif // SIMPLE_PLANNING_SIMULATOR__UTILS__CSV_LOADER_HPP_ +} // namespace autoware::simulator::simple_planning_simulator + +#endif // AUTOWARE__SIMPLE_PLANNING_SIMULATOR__UTILS__CSV_LOADER_HPP_ diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/utils/mechanical_controller.hpp b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/utils/mechanical_controller.hpp similarity index 92% rename from simulator/simple_planning_simulator/include/simple_planning_simulator/utils/mechanical_controller.hpp rename to simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/utils/mechanical_controller.hpp index fcb8d41dd72b5..7850d74d45036 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/utils/mechanical_controller.hpp +++ b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/utils/mechanical_controller.hpp @@ -1,4 +1,4 @@ -// Copyright 2024 The Autoware Foundation. +// Copyright 2025 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. @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SIMPLE_PLANNING_SIMULATOR__UTILS__MECHANICAL_CONTROLLER_HPP_ -#define SIMPLE_PLANNING_SIMULATOR__UTILS__MECHANICAL_CONTROLLER_HPP_ +#ifndef AUTOWARE__SIMPLE_PLANNING_SIMULATOR__UTILS__MECHANICAL_CONTROLLER_HPP_ +#define AUTOWARE__SIMPLE_PLANNING_SIMULATOR__UTILS__MECHANICAL_CONTROLLER_HPP_ #include #include @@ -21,7 +21,7 @@ #include #include -namespace autoware::simple_planning_simulator::utils::mechanical_controller +namespace autoware::simulator::simple_planning_simulator { using DelayBuffer = std::deque>; @@ -203,6 +203,6 @@ class MechanicalController const SteeringDynamics & dynamics) const; }; -} // namespace autoware::simple_planning_simulator::utils::mechanical_controller +} // namespace autoware::simulator::simple_planning_simulator -#endif // SIMPLE_PLANNING_SIMULATOR__UTILS__MECHANICAL_CONTROLLER_HPP_ +#endif // AUTOWARE__SIMPLE_PLANNING_SIMULATOR__UTILS__MECHANICAL_CONTROLLER_HPP_ diff --git a/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model.hpp b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model.hpp new file mode 100644 index 0000000000000..d7ee90fdf5634 --- /dev/null +++ b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model.hpp @@ -0,0 +1,30 @@ +// Copyright 2025 The Autoware Foundation. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_HPP_ +#define AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_HPP_ + +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_vel.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_interface.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.hpp" + +#endif // AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_HPP_ diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.hpp b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.hpp similarity index 94% rename from simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.hpp rename to simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.hpp index 25fac72d283ee..edb52570b0a19 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.hpp +++ b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.hpp @@ -1,4 +1,4 @@ -// Copyright 2024 The Autoware Foundation. +// Copyright 2025 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. @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_ACTUATION_CMD_HPP_ -#define SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_ACTUATION_CMD_HPP_ +#ifndef AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_ACTUATION_CMD_HPP_ +#define AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_ACTUATION_CMD_HPP_ #include "autoware/interpolation/linear_interpolation.hpp" +#include "autoware/simple_planning_simulator/utils/csv_loader.hpp" +#include "autoware/simple_planning_simulator/utils/mechanical_controller.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_interface.hpp" #include "eigen3/Eigen/Core" #include "eigen3/Eigen/LU" -#include "simple_planning_simulator/utils/csv_loader.hpp" -#include "simple_planning_simulator/utils/mechanical_controller.hpp" -#include "simple_planning_simulator/vehicle_model/sim_model_interface.hpp" #include #include @@ -30,8 +30,11 @@ #include #include -using autoware::simple_planning_simulator::utils::mechanical_controller::MechanicalController; -using autoware::simple_planning_simulator::utils::mechanical_controller::MechanicalParams; +namespace autoware::simulator::simple_planning_simulator +{ + +using autoware::simulator::simple_planning_simulator::MechanicalController; +using autoware::simulator::simple_planning_simulator::MechanicalParams; /** * @class ActuationMap @@ -397,4 +400,6 @@ class SimModelActuationCmdMechanical : public SimModelActuationCmdVGR double prev_steer_tire_des_{0.0}; // }; -#endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_ACTUATION_CMD_HPP_ +} // namespace autoware::simulator::simple_planning_simulator + +#endif // AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_ACTUATION_CMD_HPP_ diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.hpp b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.hpp similarity index 90% rename from simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.hpp rename to simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.hpp index f43abd8572874..6437cdc4cdbcb 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.hpp +++ b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 The Autoware Foundation. +// Copyright 2025 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. @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_HPP_ -#define SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_HPP_ +#ifndef AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_HPP_ +#define AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_HPP_ -#include "simple_planning_simulator/vehicle_model/sim_model_interface.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_interface.hpp" #include #include @@ -24,6 +24,9 @@ #include #include +namespace autoware::simulator::simple_planning_simulator +{ + class SimModelDelaySteerAcc : public SimModelInterface { public: @@ -149,4 +152,6 @@ class SimModelDelaySteerAcc : public SimModelInterface Eigen::VectorXd calcModel(const Eigen::VectorXd & state, const Eigen::VectorXd & input) override; }; -#endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_HPP_ +} // namespace autoware::simulator::simple_planning_simulator + +#endif // AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_HPP_ diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp similarity index 89% rename from simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp rename to simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp index 1ecb74be41780..d43c86669f2bf 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp +++ b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 The Autoware Foundation. +// Copyright 2025 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. @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_HPP_ -#define SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_HPP_ +#ifndef AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_HPP_ // NOLINT +#define AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_HPP_ // NOLINT -#include "simple_planning_simulator/vehicle_model/sim_model_interface.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_interface.hpp" #include #include @@ -24,6 +24,9 @@ #include #include +namespace autoware::simulator::simple_planning_simulator +{ + class SimModelDelaySteerAccGeared : public SimModelInterface { public: @@ -160,4 +163,7 @@ class SimModelDelaySteerAccGeared : public SimModelInterface const double dt); }; -#endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_HPP_ +} // namespace autoware::simulator::simple_planning_simulator + +// NOLINTNEXTLINE +#endif // AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_HPP_ diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.hpp b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.hpp similarity index 88% rename from simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.hpp rename to simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.hpp index 83f574554fe76..300e82b6facb1 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.hpp +++ b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.hpp @@ -1,4 +1,4 @@ -// Copyright 2024 The Autoware Foundation. +// Copyright 2025 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. @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_WO_FALL_GUARD_HPP_ // NOLINT -#define SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_WO_FALL_GUARD_HPP_ // NOLINT +#ifndef AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_WO_FALL_GUARD_HPP_ // NOLINT +#define AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_WO_FALL_GUARD_HPP_ // NOLINT -#include "simple_planning_simulator/vehicle_model/sim_model_interface.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_interface.hpp" #include #include @@ -24,6 +24,9 @@ #include #include +namespace autoware::simulator::simple_planning_simulator +{ + class SimModelDelaySteerAccGearedWoFallGuard : public SimModelInterface { public: @@ -145,6 +148,7 @@ class SimModelDelaySteerAccGearedWoFallGuard : public SimModelInterface Eigen::VectorXd calcModel(const Eigen::VectorXd & state, const Eigen::VectorXd & input) override; }; -// clang-format off -#endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_WO_FALL_GUARD_HPP_ // NOLINT -// clang-format on +} // namespace autoware::simulator::simple_planning_simulator + +// NOLINTNEXTLINE +#endif // AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_ACC_GEARED_WO_FALL_GUARD_HPP_ diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.hpp b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.hpp similarity index 90% rename from simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.hpp rename to simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.hpp index 381b6ae9da4e2..6b7323db2d9fb 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.hpp +++ b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.hpp @@ -1,4 +1,4 @@ -// Copyright 2023 The Autoware Foundation. +// Copyright 2025 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. @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_MAP_ACC_GEARED_HPP_ -#define SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_MAP_ACC_GEARED_HPP_ +#ifndef AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_MAP_ACC_GEARED_HPP_ // NOLINT +#define AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_MAP_ACC_GEARED_HPP_ // NOLINT #include "autoware/interpolation/linear_interpolation.hpp" +#include "autoware/simple_planning_simulator/utils/csv_loader.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_interface.hpp" #include "eigen3/Eigen/Core" #include "eigen3/Eigen/LU" -#include "simple_planning_simulator/utils/csv_loader.hpp" -#include "simple_planning_simulator/vehicle_model/sim_model_interface.hpp" #include #include @@ -27,6 +27,9 @@ #include #include +namespace autoware::simulator::simple_planning_simulator +{ + class AccelerationMap { public: @@ -209,4 +212,7 @@ class SimModelDelaySteerMapAccGeared : public SimModelInterface const double dt); }; -#endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_MAP_ACC_GEARED_HPP_ +} // namespace autoware::simulator::simple_planning_simulator + +// NOLINTNEXTLINE +#endif // AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_MAP_ACC_GEARED_HPP_ diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.hpp b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.hpp similarity index 89% rename from simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.hpp rename to simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.hpp index 61a9e8d0a5643..d878ef01c0536 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.hpp +++ b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 The Autoware Foundation. +// Copyright 2025 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. @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_VEL_HPP_ -#define SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_VEL_HPP_ +#ifndef AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_VEL_HPP_ +#define AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_VEL_HPP_ -#include "simple_planning_simulator/vehicle_model/sim_model_interface.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_interface.hpp" #include #include @@ -23,6 +23,10 @@ #include #include #include + +namespace autoware::simulator::simple_planning_simulator +{ + /** * @class SimModelDelaySteerVel * @brief calculate delay steering dynamics @@ -149,4 +153,6 @@ class SimModelDelaySteerVel : public SimModelInterface Eigen::VectorXd calcModel(const Eigen::VectorXd & state, const Eigen::VectorXd & input) override; }; -#endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_VEL_HPP_ +} // namespace autoware::simulator::simple_planning_simulator + +#endif // AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_DELAY_STEER_VEL_HPP_ diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc.hpp b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc.hpp similarity index 80% rename from simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc.hpp rename to simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc.hpp index e4fcaa59f1294..86e33b13f0e3d 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc.hpp +++ b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 The Autoware Foundation. +// Copyright 2025 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. @@ -12,16 +12,19 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_IDEAL_STEER_ACC_HPP_ -#define SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_IDEAL_STEER_ACC_HPP_ +#ifndef AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_IDEAL_STEER_ACC_HPP_ +#define AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_IDEAL_STEER_ACC_HPP_ -#include "simple_planning_simulator/vehicle_model/sim_model_interface.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_interface.hpp" #include #include #include +namespace autoware::simulator::simple_planning_simulator +{ + /** * @class SimModelIdealSteerAcc * @brief calculate ideal steering dynamics @@ -103,4 +106,6 @@ class SimModelIdealSteerAcc : public SimModelInterface Eigen::VectorXd calcModel(const Eigen::VectorXd & state, const Eigen::VectorXd & input) override; }; -#endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_IDEAL_STEER_ACC_HPP_ +} // namespace autoware::simulator::simple_planning_simulator + +#endif // AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_IDEAL_STEER_ACC_HPP_ diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.hpp b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.hpp similarity index 83% rename from simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.hpp rename to simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.hpp index c73cc54f4ea99..158326dbbde32 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.hpp +++ b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 The Autoware Foundation. +// Copyright 2025 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. @@ -12,16 +12,19 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_IDEAL_STEER_ACC_GEARED_HPP_ -#define SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_IDEAL_STEER_ACC_GEARED_HPP_ +#ifndef AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_IDEAL_STEER_ACC_GEARED_HPP_ +#define AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_IDEAL_STEER_ACC_GEARED_HPP_ -#include "simple_planning_simulator/vehicle_model/sim_model_interface.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_interface.hpp" #include #include #include +namespace autoware::simulator::simple_planning_simulator +{ + /** * @class SimModelIdealSteerAccGeared * @brief calculate ideal steering dynamics @@ -115,4 +118,6 @@ class SimModelIdealSteerAccGeared : public SimModelInterface const double dt); }; -#endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_IDEAL_STEER_ACC_GEARED_HPP_ +} // namespace autoware::simulator::simple_planning_simulator + +#endif // AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_IDEAL_STEER_ACC_GEARED_HPP_ diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_vel.hpp b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_vel.hpp similarity index 80% rename from simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_vel.hpp rename to simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_vel.hpp index 09046cab89dc4..4febc830f33b5 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_vel.hpp +++ b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_vel.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 The Autoware Foundation. +// Copyright 2025 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. @@ -12,15 +12,19 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_IDEAL_STEER_VEL_HPP_ -#define SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_IDEAL_STEER_VEL_HPP_ +#ifndef AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_IDEAL_STEER_VEL_HPP_ +#define AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_IDEAL_STEER_VEL_HPP_ -#include "simple_planning_simulator/vehicle_model/sim_model_interface.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_interface.hpp" #include #include #include + +namespace autoware::simulator::simple_planning_simulator +{ + /** * @class SimModelIdealSteerVel * @brief calculate ideal steering dynamics @@ -104,4 +108,6 @@ class SimModelIdealSteerVel : public SimModelInterface Eigen::VectorXd calcModel(const Eigen::VectorXd & state, const Eigen::VectorXd & input) override; }; -#endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_IDEAL_STEER_VEL_HPP_ +} // namespace autoware::simulator::simple_planning_simulator + +#endif // AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_IDEAL_STEER_VEL_HPP_ diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_interface.hpp b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_interface.hpp similarity index 91% rename from simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_interface.hpp rename to simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_interface.hpp index bab4531484aa6..5af19c00e4c07 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_interface.hpp +++ b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_interface.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 The Autoware Foundation. +// Copyright 2025 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. @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_INTERFACE_HPP_ -#define SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_INTERFACE_HPP_ +#ifndef AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_INTERFACE_HPP_ +#define AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_INTERFACE_HPP_ #include @@ -22,6 +22,9 @@ #include +namespace autoware::simulator::simple_planning_simulator +{ + /** * @class SimModelInterface * @brief simple_planning_simulator vehicle model class to calculate vehicle dynamics @@ -178,4 +181,6 @@ class SimModelInterface const Eigen::VectorXd & state, const Eigen::VectorXd & input) = 0; }; -#endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_INTERFACE_HPP_ +} // namespace autoware::simulator::simple_planning_simulator + +#endif // AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_INTERFACE_HPP_ diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.hpp b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.hpp similarity index 86% rename from simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.hpp rename to simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.hpp index c6301db42620e..124c0d2532069 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.hpp +++ b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.hpp @@ -1,4 +1,4 @@ -// Copyright 2024 The Autoware Foundation. +// Copyright 2025 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. @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_LEARNED_STEER_VEL_HPP_ -#define SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_LEARNED_STEER_VEL_HPP_ +#ifndef AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_LEARNED_STEER_VEL_HPP_ +#define AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_LEARNED_STEER_VEL_HPP_ +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_interface.hpp" #include "learning_based_vehicle_model/interconnected_model.hpp" -#include "simple_planning_simulator/vehicle_model/sim_model_interface.hpp" #include #include @@ -27,6 +27,9 @@ #include #include +namespace autoware::simulator::simple_planning_simulator +{ + /** * @class SimModelLearnedSteerVel * @brief calculate delay steering dynamics @@ -141,4 +144,6 @@ class SimModelLearnedSteerVel : public SimModelInterface /*delay steer velocity* } }; -#endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_LEARNED_STEER_VEL_HPP_ +} // namespace autoware::simulator::simple_planning_simulator + +#endif // AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_LEARNED_STEER_VEL_HPP_ diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/visibility_control.hpp b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/visibility_control.hpp similarity index 85% rename from simulator/simple_planning_simulator/include/simple_planning_simulator/visibility_control.hpp rename to simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/visibility_control.hpp index 107367b286f80..2edd9467532fa 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/visibility_control.hpp +++ b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/visibility_control.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 The Autoware Foundation +// Copyright 2025 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. @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SIMPLE_PLANNING_SIMULATOR__VISIBILITY_CONTROL_HPP_ -#define SIMPLE_PLANNING_SIMULATOR__VISIBILITY_CONTROL_HPP_ +#ifndef AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VISIBILITY_CONTROL_HPP_ +#define AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VISIBILITY_CONTROL_HPP_ #if defined(__WIN32) #if defined(PLANNING_SIMULATOR_BUILDING_DLL) || defined(PLANNING_SIMULATOR_EXPORTS) @@ -35,4 +35,4 @@ #error "Unsupported Build Configuration" #endif // defined(_WINDOWS) -#endif // SIMPLE_PLANNING_SIMULATOR__VISIBILITY_CONTROL_HPP_ +#endif // AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VISIBILITY_CONTROL_HPP_ diff --git a/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py b/simulator/autoware_simple_planning_simulator/launch/simple_planning_simulator.launch.py similarity index 95% rename from simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py rename to simulator/autoware_simple_planning_simulator/launch/simple_planning_simulator.launch.py index aed088de9fd22..df93acc6e0ff7 100644 --- a/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py +++ b/simulator/autoware_simple_planning_simulator/launch/simple_planning_simulator.launch.py @@ -1,4 +1,4 @@ -# Copyright 2021 The Autoware Foundation. +# Copyright 2025 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. @@ -87,9 +87,8 @@ def launch_setup(context, *args, **kwargs): ) simple_planning_simulator_node = Node( - package="simple_planning_simulator", - executable="simple_planning_simulator_exe", - name="simple_planning_simulator", + package="autoware_simple_planning_simulator", + executable="autoware_simple_planning_simulator_node", namespace="simulation", output="screen", parameters=[ @@ -151,7 +150,7 @@ def add_launch_arg(name: str, default_value=None, description=None): add_launch_arg( "vehicle_characteristics_param_file", [ - FindPackageShare("simple_planning_simulator"), + FindPackageShare("autoware_simple_planning_simulator"), "/param/vehicle_characteristics.param.yaml", ], "path to config file for vehicle characteristics", @@ -160,7 +159,7 @@ def add_launch_arg(name: str, default_value=None, description=None): add_launch_arg( "simulator_model_param_file", [ - FindPackageShare("simple_planning_simulator"), + FindPackageShare("autoware_simple_planning_simulator"), "/param/simple_planning_simulator_default.param.yaml", ], "path to config file for simulator_model", @@ -169,7 +168,7 @@ def add_launch_arg(name: str, default_value=None, description=None): add_launch_arg( "acceleration_param_file", [ - FindPackageShare("simple_planning_simulator"), + FindPackageShare("autoware_simple_planning_simulator"), "/param/acceleration_map.csv", ], ) diff --git a/simulator/simple_planning_simulator/media/acceleration_map.svg b/simulator/autoware_simple_planning_simulator/media/acceleration_map.svg similarity index 100% rename from simulator/simple_planning_simulator/media/acceleration_map.svg rename to simulator/autoware_simple_planning_simulator/media/acceleration_map.svg diff --git a/simulator/simple_planning_simulator/media/mechanical_controller.drawio.svg b/simulator/autoware_simple_planning_simulator/media/mechanical_controller.drawio.svg similarity index 100% rename from simulator/simple_planning_simulator/media/mechanical_controller.drawio.svg rename to simulator/autoware_simple_planning_simulator/media/mechanical_controller.drawio.svg diff --git a/simulator/simple_planning_simulator/media/mechanical_controller_system_identification.png b/simulator/autoware_simple_planning_simulator/media/mechanical_controller_system_identification.png similarity index 100% rename from simulator/simple_planning_simulator/media/mechanical_controller_system_identification.png rename to simulator/autoware_simple_planning_simulator/media/mechanical_controller_system_identification.png diff --git a/simulator/simple_planning_simulator/media/pitch-calculation.drawio.svg b/simulator/autoware_simple_planning_simulator/media/pitch-calculation.drawio.svg similarity index 100% rename from simulator/simple_planning_simulator/media/pitch-calculation.drawio.svg rename to simulator/autoware_simple_planning_simulator/media/pitch-calculation.drawio.svg diff --git a/simulator/simple_planning_simulator/media/vgr_sim.drawio.svg b/simulator/autoware_simple_planning_simulator/media/vgr_sim.drawio.svg similarity index 100% rename from simulator/simple_planning_simulator/media/vgr_sim.drawio.svg rename to simulator/autoware_simple_planning_simulator/media/vgr_sim.drawio.svg diff --git a/simulator/simple_planning_simulator/package.xml b/simulator/autoware_simple_planning_simulator/package.xml similarity index 94% rename from simulator/simple_planning_simulator/package.xml rename to simulator/autoware_simple_planning_simulator/package.xml index 5bd7a2f74eacc..790e48cd80cc1 100644 --- a/simulator/simple_planning_simulator/package.xml +++ b/simulator/autoware_simple_planning_simulator/package.xml @@ -1,7 +1,7 @@ - simple_planning_simulator + autoware_simple_planning_simulator 0.40.0 simple_planning_simulator as a ROS 2 node Takamasa Horibe @@ -10,6 +10,7 @@ Mamoru Sobue Zulfaqar Azmi Temkei Kem + Junya Sasaki Kotaro Yoshimoto Apache License 2.0 diff --git a/simulator/simple_planning_simulator/param/acceleration_map.csv b/simulator/autoware_simple_planning_simulator/param/acceleration_map.csv similarity index 100% rename from simulator/simple_planning_simulator/param/acceleration_map.csv rename to simulator/autoware_simple_planning_simulator/param/acceleration_map.csv diff --git a/simulator/simple_planning_simulator/param/simple_planning_simulator_default.param.yaml b/simulator/autoware_simple_planning_simulator/param/simple_planning_simulator_default.param.yaml similarity index 100% rename from simulator/simple_planning_simulator/param/simple_planning_simulator_default.param.yaml rename to simulator/autoware_simple_planning_simulator/param/simple_planning_simulator_default.param.yaml diff --git a/simulator/simple_planning_simulator/param/simple_planning_simulator_mechanical_sample.param.yaml b/simulator/autoware_simple_planning_simulator/param/simple_planning_simulator_mechanical_sample.param.yaml similarity index 100% rename from simulator/simple_planning_simulator/param/simple_planning_simulator_mechanical_sample.param.yaml rename to simulator/autoware_simple_planning_simulator/param/simple_planning_simulator_mechanical_sample.param.yaml diff --git a/simulator/simple_planning_simulator/param/vehicle_characteristics.param.yaml b/simulator/autoware_simple_planning_simulator/param/vehicle_characteristics.param.yaml similarity index 100% rename from simulator/simple_planning_simulator/param/vehicle_characteristics.param.yaml rename to simulator/autoware_simple_planning_simulator/param/vehicle_characteristics.param.yaml diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp similarity index 98% rename from simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp rename to simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp index 8c95e144b3f8d..b03de1906db78 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp +++ b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 The Autoware Foundation. +// Copyright 2025 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. @@ -12,16 +12,16 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "simple_planning_simulator/simple_planning_simulator_core.hpp" +#include "autoware/simple_planning_simulator/simple_planning_simulator_core.hpp" #include "autoware/motion_utils/trajectory/trajectory.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" #include "autoware/universe_utils/ros/msg_covariance.hpp" #include "autoware/universe_utils/ros/update_param.hpp" #include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" #include "rclcpp_components/register_node_macro.hpp" -#include "simple_planning_simulator/vehicle_model/sim_model.hpp" -#include "simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.hpp" #include #include @@ -43,7 +43,7 @@ using namespace std::literals::chrono_literals; -namespace +namespace autoware::simulator::simple_planning_simulator { autoware_vehicle_msgs::msg::VelocityReport to_velocity_report( @@ -91,12 +91,6 @@ std::vector convert_centerline_to_points( } return centerline_points; } -} // namespace - -namespace simulation -{ -namespace simple_planning_simulator -{ SimplePlanningSimulator::SimplePlanningSimulator(const rclcpp::NodeOptions & options) : Node("simple_planning_simulator", options), tf_buffer_(get_clock()), tf_listener_(tf_buffer_) @@ -957,7 +951,7 @@ void SimplePlanningSimulator::publish_actuation_status() actuation_status.value().header.frame_id = simulated_frame_id_; pub_actuation_status_->publish(actuation_status.value()); } -} // namespace simple_planning_simulator -} // namespace simulation +} // namespace autoware::simulator::simple_planning_simulator -RCLCPP_COMPONENTS_REGISTER_NODE(simulation::simple_planning_simulator::SimplePlanningSimulator) +RCLCPP_COMPONENTS_REGISTER_NODE( + autoware::simulator::simple_planning_simulator::SimplePlanningSimulator) diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/utils/csv_loader.cpp b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/utils/csv_loader.cpp similarity index 94% rename from simulator/simple_planning_simulator/src/simple_planning_simulator/utils/csv_loader.cpp rename to simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/utils/csv_loader.cpp index fa1f7978a798c..0a4f03c959ff0 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/utils/csv_loader.cpp +++ b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/utils/csv_loader.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 Tier IV, Inc. All rights reserved. +// Copyright 2025 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. @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "simple_planning_simulator/utils/csv_loader.hpp" +#include "autoware/simple_planning_simulator/utils/csv_loader.hpp" #include #include @@ -21,6 +21,9 @@ #include #include +namespace autoware::simulator::simple_planning_simulator +{ + CSVLoader::CSVLoader(const std::string & csv_path) { csv_path_ = csv_path; @@ -152,3 +155,5 @@ double CSVLoader::clampValue(const double val, const std::vector & range } return val; } + +} // namespace autoware::simulator::simple_planning_simulator diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/utils/mechanical_controller.cpp b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/utils/mechanical_controller.cpp similarity index 97% rename from simulator/simple_planning_simulator/src/simple_planning_simulator/utils/mechanical_controller.cpp rename to simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/utils/mechanical_controller.cpp index 0977cd9e25a92..84f4ff4ea0ba4 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/utils/mechanical_controller.cpp +++ b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/utils/mechanical_controller.cpp @@ -1,4 +1,4 @@ -// Copyright 2024 The Autoware Foundation. +// Copyright 2025 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. @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "simple_planning_simulator/utils/mechanical_controller.hpp" +#include "autoware/simple_planning_simulator/utils/mechanical_controller.hpp" #include #include @@ -24,7 +24,7 @@ #include #include -namespace autoware::simple_planning_simulator::utils::mechanical_controller +namespace autoware::simulator::simple_planning_simulator { using DelayBuffer = std::deque>; @@ -349,4 +349,4 @@ StepResult MechanicalController::run_one_step( return {delay_buffer_new, pid_error, d_state, false}; } -} // namespace autoware::simple_planning_simulator::utils::mechanical_controller +} // namespace autoware::simulator::simple_planning_simulator diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.cpp b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.cpp similarity index 98% rename from simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.cpp rename to simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.cpp index bfcf571d8c09b..4db0b0856ea25 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.cpp +++ b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.cpp @@ -1,4 +1,4 @@ -// Copyright 2024 The Autoware Foundation. +// Copyright 2025 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. @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.hpp" #include "autoware_vehicle_msgs/msg/gear_command.hpp" @@ -20,6 +20,9 @@ #include #include +namespace autoware::simulator::simple_planning_simulator +{ + bool ActuationMap::readActuationMapFromCSV(const std::string & csv_path, const bool validation) { CSVLoader csv(csv_path); @@ -517,3 +520,4 @@ void SimModelActuationCmdMechanical::setState(const Eigen::VectorXd & state) state_ = state; } /* ---------------------------------------- */ +} // namespace autoware::simulator::simple_planning_simulator diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.cpp b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.cpp similarity index 94% rename from simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.cpp rename to simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.cpp index 6a9b5c65d4760..fbe4db941e8de 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.cpp +++ b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 The Autoware Foundation. +// Copyright 2025 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. @@ -12,10 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.hpp" #include +namespace autoware::simulator::simple_planning_simulator +{ + SimModelDelaySteerAcc::SimModelDelaySteerAcc( double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, double dt, double acc_delay, double acc_time_constant, double steer_delay, @@ -135,3 +138,5 @@ Eigen::VectorXd SimModelDelaySteerAcc::calcModel( return d_state; } + +} // namespace autoware::simulator::simple_planning_simulator diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp similarity index 96% rename from simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp rename to simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp index 88b0e6c639fd1..8db40f7cc5298 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp +++ b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 The Autoware Foundation. +// Copyright 2025 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. @@ -12,12 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp" #include "autoware_vehicle_msgs/msg/gear_command.hpp" #include +namespace autoware::simulator::simple_planning_simulator +{ + SimModelDelaySteerAccGeared::SimModelDelaySteerAccGeared( double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, double dt, double acc_delay, double acc_time_constant, double steer_delay, @@ -180,3 +183,5 @@ void SimModelDelaySteerAccGeared::updateStateWithGear( setStopState(); } } + +} // namespace autoware::simulator::simple_planning_simulator diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.cpp b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.cpp similarity index 96% rename from simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.cpp rename to simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.cpp index 78cfa6caeb946..5e26132aa3e5e 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.cpp +++ b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.cpp @@ -1,4 +1,4 @@ -// Copyright 2024 The Autoware Foundation. +// Copyright 2025 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. @@ -12,12 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.hpp" #include "autoware_vehicle_msgs/msg/gear_command.hpp" #include +namespace autoware::simulator::simple_planning_simulator +{ + SimModelDelaySteerAccGearedWoFallGuard::SimModelDelaySteerAccGearedWoFallGuard( double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, double dt, double acc_delay, double acc_time_constant, double steer_delay, @@ -181,3 +184,5 @@ Eigen::VectorXd SimModelDelaySteerAccGearedWoFallGuard::calcModel( return d_state; } + +} // namespace autoware::simulator::simple_planning_simulator diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.cpp b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.cpp similarity index 95% rename from simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.cpp rename to simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.cpp index ffef5ab7b236c..dc576872a6c18 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.cpp +++ b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 The Autoware Foundation. +// Copyright 2025 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. @@ -12,13 +12,16 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.hpp" #include "autoware_vehicle_msgs/msg/gear_command.hpp" #include #include +namespace autoware::simulator::simple_planning_simulator +{ + SimModelDelaySteerMapAccGeared::SimModelDelaySteerMapAccGeared( double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, double dt, double acc_delay, double acc_time_constant, double steer_delay, @@ -168,3 +171,5 @@ void SimModelDelaySteerMapAccGeared::updateStateWithGear( state(IDX::ACCX) = (state(IDX::VX) - prev_state(IDX::VX)) / std::max(dt, 1.0e-5); } } + +} // namespace autoware::simulator::simple_planning_simulator diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.cpp b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.cpp similarity index 94% rename from simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.cpp rename to simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.cpp index 1ee08fad566f5..66d42d4719bf0 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.cpp +++ b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 The Autoware Foundation. +// Copyright 2025 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. @@ -12,10 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.hpp" #include +namespace autoware::simulator::simple_planning_simulator +{ + SimModelDelaySteerVel::SimModelDelaySteerVel( double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, double dt, double vx_delay, double vx_time_constant, double steer_delay, @@ -132,3 +135,5 @@ Eigen::VectorXd SimModelDelaySteerVel::calcModel( return d_state; } + +} // namespace autoware::simulator::simple_planning_simulator diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc.cpp b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc.cpp similarity index 88% rename from simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc.cpp rename to simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc.cpp index 2edf43f0a743c..f5512c4bdb4b3 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc.cpp +++ b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 The Autoware Foundation. +// Copyright 2025 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. @@ -12,7 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc.hpp" + +namespace autoware::simulator::simple_planning_simulator +{ SimModelIdealSteerAcc::SimModelIdealSteerAcc(double wheelbase) : SimModelInterface(4 /* dim x */, 2 /* dim u */), wheelbase_(wheelbase) @@ -72,3 +75,5 @@ Eigen::VectorXd SimModelIdealSteerAcc::calcModel( return d_state; } + +} // namespace autoware::simulator::simple_planning_simulator diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.cpp b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.cpp similarity index 93% rename from simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.cpp rename to simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.cpp index 46538778bd1b1..e06ca161d36e0 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.cpp +++ b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 The Autoware Foundation. +// Copyright 2025 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. @@ -12,12 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.hpp" #include "autoware_vehicle_msgs/msg/gear_command.hpp" #include +namespace autoware::simulator::simple_planning_simulator +{ + SimModelIdealSteerAccGeared::SimModelIdealSteerAccGeared(double wheelbase) : SimModelInterface(4 /* dim x */, 2 /* dim u */), wheelbase_(wheelbase), current_acc_(0.0) { @@ -115,3 +118,5 @@ void SimModelIdealSteerAccGeared::updateStateWithGear( // calculate acc from velocity diff current_acc_ = (state(IDX::VX) - prev_state(IDX::VX)) / std::max(dt, 1.0e-5); } + +} // namespace autoware::simulator::simple_planning_simulator diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_vel.cpp b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_vel.cpp similarity index 88% rename from simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_vel.cpp rename to simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_vel.cpp index e43ac4aa8eae5..6009b2f0f3fd5 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_vel.cpp +++ b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_vel.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 The Autoware Foundation. +// Copyright 2025 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. @@ -12,7 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "simple_planning_simulator/vehicle_model/sim_model_ideal_steer_vel.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_vel.hpp" + +namespace autoware::simulator::simple_planning_simulator +{ SimModelIdealSteerVel::SimModelIdealSteerVel(double wheelbase) : SimModelInterface(3 /* dim x */, 2 /* dim u */), wheelbase_(wheelbase) @@ -72,3 +75,5 @@ Eigen::VectorXd SimModelIdealSteerVel::calcModel( return d_state; } + +} // namespace autoware::simulator::simple_planning_simulator diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_interface.cpp b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_interface.cpp similarity index 87% rename from simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_interface.cpp rename to simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_interface.cpp index 8d17f72e0c3b3..33135f40c4c87 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_interface.cpp +++ b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_interface.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 The Autoware Foundation. +// Copyright 2025 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. @@ -12,7 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "simple_planning_simulator/vehicle_model/sim_model_interface.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_interface.hpp" + +namespace autoware::simulator::simple_planning_simulator +{ SimModelInterface::SimModelInterface(int dim_x, int dim_u) : dim_x_(dim_x), dim_u_(dim_u) { @@ -57,3 +60,5 @@ uint8_t SimModelInterface::getGear() const { return gear_; } + +} // namespace autoware::simulator::simple_planning_simulator diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.cpp b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.cpp similarity index 90% rename from simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.cpp rename to simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.cpp index 4ddcc0e498b70..2d9c8d8ab0e0e 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.cpp +++ b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.cpp @@ -1,4 +1,4 @@ -// Copyright 2024 The Autoware Foundation. +// Copyright 2025 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. @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.hpp" +#include "autoware/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.hpp" #include "learning_based_vehicle_model/interconnected_model.hpp" @@ -21,6 +21,9 @@ #include #include +namespace autoware::simulator::simple_planning_simulator +{ + SimModelLearnedSteerVel::SimModelLearnedSteerVel( double dt, std::vector model_python_paths, std::vector model_param_paths, std::vector model_class_names) @@ -89,3 +92,5 @@ void SimModelLearnedSteerVel::update(const double & dt) current_ax_ = (input_(IDX_U::VX_DES) - prev_vx_) / dt; prev_vx_ = input_(IDX_U::VX_DES); } + +} // namespace autoware::simulator::simple_planning_simulator diff --git a/simulator/simple_planning_simulator/test/actuation_cmd_map/accel_map.csv b/simulator/autoware_simple_planning_simulator/test/actuation_cmd_map/accel_map.csv similarity index 100% rename from simulator/simple_planning_simulator/test/actuation_cmd_map/accel_map.csv rename to simulator/autoware_simple_planning_simulator/test/actuation_cmd_map/accel_map.csv diff --git a/simulator/simple_planning_simulator/test/actuation_cmd_map/brake_map.csv b/simulator/autoware_simple_planning_simulator/test/actuation_cmd_map/brake_map.csv similarity index 100% rename from simulator/simple_planning_simulator/test/actuation_cmd_map/brake_map.csv rename to simulator/autoware_simple_planning_simulator/test/actuation_cmd_map/brake_map.csv diff --git a/simulator/simple_planning_simulator/test/actuation_cmd_map/steer_map.csv b/simulator/autoware_simple_planning_simulator/test/actuation_cmd_map/steer_map.csv similarity index 100% rename from simulator/simple_planning_simulator/test/actuation_cmd_map/steer_map.csv rename to simulator/autoware_simple_planning_simulator/test/actuation_cmd_map/steer_map.csv diff --git a/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp b/simulator/autoware_simple_planning_simulator/test/test_simple_planning_simulator.cpp similarity index 98% rename from simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp rename to simulator/autoware_simple_planning_simulator/test/test_simple_planning_simulator.cpp index 0baa3302f86c7..afe816ee8944a 100644 --- a/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp +++ b/simulator/autoware_simple_planning_simulator/test/test_simple_planning_simulator.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 The Autoware Foundation +// Copyright 2025 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. @@ -13,8 +13,8 @@ // limitations under the License. #include "ament_index_cpp/get_package_share_directory.hpp" +#include "autoware/simple_planning_simulator/simple_planning_simulator_core.hpp" #include "gtest/gtest.h" -#include "simple_planning_simulator/simple_planning_simulator_core.hpp" #include "tf2/utils.h" #include "tier4_vehicle_msgs/msg/actuation_command_stamped.hpp" @@ -32,15 +32,15 @@ #include +namespace autoware::simulator::simple_planning_simulator +{ + using autoware_control_msgs::msg::Control; using autoware_vehicle_msgs::msg::GearCommand; using geometry_msgs::msg::PoseWithCovarianceStamped; using nav_msgs::msg::Odometry; using tier4_vehicle_msgs::msg::ActuationCommandStamped; -using simulation::simple_planning_simulator::InputCommand; -using simulation::simple_planning_simulator::SimplePlanningSimulator; - std::string toStrInfo(const Odometry & o) { const auto & p = o.pose.pose; @@ -317,7 +317,8 @@ TEST_P(TestSimplePlanningSimulator, TestIdealSteerVel) node_options.append_parameter_override("brake_time_constant", 0.2); node_options.append_parameter_override("convert_accel_cmd", true); node_options.append_parameter_override("convert_brake_cmd", true); - const auto share_dir = ament_index_cpp::get_package_share_directory("simple_planning_simulator"); + const auto share_dir = + ament_index_cpp::get_package_share_directory("autoware_simple_planning_simulator"); const auto accel_map_path = share_dir + "/test/actuation_cmd_map/accel_map.csv"; const auto brake_map_path = share_dir + "/test/actuation_cmd_map/brake_map.csv"; const auto steer_map_path = share_dir + "/test/actuation_cmd_map/steer_map.csv"; @@ -456,3 +457,5 @@ INSTANTIATE_TEST_SUITE_P( std::make_tuple(CommandType::Actuation, "ACTUATION_CMD_STEER_MAP"), std::make_tuple(CommandType::Actuation, "ACTUATION_CMD_VGR"), std::make_tuple(CommandType::Actuation, "ACTUATION_CMD_MECHANICAL"))); + +} // namespace autoware::simulator::simple_planning_simulator diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model.hpp deleted file mode 100644 index 52c3825ae1888..0000000000000 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model.hpp +++ /dev/null @@ -1,30 +0,0 @@ -// Copyright 2021 The Autoware Foundation. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_HPP_ -#define SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_HPP_ - -#include "simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.hpp" -#include "simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.hpp" -#include "simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.hpp" -#include "simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared_wo_fall_guard.hpp" -#include "simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.hpp" -#include "simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.hpp" -#include "simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc.hpp" -#include "simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.hpp" -#include "simple_planning_simulator/vehicle_model/sim_model_ideal_steer_vel.hpp" -#include "simple_planning_simulator/vehicle_model/sim_model_interface.hpp" -#include "simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.hpp" - -#endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_HPP_ From bca90301b2a0c142402ec59d1e59f78452bc58a9 Mon Sep 17 00:00:00 2001 From: "Kem (TiankuiXian)" <1041084556@qq.com> Date: Thu, 23 Jan 2025 18:02:30 +0900 Subject: [PATCH 303/334] feat(autoware_control_evaluator): add new boundary_distance metrics (#9984) * add boundary_distance metric Signed-off-by: xtk8532704 <1041084556@qq.com> * pre-commit Signed-off-by: xtk8532704 <1041084556@qq.com> * use path topic instead of lanenet. Signed-off-by: xtk8532704 <1041084556@qq.com> * remove unused import Signed-off-by: xtk8532704 <1041084556@qq.com> * apply is_point_left_of_line Signed-off-by: xtk8532704 <1041084556@qq.com> * fix typo Signed-off-by: xtk8532704 <1041084556@qq.com> * fix test bug Signed-off-by: xtk8532704 <1041084556@qq.com> * manual pre-commit Signed-off-by: xtk8532704 <1041084556@qq.com> --------- Signed-off-by: xtk8532704 <1041084556@qq.com> Co-authored-by: t4-adc --- .../autoware_control_evaluator/CMakeLists.txt | 3 +- .../control_evaluator_node.hpp | 14 +++- .../metrics/deviation_metrics.hpp | 2 +- .../control_evaluator/metrics/metric.hpp | 11 ++- .../metrics/metrics_utils.hpp | 62 +++++++++++++++++ .../launch/control_evaluator.launch.xml | 2 + .../autoware_control_evaluator/package.xml | 2 + .../src/control_evaluator_node.cpp | 66 ++++++++++++++---- .../src/metrics/deviation_metrics.cpp | 2 +- .../src/metrics/metrics_utils.cpp | 69 +++++++++++++++++++ .../test/test_control_evaluator_node.cpp | 12 ++-- 11 files changed, 219 insertions(+), 26 deletions(-) create mode 100644 evaluator/autoware_control_evaluator/include/autoware/control_evaluator/metrics/metrics_utils.hpp create mode 100644 evaluator/autoware_control_evaluator/src/metrics/metrics_utils.cpp diff --git a/evaluator/autoware_control_evaluator/CMakeLists.txt b/evaluator/autoware_control_evaluator/CMakeLists.txt index 5d6474de88015..e01f1d2bba1f8 100644 --- a/evaluator/autoware_control_evaluator/CMakeLists.txt +++ b/evaluator/autoware_control_evaluator/CMakeLists.txt @@ -7,8 +7,7 @@ autoware_package() find_package(pluginlib REQUIRED) ament_auto_add_library(control_evaluator_node SHARED - src/control_evaluator_node.cpp - src/metrics/deviation_metrics.cpp + DIRECTORY src ) rclcpp_components_register_node(control_evaluator_node diff --git a/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp b/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp index 9606dea577bd0..663da9e9ebd87 100644 --- a/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp +++ b/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp @@ -1,4 +1,4 @@ -// Copyright 2024 Tier IV, Inc. +// Copyright 2025 Tier IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -22,6 +22,7 @@ #include #include #include +#include #include #include "geometry_msgs/msg/accel_with_covariance_stamped.hpp" @@ -30,6 +31,7 @@ #include #include #include +#include #include #include @@ -39,6 +41,9 @@ namespace control_diagnostics { using autoware::universe_utils::Accumulator; +using autoware::universe_utils::LineString2d; +using autoware::universe_utils::Point2d; +using autoware::vehicle_info_utils::VehicleInfo; using autoware_planning_msgs::msg::Trajectory; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; @@ -48,6 +53,7 @@ using autoware_planning_msgs::msg::LaneletRoute; using geometry_msgs::msg::AccelWithCovarianceStamped; using MetricMsg = tier4_metric_msgs::msg::Metric; using MetricArrayMsg = tier4_metric_msgs::msg::MetricArray; +using tier4_planning_msgs::msg::PathWithLaneId; /** * @brief Node for control evaluation @@ -64,8 +70,9 @@ class ControlEvaluatorNode : public rclcpp::Node void AddGoalLongitudinalDeviationMetricMsg(const Pose & ego_pose); void AddGoalLateralDeviationMetricMsg(const Pose & ego_pose); void AddGoalYawDeviationMetricMsg(const Pose & ego_pose); + void AddBoundaryDistanceMetricMsg(const PathWithLaneId & behavior_path, const Pose & ego_pose); - void AddLaneletMetricMsg(const Pose & ego_pose); + void AddLaneletInfoMsg(const Pose & ego_pose); void AddKinematicStateMetricMsg( const Odometry & odom, const AccelWithCovarianceStamped & accel_stamped); @@ -84,6 +91,8 @@ class ControlEvaluatorNode : public rclcpp::Node autoware::universe_utils::InterProcessPollingSubscriber< LaneletMapBin, autoware::universe_utils::polling_policy::Newest> vector_map_subscriber_{this, "~/input/vector_map", rclcpp::QoS{1}.transient_local()}; + autoware::universe_utils::InterProcessPollingSubscriber behavior_path_subscriber_{ + this, "~/input/behavior_path"}; rclcpp::Publisher::SharedPtr processing_time_pub_; @@ -106,6 +115,7 @@ class ControlEvaluatorNode : public rclcpp::Node metric_accumulators_; // 3(min, max, mean) * metric_size MetricArrayMsg metrics_msg_; + VehicleInfo vehicle_info_; autoware::route_handler::RouteHandler route_handler_; rclcpp::TimerBase::SharedPtr timer_; std::optional prev_acc_stamped_{std::nullopt}; diff --git a/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/metrics/deviation_metrics.hpp b/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/metrics/deviation_metrics.hpp index e0e04b0a65070..514dfcc69ae35 100644 --- a/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/metrics/deviation_metrics.hpp +++ b/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/metrics/deviation_metrics.hpp @@ -1,4 +1,4 @@ -// Copyright 2024 TIER IV, Inc. +// Copyright 2025 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. diff --git a/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/metrics/metric.hpp b/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/metrics/metric.hpp index be2f3135d7f7e..ab2533d0f6ed3 100644 --- a/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/metrics/metric.hpp +++ b/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/metrics/metric.hpp @@ -31,6 +31,8 @@ enum class Metric { goal_longitudinal_deviation, goal_lateral_deviation, goal_yaw_deviation, + left_boundary_distance, + right_boundary_distance, SIZE, }; @@ -40,6 +42,8 @@ static const std::unordered_map str_to_metric = { {"goal_longitudinal_deviation", Metric::goal_longitudinal_deviation}, {"goal_lateral_deviation", Metric::goal_lateral_deviation}, {"goal_yaw_deviation", Metric::goal_yaw_deviation}, + {"left_boundary_distance", Metric::left_boundary_distance}, + {"right_boundary_distance", Metric::right_boundary_distance}, }; static const std::unordered_map metric_to_str = { @@ -48,6 +52,8 @@ static const std::unordered_map metric_to_str = { {Metric::goal_longitudinal_deviation, "goal_longitudinal_deviation"}, {Metric::goal_lateral_deviation, "goal_lateral_deviation"}, {Metric::goal_yaw_deviation, "goal_yaw_deviation"}, + {Metric::left_boundary_distance, "left_boundary_distance"}, + {Metric::right_boundary_distance, "right_boundary_distance"}, }; // Metrics descriptions @@ -56,7 +62,10 @@ static const std::unordered_map metric_descriptions = { {Metric::yaw_deviation, "Yaw deviation from the reference trajectory[rad]"}, {Metric::goal_longitudinal_deviation, "Longitudinal deviation from the goal point[m]"}, {Metric::goal_lateral_deviation, "Lateral deviation from the goal point[m]"}, - {Metric::goal_yaw_deviation, "Yaw deviation from the goal point[rad]"}}; + {Metric::goal_yaw_deviation, "Yaw deviation from the goal point[rad]"}, + {Metric::left_boundary_distance, "Signed distance to the left boundary[m]"}, + {Metric::right_boundary_distance, "Signed distance to the right boundary[m]"}, +}; namespace details { diff --git a/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/metrics/metrics_utils.hpp b/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/metrics/metrics_utils.hpp new file mode 100644 index 0000000000000..9527b00aa3b9d --- /dev/null +++ b/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/metrics/metrics_utils.hpp @@ -0,0 +1,62 @@ +// Copyright 2025 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__CONTROL_EVALUATOR__METRICS__METRICS_UTILS_HPP_ +#define AUTOWARE__CONTROL_EVALUATOR__METRICS__METRICS_UTILS_HPP_ + +#include +#include + +#include +namespace control_diagnostics +{ +namespace metrics +{ +namespace utils +{ +using autoware::route_handler::RouteHandler; +using geometry_msgs::msg::Point; +using geometry_msgs::msg::Pose; + +/** + * @brief Get the closest lanelets to the ego vehicle, considering shoulder lanelets. + * @param [in] route_handler route handler + * @param [in] ego_pose ego vehicle pose + * @return closest lanelets to the ego vehicle + **/ +lanelet::ConstLanelets get_current_lanes(const RouteHandler & route_handler, const Pose & ego_pose); + +/** + * @brief Calculate the Euler distance between the vehicle and the lanelet. + * @param [in] vehicle_footprint vehicle footprint + * @param [in] line lanelet line + * @return distance between the vehicle footprint and the lanelet, 0.0 if the vehicle intersects + *with the line + **/ +double calc_distance_to_line( + const autoware::universe_utils::LinearRing2d & vehicle_footprint, + const autoware::universe_utils::LineString2d & line); + +/** + * @brief Check if the point is on the left side of the line. + * @param [in] point point + * @param [in] line line + * @return true if the ego vehicle is on the left side of the lanelet line, false otherwise + **/ +bool is_point_left_of_line(const Point & point, const std::vector & line); + +} // namespace utils +} // namespace metrics +} // namespace control_diagnostics +#endif // AUTOWARE__CONTROL_EVALUATOR__METRICS__METRICS_UTILS_HPP_ diff --git a/evaluator/autoware_control_evaluator/launch/control_evaluator.launch.xml b/evaluator/autoware_control_evaluator/launch/control_evaluator.launch.xml index 4cf795afb5a7d..7d26a58367fa1 100644 --- a/evaluator/autoware_control_evaluator/launch/control_evaluator.launch.xml +++ b/evaluator/autoware_control_evaluator/launch/control_evaluator.launch.xml @@ -5,6 +5,7 @@ + @@ -15,6 +16,7 @@ + diff --git a/evaluator/autoware_control_evaluator/package.xml b/evaluator/autoware_control_evaluator/package.xml index a636a55bc5efd..ea8f0875855d1 100644 --- a/evaluator/autoware_control_evaluator/package.xml +++ b/evaluator/autoware_control_evaluator/package.xml @@ -21,6 +21,7 @@ autoware_route_handler autoware_test_utils autoware_universe_utils + autoware_vehicle_info_utils nav_msgs nlohmann-json-dev pluginlib @@ -29,6 +30,7 @@ tf2 tf2_ros tier4_metric_msgs + tier4_planning_msgs ament_cmake_ros ament_lint_auto diff --git a/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp b/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp index 79e89423af6dd..4abfb25afeee8 100644 --- a/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp +++ b/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp @@ -1,4 +1,4 @@ -// Copyright 2024 Tier IV, Inc. +// Copyright 2025 Tier IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -14,6 +14,9 @@ #include "autoware/control_evaluator/control_evaluator_node.hpp" +#include "autoware/control_evaluator/metrics/metrics_utils.hpp" + +#include #include #include #include @@ -29,7 +32,8 @@ namespace control_diagnostics { ControlEvaluatorNode::ControlEvaluatorNode(const rclcpp::NodeOptions & node_options) -: Node("control_evaluator", node_options) +: Node("control_evaluator", node_options), + vehicle_info_(autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo()) { using std::placeholders::_1; @@ -136,17 +140,9 @@ void ControlEvaluatorNode::AddMetricMsg(const Metric & metric, const double & me } } -void ControlEvaluatorNode::AddLaneletMetricMsg(const Pose & ego_pose) +void ControlEvaluatorNode::AddLaneletInfoMsg(const Pose & ego_pose) { - const auto current_lanelets = [&]() { - lanelet::ConstLanelet closest_route_lanelet; - route_handler_.getClosestLaneletWithinRoute(ego_pose, &closest_route_lanelet); - const auto shoulder_lanelets = route_handler_.getShoulderLaneletsAtPose(ego_pose); - lanelet::ConstLanelets closest_lanelets{closest_route_lanelet}; - closest_lanelets.insert( - closest_lanelets.end(), shoulder_lanelets.begin(), shoulder_lanelets.end()); - return closest_lanelets; - }(); + const auto current_lanelets = metrics::utils::get_current_lanes(route_handler_, ego_pose); const auto arc_coordinates = lanelet::utils::getArcCoordinates(current_lanelets, ego_pose); lanelet::ConstLanelet current_lane; lanelet::utils::query::getClosestLanelet(current_lanelets, ego_pose, ¤t_lane); @@ -173,6 +169,43 @@ void ControlEvaluatorNode::AddLaneletMetricMsg(const Pose & ego_pose) } } +void ControlEvaluatorNode::AddBoundaryDistanceMetricMsg( + const PathWithLaneId & behavior_path, const Pose & ego_pose) +{ + const auto current_lanelets = metrics::utils::get_current_lanes(route_handler_, ego_pose); + lanelet::ConstLanelet current_lane; + lanelet::utils::query::getClosestLanelet(current_lanelets, ego_pose, ¤t_lane); + const auto local_vehicle_footprint = vehicle_info_.createFootprint(); + const auto current_vehicle_footprint = + transformVector(local_vehicle_footprint, autoware::universe_utils::pose2transform(ego_pose)); + + if (behavior_path.left_bound.size() >= 1) { + LineString2d left_boundary; + for (const auto & p : behavior_path.left_bound) left_boundary.push_back(Point2d(p.x, p.y)); + double distance_to_left_boundary = + metrics::utils::calc_distance_to_line(current_vehicle_footprint, left_boundary); + + if (metrics::utils::is_point_left_of_line(ego_pose.position, behavior_path.left_bound)) { + distance_to_left_boundary *= -1.0; + } + const Metric metric_left = Metric::left_boundary_distance; + AddMetricMsg(metric_left, distance_to_left_boundary); + } + + if (behavior_path.right_bound.size() >= 1) { + LineString2d right_boundary; + for (const auto & p : behavior_path.right_bound) right_boundary.push_back(Point2d(p.x, p.y)); + double distance_to_right_boundary = + metrics::utils::calc_distance_to_line(current_vehicle_footprint, right_boundary); + + if (!metrics::utils::is_point_left_of_line(ego_pose.position, behavior_path.right_bound)) { + distance_to_right_boundary *= -1.0; + } + const Metric metric_right = Metric::right_boundary_distance; + AddMetricMsg(metric_right, distance_to_right_boundary); + } +} + void ControlEvaluatorNode::AddKinematicStateMetricMsg( const Odometry & odom, const AccelWithCovarianceStamped & accel_stamped) { @@ -260,6 +293,7 @@ void ControlEvaluatorNode::onTimer() const auto traj = traj_sub_.takeData(); const auto odom = odometry_sub_.takeData(); const auto acc = accel_sub_.takeData(); + const auto behavior_path = behavior_path_subscriber_.takeData(); // calculate deviation metrics if (odom && traj && !traj->points.empty()) { @@ -271,8 +305,7 @@ void ControlEvaluatorNode::onTimer() getRouteData(); if (odom && route_handler_.isHandlerReady()) { const Pose ego_pose = odom->pose.pose; - AddLaneletMetricMsg(ego_pose); - + AddLaneletInfoMsg(ego_pose); AddGoalLongitudinalDeviationMetricMsg(ego_pose); AddGoalLateralDeviationMetricMsg(ego_pose); AddGoalYawDeviationMetricMsg(ego_pose); @@ -282,6 +315,11 @@ void ControlEvaluatorNode::onTimer() AddKinematicStateMetricMsg(*odom, *acc); } + if (odom && behavior_path) { + const Pose ego_pose = odom->pose.pose; + AddBoundaryDistanceMetricMsg(*behavior_path, ego_pose); + } + // Publish metrics metrics_msg_.stamp = now(); metrics_pub_->publish(metrics_msg_); diff --git a/evaluator/autoware_control_evaluator/src/metrics/deviation_metrics.cpp b/evaluator/autoware_control_evaluator/src/metrics/deviation_metrics.cpp index a851eeb410620..aa5b47ad31a4b 100644 --- a/evaluator/autoware_control_evaluator/src/metrics/deviation_metrics.cpp +++ b/evaluator/autoware_control_evaluator/src/metrics/deviation_metrics.cpp @@ -1,4 +1,4 @@ -// Copyright 2024 TIER IV, Inc. +// Copyright 2025 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. diff --git a/evaluator/autoware_control_evaluator/src/metrics/metrics_utils.cpp b/evaluator/autoware_control_evaluator/src/metrics/metrics_utils.cpp new file mode 100644 index 0000000000000..3fe95d4decb8d --- /dev/null +++ b/evaluator/autoware_control_evaluator/src/metrics/metrics_utils.cpp @@ -0,0 +1,69 @@ +// Copyright 2025 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/control_evaluator/metrics/metrics_utils.hpp" + +#include "autoware/motion_utils/trajectory/trajectory.hpp" + +#include +#include +#include +#include + +#include +// #include + +#include + +#include +#include +namespace control_diagnostics +{ +namespace metrics +{ +namespace utils +{ +using autoware::route_handler::RouteHandler; +using geometry_msgs::msg::Point; +using geometry_msgs::msg::Pose; + +lanelet::ConstLanelets get_current_lanes(const RouteHandler & route_handler, const Pose & ego_pose) +{ + lanelet::ConstLanelet closest_route_lanelet; + route_handler.getClosestLaneletWithinRoute(ego_pose, &closest_route_lanelet); + const auto shoulder_lanelets = route_handler.getShoulderLaneletsAtPose(ego_pose); + lanelet::ConstLanelets closest_lanelets{closest_route_lanelet}; + closest_lanelets.insert( + closest_lanelets.end(), shoulder_lanelets.begin(), shoulder_lanelets.end()); + return closest_lanelets; +} + +double calc_distance_to_line( + const autoware::universe_utils::LinearRing2d & vehicle_footprint, + const autoware::universe_utils::LineString2d & line) +{ + return boost::geometry::distance(vehicle_footprint, line); +} + +bool is_point_left_of_line(const Point & point, const std::vector & line) +{ + const size_t closest_idx = autoware::motion_utils::findNearestSegmentIndex(line, point); + const auto & p1 = line[closest_idx]; + const auto & p2 = line[closest_idx + 1]; + return ((p2.x - p1.x) * (point.y - p1.y) - (p2.y - p1.y) * (point.x - p1.x)) > 0; +} + +} // namespace utils +} // namespace metrics +} // namespace control_diagnostics diff --git a/evaluator/autoware_control_evaluator/test/test_control_evaluator_node.cpp b/evaluator/autoware_control_evaluator/test/test_control_evaluator_node.cpp index 9098ce5667424..b2dcc93855c0f 100644 --- a/evaluator/autoware_control_evaluator/test/test_control_evaluator_node.cpp +++ b/evaluator/autoware_control_evaluator/test/test_control_evaluator_node.cpp @@ -1,4 +1,4 @@ -// Copyright 2024 Tier IV, Inc. +// Copyright 2025 Tier IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -51,11 +51,13 @@ class EvalTest : public ::testing::Test rclcpp::init(0, nullptr); rclcpp::NodeOptions options; - const auto share_dir = - ament_index_cpp::get_package_share_directory("autoware_control_evaluator"); - options.arguments({"--ros-args", "-p", "output_metrics:=false"}); + const auto autoware_test_utils_dir = + ament_index_cpp::get_package_share_directory("autoware_test_utils"); + options.arguments( + {"--ros-args", "-p", "output_metrics:=false", "--params-file", + autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml"}); - dummy_node = std::make_shared("control_evaluator_test_node"); + dummy_node = std::make_shared("control_evaluator_test_node", options); eval_node = std::make_shared(options); // Enable all logging in the node auto ret = rcutils_logging_set_logger_level( From 47d55f437e14d1bd66b48626ff03ea903198a1c7 Mon Sep 17 00:00:00 2001 From: Junya Sasaki Date: Thu, 23 Jan 2025 18:06:48 +0900 Subject: [PATCH 304/334] feat: apply `autoware_` prefix for `predicted_path_checker` (#9985) * feat(predicted_path_checker): apply `autoware_` prefix (see below): Note: * In this commit, I did not organize a folder structure. The folder structure will be organized in the next some commits. * The changes will follow the Autoware's guideline as below: - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder Signed-off-by: Junya Sasaki * rename(predicted_path_checker): move headers under `include/autoware` * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit Signed-off-by: Junya Sasaki * fix(predicted_path_checker): fix include header paths * To follow the previous commit Signed-off-by: Junya Sasaki * rename: `predicted_path_checker` => `autoware_predicted_path_checker` Signed-off-by: Junya Sasaki * style(pre-commit): autofix * bug(autoware_predicted_path_checker): fix inconsistent namespacings Signed-off-by: Junya Sasaki * bug(autoware_predicted_path_checker): do not change node name * This might contaminate topic name Signed-off-by: Junya Sasaki * style(pre-commit): autofix * bug(tier4_control_launch): fix wrong package/plugin names Signed-off-by: Junya Sasaki --------- Signed-off-by: Junya Sasaki Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../CHANGELOG.rst | 0 .../CMakeLists.txt | 10 +++---- .../README.md | 0 .../config/predicted_path_checker.param.yaml | 0 .../images/FlowChart.png | Bin .../images/Z_axis_filtering.png | Bin .../images/general-structure.png | Bin .../collision_checker.hpp | 14 +++++----- .../predicted_path_checker/debug_marker.hpp | 10 +++---- .../predicted_path_checker_node.hpp | 14 +++++----- .../predicted_path_checker/utils.hpp | 10 +++---- .../launch/predicted_path_checker.launch.xml | 4 +-- .../package.xml | 3 +- .../collision_checker.cpp | 18 ++++++------ .../debug_marker.cpp | 6 ++-- .../predicted_path_checker_node.cpp | 26 ++++++++---------- .../src/predicted_path_checker_node/utils.cpp | 12 ++++---- .../launch/control.launch.xml | 2 +- 18 files changed, 64 insertions(+), 65 deletions(-) rename control/{predicted_path_checker => autoware_predicted_path_checker}/CHANGELOG.rst (100%) rename control/{predicted_path_checker => autoware_predicted_path_checker}/CMakeLists.txt (68%) rename control/{predicted_path_checker => autoware_predicted_path_checker}/README.md (100%) rename control/{predicted_path_checker => autoware_predicted_path_checker}/config/predicted_path_checker.param.yaml (100%) rename control/{predicted_path_checker => autoware_predicted_path_checker}/images/FlowChart.png (100%) rename control/{predicted_path_checker => autoware_predicted_path_checker}/images/Z_axis_filtering.png (100%) rename control/{predicted_path_checker => autoware_predicted_path_checker}/images/general-structure.png (100%) rename control/{predicted_path_checker/include => autoware_predicted_path_checker/include/autoware}/predicted_path_checker/collision_checker.hpp (90%) rename control/{predicted_path_checker/include => autoware_predicted_path_checker/include/autoware}/predicted_path_checker/debug_marker.hpp (91%) rename control/{predicted_path_checker/include => autoware_predicted_path_checker/include/autoware}/predicted_path_checker/predicted_path_checker_node.hpp (93%) rename control/{predicted_path_checker/include => autoware_predicted_path_checker/include/autoware}/predicted_path_checker/utils.hpp (94%) rename control/{predicted_path_checker => autoware_predicted_path_checker}/launch/predicted_path_checker.launch.xml (79%) rename control/{predicted_path_checker => autoware_predicted_path_checker}/package.xml (93%) rename control/{predicted_path_checker => autoware_predicted_path_checker}/src/predicted_path_checker_node/collision_checker.cpp (93%) rename control/{predicted_path_checker => autoware_predicted_path_checker}/src/predicted_path_checker_node/debug_marker.cpp (98%) rename control/{predicted_path_checker => autoware_predicted_path_checker}/src/predicted_path_checker_node/predicted_path_checker_node.cpp (95%) rename control/{predicted_path_checker => autoware_predicted_path_checker}/src/predicted_path_checker_node/utils.cpp (98%) diff --git a/control/predicted_path_checker/CHANGELOG.rst b/control/autoware_predicted_path_checker/CHANGELOG.rst similarity index 100% rename from control/predicted_path_checker/CHANGELOG.rst rename to control/autoware_predicted_path_checker/CHANGELOG.rst diff --git a/control/predicted_path_checker/CMakeLists.txt b/control/autoware_predicted_path_checker/CMakeLists.txt similarity index 68% rename from control/predicted_path_checker/CMakeLists.txt rename to control/autoware_predicted_path_checker/CMakeLists.txt index cfbe95df99e74..d14798805b5e5 100644 --- a/control/predicted_path_checker/CMakeLists.txt +++ b/control/autoware_predicted_path_checker/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(predicted_path_checker) +project(autoware_predicted_path_checker) find_package(autoware_cmake REQUIRED) autoware_package() @@ -12,7 +12,7 @@ include_directories( ${Eigen3_INCLUDE_DIRS} ) -ament_auto_add_library(predicted_path_checker SHARED +ament_auto_add_library(${PROJECT_NAME} SHARED src/predicted_path_checker_node/predicted_path_checker_node.cpp src/predicted_path_checker_node/collision_checker.cpp src/predicted_path_checker_node/utils.cpp @@ -20,9 +20,9 @@ ament_auto_add_library(predicted_path_checker SHARED ) -rclcpp_components_register_node(predicted_path_checker - PLUGIN "autoware::motion::control::predicted_path_checker::PredictedPathCheckerNode" - EXECUTABLE predicted_path_checker_node +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "autoware::predicted_path_checker::PredictedPathCheckerNode" + EXECUTABLE ${PROJECT_NAME}_node ) if(BUILD_TESTING) diff --git a/control/predicted_path_checker/README.md b/control/autoware_predicted_path_checker/README.md similarity index 100% rename from control/predicted_path_checker/README.md rename to control/autoware_predicted_path_checker/README.md diff --git a/control/predicted_path_checker/config/predicted_path_checker.param.yaml b/control/autoware_predicted_path_checker/config/predicted_path_checker.param.yaml similarity index 100% rename from control/predicted_path_checker/config/predicted_path_checker.param.yaml rename to control/autoware_predicted_path_checker/config/predicted_path_checker.param.yaml diff --git a/control/predicted_path_checker/images/FlowChart.png b/control/autoware_predicted_path_checker/images/FlowChart.png similarity index 100% rename from control/predicted_path_checker/images/FlowChart.png rename to control/autoware_predicted_path_checker/images/FlowChart.png diff --git a/control/predicted_path_checker/images/Z_axis_filtering.png b/control/autoware_predicted_path_checker/images/Z_axis_filtering.png similarity index 100% rename from control/predicted_path_checker/images/Z_axis_filtering.png rename to control/autoware_predicted_path_checker/images/Z_axis_filtering.png diff --git a/control/predicted_path_checker/images/general-structure.png b/control/autoware_predicted_path_checker/images/general-structure.png similarity index 100% rename from control/predicted_path_checker/images/general-structure.png rename to control/autoware_predicted_path_checker/images/general-structure.png diff --git a/control/predicted_path_checker/include/predicted_path_checker/collision_checker.hpp b/control/autoware_predicted_path_checker/include/autoware/predicted_path_checker/collision_checker.hpp similarity index 90% rename from control/predicted_path_checker/include/predicted_path_checker/collision_checker.hpp rename to control/autoware_predicted_path_checker/include/autoware/predicted_path_checker/collision_checker.hpp index e2c76bec24860..bed95f4d8987c 100644 --- a/control/predicted_path_checker/include/predicted_path_checker/collision_checker.hpp +++ b/control/autoware_predicted_path_checker/include/autoware/predicted_path_checker/collision_checker.hpp @@ -12,17 +12,17 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PREDICTED_PATH_CHECKER__COLLISION_CHECKER_HPP_ -#define PREDICTED_PATH_CHECKER__COLLISION_CHECKER_HPP_ +#ifndef AUTOWARE__PREDICTED_PATH_CHECKER__COLLISION_CHECKER_HPP_ +#define AUTOWARE__PREDICTED_PATH_CHECKER__COLLISION_CHECKER_HPP_ #include #include +#include +#include #include #include #include #include -#include -#include #include #include @@ -40,7 +40,7 @@ #include #include -namespace autoware::motion::control::predicted_path_checker +namespace autoware::predicted_path_checker { using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; @@ -123,6 +123,6 @@ class CollisionChecker autoware::vehicle_info_utils::VehicleInfo vehicle_info_; std::vector predicted_object_history_{}; }; -} // namespace autoware::motion::control::predicted_path_checker +} // namespace autoware::predicted_path_checker -#endif // PREDICTED_PATH_CHECKER__COLLISION_CHECKER_HPP_ +#endif // AUTOWARE__PREDICTED_PATH_CHECKER__COLLISION_CHECKER_HPP_ diff --git a/control/predicted_path_checker/include/predicted_path_checker/debug_marker.hpp b/control/autoware_predicted_path_checker/include/autoware/predicted_path_checker/debug_marker.hpp similarity index 91% rename from control/predicted_path_checker/include/predicted_path_checker/debug_marker.hpp rename to control/autoware_predicted_path_checker/include/autoware/predicted_path_checker/debug_marker.hpp index 0f537d52cee06..f9dff3347272a 100644 --- a/control/predicted_path_checker/include/predicted_path_checker/debug_marker.hpp +++ b/control/autoware_predicted_path_checker/include/autoware/predicted_path_checker/debug_marker.hpp @@ -11,8 +11,8 @@ // 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 PREDICTED_PATH_CHECKER__DEBUG_MARKER_HPP_ -#define PREDICTED_PATH_CHECKER__DEBUG_MARKER_HPP_ +#ifndef AUTOWARE__PREDICTED_PATH_CHECKER__DEBUG_MARKER_HPP_ +#define AUTOWARE__PREDICTED_PATH_CHECKER__DEBUG_MARKER_HPP_ #include @@ -35,7 +35,7 @@ #include #include -namespace autoware::motion::control::predicted_path_checker +namespace autoware::predicted_path_checker { enum class PolygonType : int8_t { Vehicle = 0, Collision }; @@ -87,6 +87,6 @@ class PredictedPathCheckerDebugNode std::vector> collision_polyhedrons_; }; -} // namespace autoware::motion::control::predicted_path_checker +} // namespace autoware::predicted_path_checker -#endif // PREDICTED_PATH_CHECKER__DEBUG_MARKER_HPP_ +#endif // AUTOWARE__PREDICTED_PATH_CHECKER__DEBUG_MARKER_HPP_ diff --git a/control/predicted_path_checker/include/predicted_path_checker/predicted_path_checker_node.hpp b/control/autoware_predicted_path_checker/include/autoware/predicted_path_checker/predicted_path_checker_node.hpp similarity index 93% rename from control/predicted_path_checker/include/predicted_path_checker/predicted_path_checker_node.hpp rename to control/autoware_predicted_path_checker/include/autoware/predicted_path_checker/predicted_path_checker_node.hpp index 68b879743c5c5..33e0cb13efdca 100644 --- a/control/predicted_path_checker/include/predicted_path_checker/predicted_path_checker_node.hpp +++ b/control/autoware_predicted_path_checker/include/autoware/predicted_path_checker/predicted_path_checker_node.hpp @@ -12,20 +12,20 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PREDICTED_PATH_CHECKER__PREDICTED_PATH_CHECKER_NODE_HPP_ -#define PREDICTED_PATH_CHECKER__PREDICTED_PATH_CHECKER_NODE_HPP_ +#ifndef AUTOWARE__PREDICTED_PATH_CHECKER__PREDICTED_PATH_CHECKER_NODE_HPP_ +#define AUTOWARE__PREDICTED_PATH_CHECKER__PREDICTED_PATH_CHECKER_NODE_HPP_ #include #include #include #include +#include +#include #include #include #include #include #include -#include -#include #include #include @@ -45,7 +45,7 @@ #include #include -namespace autoware::motion::control::predicted_path_checker +namespace autoware::predicted_path_checker { using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; @@ -178,6 +178,6 @@ class PredictedPathCheckerNode : public rclcpp::Node // Diagnostic Updater diagnostic_updater::Updater updater_; }; -} // namespace autoware::motion::control::predicted_path_checker +} // namespace autoware::predicted_path_checker -#endif // PREDICTED_PATH_CHECKER__PREDICTED_PATH_CHECKER_NODE_HPP_ +#endif // AUTOWARE__PREDICTED_PATH_CHECKER__PREDICTED_PATH_CHECKER_NODE_HPP_ diff --git a/control/predicted_path_checker/include/predicted_path_checker/utils.hpp b/control/autoware_predicted_path_checker/include/autoware/predicted_path_checker/utils.hpp similarity index 94% rename from control/predicted_path_checker/include/predicted_path_checker/utils.hpp rename to control/autoware_predicted_path_checker/include/autoware/predicted_path_checker/utils.hpp index 984584d16aa8f..bf46025242401 100644 --- a/control/predicted_path_checker/include/predicted_path_checker/utils.hpp +++ b/control/autoware_predicted_path_checker/include/autoware/predicted_path_checker/utils.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PREDICTED_PATH_CHECKER__UTILS_HPP_ -#define PREDICTED_PATH_CHECKER__UTILS_HPP_ +#ifndef AUTOWARE__PREDICTED_PATH_CHECKER__UTILS_HPP_ +#define AUTOWARE__PREDICTED_PATH_CHECKER__UTILS_HPP_ #include #include @@ -36,7 +36,7 @@ #include #include -namespace utils +namespace autoware::predicted_path_checker { using autoware::universe_utils::Point2d; @@ -99,6 +99,6 @@ void getCurrentObjectPose( const rclcpp::Time & current_time); bool isFrontObstacle(const Pose & ego_pose, const geometry_msgs::msg::Point & obstacle_pos); -} // namespace utils +} // namespace autoware::predicted_path_checker -#endif // PREDICTED_PATH_CHECKER__UTILS_HPP_ +#endif // AUTOWARE__PREDICTED_PATH_CHECKER__UTILS_HPP_ diff --git a/control/predicted_path_checker/launch/predicted_path_checker.launch.xml b/control/autoware_predicted_path_checker/launch/predicted_path_checker.launch.xml similarity index 79% rename from control/predicted_path_checker/launch/predicted_path_checker.launch.xml rename to control/autoware_predicted_path_checker/launch/predicted_path_checker.launch.xml index 6af1372a5bb4a..b0b8b385e7697 100755 --- a/control/predicted_path_checker/launch/predicted_path_checker.launch.xml +++ b/control/autoware_predicted_path_checker/launch/predicted_path_checker.launch.xml @@ -5,11 +5,11 @@ - + - + diff --git a/control/predicted_path_checker/package.xml b/control/autoware_predicted_path_checker/package.xml similarity index 93% rename from control/predicted_path_checker/package.xml rename to control/autoware_predicted_path_checker/package.xml index a6780a4c00519..f1d98673420c1 100644 --- a/control/predicted_path_checker/package.xml +++ b/control/autoware_predicted_path_checker/package.xml @@ -1,11 +1,12 @@ - predicted_path_checker + autoware_predicted_path_checker 0.40.0 The predicted_path_checker package Berkay Karaman + Junya Sasaki Apache 2.0 Berkay Karaman diff --git a/control/predicted_path_checker/src/predicted_path_checker_node/collision_checker.cpp b/control/autoware_predicted_path_checker/src/predicted_path_checker_node/collision_checker.cpp similarity index 93% rename from control/predicted_path_checker/src/predicted_path_checker_node/collision_checker.cpp rename to control/autoware_predicted_path_checker/src/predicted_path_checker_node/collision_checker.cpp index 2841888b61bcc..d21766f36e202 100644 --- a/control/predicted_path_checker/src/predicted_path_checker_node/collision_checker.cpp +++ b/control/autoware_predicted_path_checker/src/predicted_path_checker_node/collision_checker.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "predicted_path_checker/collision_checker.hpp" +#include "autoware/predicted_path_checker/collision_checker.hpp" #include #include @@ -22,7 +22,7 @@ #include #include -namespace autoware::motion::control::predicted_path_checker +namespace autoware::predicted_path_checker { CollisionChecker::CollisionChecker( rclcpp::Node * node, std::shared_ptr debug_ptr) @@ -61,7 +61,7 @@ CollisionChecker::checkTrajectoryForCollision( // create one-step polygon for vehicle Polygon2d one_step_move_vehicle_polygon2d = - utils::createOneStepPolygon(p_front, p_back, vehicle_info_, param_.width_margin); + createOneStepPolygon(p_front, p_back, vehicle_info_, param_.width_margin); if (param_.enable_z_axis_obstacle_filtering) { debug_ptr_->pushPolyhedron( one_step_move_vehicle_polygon2d, z_min, z_max, PolygonType::Vehicle); @@ -126,7 +126,7 @@ CollisionChecker::checkObstacleHistory( std::vector> collision_points_in_history; for (const auto & obj_history : predicted_object_history_) { if (param_.enable_z_axis_obstacle_filtering) { - if (!utils::intersectsInZAxis(obj_history.object, z_min, z_max)) { + if (!intersectsInZAxis(obj_history.object, z_min, z_max)) { continue; } } @@ -169,11 +169,11 @@ CollisionChecker::checkDynamicObjects( for (size_t i = 0; i < dynamic_objects->objects.size(); ++i) { const auto & obj = dynamic_objects->objects.at(i); if (param_.enable_z_axis_obstacle_filtering) { - if (!utils::intersectsInZAxis(obj, z_min, z_max)) { + if (!intersectsInZAxis(obj, z_min, z_max)) { continue; } } - const auto object_polygon = utils::convertObjToPolygon(obj); + const auto object_polygon = convertObjToPolygon(obj); if (object_polygon.outer().empty()) { // unsupported type continue; @@ -205,7 +205,7 @@ CollisionChecker::checkDynamicObjects( } geometry_msgs::msg::Point nearest_collision_point_tmp; - double norm = utils::getNearestPointAndDistanceForPredictedObject( + double norm = getNearestPointAndDistanceForPredictedObject( collision_point_array, base_pose, &nearest_collision_point_tmp); if (norm < min_norm_collision_norm || !is_init) { min_norm_collision_norm = norm; @@ -217,7 +217,7 @@ CollisionChecker::checkDynamicObjects( } if (is_init) { const auto & obj = dynamic_objects->objects.at(nearest_collision_object_index); - const auto obstacle_polygon = utils::convertObjToPolygon(obj); + const auto obstacle_polygon = convertObjToPolygon(obj); if (param_.enable_z_axis_obstacle_filtering) { debug_ptr_->pushPolyhedron(obstacle_polygon, z_min, z_max, PolygonType::Collision); } else { @@ -229,4 +229,4 @@ CollisionChecker::checkDynamicObjects( } return boost::none; } -} // namespace autoware::motion::control::predicted_path_checker +} // namespace autoware::predicted_path_checker diff --git a/control/predicted_path_checker/src/predicted_path_checker_node/debug_marker.cpp b/control/autoware_predicted_path_checker/src/predicted_path_checker_node/debug_marker.cpp similarity index 98% rename from control/predicted_path_checker/src/predicted_path_checker_node/debug_marker.cpp rename to control/autoware_predicted_path_checker/src/predicted_path_checker_node/debug_marker.cpp index 3fae5e38e7ede..61125b88484f0 100644 --- a/control/predicted_path_checker/src/predicted_path_checker_node/debug_marker.cpp +++ b/control/autoware_predicted_path_checker/src/predicted_path_checker_node/debug_marker.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "predicted_path_checker/debug_marker.hpp" +#include "autoware/predicted_path_checker/debug_marker.hpp" #include #include @@ -38,7 +38,7 @@ using autoware::universe_utils::createMarkerOrientation; using autoware::universe_utils::createMarkerScale; using autoware::universe_utils::createPoint; -namespace autoware::motion::control::predicted_path_checker +namespace autoware::predicted_path_checker { PredictedPathCheckerDebugNode::PredictedPathCheckerDebugNode( rclcpp::Node * node, const double base_link2front) @@ -326,4 +326,4 @@ visualization_msgs::msg::MarkerArray PredictedPathCheckerDebugNode::makeVisualiz return msg; } -} // namespace autoware::motion::control::predicted_path_checker +} // namespace autoware::predicted_path_checker diff --git a/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp b/control/autoware_predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp similarity index 95% rename from control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp rename to control/autoware_predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp index f199bc731e68e..e849508f32e50 100644 --- a/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp +++ b/control/autoware_predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "predicted_path_checker/predicted_path_checker_node.hpp" +#include "autoware/predicted_path_checker/predicted_path_checker_node.hpp" #include #include @@ -26,7 +26,7 @@ #include #include -namespace autoware::motion::control::predicted_path_checker +namespace autoware::predicted_path_checker { PredictedPathCheckerNode::PredictedPathCheckerNode(const rclcpp::NodeOptions & node_options) @@ -301,7 +301,7 @@ void PredictedPathCheckerNode::onTimer() // Check if the vehicle is in the brake distance - const bool is_in_brake_distance = utils::isInBrakeDistance( + const bool is_in_brake_distance = isInBrakeDistance( predicted_trajectory_array, stop_idx, relative_velocity, relative_acceleration, node_param_.max_deceleration, node_param_.delay_time); @@ -431,7 +431,7 @@ bool PredictedPathCheckerNode::isItDiscretePoint( const auto nearest_segment = autoware::motion_utils::findNearestSegmentIndex(reference_trajectory, collision_point.pose); - const auto nearest_point = utils::calcInterpolatedPoint( + const auto nearest_point = calcInterpolatedPoint( reference_trajectory, collision_point.pose.position, *nearest_segment, false); const auto distance = autoware::universe_utils::calcDistance2d( @@ -495,7 +495,7 @@ void PredictedPathCheckerNode::extendTrajectoryPointsArray(TrajectoryPoints & tr // collision_point. const double extend_distance = vehicle_info_.max_longitudinal_offset_m + node_param_.stop_margin; const auto & goal_point = trajectory.back(); - const auto trajectory_point_extend = utils::getExtendTrajectoryPoint(extend_distance, goal_point); + const auto trajectory_point_extend = getExtendTrajectoryPoint(extend_distance, goal_point); trajectory.push_back(trajectory_point_extend); } @@ -506,14 +506,14 @@ size_t PredictedPathCheckerNode::insertStopPoint( autoware::motion_utils::findNearestSegmentIndex(trajectory, collision_point); const auto nearest_collision_point = - utils::calcInterpolatedPoint(trajectory, collision_point, nearest_collision_segment, true); + calcInterpolatedPoint(trajectory, collision_point, nearest_collision_segment, true); const size_t collision_idx = nearest_collision_segment + 1; trajectory.insert(trajectory.begin() + static_cast(collision_idx), nearest_collision_point); const auto stop_point = - utils::findStopPoint(trajectory, collision_idx, node_param_.stop_margin, vehicle_info_); + findStopPoint(trajectory, collision_idx, node_param_.stop_margin, vehicle_info_); const size_t stop_idx = stop_point.first + 1; trajectory.insert(trajectory.begin() + static_cast(stop_idx), stop_point.second); @@ -550,13 +550,12 @@ void PredictedPathCheckerNode::filterObstacles( for (auto & object : object_ptr_.get()->objects) { // Check is it in front of ego vehicle - if (!utils::isFrontObstacle( - ego_pose, object.kinematics.initial_pose_with_covariance.pose.position)) { + if (!isFrontObstacle(ego_pose, object.kinematics.initial_pose_with_covariance.pose.position)) { continue; } // Check is it near to trajectory - const double max_length = utils::calcObstacleMaxLength(object.shape); + const double max_length = calcObstacleMaxLength(object.shape); const size_t seg_idx = autoware::motion_utils::findNearestSegmentIndex( traj, object.kinematics.initial_pose_with_covariance.pose.position); const auto p_front = autoware::universe_utils::getPoint(traj.at(seg_idx)); @@ -580,14 +579,13 @@ void PredictedPathCheckerNode::filterObstacles( } PredictedObject filtered_object = object; if (use_prediction) { - utils::getCurrentObjectPose(filtered_object, object_ptr_.get()->header.stamp, this->now()); + getCurrentObjectPose(filtered_object, object_ptr_.get()->header.stamp, this->now()); } filtered_objects.objects.push_back(filtered_object); } } -} // namespace autoware::motion::control::predicted_path_checker +} // namespace autoware::predicted_path_checker #include -RCLCPP_COMPONENTS_REGISTER_NODE( - autoware::motion::control::predicted_path_checker::PredictedPathCheckerNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::predicted_path_checker::PredictedPathCheckerNode) diff --git a/control/predicted_path_checker/src/predicted_path_checker_node/utils.cpp b/control/autoware_predicted_path_checker/src/predicted_path_checker_node/utils.cpp similarity index 98% rename from control/predicted_path_checker/src/predicted_path_checker_node/utils.cpp rename to control/autoware_predicted_path_checker/src/predicted_path_checker_node/utils.cpp index 12e38fd9968ab..c3d4a8b3c7594 100644 --- a/control/predicted_path_checker/src/predicted_path_checker_node/utils.cpp +++ b/control/autoware_predicted_path_checker/src/predicted_path_checker_node/utils.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "predicted_path_checker/utils.hpp" +#include "autoware/predicted_path_checker/utils.hpp" #include #include @@ -20,7 +20,7 @@ #include -namespace utils +namespace autoware::predicted_path_checker { using autoware::motion_utils::findFirstNearestIndexWithSoftConstraints; @@ -355,15 +355,15 @@ Polygon2d convertObjToPolygon(const PredictedObject & obj) { Polygon2d object_polygon{}; if (obj.shape.type == autoware_perception_msgs::msg::Shape::CYLINDER) { - object_polygon = utils::convertCylindricalObjectToGeometryPolygon( + object_polygon = convertCylindricalObjectToGeometryPolygon( obj.kinematics.initial_pose_with_covariance.pose, obj.shape); } else if (obj.shape.type == autoware_perception_msgs::msg::Shape::BOUNDING_BOX) { const double & length_m = obj.shape.dimensions.x / 2; const double & width_m = obj.shape.dimensions.y / 2; - object_polygon = utils::convertBoundingBoxObjectToGeometryPolygon( + object_polygon = convertBoundingBoxObjectToGeometryPolygon( obj.kinematics.initial_pose_with_covariance.pose, length_m, length_m, width_m); } else if (obj.shape.type == autoware_perception_msgs::msg::Shape::POLYGON) { - object_polygon = utils::convertPolygonObjectToGeometryPolygon( + object_polygon = convertPolygonObjectToGeometryPolygon( obj.kinematics.initial_pose_with_covariance.pose, obj.shape); } else { throw std::runtime_error("Unsupported shape type"); @@ -430,4 +430,4 @@ void getCurrentObjectPose( 0.0, 0.0, autoware::universe_utils::normalizeRadian(yaw + delta_yaw)); } -} // namespace utils +} // namespace autoware::predicted_path_checker diff --git a/launch/tier4_control_launch/launch/control.launch.xml b/launch/tier4_control_launch/launch/control.launch.xml index 2b0339f1c5cad..f35f02e1d0a80 100644 --- a/launch/tier4_control_launch/launch/control.launch.xml +++ b/launch/tier4_control_launch/launch/control.launch.xml @@ -257,7 +257,7 @@ - + From f0c81707fc13ebd8beb9f0e46af13becbd239667 Mon Sep 17 00:00:00 2001 From: Junya Sasaki Date: Thu, 23 Jan 2025 18:15:59 +0900 Subject: [PATCH 305/334] feat: apply `autoware_` prefix for `scenario_simulator_v2_adapter` (#9957) * feat(autoware_scenario_simulator_v2_adapter): apply `autoware_` prefix (see below): * In this commit, I did not organize a folder structure. The folder structure will be organized in the next some commits. * The changes will follow the Autoware's guideline as below: - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder Signed-off-by: Junya Sasaki * rename(scenario_simulator_v2_adapter): move headers under `include/autoware`: * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit Signed-off-by: Junya Sasaki * fix(scenario_simulator_v2_adapter): fix include paths * To follow the previous commit Signed-off-by: Junya Sasaki * rename: `scenario_simulator_v2_adapter` => `autoware_scenario_simulator_v2_adapter` Signed-off-by: Junya Sasaki * bug(autoware_scenario_simulator_v2_adapter): revert wrongly updated copyrights Signed-off-by: Junya Sasaki * bug(autoware_scenario_simulator_v2_adapter): `autoware_` prefix is not needed here Signed-off-by: Junya Sasaki * bug(autoware_scenario_simulator_v2_adapter): wrong package name in launch side Signed-off-by: Junya Sasaki --------- Signed-off-by: Junya Sasaki --- .../CHANGELOG.rst | 0 .../CMakeLists.txt | 16 ++++++++-------- .../README.md | 0 .../scenario_simulator_v2_adapter.param.yaml | 0 .../converter_node.hpp | 12 ++++++------ .../package.xml | 3 ++- .../scenario_simulator_v2_adapter.schema.json | 0 .../src/converter_node.cpp | 13 +++++-------- .../test/test_converter_node.cpp | 6 +++--- .../launch/simulator.launch.xml | 2 +- 10 files changed, 25 insertions(+), 27 deletions(-) rename evaluator/{scenario_simulator_v2_adapter => autoware_scenario_simulator_v2_adapter}/CHANGELOG.rst (100%) rename evaluator/{scenario_simulator_v2_adapter => autoware_scenario_simulator_v2_adapter}/CMakeLists.txt (60%) rename evaluator/{scenario_simulator_v2_adapter => autoware_scenario_simulator_v2_adapter}/README.md (100%) rename evaluator/{scenario_simulator_v2_adapter => autoware_scenario_simulator_v2_adapter}/config/scenario_simulator_v2_adapter.param.yaml (100%) rename evaluator/{scenario_simulator_v2_adapter/include => autoware_scenario_simulator_v2_adapter/include/autoware}/scenario_simulator_v2_adapter/converter_node.hpp (84%) rename evaluator/{scenario_simulator_v2_adapter => autoware_scenario_simulator_v2_adapter}/package.xml (90%) rename evaluator/{scenario_simulator_v2_adapter => autoware_scenario_simulator_v2_adapter}/schema/scenario_simulator_v2_adapter.schema.json (100%) rename evaluator/{scenario_simulator_v2_adapter => autoware_scenario_simulator_v2_adapter}/src/converter_node.cpp (90%) rename evaluator/{scenario_simulator_v2_adapter => autoware_scenario_simulator_v2_adapter}/test/test_converter_node.cpp (95%) diff --git a/evaluator/scenario_simulator_v2_adapter/CHANGELOG.rst b/evaluator/autoware_scenario_simulator_v2_adapter/CHANGELOG.rst similarity index 100% rename from evaluator/scenario_simulator_v2_adapter/CHANGELOG.rst rename to evaluator/autoware_scenario_simulator_v2_adapter/CHANGELOG.rst diff --git a/evaluator/scenario_simulator_v2_adapter/CMakeLists.txt b/evaluator/autoware_scenario_simulator_v2_adapter/CMakeLists.txt similarity index 60% rename from evaluator/scenario_simulator_v2_adapter/CMakeLists.txt rename to evaluator/autoware_scenario_simulator_v2_adapter/CMakeLists.txt index 576bd9682725a..7e45858383e71 100644 --- a/evaluator/scenario_simulator_v2_adapter/CMakeLists.txt +++ b/evaluator/autoware_scenario_simulator_v2_adapter/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required(VERSION 3.16.3) # Ubuntu 20.04 default CMake version -project(scenario_simulator_v2_adapter) +project(autoware_scenario_simulator_v2_adapter) if(NOT CMAKE_CXX_STANDARD) set(CMAKE_CXX_STANDARD 14) @@ -16,24 +16,24 @@ find_package(pluginlib REQUIRED) ament_auto_find_build_dependencies() -ament_auto_add_library(${PROJECT_NAME}_node SHARED +ament_auto_add_library(${PROJECT_NAME} SHARED src/converter_node.cpp ) -rclcpp_components_register_node(${PROJECT_NAME}_node - PLUGIN "scenario_simulator_v2_adapter::MetricConverter" - EXECUTABLE ${PROJECT_NAME} +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "autoware::scenario_simulator_v2_adapter::MetricConverter" + EXECUTABLE ${PROJECT_NAME}_node ) if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() - ament_add_gtest(test_${PROJECT_NAME} + ament_add_gtest(test_scenario_simulator_v2_adapter test/test_converter_node.cpp ) - target_link_libraries(test_${PROJECT_NAME} - ${PROJECT_NAME}_node + target_link_libraries(test_scenario_simulator_v2_adapter + ${PROJECT_NAME} ) endif() diff --git a/evaluator/scenario_simulator_v2_adapter/README.md b/evaluator/autoware_scenario_simulator_v2_adapter/README.md similarity index 100% rename from evaluator/scenario_simulator_v2_adapter/README.md rename to evaluator/autoware_scenario_simulator_v2_adapter/README.md diff --git a/evaluator/scenario_simulator_v2_adapter/config/scenario_simulator_v2_adapter.param.yaml b/evaluator/autoware_scenario_simulator_v2_adapter/config/scenario_simulator_v2_adapter.param.yaml similarity index 100% rename from evaluator/scenario_simulator_v2_adapter/config/scenario_simulator_v2_adapter.param.yaml rename to evaluator/autoware_scenario_simulator_v2_adapter/config/scenario_simulator_v2_adapter.param.yaml diff --git a/evaluator/scenario_simulator_v2_adapter/include/scenario_simulator_v2_adapter/converter_node.hpp b/evaluator/autoware_scenario_simulator_v2_adapter/include/autoware/scenario_simulator_v2_adapter/converter_node.hpp similarity index 84% rename from evaluator/scenario_simulator_v2_adapter/include/scenario_simulator_v2_adapter/converter_node.hpp rename to evaluator/autoware_scenario_simulator_v2_adapter/include/autoware/scenario_simulator_v2_adapter/converter_node.hpp index 1ac4585035277..a8afc6dcd9e21 100644 --- a/evaluator/scenario_simulator_v2_adapter/include/scenario_simulator_v2_adapter/converter_node.hpp +++ b/evaluator/autoware_scenario_simulator_v2_adapter/include/autoware/scenario_simulator_v2_adapter/converter_node.hpp @@ -1,4 +1,4 @@ -// Copyright 2023 Tier IV, Inc. +// Copyright 2023 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SCENARIO_SIMULATOR_V2_ADAPTER__CONVERTER_NODE_HPP_ -#define SCENARIO_SIMULATOR_V2_ADAPTER__CONVERTER_NODE_HPP_ +#ifndef AUTOWARE__SCENARIO_SIMULATOR_V2_ADAPTER__CONVERTER_NODE_HPP_ +#define AUTOWARE__SCENARIO_SIMULATOR_V2_ADAPTER__CONVERTER_NODE_HPP_ #include @@ -27,7 +27,7 @@ #include #include -namespace scenario_simulator_v2_adapter +namespace autoware::scenario_simulator_v2_adapter { using tier4_metric_msgs::msg::Metric; using tier4_metric_msgs::msg::MetricArray; @@ -61,6 +61,6 @@ class MetricConverter : public rclcpp::Node std::vector::SharedPtr>> params_pub_; }; -} // namespace scenario_simulator_v2_adapter +} // namespace autoware::scenario_simulator_v2_adapter -#endif // SCENARIO_SIMULATOR_V2_ADAPTER__CONVERTER_NODE_HPP_ +#endif // AUTOWARE__SCENARIO_SIMULATOR_V2_ADAPTER__CONVERTER_NODE_HPP_ diff --git a/evaluator/scenario_simulator_v2_adapter/package.xml b/evaluator/autoware_scenario_simulator_v2_adapter/package.xml similarity index 90% rename from evaluator/scenario_simulator_v2_adapter/package.xml rename to evaluator/autoware_scenario_simulator_v2_adapter/package.xml index 3922bc84d78d5..7d3fe5246c110 100644 --- a/evaluator/scenario_simulator_v2_adapter/package.xml +++ b/evaluator/autoware_scenario_simulator_v2_adapter/package.xml @@ -1,13 +1,14 @@ - scenario_simulator_v2_adapter + autoware_scenario_simulator_v2_adapter 0.40.0 Node for converting autoware's messages into UserDefinedValue messages Kyoichi Sugahara Maxime CLEMENT Takamasa Horibe Takamasa Horibe + Junya Sasaki Apache License 2.0 ament_cmake_auto diff --git a/evaluator/scenario_simulator_v2_adapter/schema/scenario_simulator_v2_adapter.schema.json b/evaluator/autoware_scenario_simulator_v2_adapter/schema/scenario_simulator_v2_adapter.schema.json similarity index 100% rename from evaluator/scenario_simulator_v2_adapter/schema/scenario_simulator_v2_adapter.schema.json rename to evaluator/autoware_scenario_simulator_v2_adapter/schema/scenario_simulator_v2_adapter.schema.json diff --git a/evaluator/scenario_simulator_v2_adapter/src/converter_node.cpp b/evaluator/autoware_scenario_simulator_v2_adapter/src/converter_node.cpp similarity index 90% rename from evaluator/scenario_simulator_v2_adapter/src/converter_node.cpp rename to evaluator/autoware_scenario_simulator_v2_adapter/src/converter_node.cpp index 4c0464b8b2d41..8ccfc2e3854d3 100644 --- a/evaluator/scenario_simulator_v2_adapter/src/converter_node.cpp +++ b/evaluator/autoware_scenario_simulator_v2_adapter/src/converter_node.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 Tier IV, Inc. +// Copyright 2023 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "scenario_simulator_v2_adapter/converter_node.hpp" +#include "autoware/scenario_simulator_v2_adapter/converter_node.hpp" #include #include #include -namespace +namespace autoware::scenario_simulator_v2_adapter { std::string removeInvalidTopicString(const std::string & input_string) { @@ -31,10 +31,7 @@ std::string removeInvalidTopicString(const std::string & input_string) } return result; } -} // namespace -namespace scenario_simulator_v2_adapter -{ MetricConverter::MetricConverter(const rclcpp::NodeOptions & node_options) : Node("scenario_simulator_v2_adapter", node_options) { @@ -81,7 +78,7 @@ rclcpp::Publisher::SharedPtr MetricConverter::getPublisher( } return pubs.at(topic_name); } -} // namespace scenario_simulator_v2_adapter +} // namespace autoware::scenario_simulator_v2_adapter #include "rclcpp_components/register_node_macro.hpp" -RCLCPP_COMPONENTS_REGISTER_NODE(scenario_simulator_v2_adapter::MetricConverter) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::scenario_simulator_v2_adapter::MetricConverter) diff --git a/evaluator/scenario_simulator_v2_adapter/test/test_converter_node.cpp b/evaluator/autoware_scenario_simulator_v2_adapter/test/test_converter_node.cpp similarity index 95% rename from evaluator/scenario_simulator_v2_adapter/test/test_converter_node.cpp rename to evaluator/autoware_scenario_simulator_v2_adapter/test/test_converter_node.cpp index de2a12ac2caaa..d7ecfc50a1bcf 100644 --- a/evaluator/scenario_simulator_v2_adapter/test/test_converter_node.cpp +++ b/evaluator/autoware_scenario_simulator_v2_adapter/test/test_converter_node.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 Tier IV, Inc. +// Copyright 2023 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "scenario_simulator_v2_adapter/converter_node.hpp" +#include "autoware/scenario_simulator_v2_adapter/converter_node.hpp" #include @@ -28,7 +28,7 @@ #include #include -using ConverterNode = scenario_simulator_v2_adapter::MetricConverter; +using ConverterNode = autoware::scenario_simulator_v2_adapter::MetricConverter; using tier4_metric_msgs::msg::Metric; using tier4_metric_msgs::msg::MetricArray; using tier4_simulation_msgs::msg::UserDefinedValue; diff --git a/launch/tier4_simulator_launch/launch/simulator.launch.xml b/launch/tier4_simulator_launch/launch/simulator.launch.xml index 1255061a474db..a879340bc4d0c 100644 --- a/launch/tier4_simulator_launch/launch/simulator.launch.xml +++ b/launch/tier4_simulator_launch/launch/simulator.launch.xml @@ -208,7 +208,7 @@ - + From dbfee16a046c1c7a98502678a0be8fee04aea905 Mon Sep 17 00:00:00 2001 From: Junya Sasaki Date: Thu, 23 Jan 2025 18:34:19 +0900 Subject: [PATCH 306/334] feat: apply `autoware_` prefix for `mrm_handler` (#9974) * feat(mrm_handler): apply `autoware_` prefix (see below): Note: * In this commit, I did not organize a folder structure. The folder structure will be organized in the next some commits. * The changes will follow the Autoware's guideline as below: - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder Signed-off-by: Junya Sasaki * rename(mrm_handler): move a header under `include/autoware`: * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit Signed-off-by: Junya Sasaki * fix(mrm_handler): fix include header path * To follow the previous commit Signed-off-by: Junya Sasaki * rename: `mrm_handler` => `autoware_mrm_handler` Signed-off-by: Junya Sasaki * bug(tier4_system_launch): fix a missing `autoware_` for `mrm_handler` Signed-off-by: Junya Sasaki * bug(mrm_handler): revert wrongly updated copyrights Signed-off-by: Junya Sasaki * update(mrm_handler): `README.md` Signed-off-by: Junya Sasaki * bug(autoware_mrm_handler): fix a critical bug that contaminates topic name Signed-off-by: Junya Sasaki --------- Signed-off-by: Junya Sasaki --- launch/tier4_system_launch/launch/system.launch.xml | 2 +- .../CHANGELOG.rst | 0 .../CMakeLists.txt | 4 ++-- .../{mrm_handler => autoware_mrm_handler}/README.md | 2 +- .../config/mrm_handler.param.yaml | 0 .../image/mrm-state.svg | 0 .../autoware}/mrm_handler/mrm_handler_core.hpp | 11 ++++++++--- .../launch/mrm_handler.launch.xml | 4 ++-- .../{mrm_handler => autoware_mrm_handler}/package.xml | 3 ++- .../schema/mrm_handler.schema.json | 0 .../src/mrm_handler/mrm_handler_core.cpp | 9 +++++++-- 11 files changed, 23 insertions(+), 12 deletions(-) rename system/{mrm_handler => autoware_mrm_handler}/CHANGELOG.rst (100%) rename system/{mrm_handler => autoware_mrm_handler}/CMakeLists.txt (82%) rename system/{mrm_handler => autoware_mrm_handler}/README.md (97%) rename system/{mrm_handler => autoware_mrm_handler}/config/mrm_handler.param.yaml (100%) rename system/{mrm_handler => autoware_mrm_handler}/image/mrm-state.svg (100%) rename system/{mrm_handler/include => autoware_mrm_handler/include/autoware}/mrm_handler/mrm_handler_core.hpp (96%) rename system/{mrm_handler => autoware_mrm_handler}/launch/mrm_handler.launch.xml (92%) rename system/{mrm_handler => autoware_mrm_handler}/package.xml (90%) rename system/{mrm_handler => autoware_mrm_handler}/schema/mrm_handler.schema.json (100%) rename system/{mrm_handler => autoware_mrm_handler}/src/mrm_handler/mrm_handler_core.cpp (99%) diff --git a/launch/tier4_system_launch/launch/system.launch.xml b/launch/tier4_system_launch/launch/system.launch.xml index c37db6bca4ffe..56c7e8ab810ce 100644 --- a/launch/tier4_system_launch/launch/system.launch.xml +++ b/launch/tier4_system_launch/launch/system.launch.xml @@ -105,7 +105,7 @@ - + diff --git a/system/mrm_handler/CHANGELOG.rst b/system/autoware_mrm_handler/CHANGELOG.rst similarity index 100% rename from system/mrm_handler/CHANGELOG.rst rename to system/autoware_mrm_handler/CHANGELOG.rst diff --git a/system/mrm_handler/CMakeLists.txt b/system/autoware_mrm_handler/CMakeLists.txt similarity index 82% rename from system/mrm_handler/CMakeLists.txt rename to system/autoware_mrm_handler/CMakeLists.txt index 93e03e7f20ead..ba960c05924d5 100644 --- a/system/mrm_handler/CMakeLists.txt +++ b/system/autoware_mrm_handler/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(mrm_handler) +project(autoware_mrm_handler) find_package(autoware_cmake REQUIRED) autoware_package() @@ -9,7 +9,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED ) rclcpp_components_register_node(${PROJECT_NAME} - PLUGIN "MrmHandler" + PLUGIN "autoware::mrm_handler::MrmHandler" EXECUTABLE ${PROJECT_NAME}_node EXECUTOR MultiThreadedExecutor ) diff --git a/system/mrm_handler/README.md b/system/autoware_mrm_handler/README.md similarity index 97% rename from system/mrm_handler/README.md rename to system/autoware_mrm_handler/README.md index 8ccb95e6ca8d3..ea2a63e51cd4b 100644 --- a/system/mrm_handler/README.md +++ b/system/autoware_mrm_handler/README.md @@ -37,7 +37,7 @@ MRM Handler is a node to select a proper MRM from a system failure state contain ## Parameters -{{ json_to_markdown("system/mrm_handler/schema/mrm_handler.schema.json") }} +{{ json_to_markdown("system/autoware_mrm_handler/schema/mrm_handler.schema.json") }} ## Assumptions / Known limits diff --git a/system/mrm_handler/config/mrm_handler.param.yaml b/system/autoware_mrm_handler/config/mrm_handler.param.yaml similarity index 100% rename from system/mrm_handler/config/mrm_handler.param.yaml rename to system/autoware_mrm_handler/config/mrm_handler.param.yaml diff --git a/system/mrm_handler/image/mrm-state.svg b/system/autoware_mrm_handler/image/mrm-state.svg similarity index 100% rename from system/mrm_handler/image/mrm-state.svg rename to system/autoware_mrm_handler/image/mrm-state.svg diff --git a/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp b/system/autoware_mrm_handler/include/autoware/mrm_handler/mrm_handler_core.hpp similarity index 96% rename from system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp rename to system/autoware_mrm_handler/include/autoware/mrm_handler/mrm_handler_core.hpp index b292ab1d874d3..8d74db4e5c843 100644 --- a/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp +++ b/system/autoware_mrm_handler/include/autoware/mrm_handler/mrm_handler_core.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MRM_HANDLER__MRM_HANDLER_CORE_HPP_ -#define MRM_HANDLER__MRM_HANDLER_CORE_HPP_ +#ifndef AUTOWARE__MRM_HANDLER__MRM_HANDLER_CORE_HPP_ +#define AUTOWARE__MRM_HANDLER__MRM_HANDLER_CORE_HPP_ // Core #include @@ -41,6 +41,9 @@ #include #include +namespace autoware::mrm_handler +{ + struct HazardLampPolicy { bool emergency; @@ -162,4 +165,6 @@ class MrmHandler : public rclcpp::Node bool isArrivedAtGoal(); }; -#endif // MRM_HANDLER__MRM_HANDLER_CORE_HPP_ +} // namespace autoware::mrm_handler + +#endif // AUTOWARE__MRM_HANDLER__MRM_HANDLER_CORE_HPP_ diff --git a/system/mrm_handler/launch/mrm_handler.launch.xml b/system/autoware_mrm_handler/launch/mrm_handler.launch.xml similarity index 92% rename from system/mrm_handler/launch/mrm_handler.launch.xml rename to system/autoware_mrm_handler/launch/mrm_handler.launch.xml index 51a22cf92bebc..d3ed4fb499729 100644 --- a/system/mrm_handler/launch/mrm_handler.launch.xml +++ b/system/autoware_mrm_handler/launch/mrm_handler.launch.xml @@ -17,10 +17,10 @@ - + - + diff --git a/system/mrm_handler/package.xml b/system/autoware_mrm_handler/package.xml similarity index 90% rename from system/mrm_handler/package.xml rename to system/autoware_mrm_handler/package.xml index d330680e87049..cf70663b81122 100644 --- a/system/mrm_handler/package.xml +++ b/system/autoware_mrm_handler/package.xml @@ -1,12 +1,13 @@ - mrm_handler + autoware_mrm_handler 0.40.0 The mrm_handler ROS 2 package Makoto Kurihara Ryuta Kambe Tetsuhiro Kawaguchi + Junya Sasaki Apache License 2.0 ament_cmake_auto diff --git a/system/mrm_handler/schema/mrm_handler.schema.json b/system/autoware_mrm_handler/schema/mrm_handler.schema.json similarity index 100% rename from system/mrm_handler/schema/mrm_handler.schema.json rename to system/autoware_mrm_handler/schema/mrm_handler.schema.json diff --git a/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp b/system/autoware_mrm_handler/src/mrm_handler/mrm_handler_core.cpp similarity index 99% rename from system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp rename to system/autoware_mrm_handler/src/mrm_handler/mrm_handler_core.cpp index b5f4bbaeefc46..e9429300de573 100644 --- a/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp +++ b/system/autoware_mrm_handler/src/mrm_handler/mrm_handler_core.cpp @@ -11,13 +11,16 @@ // CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language // governing permissions and limitations under the License. -#include "mrm_handler/mrm_handler_core.hpp" +#include "autoware/mrm_handler/mrm_handler_core.hpp" #include #include #include #include +namespace autoware::mrm_handler +{ + MrmHandler::MrmHandler(const rclcpp::NodeOptions & options) : Node("mrm_handler", options) { // Parameter @@ -583,5 +586,7 @@ bool MrmHandler::isArrivedAtGoal() return state->mode == OperationModeState::STOP; } +} // namespace autoware::mrm_handler + #include -RCLCPP_COMPONENTS_REGISTER_NODE(MrmHandler) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::mrm_handler::MrmHandler) From c53af8a8c1bf2e3180ca6e17727204ec73016338 Mon Sep 17 00:00:00 2001 From: Junya Sasaki Date: Thu, 23 Jan 2025 18:36:31 +0900 Subject: [PATCH 307/334] feat: apply `autoware_` prefix for `mrm_emergency_stop_operator` (#9973) * feat(mrm_emergency_stop_operator): apply `autoware_` prefix (see below): Note: * In this commit, I did not organize a folder structure. The folder structure will be organized in the next some commits. * The changes will follow the Autoware's guideline as below: - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder Signed-off-by: Junya Sasaki * rename(mrm_emergency_stop_operator): move a header under `include/autoware`: * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit Signed-off-by: Junya Sasaki * fix(mrm_emergency_stop_operator): fix include header path * To follow the previous commit Signed-off-by: Junya Sasaki * rename: `mrm_emergency_stop_operator` => `autoware_mrm_emergency_stop_operator` Signed-off-by: Junya Sasaki * bug(autoware_mrm_emergency_stop_operator): revert wrongly updated copyrights Signed-off-by: Junya Sasaki * bug(tier4_system_launch): fix a missing `autoware_` for `mrm_emergency_stop_operator` Signed-off-by: Junya Sasaki * bug(autoware_mrm_emergency_stop_operator): fix critical bugs that contaminate topic names Signed-off-by: Junya Sasaki --------- Signed-off-by: Junya Sasaki --- .../launch/system.launch.xml | 2 +- .../CHANGELOG.rst | 0 .../CMakeLists.txt | 19 +++++++++++++++++++ .../README.md | 0 .../mrm_emergency_stop_operator.param.yaml | 0 .../mrm_emergency_stop_operator_core.hpp | 10 +++++----- .../mrm_emergency_stop_operator.launch.py | 6 +++--- .../package.xml | 3 ++- .../mrm_emergency_stop_operator_core.cpp | 8 ++++---- .../CMakeLists.txt | 18 ------------------ 10 files changed, 34 insertions(+), 32 deletions(-) rename system/{mrm_emergency_stop_operator => autoware_mrm_emergency_stop_operator}/CHANGELOG.rst (100%) create mode 100644 system/autoware_mrm_emergency_stop_operator/CMakeLists.txt rename system/{mrm_emergency_stop_operator => autoware_mrm_emergency_stop_operator}/README.md (100%) rename system/{mrm_emergency_stop_operator => autoware_mrm_emergency_stop_operator}/config/mrm_emergency_stop_operator.param.yaml (100%) rename system/{mrm_emergency_stop_operator/include => autoware_mrm_emergency_stop_operator/include/autoware}/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.hpp (86%) rename system/{mrm_emergency_stop_operator => autoware_mrm_emergency_stop_operator}/launch/mrm_emergency_stop_operator.launch.py (91%) rename system/{mrm_emergency_stop_operator => autoware_mrm_emergency_stop_operator}/package.xml (89%) rename system/{mrm_emergency_stop_operator => autoware_mrm_emergency_stop_operator}/src/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.cpp (94%) delete mode 100644 system/mrm_emergency_stop_operator/CMakeLists.txt diff --git a/launch/tier4_system_launch/launch/system.launch.xml b/launch/tier4_system_launch/launch/system.launch.xml index 56c7e8ab810ce..b61007dcfa209 100644 --- a/launch/tier4_system_launch/launch/system.launch.xml +++ b/launch/tier4_system_launch/launch/system.launch.xml @@ -85,7 +85,7 @@ - + diff --git a/system/mrm_emergency_stop_operator/CHANGELOG.rst b/system/autoware_mrm_emergency_stop_operator/CHANGELOG.rst similarity index 100% rename from system/mrm_emergency_stop_operator/CHANGELOG.rst rename to system/autoware_mrm_emergency_stop_operator/CHANGELOG.rst diff --git a/system/autoware_mrm_emergency_stop_operator/CMakeLists.txt b/system/autoware_mrm_emergency_stop_operator/CMakeLists.txt new file mode 100644 index 0000000000000..a4403aaf11ed1 --- /dev/null +++ b/system/autoware_mrm_emergency_stop_operator/CMakeLists.txt @@ -0,0 +1,19 @@ +cmake_minimum_required(VERSION 3.14) +project(autoware_mrm_emergency_stop_operator) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_library(${PROJECT_NAME}_component SHARED + src/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.cpp +) + +rclcpp_components_register_node(${PROJECT_NAME}_component + PLUGIN "autoware::mrm_emergency_stop_operator::MrmEmergencyStopOperator" + EXECUTABLE ${PROJECT_NAME}_node +) + +ament_auto_package(INSTALL_TO_SHARE + launch + config +) diff --git a/system/mrm_emergency_stop_operator/README.md b/system/autoware_mrm_emergency_stop_operator/README.md similarity index 100% rename from system/mrm_emergency_stop_operator/README.md rename to system/autoware_mrm_emergency_stop_operator/README.md diff --git a/system/mrm_emergency_stop_operator/config/mrm_emergency_stop_operator.param.yaml b/system/autoware_mrm_emergency_stop_operator/config/mrm_emergency_stop_operator.param.yaml similarity index 100% rename from system/mrm_emergency_stop_operator/config/mrm_emergency_stop_operator.param.yaml rename to system/autoware_mrm_emergency_stop_operator/config/mrm_emergency_stop_operator.param.yaml diff --git a/system/mrm_emergency_stop_operator/include/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.hpp b/system/autoware_mrm_emergency_stop_operator/include/autoware/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.hpp similarity index 86% rename from system/mrm_emergency_stop_operator/include/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.hpp rename to system/autoware_mrm_emergency_stop_operator/include/autoware/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.hpp index d7995a51ac8fb..93df3be01cae8 100644 --- a/system/mrm_emergency_stop_operator/include/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.hpp +++ b/system/autoware_mrm_emergency_stop_operator/include/autoware/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MRM_EMERGENCY_STOP_OPERATOR__MRM_EMERGENCY_STOP_OPERATOR_CORE_HPP_ -#define MRM_EMERGENCY_STOP_OPERATOR__MRM_EMERGENCY_STOP_OPERATOR_CORE_HPP_ +#ifndef AUTOWARE__MRM_EMERGENCY_STOP_OPERATOR__MRM_EMERGENCY_STOP_OPERATOR_CORE_HPP_ +#define AUTOWARE__MRM_EMERGENCY_STOP_OPERATOR__MRM_EMERGENCY_STOP_OPERATOR_CORE_HPP_ // Core #include @@ -28,7 +28,7 @@ #include #include -namespace mrm_emergency_stop_operator +namespace autoware::mrm_emergency_stop_operator { using autoware_control_msgs::msg::Control; using tier4_system_msgs::msg::MrmBehaviorStatus; @@ -86,6 +86,6 @@ class MrmEmergencyStopOperator : public rclcpp::Node Control calcTargetAcceleration(const Control & prev_control_cmd) const; }; -} // namespace mrm_emergency_stop_operator +} // namespace autoware::mrm_emergency_stop_operator -#endif // MRM_EMERGENCY_STOP_OPERATOR__MRM_EMERGENCY_STOP_OPERATOR_CORE_HPP_ +#endif // AUTOWARE__MRM_EMERGENCY_STOP_OPERATOR__MRM_EMERGENCY_STOP_OPERATOR_CORE_HPP_ diff --git a/system/mrm_emergency_stop_operator/launch/mrm_emergency_stop_operator.launch.py b/system/autoware_mrm_emergency_stop_operator/launch/mrm_emergency_stop_operator.launch.py similarity index 91% rename from system/mrm_emergency_stop_operator/launch/mrm_emergency_stop_operator.launch.py rename to system/autoware_mrm_emergency_stop_operator/launch/mrm_emergency_stop_operator.launch.py index 769c121c18ac9..c00494a0f1b88 100644 --- a/system/mrm_emergency_stop_operator/launch/mrm_emergency_stop_operator.launch.py +++ b/system/autoware_mrm_emergency_stop_operator/launch/mrm_emergency_stop_operator.launch.py @@ -28,8 +28,8 @@ def launch_setup(context, *args, **kwargs): params = yaml.safe_load(f)["/**"]["ros__parameters"] component = ComposableNode( - package="mrm_emergency_stop_operator", - plugin="mrm_emergency_stop_operator::MrmEmergencyStopOperator", + package="autoware_mrm_emergency_stop_operator", + plugin="autoware::mrm_emergency_stop_operator::MrmEmergencyStopOperator", name="mrm_emergency_stop_operator", parameters=[ params, @@ -61,7 +61,7 @@ def generate_launch_description(): DeclareLaunchArgument( "config_file", default_value=[ - FindPackageShare("mrm_emergency_stop_operator"), + FindPackageShare("autoware_mrm_emergency_stop_operator"), "/config/mrm_emergency_stop_operator.param.yaml", ], description="path to the parameter file of mrm_emergency_stop_operator", diff --git a/system/mrm_emergency_stop_operator/package.xml b/system/autoware_mrm_emergency_stop_operator/package.xml similarity index 89% rename from system/mrm_emergency_stop_operator/package.xml rename to system/autoware_mrm_emergency_stop_operator/package.xml index 7614373672f31..fbacf7f0ae063 100644 --- a/system/mrm_emergency_stop_operator/package.xml +++ b/system/autoware_mrm_emergency_stop_operator/package.xml @@ -1,11 +1,12 @@ - mrm_emergency_stop_operator + autoware_mrm_emergency_stop_operator 0.40.0 The MRM emergency stop operator package Makoto Kurihara Tomohito Ando + Junya Sasaki Apache License 2.0 ament_cmake_auto diff --git a/system/mrm_emergency_stop_operator/src/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.cpp b/system/autoware_mrm_emergency_stop_operator/src/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.cpp similarity index 94% rename from system/mrm_emergency_stop_operator/src/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.cpp rename to system/autoware_mrm_emergency_stop_operator/src/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.cpp index 9c941888a3545..7db4ddaef9a9c 100644 --- a/system/mrm_emergency_stop_operator/src/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.cpp +++ b/system/autoware_mrm_emergency_stop_operator/src/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.hpp" +#include "autoware/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.hpp" #include #include -namespace mrm_emergency_stop_operator +namespace autoware::mrm_emergency_stop_operator { MrmEmergencyStopOperator::MrmEmergencyStopOperator(const rclcpp::NodeOptions & node_options) @@ -150,7 +150,7 @@ Control MrmEmergencyStopOperator::calcTargetAcceleration(const Control & prev_co return control_cmd; } -} // namespace mrm_emergency_stop_operator +} // namespace autoware::mrm_emergency_stop_operator #include -RCLCPP_COMPONENTS_REGISTER_NODE(mrm_emergency_stop_operator::MrmEmergencyStopOperator) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::mrm_emergency_stop_operator::MrmEmergencyStopOperator) diff --git a/system/mrm_emergency_stop_operator/CMakeLists.txt b/system/mrm_emergency_stop_operator/CMakeLists.txt deleted file mode 100644 index 77d300f5c370b..0000000000000 --- a/system/mrm_emergency_stop_operator/CMakeLists.txt +++ /dev/null @@ -1,18 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(mrm_emergency_stop_operator) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -ament_auto_add_library(mrm_emergency_stop_operator_component SHARED - src/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.cpp -) - -rclcpp_components_register_node(mrm_emergency_stop_operator_component - PLUGIN "mrm_emergency_stop_operator::MrmEmergencyStopOperator" - EXECUTABLE mrm_emergency_stop_operator) - -ament_auto_package(INSTALL_TO_SHARE - launch - config -) From 972f445064b06c2e3f0ca934eddbee537d81e18e Mon Sep 17 00:00:00 2001 From: Junya Sasaki Date: Thu, 23 Jan 2025 18:36:46 +0900 Subject: [PATCH 308/334] feat: apply `autoware_` prefix for `mrm_comfortable_stop_operator` (#10011) * feat(mrm_comfortable_stop_operator): apply `autoware_` prefix (see below): Note: * In this commit, I did not organize a folder structure. The folder structure will be organized in the next some commits. * The changes will follow the Autoware's guideline as below: - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder Signed-off-by: Junya Sasaki * rename(mrm_comfortable_stop_operator): move a header under `include/autoware` * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit Signed-off-by: Junya Sasaki * fix(mrm_comfortable_stop_operator): fix include header path * To follow the previous commit Signed-off-by: Junya Sasaki * rename: `mrm_comfortable_stop_operator` => `autoware_mrm_comfortable_stop_operator` Signed-off-by: Junya Sasaki * update: `CODEOWNERS` Signed-off-by: Junya Sasaki --------- Signed-off-by: Junya Sasaki --- .github/CODEOWNERS | 2 +- .../launch/system.launch.xml | 2 +- .../CHANGELOG.rst | 0 .../CMakeLists.txt | 19 +++++++++++++++++++ .../README.md | 0 .../mrm_comfortable_stop_operator.param.yaml | 0 .../mrm_comfortable_stop_operator_core.hpp | 10 +++++----- .../mrm_comfortable_stop_operator.launch.py | 6 +++--- .../package.xml | 3 ++- .../mrm_comfortable_stop_operator_core.cpp | 8 ++++---- .../CMakeLists.txt | 18 ------------------ 11 files changed, 35 insertions(+), 33 deletions(-) rename system/{mrm_comfortable_stop_operator => autoware_mrm_comfortable_stop_operator}/CHANGELOG.rst (100%) create mode 100644 system/autoware_mrm_comfortable_stop_operator/CMakeLists.txt rename system/{mrm_comfortable_stop_operator => autoware_mrm_comfortable_stop_operator}/README.md (100%) rename system/{mrm_comfortable_stop_operator => autoware_mrm_comfortable_stop_operator}/config/mrm_comfortable_stop_operator.param.yaml (100%) rename system/{mrm_comfortable_stop_operator/include => autoware_mrm_comfortable_stop_operator/include/autoware}/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.hpp (86%) rename system/{mrm_comfortable_stop_operator => autoware_mrm_comfortable_stop_operator}/launch/mrm_comfortable_stop_operator.launch.py (91%) rename system/{mrm_comfortable_stop_operator => autoware_mrm_comfortable_stop_operator}/package.xml (89%) rename system/{mrm_comfortable_stop_operator => autoware_mrm_comfortable_stop_operator}/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp (94%) delete mode 100644 system/mrm_comfortable_stop_operator/CMakeLists.txt diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 7e76a883c36e9..fafe8432a51ba 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -221,7 +221,7 @@ system/autoware_dummy_diag_publisher/** fumihito.ito@tier4.jp tetsuhiro.kawaguch system/autoware_dummy_infrastructure/** ryohsuke.mitsudome@tier4.jp system/autoware_duplicated_node_checker/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp uken.ryu@tier4.jp junya.sasaki@tier4.jp system/hazard_status_converter/** isamu.takagi@tier4.jp -system/mrm_comfortable_stop_operator/** makoto.kurihara@tier4.jp tomohito.ando@tier4.jp +system/autoware_mrm_comfortable_stop_operator/** makoto.kurihara@tier4.jp tomohito.ando@tier4.jp junya.sasaki@tier4.jp system/mrm_emergency_stop_operator/** makoto.kurihara@tier4.jp tomohito.ando@tier4.jp system/mrm_handler/** makoto.kurihara@tier4.jp ryuta.kambe@tier4.jp tetsuhiro.kawaguchi@tier4.jp system/system_diagnostic_monitor/** isamu.takagi@tier4.jp diff --git a/launch/tier4_system_launch/launch/system.launch.xml b/launch/tier4_system_launch/launch/system.launch.xml index b61007dcfa209..7b7d192dd1879 100644 --- a/launch/tier4_system_launch/launch/system.launch.xml +++ b/launch/tier4_system_launch/launch/system.launch.xml @@ -80,7 +80,7 @@ - + diff --git a/system/mrm_comfortable_stop_operator/CHANGELOG.rst b/system/autoware_mrm_comfortable_stop_operator/CHANGELOG.rst similarity index 100% rename from system/mrm_comfortable_stop_operator/CHANGELOG.rst rename to system/autoware_mrm_comfortable_stop_operator/CHANGELOG.rst diff --git a/system/autoware_mrm_comfortable_stop_operator/CMakeLists.txt b/system/autoware_mrm_comfortable_stop_operator/CMakeLists.txt new file mode 100644 index 0000000000000..3ee028cd31608 --- /dev/null +++ b/system/autoware_mrm_comfortable_stop_operator/CMakeLists.txt @@ -0,0 +1,19 @@ +cmake_minimum_required(VERSION 3.14) +project(autoware_mrm_comfortable_stop_operator) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_library(${PROJECT_NAME}_component SHARED + src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp +) + +rclcpp_components_register_node(${PROJECT_NAME}_component + PLUGIN "autoware::mrm_comfortable_stop_operator::MrmComfortableStopOperator" + EXECUTABLE ${PROJECT_NAME}_node +) + +ament_auto_package(INSTALL_TO_SHARE + launch + config +) diff --git a/system/mrm_comfortable_stop_operator/README.md b/system/autoware_mrm_comfortable_stop_operator/README.md similarity index 100% rename from system/mrm_comfortable_stop_operator/README.md rename to system/autoware_mrm_comfortable_stop_operator/README.md diff --git a/system/mrm_comfortable_stop_operator/config/mrm_comfortable_stop_operator.param.yaml b/system/autoware_mrm_comfortable_stop_operator/config/mrm_comfortable_stop_operator.param.yaml similarity index 100% rename from system/mrm_comfortable_stop_operator/config/mrm_comfortable_stop_operator.param.yaml rename to system/autoware_mrm_comfortable_stop_operator/config/mrm_comfortable_stop_operator.param.yaml diff --git a/system/mrm_comfortable_stop_operator/include/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.hpp b/system/autoware_mrm_comfortable_stop_operator/include/autoware/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.hpp similarity index 86% rename from system/mrm_comfortable_stop_operator/include/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.hpp rename to system/autoware_mrm_comfortable_stop_operator/include/autoware/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.hpp index eb84191f481f9..0dbaef1f1df21 100644 --- a/system/mrm_comfortable_stop_operator/include/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.hpp +++ b/system/autoware_mrm_comfortable_stop_operator/include/autoware/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MRM_COMFORTABLE_STOP_OPERATOR__MRM_COMFORTABLE_STOP_OPERATOR_CORE_HPP_ -#define MRM_COMFORTABLE_STOP_OPERATOR__MRM_COMFORTABLE_STOP_OPERATOR_CORE_HPP_ +#ifndef AUTOWARE__MRM_COMFORTABLE_STOP_OPERATOR__MRM_COMFORTABLE_STOP_OPERATOR_CORE_HPP_ +#define AUTOWARE__MRM_COMFORTABLE_STOP_OPERATOR__MRM_COMFORTABLE_STOP_OPERATOR_CORE_HPP_ // Core #include @@ -29,7 +29,7 @@ // ROS 2 core #include -namespace mrm_comfortable_stop_operator +namespace autoware::mrm_comfortable_stop_operator { struct Parameters @@ -81,6 +81,6 @@ class MrmComfortableStopOperator : public rclcpp::Node OnSetParametersCallbackHandle::SharedPtr set_param_res_; }; -} // namespace mrm_comfortable_stop_operator +} // namespace autoware::mrm_comfortable_stop_operator -#endif // MRM_COMFORTABLE_STOP_OPERATOR__MRM_COMFORTABLE_STOP_OPERATOR_CORE_HPP_ +#endif // AUTOWARE__MRM_COMFORTABLE_STOP_OPERATOR__MRM_COMFORTABLE_STOP_OPERATOR_CORE_HPP_ diff --git a/system/mrm_comfortable_stop_operator/launch/mrm_comfortable_stop_operator.launch.py b/system/autoware_mrm_comfortable_stop_operator/launch/mrm_comfortable_stop_operator.launch.py similarity index 91% rename from system/mrm_comfortable_stop_operator/launch/mrm_comfortable_stop_operator.launch.py rename to system/autoware_mrm_comfortable_stop_operator/launch/mrm_comfortable_stop_operator.launch.py index 9181af398e3d6..50dabf74206af 100644 --- a/system/mrm_comfortable_stop_operator/launch/mrm_comfortable_stop_operator.launch.py +++ b/system/autoware_mrm_comfortable_stop_operator/launch/mrm_comfortable_stop_operator.launch.py @@ -28,8 +28,8 @@ def launch_setup(context, *args, **kwargs): params = yaml.safe_load(f)["/**"]["ros__parameters"] component = ComposableNode( - package="mrm_comfortable_stop_operator", - plugin="mrm_comfortable_stop_operator::MrmComfortableStopOperator", + package="autoware_mrm_comfortable_stop_operator", + plugin="autoware::mrm_comfortable_stop_operator::MrmComfortableStopOperator", name="mrm_comfortable_stop_operator", parameters=[ params, @@ -61,7 +61,7 @@ def generate_launch_description(): DeclareLaunchArgument( "config_file", default_value=[ - FindPackageShare("mrm_comfortable_stop_operator"), + FindPackageShare("autoware_mrm_comfortable_stop_operator"), "/config/mrm_comfortable_stop_operator.param.yaml", ], description="path to the parameter file of mrm_comfortable_stop_operator", diff --git a/system/mrm_comfortable_stop_operator/package.xml b/system/autoware_mrm_comfortable_stop_operator/package.xml similarity index 89% rename from system/mrm_comfortable_stop_operator/package.xml rename to system/autoware_mrm_comfortable_stop_operator/package.xml index 58ff309d825f1..8437a4c926b2d 100644 --- a/system/mrm_comfortable_stop_operator/package.xml +++ b/system/autoware_mrm_comfortable_stop_operator/package.xml @@ -1,11 +1,12 @@ - mrm_comfortable_stop_operator + autoware_mrm_comfortable_stop_operator 0.40.0 The MRM comfortable stop operator package Makoto Kurihara Tomohito Ando + Junya Sasaki Apache License 2.0 ament_cmake_auto diff --git a/system/mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp b/system/autoware_mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp similarity index 94% rename from system/mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp rename to system/autoware_mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp index fc703ab16e259..397367e568a25 100644 --- a/system/mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp +++ b/system/autoware_mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.hpp" +#include "autoware/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.hpp" #include #include -namespace mrm_comfortable_stop_operator +namespace autoware::mrm_comfortable_stop_operator { MrmComfortableStopOperator::MrmComfortableStopOperator(const rclcpp::NodeOptions & node_options) @@ -123,7 +123,7 @@ void MrmComfortableStopOperator::onTimer() const publishStatus(); } -} // namespace mrm_comfortable_stop_operator +} // namespace autoware::mrm_comfortable_stop_operator #include -RCLCPP_COMPONENTS_REGISTER_NODE(mrm_comfortable_stop_operator::MrmComfortableStopOperator) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::mrm_comfortable_stop_operator::MrmComfortableStopOperator) diff --git a/system/mrm_comfortable_stop_operator/CMakeLists.txt b/system/mrm_comfortable_stop_operator/CMakeLists.txt deleted file mode 100644 index 19bc4f6d66d5f..0000000000000 --- a/system/mrm_comfortable_stop_operator/CMakeLists.txt +++ /dev/null @@ -1,18 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(mrm_comfortable_stop_operator) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -ament_auto_add_library(mrm_comfortable_stop_operator_component SHARED - src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp -) - -rclcpp_components_register_node(mrm_comfortable_stop_operator_component - PLUGIN "mrm_comfortable_stop_operator::MrmComfortableStopOperator" - EXECUTABLE mrm_comfortable_stop_operator) - -ament_auto_package(INSTALL_TO_SHARE - launch - config -) From 8b0b9a7223278e72607f2da2b9f76ceaadc5f30a Mon Sep 17 00:00:00 2001 From: "Kem (TiankuiXian)" <1041084556@qq.com> Date: Thu, 23 Jan 2025 22:01:46 +0900 Subject: [PATCH 309/334] feat(autoware_control_evaluator): add new steering metrics (#10012) --- .../control_evaluator_node.hpp | 20 +++++++- .../control_evaluator/metrics/metric.hpp | 12 +++++ .../launch/control_evaluator.launch.xml | 2 + .../autoware_control_evaluator/package.xml | 1 + .../src/control_evaluator_node.cpp | 46 +++++++++++++++++++ 5 files changed, 79 insertions(+), 2 deletions(-) diff --git a/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp b/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp index 663da9e9ebd87..06f188a1fb63d 100644 --- a/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp +++ b/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp @@ -25,6 +25,7 @@ #include #include +#include "autoware_vehicle_msgs/msg/steering_report.hpp" #include "geometry_msgs/msg/accel_with_covariance_stamped.hpp" #include #include @@ -45,6 +46,7 @@ using autoware::universe_utils::LineString2d; using autoware::universe_utils::Point2d; using autoware::vehicle_info_utils::VehicleInfo; using autoware_planning_msgs::msg::Trajectory; +using autoware_vehicle_msgs::msg::SteeringReport; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using nav_msgs::msg::Odometry; @@ -75,6 +77,7 @@ class ControlEvaluatorNode : public rclcpp::Node void AddLaneletInfoMsg(const Pose & ego_pose); void AddKinematicStateMetricMsg( const Odometry & odom, const AccelWithCovarianceStamped & accel_stamped); + void AddSteeringMetricMsg(const SteeringReport & steering_report); void onTimer(); @@ -93,6 +96,8 @@ class ControlEvaluatorNode : public rclcpp::Node vector_map_subscriber_{this, "~/input/vector_map", rclcpp::QoS{1}.transient_local()}; autoware::universe_utils::InterProcessPollingSubscriber behavior_path_subscriber_{ this, "~/input/behavior_path"}; + autoware::universe_utils::InterProcessPollingSubscriber steering_sub_{ + this, "~/input/steering_status"}; rclcpp::Publisher::SharedPtr processing_time_pub_; @@ -107,8 +112,16 @@ class ControlEvaluatorNode : public rclcpp::Node // Metric const std::vector metrics_ = { // collect all metrics - Metric::lateral_deviation, Metric::yaw_deviation, Metric::goal_longitudinal_deviation, - Metric::goal_lateral_deviation, Metric::goal_yaw_deviation, + Metric::lateral_deviation, + Metric::yaw_deviation, + Metric::goal_longitudinal_deviation, + Metric::goal_lateral_deviation, + Metric::goal_yaw_deviation, + Metric::left_boundary_distance, + Metric::right_boundary_distance, + Metric::steering_angle, + Metric::steering_rate, + Metric::steering_acceleration, }; std::array, static_cast(Metric::SIZE)> @@ -119,6 +132,9 @@ class ControlEvaluatorNode : public rclcpp::Node autoware::route_handler::RouteHandler route_handler_; rclcpp::TimerBase::SharedPtr timer_; std::optional prev_acc_stamped_{std::nullopt}; + std::optional prev_steering_angle_{std::nullopt}; + std::optional prev_steering_rate_{std::nullopt}; + std::optional prev_steering_angle_timestamp_{std::nullopt}; }; } // namespace control_diagnostics diff --git a/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/metrics/metric.hpp b/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/metrics/metric.hpp index ab2533d0f6ed3..39ef6fa26dfa8 100644 --- a/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/metrics/metric.hpp +++ b/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/metrics/metric.hpp @@ -33,6 +33,9 @@ enum class Metric { goal_yaw_deviation, left_boundary_distance, right_boundary_distance, + steering_angle, + steering_rate, + steering_acceleration, SIZE, }; @@ -44,6 +47,9 @@ static const std::unordered_map str_to_metric = { {"goal_yaw_deviation", Metric::goal_yaw_deviation}, {"left_boundary_distance", Metric::left_boundary_distance}, {"right_boundary_distance", Metric::right_boundary_distance}, + {"steering_angle", Metric::steering_angle}, + {"steering_rate", Metric::steering_rate}, + {"steering_acceleration", Metric::steering_acceleration}, }; static const std::unordered_map metric_to_str = { @@ -54,6 +60,9 @@ static const std::unordered_map metric_to_str = { {Metric::goal_yaw_deviation, "goal_yaw_deviation"}, {Metric::left_boundary_distance, "left_boundary_distance"}, {Metric::right_boundary_distance, "right_boundary_distance"}, + {Metric::steering_angle, "steering_angle"}, + {Metric::steering_rate, "steering_rate"}, + {Metric::steering_acceleration, "steering_acceleration"}, }; // Metrics descriptions @@ -65,6 +74,9 @@ static const std::unordered_map metric_descriptions = { {Metric::goal_yaw_deviation, "Yaw deviation from the goal point[rad]"}, {Metric::left_boundary_distance, "Signed distance to the left boundary[m]"}, {Metric::right_boundary_distance, "Signed distance to the right boundary[m]"}, + {Metric::steering_angle, "Steering angle[rad]"}, + {Metric::steering_rate, "Steering angle rate[rad/s]"}, + {Metric::steering_acceleration, "Steering angle acceleration[rad/s^2]"}, }; namespace details diff --git a/evaluator/autoware_control_evaluator/launch/control_evaluator.launch.xml b/evaluator/autoware_control_evaluator/launch/control_evaluator.launch.xml index 7d26a58367fa1..f1415410c13e4 100644 --- a/evaluator/autoware_control_evaluator/launch/control_evaluator.launch.xml +++ b/evaluator/autoware_control_evaluator/launch/control_evaluator.launch.xml @@ -6,6 +6,7 @@ + @@ -17,6 +18,7 @@ + diff --git a/evaluator/autoware_control_evaluator/package.xml b/evaluator/autoware_control_evaluator/package.xml index ea8f0875855d1..0bc319e485387 100644 --- a/evaluator/autoware_control_evaluator/package.xml +++ b/evaluator/autoware_control_evaluator/package.xml @@ -22,6 +22,7 @@ autoware_test_utils autoware_universe_utils autoware_vehicle_info_utils + autoware_vehicle_msgs nav_msgs nlohmann-json-dev pluginlib diff --git a/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp b/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp index 4abfb25afeee8..435d1bb8c4dd3 100644 --- a/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp +++ b/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp @@ -244,6 +244,47 @@ void ControlEvaluatorNode::AddKinematicStateMetricMsg( return; } +void ControlEvaluatorNode::AddSteeringMetricMsg(const SteeringReport & steering_status) +{ + // steering angle + double cur_steering_angle = steering_status.steering_tire_angle; + const double cur_t = static_cast(steering_status.stamp.sec) + + static_cast(steering_status.stamp.nanosec) * 1e-9; + AddMetricMsg(Metric::steering_angle, cur_steering_angle); + + if (!prev_steering_angle_timestamp_.has_value()) { + prev_steering_angle_timestamp_ = cur_t; + prev_steering_angle_ = cur_steering_angle; + return; + } + + // d_t + const double dt = cur_t - prev_steering_angle_timestamp_.value(); + if (dt < std::numeric_limits::epsilon()) { + prev_steering_angle_timestamp_ = cur_t; + prev_steering_angle_ = cur_steering_angle; + return; + } + + // steering rate + const double steering_rate = (cur_steering_angle - prev_steering_angle_.value()) / dt; + AddMetricMsg(Metric::steering_rate, steering_rate); + + // steering acceleration + if (!prev_steering_rate_.has_value()) { + prev_steering_angle_timestamp_ = cur_t; + prev_steering_angle_ = cur_steering_angle; + prev_steering_rate_ = steering_rate; + return; + } + const double steering_acceleration = (steering_rate - prev_steering_rate_.value()) / dt; + AddMetricMsg(Metric::steering_acceleration, steering_acceleration); + + prev_steering_angle_timestamp_ = cur_t; + prev_steering_angle_ = cur_steering_angle; + prev_steering_rate_ = steering_rate; +} + void ControlEvaluatorNode::AddLateralDeviationMetricMsg( const Trajectory & traj, const Point & ego_point) { @@ -294,6 +335,7 @@ void ControlEvaluatorNode::onTimer() const auto odom = odometry_sub_.takeData(); const auto acc = accel_sub_.takeData(); const auto behavior_path = behavior_path_subscriber_.takeData(); + const auto steering_status = steering_sub_.takeData(); // calculate deviation metrics if (odom && traj && !traj->points.empty()) { @@ -320,6 +362,10 @@ void ControlEvaluatorNode::onTimer() AddBoundaryDistanceMetricMsg(*behavior_path, ego_pose); } + if (steering_status) { + AddSteeringMetricMsg(*steering_status); + } + // Publish metrics metrics_msg_.stamp = now(); metrics_pub_->publish(metrics_msg_); From 2169394cc2d3e233ee1eee487d9cb28bcf1e6d8d Mon Sep 17 00:00:00 2001 From: Junya Sasaki Date: Fri, 24 Jan 2025 10:10:03 +0900 Subject: [PATCH 310/334] fix(tier4_simulator_launch): fix a wrong package name: `fault_injection` => `autoware_fault_injection` (#10014) Signed-off-by: Junya Sasaki --- launch/tier4_simulator_launch/launch/simulator.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/launch/tier4_simulator_launch/launch/simulator.launch.xml b/launch/tier4_simulator_launch/launch/simulator.launch.xml index a879340bc4d0c..e5468b4f22a18 100644 --- a/launch/tier4_simulator_launch/launch/simulator.launch.xml +++ b/launch/tier4_simulator_launch/launch/simulator.launch.xml @@ -40,7 +40,7 @@ - + From ecc93f1f48437ef7400eb6c0d0390d8eef7a69f8 Mon Sep 17 00:00:00 2001 From: Junya Sasaki Date: Fri, 24 Jan 2025 13:19:47 +0900 Subject: [PATCH 311/334] feat: apply `autoware_` prefix for `control_performance_analysis` (#9982) * feat(control_performance_analysis): apply `autoware_` prefix (see below): Note: * In this commit, I did not organize a folder structure. The folder structure will be organized in the next some commits. * The changes will follow the Autoware's guideline as below: - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder Signed-off-by: Junya Sasaki * rename(control_performance_analysis): move headers under `include/autoware`: * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit Signed-off-by: Junya Sasaki * fix(control_performance_analysis): fix include paths * To follow the previous commit Signed-off-by: Junya Sasaki * rename: `control_performance_analysis` => `autoware_control_performance_analysis` Signed-off-by: Junya Sasaki * style(pre-commit): autofix * bug(autoware_control_performance_analysis): fix inconsistent namespacing Signed-off-by: Junya Sasaki * style(pre-commit): autofix * update(autoware_control_performance_analysis): `README.md` Signed-off-by: Junya Sasaki * bug(autoware_control_performance_analysis): fix critical bugs that contaminate topic name Signed-off-by: Junya Sasaki * style(pre-commit): autofix * fix: update package name for error_rqt_multiplot.xml Signed-off-by: Ryohsuke Mitsudome * fix: update package name for control_performance_plot.py Signed-off-by: Ryohsuke Mitsudome * docs(autoware_control_performance_analysis): update package name in README and CHANGELOG.rst Signed-off-by: Ryohsuke Mitsudome * style(pre-commit): autofix --------- Signed-off-by: Junya Sasaki Signed-off-by: Ryohsuke Mitsudome Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Ryohsuke Mitsudome Co-authored-by: SakodaShintaro --- .../CHANGELOG.rst | 6 ++-- .../CMakeLists.txt | 14 ++++---- .../README.md | 18 +++++------ .../control_performance_analysis.param.yaml | 0 .../config/controller_monitor.xml | 0 .../config/error_rqt_multiplot.xml | 32 +++++++++---------- .../control_performance_analysis_core.hpp | 28 ++++++++-------- .../control_performance_analysis_node.hpp | 22 ++++++------- .../control_performance_analysis_utils.hpp | 12 +++---- .../control_performance_analysis.launch.xml | 4 +-- .../msg/DrivingMonitorStamped.msg | 6 ++++ .../msg/Error.msg | 0 .../msg/ErrorStamped.msg | 2 ++ .../msg/FloatStamped.msg | 0 .../package.xml | 3 +- .../control_performance_analysis.schema.json | 0 .../scripts/control_performance_plot.py | 4 +-- .../src/control_performance_analysis_core.cpp | 25 +++++++++------ .../src/control_performance_analysis_node.cpp | 26 +++++++-------- .../control_performance_analysis_utils.cpp | 8 ++--- .../msg/DrivingMonitorStamped.msg | 6 ---- .../msg/ErrorStamped.msg | 2 -- 22 files changed, 110 insertions(+), 108 deletions(-) rename control/{control_performance_analysis => autoware_control_performance_analysis}/CHANGELOG.rst (99%) rename control/{control_performance_analysis => autoware_control_performance_analysis}/CMakeLists.txt (78%) rename control/{control_performance_analysis => autoware_control_performance_analysis}/README.md (89%) rename control/{control_performance_analysis => autoware_control_performance_analysis}/config/control_performance_analysis.param.yaml (100%) rename control/{control_performance_analysis => autoware_control_performance_analysis}/config/controller_monitor.xml (100%) rename control/{control_performance_analysis => autoware_control_performance_analysis}/config/error_rqt_multiplot.xml (96%) rename control/{control_performance_analysis/include => autoware_control_performance_analysis/include/autoware}/control_performance_analysis/control_performance_analysis_core.hpp (80%) rename control/{control_performance_analysis/include => autoware_control_performance_analysis/include/autoware}/control_performance_analysis/control_performance_analysis_node.hpp (79%) rename control/{control_performance_analysis/include => autoware_control_performance_analysis/include/autoware}/control_performance_analysis/control_performance_analysis_utils.hpp (86%) rename control/{control_performance_analysis => autoware_control_performance_analysis}/launch/control_performance_analysis.launch.xml (83%) create mode 100644 control/autoware_control_performance_analysis/msg/DrivingMonitorStamped.msg rename control/{control_performance_analysis => autoware_control_performance_analysis}/msg/Error.msg (100%) create mode 100644 control/autoware_control_performance_analysis/msg/ErrorStamped.msg rename control/{control_performance_analysis => autoware_control_performance_analysis}/msg/FloatStamped.msg (100%) rename control/{control_performance_analysis => autoware_control_performance_analysis}/package.xml (94%) rename control/{control_performance_analysis => autoware_control_performance_analysis}/schema/control_performance_analysis.schema.json (100%) rename control/{control_performance_analysis => autoware_control_performance_analysis}/scripts/control_performance_plot.py (97%) rename control/{control_performance_analysis => autoware_control_performance_analysis}/src/control_performance_analysis_core.cpp (95%) rename control/{control_performance_analysis => autoware_control_performance_analysis}/src/control_performance_analysis_node.cpp (91%) rename control/{control_performance_analysis => autoware_control_performance_analysis}/src/control_performance_analysis_utils.cpp (74%) delete mode 100644 control/control_performance_analysis/msg/DrivingMonitorStamped.msg delete mode 100644 control/control_performance_analysis/msg/ErrorStamped.msg diff --git a/control/control_performance_analysis/CHANGELOG.rst b/control/autoware_control_performance_analysis/CHANGELOG.rst similarity index 99% rename from control/control_performance_analysis/CHANGELOG.rst rename to control/autoware_control_performance_analysis/CHANGELOG.rst index 67b4f15ddde9f..55361923da83d 100644 --- a/control/control_performance_analysis/CHANGELOG.rst +++ b/control/autoware_control_performance_analysis/CHANGELOG.rst @@ -1,6 +1,6 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package control_performance_analysis -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_control_performance_analysis +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.40.0 (2024-12-12) ------------------- diff --git a/control/control_performance_analysis/CMakeLists.txt b/control/autoware_control_performance_analysis/CMakeLists.txt similarity index 78% rename from control/control_performance_analysis/CMakeLists.txt rename to control/autoware_control_performance_analysis/CMakeLists.txt index 10a305e1f7dbc..6ea320d2d402e 100644 --- a/control/control_performance_analysis/CMakeLists.txt +++ b/control/autoware_control_performance_analysis/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(control_performance_analysis) +project(autoware_control_performance_analysis) find_package(autoware_cmake REQUIRED) autoware_package() @@ -19,7 +19,7 @@ find_package(rosidl_default_generators REQUIRED) find_package(std_msgs REQUIRED) rosidl_generate_interfaces( - control_performance_analysis + ${PROJECT_NAME} "msg/Error.msg" "msg/ErrorStamped.msg" "msg/DrivingMonitorStamped.msg" @@ -40,12 +40,12 @@ ament_auto_add_library( if(${rosidl_cmake_VERSION} VERSION_LESS 2.5.0) rosidl_target_interfaces(control_performance_analysis_node - control_performance_analysis "rosidl_typesupport_cpp") + ${PROJECT_NAME} "rosidl_typesupport_cpp") rosidl_target_interfaces(control_performance_analysis_core - control_performance_analysis "rosidl_typesupport_cpp") + ${PROJECT_NAME} "rosidl_typesupport_cpp") else() rosidl_get_typesupport_target( - cpp_typesupport_target control_performance_analysis "rosidl_typesupport_cpp") + cpp_typesupport_target ${PROJECT_NAME} "rosidl_typesupport_cpp") target_link_libraries(control_performance_analysis_node "${cpp_typesupport_target}") target_link_libraries(control_performance_analysis_core "${cpp_typesupport_target}") @@ -58,8 +58,8 @@ target_link_libraries( rclcpp_components_register_node( control_performance_analysis_node - PLUGIN "control_performance_analysis::ControlPerformanceAnalysisNode" - EXECUTABLE control_performance_analysis_exe + PLUGIN "autoware::control_performance_analysis::ControlPerformanceAnalysisNode" + EXECUTABLE ${PROJECT_NAME}_node ) ament_auto_package( diff --git a/control/control_performance_analysis/README.md b/control/autoware_control_performance_analysis/README.md similarity index 89% rename from control/control_performance_analysis/README.md rename to control/autoware_control_performance_analysis/README.md index e87efbe179eee..e57126b28cb5f 100644 --- a/control/control_performance_analysis/README.md +++ b/control/autoware_control_performance_analysis/README.md @@ -1,13 +1,13 @@ -# control_performance_analysis +# autoware_control_performance_analysis ## Purpose -`control_performance_analysis` is the package to analyze the tracking performance of a control module and monitor the driving status of the vehicle. +`autoware_control_performance_analysis` is the package to analyze the tracking performance of a control module and monitor the driving status of the vehicle. This package is used as a tool to quantify the results of the control module. That's why it doesn't interfere with the core logic of autonomous driving. -Based on the various input from planning, control, and vehicle, it publishes the result of analysis as `control_performance_analysis::msg::ErrorStamped` defined in this package. +Based on the various input from planning, control, and vehicle, it publishes the result of analysis as `autoware_control_performance_analysis::msg::ErrorStamped` defined in this package. All results in `ErrorStamped` message are calculated in Frenet Frame of curve. Errors and velocity errors are calculated by using paper below. @@ -35,14 +35,14 @@ Error acceleration calculations are made based on the velocity calculations abov ### Output topics -| Name | Type | Description | -| --------------------------------------- | -------------------------------------------------------- | --------------------------------------------------- | -| `/control_performance/performance_vars` | control_performance_analysis::msg::ErrorStamped | The result of the performance analysis. | -| `/control_performance/driving_status` | control_performance_analysis::msg::DrivingMonitorStamped | Driving status (acceleration, jerk etc.) monitoring | +| Name | Type | Description | +| --------------------------------------- | ----------------------------------------------------------------- | --------------------------------------------------- | +| `/control_performance/performance_vars` | autoware_control_performance_analysis::msg::ErrorStamped | The result of the performance analysis. | +| `/control_performance/driving_status` | autoware_control_performance_analysis::msg::DrivingMonitorStamped | Driving status (acceleration, jerk etc.) monitoring | ### Outputs -#### control_performance_analysis::msg::DrivingMonitorStamped +#### autoware_control_performance_analysis::msg::DrivingMonitorStamped | Name | Type | Description | | ---------------------------- | ----- | --------------------------------------------------------------------- | @@ -53,7 +53,7 @@ Error acceleration calculations are made based on the velocity calculations abov | `desired_steering_angle` | float | $[ \mathrm{rad} ]$ | | `controller_processing_time` | float | Timestamp between last two control command messages $[ \mathrm{ms} ]$ | -#### control_performance_analysis::msg::ErrorStamped +#### autoware_control_performance_analysis::msg::ErrorStamped | Name | Type | Description | | ------------------------------------------ | ----- | ----------------------------------------------------------------------------------------------------------------------------------------- | diff --git a/control/control_performance_analysis/config/control_performance_analysis.param.yaml b/control/autoware_control_performance_analysis/config/control_performance_analysis.param.yaml similarity index 100% rename from control/control_performance_analysis/config/control_performance_analysis.param.yaml rename to control/autoware_control_performance_analysis/config/control_performance_analysis.param.yaml diff --git a/control/control_performance_analysis/config/controller_monitor.xml b/control/autoware_control_performance_analysis/config/controller_monitor.xml similarity index 100% rename from control/control_performance_analysis/config/controller_monitor.xml rename to control/autoware_control_performance_analysis/config/controller_monitor.xml diff --git a/control/control_performance_analysis/config/error_rqt_multiplot.xml b/control/autoware_control_performance_analysis/config/error_rqt_multiplot.xml similarity index 96% rename from control/control_performance_analysis/config/error_rqt_multiplot.xml rename to control/autoware_control_performance_analysis/config/error_rqt_multiplot.xml index 8597cbdaa253e..b75115929456f 100644 --- a/control/control_performance_analysis/config/error_rqt_multiplot.xml +++ b/control/autoware_control_performance_analysis/config/error_rqt_multiplot.xml @@ -36,7 +36,7 @@ 0 /control_performance/performance_vars - control_performance_analysis/ErrorStamped + autoware_control_performance_analysis/ErrorStamped error/lateral_error @@ -49,7 +49,7 @@ 0 /control_performance/performance_vars - control_performance_analysis/ErrorStamped + autoware_control_performance_analysis/ErrorStamped @@ -110,7 +110,7 @@ 0 /control_performance/performance_vars - control_performance_analysis/ErrorStamped + autoware_control_performance_analysis/ErrorStamped error/error_energy @@ -123,7 +123,7 @@ 0 /control_performance/performance_vars - control_performance_analysis/ErrorStamped + autoware_control_performance_analysis/ErrorStamped @@ -184,7 +184,7 @@ 0 /control_performance/performance_vars - control_performance_analysis/ErrorStamped + autoware_control_performance_analysis/ErrorStamped error/lateral_error_velocity @@ -197,7 +197,7 @@ 0 /control_performance/performance_vars - control_performance_analysis/ErrorStamped + autoware_control_performance_analysis/ErrorStamped @@ -260,7 +260,7 @@ 0 /control_performance/performance_vars - control_performance_analysis/ErrorStamped + autoware_control_performance_analysis/ErrorStamped error/heading_error @@ -273,7 +273,7 @@ 0 /control_performance/performance_vars - control_performance_analysis/ErrorStamped + autoware_control_performance_analysis/ErrorStamped @@ -334,7 +334,7 @@ 0 /control_performance/performance_vars - control_performance_analysis/ErrorStamped + autoware_control_performance_analysis/ErrorStamped error/control_effort_energy @@ -347,7 +347,7 @@ 0 /control_performance/performance_vars - control_performance_analysis/ErrorStamped + autoware_control_performance_analysis/ErrorStamped @@ -408,7 +408,7 @@ 0 /control_performance/performance_vars - control_performance_analysis/ErrorStamped + autoware_control_performance_analysis/ErrorStamped error/lateral_error_acceleration @@ -421,7 +421,7 @@ 0 /control_performance/performance_vars - control_performance_analysis/ErrorStamped + autoware_control_performance_analysis/ErrorStamped @@ -484,7 +484,7 @@ 0 /control_performance/performance_vars - control_performance_analysis/ErrorStamped + autoware_control_performance_analysis/ErrorStamped error/value_approximation @@ -497,7 +497,7 @@ 0 /control_performance/performance_vars - control_performance_analysis/ErrorStamped + autoware_control_performance_analysis/ErrorStamped @@ -558,7 +558,7 @@ 0 /control_performance/performance_vars - control_performance_analysis/ErrorStamped + autoware_control_performance_analysis/ErrorStamped error/curvature_estimate @@ -571,7 +571,7 @@ 0 /control_performance/performance_vars - control_performance_analysis/ErrorStamped + autoware_control_performance_analysis/ErrorStamped diff --git a/control/control_performance_analysis/include/control_performance_analysis/control_performance_analysis_core.hpp b/control/autoware_control_performance_analysis/include/autoware/control_performance_analysis/control_performance_analysis_core.hpp similarity index 80% rename from control/control_performance_analysis/include/control_performance_analysis/control_performance_analysis_core.hpp rename to control/autoware_control_performance_analysis/include/autoware/control_performance_analysis/control_performance_analysis_core.hpp index db0afc134ff79..4f6b9c237279f 100644 --- a/control/control_performance_analysis/include/control_performance_analysis/control_performance_analysis_core.hpp +++ b/control/autoware_control_performance_analysis/include/autoware/control_performance_analysis/control_performance_analysis_core.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 - 2022 Tier IV, Inc., Leo Drive Teknoloji A.Ş. +// Copyright 2021 - 2025 Tier IV, Inc., Leo Drive Teknoloji A.Ş. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_CORE_HPP_ -#define CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_CORE_HPP_ +#ifndef AUTOWARE__CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_CORE_HPP_ +#define AUTOWARE__CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_CORE_HPP_ +#include "autoware/control_performance_analysis/control_performance_analysis_utils.hpp" #include "autoware/motion_utils/trajectory/trajectory.hpp" -#include "control_performance_analysis/control_performance_analysis_utils.hpp" -#include "control_performance_analysis/msg/driving_monitor_stamped.hpp" -#include "control_performance_analysis/msg/error_stamped.hpp" -#include "control_performance_analysis/msg/float_stamped.hpp" +#include "autoware_control_performance_analysis/msg/driving_monitor_stamped.hpp" +#include "autoware_control_performance_analysis/msg/error_stamped.hpp" +#include "autoware_control_performance_analysis/msg/float_stamped.hpp" #include #include @@ -37,15 +37,15 @@ #include #include -namespace control_performance_analysis +namespace autoware::control_performance_analysis { using autoware_control_msgs::msg::Control; +using autoware_control_performance_analysis::msg::DrivingMonitorStamped; +using autoware_control_performance_analysis::msg::Error; +using autoware_control_performance_analysis::msg::ErrorStamped; +using autoware_control_performance_analysis::msg::FloatStamped; using autoware_planning_msgs::msg::Trajectory; using autoware_vehicle_msgs::msg::SteeringReport; -using control_performance_analysis::msg::DrivingMonitorStamped; -using control_performance_analysis::msg::Error; -using control_performance_analysis::msg::ErrorStamped; -using control_performance_analysis::msg::FloatStamped; using geometry_msgs::msg::Pose; using geometry_msgs::msg::PoseArray; using geometry_msgs::msg::Twist; @@ -129,6 +129,6 @@ class ControlPerformanceAnalysisCore rclcpp::Logger logger_{rclcpp::get_logger("control_performance_analysis")}; rclcpp::Clock clock_{RCL_ROS_TIME}; }; -} // namespace control_performance_analysis +} // namespace autoware::control_performance_analysis -#endif // CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_CORE_HPP_ +#endif // AUTOWARE__CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_CORE_HPP_ diff --git a/control/control_performance_analysis/include/control_performance_analysis/control_performance_analysis_node.hpp b/control/autoware_control_performance_analysis/include/autoware/control_performance_analysis/control_performance_analysis_node.hpp similarity index 79% rename from control/control_performance_analysis/include/control_performance_analysis/control_performance_analysis_node.hpp rename to control/autoware_control_performance_analysis/include/autoware/control_performance_analysis/control_performance_analysis_node.hpp index 16e383916eb6d..973574d47c50f 100644 --- a/control/control_performance_analysis/include/control_performance_analysis/control_performance_analysis_node.hpp +++ b/control/autoware_control_performance_analysis/include/autoware/control_performance_analysis/control_performance_analysis_node.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 - 2022 Tier IV, Inc., Leo Drive Teknoloji A.Ş. +// Copyright 2021 - 2025 Tier IV, Inc., Leo Drive Teknoloji A.Ş. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_NODE_HPP_ -#define CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_NODE_HPP_ +#ifndef AUTOWARE__CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_NODE_HPP_ +#define AUTOWARE__CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_NODE_HPP_ -#include "control_performance_analysis/control_performance_analysis_core.hpp" -#include "control_performance_analysis/msg/driving_monitor_stamped.hpp" -#include "control_performance_analysis/msg/error_stamped.hpp" +#include "autoware/control_performance_analysis/control_performance_analysis_core.hpp" +#include "autoware_control_performance_analysis/msg/driving_monitor_stamped.hpp" +#include "autoware_control_performance_analysis/msg/error_stamped.hpp" #include #include @@ -34,13 +34,13 @@ #include #include -namespace control_performance_analysis +namespace autoware::control_performance_analysis { using autoware_control_msgs::msg::Control; +using autoware_control_performance_analysis::msg::DrivingMonitorStamped; +using autoware_control_performance_analysis::msg::ErrorStamped; using autoware_planning_msgs::msg::Trajectory; using autoware_vehicle_msgs::msg::SteeringReport; -using control_performance_analysis::msg::DrivingMonitorStamped; -using control_performance_analysis::msg::ErrorStamped; using geometry_msgs::msg::PoseStamped; using nav_msgs::msg::Odometry; @@ -92,6 +92,6 @@ class ControlPerformanceAnalysisNode : public rclcpp::Node // Algorithm std::unique_ptr control_performance_core_ptr_; }; -} // namespace control_performance_analysis +} // namespace autoware::control_performance_analysis -#endif // CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_NODE_HPP_ +#endif // AUTOWARE__CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_NODE_HPP_ diff --git a/control/control_performance_analysis/include/control_performance_analysis/control_performance_analysis_utils.hpp b/control/autoware_control_performance_analysis/include/autoware/control_performance_analysis/control_performance_analysis_utils.hpp similarity index 86% rename from control/control_performance_analysis/include/control_performance_analysis/control_performance_analysis_utils.hpp rename to control/autoware_control_performance_analysis/include/autoware/control_performance_analysis/control_performance_analysis_utils.hpp index fb939d825b653..2199a0b20d7c1 100644 --- a/control/control_performance_analysis/include/control_performance_analysis/control_performance_analysis_utils.hpp +++ b/control/autoware_control_performance_analysis/include/autoware/control_performance_analysis/control_performance_analysis_utils.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 - 2022 Tier IV, Inc., Leo Drive Teknoloji A.Ş. +// Copyright 2021 - 2025 Tier IV, Inc., Leo Drive Teknoloji A.Ş. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_UTILS_HPP_ -#define CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_UTILS_HPP_ +#ifndef AUTOWARE__CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_UTILS_HPP_ +#define AUTOWARE__CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_UTILS_HPP_ #include #include @@ -28,7 +28,7 @@ #include #include -namespace control_performance_analysis +namespace autoware::control_performance_analysis { namespace utils { @@ -84,6 +84,6 @@ double curvatureFromThreePoints( std::array const & c); } // namespace utils -} // namespace control_performance_analysis +} // namespace autoware::control_performance_analysis -#endif // CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_UTILS_HPP_ +#endif // AUTOWARE__CONTROL_PERFORMANCE_ANALYSIS__CONTROL_PERFORMANCE_ANALYSIS_UTILS_HPP_ diff --git a/control/control_performance_analysis/launch/control_performance_analysis.launch.xml b/control/autoware_control_performance_analysis/launch/control_performance_analysis.launch.xml similarity index 83% rename from control/control_performance_analysis/launch/control_performance_analysis.launch.xml rename to control/autoware_control_performance_analysis/launch/control_performance_analysis.launch.xml index f2997f0e10b83..eb479942e31a4 100644 --- a/control/control_performance_analysis/launch/control_performance_analysis.launch.xml +++ b/control/autoware_control_performance_analysis/launch/control_performance_analysis.launch.xml @@ -1,5 +1,5 @@ - + @@ -10,7 +10,7 @@ - + diff --git a/control/autoware_control_performance_analysis/msg/DrivingMonitorStamped.msg b/control/autoware_control_performance_analysis/msg/DrivingMonitorStamped.msg new file mode 100644 index 0000000000000..408a5a283e7bc --- /dev/null +++ b/control/autoware_control_performance_analysis/msg/DrivingMonitorStamped.msg @@ -0,0 +1,6 @@ +autoware_control_performance_analysis/FloatStamped longitudinal_acceleration +autoware_control_performance_analysis/FloatStamped longitudinal_jerk +autoware_control_performance_analysis/FloatStamped lateral_acceleration +autoware_control_performance_analysis/FloatStamped lateral_jerk +autoware_control_performance_analysis/FloatStamped desired_steering_angle +autoware_control_performance_analysis/FloatStamped controller_processing_time diff --git a/control/control_performance_analysis/msg/Error.msg b/control/autoware_control_performance_analysis/msg/Error.msg similarity index 100% rename from control/control_performance_analysis/msg/Error.msg rename to control/autoware_control_performance_analysis/msg/Error.msg diff --git a/control/autoware_control_performance_analysis/msg/ErrorStamped.msg b/control/autoware_control_performance_analysis/msg/ErrorStamped.msg new file mode 100644 index 0000000000000..813c68d803e5b --- /dev/null +++ b/control/autoware_control_performance_analysis/msg/ErrorStamped.msg @@ -0,0 +1,2 @@ +std_msgs/Header header +autoware_control_performance_analysis/Error error diff --git a/control/control_performance_analysis/msg/FloatStamped.msg b/control/autoware_control_performance_analysis/msg/FloatStamped.msg similarity index 100% rename from control/control_performance_analysis/msg/FloatStamped.msg rename to control/autoware_control_performance_analysis/msg/FloatStamped.msg diff --git a/control/control_performance_analysis/package.xml b/control/autoware_control_performance_analysis/package.xml similarity index 94% rename from control/control_performance_analysis/package.xml rename to control/autoware_control_performance_analysis/package.xml index f2630a7d47f62..1730277a87445 100644 --- a/control/control_performance_analysis/package.xml +++ b/control/autoware_control_performance_analysis/package.xml @@ -1,7 +1,7 @@ - control_performance_analysis + autoware_control_performance_analysis 0.40.0 Controller Performance Evaluation Berkay Karaman @@ -12,6 +12,7 @@ Takamasa Horibe Satoshi Ota Takayuki Murooka + Junya Sasaki Apache License 2.0 diff --git a/control/control_performance_analysis/schema/control_performance_analysis.schema.json b/control/autoware_control_performance_analysis/schema/control_performance_analysis.schema.json similarity index 100% rename from control/control_performance_analysis/schema/control_performance_analysis.schema.json rename to control/autoware_control_performance_analysis/schema/control_performance_analysis.schema.json diff --git a/control/control_performance_analysis/scripts/control_performance_plot.py b/control/autoware_control_performance_analysis/scripts/control_performance_plot.py similarity index 97% rename from control/control_performance_analysis/scripts/control_performance_plot.py rename to control/autoware_control_performance_analysis/scripts/control_performance_plot.py index d4a6038465e12..a30266a32809f 100644 --- a/control/control_performance_analysis/scripts/control_performance_plot.py +++ b/control/autoware_control_performance_analysis/scripts/control_performance_plot.py @@ -17,9 +17,9 @@ import argparse import math +from autoware_control_performance_analysis.msg import DrivingMonitorStamped +from autoware_control_performance_analysis.msg import ErrorStamped from autoware_internal_debug_msgs.msg import BoolStamped -from control_performance_analysis.msg import DrivingMonitorStamped -from control_performance_analysis.msg import ErrorStamped import matplotlib.pyplot as plt from nav_msgs.msg import Odometry import rclpy diff --git a/control/control_performance_analysis/src/control_performance_analysis_core.cpp b/control/autoware_control_performance_analysis/src/control_performance_analysis_core.cpp similarity index 95% rename from control/control_performance_analysis/src/control_performance_analysis_core.cpp rename to control/autoware_control_performance_analysis/src/control_performance_analysis_core.cpp index 08f736dd0b630..a5b818c64592e 100644 --- a/control/control_performance_analysis/src/control_performance_analysis_core.cpp +++ b/control/autoware_control_performance_analysis/src/control_performance_analysis_core.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 - 2022 Tier IV, Inc., Leo Drive Teknoloji A.Ş. +// Copyright 2021 - 2025 Tier IV, Inc., Leo Drive Teknoloji A.Ş. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "control_performance_analysis/control_performance_analysis_core.hpp" +#include "autoware/control_performance_analysis/control_performance_analysis_core.hpp" #include "autoware/motion_utils/trajectory/interpolation.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" @@ -25,14 +25,15 @@ #include #include -namespace control_performance_analysis +namespace autoware::control_performance_analysis { using geometry_msgs::msg::Quaternion; ControlPerformanceAnalysisCore::ControlPerformanceAnalysisCore() { - prev_target_vars_ = std::make_unique(); - prev_driving_vars_ = std::make_unique(); + prev_target_vars_ = std::make_unique(); + prev_driving_vars_ = + std::make_unique(); odom_history_ptr_ = std::make_shared>(); p_.odom_interval_ = 0; p_.curvature_interval_length_ = 10.0; @@ -46,8 +47,9 @@ ControlPerformanceAnalysisCore::ControlPerformanceAnalysisCore() ControlPerformanceAnalysisCore::ControlPerformanceAnalysisCore(Params & p) : p_{p} { // prepare control performance struct - prev_target_vars_ = std::make_unique(); - prev_driving_vars_ = std::make_unique(); + prev_target_vars_ = std::make_unique(); + prev_driving_vars_ = + std::make_unique(); odom_history_ptr_ = std::make_shared>(); } @@ -251,7 +253,8 @@ bool ControlPerformanceAnalysisCore::calculateErrorVars() lpf(error.error_energy, prev_error.error_energy); } - prev_target_vars_ = std::make_unique(error_vars); + prev_target_vars_ = + std::make_unique(error_vars); return true; } @@ -336,7 +339,9 @@ bool ControlPerformanceAnalysisCore::calculateDrivingVars() lpf(curr.desired_steering_angle.data, prev->desired_steering_angle.data); } - prev_driving_vars_ = std::make_unique(driving_status_vars); + prev_driving_vars_ = + std::make_unique( + driving_status_vars); last_odom_header.stamp = odom_history_ptr_->at(odom_size - 1).header.stamp; last_steering_report.stamp = current_vec_steering_msg_ptr_->stamp; @@ -544,4 +549,4 @@ double ControlPerformanceAnalysisCore::estimatePurePursuitCurvature() return curvature_pure_pursuit; } -} // namespace control_performance_analysis +} // namespace autoware::control_performance_analysis diff --git a/control/control_performance_analysis/src/control_performance_analysis_node.cpp b/control/autoware_control_performance_analysis/src/control_performance_analysis_node.cpp similarity index 91% rename from control/control_performance_analysis/src/control_performance_analysis_node.cpp rename to control/autoware_control_performance_analysis/src/control_performance_analysis_node.cpp index 47ce3ce07e83c..1eaf8384614f8 100644 --- a/control/control_performance_analysis/src/control_performance_analysis_node.cpp +++ b/control/autoware_control_performance_analysis/src/control_performance_analysis_node.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 - 2022 Tier IV, Inc., Leo Drive Teknoloji A.Ş. +// Copyright 2021 - 2025 Tier IV, Inc., Leo Drive Teknoloji A.Ş. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,27 +12,22 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "control_performance_analysis/control_performance_analysis_node.hpp" +#include "autoware/control_performance_analysis/control_performance_analysis_node.hpp" -#include "control_performance_analysis/msg/driving_monitor_stamped.hpp" -#include "control_performance_analysis/msg/error_stamped.hpp" +#include "autoware_control_performance_analysis/msg/driving_monitor_stamped.hpp" +#include "autoware_control_performance_analysis/msg/error_stamped.hpp" #include #include #include -namespace -{ -using autoware_control_msgs::msg::Control; -using control_performance_analysis::msg::DrivingMonitorStamped; -using control_performance_analysis::msg::ErrorStamped; - -} // namespace - -namespace control_performance_analysis +namespace autoware::control_performance_analysis { using autoware::vehicle_info_utils::VehicleInfoUtils; +using autoware_control_msgs::msg::Control; +using autoware_control_performance_analysis::msg::DrivingMonitorStamped; +using autoware_control_performance_analysis::msg::ErrorStamped; ControlPerformanceAnalysisNode::ControlPerformanceAnalysisNode( const rclcpp::NodeOptions & node_options) @@ -195,7 +190,8 @@ bool ControlPerformanceAnalysisNode::isValidTrajectory(const Trajectory & traj) return check_condition; } -} // namespace control_performance_analysis +} // namespace autoware::control_performance_analysis #include -RCLCPP_COMPONENTS_REGISTER_NODE(control_performance_analysis::ControlPerformanceAnalysisNode) +RCLCPP_COMPONENTS_REGISTER_NODE( + autoware::control_performance_analysis::ControlPerformanceAnalysisNode) diff --git a/control/control_performance_analysis/src/control_performance_analysis_utils.cpp b/control/autoware_control_performance_analysis/src/control_performance_analysis_utils.cpp similarity index 74% rename from control/control_performance_analysis/src/control_performance_analysis_utils.cpp rename to control/autoware_control_performance_analysis/src/control_performance_analysis_utils.cpp index f96aba2b54547..721bcfd1ff83d 100644 --- a/control/control_performance_analysis/src/control_performance_analysis_utils.cpp +++ b/control/autoware_control_performance_analysis/src/control_performance_analysis_utils.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 - 2022 Tier IV, Inc., Leo Drive Teknoloji A.Ş. +// Copyright 2021 - 2025 Tier IV, Inc., Leo Drive Teknoloji A.Ş. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "control_performance_analysis/control_performance_analysis_utils.hpp" +#include "autoware/control_performance_analysis/control_performance_analysis_utils.hpp" #include -namespace control_performance_analysis +namespace autoware::control_performance_analysis { namespace utils { @@ -26,4 +26,4 @@ double determinant(std::array const & a, std::array const } } // namespace utils -} // namespace control_performance_analysis +} // namespace autoware::control_performance_analysis diff --git a/control/control_performance_analysis/msg/DrivingMonitorStamped.msg b/control/control_performance_analysis/msg/DrivingMonitorStamped.msg deleted file mode 100644 index 2dea0b5e36b8f..0000000000000 --- a/control/control_performance_analysis/msg/DrivingMonitorStamped.msg +++ /dev/null @@ -1,6 +0,0 @@ -control_performance_analysis/FloatStamped longitudinal_acceleration -control_performance_analysis/FloatStamped longitudinal_jerk -control_performance_analysis/FloatStamped lateral_acceleration -control_performance_analysis/FloatStamped lateral_jerk -control_performance_analysis/FloatStamped desired_steering_angle -control_performance_analysis/FloatStamped controller_processing_time diff --git a/control/control_performance_analysis/msg/ErrorStamped.msg b/control/control_performance_analysis/msg/ErrorStamped.msg deleted file mode 100644 index 8b0b37f653b40..0000000000000 --- a/control/control_performance_analysis/msg/ErrorStamped.msg +++ /dev/null @@ -1,2 +0,0 @@ -std_msgs/Header header -control_performance_analysis/Error error From 59071cabc0ad6ebae50d0bfee28dae60890975e5 Mon Sep 17 00:00:00 2001 From: Junya Sasaki Date: Fri, 24 Jan 2025 17:06:00 +0900 Subject: [PATCH 312/334] feat: apply `autoware_` prefix for `system_monitor` (#10017) * feat(system_monitor): apply `autoware_` prefix (see below): * The `system_monitor` operates independently from other modules in `autoware.universe`, so the `autoware_` prefix is added only to the package name. * The `autoware::` namespace is not used because C language does not support namespaces. * Headers are not moved under `include/autoware` to maintain compatibility for use outside the `autoware` context. * For users utilizing this package within `autoware.universe`, only the package name includes the `autoware_` prefix. This approach explains the unique namespacing and naming conventions for `system_monitor` compared to other packages. Signed-off-by: Junya Sasaki * bug(system_monitor): fix missing package name update Signed-off-by: Junya Sasaki * rename: `system_monitor` => `autoware_system_monitor` Signed-off-by: Junya Sasaki * style(pre-commit): autofix * update: `CODEOWNERS` Signed-off-by: Junya Sasaki * bug(autoware_system_monitor): apply missing fix Signed-off-by: Junya Sasaki * update: `CODEOWNERS` Signed-off-by: Junya Sasaki --------- Signed-off-by: Junya Sasaki Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .github/CODEOWNERS | 4 +-- .../launch/system.launch.xml | 2 +- launch/tier4_system_launch/package.xml | 2 +- .../CHANGELOG.rst | 0 .../CMakeLists.txt | 2 +- .../README.md | 2 +- .../cmake/FindNVML.cmake | 0 .../config/cpu_monitor.param.yaml | 0 .../config/gpu_monitor.param.yaml | 0 .../config/hdd_monitor.param.yaml | 0 .../config/mem_monitor.param.yaml | 0 .../config/net_monitor.param.yaml | 0 .../config/ntp_monitor.param.yaml | 0 .../config/process_monitor.param.yaml | 0 .../config/voltage_monitor.param.yaml | 0 .../docs/class_diagrams.md | 0 .../docs/hdd_reader.md | 0 .../docs/images/class_cpu_monitor.png | Bin .../docs/images/class_gpu_monitor.png | Bin .../docs/images/class_hdd_monitor.png | Bin .../docs/images/class_mem_monitor.png | Bin .../docs/images/class_net_monitor.png | Bin .../docs/images/class_ntp_monitor.png | Bin .../docs/images/class_process_monitor.png | Bin .../docs/images/seq_cpu_monitor.png | Bin .../docs/images/seq_gpu_monitor.png | Bin .../docs/images/seq_hdd_monitor.png | Bin .../docs/images/seq_mem_monitor.png | Bin .../docs/images/seq_net_monitor.png | Bin .../docs/images/seq_ntp_monitor.png | Bin .../docs/images/seq_process_monitor.png | Bin .../docs/msr_reader.md | 0 .../docs/ros_parameters.md | 0 .../docs/seq_diagrams.md | 0 .../docs/topics_cpu_monitor.md | 0 .../docs/topics_gpu_monitor.md | 0 .../docs/topics_hdd_monitor.md | 0 .../docs/topics_mem_monitor.md | 0 .../docs/topics_net_monitor.md | 0 .../docs/topics_ntp_monitor.md | 0 .../docs/topics_process_monitor.md | 0 .../docs/topics_voltage_monitor.md | 0 .../docs/traffic_reader.md | 0 .../cpu_monitor/arm_cpu_monitor.hpp | 0 .../cpu_monitor/cpu_monitor_base.hpp | 0 .../cpu_monitor/intel_cpu_monitor.hpp | 0 .../cpu_monitor/raspi_cpu_monitor.hpp | 0 .../cpu_monitor/tegra_cpu_monitor.hpp | 0 .../cpu_monitor/unknown_cpu_monitor.hpp | 0 .../gpu_monitor/gpu_monitor_base.hpp | 0 .../gpu_monitor/nvml_gpu_monitor.hpp | 0 .../gpu_monitor/tegra_gpu_monitor.hpp | 0 .../gpu_monitor/unknown_gpu_monitor.hpp | 0 .../hdd_monitor/hdd_monitor.hpp | 0 .../system_monitor/hdd_reader/hdd_reader.hpp | 0 .../mem_monitor/mem_monitor.hpp | 0 .../system_monitor/msr_reader/msr_reader.hpp | 0 .../net_monitor/net_monitor.hpp | 0 .../system_monitor/net_monitor/nl80211.hpp | 0 .../ntp_monitor/ntp_monitor.hpp | 0 .../process_monitor/diag_task.hpp | 0 .../process_monitor/process_monitor.hpp | 0 .../system_monitor/system_monitor_utility.hpp | 0 .../traffic_reader/traffic_reader_common.hpp | 0 .../traffic_reader/traffic_reader_service.hpp | 0 .../voltage_monitor/voltage_monitor.hpp | 0 .../launch/system_monitor.launch.xml | 32 +++++++++--------- .../package.xml | 3 +- .../reader/hdd_reader/hdd_reader.cpp | 0 .../reader/msr_reader/msr_reader.cpp | 0 .../traffic_reader/traffic_reader_main.cpp | 0 .../traffic_reader/traffic_reader_service.cpp | 0 .../src/cpu_monitor/arm_cpu_monitor.cpp | 0 .../src/cpu_monitor/cpu_monitor_base.cpp | 0 .../src/cpu_monitor/intel_cpu_monitor.cpp | 0 .../src/cpu_monitor/raspi_cpu_monitor.cpp | 0 .../src/cpu_monitor/tegra_cpu_monitor.cpp | 0 .../src/cpu_monitor/unknown_cpu_monitor.cpp | 0 .../src/gpu_monitor/gpu_monitor_base.cpp | 0 .../src/gpu_monitor/nvml_gpu_monitor.cpp | 0 .../src/gpu_monitor/tegra_gpu_monitor.cpp | 0 .../src/gpu_monitor/unknown_gpu_monitor.cpp | 0 .../src/hdd_monitor/hdd_monitor.cpp | 0 .../src/mem_monitor/mem_monitor.cpp | 0 .../src/net_monitor/net_monitor.cpp | 0 .../src/net_monitor/nl80211.cpp | 0 .../src/ntp_monitor/ntp_monitor.cpp | 0 .../src/process_monitor/process_monitor.cpp | 0 .../src/voltage_monitor/voltage_monitor.cpp | 0 .../test/config/test_hdd_monitor.param.yaml | 0 .../test/config/test_net_monitor.param.yaml | 0 .../test/config/test_ntp_monitor.param.yaml | 0 .../test/src/cpu_monitor/mpstat1.cpp | 0 .../test/src/cpu_monitor/mpstat2.cpp | 0 .../src/cpu_monitor/test_arm_cpu_monitor.cpp | 0 .../cpu_monitor/test_intel_cpu_monitor.cpp | 0 .../cpu_monitor/test_raspi_cpu_monitor.cpp | 0 .../cpu_monitor/test_tegra_cpu_monitor.cpp | 0 .../cpu_monitor/test_unknown_cpu_monitor.cpp | 0 .../src/gpu_monitor/test_nvml_gpu_monitor.cpp | 0 .../gpu_monitor/test_tegra_gpu_monitor.cpp | 0 .../gpu_monitor/test_unknown_gpu_monitor.cpp | 0 .../test/src/hdd_monitor/df1.cpp | 0 .../test/src/hdd_monitor/test_hdd_monitor.cpp | 0 .../test/src/mem_monitor/free1.cpp | 0 .../test/src/mem_monitor/test_mem_monitor.cpp | 0 .../test/src/net_monitor/test_net_monitor.cpp | 0 .../test/src/ntp_monitor/ntpdate1.cpp | 0 .../test/src/ntp_monitor/test_ntp_monitor.cpp | 0 .../test/src/process_monitor/echo1.cpp | 0 .../test/src/process_monitor/sed1.cpp | 0 .../test/src/process_monitor/sort1.cpp | 0 .../process_monitor/test_process_monitor.cpp | 0 .../test/src/process_monitor/top1.cpp | 0 .../test/src/process_monitor/top2.cpp | 0 .../test/src/process_monitor/top3.cpp | 0 116 files changed, 24 insertions(+), 23 deletions(-) rename system/{system_monitor => autoware_system_monitor}/CHANGELOG.rst (100%) rename system/{system_monitor => autoware_system_monitor}/CMakeLists.txt (99%) rename system/{system_monitor => autoware_system_monitor}/README.md (99%) rename system/{system_monitor => autoware_system_monitor}/cmake/FindNVML.cmake (100%) rename system/{system_monitor => autoware_system_monitor}/config/cpu_monitor.param.yaml (100%) rename system/{system_monitor => autoware_system_monitor}/config/gpu_monitor.param.yaml (100%) rename system/{system_monitor => autoware_system_monitor}/config/hdd_monitor.param.yaml (100%) rename system/{system_monitor => autoware_system_monitor}/config/mem_monitor.param.yaml (100%) rename system/{system_monitor => autoware_system_monitor}/config/net_monitor.param.yaml (100%) rename system/{system_monitor => autoware_system_monitor}/config/ntp_monitor.param.yaml (100%) rename system/{system_monitor => autoware_system_monitor}/config/process_monitor.param.yaml (100%) rename system/{system_monitor => autoware_system_monitor}/config/voltage_monitor.param.yaml (100%) rename system/{system_monitor => autoware_system_monitor}/docs/class_diagrams.md (100%) rename system/{system_monitor => autoware_system_monitor}/docs/hdd_reader.md (100%) rename system/{system_monitor => autoware_system_monitor}/docs/images/class_cpu_monitor.png (100%) rename system/{system_monitor => autoware_system_monitor}/docs/images/class_gpu_monitor.png (100%) rename system/{system_monitor => autoware_system_monitor}/docs/images/class_hdd_monitor.png (100%) rename system/{system_monitor => autoware_system_monitor}/docs/images/class_mem_monitor.png (100%) rename system/{system_monitor => autoware_system_monitor}/docs/images/class_net_monitor.png (100%) rename system/{system_monitor => autoware_system_monitor}/docs/images/class_ntp_monitor.png (100%) rename system/{system_monitor => autoware_system_monitor}/docs/images/class_process_monitor.png (100%) rename system/{system_monitor => autoware_system_monitor}/docs/images/seq_cpu_monitor.png (100%) rename system/{system_monitor => autoware_system_monitor}/docs/images/seq_gpu_monitor.png (100%) rename system/{system_monitor => autoware_system_monitor}/docs/images/seq_hdd_monitor.png (100%) rename system/{system_monitor => autoware_system_monitor}/docs/images/seq_mem_monitor.png (100%) rename system/{system_monitor => autoware_system_monitor}/docs/images/seq_net_monitor.png (100%) rename system/{system_monitor => autoware_system_monitor}/docs/images/seq_ntp_monitor.png (100%) rename system/{system_monitor => autoware_system_monitor}/docs/images/seq_process_monitor.png (100%) rename system/{system_monitor => autoware_system_monitor}/docs/msr_reader.md (100%) rename system/{system_monitor => autoware_system_monitor}/docs/ros_parameters.md (100%) rename system/{system_monitor => autoware_system_monitor}/docs/seq_diagrams.md (100%) rename system/{system_monitor => autoware_system_monitor}/docs/topics_cpu_monitor.md (100%) rename system/{system_monitor => autoware_system_monitor}/docs/topics_gpu_monitor.md (100%) rename system/{system_monitor => autoware_system_monitor}/docs/topics_hdd_monitor.md (100%) rename system/{system_monitor => autoware_system_monitor}/docs/topics_mem_monitor.md (100%) rename system/{system_monitor => autoware_system_monitor}/docs/topics_net_monitor.md (100%) rename system/{system_monitor => autoware_system_monitor}/docs/topics_ntp_monitor.md (100%) rename system/{system_monitor => autoware_system_monitor}/docs/topics_process_monitor.md (100%) rename system/{system_monitor => autoware_system_monitor}/docs/topics_voltage_monitor.md (100%) rename system/{system_monitor => autoware_system_monitor}/docs/traffic_reader.md (100%) rename system/{system_monitor => autoware_system_monitor}/include/system_monitor/cpu_monitor/arm_cpu_monitor.hpp (100%) rename system/{system_monitor => autoware_system_monitor}/include/system_monitor/cpu_monitor/cpu_monitor_base.hpp (100%) rename system/{system_monitor => autoware_system_monitor}/include/system_monitor/cpu_monitor/intel_cpu_monitor.hpp (100%) rename system/{system_monitor => autoware_system_monitor}/include/system_monitor/cpu_monitor/raspi_cpu_monitor.hpp (100%) rename system/{system_monitor => autoware_system_monitor}/include/system_monitor/cpu_monitor/tegra_cpu_monitor.hpp (100%) rename system/{system_monitor => autoware_system_monitor}/include/system_monitor/cpu_monitor/unknown_cpu_monitor.hpp (100%) rename system/{system_monitor => autoware_system_monitor}/include/system_monitor/gpu_monitor/gpu_monitor_base.hpp (100%) rename system/{system_monitor => autoware_system_monitor}/include/system_monitor/gpu_monitor/nvml_gpu_monitor.hpp (100%) rename system/{system_monitor => autoware_system_monitor}/include/system_monitor/gpu_monitor/tegra_gpu_monitor.hpp (100%) rename system/{system_monitor => autoware_system_monitor}/include/system_monitor/gpu_monitor/unknown_gpu_monitor.hpp (100%) rename system/{system_monitor => autoware_system_monitor}/include/system_monitor/hdd_monitor/hdd_monitor.hpp (100%) rename system/{system_monitor => autoware_system_monitor}/include/system_monitor/hdd_reader/hdd_reader.hpp (100%) rename system/{system_monitor => autoware_system_monitor}/include/system_monitor/mem_monitor/mem_monitor.hpp (100%) rename system/{system_monitor => autoware_system_monitor}/include/system_monitor/msr_reader/msr_reader.hpp (100%) rename system/{system_monitor => autoware_system_monitor}/include/system_monitor/net_monitor/net_monitor.hpp (100%) rename system/{system_monitor => autoware_system_monitor}/include/system_monitor/net_monitor/nl80211.hpp (100%) rename system/{system_monitor => autoware_system_monitor}/include/system_monitor/ntp_monitor/ntp_monitor.hpp (100%) rename system/{system_monitor => autoware_system_monitor}/include/system_monitor/process_monitor/diag_task.hpp (100%) rename system/{system_monitor => autoware_system_monitor}/include/system_monitor/process_monitor/process_monitor.hpp (100%) rename system/{system_monitor => autoware_system_monitor}/include/system_monitor/system_monitor_utility.hpp (100%) rename system/{system_monitor => autoware_system_monitor}/include/system_monitor/traffic_reader/traffic_reader_common.hpp (100%) rename system/{system_monitor => autoware_system_monitor}/include/system_monitor/traffic_reader/traffic_reader_service.hpp (100%) rename system/{system_monitor => autoware_system_monitor}/include/system_monitor/voltage_monitor/voltage_monitor.hpp (100%) rename system/{system_monitor => autoware_system_monitor}/launch/system_monitor.launch.xml (52%) rename system/{system_monitor => autoware_system_monitor}/package.xml (92%) rename system/{system_monitor => autoware_system_monitor}/reader/hdd_reader/hdd_reader.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/reader/msr_reader/msr_reader.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/reader/traffic_reader/traffic_reader_main.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/reader/traffic_reader/traffic_reader_service.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/src/cpu_monitor/arm_cpu_monitor.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/src/cpu_monitor/cpu_monitor_base.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/src/cpu_monitor/intel_cpu_monitor.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/src/cpu_monitor/raspi_cpu_monitor.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/src/cpu_monitor/tegra_cpu_monitor.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/src/cpu_monitor/unknown_cpu_monitor.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/src/gpu_monitor/gpu_monitor_base.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/src/gpu_monitor/nvml_gpu_monitor.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/src/gpu_monitor/tegra_gpu_monitor.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/src/gpu_monitor/unknown_gpu_monitor.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/src/hdd_monitor/hdd_monitor.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/src/mem_monitor/mem_monitor.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/src/net_monitor/net_monitor.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/src/net_monitor/nl80211.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/src/ntp_monitor/ntp_monitor.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/src/process_monitor/process_monitor.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/src/voltage_monitor/voltage_monitor.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/test/config/test_hdd_monitor.param.yaml (100%) rename system/{system_monitor => autoware_system_monitor}/test/config/test_net_monitor.param.yaml (100%) rename system/{system_monitor => autoware_system_monitor}/test/config/test_ntp_monitor.param.yaml (100%) rename system/{system_monitor => autoware_system_monitor}/test/src/cpu_monitor/mpstat1.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/test/src/cpu_monitor/mpstat2.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/test/src/cpu_monitor/test_arm_cpu_monitor.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/test/src/cpu_monitor/test_intel_cpu_monitor.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/test/src/cpu_monitor/test_raspi_cpu_monitor.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/test/src/cpu_monitor/test_tegra_cpu_monitor.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/test/src/cpu_monitor/test_unknown_cpu_monitor.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/test/src/gpu_monitor/test_nvml_gpu_monitor.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/test/src/gpu_monitor/test_tegra_gpu_monitor.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/test/src/gpu_monitor/test_unknown_gpu_monitor.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/test/src/hdd_monitor/df1.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/test/src/hdd_monitor/test_hdd_monitor.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/test/src/mem_monitor/free1.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/test/src/mem_monitor/test_mem_monitor.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/test/src/net_monitor/test_net_monitor.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/test/src/ntp_monitor/ntpdate1.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/test/src/ntp_monitor/test_ntp_monitor.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/test/src/process_monitor/echo1.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/test/src/process_monitor/sed1.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/test/src/process_monitor/sort1.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/test/src/process_monitor/test_process_monitor.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/test/src/process_monitor/top1.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/test/src/process_monitor/top2.cpp (100%) rename system/{system_monitor => autoware_system_monitor}/test/src/process_monitor/top3.cpp (100%) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index fafe8432a51ba..f51691a02e6d2 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -61,7 +61,7 @@ launch/tier4_perception_launch/** shunsuke.miura@tier4.jp taekjin.lee@tier4.jp y launch/tier4_planning_launch/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zhe.shen@tier4.jp zulfaqar.azmi@tier4.jp launch/tier4_sensing_launch/** yukihiro.saito@tier4.jp launch/tier4_simulator_launch/** keisuke.shima@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp -launch/tier4_system_launch/** fumihito.ito@tier4.jp tetsuhiro.kawaguchi@tier4.jp +launch/tier4_system_launch/** fumihito.ito@tier4.jp tetsuhiro.kawaguchi@tier4.jp junya.sasaki@tier4.jp launch/tier4_vehicle_launch/** yukihiro.saito@tier4.jp localization/autoware_ekf_localizer/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp takamasa.horibe@tier4.jp takeshi.ishita@tier4.jp yamato.ando@tier4.jp localization/autoware_geo_pose_projector/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp @@ -225,7 +225,7 @@ system/autoware_mrm_comfortable_stop_operator/** makoto.kurihara@tier4.jp tomohi system/mrm_emergency_stop_operator/** makoto.kurihara@tier4.jp tomohito.ando@tier4.jp system/mrm_handler/** makoto.kurihara@tier4.jp ryuta.kambe@tier4.jp tetsuhiro.kawaguchi@tier4.jp system/system_diagnostic_monitor/** isamu.takagi@tier4.jp -system/system_monitor/** fumihito.ito@tier4.jp tetsuhiro.kawaguchi@tier4.jp +system/autoware_system_monitor/** fumihito.ito@tier4.jp tetsuhiro.kawaguchi@tier4.jp junya.sasaki@tier4.jp system/topic_state_monitor/** ryohsuke.mitsudome@tier4.jp system/velodyne_monitor/** fumihito.ito@tier4.jp tools/reaction_analyzer/** berkay@leodrive.ai diff --git a/launch/tier4_system_launch/launch/system.launch.xml b/launch/tier4_system_launch/launch/system.launch.xml index 7b7d192dd1879..19823b96b082e 100644 --- a/launch/tier4_system_launch/launch/system.launch.xml +++ b/launch/tier4_system_launch/launch/system.launch.xml @@ -39,7 +39,7 @@ - + diff --git a/launch/tier4_system_launch/package.xml b/launch/tier4_system_launch/package.xml index 9f5678b937dbc..fd76fd52a0f29 100644 --- a/launch/tier4_system_launch/package.xml +++ b/launch/tier4_system_launch/package.xml @@ -11,8 +11,8 @@ ament_cmake_auto autoware_cmake + autoware_system_monitor component_state_monitor - system_monitor ament_lint_auto autoware_lint_common diff --git a/system/system_monitor/CHANGELOG.rst b/system/autoware_system_monitor/CHANGELOG.rst similarity index 100% rename from system/system_monitor/CHANGELOG.rst rename to system/autoware_system_monitor/CHANGELOG.rst diff --git a/system/system_monitor/CMakeLists.txt b/system/autoware_system_monitor/CMakeLists.txt similarity index 99% rename from system/system_monitor/CMakeLists.txt rename to system/autoware_system_monitor/CMakeLists.txt index be3f8fadc8a81..cb6b8197ae03a 100644 --- a/system/system_monitor/CMakeLists.txt +++ b/system/autoware_system_monitor/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(system_monitor) +project(autoware_system_monitor) find_package(autoware_cmake REQUIRED) autoware_package() diff --git a/system/system_monitor/README.md b/system/autoware_system_monitor/README.md similarity index 99% rename from system/system_monitor/README.md rename to system/autoware_system_monitor/README.md index d00c57c895279..06b79422f833e 100644 --- a/system/system_monitor/README.md +++ b/system/autoware_system_monitor/README.md @@ -33,7 +33,7 @@ Use colcon build and launch in the same way as other packages. ```sh colcon build source install/setup.bash -ros2 launch system_monitor system_monitor.launch.xml +ros2 launch autoware_system_monitor system_monitor.launch.xml ``` CPU and GPU monitoring method differs depending on platform.
diff --git a/system/system_monitor/cmake/FindNVML.cmake b/system/autoware_system_monitor/cmake/FindNVML.cmake similarity index 100% rename from system/system_monitor/cmake/FindNVML.cmake rename to system/autoware_system_monitor/cmake/FindNVML.cmake diff --git a/system/system_monitor/config/cpu_monitor.param.yaml b/system/autoware_system_monitor/config/cpu_monitor.param.yaml similarity index 100% rename from system/system_monitor/config/cpu_monitor.param.yaml rename to system/autoware_system_monitor/config/cpu_monitor.param.yaml diff --git a/system/system_monitor/config/gpu_monitor.param.yaml b/system/autoware_system_monitor/config/gpu_monitor.param.yaml similarity index 100% rename from system/system_monitor/config/gpu_monitor.param.yaml rename to system/autoware_system_monitor/config/gpu_monitor.param.yaml diff --git a/system/system_monitor/config/hdd_monitor.param.yaml b/system/autoware_system_monitor/config/hdd_monitor.param.yaml similarity index 100% rename from system/system_monitor/config/hdd_monitor.param.yaml rename to system/autoware_system_monitor/config/hdd_monitor.param.yaml diff --git a/system/system_monitor/config/mem_monitor.param.yaml b/system/autoware_system_monitor/config/mem_monitor.param.yaml similarity index 100% rename from system/system_monitor/config/mem_monitor.param.yaml rename to system/autoware_system_monitor/config/mem_monitor.param.yaml diff --git a/system/system_monitor/config/net_monitor.param.yaml b/system/autoware_system_monitor/config/net_monitor.param.yaml similarity index 100% rename from system/system_monitor/config/net_monitor.param.yaml rename to system/autoware_system_monitor/config/net_monitor.param.yaml diff --git a/system/system_monitor/config/ntp_monitor.param.yaml b/system/autoware_system_monitor/config/ntp_monitor.param.yaml similarity index 100% rename from system/system_monitor/config/ntp_monitor.param.yaml rename to system/autoware_system_monitor/config/ntp_monitor.param.yaml diff --git a/system/system_monitor/config/process_monitor.param.yaml b/system/autoware_system_monitor/config/process_monitor.param.yaml similarity index 100% rename from system/system_monitor/config/process_monitor.param.yaml rename to system/autoware_system_monitor/config/process_monitor.param.yaml diff --git a/system/system_monitor/config/voltage_monitor.param.yaml b/system/autoware_system_monitor/config/voltage_monitor.param.yaml similarity index 100% rename from system/system_monitor/config/voltage_monitor.param.yaml rename to system/autoware_system_monitor/config/voltage_monitor.param.yaml diff --git a/system/system_monitor/docs/class_diagrams.md b/system/autoware_system_monitor/docs/class_diagrams.md similarity index 100% rename from system/system_monitor/docs/class_diagrams.md rename to system/autoware_system_monitor/docs/class_diagrams.md diff --git a/system/system_monitor/docs/hdd_reader.md b/system/autoware_system_monitor/docs/hdd_reader.md similarity index 100% rename from system/system_monitor/docs/hdd_reader.md rename to system/autoware_system_monitor/docs/hdd_reader.md diff --git a/system/system_monitor/docs/images/class_cpu_monitor.png b/system/autoware_system_monitor/docs/images/class_cpu_monitor.png similarity index 100% rename from system/system_monitor/docs/images/class_cpu_monitor.png rename to system/autoware_system_monitor/docs/images/class_cpu_monitor.png diff --git a/system/system_monitor/docs/images/class_gpu_monitor.png b/system/autoware_system_monitor/docs/images/class_gpu_monitor.png similarity index 100% rename from system/system_monitor/docs/images/class_gpu_monitor.png rename to system/autoware_system_monitor/docs/images/class_gpu_monitor.png diff --git a/system/system_monitor/docs/images/class_hdd_monitor.png b/system/autoware_system_monitor/docs/images/class_hdd_monitor.png similarity index 100% rename from system/system_monitor/docs/images/class_hdd_monitor.png rename to system/autoware_system_monitor/docs/images/class_hdd_monitor.png diff --git a/system/system_monitor/docs/images/class_mem_monitor.png b/system/autoware_system_monitor/docs/images/class_mem_monitor.png similarity index 100% rename from system/system_monitor/docs/images/class_mem_monitor.png rename to system/autoware_system_monitor/docs/images/class_mem_monitor.png diff --git a/system/system_monitor/docs/images/class_net_monitor.png b/system/autoware_system_monitor/docs/images/class_net_monitor.png similarity index 100% rename from system/system_monitor/docs/images/class_net_monitor.png rename to system/autoware_system_monitor/docs/images/class_net_monitor.png diff --git a/system/system_monitor/docs/images/class_ntp_monitor.png b/system/autoware_system_monitor/docs/images/class_ntp_monitor.png similarity index 100% rename from system/system_monitor/docs/images/class_ntp_monitor.png rename to system/autoware_system_monitor/docs/images/class_ntp_monitor.png diff --git a/system/system_monitor/docs/images/class_process_monitor.png b/system/autoware_system_monitor/docs/images/class_process_monitor.png similarity index 100% rename from system/system_monitor/docs/images/class_process_monitor.png rename to system/autoware_system_monitor/docs/images/class_process_monitor.png diff --git a/system/system_monitor/docs/images/seq_cpu_monitor.png b/system/autoware_system_monitor/docs/images/seq_cpu_monitor.png similarity index 100% rename from system/system_monitor/docs/images/seq_cpu_monitor.png rename to system/autoware_system_monitor/docs/images/seq_cpu_monitor.png diff --git a/system/system_monitor/docs/images/seq_gpu_monitor.png b/system/autoware_system_monitor/docs/images/seq_gpu_monitor.png similarity index 100% rename from system/system_monitor/docs/images/seq_gpu_monitor.png rename to system/autoware_system_monitor/docs/images/seq_gpu_monitor.png diff --git a/system/system_monitor/docs/images/seq_hdd_monitor.png b/system/autoware_system_monitor/docs/images/seq_hdd_monitor.png similarity index 100% rename from system/system_monitor/docs/images/seq_hdd_monitor.png rename to system/autoware_system_monitor/docs/images/seq_hdd_monitor.png diff --git a/system/system_monitor/docs/images/seq_mem_monitor.png b/system/autoware_system_monitor/docs/images/seq_mem_monitor.png similarity index 100% rename from system/system_monitor/docs/images/seq_mem_monitor.png rename to system/autoware_system_monitor/docs/images/seq_mem_monitor.png diff --git a/system/system_monitor/docs/images/seq_net_monitor.png b/system/autoware_system_monitor/docs/images/seq_net_monitor.png similarity index 100% rename from system/system_monitor/docs/images/seq_net_monitor.png rename to system/autoware_system_monitor/docs/images/seq_net_monitor.png diff --git a/system/system_monitor/docs/images/seq_ntp_monitor.png b/system/autoware_system_monitor/docs/images/seq_ntp_monitor.png similarity index 100% rename from system/system_monitor/docs/images/seq_ntp_monitor.png rename to system/autoware_system_monitor/docs/images/seq_ntp_monitor.png diff --git a/system/system_monitor/docs/images/seq_process_monitor.png b/system/autoware_system_monitor/docs/images/seq_process_monitor.png similarity index 100% rename from system/system_monitor/docs/images/seq_process_monitor.png rename to system/autoware_system_monitor/docs/images/seq_process_monitor.png diff --git a/system/system_monitor/docs/msr_reader.md b/system/autoware_system_monitor/docs/msr_reader.md similarity index 100% rename from system/system_monitor/docs/msr_reader.md rename to system/autoware_system_monitor/docs/msr_reader.md diff --git a/system/system_monitor/docs/ros_parameters.md b/system/autoware_system_monitor/docs/ros_parameters.md similarity index 100% rename from system/system_monitor/docs/ros_parameters.md rename to system/autoware_system_monitor/docs/ros_parameters.md diff --git a/system/system_monitor/docs/seq_diagrams.md b/system/autoware_system_monitor/docs/seq_diagrams.md similarity index 100% rename from system/system_monitor/docs/seq_diagrams.md rename to system/autoware_system_monitor/docs/seq_diagrams.md diff --git a/system/system_monitor/docs/topics_cpu_monitor.md b/system/autoware_system_monitor/docs/topics_cpu_monitor.md similarity index 100% rename from system/system_monitor/docs/topics_cpu_monitor.md rename to system/autoware_system_monitor/docs/topics_cpu_monitor.md diff --git a/system/system_monitor/docs/topics_gpu_monitor.md b/system/autoware_system_monitor/docs/topics_gpu_monitor.md similarity index 100% rename from system/system_monitor/docs/topics_gpu_monitor.md rename to system/autoware_system_monitor/docs/topics_gpu_monitor.md diff --git a/system/system_monitor/docs/topics_hdd_monitor.md b/system/autoware_system_monitor/docs/topics_hdd_monitor.md similarity index 100% rename from system/system_monitor/docs/topics_hdd_monitor.md rename to system/autoware_system_monitor/docs/topics_hdd_monitor.md diff --git a/system/system_monitor/docs/topics_mem_monitor.md b/system/autoware_system_monitor/docs/topics_mem_monitor.md similarity index 100% rename from system/system_monitor/docs/topics_mem_monitor.md rename to system/autoware_system_monitor/docs/topics_mem_monitor.md diff --git a/system/system_monitor/docs/topics_net_monitor.md b/system/autoware_system_monitor/docs/topics_net_monitor.md similarity index 100% rename from system/system_monitor/docs/topics_net_monitor.md rename to system/autoware_system_monitor/docs/topics_net_monitor.md diff --git a/system/system_monitor/docs/topics_ntp_monitor.md b/system/autoware_system_monitor/docs/topics_ntp_monitor.md similarity index 100% rename from system/system_monitor/docs/topics_ntp_monitor.md rename to system/autoware_system_monitor/docs/topics_ntp_monitor.md diff --git a/system/system_monitor/docs/topics_process_monitor.md b/system/autoware_system_monitor/docs/topics_process_monitor.md similarity index 100% rename from system/system_monitor/docs/topics_process_monitor.md rename to system/autoware_system_monitor/docs/topics_process_monitor.md diff --git a/system/system_monitor/docs/topics_voltage_monitor.md b/system/autoware_system_monitor/docs/topics_voltage_monitor.md similarity index 100% rename from system/system_monitor/docs/topics_voltage_monitor.md rename to system/autoware_system_monitor/docs/topics_voltage_monitor.md diff --git a/system/system_monitor/docs/traffic_reader.md b/system/autoware_system_monitor/docs/traffic_reader.md similarity index 100% rename from system/system_monitor/docs/traffic_reader.md rename to system/autoware_system_monitor/docs/traffic_reader.md diff --git a/system/system_monitor/include/system_monitor/cpu_monitor/arm_cpu_monitor.hpp b/system/autoware_system_monitor/include/system_monitor/cpu_monitor/arm_cpu_monitor.hpp similarity index 100% rename from system/system_monitor/include/system_monitor/cpu_monitor/arm_cpu_monitor.hpp rename to system/autoware_system_monitor/include/system_monitor/cpu_monitor/arm_cpu_monitor.hpp diff --git a/system/system_monitor/include/system_monitor/cpu_monitor/cpu_monitor_base.hpp b/system/autoware_system_monitor/include/system_monitor/cpu_monitor/cpu_monitor_base.hpp similarity index 100% rename from system/system_monitor/include/system_monitor/cpu_monitor/cpu_monitor_base.hpp rename to system/autoware_system_monitor/include/system_monitor/cpu_monitor/cpu_monitor_base.hpp diff --git a/system/system_monitor/include/system_monitor/cpu_monitor/intel_cpu_monitor.hpp b/system/autoware_system_monitor/include/system_monitor/cpu_monitor/intel_cpu_monitor.hpp similarity index 100% rename from system/system_monitor/include/system_monitor/cpu_monitor/intel_cpu_monitor.hpp rename to system/autoware_system_monitor/include/system_monitor/cpu_monitor/intel_cpu_monitor.hpp diff --git a/system/system_monitor/include/system_monitor/cpu_monitor/raspi_cpu_monitor.hpp b/system/autoware_system_monitor/include/system_monitor/cpu_monitor/raspi_cpu_monitor.hpp similarity index 100% rename from system/system_monitor/include/system_monitor/cpu_monitor/raspi_cpu_monitor.hpp rename to system/autoware_system_monitor/include/system_monitor/cpu_monitor/raspi_cpu_monitor.hpp diff --git a/system/system_monitor/include/system_monitor/cpu_monitor/tegra_cpu_monitor.hpp b/system/autoware_system_monitor/include/system_monitor/cpu_monitor/tegra_cpu_monitor.hpp similarity index 100% rename from system/system_monitor/include/system_monitor/cpu_monitor/tegra_cpu_monitor.hpp rename to system/autoware_system_monitor/include/system_monitor/cpu_monitor/tegra_cpu_monitor.hpp diff --git a/system/system_monitor/include/system_monitor/cpu_monitor/unknown_cpu_monitor.hpp b/system/autoware_system_monitor/include/system_monitor/cpu_monitor/unknown_cpu_monitor.hpp similarity index 100% rename from system/system_monitor/include/system_monitor/cpu_monitor/unknown_cpu_monitor.hpp rename to system/autoware_system_monitor/include/system_monitor/cpu_monitor/unknown_cpu_monitor.hpp diff --git a/system/system_monitor/include/system_monitor/gpu_monitor/gpu_monitor_base.hpp b/system/autoware_system_monitor/include/system_monitor/gpu_monitor/gpu_monitor_base.hpp similarity index 100% rename from system/system_monitor/include/system_monitor/gpu_monitor/gpu_monitor_base.hpp rename to system/autoware_system_monitor/include/system_monitor/gpu_monitor/gpu_monitor_base.hpp diff --git a/system/system_monitor/include/system_monitor/gpu_monitor/nvml_gpu_monitor.hpp b/system/autoware_system_monitor/include/system_monitor/gpu_monitor/nvml_gpu_monitor.hpp similarity index 100% rename from system/system_monitor/include/system_monitor/gpu_monitor/nvml_gpu_monitor.hpp rename to system/autoware_system_monitor/include/system_monitor/gpu_monitor/nvml_gpu_monitor.hpp diff --git a/system/system_monitor/include/system_monitor/gpu_monitor/tegra_gpu_monitor.hpp b/system/autoware_system_monitor/include/system_monitor/gpu_monitor/tegra_gpu_monitor.hpp similarity index 100% rename from system/system_monitor/include/system_monitor/gpu_monitor/tegra_gpu_monitor.hpp rename to system/autoware_system_monitor/include/system_monitor/gpu_monitor/tegra_gpu_monitor.hpp diff --git a/system/system_monitor/include/system_monitor/gpu_monitor/unknown_gpu_monitor.hpp b/system/autoware_system_monitor/include/system_monitor/gpu_monitor/unknown_gpu_monitor.hpp similarity index 100% rename from system/system_monitor/include/system_monitor/gpu_monitor/unknown_gpu_monitor.hpp rename to system/autoware_system_monitor/include/system_monitor/gpu_monitor/unknown_gpu_monitor.hpp diff --git a/system/system_monitor/include/system_monitor/hdd_monitor/hdd_monitor.hpp b/system/autoware_system_monitor/include/system_monitor/hdd_monitor/hdd_monitor.hpp similarity index 100% rename from system/system_monitor/include/system_monitor/hdd_monitor/hdd_monitor.hpp rename to system/autoware_system_monitor/include/system_monitor/hdd_monitor/hdd_monitor.hpp diff --git a/system/system_monitor/include/system_monitor/hdd_reader/hdd_reader.hpp b/system/autoware_system_monitor/include/system_monitor/hdd_reader/hdd_reader.hpp similarity index 100% rename from system/system_monitor/include/system_monitor/hdd_reader/hdd_reader.hpp rename to system/autoware_system_monitor/include/system_monitor/hdd_reader/hdd_reader.hpp diff --git a/system/system_monitor/include/system_monitor/mem_monitor/mem_monitor.hpp b/system/autoware_system_monitor/include/system_monitor/mem_monitor/mem_monitor.hpp similarity index 100% rename from system/system_monitor/include/system_monitor/mem_monitor/mem_monitor.hpp rename to system/autoware_system_monitor/include/system_monitor/mem_monitor/mem_monitor.hpp diff --git a/system/system_monitor/include/system_monitor/msr_reader/msr_reader.hpp b/system/autoware_system_monitor/include/system_monitor/msr_reader/msr_reader.hpp similarity index 100% rename from system/system_monitor/include/system_monitor/msr_reader/msr_reader.hpp rename to system/autoware_system_monitor/include/system_monitor/msr_reader/msr_reader.hpp diff --git a/system/system_monitor/include/system_monitor/net_monitor/net_monitor.hpp b/system/autoware_system_monitor/include/system_monitor/net_monitor/net_monitor.hpp similarity index 100% rename from system/system_monitor/include/system_monitor/net_monitor/net_monitor.hpp rename to system/autoware_system_monitor/include/system_monitor/net_monitor/net_monitor.hpp diff --git a/system/system_monitor/include/system_monitor/net_monitor/nl80211.hpp b/system/autoware_system_monitor/include/system_monitor/net_monitor/nl80211.hpp similarity index 100% rename from system/system_monitor/include/system_monitor/net_monitor/nl80211.hpp rename to system/autoware_system_monitor/include/system_monitor/net_monitor/nl80211.hpp diff --git a/system/system_monitor/include/system_monitor/ntp_monitor/ntp_monitor.hpp b/system/autoware_system_monitor/include/system_monitor/ntp_monitor/ntp_monitor.hpp similarity index 100% rename from system/system_monitor/include/system_monitor/ntp_monitor/ntp_monitor.hpp rename to system/autoware_system_monitor/include/system_monitor/ntp_monitor/ntp_monitor.hpp diff --git a/system/system_monitor/include/system_monitor/process_monitor/diag_task.hpp b/system/autoware_system_monitor/include/system_monitor/process_monitor/diag_task.hpp similarity index 100% rename from system/system_monitor/include/system_monitor/process_monitor/diag_task.hpp rename to system/autoware_system_monitor/include/system_monitor/process_monitor/diag_task.hpp diff --git a/system/system_monitor/include/system_monitor/process_monitor/process_monitor.hpp b/system/autoware_system_monitor/include/system_monitor/process_monitor/process_monitor.hpp similarity index 100% rename from system/system_monitor/include/system_monitor/process_monitor/process_monitor.hpp rename to system/autoware_system_monitor/include/system_monitor/process_monitor/process_monitor.hpp diff --git a/system/system_monitor/include/system_monitor/system_monitor_utility.hpp b/system/autoware_system_monitor/include/system_monitor/system_monitor_utility.hpp similarity index 100% rename from system/system_monitor/include/system_monitor/system_monitor_utility.hpp rename to system/autoware_system_monitor/include/system_monitor/system_monitor_utility.hpp diff --git a/system/system_monitor/include/system_monitor/traffic_reader/traffic_reader_common.hpp b/system/autoware_system_monitor/include/system_monitor/traffic_reader/traffic_reader_common.hpp similarity index 100% rename from system/system_monitor/include/system_monitor/traffic_reader/traffic_reader_common.hpp rename to system/autoware_system_monitor/include/system_monitor/traffic_reader/traffic_reader_common.hpp diff --git a/system/system_monitor/include/system_monitor/traffic_reader/traffic_reader_service.hpp b/system/autoware_system_monitor/include/system_monitor/traffic_reader/traffic_reader_service.hpp similarity index 100% rename from system/system_monitor/include/system_monitor/traffic_reader/traffic_reader_service.hpp rename to system/autoware_system_monitor/include/system_monitor/traffic_reader/traffic_reader_service.hpp diff --git a/system/system_monitor/include/system_monitor/voltage_monitor/voltage_monitor.hpp b/system/autoware_system_monitor/include/system_monitor/voltage_monitor/voltage_monitor.hpp similarity index 100% rename from system/system_monitor/include/system_monitor/voltage_monitor/voltage_monitor.hpp rename to system/autoware_system_monitor/include/system_monitor/voltage_monitor/voltage_monitor.hpp diff --git a/system/system_monitor/launch/system_monitor.launch.xml b/system/autoware_system_monitor/launch/system_monitor.launch.xml similarity index 52% rename from system/system_monitor/launch/system_monitor.launch.xml rename to system/autoware_system_monitor/launch/system_monitor.launch.xml index c6d29dd6b772f..14d1e122801b9 100644 --- a/system/system_monitor/launch/system_monitor.launch.xml +++ b/system/autoware_system_monitor/launch/system_monitor.launch.xml @@ -1,37 +1,37 @@ - - - - - - - - + + + + + + + + - + - + - + - + - + - + - + - + diff --git a/system/system_monitor/package.xml b/system/autoware_system_monitor/package.xml similarity index 92% rename from system/system_monitor/package.xml rename to system/autoware_system_monitor/package.xml index df63dac90551c..23add17adbf6f 100644 --- a/system/system_monitor/package.xml +++ b/system/autoware_system_monitor/package.xml @@ -1,11 +1,12 @@ - system_monitor + autoware_system_monitor 0.40.0 The system_monitor package Fumihito Ito TetsuKawa + Junya Sasaki Apache License 2.0 ament_cmake_auto diff --git a/system/system_monitor/reader/hdd_reader/hdd_reader.cpp b/system/autoware_system_monitor/reader/hdd_reader/hdd_reader.cpp similarity index 100% rename from system/system_monitor/reader/hdd_reader/hdd_reader.cpp rename to system/autoware_system_monitor/reader/hdd_reader/hdd_reader.cpp diff --git a/system/system_monitor/reader/msr_reader/msr_reader.cpp b/system/autoware_system_monitor/reader/msr_reader/msr_reader.cpp similarity index 100% rename from system/system_monitor/reader/msr_reader/msr_reader.cpp rename to system/autoware_system_monitor/reader/msr_reader/msr_reader.cpp diff --git a/system/system_monitor/reader/traffic_reader/traffic_reader_main.cpp b/system/autoware_system_monitor/reader/traffic_reader/traffic_reader_main.cpp similarity index 100% rename from system/system_monitor/reader/traffic_reader/traffic_reader_main.cpp rename to system/autoware_system_monitor/reader/traffic_reader/traffic_reader_main.cpp diff --git a/system/system_monitor/reader/traffic_reader/traffic_reader_service.cpp b/system/autoware_system_monitor/reader/traffic_reader/traffic_reader_service.cpp similarity index 100% rename from system/system_monitor/reader/traffic_reader/traffic_reader_service.cpp rename to system/autoware_system_monitor/reader/traffic_reader/traffic_reader_service.cpp diff --git a/system/system_monitor/src/cpu_monitor/arm_cpu_monitor.cpp b/system/autoware_system_monitor/src/cpu_monitor/arm_cpu_monitor.cpp similarity index 100% rename from system/system_monitor/src/cpu_monitor/arm_cpu_monitor.cpp rename to system/autoware_system_monitor/src/cpu_monitor/arm_cpu_monitor.cpp diff --git a/system/system_monitor/src/cpu_monitor/cpu_monitor_base.cpp b/system/autoware_system_monitor/src/cpu_monitor/cpu_monitor_base.cpp similarity index 100% rename from system/system_monitor/src/cpu_monitor/cpu_monitor_base.cpp rename to system/autoware_system_monitor/src/cpu_monitor/cpu_monitor_base.cpp diff --git a/system/system_monitor/src/cpu_monitor/intel_cpu_monitor.cpp b/system/autoware_system_monitor/src/cpu_monitor/intel_cpu_monitor.cpp similarity index 100% rename from system/system_monitor/src/cpu_monitor/intel_cpu_monitor.cpp rename to system/autoware_system_monitor/src/cpu_monitor/intel_cpu_monitor.cpp diff --git a/system/system_monitor/src/cpu_monitor/raspi_cpu_monitor.cpp b/system/autoware_system_monitor/src/cpu_monitor/raspi_cpu_monitor.cpp similarity index 100% rename from system/system_monitor/src/cpu_monitor/raspi_cpu_monitor.cpp rename to system/autoware_system_monitor/src/cpu_monitor/raspi_cpu_monitor.cpp diff --git a/system/system_monitor/src/cpu_monitor/tegra_cpu_monitor.cpp b/system/autoware_system_monitor/src/cpu_monitor/tegra_cpu_monitor.cpp similarity index 100% rename from system/system_monitor/src/cpu_monitor/tegra_cpu_monitor.cpp rename to system/autoware_system_monitor/src/cpu_monitor/tegra_cpu_monitor.cpp diff --git a/system/system_monitor/src/cpu_monitor/unknown_cpu_monitor.cpp b/system/autoware_system_monitor/src/cpu_monitor/unknown_cpu_monitor.cpp similarity index 100% rename from system/system_monitor/src/cpu_monitor/unknown_cpu_monitor.cpp rename to system/autoware_system_monitor/src/cpu_monitor/unknown_cpu_monitor.cpp diff --git a/system/system_monitor/src/gpu_monitor/gpu_monitor_base.cpp b/system/autoware_system_monitor/src/gpu_monitor/gpu_monitor_base.cpp similarity index 100% rename from system/system_monitor/src/gpu_monitor/gpu_monitor_base.cpp rename to system/autoware_system_monitor/src/gpu_monitor/gpu_monitor_base.cpp diff --git a/system/system_monitor/src/gpu_monitor/nvml_gpu_monitor.cpp b/system/autoware_system_monitor/src/gpu_monitor/nvml_gpu_monitor.cpp similarity index 100% rename from system/system_monitor/src/gpu_monitor/nvml_gpu_monitor.cpp rename to system/autoware_system_monitor/src/gpu_monitor/nvml_gpu_monitor.cpp diff --git a/system/system_monitor/src/gpu_monitor/tegra_gpu_monitor.cpp b/system/autoware_system_monitor/src/gpu_monitor/tegra_gpu_monitor.cpp similarity index 100% rename from system/system_monitor/src/gpu_monitor/tegra_gpu_monitor.cpp rename to system/autoware_system_monitor/src/gpu_monitor/tegra_gpu_monitor.cpp diff --git a/system/system_monitor/src/gpu_monitor/unknown_gpu_monitor.cpp b/system/autoware_system_monitor/src/gpu_monitor/unknown_gpu_monitor.cpp similarity index 100% rename from system/system_monitor/src/gpu_monitor/unknown_gpu_monitor.cpp rename to system/autoware_system_monitor/src/gpu_monitor/unknown_gpu_monitor.cpp diff --git a/system/system_monitor/src/hdd_monitor/hdd_monitor.cpp b/system/autoware_system_monitor/src/hdd_monitor/hdd_monitor.cpp similarity index 100% rename from system/system_monitor/src/hdd_monitor/hdd_monitor.cpp rename to system/autoware_system_monitor/src/hdd_monitor/hdd_monitor.cpp diff --git a/system/system_monitor/src/mem_monitor/mem_monitor.cpp b/system/autoware_system_monitor/src/mem_monitor/mem_monitor.cpp similarity index 100% rename from system/system_monitor/src/mem_monitor/mem_monitor.cpp rename to system/autoware_system_monitor/src/mem_monitor/mem_monitor.cpp diff --git a/system/system_monitor/src/net_monitor/net_monitor.cpp b/system/autoware_system_monitor/src/net_monitor/net_monitor.cpp similarity index 100% rename from system/system_monitor/src/net_monitor/net_monitor.cpp rename to system/autoware_system_monitor/src/net_monitor/net_monitor.cpp diff --git a/system/system_monitor/src/net_monitor/nl80211.cpp b/system/autoware_system_monitor/src/net_monitor/nl80211.cpp similarity index 100% rename from system/system_monitor/src/net_monitor/nl80211.cpp rename to system/autoware_system_monitor/src/net_monitor/nl80211.cpp diff --git a/system/system_monitor/src/ntp_monitor/ntp_monitor.cpp b/system/autoware_system_monitor/src/ntp_monitor/ntp_monitor.cpp similarity index 100% rename from system/system_monitor/src/ntp_monitor/ntp_monitor.cpp rename to system/autoware_system_monitor/src/ntp_monitor/ntp_monitor.cpp diff --git a/system/system_monitor/src/process_monitor/process_monitor.cpp b/system/autoware_system_monitor/src/process_monitor/process_monitor.cpp similarity index 100% rename from system/system_monitor/src/process_monitor/process_monitor.cpp rename to system/autoware_system_monitor/src/process_monitor/process_monitor.cpp diff --git a/system/system_monitor/src/voltage_monitor/voltage_monitor.cpp b/system/autoware_system_monitor/src/voltage_monitor/voltage_monitor.cpp similarity index 100% rename from system/system_monitor/src/voltage_monitor/voltage_monitor.cpp rename to system/autoware_system_monitor/src/voltage_monitor/voltage_monitor.cpp diff --git a/system/system_monitor/test/config/test_hdd_monitor.param.yaml b/system/autoware_system_monitor/test/config/test_hdd_monitor.param.yaml similarity index 100% rename from system/system_monitor/test/config/test_hdd_monitor.param.yaml rename to system/autoware_system_monitor/test/config/test_hdd_monitor.param.yaml diff --git a/system/system_monitor/test/config/test_net_monitor.param.yaml b/system/autoware_system_monitor/test/config/test_net_monitor.param.yaml similarity index 100% rename from system/system_monitor/test/config/test_net_monitor.param.yaml rename to system/autoware_system_monitor/test/config/test_net_monitor.param.yaml diff --git a/system/system_monitor/test/config/test_ntp_monitor.param.yaml b/system/autoware_system_monitor/test/config/test_ntp_monitor.param.yaml similarity index 100% rename from system/system_monitor/test/config/test_ntp_monitor.param.yaml rename to system/autoware_system_monitor/test/config/test_ntp_monitor.param.yaml diff --git a/system/system_monitor/test/src/cpu_monitor/mpstat1.cpp b/system/autoware_system_monitor/test/src/cpu_monitor/mpstat1.cpp similarity index 100% rename from system/system_monitor/test/src/cpu_monitor/mpstat1.cpp rename to system/autoware_system_monitor/test/src/cpu_monitor/mpstat1.cpp diff --git a/system/system_monitor/test/src/cpu_monitor/mpstat2.cpp b/system/autoware_system_monitor/test/src/cpu_monitor/mpstat2.cpp similarity index 100% rename from system/system_monitor/test/src/cpu_monitor/mpstat2.cpp rename to system/autoware_system_monitor/test/src/cpu_monitor/mpstat2.cpp diff --git a/system/system_monitor/test/src/cpu_monitor/test_arm_cpu_monitor.cpp b/system/autoware_system_monitor/test/src/cpu_monitor/test_arm_cpu_monitor.cpp similarity index 100% rename from system/system_monitor/test/src/cpu_monitor/test_arm_cpu_monitor.cpp rename to system/autoware_system_monitor/test/src/cpu_monitor/test_arm_cpu_monitor.cpp diff --git a/system/system_monitor/test/src/cpu_monitor/test_intel_cpu_monitor.cpp b/system/autoware_system_monitor/test/src/cpu_monitor/test_intel_cpu_monitor.cpp similarity index 100% rename from system/system_monitor/test/src/cpu_monitor/test_intel_cpu_monitor.cpp rename to system/autoware_system_monitor/test/src/cpu_monitor/test_intel_cpu_monitor.cpp diff --git a/system/system_monitor/test/src/cpu_monitor/test_raspi_cpu_monitor.cpp b/system/autoware_system_monitor/test/src/cpu_monitor/test_raspi_cpu_monitor.cpp similarity index 100% rename from system/system_monitor/test/src/cpu_monitor/test_raspi_cpu_monitor.cpp rename to system/autoware_system_monitor/test/src/cpu_monitor/test_raspi_cpu_monitor.cpp diff --git a/system/system_monitor/test/src/cpu_monitor/test_tegra_cpu_monitor.cpp b/system/autoware_system_monitor/test/src/cpu_monitor/test_tegra_cpu_monitor.cpp similarity index 100% rename from system/system_monitor/test/src/cpu_monitor/test_tegra_cpu_monitor.cpp rename to system/autoware_system_monitor/test/src/cpu_monitor/test_tegra_cpu_monitor.cpp diff --git a/system/system_monitor/test/src/cpu_monitor/test_unknown_cpu_monitor.cpp b/system/autoware_system_monitor/test/src/cpu_monitor/test_unknown_cpu_monitor.cpp similarity index 100% rename from system/system_monitor/test/src/cpu_monitor/test_unknown_cpu_monitor.cpp rename to system/autoware_system_monitor/test/src/cpu_monitor/test_unknown_cpu_monitor.cpp diff --git a/system/system_monitor/test/src/gpu_monitor/test_nvml_gpu_monitor.cpp b/system/autoware_system_monitor/test/src/gpu_monitor/test_nvml_gpu_monitor.cpp similarity index 100% rename from system/system_monitor/test/src/gpu_monitor/test_nvml_gpu_monitor.cpp rename to system/autoware_system_monitor/test/src/gpu_monitor/test_nvml_gpu_monitor.cpp diff --git a/system/system_monitor/test/src/gpu_monitor/test_tegra_gpu_monitor.cpp b/system/autoware_system_monitor/test/src/gpu_monitor/test_tegra_gpu_monitor.cpp similarity index 100% rename from system/system_monitor/test/src/gpu_monitor/test_tegra_gpu_monitor.cpp rename to system/autoware_system_monitor/test/src/gpu_monitor/test_tegra_gpu_monitor.cpp diff --git a/system/system_monitor/test/src/gpu_monitor/test_unknown_gpu_monitor.cpp b/system/autoware_system_monitor/test/src/gpu_monitor/test_unknown_gpu_monitor.cpp similarity index 100% rename from system/system_monitor/test/src/gpu_monitor/test_unknown_gpu_monitor.cpp rename to system/autoware_system_monitor/test/src/gpu_monitor/test_unknown_gpu_monitor.cpp diff --git a/system/system_monitor/test/src/hdd_monitor/df1.cpp b/system/autoware_system_monitor/test/src/hdd_monitor/df1.cpp similarity index 100% rename from system/system_monitor/test/src/hdd_monitor/df1.cpp rename to system/autoware_system_monitor/test/src/hdd_monitor/df1.cpp diff --git a/system/system_monitor/test/src/hdd_monitor/test_hdd_monitor.cpp b/system/autoware_system_monitor/test/src/hdd_monitor/test_hdd_monitor.cpp similarity index 100% rename from system/system_monitor/test/src/hdd_monitor/test_hdd_monitor.cpp rename to system/autoware_system_monitor/test/src/hdd_monitor/test_hdd_monitor.cpp diff --git a/system/system_monitor/test/src/mem_monitor/free1.cpp b/system/autoware_system_monitor/test/src/mem_monitor/free1.cpp similarity index 100% rename from system/system_monitor/test/src/mem_monitor/free1.cpp rename to system/autoware_system_monitor/test/src/mem_monitor/free1.cpp diff --git a/system/system_monitor/test/src/mem_monitor/test_mem_monitor.cpp b/system/autoware_system_monitor/test/src/mem_monitor/test_mem_monitor.cpp similarity index 100% rename from system/system_monitor/test/src/mem_monitor/test_mem_monitor.cpp rename to system/autoware_system_monitor/test/src/mem_monitor/test_mem_monitor.cpp diff --git a/system/system_monitor/test/src/net_monitor/test_net_monitor.cpp b/system/autoware_system_monitor/test/src/net_monitor/test_net_monitor.cpp similarity index 100% rename from system/system_monitor/test/src/net_monitor/test_net_monitor.cpp rename to system/autoware_system_monitor/test/src/net_monitor/test_net_monitor.cpp diff --git a/system/system_monitor/test/src/ntp_monitor/ntpdate1.cpp b/system/autoware_system_monitor/test/src/ntp_monitor/ntpdate1.cpp similarity index 100% rename from system/system_monitor/test/src/ntp_monitor/ntpdate1.cpp rename to system/autoware_system_monitor/test/src/ntp_monitor/ntpdate1.cpp diff --git a/system/system_monitor/test/src/ntp_monitor/test_ntp_monitor.cpp b/system/autoware_system_monitor/test/src/ntp_monitor/test_ntp_monitor.cpp similarity index 100% rename from system/system_monitor/test/src/ntp_monitor/test_ntp_monitor.cpp rename to system/autoware_system_monitor/test/src/ntp_monitor/test_ntp_monitor.cpp diff --git a/system/system_monitor/test/src/process_monitor/echo1.cpp b/system/autoware_system_monitor/test/src/process_monitor/echo1.cpp similarity index 100% rename from system/system_monitor/test/src/process_monitor/echo1.cpp rename to system/autoware_system_monitor/test/src/process_monitor/echo1.cpp diff --git a/system/system_monitor/test/src/process_monitor/sed1.cpp b/system/autoware_system_monitor/test/src/process_monitor/sed1.cpp similarity index 100% rename from system/system_monitor/test/src/process_monitor/sed1.cpp rename to system/autoware_system_monitor/test/src/process_monitor/sed1.cpp diff --git a/system/system_monitor/test/src/process_monitor/sort1.cpp b/system/autoware_system_monitor/test/src/process_monitor/sort1.cpp similarity index 100% rename from system/system_monitor/test/src/process_monitor/sort1.cpp rename to system/autoware_system_monitor/test/src/process_monitor/sort1.cpp diff --git a/system/system_monitor/test/src/process_monitor/test_process_monitor.cpp b/system/autoware_system_monitor/test/src/process_monitor/test_process_monitor.cpp similarity index 100% rename from system/system_monitor/test/src/process_monitor/test_process_monitor.cpp rename to system/autoware_system_monitor/test/src/process_monitor/test_process_monitor.cpp diff --git a/system/system_monitor/test/src/process_monitor/top1.cpp b/system/autoware_system_monitor/test/src/process_monitor/top1.cpp similarity index 100% rename from system/system_monitor/test/src/process_monitor/top1.cpp rename to system/autoware_system_monitor/test/src/process_monitor/top1.cpp diff --git a/system/system_monitor/test/src/process_monitor/top2.cpp b/system/autoware_system_monitor/test/src/process_monitor/top2.cpp similarity index 100% rename from system/system_monitor/test/src/process_monitor/top2.cpp rename to system/autoware_system_monitor/test/src/process_monitor/top2.cpp diff --git a/system/system_monitor/test/src/process_monitor/top3.cpp b/system/autoware_system_monitor/test/src/process_monitor/top3.cpp similarity index 100% rename from system/system_monitor/test/src/process_monitor/top3.cpp rename to system/autoware_system_monitor/test/src/process_monitor/top3.cpp From c97919b0dc308765c94ea5ea1fb1f8244ad6efe4 Mon Sep 17 00:00:00 2001 From: Junya Sasaki Date: Fri, 24 Jan 2025 20:08:58 +0900 Subject: [PATCH 313/334] feat: apply `autoware_` prefix for `bag_time_manager_rviz_plugin` (#9986) Signed-off-by: Junya Sasaki Signed-off-by: Ryohsuke Mitsudome Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: SakodaShintaro Co-authored-by: Ryohsuke Mitsudome --- .../CHANGELOG.rst | 6 +++--- .../CMakeLists.txt | 2 +- .../README.md | 2 +- .../icons/classes/BagTimeManagerPanel.png | Bin .../images/add_bag_time_manager_panel.png | Bin .../images/bag_time_manager_panel.png | Bin .../images/select_panels.png | Bin .../package.xml | 3 ++- .../plugins/plugin_description.xml | 4 ++-- .../src/bag_time_manager_panel.cpp | 9 +++++---- .../src/bag_time_manager_panel.hpp | 6 +++--- 11 files changed, 17 insertions(+), 15 deletions(-) rename visualization/{bag_time_manager_rviz_plugin => autoware_bag_time_manager_rviz_plugin}/CHANGELOG.rst (93%) rename visualization/{bag_time_manager_rviz_plugin => autoware_bag_time_manager_rviz_plugin}/CMakeLists.txt (92%) rename visualization/{bag_time_manager_rviz_plugin => autoware_bag_time_manager_rviz_plugin}/README.md (92%) rename visualization/{bag_time_manager_rviz_plugin => autoware_bag_time_manager_rviz_plugin}/icons/classes/BagTimeManagerPanel.png (100%) rename visualization/{bag_time_manager_rviz_plugin => autoware_bag_time_manager_rviz_plugin}/images/add_bag_time_manager_panel.png (100%) rename visualization/{bag_time_manager_rviz_plugin => autoware_bag_time_manager_rviz_plugin}/images/bag_time_manager_panel.png (100%) rename visualization/{bag_time_manager_rviz_plugin => autoware_bag_time_manager_rviz_plugin}/images/select_panels.png (100%) rename visualization/{bag_time_manager_rviz_plugin => autoware_bag_time_manager_rviz_plugin}/package.xml (88%) rename visualization/{bag_time_manager_rviz_plugin => autoware_bag_time_manager_rviz_plugin}/plugins/plugin_description.xml (52%) rename visualization/{bag_time_manager_rviz_plugin => autoware_bag_time_manager_rviz_plugin}/src/bag_time_manager_panel.cpp (92%) rename visualization/{bag_time_manager_rviz_plugin => autoware_bag_time_manager_rviz_plugin}/src/bag_time_manager_panel.hpp (91%) diff --git a/visualization/bag_time_manager_rviz_plugin/CHANGELOG.rst b/visualization/autoware_bag_time_manager_rviz_plugin/CHANGELOG.rst similarity index 93% rename from visualization/bag_time_manager_rviz_plugin/CHANGELOG.rst rename to visualization/autoware_bag_time_manager_rviz_plugin/CHANGELOG.rst index df222e8eb584e..b9a32e20f76c4 100644 --- a/visualization/bag_time_manager_rviz_plugin/CHANGELOG.rst +++ b/visualization/autoware_bag_time_manager_rviz_plugin/CHANGELOG.rst @@ -1,6 +1,6 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package bag_time_manager_rviz_plugin -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_bag_time_manager_rviz_plugin +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.40.0 (2024-12-12) ------------------- diff --git a/visualization/bag_time_manager_rviz_plugin/CMakeLists.txt b/visualization/autoware_bag_time_manager_rviz_plugin/CMakeLists.txt similarity index 92% rename from visualization/bag_time_manager_rviz_plugin/CMakeLists.txt rename to visualization/autoware_bag_time_manager_rviz_plugin/CMakeLists.txt index ccf9961fc55cc..5ee02349f7d96 100644 --- a/visualization/bag_time_manager_rviz_plugin/CMakeLists.txt +++ b/visualization/autoware_bag_time_manager_rviz_plugin/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(bag_time_manager_rviz_plugin) +project(autoware_bag_time_manager_rviz_plugin) find_package(autoware_cmake REQUIRED) autoware_package() diff --git a/visualization/bag_time_manager_rviz_plugin/README.md b/visualization/autoware_bag_time_manager_rviz_plugin/README.md similarity index 92% rename from visualization/bag_time_manager_rviz_plugin/README.md rename to visualization/autoware_bag_time_manager_rviz_plugin/README.md index 2fad6b2204bb9..58d81d06dffa4 100644 --- a/visualization/bag_time_manager_rviz_plugin/README.md +++ b/visualization/autoware_bag_time_manager_rviz_plugin/README.md @@ -1,4 +1,4 @@ -# bag_time_manager_rviz_plugin +# autoware_bag_time_manager_rviz_plugin ## Purpose diff --git a/visualization/bag_time_manager_rviz_plugin/icons/classes/BagTimeManagerPanel.png b/visualization/autoware_bag_time_manager_rviz_plugin/icons/classes/BagTimeManagerPanel.png similarity index 100% rename from visualization/bag_time_manager_rviz_plugin/icons/classes/BagTimeManagerPanel.png rename to visualization/autoware_bag_time_manager_rviz_plugin/icons/classes/BagTimeManagerPanel.png diff --git a/visualization/bag_time_manager_rviz_plugin/images/add_bag_time_manager_panel.png b/visualization/autoware_bag_time_manager_rviz_plugin/images/add_bag_time_manager_panel.png similarity index 100% rename from visualization/bag_time_manager_rviz_plugin/images/add_bag_time_manager_panel.png rename to visualization/autoware_bag_time_manager_rviz_plugin/images/add_bag_time_manager_panel.png diff --git a/visualization/bag_time_manager_rviz_plugin/images/bag_time_manager_panel.png b/visualization/autoware_bag_time_manager_rviz_plugin/images/bag_time_manager_panel.png similarity index 100% rename from visualization/bag_time_manager_rviz_plugin/images/bag_time_manager_panel.png rename to visualization/autoware_bag_time_manager_rviz_plugin/images/bag_time_manager_panel.png diff --git a/visualization/bag_time_manager_rviz_plugin/images/select_panels.png b/visualization/autoware_bag_time_manager_rviz_plugin/images/select_panels.png similarity index 100% rename from visualization/bag_time_manager_rviz_plugin/images/select_panels.png rename to visualization/autoware_bag_time_manager_rviz_plugin/images/select_panels.png diff --git a/visualization/bag_time_manager_rviz_plugin/package.xml b/visualization/autoware_bag_time_manager_rviz_plugin/package.xml similarity index 88% rename from visualization/bag_time_manager_rviz_plugin/package.xml rename to visualization/autoware_bag_time_manager_rviz_plugin/package.xml index 365dad286d22c..916d1b4674620 100644 --- a/visualization/bag_time_manager_rviz_plugin/package.xml +++ b/visualization/autoware_bag_time_manager_rviz_plugin/package.xml @@ -1,10 +1,11 @@ - bag_time_manager_rviz_plugin + autoware_bag_time_manager_rviz_plugin 0.40.0 Rviz plugin to publish and control the ros bag Taiki Tanaka + Junya Sasaki Apache License 2.0 ament_cmake_auto diff --git a/visualization/bag_time_manager_rviz_plugin/plugins/plugin_description.xml b/visualization/autoware_bag_time_manager_rviz_plugin/plugins/plugin_description.xml similarity index 52% rename from visualization/bag_time_manager_rviz_plugin/plugins/plugin_description.xml rename to visualization/autoware_bag_time_manager_rviz_plugin/plugins/plugin_description.xml index 2a3bbf667b715..f8c678a75b4ee 100644 --- a/visualization/bag_time_manager_rviz_plugin/plugins/plugin_description.xml +++ b/visualization/autoware_bag_time_manager_rviz_plugin/plugins/plugin_description.xml @@ -1,7 +1,7 @@ - + Panel that publishes a service to modify its speed. diff --git a/visualization/bag_time_manager_rviz_plugin/src/bag_time_manager_panel.cpp b/visualization/autoware_bag_time_manager_rviz_plugin/src/bag_time_manager_panel.cpp similarity index 92% rename from visualization/bag_time_manager_rviz_plugin/src/bag_time_manager_panel.cpp rename to visualization/autoware_bag_time_manager_rviz_plugin/src/bag_time_manager_panel.cpp index cae9660b51266..7ab003e2880de 100644 --- a/visualization/bag_time_manager_rviz_plugin/src/bag_time_manager_panel.cpp +++ b/visualization/autoware_bag_time_manager_rviz_plugin/src/bag_time_manager_panel.cpp @@ -1,5 +1,5 @@ // -// Copyright 2022 Tier IV, Inc. All rights reserved. +// Copyright 2025 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. @@ -23,7 +23,7 @@ #include -namespace rviz_plugins +namespace autoware::visualization::bag_time_manager_rviz_plugin { BagTimeManagerPanel::BagTimeManagerPanel(QWidget * parent) : rviz_common::Panel(parent) { @@ -111,7 +111,8 @@ void BagTimeManagerPanel::onApplyRateClicked() } }); } -} // namespace rviz_plugins +} // namespace autoware::visualization::bag_time_manager_rviz_plugin #include -PLUGINLIB_EXPORT_CLASS(rviz_plugins::BagTimeManagerPanel, rviz_common::Panel) +PLUGINLIB_EXPORT_CLASS( + autoware::visualization::bag_time_manager_rviz_plugin::BagTimeManagerPanel, rviz_common::Panel) diff --git a/visualization/bag_time_manager_rviz_plugin/src/bag_time_manager_panel.hpp b/visualization/autoware_bag_time_manager_rviz_plugin/src/bag_time_manager_panel.hpp similarity index 91% rename from visualization/bag_time_manager_rviz_plugin/src/bag_time_manager_panel.hpp rename to visualization/autoware_bag_time_manager_rviz_plugin/src/bag_time_manager_panel.hpp index 2cc4b98a6dabf..710d20046a548 100644 --- a/visualization/bag_time_manager_rviz_plugin/src/bag_time_manager_panel.hpp +++ b/visualization/autoware_bag_time_manager_rviz_plugin/src/bag_time_manager_panel.hpp @@ -1,5 +1,5 @@ // -// Copyright 2022 Tier IV, Inc. All rights reserved. +// Copyright 2025 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. @@ -29,7 +29,7 @@ #include #include -namespace rviz_plugins +namespace autoware::visualization::bag_time_manager_rviz_plugin { using rosbag2_interfaces::srv::Pause; using rosbag2_interfaces::srv::Resume; @@ -67,6 +67,6 @@ protected Q_SLOTS: STATE current_state_{RESUME}; }; -} // namespace rviz_plugins +} // namespace autoware::visualization::bag_time_manager_rviz_plugin #endif // BAG_TIME_MANAGER_PANEL_HPP_ From a838e0614f1a433bcc853d523fd3014a64036953 Mon Sep 17 00:00:00 2001 From: Junya Sasaki Date: Fri, 24 Jan 2025 20:10:56 +0900 Subject: [PATCH 314/334] feat: apply `autoware_` prefix for `dummy_perception_publisher` (#9987) Signed-off-by: Junya Sasaki Signed-off-by: Ryohsuke Mitsudome Signed-off-by: Shintaro Sakoda --- .../launch/perception.launch.xml | 2 +- .../launch/simulator.launch.xml | 4 ++-- launch/tier4_simulator_launch/package.xml | 2 +- .../CHANGELOG.rst | 6 +++--- .../CMakeLists.txt | 18 +++++++++--------- .../README.md | 0 .../dummy_perception_publisher/node.hpp | 10 +++++++--- .../signed_distance_function.hpp | 10 +++++----- .../dummy_perception_publisher.launch.xml | 4 ++-- .../package.xml | 5 +++-- .../src/empty_objects_publisher.cpp | 7 ++++++- .../src/main.cpp | 5 +++-- .../src/node.cpp | 7 ++++++- .../src/pointcloud_creator.cpp | 18 +++++++++--------- .../src/signed_distance_function.cpp | 6 +++--- .../test/src/test_signed_distance_function.cpp | 17 ++++++++++------- 16 files changed, 70 insertions(+), 51 deletions(-) rename simulator/{dummy_perception_publisher => autoware_dummy_perception_publisher}/CHANGELOG.rst (99%) rename simulator/{dummy_perception_publisher => autoware_dummy_perception_publisher}/CMakeLists.txt (70%) rename simulator/{dummy_perception_publisher => autoware_dummy_perception_publisher}/README.md (100%) rename simulator/{dummy_perception_publisher/include => autoware_dummy_perception_publisher/include/autoware}/dummy_perception_publisher/node.hpp (94%) rename simulator/{dummy_perception_publisher/include => autoware_dummy_perception_publisher/include/autoware}/dummy_perception_publisher/signed_distance_function.hpp (85%) rename simulator/{dummy_perception_publisher => autoware_dummy_perception_publisher}/launch/dummy_perception_publisher.launch.xml (90%) rename simulator/{dummy_perception_publisher => autoware_dummy_perception_publisher}/package.xml (85%) rename simulator/{dummy_perception_publisher => autoware_dummy_perception_publisher}/src/empty_objects_publisher.cpp (89%) rename simulator/{dummy_perception_publisher => autoware_dummy_perception_publisher}/src/main.cpp (81%) rename simulator/{dummy_perception_publisher => autoware_dummy_perception_publisher}/src/node.cpp (99%) rename simulator/{dummy_perception_publisher => autoware_dummy_perception_publisher}/src/pointcloud_creator.cpp (96%) rename simulator/{dummy_perception_publisher => autoware_dummy_perception_publisher}/src/signed_distance_function.cpp (94%) rename simulator/{dummy_perception_publisher => autoware_dummy_perception_publisher}/test/src/test_signed_distance_function.cpp (82%) diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index 9f325466ed107..ffa6291257b87 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -287,7 +287,7 @@ - + diff --git a/launch/tier4_simulator_launch/launch/simulator.launch.xml b/launch/tier4_simulator_launch/launch/simulator.launch.xml index e5468b4f22a18..1ff16f2f4fe81 100644 --- a/launch/tier4_simulator_launch/launch/simulator.launch.xml +++ b/launch/tier4_simulator_launch/launch/simulator.launch.xml @@ -47,7 +47,7 @@ - + @@ -111,7 +111,7 @@ - + diff --git a/launch/tier4_simulator_launch/package.xml b/launch/tier4_simulator_launch/package.xml index f12209f4ab3ef..030c7ab143255 100644 --- a/launch/tier4_simulator_launch/package.xml +++ b/launch/tier4_simulator_launch/package.xml @@ -14,9 +14,9 @@ ament_cmake_auto autoware_cmake + autoware_dummy_perception_publisher autoware_fault_injection autoware_simple_planning_simulator - dummy_perception_publisher ament_lint_auto autoware_lint_common diff --git a/simulator/dummy_perception_publisher/CHANGELOG.rst b/simulator/autoware_dummy_perception_publisher/CHANGELOG.rst similarity index 99% rename from simulator/dummy_perception_publisher/CHANGELOG.rst rename to simulator/autoware_dummy_perception_publisher/CHANGELOG.rst index 50b2396ae0311..ada832a084f22 100644 --- a/simulator/dummy_perception_publisher/CHANGELOG.rst +++ b/simulator/autoware_dummy_perception_publisher/CHANGELOG.rst @@ -1,6 +1,6 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package dummy_perception_publisher -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_dummy_perception_publisher +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.40.0 (2024-12-12) ------------------- diff --git a/simulator/dummy_perception_publisher/CMakeLists.txt b/simulator/autoware_dummy_perception_publisher/CMakeLists.txt similarity index 70% rename from simulator/dummy_perception_publisher/CMakeLists.txt rename to simulator/autoware_dummy_perception_publisher/CMakeLists.txt index 0acf4694d03a6..9ac146b182a9a 100644 --- a/simulator/dummy_perception_publisher/CMakeLists.txt +++ b/simulator/autoware_dummy_perception_publisher/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(dummy_perception_publisher) +project(autoware_dummy_perception_publisher) find_package(autoware_cmake REQUIRED) autoware_package() @@ -23,19 +23,19 @@ ament_auto_add_library(signed_distance_function SHARED src/signed_distance_function.cpp ) -ament_auto_add_executable(dummy_perception_publisher_node +ament_auto_add_executable(${PROJECT_NAME}_node src/main.cpp src/node.cpp src/pointcloud_creator.cpp ) -target_link_libraries(dummy_perception_publisher_node +target_link_libraries(${PROJECT_NAME}_node signed_distance_function ) -ament_target_dependencies(dummy_perception_publisher_node ${${PROJECT_NAME}_DEPENDENCIES}) +ament_target_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_DEPENDENCIES}) -target_include_directories(dummy_perception_publisher_node +target_include_directories(${PROJECT_NAME}_node PUBLIC $ $) @@ -43,14 +43,14 @@ target_include_directories(dummy_perception_publisher_node # PCL dependencies - `ament_target_dependencies` doesn't respect the # components/modules selected above and only links in `common` ,so we need # to do this manually. -target_compile_definitions(dummy_perception_publisher_node PRIVATE ${PCL_DEFINITIONS}) -target_include_directories(dummy_perception_publisher_node PRIVATE ${PCL_INCLUDE_DIRS}) +target_compile_definitions(${PROJECT_NAME}_node PRIVATE ${PCL_DEFINITIONS}) +target_include_directories(${PROJECT_NAME}_node PRIVATE ${PCL_INCLUDE_DIRS}) # Unfortunately, this one can't be PRIVATE because only the plain or only the # keyword (PRIVATE) signature of target_link_libraries can be used for one # target, not both. The plain signature is already used inside # `ament_target_dependencies` and possibly rosidl_target_interfaces. -target_link_libraries(dummy_perception_publisher_node ${PCL_LIBRARIES}) -target_link_directories(dummy_perception_publisher_node PRIVATE ${PCL_LIBRARY_DIRS}) +target_link_libraries(${PROJECT_NAME}_node ${PCL_LIBRARIES}) +target_link_directories(${PROJECT_NAME}_node PRIVATE ${PCL_LIBRARY_DIRS}) ament_auto_add_executable(empty_objects_publisher diff --git a/simulator/dummy_perception_publisher/README.md b/simulator/autoware_dummy_perception_publisher/README.md similarity index 100% rename from simulator/dummy_perception_publisher/README.md rename to simulator/autoware_dummy_perception_publisher/README.md diff --git a/simulator/dummy_perception_publisher/include/dummy_perception_publisher/node.hpp b/simulator/autoware_dummy_perception_publisher/include/autoware/dummy_perception_publisher/node.hpp similarity index 94% rename from simulator/dummy_perception_publisher/include/dummy_perception_publisher/node.hpp rename to simulator/autoware_dummy_perception_publisher/include/autoware/dummy_perception_publisher/node.hpp index cf46ecddf516f..413ba4d82b836 100644 --- a/simulator/dummy_perception_publisher/include/dummy_perception_publisher/node.hpp +++ b/simulator/autoware_dummy_perception_publisher/include/autoware/dummy_perception_publisher/node.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef DUMMY_PERCEPTION_PUBLISHER__NODE_HPP_ -#define DUMMY_PERCEPTION_PUBLISHER__NODE_HPP_ +#ifndef AUTOWARE__DUMMY_PERCEPTION_PUBLISHER__NODE_HPP_ +#define AUTOWARE__DUMMY_PERCEPTION_PUBLISHER__NODE_HPP_ #include @@ -41,6 +41,8 @@ #include #include +namespace autoware::dummy_perception_publisher +{ struct ObjectInfo { ObjectInfo( @@ -139,4 +141,6 @@ class DummyPerceptionPublisherNode : public rclcpp::Node ~DummyPerceptionPublisherNode() {} }; -#endif // DUMMY_PERCEPTION_PUBLISHER__NODE_HPP_ +} // namespace autoware::dummy_perception_publisher + +#endif // AUTOWARE__DUMMY_PERCEPTION_PUBLISHER__NODE_HPP_ diff --git a/simulator/dummy_perception_publisher/include/dummy_perception_publisher/signed_distance_function.hpp b/simulator/autoware_dummy_perception_publisher/include/autoware/dummy_perception_publisher/signed_distance_function.hpp similarity index 85% rename from simulator/dummy_perception_publisher/include/dummy_perception_publisher/signed_distance_function.hpp rename to simulator/autoware_dummy_perception_publisher/include/autoware/dummy_perception_publisher/signed_distance_function.hpp index abf24cb8dd4e6..349cbe42ec0bc 100644 --- a/simulator/dummy_perception_publisher/include/dummy_perception_publisher/signed_distance_function.hpp +++ b/simulator/autoware_dummy_perception_publisher/include/autoware/dummy_perception_publisher/signed_distance_function.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef DUMMY_PERCEPTION_PUBLISHER__SIGNED_DISTANCE_FUNCTION_HPP_ -#define DUMMY_PERCEPTION_PUBLISHER__SIGNED_DISTANCE_FUNCTION_HPP_ +#ifndef AUTOWARE__DUMMY_PERCEPTION_PUBLISHER__SIGNED_DISTANCE_FUNCTION_HPP_ +#define AUTOWARE__DUMMY_PERCEPTION_PUBLISHER__SIGNED_DISTANCE_FUNCTION_HPP_ #include @@ -23,7 +23,7 @@ #include #include -namespace signed_distance_function +namespace autoware::dummy_perception_publisher { class AbstractSignedDistanceFunction @@ -69,6 +69,6 @@ class CompositeSDF : public AbstractSignedDistanceFunction std::vector> sdf_ptrs_; }; -} // namespace signed_distance_function +} // namespace autoware::dummy_perception_publisher -#endif // DUMMY_PERCEPTION_PUBLISHER__SIGNED_DISTANCE_FUNCTION_HPP_ +#endif // AUTOWARE__DUMMY_PERCEPTION_PUBLISHER__SIGNED_DISTANCE_FUNCTION_HPP_ diff --git a/simulator/dummy_perception_publisher/launch/dummy_perception_publisher.launch.xml b/simulator/autoware_dummy_perception_publisher/launch/dummy_perception_publisher.launch.xml similarity index 90% rename from simulator/dummy_perception_publisher/launch/dummy_perception_publisher.launch.xml rename to simulator/autoware_dummy_perception_publisher/launch/dummy_perception_publisher.launch.xml index 41025f74cbe50..ed9c38f7dc9b5 100644 --- a/simulator/dummy_perception_publisher/launch/dummy_perception_publisher.launch.xml +++ b/simulator/autoware_dummy_perception_publisher/launch/dummy_perception_publisher.launch.xml @@ -9,7 +9,7 @@ - + @@ -30,7 +30,7 @@ - + diff --git a/simulator/dummy_perception_publisher/package.xml b/simulator/autoware_dummy_perception_publisher/package.xml similarity index 85% rename from simulator/dummy_perception_publisher/package.xml rename to simulator/autoware_dummy_perception_publisher/package.xml index 4f78acd6c07f2..6c75a9b3c0277 100644 --- a/simulator/dummy_perception_publisher/package.xml +++ b/simulator/autoware_dummy_perception_publisher/package.xml @@ -1,10 +1,11 @@ - dummy_perception_publisher + autoware_dummy_perception_publisher 0.40.0 - The dummy_perception_publisher package + The autoware_dummy_perception_publisher package Yukihiro Saito + Junya Sasaki Apache License 2.0 ament_cmake_auto diff --git a/simulator/dummy_perception_publisher/src/empty_objects_publisher.cpp b/simulator/autoware_dummy_perception_publisher/src/empty_objects_publisher.cpp similarity index 89% rename from simulator/dummy_perception_publisher/src/empty_objects_publisher.cpp rename to simulator/autoware_dummy_perception_publisher/src/empty_objects_publisher.cpp index 2d1ea626fb1ac..2a2a1d89ffcb8 100644 --- a/simulator/dummy_perception_publisher/src/empty_objects_publisher.cpp +++ b/simulator/autoware_dummy_perception_publisher/src/empty_objects_publisher.cpp @@ -19,6 +19,9 @@ #include #include +namespace autoware::dummy_perception_publisher +{ + class EmptyObjectsPublisher : public rclcpp::Node { public: @@ -45,10 +48,12 @@ class EmptyObjectsPublisher : public rclcpp::Node } }; +} // namespace autoware::dummy_perception_publisher + int main(int argc, char ** argv) { rclcpp::init(argc, argv); - rclcpp::spin(std::make_shared()); + rclcpp::spin(std::make_shared()); rclcpp::shutdown(); return 0; } diff --git a/simulator/dummy_perception_publisher/src/main.cpp b/simulator/autoware_dummy_perception_publisher/src/main.cpp similarity index 81% rename from simulator/dummy_perception_publisher/src/main.cpp rename to simulator/autoware_dummy_perception_publisher/src/main.cpp index 5e627f2cbc8ed..224074f15f3c5 100644 --- a/simulator/dummy_perception_publisher/src/main.cpp +++ b/simulator/autoware_dummy_perception_publisher/src/main.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "dummy_perception_publisher/node.hpp" +#include "autoware/dummy_perception_publisher/node.hpp" #include @@ -21,7 +21,8 @@ int main(int argc, char ** argv) { rclcpp::init(argc, argv); - rclcpp::spin(std::make_shared()); + rclcpp::spin( + std::make_shared()); rclcpp::shutdown(); return 0; diff --git a/simulator/dummy_perception_publisher/src/node.cpp b/simulator/autoware_dummy_perception_publisher/src/node.cpp similarity index 99% rename from simulator/dummy_perception_publisher/src/node.cpp rename to simulator/autoware_dummy_perception_publisher/src/node.cpp index d72b16d303cec..22797e252813c 100644 --- a/simulator/dummy_perception_publisher/src/node.cpp +++ b/simulator/autoware_dummy_perception_publisher/src/node.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "dummy_perception_publisher/node.hpp" +#include "autoware/dummy_perception_publisher/node.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" @@ -35,6 +35,9 @@ #include #include +namespace autoware::dummy_perception_publisher +{ + using autoware_perception_msgs::msg::TrackedObject; using autoware_perception_msgs::msg::TrackedObjects; @@ -428,3 +431,5 @@ void DummyPerceptionPublisherNode::objectCallback( } } } + +} // namespace autoware::dummy_perception_publisher diff --git a/simulator/dummy_perception_publisher/src/pointcloud_creator.cpp b/simulator/autoware_dummy_perception_publisher/src/pointcloud_creator.cpp similarity index 96% rename from simulator/dummy_perception_publisher/src/pointcloud_creator.cpp rename to simulator/autoware_dummy_perception_publisher/src/pointcloud_creator.cpp index 977336f63eee3..a2f84841e4ff2 100644 --- a/simulator/dummy_perception_publisher/src/pointcloud_creator.cpp +++ b/simulator/autoware_dummy_perception_publisher/src/pointcloud_creator.cpp @@ -1,4 +1,4 @@ -// Copyright 2020 Tier IV, Inc. +// Copyright 2025 Tier IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "dummy_perception_publisher/node.hpp" -#include "dummy_perception_publisher/signed_distance_function.hpp" +#include "autoware/dummy_perception_publisher/node.hpp" +#include "autoware/dummy_perception_publisher/signed_distance_function.hpp" #include @@ -26,7 +26,7 @@ #include #include -namespace +namespace autoware::dummy_perception_publisher { static constexpr double epsilon = 0.001; @@ -45,8 +45,6 @@ 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 @@ -200,13 +198,13 @@ std::vector::Ptr> EgoCentricPointCloudCreator::cr const std::vector & obj_infos, const tf2::Transform & tf_base_link2map, std::mt19937 & random_generator, pcl::PointCloud::Ptr & merged_pointcloud) const { - std::vector> sdf_ptrs; + std::vector> sdf_ptrs; for (const auto & obj_info : obj_infos) { - const auto sdf_ptr = std::make_shared( + const auto sdf_ptr = std::make_shared( obj_info.length, obj_info.width, tf_base_link2map * obj_info.tf_map2moved_object); sdf_ptrs.push_back(sdf_ptr); } - const auto composite_sdf = signed_distance_function::CompositeSDF(sdf_ptrs); + const auto composite_sdf = CompositeSDF(sdf_ptrs); std::vector::Ptr> pointclouds(obj_infos.size()); for (size_t i = 0; i < obj_infos.size(); ++i) { @@ -261,3 +259,5 @@ std::vector::Ptr> EgoCentricPointCloudCreator::cr } return pointclouds; } + +} // namespace autoware::dummy_perception_publisher diff --git a/simulator/dummy_perception_publisher/src/signed_distance_function.cpp b/simulator/autoware_dummy_perception_publisher/src/signed_distance_function.cpp similarity index 94% rename from simulator/dummy_perception_publisher/src/signed_distance_function.cpp rename to simulator/autoware_dummy_perception_publisher/src/signed_distance_function.cpp index 01bef1851b25e..c6a720e33fefa 100644 --- a/simulator/dummy_perception_publisher/src/signed_distance_function.cpp +++ b/simulator/autoware_dummy_perception_publisher/src/signed_distance_function.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "dummy_perception_publisher/signed_distance_function.hpp" +#include "autoware/dummy_perception_publisher/signed_distance_function.hpp" #include @@ -20,7 +20,7 @@ #include #include -namespace signed_distance_function +namespace autoware::dummy_perception_publisher { double AbstractSignedDistanceFunction::getSphereTracingDist( @@ -89,4 +89,4 @@ size_t CompositeSDF::nearest_sdf_index(double x, double y) const return idx_min; } -} // namespace signed_distance_function +} // namespace autoware::dummy_perception_publisher diff --git a/simulator/dummy_perception_publisher/test/src/test_signed_distance_function.cpp b/simulator/autoware_dummy_perception_publisher/test/src/test_signed_distance_function.cpp similarity index 82% rename from simulator/dummy_perception_publisher/test/src/test_signed_distance_function.cpp rename to simulator/autoware_dummy_perception_publisher/test/src/test_signed_distance_function.cpp index 5b8dcee549ea7..e7bb667a1dec2 100644 --- a/simulator/dummy_perception_publisher/test/src/test_signed_distance_function.cpp +++ b/simulator/autoware_dummy_perception_publisher/test/src/test_signed_distance_function.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "dummy_perception_publisher/signed_distance_function.hpp" +#include "autoware/dummy_perception_publisher/signed_distance_function.hpp" #include #include @@ -23,7 +23,8 @@ #include #include -namespace sdf = signed_distance_function; +namespace autoware::dummy_perception_publisher +{ TEST(SignedDistanceFunctionTest, BoxSDF) { @@ -33,7 +34,7 @@ TEST(SignedDistanceFunctionTest, BoxSDF) // test with identity transform const auto q = tf2::Quaternion(tf2::Vector3(0, 0, 1.0), 0.0); const auto tf_global2local = tf2::Transform(q); - const auto func = sdf::BoxSDF(1., 2., tf_global2local); + const auto func = BoxSDF(1., 2., tf_global2local); ASSERT_NEAR(func(0.0, 0.0), -0.5, eps); ASSERT_NEAR(func(0.0, 1.0), 0.0, eps); ASSERT_NEAR(func(0.0, 1.5), 0.5, eps); @@ -50,7 +51,7 @@ TEST(SignedDistanceFunctionTest, BoxSDF) // test with rotation (90 deg) and translation const auto q = tf2::Quaternion(tf2::Vector3(0, 0, 1.0), M_PI * 0.5); const auto tf_global2local = tf2::Transform(q, tf2::Vector3(1.0, 1.0, 0.0)); - const auto func = sdf::BoxSDF(1., 2., tf_global2local); + const auto func = BoxSDF(1., 2., tf_global2local); ASSERT_NEAR(func(1.0, 1.0), -0.5, eps); ASSERT_NEAR(func(0.0, 0.0), 0.5, eps); @@ -63,11 +64,11 @@ TEST(SignedDistanceFunctionTest, CompositeSDF) const double eps = 1e-5; const auto q_identity = tf2::Quaternion(tf2::Vector3(0, 0, 1.0), 0.0); const auto f1 = - std::make_shared(1., 1., tf2::Transform(q_identity, tf2::Vector3(0, 0, 0))); + std::make_shared(1., 1., tf2::Transform(q_identity, tf2::Vector3(0, 0, 0))); const auto f2 = - std::make_shared(1., 1., tf2::Transform(q_identity, tf2::Vector3(0, 2.0, 0))); + std::make_shared(1., 1., tf2::Transform(q_identity, tf2::Vector3(0, 2.0, 0))); const auto func = - sdf::CompositeSDF(std::vector>{f1, f2}); + CompositeSDF(std::vector>{f1, f2}); ASSERT_NEAR(func(0.0, 0.9), 0.4, eps); ASSERT_NEAR(func(0.0, 1.1), 0.4, eps); ASSERT_NEAR(func(0.0, 0.1), -0.4, eps); @@ -77,6 +78,8 @@ TEST(SignedDistanceFunctionTest, CompositeSDF) // ASSERT_NEAR(func.getSphereTracingDist(0.0, 1.0, M_PI * -0.5, eps), 0.5, eps); } +} // namespace autoware::dummy_perception_publisher + int main(int argc, char ** argv) { testing::InitGoogleTest(&argc, argv); From 1794419b46566aa6042a27243b4830f0218fafc3 Mon Sep 17 00:00:00 2001 From: Junya Sasaki Date: Fri, 24 Jan 2025 20:11:58 +0900 Subject: [PATCH 315/334] feat: apply `autoware_` prefix for `hazard_status_converter` (#9971) Signed-off-by: Junya Sasaki Signed-off-by: Shintaro Sakoda Signed-off-by: Ryohsuke Mitsudome --- launch/tier4_system_launch/launch/system.launch.xml | 2 +- .../CHANGELOG.rst | 6 +++--- .../CMakeLists.txt | 6 +++--- .../launch/hazard_status_converter.launch.xml | 2 +- .../package.xml | 5 +++-- .../src/converter.cpp | 6 +++--- .../src/converter.hpp | 4 ++-- 7 files changed, 16 insertions(+), 15 deletions(-) rename system/{hazard_status_converter => autoware_hazard_status_converter}/CHANGELOG.rst (96%) rename system/{hazard_status_converter => autoware_hazard_status_converter}/CMakeLists.txt (66%) rename system/{hazard_status_converter => autoware_hazard_status_converter}/launch/hazard_status_converter.launch.xml (66%) rename system/{hazard_status_converter => autoware_hazard_status_converter}/package.xml (82%) rename system/{hazard_status_converter => autoware_hazard_status_converter}/src/converter.cpp (96%) rename system/{hazard_status_converter => autoware_hazard_status_converter}/src/converter.hpp (94%) diff --git a/launch/tier4_system_launch/launch/system.launch.xml b/launch/tier4_system_launch/launch/system.launch.xml index 19823b96b082e..8e8e17bc772e0 100644 --- a/launch/tier4_system_launch/launch/system.launch.xml +++ b/launch/tier4_system_launch/launch/system.launch.xml @@ -100,7 +100,7 @@ - + diff --git a/system/hazard_status_converter/CHANGELOG.rst b/system/autoware_hazard_status_converter/CHANGELOG.rst similarity index 96% rename from system/hazard_status_converter/CHANGELOG.rst rename to system/autoware_hazard_status_converter/CHANGELOG.rst index a0c8e0ae193d1..aca530f3acf9b 100644 --- a/system/hazard_status_converter/CHANGELOG.rst +++ b/system/autoware_hazard_status_converter/CHANGELOG.rst @@ -1,6 +1,6 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package hazard_status_converter -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_hazard_status_converter +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.40.0 (2024-12-12) ------------------- diff --git a/system/hazard_status_converter/CMakeLists.txt b/system/autoware_hazard_status_converter/CMakeLists.txt similarity index 66% rename from system/hazard_status_converter/CMakeLists.txt rename to system/autoware_hazard_status_converter/CMakeLists.txt index b253f9fc51f2b..b49a67f24a693 100644 --- a/system/hazard_status_converter/CMakeLists.txt +++ b/system/autoware_hazard_status_converter/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(hazard_status_converter) +project(autoware_hazard_status_converter) find_package(autoware_cmake REQUIRED) autoware_package() @@ -9,8 +9,8 @@ ament_auto_add_library(${PROJECT_NAME} SHARED ) rclcpp_components_register_node(${PROJECT_NAME} - PLUGIN "hazard_status_converter::Converter" - EXECUTABLE converter + PLUGIN "autoware::hazard_status_converter::Converter" + EXECUTABLE ${PROJECT_NAME}_node ) ament_auto_package(INSTALL_TO_SHARE launch) diff --git a/system/hazard_status_converter/launch/hazard_status_converter.launch.xml b/system/autoware_hazard_status_converter/launch/hazard_status_converter.launch.xml similarity index 66% rename from system/hazard_status_converter/launch/hazard_status_converter.launch.xml rename to system/autoware_hazard_status_converter/launch/hazard_status_converter.launch.xml index 84318a921d4ce..26164c5ad50b0 100644 --- a/system/hazard_status_converter/launch/hazard_status_converter.launch.xml +++ b/system/autoware_hazard_status_converter/launch/hazard_status_converter.launch.xml @@ -1,5 +1,5 @@ - + diff --git a/system/hazard_status_converter/package.xml b/system/autoware_hazard_status_converter/package.xml similarity index 82% rename from system/hazard_status_converter/package.xml rename to system/autoware_hazard_status_converter/package.xml index 80cc53c08e16d..f2f7d93c19132 100644 --- a/system/hazard_status_converter/package.xml +++ b/system/autoware_hazard_status_converter/package.xml @@ -1,10 +1,11 @@ - hazard_status_converter + autoware_hazard_status_converter 0.40.0 - The hazard_status_converter package + The autoware_hazard_status_converter package Takagi, Isamu + Junya Sasaki Apache License 2.0 ament_cmake_auto diff --git a/system/hazard_status_converter/src/converter.cpp b/system/autoware_hazard_status_converter/src/converter.cpp similarity index 96% rename from system/hazard_status_converter/src/converter.cpp rename to system/autoware_hazard_status_converter/src/converter.cpp index 52cfef93aa522..9faf4e186e06c 100644 --- a/system/hazard_status_converter/src/converter.cpp +++ b/system/autoware_hazard_status_converter/src/converter.cpp @@ -18,7 +18,7 @@ #include #include -namespace hazard_status_converter +namespace autoware::hazard_status_converter { Converter::Converter(const rclcpp::NodeOptions & options) : Node("converter", options) @@ -125,7 +125,7 @@ void Converter::on_update(DiagGraph::ConstSharedPtr graph) pub_hazard_->publish(hazard); } -} // namespace hazard_status_converter +} // namespace autoware::hazard_status_converter #include -RCLCPP_COMPONENTS_REGISTER_NODE(hazard_status_converter::Converter) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::hazard_status_converter::Converter) diff --git a/system/hazard_status_converter/src/converter.hpp b/system/autoware_hazard_status_converter/src/converter.hpp similarity index 94% rename from system/hazard_status_converter/src/converter.hpp rename to system/autoware_hazard_status_converter/src/converter.hpp index 8011b911f3d42..651ccdf45285c 100644 --- a/system/hazard_status_converter/src/converter.hpp +++ b/system/autoware_hazard_status_converter/src/converter.hpp @@ -24,7 +24,7 @@ #include -namespace hazard_status_converter +namespace autoware::hazard_status_converter { class Converter : public rclcpp::Node @@ -48,6 +48,6 @@ class Converter : public rclcpp::Node std::unordered_set auto_mode_tree_; }; -} // namespace hazard_status_converter +} // namespace autoware::hazard_status_converter #endif // CONVERTER_HPP_ From de92439514365786f227abafd11e79678c451fb8 Mon Sep 17 00:00:00 2001 From: Junya Sasaki Date: Fri, 24 Jan 2025 20:13:25 +0900 Subject: [PATCH 316/334] feat: apply `autoware_` prefix for `learning_based_vehicle_model` (#9991) Signed-off-by: Junya Sasaki Signed-off-by: Shintaro Sakoda Signed-off-by: Ryohsuke Mitsudome --- .../CHANGELOG.rst | 6 +++--- .../CMakeLists.txt | 2 +- .../README.md | 0 .../image/python_model_interface.png | Bin .../interconnected_model.hpp | 19 +++++++++++------- .../model_connections_helpers.hpp | 13 ++++++++---- .../simple_pymodel.hpp | 17 ++++++++++------ .../submodel_interface.hpp | 13 ++++++++---- .../package.xml | 5 +++-- .../src/interconnected_model.cpp | 9 +++++++-- .../src/model_connections_helpers.cpp | 9 +++++++-- .../src/simple_pymodel.cpp | 9 +++++++-- .../src/submodel_interface.cpp | 4 ++-- .../CMakeLists.txt | 4 ++-- .../README.md | 2 +- .../sim_model_learned_steer_vel.hpp | 4 ++-- .../package.xml | 2 +- .../sim_model_learned_steer_vel.cpp | 2 +- 18 files changed, 78 insertions(+), 42 deletions(-) rename simulator/{learning_based_vehicle_model => autoware_learning_based_vehicle_model}/CHANGELOG.rst (95%) rename simulator/{learning_based_vehicle_model => autoware_learning_based_vehicle_model}/CMakeLists.txt (92%) rename simulator/{learning_based_vehicle_model => autoware_learning_based_vehicle_model}/README.md (100%) rename simulator/{learning_based_vehicle_model => autoware_learning_based_vehicle_model}/image/python_model_interface.png (100%) rename simulator/{learning_based_vehicle_model/include => autoware_learning_based_vehicle_model/include/autoware}/learning_based_vehicle_model/interconnected_model.hpp (86%) rename simulator/{learning_based_vehicle_model/include => autoware_learning_based_vehicle_model/include/autoware}/learning_based_vehicle_model/model_connections_helpers.hpp (68%) rename simulator/{learning_based_vehicle_model/include => autoware_learning_based_vehicle_model/include/autoware}/learning_based_vehicle_model/simple_pymodel.hpp (85%) rename simulator/{learning_based_vehicle_model/include => autoware_learning_based_vehicle_model/include/autoware}/learning_based_vehicle_model/submodel_interface.hpp (82%) rename simulator/{learning_based_vehicle_model => autoware_learning_based_vehicle_model}/package.xml (78%) rename simulator/{learning_based_vehicle_model => autoware_learning_based_vehicle_model}/src/interconnected_model.cpp (95%) rename simulator/{learning_based_vehicle_model => autoware_learning_based_vehicle_model}/src/model_connections_helpers.cpp (88%) rename simulator/{learning_based_vehicle_model => autoware_learning_based_vehicle_model}/src/simple_pymodel.cpp (94%) rename simulator/{learning_based_vehicle_model => autoware_learning_based_vehicle_model}/src/submodel_interface.cpp (82%) diff --git a/simulator/learning_based_vehicle_model/CHANGELOG.rst b/simulator/autoware_learning_based_vehicle_model/CHANGELOG.rst similarity index 95% rename from simulator/learning_based_vehicle_model/CHANGELOG.rst rename to simulator/autoware_learning_based_vehicle_model/CHANGELOG.rst index ed271370a6840..d58a509138a83 100644 --- a/simulator/learning_based_vehicle_model/CHANGELOG.rst +++ b/simulator/autoware_learning_based_vehicle_model/CHANGELOG.rst @@ -1,6 +1,6 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package learning_based_vehicle_model -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_learning_based_vehicle_model +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.40.0 (2024-12-12) ------------------- diff --git a/simulator/learning_based_vehicle_model/CMakeLists.txt b/simulator/autoware_learning_based_vehicle_model/CMakeLists.txt similarity index 92% rename from simulator/learning_based_vehicle_model/CMakeLists.txt rename to simulator/autoware_learning_based_vehicle_model/CMakeLists.txt index 58a3ad57e6f9e..02159e7d282bc 100644 --- a/simulator/learning_based_vehicle_model/CMakeLists.txt +++ b/simulator/autoware_learning_based_vehicle_model/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14.4) -project(learning_based_vehicle_model) +project(autoware_learning_based_vehicle_model) find_package(autoware_cmake REQUIRED) autoware_package() diff --git a/simulator/learning_based_vehicle_model/README.md b/simulator/autoware_learning_based_vehicle_model/README.md similarity index 100% rename from simulator/learning_based_vehicle_model/README.md rename to simulator/autoware_learning_based_vehicle_model/README.md diff --git a/simulator/learning_based_vehicle_model/image/python_model_interface.png b/simulator/autoware_learning_based_vehicle_model/image/python_model_interface.png similarity index 100% rename from simulator/learning_based_vehicle_model/image/python_model_interface.png rename to simulator/autoware_learning_based_vehicle_model/image/python_model_interface.png diff --git a/simulator/learning_based_vehicle_model/include/learning_based_vehicle_model/interconnected_model.hpp b/simulator/autoware_learning_based_vehicle_model/include/autoware/learning_based_vehicle_model/interconnected_model.hpp similarity index 86% rename from simulator/learning_based_vehicle_model/include/learning_based_vehicle_model/interconnected_model.hpp rename to simulator/autoware_learning_based_vehicle_model/include/autoware/learning_based_vehicle_model/interconnected_model.hpp index 56a196c257189..b08a8957dff7d 100644 --- a/simulator/learning_based_vehicle_model/include/learning_based_vehicle_model/interconnected_model.hpp +++ b/simulator/autoware_learning_based_vehicle_model/include/autoware/learning_based_vehicle_model/interconnected_model.hpp @@ -1,4 +1,4 @@ -// Copyright 2024 The Autoware Foundation. +// Copyright 2025 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. @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef LEARNING_BASED_VEHICLE_MODEL__INTERCONNECTED_MODEL_HPP_ -#define LEARNING_BASED_VEHICLE_MODEL__INTERCONNECTED_MODEL_HPP_ +#ifndef AUTOWARE__LEARNING_BASED_VEHICLE_MODEL__INTERCONNECTED_MODEL_HPP_ +#define AUTOWARE__LEARNING_BASED_VEHICLE_MODEL__INTERCONNECTED_MODEL_HPP_ -#include "learning_based_vehicle_model/model_connections_helpers.hpp" -#include "learning_based_vehicle_model/simple_pymodel.hpp" -#include "learning_based_vehicle_model/submodel_interface.hpp" +#include "autoware/learning_based_vehicle_model/model_connections_helpers.hpp" +#include "autoware/learning_based_vehicle_model/simple_pymodel.hpp" +#include "autoware/learning_based_vehicle_model/submodel_interface.hpp" #include #include @@ -29,6 +29,9 @@ #include #include +namespace autoware::simulator::learning_based_vehicle_model +{ + namespace py = pybind11; class __attribute__((visibility("default"))) InterconnectedModel @@ -127,4 +130,6 @@ class __attribute__((visibility("default"))) InterconnectedModel std::vector updatePyModel(std::vector psim_input); }; -#endif // LEARNING_BASED_VEHICLE_MODEL__INTERCONNECTED_MODEL_HPP_ +} // namespace autoware::simulator::learning_based_vehicle_model + +#endif // AUTOWARE__LEARNING_BASED_VEHICLE_MODEL__INTERCONNECTED_MODEL_HPP_ diff --git a/simulator/learning_based_vehicle_model/include/learning_based_vehicle_model/model_connections_helpers.hpp b/simulator/autoware_learning_based_vehicle_model/include/autoware/learning_based_vehicle_model/model_connections_helpers.hpp similarity index 68% rename from simulator/learning_based_vehicle_model/include/learning_based_vehicle_model/model_connections_helpers.hpp rename to simulator/autoware_learning_based_vehicle_model/include/autoware/learning_based_vehicle_model/model_connections_helpers.hpp index 0d46169600b2f..94d206fece130 100644 --- a/simulator/learning_based_vehicle_model/include/learning_based_vehicle_model/model_connections_helpers.hpp +++ b/simulator/autoware_learning_based_vehicle_model/include/autoware/learning_based_vehicle_model/model_connections_helpers.hpp @@ -1,4 +1,4 @@ -// Copyright 2024 The Autoware Foundation. +// Copyright 2025 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. @@ -12,12 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef LEARNING_BASED_VEHICLE_MODEL__MODEL_CONNECTIONS_HELPERS_HPP_ -#define LEARNING_BASED_VEHICLE_MODEL__MODEL_CONNECTIONS_HELPERS_HPP_ +#ifndef AUTOWARE__LEARNING_BASED_VEHICLE_MODEL__MODEL_CONNECTIONS_HELPERS_HPP_ +#define AUTOWARE__LEARNING_BASED_VEHICLE_MODEL__MODEL_CONNECTIONS_HELPERS_HPP_ #include #include +namespace autoware::simulator::learning_based_vehicle_model +{ + std::vector fillVectorUsingMap( std::vector vector1, std::vector vector2, const std::vector & map, bool inverse); @@ -25,4 +28,6 @@ std::vector fillVectorUsingMap( std::vector createConnectionsMap( const std::vector & connection_names_1, const std::vector & connection_names_2); -#endif // LEARNING_BASED_VEHICLE_MODEL__MODEL_CONNECTIONS_HELPERS_HPP_ +} // namespace autoware::simulator::learning_based_vehicle_model + +#endif // AUTOWARE__LEARNING_BASED_VEHICLE_MODEL__MODEL_CONNECTIONS_HELPERS_HPP_ diff --git a/simulator/learning_based_vehicle_model/include/learning_based_vehicle_model/simple_pymodel.hpp b/simulator/autoware_learning_based_vehicle_model/include/autoware/learning_based_vehicle_model/simple_pymodel.hpp similarity index 85% rename from simulator/learning_based_vehicle_model/include/learning_based_vehicle_model/simple_pymodel.hpp rename to simulator/autoware_learning_based_vehicle_model/include/autoware/learning_based_vehicle_model/simple_pymodel.hpp index fd9cf5cf44de9..270a30b5e23dd 100644 --- a/simulator/learning_based_vehicle_model/include/learning_based_vehicle_model/simple_pymodel.hpp +++ b/simulator/autoware_learning_based_vehicle_model/include/autoware/learning_based_vehicle_model/simple_pymodel.hpp @@ -1,4 +1,4 @@ -// Copyright 2024 The Autoware Foundation. +// Copyright 2025 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. @@ -13,11 +13,11 @@ // limitations under the License. // cspell:ignore pymodel -#ifndef LEARNING_BASED_VEHICLE_MODEL__SIMPLE_PYMODEL_HPP_ -#define LEARNING_BASED_VEHICLE_MODEL__SIMPLE_PYMODEL_HPP_ +#ifndef AUTOWARE__LEARNING_BASED_VEHICLE_MODEL__SIMPLE_PYMODEL_HPP_ +#define AUTOWARE__LEARNING_BASED_VEHICLE_MODEL__SIMPLE_PYMODEL_HPP_ -#include "learning_based_vehicle_model/model_connections_helpers.hpp" -#include "learning_based_vehicle_model/submodel_interface.hpp" +#include "autoware/learning_based_vehicle_model/model_connections_helpers.hpp" +#include "autoware/learning_based_vehicle_model/submodel_interface.hpp" #include #include @@ -25,6 +25,9 @@ #include #include +namespace autoware::simulator::learning_based_vehicle_model +{ + namespace py = pybind11; /** @@ -99,4 +102,6 @@ class SimplePyModel : public SubModelInterface void mapOutputs(std::vector signals_vec_names) override; }; -#endif // LEARNING_BASED_VEHICLE_MODEL__SIMPLE_PYMODEL_HPP_ +} // namespace autoware::simulator::learning_based_vehicle_model + +#endif // AUTOWARE__LEARNING_BASED_VEHICLE_MODEL__SIMPLE_PYMODEL_HPP_ diff --git a/simulator/learning_based_vehicle_model/include/learning_based_vehicle_model/submodel_interface.hpp b/simulator/autoware_learning_based_vehicle_model/include/autoware/learning_based_vehicle_model/submodel_interface.hpp similarity index 82% rename from simulator/learning_based_vehicle_model/include/learning_based_vehicle_model/submodel_interface.hpp rename to simulator/autoware_learning_based_vehicle_model/include/autoware/learning_based_vehicle_model/submodel_interface.hpp index 1cbad103278fb..f97158aadcd2b 100644 --- a/simulator/learning_based_vehicle_model/include/learning_based_vehicle_model/submodel_interface.hpp +++ b/simulator/autoware_learning_based_vehicle_model/include/autoware/learning_based_vehicle_model/submodel_interface.hpp @@ -1,4 +1,4 @@ -// Copyright 2024 The Autoware Foundation. +// Copyright 2025 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. @@ -12,11 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef LEARNING_BASED_VEHICLE_MODEL__SUBMODEL_INTERFACE_HPP_ -#define LEARNING_BASED_VEHICLE_MODEL__SUBMODEL_INTERFACE_HPP_ +#ifndef AUTOWARE__LEARNING_BASED_VEHICLE_MODEL__SUBMODEL_INTERFACE_HPP_ +#define AUTOWARE__LEARNING_BASED_VEHICLE_MODEL__SUBMODEL_INTERFACE_HPP_ #include +namespace autoware::simulator::learning_based_vehicle_model +{ + class SubModelInterface { public: @@ -59,4 +62,6 @@ class SubModelInterface std::vector model_signals_vec, std::vector model_signals_vec_next) = 0; }; -#endif // LEARNING_BASED_VEHICLE_MODEL__SUBMODEL_INTERFACE_HPP_ +} // namespace autoware::simulator::learning_based_vehicle_model + +#endif // AUTOWARE__LEARNING_BASED_VEHICLE_MODEL__SUBMODEL_INTERFACE_HPP_ diff --git a/simulator/learning_based_vehicle_model/package.xml b/simulator/autoware_learning_based_vehicle_model/package.xml similarity index 78% rename from simulator/learning_based_vehicle_model/package.xml rename to simulator/autoware_learning_based_vehicle_model/package.xml index 317be3d0990ca..b6b381801636d 100644 --- a/simulator/learning_based_vehicle_model/package.xml +++ b/simulator/autoware_learning_based_vehicle_model/package.xml @@ -1,11 +1,12 @@ - learning_based_vehicle_model + autoware_learning_based_vehicle_model 0.40.0 - learning_based_vehicle_model for simple_planning_simulator + autoware_learning_based_vehicle_model for simple_planning_simulator Maxime Clement Tomas Nagy + Junya Sasaki Apache License 2.0 ament_cmake_auto diff --git a/simulator/learning_based_vehicle_model/src/interconnected_model.cpp b/simulator/autoware_learning_based_vehicle_model/src/interconnected_model.cpp similarity index 95% rename from simulator/learning_based_vehicle_model/src/interconnected_model.cpp rename to simulator/autoware_learning_based_vehicle_model/src/interconnected_model.cpp index e495aceb8da9c..1f92e8cd058a5 100644 --- a/simulator/learning_based_vehicle_model/src/interconnected_model.cpp +++ b/simulator/autoware_learning_based_vehicle_model/src/interconnected_model.cpp @@ -1,4 +1,4 @@ -// Copyright 2024 The Autoware Foundation. +// Copyright 2025 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. @@ -12,12 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "learning_based_vehicle_model/interconnected_model.hpp" +#include "autoware/learning_based_vehicle_model/interconnected_model.hpp" #include #include #include +namespace autoware::simulator::learning_based_vehicle_model +{ + void InterconnectedModel::mapInputs(std::vector in_names) { // index in "map_in_to_sig_vec" is index in "in_names" and value in "map_in_to_sig_vec" is index @@ -139,3 +142,5 @@ std::vector InterconnectedModel::updatePyModel(std::vector psim_ return psim_next_state; } + +} // namespace autoware::simulator::learning_based_vehicle_model diff --git a/simulator/learning_based_vehicle_model/src/model_connections_helpers.cpp b/simulator/autoware_learning_based_vehicle_model/src/model_connections_helpers.cpp similarity index 88% rename from simulator/learning_based_vehicle_model/src/model_connections_helpers.cpp rename to simulator/autoware_learning_based_vehicle_model/src/model_connections_helpers.cpp index b300f3837b18a..284607744e218 100644 --- a/simulator/learning_based_vehicle_model/src/model_connections_helpers.cpp +++ b/simulator/autoware_learning_based_vehicle_model/src/model_connections_helpers.cpp @@ -1,4 +1,4 @@ -// Copyright 2024 The Autoware Foundation. +// Copyright 2025 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. @@ -12,10 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "learning_based_vehicle_model/model_connections_helpers.hpp" +#include "autoware/learning_based_vehicle_model/model_connections_helpers.hpp" #include +namespace autoware::simulator::learning_based_vehicle_model +{ + std::vector fillVectorUsingMap( std::vector vector1, std::vector vector2, const std::vector & map, bool inverse) @@ -48,3 +51,5 @@ std::vector createConnectionsMap( } return connection_map; } + +} // namespace autoware::simulator::learning_based_vehicle_model diff --git a/simulator/learning_based_vehicle_model/src/simple_pymodel.cpp b/simulator/autoware_learning_based_vehicle_model/src/simple_pymodel.cpp similarity index 94% rename from simulator/learning_based_vehicle_model/src/simple_pymodel.cpp rename to simulator/autoware_learning_based_vehicle_model/src/simple_pymodel.cpp index 10581179baf4a..50ceb14ff90e6 100644 --- a/simulator/learning_based_vehicle_model/src/simple_pymodel.cpp +++ b/simulator/autoware_learning_based_vehicle_model/src/simple_pymodel.cpp @@ -1,4 +1,4 @@ -// Copyright 2024 The Autoware Foundation. +// Copyright 2025 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. @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "learning_based_vehicle_model/simple_pymodel.hpp" +#include "autoware/learning_based_vehicle_model/simple_pymodel.hpp" #include #include @@ -20,6 +20,9 @@ #include #include +namespace autoware::simulator::learning_based_vehicle_model +{ + namespace py = pybind11; SimplePyModel::SimplePyModel( @@ -110,3 +113,5 @@ void SimplePyModel::mapOutputs(std::vector signals_vec_names) // "map_py_model_outputs_to_sig_vec" is index in "signals_vec_names" map_py_model_outputs_to_sig_vec = createConnectionsMap(signals_vec_names, py_model_state_names); } + +} // namespace autoware::simulator::learning_based_vehicle_model diff --git a/simulator/learning_based_vehicle_model/src/submodel_interface.cpp b/simulator/autoware_learning_based_vehicle_model/src/submodel_interface.cpp similarity index 82% rename from simulator/learning_based_vehicle_model/src/submodel_interface.cpp rename to simulator/autoware_learning_based_vehicle_model/src/submodel_interface.cpp index 906aff4b01ae0..cc525b990801b 100644 --- a/simulator/learning_based_vehicle_model/src/submodel_interface.cpp +++ b/simulator/autoware_learning_based_vehicle_model/src/submodel_interface.cpp @@ -1,4 +1,4 @@ -// Copyright 2024 The Autoware Foundation. +// Copyright 2025 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. @@ -12,4 +12,4 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "learning_based_vehicle_model/submodel_interface.hpp" +#include "autoware/learning_based_vehicle_model/submodel_interface.hpp" diff --git a/simulator/autoware_simple_planning_simulator/CMakeLists.txt b/simulator/autoware_simple_planning_simulator/CMakeLists.txt index ab4ac8218e193..18f2486796d96 100644 --- a/simulator/autoware_simple_planning_simulator/CMakeLists.txt +++ b/simulator/autoware_simple_planning_simulator/CMakeLists.txt @@ -3,7 +3,7 @@ project(autoware_simple_planning_simulator) find_package(autoware_cmake REQUIRED) find_package(Python3 COMPONENTS Interpreter Development) -find_package(learning_based_vehicle_model REQUIRED) +find_package(autoware_learning_based_vehicle_model REQUIRED) autoware_package() # Component @@ -25,7 +25,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/simple_planning_simulator/utils/csv_loader.cpp src/simple_planning_simulator/utils/mechanical_controller.cpp ) -target_include_directories(${PROJECT_NAME} PUBLIC ${Python3_INCLUDE_DIRS} ${learning_based_vehicle_model_INCLUDE_DIRS}) +target_include_directories(${PROJECT_NAME} PUBLIC ${Python3_INCLUDE_DIRS} ${autoware_learning_based_vehicle_model_INCLUDE_DIRS}) # Node executable rclcpp_components_register_node(${PROJECT_NAME} PLUGIN "autoware::simulator::simple_planning_simulator::SimplePlanningSimulator" diff --git a/simulator/autoware_simple_planning_simulator/README.md b/simulator/autoware_simple_planning_simulator/README.md index 385f4aa1c7eab..89fe55af1c3ff 100644 --- a/simulator/autoware_simple_planning_simulator/README.md +++ b/simulator/autoware_simple_planning_simulator/README.md @@ -64,7 +64,7 @@ The purpose of this simulator is for the integration test of planning and contro - `DELAY_STEER_ACC_GEARED` - `DELAY_STEER_ACC_GEARED_WO_FALL_GUARD` - `DELAY_STEER_MAP_ACC_GEARED`: applies 1D dynamics and time delay to the steering and acceleration commands. The simulated acceleration is determined by a value converted through the provided acceleration map. This model is valuable for an accurate simulation with acceleration deviations in a real vehicle. -- `LEARNED_STEER_VEL`: launches learned python models. More about this [here](../learning_based_vehicle_model). +- `LEARNED_STEER_VEL`: launches learned python models. More about this [here](../autoware_learning_based_vehicle_model). The following models receive `ACTUATION_CMD` generated from `raw_vehicle_cmd_converter`. Therefore, when these models are selected, the `raw_vehicle_cmd_converter` is also launched. diff --git a/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.hpp b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.hpp index 124c0d2532069..0aa525cd3f5c1 100644 --- a/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.hpp +++ b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.hpp @@ -15,8 +15,8 @@ #ifndef AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_LEARNED_STEER_VEL_HPP_ #define AUTOWARE__SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_LEARNED_STEER_VEL_HPP_ +#include "autoware/learning_based_vehicle_model/interconnected_model.hpp" #include "autoware/simple_planning_simulator/vehicle_model/sim_model_interface.hpp" -#include "learning_based_vehicle_model/interconnected_model.hpp" #include #include @@ -77,7 +77,7 @@ class SimModelLearnedSteerVel : public SimModelInterface /*delay steer velocity* STEER_DES, }; - InterconnectedModel vehicle; + autoware::simulator::learning_based_vehicle_model::InterconnectedModel vehicle; double prev_vx_ = 0.0; double current_ax_ = 0.0; diff --git a/simulator/autoware_simple_planning_simulator/package.xml b/simulator/autoware_simple_planning_simulator/package.xml index 790e48cd80cc1..47dbb3c0a422f 100644 --- a/simulator/autoware_simple_planning_simulator/package.xml +++ b/simulator/autoware_simple_planning_simulator/package.xml @@ -19,6 +19,7 @@ autoware_control_msgs autoware_lanelet2_extension + autoware_learning_based_vehicle_model autoware_map_msgs autoware_motion_utils autoware_planning_msgs @@ -27,7 +28,6 @@ autoware_vehicle_msgs geometry_msgs lanelet2_core - learning_based_vehicle_model nav_msgs rclcpp rclcpp_components diff --git a/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.cpp b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.cpp index 2d9c8d8ab0e0e..ce7ba2d48bac2 100644 --- a/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.cpp +++ b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.cpp @@ -14,7 +14,7 @@ #include "autoware/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.hpp" -#include "learning_based_vehicle_model/interconnected_model.hpp" +#include "autoware/learning_based_vehicle_model/interconnected_model.hpp" #include #include From 587211383ff5ddd999597104438742ab792bbe0c Mon Sep 17 00:00:00 2001 From: Junya Sasaki Date: Fri, 24 Jan 2025 20:14:51 +0900 Subject: [PATCH 317/334] feat: apply `autoware_` prefix for `evaluator/kinematic_evaluator` (#9936) Signed-off-by: Junya Sasaki Signed-off-by: Ryohsuke Mitsudome --- .github/CODEOWNERS | 2 +- .../CHANGELOG.rst | 6 +++--- .../CMakeLists.txt | 17 ++++++++--------- .../autoware_kinematic_evaluator/README.md | 7 +++++++ .../kinematic_evaluator_node.hpp | 12 ++++++------ .../metrics/kinematic_metrics.hpp | 10 +++++----- .../kinematic_evaluator/metrics/metric.hpp | 10 +++++----- .../kinematic_evaluator/metrics_calculator.hpp | 14 +++++++------- .../kinematic_evaluator/parameters.hpp | 12 ++++++------ .../launch/kinematic_evaluator.launch.xml | 8 ++++++++ .../package.xml | 3 ++- .../param/kinematic_evaluator.defaults.yaml | 0 .../schema/kinematic_evaluator.schema.json | 0 .../src/kinematic_evaluator_node.cpp | 8 ++++---- .../src/metrics/kinematic_metrics.cpp | 11 ++++++----- .../src/metrics_calculator.cpp | 8 ++++---- .../test/test_kinematic_evaluator_node.cpp | 13 +++++++------ evaluator/kinematic_evaluator/README.md | 7 ------- .../launch/kinematic_evaluator.launch.xml | 8 -------- 19 files changed, 79 insertions(+), 77 deletions(-) rename evaluator/{kinematic_evaluator => autoware_kinematic_evaluator}/CHANGELOG.rst (97%) rename evaluator/{kinematic_evaluator => autoware_kinematic_evaluator}/CMakeLists.txt (67%) create mode 100644 evaluator/autoware_kinematic_evaluator/README.md rename evaluator/{kinematic_evaluator/include => autoware_kinematic_evaluator/include/autoware}/kinematic_evaluator/kinematic_evaluator_node.hpp (86%) rename evaluator/{kinematic_evaluator/include => autoware_kinematic_evaluator/include/autoware}/kinematic_evaluator/metrics/kinematic_metrics.hpp (78%) rename evaluator/{kinematic_evaluator/include => autoware_kinematic_evaluator/include/autoware}/kinematic_evaluator/metrics/metric.hpp (86%) rename evaluator/{kinematic_evaluator/include => autoware_kinematic_evaluator/include/autoware}/kinematic_evaluator/metrics_calculator.hpp (78%) rename evaluator/{kinematic_evaluator/include => autoware_kinematic_evaluator/include/autoware}/kinematic_evaluator/parameters.hpp (71%) create mode 100644 evaluator/autoware_kinematic_evaluator/launch/kinematic_evaluator.launch.xml rename evaluator/{kinematic_evaluator => autoware_kinematic_evaluator}/package.xml (92%) rename evaluator/{kinematic_evaluator => autoware_kinematic_evaluator}/param/kinematic_evaluator.defaults.yaml (100%) rename evaluator/{kinematic_evaluator => autoware_kinematic_evaluator}/schema/kinematic_evaluator.schema.json (100%) rename evaluator/{kinematic_evaluator => autoware_kinematic_evaluator}/src/kinematic_evaluator_node.cpp (95%) rename evaluator/{kinematic_evaluator => autoware_kinematic_evaluator}/src/metrics/kinematic_metrics.cpp (64%) rename evaluator/{kinematic_evaluator => autoware_kinematic_evaluator}/src/metrics_calculator.cpp (82%) rename evaluator/{kinematic_evaluator => autoware_kinematic_evaluator}/test/test_kinematic_evaluator_node.cpp (89%) delete mode 100644 evaluator/kinematic_evaluator/README.md delete mode 100644 evaluator/kinematic_evaluator/launch/kinematic_evaluator.launch.xml diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index f51691a02e6d2..28a8ab262789e 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -49,7 +49,7 @@ control/control_performance_analysis/** berkay@leodrive.ai fumiya.watanabe@tier4 control/predicted_path_checker/** berkay@leodrive.ai evaluator/autoware_control_evaluator/** daniel.sanchez@tier4.jp kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp temkei.kem@tier4.jp evaluator/autoware_planning_evaluator/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp temkei.kem@tier4.jp -evaluator/kinematic_evaluator/** dominik.jargot@robotec.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp +evaluator/autoware_kinematic_evaluator/** dominik.jargot@robotec.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp junya.sasaki@tier4.jp evaluator/localization_evaluator/** anh.nguyen.2@tier4.jp dominik.jargot@robotec.ai koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp evaluator/autoware_perception_online_evaluator/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp kotaro.uetake@tier4.jp kyoichi.sugahara@tier4.jp shunsuke.miura@tier4.jp yoshi.ri@tier4.jp junya.sasaki@tier4.jp evaluator/scenario_simulator_v2_adapter/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp takamasa.horibe@tier4.jp temkei.kem@tier4.jp diff --git a/evaluator/kinematic_evaluator/CHANGELOG.rst b/evaluator/autoware_kinematic_evaluator/CHANGELOG.rst similarity index 97% rename from evaluator/kinematic_evaluator/CHANGELOG.rst rename to evaluator/autoware_kinematic_evaluator/CHANGELOG.rst index 2283ea3b36a95..7e997e497652a 100644 --- a/evaluator/kinematic_evaluator/CHANGELOG.rst +++ b/evaluator/autoware_kinematic_evaluator/CHANGELOG.rst @@ -1,6 +1,6 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package kinematic_evaluator -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_kinematic_evaluator +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.40.0 (2024-12-12) ------------------- diff --git a/evaluator/kinematic_evaluator/CMakeLists.txt b/evaluator/autoware_kinematic_evaluator/CMakeLists.txt similarity index 67% rename from evaluator/kinematic_evaluator/CMakeLists.txt rename to evaluator/autoware_kinematic_evaluator/CMakeLists.txt index 6c1b6abc3dace..721f164016c6c 100644 --- a/evaluator/kinematic_evaluator/CMakeLists.txt +++ b/evaluator/autoware_kinematic_evaluator/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(kinematic_evaluator) +project(autoware_kinematic_evaluator) if(NOT CMAKE_CXX_STANDARD) set(CMAKE_CXX_STANDARD 14) @@ -15,26 +15,25 @@ autoware_package() find_package(ament_cmake_auto REQUIRED) ament_auto_find_build_dependencies() -ament_auto_add_library(${PROJECT_NAME}_node SHARED +ament_auto_add_library(${PROJECT_NAME} SHARED src/metrics_calculator.cpp - src/${PROJECT_NAME}_node.cpp src/kinematic_evaluator_node.cpp src/metrics/kinematic_metrics.cpp ) -rclcpp_components_register_node(${PROJECT_NAME}_node - PLUGIN "kinematic_diagnostics::KinematicEvaluatorNode" - EXECUTABLE ${PROJECT_NAME} +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "autoware::kinematic_diagnostics::KinematicEvaluatorNode" + EXECUTABLE ${PROJECT_NAME}_node ) if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() - ament_add_gtest(test_${PROJECT_NAME} + ament_add_gtest(test_kinematic_evaluator test/test_kinematic_evaluator_node.cpp ) - target_link_libraries(test_${PROJECT_NAME} - ${PROJECT_NAME}_node + target_link_libraries(test_kinematic_evaluator + ${PROJECT_NAME} ) endif() diff --git a/evaluator/autoware_kinematic_evaluator/README.md b/evaluator/autoware_kinematic_evaluator/README.md new file mode 100644 index 0000000000000..341229bd0aac6 --- /dev/null +++ b/evaluator/autoware_kinematic_evaluator/README.md @@ -0,0 +1,7 @@ +# autoware_kinematic_evaluator + +TBD + +## Parameters + +{{json_to_markdown("evaluator/autoware_kinematic_evaluator/schema/kinematic_evaluator.schema.json")}} diff --git a/evaluator/kinematic_evaluator/include/kinematic_evaluator/kinematic_evaluator_node.hpp b/evaluator/autoware_kinematic_evaluator/include/autoware/kinematic_evaluator/kinematic_evaluator_node.hpp similarity index 86% rename from evaluator/kinematic_evaluator/include/kinematic_evaluator/kinematic_evaluator_node.hpp rename to evaluator/autoware_kinematic_evaluator/include/autoware/kinematic_evaluator/kinematic_evaluator_node.hpp index d401f63649468..053fbfc11f192 100644 --- a/evaluator/kinematic_evaluator/include/kinematic_evaluator/kinematic_evaluator_node.hpp +++ b/evaluator/autoware_kinematic_evaluator/include/autoware/kinematic_evaluator/kinematic_evaluator_node.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef KINEMATIC_EVALUATOR__KINEMATIC_EVALUATOR_NODE_HPP_ -#define KINEMATIC_EVALUATOR__KINEMATIC_EVALUATOR_NODE_HPP_ +#ifndef AUTOWARE__KINEMATIC_EVALUATOR__KINEMATIC_EVALUATOR_NODE_HPP_ +#define AUTOWARE__KINEMATIC_EVALUATOR__KINEMATIC_EVALUATOR_NODE_HPP_ +#include "autoware/kinematic_evaluator/metrics_calculator.hpp" #include "autoware/universe_utils/math/accumulator.hpp" -#include "kinematic_evaluator/metrics_calculator.hpp" #include "rclcpp/rclcpp.hpp" #include "tf2_ros/buffer.h" #include "tf2_ros/transform_listener.h" @@ -31,7 +31,7 @@ #include #include -namespace kinematic_diagnostics +namespace autoware::kinematic_diagnostics { using autoware::universe_utils::Accumulator; using diagnostic_msgs::msg::DiagnosticArray; @@ -78,6 +78,6 @@ class KinematicEvaluatorNode : public rclcpp::Node std::array>, static_cast(Metric::SIZE)> metric_stats_; std::unordered_map> metrics_dict_; }; -} // namespace kinematic_diagnostics +} // namespace autoware::kinematic_diagnostics -#endif // KINEMATIC_EVALUATOR__KINEMATIC_EVALUATOR_NODE_HPP_ +#endif // AUTOWARE__KINEMATIC_EVALUATOR__KINEMATIC_EVALUATOR_NODE_HPP_ diff --git a/evaluator/kinematic_evaluator/include/kinematic_evaluator/metrics/kinematic_metrics.hpp b/evaluator/autoware_kinematic_evaluator/include/autoware/kinematic_evaluator/metrics/kinematic_metrics.hpp similarity index 78% rename from evaluator/kinematic_evaluator/include/kinematic_evaluator/metrics/kinematic_metrics.hpp rename to evaluator/autoware_kinematic_evaluator/include/autoware/kinematic_evaluator/metrics/kinematic_metrics.hpp index e7d18910e7c39..2ae1f60902de7 100644 --- a/evaluator/kinematic_evaluator/include/kinematic_evaluator/metrics/kinematic_metrics.hpp +++ b/evaluator/autoware_kinematic_evaluator/include/autoware/kinematic_evaluator/metrics/kinematic_metrics.hpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef KINEMATIC_EVALUATOR__METRICS__KINEMATIC_METRICS_HPP_ -#define KINEMATIC_EVALUATOR__METRICS__KINEMATIC_METRICS_HPP_ +#ifndef AUTOWARE__KINEMATIC_EVALUATOR__METRICS__KINEMATIC_METRICS_HPP_ +#define AUTOWARE__KINEMATIC_EVALUATOR__METRICS__KINEMATIC_METRICS_HPP_ #include "autoware/universe_utils/math/accumulator.hpp" #include -namespace kinematic_diagnostics +namespace autoware::kinematic_diagnostics { namespace metrics { @@ -35,6 +35,6 @@ using nav_msgs::msg::Odometry; Accumulator updateVelocityStats(const double & value, const Accumulator stat_prev); } // namespace metrics -} // namespace kinematic_diagnostics +} // namespace autoware::kinematic_diagnostics -#endif // KINEMATIC_EVALUATOR__METRICS__KINEMATIC_METRICS_HPP_ +#endif // AUTOWARE__KINEMATIC_EVALUATOR__METRICS__KINEMATIC_METRICS_HPP_ diff --git a/evaluator/kinematic_evaluator/include/kinematic_evaluator/metrics/metric.hpp b/evaluator/autoware_kinematic_evaluator/include/autoware/kinematic_evaluator/metrics/metric.hpp similarity index 86% rename from evaluator/kinematic_evaluator/include/kinematic_evaluator/metrics/metric.hpp rename to evaluator/autoware_kinematic_evaluator/include/autoware/kinematic_evaluator/metrics/metric.hpp index 2e46d655312d8..01d645355b4f5 100644 --- a/evaluator/kinematic_evaluator/include/kinematic_evaluator/metrics/metric.hpp +++ b/evaluator/autoware_kinematic_evaluator/include/autoware/kinematic_evaluator/metrics/metric.hpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef KINEMATIC_EVALUATOR__METRICS__METRIC_HPP_ -#define KINEMATIC_EVALUATOR__METRICS__METRIC_HPP_ +#ifndef AUTOWARE__KINEMATIC_EVALUATOR__METRICS__METRIC_HPP_ +#define AUTOWARE__KINEMATIC_EVALUATOR__METRICS__METRIC_HPP_ #include #include #include #include -namespace kinematic_diagnostics +namespace autoware::kinematic_diagnostics { /** * @brief Enumeration of velocity metrics @@ -57,6 +57,6 @@ static struct CheckCorrectMaps } check; } // namespace details -} // namespace kinematic_diagnostics +} // namespace autoware::kinematic_diagnostics -#endif // KINEMATIC_EVALUATOR__METRICS__METRIC_HPP_ +#endif // AUTOWARE__KINEMATIC_EVALUATOR__METRICS__METRIC_HPP_ diff --git a/evaluator/kinematic_evaluator/include/kinematic_evaluator/metrics_calculator.hpp b/evaluator/autoware_kinematic_evaluator/include/autoware/kinematic_evaluator/metrics_calculator.hpp similarity index 78% rename from evaluator/kinematic_evaluator/include/kinematic_evaluator/metrics_calculator.hpp rename to evaluator/autoware_kinematic_evaluator/include/autoware/kinematic_evaluator/metrics_calculator.hpp index 372d4a34af62c..0a70d6477de1a 100644 --- a/evaluator/kinematic_evaluator/include/kinematic_evaluator/metrics_calculator.hpp +++ b/evaluator/autoware_kinematic_evaluator/include/autoware/kinematic_evaluator/metrics_calculator.hpp @@ -12,17 +12,17 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef KINEMATIC_EVALUATOR__METRICS_CALCULATOR_HPP_ -#define KINEMATIC_EVALUATOR__METRICS_CALCULATOR_HPP_ +#ifndef AUTOWARE__KINEMATIC_EVALUATOR__METRICS_CALCULATOR_HPP_ +#define AUTOWARE__KINEMATIC_EVALUATOR__METRICS_CALCULATOR_HPP_ +#include "autoware/kinematic_evaluator/metrics/metric.hpp" +#include "autoware/kinematic_evaluator/parameters.hpp" #include "autoware/universe_utils/math/accumulator.hpp" -#include "kinematic_evaluator/metrics/metric.hpp" -#include "kinematic_evaluator/parameters.hpp" #include "geometry_msgs/msg/pose.hpp" #include -namespace kinematic_diagnostics +namespace autoware::kinematic_diagnostics { using autoware::universe_utils::Accumulator; using nav_msgs::msg::Odometry; @@ -52,6 +52,6 @@ class MetricsCalculator const Metric metric, const Odometry & odom, const Accumulator stat_prev) const; }; // class MetricsCalculator -} // namespace kinematic_diagnostics +} // namespace autoware::kinematic_diagnostics -#endif // KINEMATIC_EVALUATOR__METRICS_CALCULATOR_HPP_ +#endif // AUTOWARE__KINEMATIC_EVALUATOR__METRICS_CALCULATOR_HPP_ diff --git a/evaluator/kinematic_evaluator/include/kinematic_evaluator/parameters.hpp b/evaluator/autoware_kinematic_evaluator/include/autoware/kinematic_evaluator/parameters.hpp similarity index 71% rename from evaluator/kinematic_evaluator/include/kinematic_evaluator/parameters.hpp rename to evaluator/autoware_kinematic_evaluator/include/autoware/kinematic_evaluator/parameters.hpp index dada46f44292f..22e6fc91720c2 100644 --- a/evaluator/kinematic_evaluator/include/kinematic_evaluator/parameters.hpp +++ b/evaluator/autoware_kinematic_evaluator/include/autoware/kinematic_evaluator/parameters.hpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef KINEMATIC_EVALUATOR__PARAMETERS_HPP_ -#define KINEMATIC_EVALUATOR__PARAMETERS_HPP_ +#ifndef AUTOWARE__KINEMATIC_EVALUATOR__PARAMETERS_HPP_ +#define AUTOWARE__KINEMATIC_EVALUATOR__PARAMETERS_HPP_ -#include "kinematic_evaluator/metrics/metric.hpp" +#include "autoware/kinematic_evaluator/metrics/metric.hpp" #include -namespace kinematic_diagnostics +namespace autoware::kinematic_diagnostics { /** * @brief Enumeration of trajectory metrics @@ -29,6 +29,6 @@ struct Parameters std::array(Metric::SIZE)> metrics{}; // default values to false }; // struct Parameters -} // namespace kinematic_diagnostics +} // namespace autoware::kinematic_diagnostics -#endif // KINEMATIC_EVALUATOR__PARAMETERS_HPP_ +#endif // AUTOWARE__KINEMATIC_EVALUATOR__PARAMETERS_HPP_ diff --git a/evaluator/autoware_kinematic_evaluator/launch/kinematic_evaluator.launch.xml b/evaluator/autoware_kinematic_evaluator/launch/kinematic_evaluator.launch.xml new file mode 100644 index 0000000000000..60818f875b9d0 --- /dev/null +++ b/evaluator/autoware_kinematic_evaluator/launch/kinematic_evaluator.launch.xml @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/evaluator/kinematic_evaluator/package.xml b/evaluator/autoware_kinematic_evaluator/package.xml similarity index 92% rename from evaluator/kinematic_evaluator/package.xml rename to evaluator/autoware_kinematic_evaluator/package.xml index fbd5df3f27765..f64ad900976c9 100644 --- a/evaluator/kinematic_evaluator/package.xml +++ b/evaluator/autoware_kinematic_evaluator/package.xml @@ -1,6 +1,6 @@ - kinematic_evaluator + autoware_kinematic_evaluator 0.40.0 kinematic evaluator ROS 2 node @@ -11,6 +11,7 @@ Takayuki Murooka Fumiya Watanabe Satoshi Ota + Junya Sasaki Apache License 2.0 diff --git a/evaluator/kinematic_evaluator/param/kinematic_evaluator.defaults.yaml b/evaluator/autoware_kinematic_evaluator/param/kinematic_evaluator.defaults.yaml similarity index 100% rename from evaluator/kinematic_evaluator/param/kinematic_evaluator.defaults.yaml rename to evaluator/autoware_kinematic_evaluator/param/kinematic_evaluator.defaults.yaml diff --git a/evaluator/kinematic_evaluator/schema/kinematic_evaluator.schema.json b/evaluator/autoware_kinematic_evaluator/schema/kinematic_evaluator.schema.json similarity index 100% rename from evaluator/kinematic_evaluator/schema/kinematic_evaluator.schema.json rename to evaluator/autoware_kinematic_evaluator/schema/kinematic_evaluator.schema.json diff --git a/evaluator/kinematic_evaluator/src/kinematic_evaluator_node.cpp b/evaluator/autoware_kinematic_evaluator/src/kinematic_evaluator_node.cpp similarity index 95% rename from evaluator/kinematic_evaluator/src/kinematic_evaluator_node.cpp rename to evaluator/autoware_kinematic_evaluator/src/kinematic_evaluator_node.cpp index d34f9deb7f1ba..93a6bf9f046b1 100644 --- a/evaluator/kinematic_evaluator/src/kinematic_evaluator_node.cpp +++ b/evaluator/autoware_kinematic_evaluator/src/kinematic_evaluator_node.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "kinematic_evaluator/kinematic_evaluator_node.hpp" +#include "autoware/kinematic_evaluator/kinematic_evaluator_node.hpp" #include "boost/lexical_cast.hpp" @@ -22,7 +22,7 @@ #include #include -namespace kinematic_diagnostics +namespace autoware::kinematic_diagnostics { KinematicEvaluatorNode::KinematicEvaluatorNode(const rclcpp::NodeOptions & node_options) : Node("kinematic_evaluator", node_options) @@ -139,7 +139,7 @@ geometry_msgs::msg::Pose KinematicEvaluatorNode::getCurrentEgoPose() const return p; } -} // namespace kinematic_diagnostics +} // namespace autoware::kinematic_diagnostics #include "rclcpp_components/register_node_macro.hpp" -RCLCPP_COMPONENTS_REGISTER_NODE(kinematic_diagnostics::KinematicEvaluatorNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::kinematic_diagnostics::KinematicEvaluatorNode) diff --git a/evaluator/kinematic_evaluator/src/metrics/kinematic_metrics.cpp b/evaluator/autoware_kinematic_evaluator/src/metrics/kinematic_metrics.cpp similarity index 64% rename from evaluator/kinematic_evaluator/src/metrics/kinematic_metrics.cpp rename to evaluator/autoware_kinematic_evaluator/src/metrics/kinematic_metrics.cpp index d410863a05010..c686a60436803 100644 --- a/evaluator/kinematic_evaluator/src/metrics/kinematic_metrics.cpp +++ b/evaluator/autoware_kinematic_evaluator/src/metrics/kinematic_metrics.cpp @@ -12,19 +12,20 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "kinematic_evaluator/metrics/kinematic_metrics.hpp" +#include "autoware/kinematic_evaluator/metrics/kinematic_metrics.hpp" -namespace kinematic_diagnostics +namespace autoware::kinematic_diagnostics { namespace metrics { -Accumulator updateVelocityStats(const double & value, const Accumulator stat_prev) +autoware::universe_utils::Accumulator updateVelocityStats( + const double & value, const autoware::universe_utils::Accumulator stat_prev) { - Accumulator stat(stat_prev); + autoware::universe_utils::Accumulator stat(stat_prev); stat.add(value); return stat; } } // namespace metrics -} // namespace kinematic_diagnostics +} // namespace autoware::kinematic_diagnostics diff --git a/evaluator/kinematic_evaluator/src/metrics_calculator.cpp b/evaluator/autoware_kinematic_evaluator/src/metrics_calculator.cpp similarity index 82% rename from evaluator/kinematic_evaluator/src/metrics_calculator.cpp rename to evaluator/autoware_kinematic_evaluator/src/metrics_calculator.cpp index 8b0f581817b38..85b3711ce7c8f 100644 --- a/evaluator/kinematic_evaluator/src/metrics_calculator.cpp +++ b/evaluator/autoware_kinematic_evaluator/src/metrics_calculator.cpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "kinematic_evaluator/metrics_calculator.hpp" +#include "autoware/kinematic_evaluator/metrics_calculator.hpp" -#include "kinematic_evaluator/metrics/kinematic_metrics.hpp" +#include "autoware/kinematic_evaluator/metrics/kinematic_metrics.hpp" -namespace kinematic_diagnostics +namespace autoware::kinematic_diagnostics { Accumulator MetricsCalculator::updateStat( const Metric metric, const Odometry & odom, const Accumulator stat_prev) const @@ -31,4 +31,4 @@ Accumulator MetricsCalculator::updateStat( } } -} // namespace kinematic_diagnostics +} // namespace autoware::kinematic_diagnostics diff --git a/evaluator/kinematic_evaluator/test/test_kinematic_evaluator_node.cpp b/evaluator/autoware_kinematic_evaluator/test/test_kinematic_evaluator_node.cpp similarity index 89% rename from evaluator/kinematic_evaluator/test/test_kinematic_evaluator_node.cpp rename to evaluator/autoware_kinematic_evaluator/test/test_kinematic_evaluator_node.cpp index 769f98416848f..9e8288a3a7f91 100644 --- a/evaluator/kinematic_evaluator/test/test_kinematic_evaluator_node.cpp +++ b/evaluator/autoware_kinematic_evaluator/test/test_kinematic_evaluator_node.cpp @@ -18,7 +18,7 @@ #include "rclcpp/time.hpp" #include "tf2_ros/transform_broadcaster.h" -#include +#include #include "diagnostic_msgs/msg/diagnostic_array.hpp" #include "geometry_msgs/msg/transform_stamped.hpp" @@ -32,7 +32,7 @@ #include #include -using EvalNode = kinematic_diagnostics::KinematicEvaluatorNode; +using EvalNode = autoware::kinematic_diagnostics::KinematicEvaluatorNode; using diagnostic_msgs::msg::DiagnosticArray; using nav_msgs::msg::Odometry; @@ -44,7 +44,8 @@ class EvalTest : public ::testing::Test rclcpp::init(0, nullptr); rclcpp::NodeOptions options; - const auto share_dir = ament_index_cpp::get_package_share_directory("kinematic_evaluator"); + const auto share_dir = + ament_index_cpp::get_package_share_directory("autoware_kinematic_evaluator"); options.arguments( {"--ros-args", "--params-file", share_dir + "/param/kinematic_evaluator.defaults.yaml"}); @@ -70,9 +71,9 @@ class EvalTest : public ::testing::Test ~EvalTest() override { /*rclcpp::shutdown();*/ } - void setTargetMetric(kinematic_diagnostics::Metric metric) + void setTargetMetric(autoware::kinematic_diagnostics::Metric metric) { - const auto metric_str = kinematic_diagnostics::metric_to_str.at(metric); + const auto metric_str = autoware::kinematic_diagnostics::metric_to_str.at(metric); const auto is_target_metric = [metric_str](const auto & status) { return status.name == metric_str; }; @@ -130,7 +131,7 @@ class EvalTest : public ::testing::Test TEST_F(EvalTest, TestVelocityStats) { - setTargetMetric(kinematic_diagnostics::Metric::velocity_stats); + setTargetMetric(autoware::kinematic_diagnostics::Metric::velocity_stats); Odometry odom = makeOdometry(0.0); EXPECT_DOUBLE_EQ(publishOdometryAndGetMetric(odom), 0.0); Odometry odom2 = makeOdometry(1.0); diff --git a/evaluator/kinematic_evaluator/README.md b/evaluator/kinematic_evaluator/README.md deleted file mode 100644 index 7cc826195c1b4..0000000000000 --- a/evaluator/kinematic_evaluator/README.md +++ /dev/null @@ -1,7 +0,0 @@ -# Kinematic Evaluator - -TBD - -## Parameters - -{{json_to_markdown("evaluator/kinematic_evaluator/schema/kinematic_evaluator.schema.json")}} diff --git a/evaluator/kinematic_evaluator/launch/kinematic_evaluator.launch.xml b/evaluator/kinematic_evaluator/launch/kinematic_evaluator.launch.xml deleted file mode 100644 index ebb89c2897ce3..0000000000000 --- a/evaluator/kinematic_evaluator/launch/kinematic_evaluator.launch.xml +++ /dev/null @@ -1,8 +0,0 @@ - - - - - - - - From ea214c561a1978c775967ed88006bab72cf1614e Mon Sep 17 00:00:00 2001 From: Junya Sasaki Date: Sat, 25 Jan 2025 00:54:42 +0900 Subject: [PATCH 318/334] feat: apply `autoware_` prefix for `diagnostic_graph_utils` (#9968) Signed-off-by: Junya Sasaki Signed-off-by: Ryohsuke Mitsudome --- system/autoware_default_adapi/package.xml | 2 +- system/autoware_default_adapi/src/diagnostics.hpp | 10 +++++----- .../CHANGELOG.rst | 0 .../CMakeLists.txt | 8 ++++---- .../README.md | 6 +++--- .../doc/node/converter.md | 4 ++-- .../doc/node/dump.md | 4 ++-- .../doc/node/images/rqt_runtime_monitor.png | Bin .../autoware}/diagnostic_graph_utils/graph.hpp | 10 +++++----- .../diagnostic_graph_utils/subscription.hpp | 12 ++++++------ .../launch/logging.launch.xml | 2 +- .../package.xml | 5 +++-- .../src/lib/graph.cpp | 6 +++--- .../src/lib/subscription.cpp | 6 +++--- .../src/node/converter.cpp | 6 +++--- .../src/node/converter.hpp | 6 +++--- .../src/node/dump.cpp | 6 +++--- .../src/node/dump.hpp | 6 +++--- .../src/node/logging.cpp | 6 +++--- .../src/node/logging.hpp | 6 +++--- system/autoware_hazard_status_converter/package.xml | 2 +- .../src/converter.hpp | 8 ++++---- system/diagnostic_graph_aggregator/README.md | 2 +- 23 files changed, 62 insertions(+), 61 deletions(-) rename system/{diagnostic_graph_utils => autoware_diagnostic_graph_utils}/CHANGELOG.rst (100%) rename system/{diagnostic_graph_utils => autoware_diagnostic_graph_utils}/CMakeLists.txt (74%) rename system/{diagnostic_graph_utils => autoware_diagnostic_graph_utils}/README.md (55%) rename system/{diagnostic_graph_utils => autoware_diagnostic_graph_utils}/doc/node/converter.md (80%) rename system/{diagnostic_graph_utils => autoware_diagnostic_graph_utils}/doc/node/dump.md (93%) rename system/{diagnostic_graph_utils => autoware_diagnostic_graph_utils}/doc/node/images/rqt_runtime_monitor.png (100%) rename system/{diagnostic_graph_utils/include => autoware_diagnostic_graph_utils/include/autoware}/diagnostic_graph_utils/graph.hpp (94%) rename system/{diagnostic_graph_utils/include => autoware_diagnostic_graph_utils/include/autoware}/diagnostic_graph_utils/subscription.hpp (82%) rename system/{diagnostic_graph_utils => autoware_diagnostic_graph_utils}/launch/logging.launch.xml (79%) rename system/{diagnostic_graph_utils => autoware_diagnostic_graph_utils}/package.xml (80%) rename system/{diagnostic_graph_utils => autoware_diagnostic_graph_utils}/src/lib/graph.cpp (95%) rename system/{diagnostic_graph_utils => autoware_diagnostic_graph_utils}/src/lib/subscription.cpp (92%) rename system/{diagnostic_graph_utils => autoware_diagnostic_graph_utils}/src/node/converter.cpp (88%) rename system/{diagnostic_graph_utils => autoware_diagnostic_graph_utils}/src/node/converter.hpp (89%) rename system/{diagnostic_graph_utils => autoware_diagnostic_graph_utils}/src/node/dump.cpp (96%) rename system/{diagnostic_graph_utils => autoware_diagnostic_graph_utils}/src/node/dump.hpp (88%) rename system/{diagnostic_graph_utils => autoware_diagnostic_graph_utils}/src/node/logging.cpp (95%) rename system/{diagnostic_graph_utils => autoware_diagnostic_graph_utils}/src/node/logging.hpp (90%) diff --git a/system/autoware_default_adapi/package.xml b/system/autoware_default_adapi/package.xml index 094882d0e4dd3..5125844cbfedf 100644 --- a/system/autoware_default_adapi/package.xml +++ b/system/autoware_default_adapi/package.xml @@ -17,13 +17,13 @@ autoware_adapi_version_msgs autoware_component_interface_specs_universe autoware_component_interface_utils + autoware_diagnostic_graph_utils autoware_geography_utils autoware_motion_utils autoware_planning_msgs autoware_system_msgs autoware_vehicle_info_utils autoware_vehicle_msgs - diagnostic_graph_utils geographic_msgs nav_msgs rclcpp diff --git a/system/autoware_default_adapi/src/diagnostics.hpp b/system/autoware_default_adapi/src/diagnostics.hpp index b382887aaa694..dfd94d9b06f2a 100644 --- a/system/autoware_default_adapi/src/diagnostics.hpp +++ b/system/autoware_default_adapi/src/diagnostics.hpp @@ -15,7 +15,7 @@ #ifndef DIAGNOSTICS_HPP_ #define DIAGNOSTICS_HPP_ -#include "diagnostic_graph_utils/subscription.hpp" +#include "autoware/diagnostic_graph_utils/subscription.hpp" #include @@ -31,14 +31,14 @@ class DiagnosticsNode : public rclcpp::Node explicit DiagnosticsNode(const rclcpp::NodeOptions & options); private: - using DiagGraph = diagnostic_graph_utils::DiagGraph; - using DiagUnit = diagnostic_graph_utils::DiagUnit; - using DiagLink = diagnostic_graph_utils::DiagLink; + using DiagGraph = autoware::diagnostic_graph_utils::DiagGraph; + using DiagUnit = autoware::diagnostic_graph_utils::DiagUnit; + using DiagLink = autoware::diagnostic_graph_utils::DiagLink; void on_create(DiagGraph::ConstSharedPtr graph); void on_update(DiagGraph::ConstSharedPtr graph); rclcpp::Publisher::SharedPtr pub_struct_; rclcpp::Publisher::SharedPtr pub_status_; - diagnostic_graph_utils::DiagGraphSubscription sub_graph_; + autoware::diagnostic_graph_utils::DiagGraphSubscription sub_graph_; }; } // namespace autoware::default_adapi diff --git a/system/diagnostic_graph_utils/CHANGELOG.rst b/system/autoware_diagnostic_graph_utils/CHANGELOG.rst similarity index 100% rename from system/diagnostic_graph_utils/CHANGELOG.rst rename to system/autoware_diagnostic_graph_utils/CHANGELOG.rst diff --git a/system/diagnostic_graph_utils/CMakeLists.txt b/system/autoware_diagnostic_graph_utils/CMakeLists.txt similarity index 74% rename from system/diagnostic_graph_utils/CMakeLists.txt rename to system/autoware_diagnostic_graph_utils/CMakeLists.txt index 0c36964f49237..b1de417b1bc7d 100644 --- a/system/diagnostic_graph_utils/CMakeLists.txt +++ b/system/autoware_diagnostic_graph_utils/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(diagnostic_graph_utils) +project(autoware_diagnostic_graph_utils) find_package(autoware_cmake REQUIRED) autoware_package() @@ -16,17 +16,17 @@ ament_auto_add_library(${PROJECT_NAME}_tools SHARED ) rclcpp_components_register_node(${PROJECT_NAME}_tools - PLUGIN "diagnostic_graph_utils::DumpNode" + PLUGIN "autoware::diagnostic_graph_utils::DumpNode" EXECUTABLE dump_node ) rclcpp_components_register_node(${PROJECT_NAME}_tools - PLUGIN "diagnostic_graph_utils::ConverterNode" + PLUGIN "autoware::diagnostic_graph_utils::ConverterNode" EXECUTABLE converter_node ) rclcpp_components_register_node(${PROJECT_NAME}_tools - PLUGIN "diagnostic_graph_utils::LoggingNode" + PLUGIN "autoware::diagnostic_graph_utils::LoggingNode" EXECUTABLE logging_node ) diff --git a/system/diagnostic_graph_utils/README.md b/system/autoware_diagnostic_graph_utils/README.md similarity index 55% rename from system/diagnostic_graph_utils/README.md rename to system/autoware_diagnostic_graph_utils/README.md index a06d664622bff..ac941a3575445 100644 --- a/system/diagnostic_graph_utils/README.md +++ b/system/autoware_diagnostic_graph_utils/README.md @@ -1,4 +1,4 @@ -# diagnostic_graph_utils +# autoware_diagnostic_graph_utils This package is a utility for diagnostic graph published by [diagnostic_graph_aggregator](../diagnostic_graph_aggregator/README.md). @@ -9,5 +9,5 @@ This package is a utility for diagnostic graph published by [diagnostic_graph_ag ## C++ library -- [DiagGraph](./include/diagnostic_graph_utils/graph.hpp) -- [DiagGraphSubscription](./include/diagnostic_graph_utils/subscription.hpp) +- [DiagGraph](./include/autoware/diagnostic_graph_utils/graph.hpp) +- [DiagGraphSubscription](./include/autoware/diagnostic_graph_utils/subscription.hpp) diff --git a/system/diagnostic_graph_utils/doc/node/converter.md b/system/autoware_diagnostic_graph_utils/doc/node/converter.md similarity index 80% rename from system/diagnostic_graph_utils/doc/node/converter.md rename to system/autoware_diagnostic_graph_utils/doc/node/converter.md index 407a99c87f73e..a7793b815c0b7 100644 --- a/system/diagnostic_graph_utils/doc/node/converter.md +++ b/system/autoware_diagnostic_graph_utils/doc/node/converter.md @@ -5,7 +5,7 @@ This tool converts `/diagnostics_graph` to `/diagnostics_array` so it can be rea ## Usage ```bash -ros2 run diagnostic_graph_utils converter_node +ros2 run autoware_diagnostic_graph_utils converter_node ``` ## Examples @@ -19,7 +19,7 @@ ros2 launch diagnostic_graph_aggregator example-main.launch.xml Terminal 2: ```bash -ros2 run diagnostic_graph_utils converter_node +ros2 run autoware_diagnostic_graph_utils converter_node ``` Terminal 3: diff --git a/system/diagnostic_graph_utils/doc/node/dump.md b/system/autoware_diagnostic_graph_utils/doc/node/dump.md similarity index 93% rename from system/diagnostic_graph_utils/doc/node/dump.md rename to system/autoware_diagnostic_graph_utils/doc/node/dump.md index c76bb85ed75cb..fac23d655ed64 100644 --- a/system/diagnostic_graph_utils/doc/node/dump.md +++ b/system/autoware_diagnostic_graph_utils/doc/node/dump.md @@ -5,7 +5,7 @@ This tool displays `/diagnostics_graph` in table format. ## Usage ```bash -ros2 run diagnostic_graph_utils dump_node +ros2 run autoware_diagnostic_graph_utils dump_node ``` ## Examples @@ -19,7 +19,7 @@ ros2 launch diagnostic_graph_aggregator example-main.launch.xml Terminal 2: ```bash -ros2 run diagnostic_graph_utils dump_node +ros2 run autoware_diagnostic_graph_utils dump_node ``` Output: diff --git a/system/diagnostic_graph_utils/doc/node/images/rqt_runtime_monitor.png b/system/autoware_diagnostic_graph_utils/doc/node/images/rqt_runtime_monitor.png similarity index 100% rename from system/diagnostic_graph_utils/doc/node/images/rqt_runtime_monitor.png rename to system/autoware_diagnostic_graph_utils/doc/node/images/rqt_runtime_monitor.png diff --git a/system/diagnostic_graph_utils/include/diagnostic_graph_utils/graph.hpp b/system/autoware_diagnostic_graph_utils/include/autoware/diagnostic_graph_utils/graph.hpp similarity index 94% rename from system/diagnostic_graph_utils/include/diagnostic_graph_utils/graph.hpp rename to system/autoware_diagnostic_graph_utils/include/autoware/diagnostic_graph_utils/graph.hpp index 275e4ffcb1c7e..3114ffe108b5b 100644 --- a/system/diagnostic_graph_utils/include/diagnostic_graph_utils/graph.hpp +++ b/system/autoware_diagnostic_graph_utils/include/autoware/diagnostic_graph_utils/graph.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef DIAGNOSTIC_GRAPH_UTILS__GRAPH_HPP_ -#define DIAGNOSTIC_GRAPH_UTILS__GRAPH_HPP_ +#ifndef AUTOWARE__DIAGNOSTIC_GRAPH_UTILS__GRAPH_HPP_ +#define AUTOWARE__DIAGNOSTIC_GRAPH_UTILS__GRAPH_HPP_ #include @@ -27,7 +27,7 @@ #include #include -namespace diagnostic_graph_utils +namespace autoware::diagnostic_graph_utils { class DiagLink; @@ -139,6 +139,6 @@ class DiagGraph std::vector> links_; }; -} // namespace diagnostic_graph_utils +} // namespace autoware::diagnostic_graph_utils -#endif // DIAGNOSTIC_GRAPH_UTILS__GRAPH_HPP_ +#endif // AUTOWARE__DIAGNOSTIC_GRAPH_UTILS__GRAPH_HPP_ diff --git a/system/diagnostic_graph_utils/include/diagnostic_graph_utils/subscription.hpp b/system/autoware_diagnostic_graph_utils/include/autoware/diagnostic_graph_utils/subscription.hpp similarity index 82% rename from system/diagnostic_graph_utils/include/diagnostic_graph_utils/subscription.hpp rename to system/autoware_diagnostic_graph_utils/include/autoware/diagnostic_graph_utils/subscription.hpp index 5aebde7ea3a38..97a110d0305b0 100644 --- a/system/diagnostic_graph_utils/include/diagnostic_graph_utils/subscription.hpp +++ b/system/autoware_diagnostic_graph_utils/include/autoware/diagnostic_graph_utils/subscription.hpp @@ -12,17 +12,17 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef DIAGNOSTIC_GRAPH_UTILS__SUBSCRIPTION_HPP_ -#define DIAGNOSTIC_GRAPH_UTILS__SUBSCRIPTION_HPP_ +#ifndef AUTOWARE__DIAGNOSTIC_GRAPH_UTILS__SUBSCRIPTION_HPP_ +#define AUTOWARE__DIAGNOSTIC_GRAPH_UTILS__SUBSCRIPTION_HPP_ -#include "diagnostic_graph_utils/graph.hpp" +#include "autoware/diagnostic_graph_utils/graph.hpp" #include #include #include -namespace diagnostic_graph_utils +namespace autoware::diagnostic_graph_utils { class DiagGraphSubscription @@ -48,6 +48,6 @@ class DiagGraphSubscription CallbackType update_callback_; }; -} // namespace diagnostic_graph_utils +} // namespace autoware::diagnostic_graph_utils -#endif // DIAGNOSTIC_GRAPH_UTILS__SUBSCRIPTION_HPP_ +#endif // AUTOWARE__DIAGNOSTIC_GRAPH_UTILS__SUBSCRIPTION_HPP_ diff --git a/system/diagnostic_graph_utils/launch/logging.launch.xml b/system/autoware_diagnostic_graph_utils/launch/logging.launch.xml similarity index 79% rename from system/diagnostic_graph_utils/launch/logging.launch.xml rename to system/autoware_diagnostic_graph_utils/launch/logging.launch.xml index f14a045919599..fd1d998ac9f22 100644 --- a/system/diagnostic_graph_utils/launch/logging.launch.xml +++ b/system/autoware_diagnostic_graph_utils/launch/logging.launch.xml @@ -2,7 +2,7 @@ - + diff --git a/system/diagnostic_graph_utils/package.xml b/system/autoware_diagnostic_graph_utils/package.xml similarity index 80% rename from system/diagnostic_graph_utils/package.xml rename to system/autoware_diagnostic_graph_utils/package.xml index 9c860d62a7928..57e35d149bc0a 100644 --- a/system/diagnostic_graph_utils/package.xml +++ b/system/autoware_diagnostic_graph_utils/package.xml @@ -1,10 +1,11 @@ - diagnostic_graph_utils + autoware_diagnostic_graph_utils 0.40.0 - The diagnostic_graph_utils package + The autoware_diagnostic_graph_utils package Takagi, Isamu + Junya Sasaki Apache License 2.0 ament_cmake_auto diff --git a/system/diagnostic_graph_utils/src/lib/graph.cpp b/system/autoware_diagnostic_graph_utils/src/lib/graph.cpp similarity index 95% rename from system/diagnostic_graph_utils/src/lib/graph.cpp rename to system/autoware_diagnostic_graph_utils/src/lib/graph.cpp index 007b42547bee1..6bee048f23400 100644 --- a/system/diagnostic_graph_utils/src/lib/graph.cpp +++ b/system/autoware_diagnostic_graph_utils/src/lib/graph.cpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "diagnostic_graph_utils/graph.hpp" +#include "autoware/diagnostic_graph_utils/graph.hpp" #include -namespace diagnostic_graph_utils +namespace autoware::diagnostic_graph_utils { DiagUnit::DiagnosticStatus DiagNode::create_diagnostic_status() const @@ -112,4 +112,4 @@ std::vector DiagGraph::links() const return create_ptrs(links_); } -} // namespace diagnostic_graph_utils +} // namespace autoware::diagnostic_graph_utils diff --git a/system/diagnostic_graph_utils/src/lib/subscription.cpp b/system/autoware_diagnostic_graph_utils/src/lib/subscription.cpp similarity index 92% rename from system/diagnostic_graph_utils/src/lib/subscription.cpp rename to system/autoware_diagnostic_graph_utils/src/lib/subscription.cpp index c10481ef8f16e..b1464fd2a6ccc 100644 --- a/system/diagnostic_graph_utils/src/lib/subscription.cpp +++ b/system/autoware_diagnostic_graph_utils/src/lib/subscription.cpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "diagnostic_graph_utils/subscription.hpp" +#include "autoware/diagnostic_graph_utils/subscription.hpp" #include -namespace diagnostic_graph_utils +namespace autoware::diagnostic_graph_utils { DiagGraphSubscription::DiagGraphSubscription() @@ -66,4 +66,4 @@ void DiagGraphSubscription::on_status(const DiagGraphStatus & msg) } } -} // namespace diagnostic_graph_utils +} // namespace autoware::diagnostic_graph_utils diff --git a/system/diagnostic_graph_utils/src/node/converter.cpp b/system/autoware_diagnostic_graph_utils/src/node/converter.cpp similarity index 88% rename from system/diagnostic_graph_utils/src/node/converter.cpp rename to system/autoware_diagnostic_graph_utils/src/node/converter.cpp index 159cc6e0c3cab..8ab7f98457cae 100644 --- a/system/diagnostic_graph_utils/src/node/converter.cpp +++ b/system/autoware_diagnostic_graph_utils/src/node/converter.cpp @@ -16,7 +16,7 @@ #include -namespace diagnostic_graph_utils +namespace autoware::diagnostic_graph_utils { ConverterNode::ConverterNode(const rclcpp::NodeOptions & options) : Node("converter", options) @@ -38,7 +38,7 @@ void ConverterNode::on_update(DiagGraph::ConstSharedPtr graph) pub_array_->publish(array); } -} // namespace diagnostic_graph_utils +} // namespace autoware::diagnostic_graph_utils #include -RCLCPP_COMPONENTS_REGISTER_NODE(diagnostic_graph_utils::ConverterNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::diagnostic_graph_utils::ConverterNode) diff --git a/system/diagnostic_graph_utils/src/node/converter.hpp b/system/autoware_diagnostic_graph_utils/src/node/converter.hpp similarity index 89% rename from system/diagnostic_graph_utils/src/node/converter.hpp rename to system/autoware_diagnostic_graph_utils/src/node/converter.hpp index 19364a8ff8240..d47d27c9626ca 100644 --- a/system/diagnostic_graph_utils/src/node/converter.hpp +++ b/system/autoware_diagnostic_graph_utils/src/node/converter.hpp @@ -15,14 +15,14 @@ #ifndef NODE__CONVERTER_HPP_ #define NODE__CONVERTER_HPP_ -#include "diagnostic_graph_utils/subscription.hpp" +#include "autoware/diagnostic_graph_utils/subscription.hpp" #include #include #include -namespace diagnostic_graph_utils +namespace autoware::diagnostic_graph_utils { class ConverterNode : public rclcpp::Node @@ -38,6 +38,6 @@ class ConverterNode : public rclcpp::Node DiagGraphSubscription sub_graph_; }; -} // namespace diagnostic_graph_utils +} // namespace autoware::diagnostic_graph_utils #endif // NODE__CONVERTER_HPP_ diff --git a/system/diagnostic_graph_utils/src/node/dump.cpp b/system/autoware_diagnostic_graph_utils/src/node/dump.cpp similarity index 96% rename from system/diagnostic_graph_utils/src/node/dump.cpp rename to system/autoware_diagnostic_graph_utils/src/node/dump.cpp index 42c66224b2c37..3999c2698a087 100644 --- a/system/diagnostic_graph_utils/src/node/dump.cpp +++ b/system/autoware_diagnostic_graph_utils/src/node/dump.cpp @@ -22,7 +22,7 @@ #include #include -namespace diagnostic_graph_utils +namespace autoware::diagnostic_graph_utils { DumpNode::DumpNode(const rclcpp::NodeOptions & options) : Node("dump", options) @@ -131,7 +131,7 @@ void DumpNode::on_update(DiagGraph::ConstSharedPtr graph) } } -} // namespace diagnostic_graph_utils +} // namespace autoware::diagnostic_graph_utils #include -RCLCPP_COMPONENTS_REGISTER_NODE(diagnostic_graph_utils::DumpNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::diagnostic_graph_utils::DumpNode) diff --git a/system/diagnostic_graph_utils/src/node/dump.hpp b/system/autoware_diagnostic_graph_utils/src/node/dump.hpp similarity index 88% rename from system/diagnostic_graph_utils/src/node/dump.hpp rename to system/autoware_diagnostic_graph_utils/src/node/dump.hpp index c990fb77a53db..9412692fa530c 100644 --- a/system/diagnostic_graph_utils/src/node/dump.hpp +++ b/system/autoware_diagnostic_graph_utils/src/node/dump.hpp @@ -15,14 +15,14 @@ #ifndef NODE__DUMP_HPP_ #define NODE__DUMP_HPP_ -#include "diagnostic_graph_utils/subscription.hpp" +#include "autoware/diagnostic_graph_utils/subscription.hpp" #include #include #include -namespace diagnostic_graph_utils +namespace autoware::diagnostic_graph_utils { class DumpNode : public rclcpp::Node @@ -47,6 +47,6 @@ class DumpNode : public rclcpp::Node std::string border_; }; -} // namespace diagnostic_graph_utils +} // namespace autoware::diagnostic_graph_utils #endif // NODE__DUMP_HPP_ diff --git a/system/diagnostic_graph_utils/src/node/logging.cpp b/system/autoware_diagnostic_graph_utils/src/node/logging.cpp similarity index 95% rename from system/diagnostic_graph_utils/src/node/logging.cpp rename to system/autoware_diagnostic_graph_utils/src/node/logging.cpp index 2dfc939469172..abe59ac28031d 100644 --- a/system/diagnostic_graph_utils/src/node/logging.cpp +++ b/system/autoware_diagnostic_graph_utils/src/node/logging.cpp @@ -22,7 +22,7 @@ #include #include -namespace diagnostic_graph_utils +namespace autoware::diagnostic_graph_utils { LoggingNode::LoggingNode(const rclcpp::NodeOptions & options) : Node("logging", options) @@ -107,7 +107,7 @@ void LoggingNode::dump_unit(DiagUnit * unit, int depth, const std::string & inde } } -} // namespace diagnostic_graph_utils +} // namespace autoware::diagnostic_graph_utils #include -RCLCPP_COMPONENTS_REGISTER_NODE(diagnostic_graph_utils::LoggingNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::diagnostic_graph_utils::LoggingNode) diff --git a/system/diagnostic_graph_utils/src/node/logging.hpp b/system/autoware_diagnostic_graph_utils/src/node/logging.hpp similarity index 90% rename from system/diagnostic_graph_utils/src/node/logging.hpp rename to system/autoware_diagnostic_graph_utils/src/node/logging.hpp index 81acfcd2ad82f..cbf28c3908105 100644 --- a/system/diagnostic_graph_utils/src/node/logging.hpp +++ b/system/autoware_diagnostic_graph_utils/src/node/logging.hpp @@ -15,7 +15,7 @@ #ifndef NODE__LOGGING_HPP_ #define NODE__LOGGING_HPP_ -#include "diagnostic_graph_utils/subscription.hpp" +#include "autoware/diagnostic_graph_utils/subscription.hpp" #include @@ -24,7 +24,7 @@ #include #include -namespace diagnostic_graph_utils +namespace autoware::diagnostic_graph_utils { class LoggingNode : public rclcpp::Node @@ -48,6 +48,6 @@ class LoggingNode : public rclcpp::Node bool enable_terminal_log_; }; -} // namespace diagnostic_graph_utils +} // namespace autoware::diagnostic_graph_utils #endif // NODE__LOGGING_HPP_ diff --git a/system/autoware_hazard_status_converter/package.xml b/system/autoware_hazard_status_converter/package.xml index f2f7d93c19132..457f98725843e 100644 --- a/system/autoware_hazard_status_converter/package.xml +++ b/system/autoware_hazard_status_converter/package.xml @@ -12,9 +12,9 @@ autoware_cmake autoware_adapi_v1_msgs + autoware_diagnostic_graph_utils autoware_system_msgs autoware_universe_utils - diagnostic_graph_utils diagnostic_msgs rclcpp rclcpp_components diff --git a/system/autoware_hazard_status_converter/src/converter.hpp b/system/autoware_hazard_status_converter/src/converter.hpp index 651ccdf45285c..01b28a54c4413 100644 --- a/system/autoware_hazard_status_converter/src/converter.hpp +++ b/system/autoware_hazard_status_converter/src/converter.hpp @@ -15,8 +15,8 @@ #ifndef CONVERTER_HPP_ #define CONVERTER_HPP_ +#include #include -#include #include #include @@ -34,11 +34,11 @@ class Converter : public rclcpp::Node private: using HazardStatusStamped = autoware_system_msgs::msg::HazardStatusStamped; - using DiagGraph = diagnostic_graph_utils::DiagGraph; - using DiagUnit = diagnostic_graph_utils::DiagUnit; + using DiagGraph = autoware::diagnostic_graph_utils::DiagGraph; + using DiagUnit = autoware::diagnostic_graph_utils::DiagUnit; void on_create(DiagGraph::ConstSharedPtr graph); void on_update(DiagGraph::ConstSharedPtr graph); - diagnostic_graph_utils::DiagGraphSubscription sub_graph_; + autoware::diagnostic_graph_utils::DiagGraphSubscription sub_graph_; rclcpp::Publisher::SharedPtr pub_hazard_; autoware::universe_utils::InterProcessPollingSubscriber< tier4_system_msgs::msg::EmergencyHoldingState> diff --git a/system/diagnostic_graph_aggregator/README.md b/system/diagnostic_graph_aggregator/README.md index c0cd78e0610c2..76513ca414541 100644 --- a/system/diagnostic_graph_aggregator/README.md +++ b/system/diagnostic_graph_aggregator/README.md @@ -80,7 +80,7 @@ ros2 launch diagnostic_graph_aggregator example-edit.launch.xml ## Debug tools - [tree](./doc/tool/tree.md) -- [diagnostic_graph_utils](../diagnostic_graph_utils/README.md) +- [autoware_diagnostic_graph_utils](../autoware_diagnostic_graph_utils/README.md) ## Graph file format From 40aff9fc6503eae43cf7561da3326e0b1378414d Mon Sep 17 00:00:00 2001 From: Junya Sasaki Date: Sat, 25 Jan 2025 00:57:12 +0900 Subject: [PATCH 319/334] feat: apply `autoware_` prefix for `velodyne_monitor` (#9976) Signed-off-by: Junya Sasaki Signed-off-by: Ryohsuke Mitsudome --- .../CHANGELOG.rst | 6 +++--- .../CMakeLists.txt | 4 ++-- .../README.md | 2 +- .../config/HDL-32E.param.yaml | 0 .../config/VLP-16.param.yaml | 0 .../config/VLP-32C.param.yaml | 0 .../config/VLS-128.param.yaml | 0 .../config/Velarray_M1600.param.yaml | 0 .../autoware}/velodyne_monitor/velodyne_monitor.hpp | 11 ++++++++--- .../launch/velodyne_monitor.launch.xml | 4 ++-- .../package.xml | 5 +++-- .../schema/velodyne_monitor.json | 0 .../src/velodyne_monitor.cpp | 9 +++++++-- 13 files changed, 26 insertions(+), 15 deletions(-) rename system/{velodyne_monitor => autoware_velodyne_monitor}/CHANGELOG.rst (98%) rename system/{velodyne_monitor => autoware_velodyne_monitor}/CMakeLists.txt (83%) rename system/{velodyne_monitor => autoware_velodyne_monitor}/README.md (99%) rename system/{velodyne_monitor => autoware_velodyne_monitor}/config/HDL-32E.param.yaml (100%) rename system/{velodyne_monitor => autoware_velodyne_monitor}/config/VLP-16.param.yaml (100%) rename system/{velodyne_monitor => autoware_velodyne_monitor}/config/VLP-32C.param.yaml (100%) rename system/{velodyne_monitor => autoware_velodyne_monitor}/config/VLS-128.param.yaml (100%) rename system/{velodyne_monitor => autoware_velodyne_monitor}/config/Velarray_M1600.param.yaml (100%) rename system/{velodyne_monitor/include => autoware_velodyne_monitor/include/autoware}/velodyne_monitor/velodyne_monitor.hpp (94%) rename system/{velodyne_monitor => autoware_velodyne_monitor}/launch/velodyne_monitor.launch.xml (57%) rename system/{velodyne_monitor => autoware_velodyne_monitor}/package.xml (82%) rename system/{velodyne_monitor => autoware_velodyne_monitor}/schema/velodyne_monitor.json (100%) rename system/{velodyne_monitor => autoware_velodyne_monitor}/src/velodyne_monitor.cpp (97%) diff --git a/system/velodyne_monitor/CHANGELOG.rst b/system/autoware_velodyne_monitor/CHANGELOG.rst similarity index 98% rename from system/velodyne_monitor/CHANGELOG.rst rename to system/autoware_velodyne_monitor/CHANGELOG.rst index 4cc3be4c7a3f0..67e7f7732653b 100644 --- a/system/velodyne_monitor/CHANGELOG.rst +++ b/system/autoware_velodyne_monitor/CHANGELOG.rst @@ -1,6 +1,6 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package velodyne_monitor -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_velodyne_monitor +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.40.0 (2024-12-12) ------------------- diff --git a/system/velodyne_monitor/CMakeLists.txt b/system/autoware_velodyne_monitor/CMakeLists.txt similarity index 83% rename from system/velodyne_monitor/CMakeLists.txt rename to system/autoware_velodyne_monitor/CMakeLists.txt index a09e1fe1bf012..ab2fe0aa5f56d 100644 --- a/system/velodyne_monitor/CMakeLists.txt +++ b/system/autoware_velodyne_monitor/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(velodyne_monitor) +project(autoware_velodyne_monitor) find_package(autoware_cmake REQUIRED) find_package(fmt) @@ -13,7 +13,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED target_link_libraries(${PROJECT_NAME} cpprest crypto fmt) rclcpp_components_register_node(${PROJECT_NAME} - PLUGIN "VelodyneMonitor" + PLUGIN "autoware::velodyne_monitor::VelodyneMonitor" EXECUTABLE ${PROJECT_NAME}_node ) diff --git a/system/velodyne_monitor/README.md b/system/autoware_velodyne_monitor/README.md similarity index 99% rename from system/velodyne_monitor/README.md rename to system/autoware_velodyne_monitor/README.md index f8381dbd41159..9d45f3d6a501f 100644 --- a/system/velodyne_monitor/README.md +++ b/system/autoware_velodyne_monitor/README.md @@ -1,4 +1,4 @@ -# velodyne_monitor +# autoware_velodyne_monitor ## Purpose diff --git a/system/velodyne_monitor/config/HDL-32E.param.yaml b/system/autoware_velodyne_monitor/config/HDL-32E.param.yaml similarity index 100% rename from system/velodyne_monitor/config/HDL-32E.param.yaml rename to system/autoware_velodyne_monitor/config/HDL-32E.param.yaml diff --git a/system/velodyne_monitor/config/VLP-16.param.yaml b/system/autoware_velodyne_monitor/config/VLP-16.param.yaml similarity index 100% rename from system/velodyne_monitor/config/VLP-16.param.yaml rename to system/autoware_velodyne_monitor/config/VLP-16.param.yaml diff --git a/system/velodyne_monitor/config/VLP-32C.param.yaml b/system/autoware_velodyne_monitor/config/VLP-32C.param.yaml similarity index 100% rename from system/velodyne_monitor/config/VLP-32C.param.yaml rename to system/autoware_velodyne_monitor/config/VLP-32C.param.yaml diff --git a/system/velodyne_monitor/config/VLS-128.param.yaml b/system/autoware_velodyne_monitor/config/VLS-128.param.yaml similarity index 100% rename from system/velodyne_monitor/config/VLS-128.param.yaml rename to system/autoware_velodyne_monitor/config/VLS-128.param.yaml diff --git a/system/velodyne_monitor/config/Velarray_M1600.param.yaml b/system/autoware_velodyne_monitor/config/Velarray_M1600.param.yaml similarity index 100% rename from system/velodyne_monitor/config/Velarray_M1600.param.yaml rename to system/autoware_velodyne_monitor/config/Velarray_M1600.param.yaml diff --git a/system/velodyne_monitor/include/velodyne_monitor/velodyne_monitor.hpp b/system/autoware_velodyne_monitor/include/autoware/velodyne_monitor/velodyne_monitor.hpp similarity index 94% rename from system/velodyne_monitor/include/velodyne_monitor/velodyne_monitor.hpp rename to system/autoware_velodyne_monitor/include/autoware/velodyne_monitor/velodyne_monitor.hpp index 841199a845bbf..092dcb24d7ae9 100644 --- a/system/velodyne_monitor/include/velodyne_monitor/velodyne_monitor.hpp +++ b/system/autoware_velodyne_monitor/include/autoware/velodyne_monitor/velodyne_monitor.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef VELODYNE_MONITOR__VELODYNE_MONITOR_HPP_ -#define VELODYNE_MONITOR__VELODYNE_MONITOR_HPP_ +#ifndef AUTOWARE__VELODYNE_MONITOR__VELODYNE_MONITOR_HPP_ +#define AUTOWARE__VELODYNE_MONITOR__VELODYNE_MONITOR_HPP_ /** * @file velodyne_monitor.hpp @@ -31,6 +31,9 @@ // Include after diagnostic_updater because it causes errors #include +namespace autoware::velodyne_monitor +{ + namespace http = web::http; namespace client = web::http::client; namespace json = web::json; @@ -115,4 +118,6 @@ class VelodyneMonitor : public rclcpp::Node {DiagStatus::OK, "OK"}, {DiagStatus::WARN, "RPM low"}, {DiagStatus::ERROR, "RPM too low"}}; }; -#endif // VELODYNE_MONITOR__VELODYNE_MONITOR_HPP_ +} // namespace autoware::velodyne_monitor + +#endif // AUTOWARE__VELODYNE_MONITOR__VELODYNE_MONITOR_HPP_ diff --git a/system/velodyne_monitor/launch/velodyne_monitor.launch.xml b/system/autoware_velodyne_monitor/launch/velodyne_monitor.launch.xml similarity index 57% rename from system/velodyne_monitor/launch/velodyne_monitor.launch.xml rename to system/autoware_velodyne_monitor/launch/velodyne_monitor.launch.xml index 0dbbc39a9f9e4..3d72d4f1f077e 100644 --- a/system/velodyne_monitor/launch/velodyne_monitor.launch.xml +++ b/system/autoware_velodyne_monitor/launch/velodyne_monitor.launch.xml @@ -1,8 +1,8 @@ - + - + diff --git a/system/velodyne_monitor/package.xml b/system/autoware_velodyne_monitor/package.xml similarity index 82% rename from system/velodyne_monitor/package.xml rename to system/autoware_velodyne_monitor/package.xml index 0dc8ae5f00a5d..677df93ecde43 100644 --- a/system/velodyne_monitor/package.xml +++ b/system/autoware_velodyne_monitor/package.xml @@ -1,10 +1,11 @@ - velodyne_monitor + autoware_velodyne_monitor 0.40.0 - The velodyne_monitor package + The autoware_velodyne_monitor package Fumihito Ito + Junya Sasaki Apache License 2.0 ament_cmake_auto diff --git a/system/velodyne_monitor/schema/velodyne_monitor.json b/system/autoware_velodyne_monitor/schema/velodyne_monitor.json similarity index 100% rename from system/velodyne_monitor/schema/velodyne_monitor.json rename to system/autoware_velodyne_monitor/schema/velodyne_monitor.json diff --git a/system/velodyne_monitor/src/velodyne_monitor.cpp b/system/autoware_velodyne_monitor/src/velodyne_monitor.cpp similarity index 97% rename from system/velodyne_monitor/src/velodyne_monitor.cpp rename to system/autoware_velodyne_monitor/src/velodyne_monitor.cpp index f9ab3ea14b4c0..83429229b7c4c 100644 --- a/system/velodyne_monitor/src/velodyne_monitor.cpp +++ b/system/autoware_velodyne_monitor/src/velodyne_monitor.cpp @@ -17,7 +17,7 @@ * @brief Velodyne monitor class */ -#include "velodyne_monitor/velodyne_monitor.hpp" +#include "autoware/velodyne_monitor/velodyne_monitor.hpp" #include @@ -30,6 +30,9 @@ #define FMT_HEADER_ONLY #include +namespace autoware::velodyne_monitor +{ + VelodyneMonitor::VelodyneMonitor(const rclcpp::NodeOptions & options) : Node("velodyne_monitor", options), updater_(this) { @@ -231,5 +234,7 @@ float VelodyneMonitor::convertTemperature(int raw) return std::sqrt(2.1962e6 + (1.8639 - static_cast(raw) * 5.0 / 4096) / 3.88e-6) - 1481.96; } +} // namespace autoware::velodyne_monitor + #include -RCLCPP_COMPONENTS_REGISTER_NODE(VelodyneMonitor) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::velodyne_monitor::VelodyneMonitor) From e8b05c23c6b4f74cde377d122a63b84a02478a77 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 27 Jan 2025 08:46:10 +0900 Subject: [PATCH 320/334] refactor(goal_planner): divide extract_dynamic_object/is_goal_in_lanes util function (#10019) Signed-off-by: Mamoru Sobue --- .../util.hpp | 9 +++ .../src/goal_planner_module.cpp | 64 +++--------------- .../src/util.cpp | 65 +++++++++++++++++++ 3 files changed, 82 insertions(+), 56 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/util.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/util.hpp index f00d9d41622e9..7f375da295fb9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/util.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/util.hpp @@ -185,6 +185,15 @@ std::optional calcRefinedGoal( std::optional calcClosestPose( const lanelet::ConstLineString3d line, const Point & query_point); +autoware_perception_msgs::msg::PredictedObjects extract_dynamic_objects( + const autoware_perception_msgs::msg::PredictedObjects & original_objects, + const route_handler::RouteHandler & route_handler, const GoalPlannerParameters & parameters, + const double vehicle_width); + +bool is_goal_reachable_on_path( + const lanelet::ConstLanelets current_lanes, const route_handler::RouteHandler & route_handler, + const bool left_side_parking); + } // namespace autoware::behavior_path_planner::goal_planner_utils #endif // AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__UTIL_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index c7e32a47a59f9..0a92f6d99dfeb 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -615,29 +615,11 @@ void GoalPlannerModule::updateData() universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); // extract static and dynamic objects in extraction polygon for path collision check - const auto & p = parameters_; - const auto & rh = *(planner_data_->route_handler); - const auto objects = *(planner_data_->dynamic_object); - const double vehicle_width = planner_data_->parameters.vehicle_width; - const auto pull_over_lanes = goal_planner_utils::getPullOverLanes( - rh, left_side_parking_, p->backward_goal_search_length, p->forward_goal_search_length); - const auto objects_extraction_polygon = goal_planner_utils::generateObjectExtractionPolygon( - pull_over_lanes, left_side_parking_, p->detection_bound_offset, - p->margin_from_boundary + p->max_lateral_offset + vehicle_width); - if (objects_extraction_polygon.has_value()) { - debug_data_.objects_extraction_polygon = objects_extraction_polygon.value(); - } - PredictedObjects dynamic_target_objects{}; - for (const auto & object : objects.objects) { - const auto object_polygon = universe_utils::toPolygon2d(object); - if ( - objects_extraction_polygon.has_value() && - boost::geometry::intersects(object_polygon, objects_extraction_polygon.value())) { - dynamic_target_objects.objects.push_back(object); - } - } + const auto dynamic_target_objects = goal_planner_utils::extract_dynamic_objects( + *(planner_data_->dynamic_object), *(planner_data_->route_handler), *parameters_, + planner_data_->parameters.vehicle_width); const auto static_target_objects = utils::path_safety_checker::filterObjectsByVelocity( - dynamic_target_objects, p->th_moving_object_velocity); + dynamic_target_objects, parameters_->th_moving_object_velocity); // update goal searcher and generate goal candidates if (goal_candidates_.empty()) { @@ -753,39 +735,9 @@ bool GoalPlannerModule::isExecutionRequested() const // check if goal_pose is in current_lanes or neighboring road lanes const lanelet::ConstLanelets current_lanes = utils::getCurrentLanesFromPath(getPreviousModuleOutput().reference_path, planner_data_); - const auto getNeighboringLane = - [&](const lanelet::ConstLanelet & lane) -> std::optional { - return left_side_parking_ ? route_handler->getLeftLanelet(lane, false, true) - : route_handler->getRightLanelet(lane, false, true); - }; - lanelet::ConstLanelets goal_check_lanes = current_lanes; - for (const auto & lane : current_lanes) { - auto neighboring_lane = getNeighboringLane(lane); - while (neighboring_lane) { - goal_check_lanes.push_back(neighboring_lane.value()); - neighboring_lane = getNeighboringLane(neighboring_lane.value()); - } - } - const bool goal_is_in_current_segment_lanes = std::any_of( - goal_check_lanes.begin(), goal_check_lanes.end(), [&](const lanelet::ConstLanelet & lane) { - return lanelet::utils::isInLanelet(goal_pose, lane); - }); - - // check that goal is in current neighbor shoulder lane - const bool goal_is_in_current_shoulder_lanes = std::invoke([&]() { - for (const auto & lane : current_lanes) { - const auto shoulder_lane = left_side_parking_ ? route_handler->getLeftShoulderLanelet(lane) - : route_handler->getRightShoulderLanelet(lane); - if (shoulder_lane && lanelet::utils::isInLanelet(goal_pose, *shoulder_lane)) { - return true; - } - } - return false; - }); - - // if goal is not in current_lanes and current_shoulder_lanes, do not execute goal_planner, - // because goal arc coordinates cannot be calculated. - if (!goal_is_in_current_segment_lanes && !goal_is_in_current_shoulder_lanes) { + const bool is_goal_reachable = goal_planner_utils::is_goal_reachable_on_path( + current_lanes, *(planner_data_->route_handler), left_side_parking_); + if (!is_goal_reachable) { return false; } @@ -793,7 +745,7 @@ bool GoalPlannerModule::isExecutionRequested() const // 1) goal_pose is in current_lanes, plan path to the original fixed goal // 2) goal_pose is NOT in current_lanes, do not execute goal_planner if (!utils::isAllowedGoalModification(route_handler)) { - return goal_is_in_current_segment_lanes; + return is_goal_reachable; } // if goal arc coordinates can be calculated, check if goal is in request_length diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp index a2a64fc700676..fb39a34c9ac91 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp @@ -831,4 +831,69 @@ std::optional calcClosestPose( return closest_pose; } +autoware_perception_msgs::msg::PredictedObjects extract_dynamic_objects( + const autoware_perception_msgs::msg::PredictedObjects & original_objects, + const route_handler::RouteHandler & route_handler, const GoalPlannerParameters & parameters, + const double vehicle_width) +{ + const bool left_side_parking = parameters.parking_policy == ParkingPolicy::LEFT_SIDE; + const auto pull_over_lanes = goal_planner_utils::getPullOverLanes( + route_handler, left_side_parking, parameters.backward_goal_search_length, + parameters.forward_goal_search_length); + const auto objects_extraction_polygon = goal_planner_utils::generateObjectExtractionPolygon( + pull_over_lanes, left_side_parking, parameters.detection_bound_offset, + parameters.margin_from_boundary + parameters.max_lateral_offset + vehicle_width); + + PredictedObjects dynamic_target_objects{}; + for (const auto & object : original_objects.objects) { + const auto object_polygon = universe_utils::toPolygon2d(object); + if ( + objects_extraction_polygon.has_value() && + boost::geometry::intersects(object_polygon, objects_extraction_polygon.value())) { + dynamic_target_objects.objects.push_back(object); + } + } + return dynamic_target_objects; +} + +bool is_goal_reachable_on_path( + const lanelet::ConstLanelets current_lanes, const route_handler::RouteHandler & route_handler, + const bool left_side_parking) +{ + const Pose goal_pose = route_handler.getOriginalGoalPose(); + const auto getNeighboringLane = + [&](const lanelet::ConstLanelet & lane) -> std::optional { + return left_side_parking ? route_handler.getLeftLanelet(lane, false, true) + : route_handler.getRightLanelet(lane, false, true); + }; + lanelet::ConstLanelets goal_check_lanes = current_lanes; + for (const auto & lane : current_lanes) { + auto neighboring_lane = getNeighboringLane(lane); + while (neighboring_lane) { + goal_check_lanes.push_back(neighboring_lane.value()); + neighboring_lane = getNeighboringLane(neighboring_lane.value()); + } + } + const bool goal_is_in_current_segment_lanes = std::any_of( + goal_check_lanes.begin(), goal_check_lanes.end(), [&](const lanelet::ConstLanelet & lane) { + return lanelet::utils::isInLanelet(goal_pose, lane); + }); + + // check that goal is in current neighbor shoulder lane + const bool goal_is_in_current_shoulder_lanes = std::invoke([&]() { + for (const auto & lane : current_lanes) { + const auto shoulder_lane = left_side_parking ? route_handler.getLeftShoulderLanelet(lane) + : route_handler.getRightShoulderLanelet(lane); + if (shoulder_lane && lanelet::utils::isInLanelet(goal_pose, *shoulder_lane)) { + return true; + } + } + return false; + }); + + // if goal is not in current_lanes and current_shoulder_lanes, do not execute goal_planner, + // because goal arc coordinates cannot be calculated. + return goal_is_in_current_segment_lanes || goal_is_in_current_shoulder_lanes; +} + } // namespace autoware::behavior_path_planner::goal_planner_utils From 7fd0259c6d44a0333901df8f9df1da2888d971df Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Mon, 27 Jan 2025 00:21:48 +0000 Subject: [PATCH 321/334] chore: update CODEOWNERS (#9847) Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> Co-authored-by: github-actions --- .github/CODEOWNERS | 73 ++++++++++++++++++++++------------------------ 1 file changed, 35 insertions(+), 38 deletions(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 28a8ab262789e..4cff38cfeb145 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -10,17 +10,13 @@ common/autoware_glog_component/** takamasa.horibe@tier4.jp common/autoware_goal_distance_calculator/** taiki.tanaka@tier4.jp common/autoware_grid_map_utils/** maxime.clement@tier4.jp common/autoware_interpolation/** fumiya.watanabe@tier4.jp takayuki.murooka@tier4.jp -common/autoware_kalman_filter/** koji.minoda@tier4.jp takeshi.ishita@tier4.jp yukihiro.saito@tier4.jp common/autoware_motion_utils/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp common/autoware_object_recognition_utils/** shunsuke.miura@tier4.jp takayuki.murooka@tier4.jp yoshi.ri@tier4.jp -common/autoware_osqp_interface/** fumiya.watanabe@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp common/autoware_path_distance_calculator/** isamu.takagi@tier4.jp -common/autoware_point_types/** david.wong@tier4.jp max.schmeller@tier4.jp common/autoware_polar_grid/** yukihiro.saito@tier4.jp common/autoware_pyplot/** mamoru.sobue@tier4.jp yukinari.hisaki.2@tier4.jp -common/autoware_qp_interface/** fumiya.watanabe@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp common/autoware_signal_processing/** ali.boyali@tier4.jp fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp -common/autoware_test_utils/** kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp zulfaqar.azmi@tier4.jp +common/autoware_test_utils/** kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp yukinari.hisaki.2@tier4.jp zulfaqar.azmi@tier4.jp common/autoware_testing/** adam.dabrowski@robotec.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp common/autoware_time_utils/** christopherj.ho@gmail.com shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp common/autoware_traffic_light_recognition_marker_publisher/** shumpei.wakabayashi@tier4.jp takeshi.miura@tier4.jp tomoya.kimura@tier4.jp @@ -31,6 +27,7 @@ common/autoware_vehicle_info_utils/** mamoru.sobue@tier4.jp shumpei.wakabayashi@ common/tier4_api_utils/** isamu.takagi@tier4.jp control/autoware_autonomous_emergency_braking/** alqudah.mohammad@tier4.jp daniel.sanchez@tier4.jp kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp control/autoware_collision_detector/** go.sakayori@tier4.jp kyoichi.sugahara@tier4.jp tomohito.ando@tier4.jp +control/autoware_control_performance_analysis/** berkay@leodrive.ai fumiya.watanabe@tier4.jp junya.sasaki@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp control/autoware_control_validator/** kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp control/autoware_external_cmd_selector/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp control/autoware_joy_controller/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp @@ -39,20 +36,19 @@ control/autoware_mpc_lateral_controller/** kyoichi.sugahara@tier4.jp takamasa.ho control/autoware_obstacle_collision_checker/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp control/autoware_operation_mode_transition_manager/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp control/autoware_pid_longitudinal_controller/** mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp yuki.takagi@tier4.jp +control/autoware_predicted_path_checker/** berkay@leodrive.ai junya.sasaki@tier4.jp control/autoware_pure_pursuit/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp control/autoware_shift_decider/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp control/autoware_smart_mpc_trajectory_follower/** kosuke.takeuchi@tier4.jp masayuki.aino@proxima-ai-tech.com takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp control/autoware_trajectory_follower_base/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp control/autoware_trajectory_follower_node/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp control/autoware_vehicle_cmd_gate/** takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp -control/control_performance_analysis/** berkay@leodrive.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp -control/predicted_path_checker/** berkay@leodrive.ai evaluator/autoware_control_evaluator/** daniel.sanchez@tier4.jp kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp temkei.kem@tier4.jp +evaluator/autoware_kinematic_evaluator/** dominik.jargot@robotec.ai fumiya.watanabe@tier4.jp junya.sasaki@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp +evaluator/autoware_localization_evaluator/** anh.nguyen.2@tier4.jp dominik.jargot@robotec.ai junya.sasaki@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp +evaluator/autoware_perception_online_evaluator/** fumiya.watanabe@tier4.jp junya.sasaki@tier4.jp kosuke.takeuchi@tier4.jp kotaro.uetake@tier4.jp kyoichi.sugahara@tier4.jp shunsuke.miura@tier4.jp yoshi.ri@tier4.jp evaluator/autoware_planning_evaluator/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp temkei.kem@tier4.jp -evaluator/autoware_kinematic_evaluator/** dominik.jargot@robotec.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp junya.sasaki@tier4.jp -evaluator/localization_evaluator/** anh.nguyen.2@tier4.jp dominik.jargot@robotec.ai koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp -evaluator/autoware_perception_online_evaluator/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp kotaro.uetake@tier4.jp kyoichi.sugahara@tier4.jp shunsuke.miura@tier4.jp yoshi.ri@tier4.jp junya.sasaki@tier4.jp -evaluator/scenario_simulator_v2_adapter/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp takamasa.horibe@tier4.jp temkei.kem@tier4.jp +evaluator/autoware_scenario_simulator_v2_adapter/** junya.sasaki@tier4.jp kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp takamasa.horibe@tier4.jp temkei.kem@tier4.jp launch/tier4_autoware_api_launch/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp launch/tier4_control_launch/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp launch/tier4_localization_launch/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp @@ -61,7 +57,7 @@ launch/tier4_perception_launch/** shunsuke.miura@tier4.jp taekjin.lee@tier4.jp y launch/tier4_planning_launch/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zhe.shen@tier4.jp zulfaqar.azmi@tier4.jp launch/tier4_sensing_launch/** yukihiro.saito@tier4.jp launch/tier4_simulator_launch/** keisuke.shima@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp -launch/tier4_system_launch/** fumihito.ito@tier4.jp tetsuhiro.kawaguchi@tier4.jp junya.sasaki@tier4.jp +launch/tier4_system_launch/** fumihito.ito@tier4.jp tetsuhiro.kawaguchi@tier4.jp launch/tier4_vehicle_launch/** yukihiro.saito@tier4.jp localization/autoware_ekf_localizer/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp takamasa.horibe@tier4.jp takeshi.ishita@tier4.jp yamato.ando@tier4.jp localization/autoware_geo_pose_projector/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp @@ -70,7 +66,6 @@ localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/* localization/autoware_landmark_based_localizer/autoware_landmark_manager/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/** shintaro.sakoda@tier4.jp yamato.ando@tier4.jp localization/autoware_localization_error_monitor/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp -localization/autoware_localization_util/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp localization/autoware_ndt_scan_matcher/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp localization/autoware_pose2twist/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp localization/autoware_pose_covariance_modifier/** melike@leodrive.ai @@ -134,12 +129,13 @@ planning/autoware_costmap_generator/** kosuke.takeuchi@tier4.jp takamasa.horibe@ planning/autoware_external_velocity_limit_selector/** satoshi.ota@tier4.jp shinnosuke.hirakawa@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/autoware_freespace_planner/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp planning/autoware_freespace_planning_algorithms/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp -planning/autoware_mission_planner/** isamu.takagi@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp ryohsuke.mitsudome@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp +planning/autoware_mission_planner_universe/** isamu.takagi@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp ryohsuke.mitsudome@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp planning/autoware_objects_of_interest_marker_interface/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp zulfaqar.azmi@tier4.jp planning/autoware_obstacle_cruise_planner/** berkay@leodrive.ai kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp yuki.takagi@tier4.jp planning/autoware_obstacle_stop_planner/** berkay@leodrive.ai bnk@leodrive.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp planning/autoware_path_optimizer/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp planning/autoware_path_smoother/** maxime.clement@tier4.jp takayuki.murooka@tier4.jp +planning/autoware_planning_factor_interface/** mamoru.sobue@tier4.jp satoshi.ota@tier4.jp planning/autoware_planning_test_manager/** kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp planning/autoware_planning_topic_converter/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp planning/autoware_planning_validator/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp @@ -147,7 +143,6 @@ planning/autoware_remaining_distance_time_calculator/** ahmed.ebrahim@leodrive.a planning/autoware_route_handler/** alqudah.mohammad@tier4.jp fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp takayuki.murooka@tier4.jp zulfaqar.azmi@tier4.jp planning/autoware_rtc_interface/** fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp taiki.tanaka@tier4.jp planning/autoware_scenario_selector/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp -planning/autoware_static_centerline_generator/** kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp planning/autoware_surround_obstacle_checker/** go.sakayori@tier4.jp satoshi.ota@tier4.jp planning/autoware_velocity_smoother/** fumiya.watanabe@tier4.jp go.sakayori@tier4.jp makoto.kurihara@tier4.jp satoshi.ota@tier4.jp takamasa.horibe@tier4.jp planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/** alqudah.mohammad@tier4.jp fumiya.watanabe@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp @@ -155,7 +150,7 @@ planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/** alqudah.mohammad@tier4.jp fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp maxime.clement@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/** daniel.sanchez@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/behavior_path_planner/autoware_behavior_path_lane_change_module/** alqudah.mohammad@tier4.jp fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp -planning/behavior_path_planner/autoware_behavior_path_planner/** fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp +planning/behavior_path_planner/autoware_behavior_path_planner/** fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp planning/behavior_path_planner/autoware_behavior_path_planner_common/** alqudah.mohammad@tier4.jp daniel.sanchez@tier4.jp fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/** daniel.sanchez@tier4.jp maxime.clement@tier4.jp planning/behavior_path_planner/autoware_behavior_path_side_shift_module/** fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp @@ -181,8 +176,8 @@ planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/** planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/** mamoru.sobue@tier4.jp maxime.clement@tier4.jp planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/** alqudah.mohammad@tier4.jp maxime.clement@tier4.jp planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/** alqudah.mohammad@tier4.jp mamoru.sobue@tier4.jp maxime.clement@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp -planning/motion_velocity_planner/autoware_motion_velocity_planner_common/** alqudah.mohammad@tier4.jp maxime.clement@tier4.jp -planning/motion_velocity_planner/autoware_motion_velocity_planner_node/** alqudah.mohammad@tier4.jp maxime.clement@tier4.jp +planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/** alqudah.mohammad@tier4.jp maxime.clement@tier4.jp +planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/** alqudah.mohammad@tier4.jp maxime.clement@tier4.jp planning/sampling_based_planner/autoware_bezier_sampler/** maxime.clement@tier4.jp planning/sampling_based_planner/autoware_frenet_planner/** maxime.clement@tier4.jp planning/sampling_based_planner/autoware_path_sampler/** maxime.clement@tier4.jp @@ -201,47 +196,49 @@ sensing/autoware_radar_tracks_noise_filter/** satoshi.tanaka@tier4.jp shunsuke.m sensing/autoware_vehicle_velocity_converter/** ryu.yamamoto@tier4.jp sensing/livox/autoware_livox_tag_filter/** kenzo.lobos@tier4.jp ryohsuke.mitsudome@tier4.jp simulator/autoware_carla_interface/** maxime.clement@tier4.jp mradityagio@gmail.com -simulator/dummy_perception_publisher/** yukihiro.saito@tier4.jp -simulator/fault_injection/** keisuke.shima@tier4.jp -simulator/learning_based_vehicle_model/** maxime.clement@tier4.jp nagy.tomas@tier4.jp -simulator/autoware_simple_planning_simulator/** mamoru.sobue@tier4.jp maxime.clement@tier4.jp takamasa.horibe@tier4.jp temkei.kem@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp kotaro.yoshimoto@tier4.jp junya.sasaki@tier4.jp -simulator/tier4_dummy_object_rviz_plugin/** yukihiro.saito@tier4.jp +simulator/autoware_dummy_perception_publisher/** junya.sasaki@tier4.jp yukihiro.saito@tier4.jp +simulator/autoware_fault_injection/** junya.sasaki@tier4.jp keisuke.shima@tier4.jp +simulator/autoware_learning_based_vehicle_model/** junya.sasaki@tier4.jp maxime.clement@tier4.jp nagy.tomas@tier4.jp +simulator/autoware_simple_planning_simulator/** junya.sasaki@tier4.jp kotaro.yoshimoto@tier4.jp mamoru.sobue@tier4.jp maxime.clement@tier4.jp takamasa.horibe@tier4.jp temkei.kem@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp simulator/autoware_vehicle_door_simulator/** isamu.takagi@tier4.jp junya.sasaki@tier4.jp +simulator/tier4_dummy_object_rviz_plugin/** yukihiro.saito@tier4.jp +system/autoware_bluetooth_monitor/** fumihito.ito@tier4.jp junya.sasaki@tier4.jp system/autoware_component_monitor/** baris@leodrive.ai memin@leodrive.ai yavuz@leodrive.ai system/autoware_default_adapi/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp +system/autoware_default_adapi_helpers/autoware_adapi_adaptors/** isamu.takagi@tier4.jp junya.sasaki@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp +system/autoware_default_adapi_helpers/autoware_adapi_visualizers/** isamu.takagi@tier4.jp junya.sasaki@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp +system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/** isamu.takagi@tier4.jp junya.sasaki@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp +system/autoware_diagnostic_graph_utils/** isamu.takagi@tier4.jp junya.sasaki@tier4.jp +system/autoware_dummy_diag_publisher/** fumihito.ito@tier4.jp tetsuhiro.kawaguchi@tier4.jp +system/autoware_dummy_infrastructure/** junya.sasaki@tier4.jp ryohsuke.mitsudome@tier4.jp +system/autoware_duplicated_node_checker/** junya.sasaki@tier4.jp mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp uken.ryu@tier4.jp +system/autoware_hazard_status_converter/** isamu.takagi@tier4.jp junya.sasaki@tier4.jp +system/autoware_mrm_comfortable_stop_operator/** junya.sasaki@tier4.jp makoto.kurihara@tier4.jp tomohito.ando@tier4.jp +system/autoware_mrm_emergency_stop_operator/** junya.sasaki@tier4.jp makoto.kurihara@tier4.jp tomohito.ando@tier4.jp +system/autoware_mrm_handler/** junya.sasaki@tier4.jp makoto.kurihara@tier4.jp ryuta.kambe@tier4.jp tetsuhiro.kawaguchi@tier4.jp system/autoware_processing_time_checker/** kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp -system/autoware_bluetooth_monitor/** fumihito.ito@tier4.jp junya.sasaki@tier4.jp +system/autoware_system_monitor/** fumihito.ito@tier4.jp junya.sasaki@tier4.jp tetsuhiro.kawaguchi@tier4.jp +system/autoware_topic_relay_controller/** makoto.kurihara@tier4.jp tetsuhiro.kawaguchi@tier4.jp +system/autoware_velodyne_monitor/** fumihito.ito@tier4.jp junya.sasaki@tier4.jp system/component_state_monitor/** isamu.takagi@tier4.jp -system/autoware_default_adapi_helpers/autoware_adapi_adaptors/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp -system/autoware_default_adapi_helpers/autoware_adapi_visualizers/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp -system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp system/diagnostic_graph_aggregator/** isamu.takagi@tier4.jp -system/diagnostic_graph_utils/** isamu.takagi@tier4.jp -system/autoware_dummy_diag_publisher/** fumihito.ito@tier4.jp tetsuhiro.kawaguchi@tier4.jp -system/autoware_dummy_infrastructure/** ryohsuke.mitsudome@tier4.jp -system/autoware_duplicated_node_checker/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp uken.ryu@tier4.jp junya.sasaki@tier4.jp -system/hazard_status_converter/** isamu.takagi@tier4.jp -system/autoware_mrm_comfortable_stop_operator/** makoto.kurihara@tier4.jp tomohito.ando@tier4.jp junya.sasaki@tier4.jp -system/mrm_emergency_stop_operator/** makoto.kurihara@tier4.jp tomohito.ando@tier4.jp -system/mrm_handler/** makoto.kurihara@tier4.jp ryuta.kambe@tier4.jp tetsuhiro.kawaguchi@tier4.jp system/system_diagnostic_monitor/** isamu.takagi@tier4.jp -system/autoware_system_monitor/** fumihito.ito@tier4.jp tetsuhiro.kawaguchi@tier4.jp junya.sasaki@tier4.jp system/topic_state_monitor/** ryohsuke.mitsudome@tier4.jp -system/velodyne_monitor/** fumihito.ito@tier4.jp tools/reaction_analyzer/** berkay@leodrive.ai vehicle/autoware_accel_brake_map_calibrator/** eiki.nagata.2@tier4.jp taiki.tanaka@tier4.jp takeshi.miura@tier4.jp tomoya.kimura@tier4.jp vehicle/autoware_external_cmd_converter/** eiki.nagata.2@tier4.jp takamasa.horibe@tier4.jp vehicle/autoware_raw_vehicle_cmd_converter/** kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp sho.iwasawa.2@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp vehicle/autoware_steer_offset_estimator/** taiki.tanaka@tier4.jp +visualization/autoware_bag_time_manager_rviz_plugin/** junya.sasaki@tier4.jp taiki.tanaka@tier4.jp visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/** ahmed.ebrahim@leodrive.ai visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/** khalil@leodrive.ai visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/** satoshi.ota@tier4.jp takayuki.murooka@tier4.jp visualization/autoware_perception_rviz_plugin/** opensource@apex.ai shunsuke.miura@tier4.jp taiki.tanaka@tier4.jp takeshi.miura@tier4.jp yoshi.ri@tier4.jp -visualization/bag_time_manager_rviz_plugin/** taiki.tanaka@tier4.jp visualization/tier4_adapi_rviz_plugin/** hiroki.ota@tier4.jp isamu.takagi@tier4.jp kosuke.takeuchi@tier4.jp visualization/tier4_camera_view_rviz_plugin/** makoto.ybauta@tier4.jp uken.ryu@tier4.jp visualization/tier4_datetime_rviz_plugin/** isamu.takagi@tier4.jp visualization/tier4_localization_rviz_plugin/** isamu.takagi@tier4.jp takamasa.horibe@tier4.jp yamato.ando@tier4.jp +visualization/tier4_planning_factor_rviz_plugin/** mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp visualization/tier4_planning_rviz_plugin/** takayuki.murooka@tier4.jp yukihiro.saito@tier4.jp visualization/tier4_state_rviz_plugin/** hiroki.ota@tier4.jp isamu.takagi@tier4.jp khalil@leodrive.ai visualization/tier4_system_rviz_plugin/** koji.minoda@tier4.jp From 0a708dab29f759334335bd365ec1ecd9ddff48cf Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Mon, 27 Jan 2025 09:49:14 +0900 Subject: [PATCH 322/334] feat: operation mode debug panel (#8933) Signed-off-by: Takagi, Isamu --- .../tier4_adapi_rviz_plugin/CMakeLists.txt | 2 +- .../tier4_adapi_rviz_plugin/README.md | 2 + .../icons/classes/StatePanel.png | Bin 18815 -> 0 bytes .../plugins/plugin_description.xml | 4 +- .../src/operation_mode_debug_panel.cpp | 221 ++++++ .../src/operation_mode_debug_panel.hpp | 76 +++ .../src/state_panel.cpp | 633 ------------------ .../src/state_panel.hpp | 206 ------ 8 files changed, 302 insertions(+), 842 deletions(-) delete mode 100644 visualization/tier4_adapi_rviz_plugin/icons/classes/StatePanel.png create mode 100644 visualization/tier4_adapi_rviz_plugin/src/operation_mode_debug_panel.cpp create mode 100644 visualization/tier4_adapi_rviz_plugin/src/operation_mode_debug_panel.hpp delete mode 100644 visualization/tier4_adapi_rviz_plugin/src/state_panel.cpp delete mode 100644 visualization/tier4_adapi_rviz_plugin/src/state_panel.hpp diff --git a/visualization/tier4_adapi_rviz_plugin/CMakeLists.txt b/visualization/tier4_adapi_rviz_plugin/CMakeLists.txt index f06ab33823a3f..c65f1de69e414 100644 --- a/visualization/tier4_adapi_rviz_plugin/CMakeLists.txt +++ b/visualization/tier4_adapi_rviz_plugin/CMakeLists.txt @@ -12,7 +12,7 @@ set(CMAKE_INCLUDE_CURRENT_DIR ON) ament_auto_add_library(${PROJECT_NAME} SHARED src/route_tool.cpp src/route_panel.cpp - src/state_panel.cpp + src/operation_mode_debug_panel.cpp src/door_panel.cpp ) diff --git a/visualization/tier4_adapi_rviz_plugin/README.md b/visualization/tier4_adapi_rviz_plugin/README.md index 4056130776178..e067e6d09b11d 100644 --- a/visualization/tier4_adapi_rviz_plugin/README.md +++ b/visualization/tier4_adapi_rviz_plugin/README.md @@ -1,5 +1,7 @@ # tier4_adapi_rviz_plugin +This package contains tools for testing AD API. For general AD API usage, we recommend using [tier4_state_rviz_plugin](../tier4_state_rviz_plugin/README.md). + ## RoutePanel To use the panel, set the topic name from 2D Goal Pose Tool to `/rviz/routing/pose`. diff --git a/visualization/tier4_adapi_rviz_plugin/icons/classes/StatePanel.png b/visualization/tier4_adapi_rviz_plugin/icons/classes/StatePanel.png deleted file mode 100644 index 6a67573717ae18b6008e00077defb27256415663..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 18815 zcmc#)ig}7!VL~0BI3P>4u>jX{5WQyQGE==@gXiZcsv`yJ3)ShVHnpzyIKV zx%UIl!@PCQ*=Oy&*IwtGaAid)9L!gkAP@*gMjEOL0wKly`$K;YTnXsp8Ulf2BxRtY zY95&f%V-`irs2ZJD-E_>W|QJ#$f(lDGUzn9FhfdJ6ls+f7g13tl1h)8=nGVpD&-eU zEXJbkUMvxiN-bt%sdy?0Ws#;2U}Tww$D9k?tJrv3b90N4w6q7mY>Vu>j)cq`Gq>&g ztxVotd7x=_%0QrfCTU6#h!Tqc9R&LG1r-?ts`)>?Y`h5pRS_lWag8OXawfXJHk9@r zwSCxzbPRm-g9n1hq$!Q)8a9)#!i(M_cz&h|6vnpsyKVD7twGSL0-4KL6Q=BD1ZeP- zzfzYzWVM-q+?d)>KwJl;5;rOeaVP-p8?mb$R~c z!r4STVAB1bJ?W`Q1N^wk6a>;QVI%JxOu}Vf{^G|)Co3MGH{(9RMV<;nHU4Za)%KSC z`;I=`QN*K~)?CjlT%q3CJ0d$G%J_7^;$JI4Ms3f{6oyJDbjK_N!4ju2 z&$?3P$rm$WTureE-aq`r%H%qf&xx}1+^E65XE7*U*@ASHv#;8ex#{Xeuo?I&+x*og zCp;~E10-qE582|U!y4K~`SF#B31Gjpj3?LDSx6hf<#=NRr5x>o;P$^l9osYrEfL{WYjQydU9;g?K5#3k=W*FphTCuCHewl5&`Uu9F)(f>MMOxB>pE z88huBN|GrNq|eH~M(ELpl-tdZkMhs%;OV+^2?6{7^3=m>h4(Sn1AF4SLTeDL;O9g! zBWaM6c%X0DechlP8B_BUQ^1_B5ImG0q$&AGba@Q1!Sx#uv;b)FNlKJ%FF!gu4goAi z+jugMiX+lt3%Db%$x}1fa)yh%A&xxGW-Lle9BaRZcr(Jl8YJvmXVoM8b*d?nDn zr>xqjT|4gjOmgjyb!-I_L=1WSO(};jF5)F9(KK9k$6juv0YKyrQRHz_DK~8jI2)+w zm-Yt$QfvYLhOutzxp@d+SUG4qO=vJ%C2^D=7atD;N#3;^c;DQzmR&&!oPfkcBJT}x-4FY#kT02m@DxoqS-{xT|$ z3PAj4Y06h5S$bR{FjZhmf2ImPCOB3Cm{OLqda0jhqvfLSxmZ+?A2<^h+z64sYjMk*OaM^512bTNz1yJX#3oL;p>F~$69vB)J^K&J0kyCuHxo2qc9?N7 zpx^)Vh!`XhEMW3-8hQ#=jbwx3L_Yk3cspR5f1h~;US}c=&En=n$AFqJRa-Trw&}AF z#AgA`>wx2@JWAg4l9l5}1GY|0Z9CNsXNdgw(z**Vj@S4BOp0I}AA5Z|Zl~>Z3kVbj zqQ+>~?`j3P7S~|HAAK#cX8I@4)zn@Yx%DiDRJ@~c4bTC4ySPXJL&So)v8RA@6#{J%M_y$DCRzdd0*FPR zEH--gPG5+|{w5Yegr~;hMSkzb)vYj91mGV5xcRrf*}fIu`8(Gk(oJHQTMWSTlpe3W z7U|f@97Ozui1Pqn>xtK!34&Gp1$<#-lg>4RGs7K!6%!+v&|>f%Vhw^400u&sGY~q5 zJ^R2hK)+x%+?N_ujGMppd5=D@{V_pS_0HC2*7x*eApoKv>S`$MhIW>f zMXBEn^5P16FfqDGOxdOTX$;a&7%;G-28$P)$1&8Il!2^?K;(-9A|F432ZYVYM^|}I z3>OV1q`?mb9wc7}dJzwJ)_0FSe8o7Cm(><8hzS0{vBcWu7VZ9!xVd$!*%0qZqPEJb=%hJ$Z_L zz~Miu9bQOq9)39Df;+w>C4k8SnA^IR``!NH4|SUf61t|;@Y}Cs7L7w2kT8`ufki#> z(|*WcvwwZbRQK{xx%^U^9it@ui(i`PZ(a!{U!?$lf%er!QwQi?Jq@BTnXsQ0^KiZy z)@H)?s!l`=|Lg4jvo;>IFs7CP;9l8V4UpAo>sjIq#`%v=kuRv~Dh zsiW)pz26t!@MhZgf>?_yj35jsQu16~;-8_l{?rj9%$d(V-9L6Mv^t{|GGZ5-C`W&WqNh29e6d|hsvmvzE$*g zQmyMXe|TD_9?2}u%kdXf_x#(4xd=B4sAmzB{R*=+ZDMv*{0=ZZw`U z1zHnRLzGA%_kVvk=&UnLH`*nK6OLz)IZ+1RaP z$_a6)pzGO}t0_(S2EeN@?u0pWGf^QOT;Fy&fIf+061Vv&k6#eQ9E?CJbN7 zR~KK=eS#kf?q9C)BZqF)@T7l`iF(-E2|R4|?91b}4Ez)Kk2FyYsGq$iY-#*_u@~1} zergZr={EWSme9lc1Lvw@G~X6iq*U zJ>6TJJ1l)Wu8Wk+%I_jO@X>ttg#2Gtvr6H&5?wENhU3wfOD|1HK$EE0JWPIo?o%@w7QX>1z=lRIcDYmm^RdaH!J$U0qdKjR{v?Nj@k8=mLg z!QaffX+{G^hFLx>yzv{!{4I7+*?C}Mw;W;Akw&+^oGNB zKbo1D;RxOCe8*HY+Wq2Z{a&$bq>kL0E*5uqV%bZU97(Rgg}axR>R3#V{3&SGo$cMU zo>il+6}(CD_7>Sn+RG>LD*ZH>q}A^P_|jLN;2-ZSZ)e^-CR7g&UCtF)C)#ml2sjLp zna0G_?3W<_14PCTp7u%y`1jJLdPCb;WW==}ZA1fH$8?tCsR>bJF?vJ$I|J{? zlTYZ~d#P!IC7nc5MI zRsbBkP4l%D7PaBB{&6DKt4yR^NwBqPM*lr^I~U=AH?+LJ*&C$ZAXr^~8P$6rvc|OQ z@5*T^JLt$TP5T0t(=wiG^sXg zEd~AVuZVrio-s!T&LrqYTve>D*P81_=>7;qF3oJb%9-_$ zl7tF5{GK`$Y)Po@y_Df6U|SUSg7!xbv_*4yVe!Q#Ebc;ZcwoSK)rHUB2ho1zr!2(h z%dVk7oadz}SQ849EKz@)p|3b8py_+bZq+KNZ|#0KdDLC_ZhWXy#9XXyyOh3&D_KBd$d5r~dZ&@?gHCJhG5mniAQ@R>y{O zFvmlJ?JS~a-%K~9k;T?h@u&=-btl<6W(Mr?#p_#Nvx_0v`ilrR<$^+%&Dej}o4vNPn* z;owRb6rB0y*XFvkd6OhCQqGB6I?r)a!X@j6i&CJJ1K0a?>M~fR$7l@HLqkBtR{DNi z#>_e~=e6CHkiV3$L3^TB!NYiWD6Xr+?LjRJ218fc9?44c9VrfHEASeRf4u5=;4Pz2 zbmAarlXGC+<}+MNXuEB2%{j_j84W=YGt*J6aB$pdMP%f^yA?e@n6EWm{~fLLbbmH# zB#6dX=5Pv<(zsg%*jkAKL5r0knZM%tivqc1CatP(x82cXPdwWwcmjs-W@q|ImYY99 zYwlE~Y-hze~lk`x3mjPB!27mzk`xg^y;8^_L_ahVv6~)|t~mfqeU``w(TZ zxrTjOPssfK`oySR$6>Am1>m)tK+)!_P=0!6FfqlwTf!xubMJn*u$lh(uwJ8c<*Bgn zDIx;XIk9`S^Zs-&ZN{2BW%h21L^x#Hy{t&3#$u%2EIrNNs9uMGjS4;G4WkVIc79S?9<_)}5sGh^o2GGu01pfp6?z7wr_`sf6M}tS@hT zNCXk5MDOIEc)b#>BL5Byp4r;f?uV$qGqs%c8FpR1U>>e-v`u`iQ65*US#Q)pH|_z0GX?kiG%%(LOU!%Ckq@v`f@JK|pfX2{xiK)~<5soB5N zZ^n6hgiX)Z0q$xxBO+$zshAz%JT;G?R^ui!yaQF=CYolEefA_D418x5EBtuv6S_T# zt>8C5ZK^P2{Tk3jP{74C9i5Z*XB90Em|L^1Lp$Ty?ZVFx%zQ38_!1Hlo_wx*Jxm>5 z;cSTnM62^vnW0! zv(<%*u%dQ#ZEdDm`^UPysNb89-plAwdG@K0)y_jBD-qUQUN%)_5(TsN78%{K)f*=5FXVTI-5jC-M0r)_e2{Uu>Io;LFZ)WTSayCh zH$y%7yq?2_WZ>t-lJJ(ErM5;8)CMsVjU&indTZFQ!V%ji9)yN-+O%Xp_zMN?x2c&~ z$h26bQIZIOY$0|Hl-A{A>HW>D%Vl99Us^*}%6q+6(o_lL&Dq|Mo_&23{zG+CyVGoa zZdPuB-3?-rE;hgTQB^{1j%hnpE81vUZxe{q7+r62)9R zQjuMBfm(#Ms?@4Z$;Ik^iw9oWqRW`6isW|}$3~+7uuRp_uSRo5+uoV%o;%fYOqe&( z|2-;yrIE5RJ-g8wo6hVoIj1wlF#nl)eXp0d4XYB-b^eG|Cv?<)1s7iS_r5%WWTvIf z2b#SW2vI-|e@Dud15=%5ScGn5xI-4JpMXeprsukuG_&3pJ9vw|;{D{iSX$ZsyN-QS zIkazCCe z5tjTIqBD|W;A`f4 z(o2%2vBi}U($ZixbedSg2KMZ`WSTOQSc*AmMXpEHQN>d_Ts3UpJGs9*!n#G=T_Pyr zRXRI_^rJ$49%InZRr>IOdrQ?H&qWVYSv0t<)_MjA=@l6!>}m{uAv-nCbu4CkNL1I0 zszx2HgbeMhEPPFWT{;-iq%i3PmyXoFdjD&`g5k23{NZw;w9<>q|Iu^oZgl-bE6dSw z^mlKsUR{#$i%`XX%3&%n7Tqbvr-=iv3Vn!kYG;%8(aknQHmT914|hK(l9+ATj)ON8U+A7k}qtQoh z(o1n!2r2de-qqvX8LPa^T2)TVwotK{{5PUlaF}h}t$?CyJIDXX_j2AsLij`a@Rsi6 zT9`WmSJ@(5~J3(YDA@J|o3An#c=nA#EWWa`laHX*T$SjobapA&u?(UWP+Q{C%@7Q}QA^ zJNv{`cm#_$-9Pc`0QTcIA;7WaQ;?NPKQ)wA2wg2XAF*`a%1+DL{Ei|8qxs#0>_+qE zIygdQ6ZJGXrnY0=Ug)~OeO>jx(RvJib8E2<`5+hRj<=UQ`XSK&;bJyBjKUK-vv>=H zGCKa(@!Sj)ME<{YC-0A1b(Bqx63NF8LaQ+pwr7++?Y;83W-@6>tv_S?kk#VM|MVs2LY-DySvyPfa--K5g8|I^)y zxR)i5=c%cxpXe{y&Af@{;>*~{b02i&{aB_$54p;>&#@87qjme%iw$;g@1y3hdBV!k zZH`JGW7Tng^Ak~%}#;Q-2Kv@J$5 zPoiIQ%EmkU-JkTeJJ;0SF{mVKykranq(ebDsHb&e)<5FL`@L~x6=ryQdf$-7vCQ0< zVKw1(9v>zMv~Hr4MzS?k%k=W&z-eNFmOLHeG{ZZM>d@B7MqQoA_xwa^NGPaDE9_=G zqs6AdhWYsONzd@+OaTr-8XOBq(wvBuPJ?Raqs7jrj-Q(vB?55luOh~nXxNd`{VH~I zM;8yWZJr7r(}dDk^xNhxwsalXR!sA1N(T6xx8%3 z9i?;He4?%(U&RqXs^zm7y_}z_XZ`rKJWdqi+!lDPbqjFCc03mCyq$|H4*?12d18Xu zsc9-IL6-9k#5yU9z|37?M|bFc*A_tKQa1XE*M2$dVt-b%RtQm5BcL!+`EtBIz{=SB z>EVhR7s6-iy&6K2n(c0w;sbP}fDO(N@z^>W*1LXDq9TP$lSj^&IGFi{KpGIP-++mV zR2tI$TwO=$)6FcJ+Rs%5-rd7wzS5;BWefCwh}pkOiJM7&g&1R6o^Ft!tBsfjK$~LV zchl!;(BZ>dy(Cy;~wVJ*0yFzq6!EcXR5$rY?4gI54mUi2JbS2$QJGSQ5Xyxt;M>AF4Sv@28`bN@} zlqwK4bFtGi`_*QHwN9+3#N)ub$|i36r9T2zdP63$?>Q-i9luzG2$gB(w!3~+Q&2P3 ztg~7hwvPLAu**HR*1BKO`siW+cbQb!0_qL(aGzg2%;p*MKf-C??dsxN<>Sk(?%vrz zzc_PV+EeGDFeZ;i84*ZtW=H3=#2j|W^|ND<(N6Ys^vYL`H`p!um`KLX43QJ|#XvZ& z5VNDI>gv4*nZ&heTY8$rMpSG1;mfQ=IFry0%W*2X;r!dHgLxC(0(fUSoX7 zwNjEXD0t!s_`m5$=5BFW$;8yBAcYLBacVr_p>vrk2KwkD((ynWWJf^m6M0>Rs^j&K zcuG{Bb;k~FsXL?edF#}7S zHZDLmq@^Y_Y4fI*ecn|MwalQipJKC!`&+AEi=Oxumg^tYvS0s6v}&dED>#4Eap zAJNq9yf;-G>9>swxt+fKLmkVyKVy>_Z%8^@94F5{sE|(%yu=RF} zU|f+?>1X;0!Jp9#;p0r9dszlE)NBFz%Xb>g4B!|F;iIe%Rte_9u|W9MNnz3b-6obM zRP{c^sD1ZD1@8DThqDat@NK>7r_aG&(BpD|3!JTXho#kHn#b%IMn={-%208He(I{j z8s5K{sLB<8*d9?YNvdlAkE1Xq4M&^5V`}zED!eajyno=M;-hVhny2RT;+R}Z9r4hs zHg0|z%N0-eaMaHz%=Q`>bdt9ENtBg7zrZD9*0FRwt#|ss^{%z@XNh|0y-*Iz&V$F+ z5b1tlj^6+i1CSkW24b4a6t9GRb-61JetIWG3TakcE8lU{iJ1*WfY zhT3M?F_AEMwx8^2o>J9?B73d2M-Ao0yblIV=w|pGk7+ zChG0Dy~rHOK1Z}(>0iZDOF^?7HV2aYQZklSUv5SgTzl!7E#o4p(rOC24ScRx|^VD=~3JdRynp4w?)W(5A0 z)_C3;5w{#ut;AeK9af+D3$6?#Btje>?{BQL*L-vD2I8Ik7Vg!@QnLe zppa1pgsr!=`wq1_mTHZ}C3xl@K9Vf_gQQRAD_36GdaZ87H=x1+REu&}7i5gjPv`MP z?=NN3^VvFySA4Is?wUDmnv~`eOyF%d=CNUipe$ZOJ}FZgXz3+QW*Yt>xpMko-JL05 zks6_=q<8Zb!SRc%GSdhvd#^TbuH?h6Nef0sA3Wjvs`Q+zGw6AI#HO>wHLBBX;iyJI zFZ5A$b~Ji_KEX=v=l0q7@oKkklDfM5JEnZw<(BE1>)c*>-8TRsJgfKBDNYu#C!HGU zbLvbP6<#?=;4iU0T&Pb*LBnMo{A)%V&E)8oVNDoVfNMGIGqDC~Tscy8s*HW5h(C^+ zG%$nRO&>=ccGarn_c)}SF|TH0#$7Cx8+pN%20+veAhSU?RF1MOcSo&5t!{_L=^j!S zwpKQodunYpRvLi#(OCA4LtJoKXSCHK;j8k9qyr5?e~KQ|t>1+SXe) z>)&;E*Mlsb=gfL7YJkKP1nqI#dXEOw6i8@(OKrTvK3jR+J9~Xn-iY+EwA~bLWlsRR z23NE2O*dU)=1+e<1VW`GQj_6h3MbAnyDHL5QY*f|gl9W++|d2#xN2PS<3Ii9G|AA= zOQyQ5g5I}YLVzr($N9aHm+H&mo*)(pv+|j@cP5Nnz1nAZ%$JsKX2hLXNhUIS$$QnG z1AL<~%s^invTXLbb=gI`FD6^i`_j_7{ay3FG_nui=Feq_SET$RM11j`*GRQ*M5-@2 zd2E<{+liz^%K)8H_K-`#W19`%J018J8$M5t{XUL%67!Kv?T5Y6%HoSPfj9xo@SRNA zO&i%cnz)EbdPRxH)73v%VP9f)rk1ApgoAeZVYB+))9p8Bqd4&bBR~*`oNY>09O~N2 z!Rp>7KnHX=U8>;-697~ZJ_sN<+Irs|Hl_`;G1z694OixT`*V|Cz_YBGLc(tM@Kohm z>JD&MYd3Xf+B|B;lk$xwEPD9_~%=V(vx(C@a6Y-H$#=bfVOn57$&>rkwrVs4#bi zIXh7e(IM6w&y9tw+~I(;y6HV5=yM_(oXxC~r9=|;e>##2d}?n{dgmZtm$kdn2_X2$ zZn1&1c*eQwvMIIRLX^A-fxxJ(8WBPe?||LSuy z{t{iR`A!>-41uqe*4_8|FWHQLq|ffyeq*aJzDYNo!z||t!@KwR;k$ICGOlv)`wp!Q zFe7=&V)-C1g>f{5f5E>X@5^pc*;|x_)H3t0Wj(Hdf}t6f7dj;Lm3y|b61$Fgis3HI zZZTE=iadp@o=Y|={({-`cL3Mp!SitW{cQ0t++xA?d#mq<7jHsy-_FH#^te&BG6e9=TM4K?yE4$gLtJB{QzeetB zryUa6*x1vKi=Ur?^*FjI-@8jse%C$IlbLGM)=y!06b)*c>gqrMkCt)IoHxxwf;h>K zI$ZxUI0Qd&(@HM3+nD1SE<}@A-dyZ1FM9v|iBvCi@E-ah@k7-!4x7-5u`g+?MqO*l zm)P-Zzu$iR6iAlY+w9>D6kT>tx3it8Zf2XNw7OwQn=-dqz_;&l(OUI~)JrvPrtJfn zwVGJjkAIYJ@iHeSyf)eOw~G0ZJld2UGPIIZu3h{4455%Qbz6lZW74FexmYeYM;8aI z$K-h3Y^GFFCuw>-YX)_9?Ig^9A4wx1xQ2#eYVG!-LK}|bv$R8@eqlJgC_fD*}q9KhIE1f_i#O7_ zT)%x`)T#K2OJP6!v6Vb?t~cc+MQq6?;as!glC6mA<(e z<%lFRX`h0@1C67z0NHWh|ZjuVZ|V8t@FP@kIUYdtPp)2I9s3B_BXeBp}-ZP z5|l~AJ-|-~e7adHXKm6rZHQ~nBqb!qRwUhuE_?tsh^Kl=Hlz{jJv5 z%a`iA?S8PdtMf0~>M^6t2;7z3^z?rn(s|R}N+Jo!JO1-*rxQyqqw0F6X>RM!ACLOT zz2%2LmeJ%LT4#%}#EGCHI_{2UWy@EDyhONJs|(RvT?Z?St5 zJe~uJKn9oH8ehO#Qs>h$z{xbsOPOK-DR@vG_GmD%r#DqpIINVFeAg~=yeiV@S@ycUgHP|m(|5vgek*ZEH4RdwK{d$6jL>+4X z`4ChMuWjS9nJF{!ij95ygn<6)v21l;z0gZ@UjZab`9s9KK++(ZU}hS#jlPp@YHsdX+N+j<%}bAm_k9)T8@LAgyH4JzSyw>)>XO5eYZ-f(KZq4CZ8KAE}&p33a#nAw#ZL!zhkYZa0_fy&Jh12UfTAj4W?< z)O2(X-CC!M1+7n}8-n0j-m&cbyUhc#29lDYkyrH{#~wfcNz*@%?SyYHR3jK#qYkg` zfOxt;Xp>!NetI3?-j2$*c6E0peFJ1k0qtRyN~0J}eb0QIcI)6yPMaCaqc?e?=5%L0 z!wWTLgHwtNdLFYf->C5f&&TSGJKKO9egTz|q7H=dL_|bSuP9CLa~>76 znCtPqJkWLkR->ldp7iOcx({hE83#s3x$hnxA+ElF{8rgnRi*qnM5H$vfR4=(~l-hR-WQi)59iT6|TZNDzuRd5R$FCqNF)uguYRz#H!g{_d46@8|;6d)C31g+?wwl9UWUN!_7@iU(y8@`IP%@=plBH%=02yJ&ynGhwto!JlUOX z4ZlnR=UHTX(m73bJ`MY1G35^fepmv;GCh*P+1Gq7e{QeWW1q~jSlc~K9=z&1x!R5Sw+>Pg|4d7B*QMP1eov^xZ{boH28L>~l{Zhb#6){LZ zm@6K(L>wtG?EU!}!s|J9nZo{zoX5(&q`-6B*F~kgn1RWbz(S1+KjtWyba%eqCgn)S zFN@z*^(@_A3M$`75z6`%5E_kQVPm~8vUW(0-)Xpgi@MOw2BBVq0JDHsQp!G~mGIp` zt+g8jO^5Tn$1Dr}bH1cx#Vy}6vXegp0~5m=T_@{(WO?uY<)bNy2_cW;Z}e~9$_)RA z&R+=3N)8DzIPSQK_PD=ZR~&XP^$^GwPJke6@_WV`6v&1R5CO#>3rm*Q23Pe8MP7zS zN4FFUff1Z$-rRg+ zUOSJkl&izPHIn6>?4GZlL7(#}f01PSSIocavf%MkVJQEWW_pySvMFl!k06}^LD&vwY0rFM7Sdo{5 z!^6JOK>wyp&Wqx=>r``x(>dQU>14zTUKY_wnmZX{if`ugWtEtf5;FbfaR!RPMaJd=iiHkN)+{o zw=7_sEj@pbvWiNnS(}3oHAP5B$P(ALz1hl~T>aEY-XZhaZD8r8xs7nX)xEONDCjv; zOUTNmo&)Iqji8`liKzLOKAgKFJ{IZWuJ!WaoUryyAsQa}xqK??8(ZCEx7KBV%c+g} zKb}#TJ3DI#oj_gNy)Lv4->#&&w<8@3lV0qv{JbmRz6E=*>$kXAjlB;|IzAm_X;uCB zv75{DlZUCPX_L_PUzBOWE8nZ-zMA|iD#R`FU!}FRHDgRnO#Q#U-C^A-YHAzgg4T%^ zfT5UUrP9zgG!1;~y?UlKy%*}N2#Hw+^T|{6+|stQd7Vod9abu&XJ-I|3zTY{NPshIIhMP4(e)?%0Uv@SDj|pppr_Jb?SU%^oes09s*d=hLG% ze`5g7Pg|}#S=k6d+Fsg@%%xAxPEJlx7nk#=$7MiN?f*(I2$fs2BE8qna6zlDpw#AvWn%g%t!02^>Yj~m`Jc$>iH%XJ+e zZKMxoZxEm;V0$ox2?Us2H~)s3I>H<)HIzL9C2*B2%2% zuoz$qGG)~AC_jk0_89l)-w}Kjrep=sU*p1KA%bo<^)Jj!7x@I^8msO> z4>V)boi5cC6{?m%cYKi1zpQXO7Sj9MjcR~0ZwA;qj*h|~Zix)e+JeBwbFm_`UgUBj zgZ3CD_k(a;jH;dGQ*p3Bd%O`FzipXyFXu?vx-t zRRt(cFcEnGVV%fzDOH|TTM%e0EhS#yS{w_?&t<&+7NqhCIwh;+O2Q)sTsc~YfC3bU zq)x}416#3Ue7ioXI|D~PEaz~kUWr15fPZx;b=F9Tzwr0+<&|tGXq@ z-!p+0U!6Y(5C2L=UkFUuSvc=t6~zQS+H_VW)Q7oK9zW$`$z@cCY7+mxgHfQ2uQhZ-Bg6F)mmEz|j=0p4I}11k?as_b+mA%#j1I8iXEwQXk2s&yQGt+}5bJPGb zYs;@L`=D=*mVrBcjz(@?+%AG&0^6ZbXHPVwwQtYzgjukZEJ2bVC7?Lfli&RQ%4ql> zZ3Bjstq?yQBdHTP-^B*^9^)d5i0V_-08a5k6bqU|cZ>@XF)H;$15M;U%QGN@6}Z0a%$-dB3&%`n1N7*~lrtIJ9})K!Z&`SKbd?mA;INup)SGh_}|FuM4}K3U^9Fb8+f3I)=dOLQaPRBqE3YvwXIT1%t;9*xKkQh>Kn}+ z;Q<4<$i;f+^O`#E1n{wLZ`^)rpKs3y{DkQ8RNlH1vu<1qB`m4Ar|D>VgG6BuM+f>~Dm_|t=53>L+p^5?Ap9utF zppJ$KnZyZs@R1KmMUXW&i^`seS3FLP#h)k*_YGfPxP+Lf^-x z_sPQj+kVNDcrI(6;l2Q!R|cD$^7tp7bf7;!t@&f~h=LG73c#aHVNd&EsO|JDJ9OOx z4GDygnsW{dr3{vF5xpd#k62wqCZIlHJHXZfU5XlU_yV<>Rk0;H^GfkD(N zC8;^cd!U6lfJ^KX0@2Cm4 zd=8d)ev_63t*c7*w-JRN1{3v+Dme+gIiEr$x928QNy2pGAlduak_Nks{AB%r4d$fH zGhrW1qRbq8d%BIF&*L}E-fw%oD&cP&m%}Rqb%t5mz_v?@_2O7|JOgdKNWi}S@&06z zP{QC}7)~36DkZQSelp`cI3;!}dXmDmA1C4Sk2IJkXca2?Rq1CeU5pr=Z$Eb|MA79r zy57rE7PN*8KqGRYA39>(eT2c|(NGsfr{%mU54|>P>rf=dU$a zVl0M^67U>rcEgp*DN>+P_xfhO3&BA|ja^IR9nZ)3c|`h+cLeVW#xuq+3uv}nG%A6$ z#JM=Sf#pn?8f_ORN$Xqfs`b>*IN!zY+eSWe1i~INHf-G~8xDL(&1R?cv=sOgWv}k5 zvteF@Dw-i34yuxg_Ahk2WZ_t?;YIDiHl87$aT0m1go-04L)r0u>_1x^n=umxKkx@T zXKB)YVqzl*IYMPkmI~jo$xVn-{?=xiJ8`YE6AE&DmVLZJomVQhqu;I!nEhjZSW}A& z9aUJDnK_|~5?EL>2L>l;*|=qJIbzC{IPFmO%Mz2JRMpR3A?xzA_EP8?g@56F6FM$q zslHsKdNUki-|0=HpNsVPE(Hds%j;8TT#?q*MZ~(-<~C%b_A2|X}`fHdwvLeljj~n5@a2L|D4uGt&g#XQX&30uL+(&sRQi{`=)W|ELz*%Z{nK;cEHSxzI zsrA`<4Rz6Z8InRbWPpDMuP7)CHtM(&gT2jMVmcA6EvW4pd-}Qk^8M1f ztkSjGqJ~jOXiyi^+0T{nVA#S8`(S%RprmWLq)G}RWd2UQ3q_lH)oTEP+*uVvg!LsN zp4D^TqM1J4uq;@HeYBs!V3ZI;JIi2~d7$Bqe6W{zYP=5{*J{>)N}3r95vhNZ5{>PP zuI(%1IF+xoU4$(JU!{WLTR0_#*HMh#ml-ls=i#wjLt?A2l@z+gU?w4~g&W3HA^s`4 z4F}UB7IHlO-A+nWfeRdy@gjRdiHelQl{X=Mi%^&FKd0*<@l5nI+3Vc#h{rC$Kmoe- zvpZ3bMn*|-qZj5396y5q;CzC9kn7s`b9To2s502|i^nLOu-LIIk#*-sAS;X19xv|T z{0*ls}liCZmq|f?Z;8zxgGkM?Er0=gxe!}5B)Cfts%zx+KRG~>%xK$^Qwgd zxLTF&cv9bZ<-o^?!iTp33(@-}y0vl_)2I~G)HF}92jl3v=#<)O=E7Rmdy2oglf|Hk z9aQ(|WOUn)IJ?Ev)&Fx6bF6)kaLn)DLr)thofgM!&@~!rT^O7bt@e5Or7|3fA$%9Z zdcgKVh^j?@4Sr`l^A=M|1^Pj?Yjm{L@U2TTmvgF?=HwY>`I&p}76Dqk08?8TUT-A< znh@%m4Kr8Z2eAG|xkt@vbVWTWWo?7J*w`48u>8$6i$5I*42V{tPKX%OlI`)B z()!3ib)k>8#b55^e=w>k^6=B1ZbJ{JnSv5WmCH4hd6f6{<7;|@XRLCWiDm99yGhA{}Wd_r0D9El$(X5~ZD@6Yeq%JJ_WnN-%QoT_^& zls{`|J%9EnfAEk~Gyx};)G-ocS*iS3?;B@s#A40HNR)|D9E{SnkxmA^FH@JMsvova zX8&ayT=lAu;Am_z@Z2<%$ z6{BjEfS{w}t2VXwOJOAH%tlL96JNh1#=Wf*>*+C=wXQ*vNIs(oaU1*ElJg~AWBoz3 zYsEM6%XU&tu#eu|7g)PJi(C|&tXR}Xn&hnaxd#gx>+j>0Lv??-YpZnq{-}DCX85D* z_dAPe6Sn6vuwUIAo->ylZ}KI6nQVFL;mT@J6n=}jh-Pjuf%pEv++Pdkdj*Zwp7DBP zrhTtVw6{gZP)&6$66l-|HJ4w8%;eg~^EPs4nrqIew2C|SrN%S*vk{KJr_g;`Y{qKK za@>)WYnnH1$Y7g~H208STe0$q*DizuUr(^Zw@=B+o)Nq~aS$e4yGfT@>daH^DKIsz z)cwow6@MRvpi+T4eltCU8Nd3QQI$>-+ zFgW?Ai;?m(M6`3~3t0MUNoj|7dB1(@$eb{5jiAiUXxRcsX%N7syb8a-?5DbXQY&dt z%QtBuucYrm*1Dmz5?dn{A0>WU5x4YjETQ|M(8cAmSNvkb`2Ku7q`f}>zYyO<$8g@x zUzs*Gk#M%Gr7AVQ9ITO)uwuolOW^S4&Y0P4a>%SIVE2Gjj|O|=mQu{^v#Iu?g_u(5R=+V-wf&8^chyn4kgY80C{bYAldhLKCoo`h9f)w_=Um8!5STwbwF{_U3Tizp{AyHC84h8bs|GATle zy3F*$Rqlvr6MURu^<;ctoJ-C-Z#8oO_$tvow?$;EY1DOi-(^S-2TIzlGbRuwb&;-U z7yZw0dus6-cg1D}!{`%wA1C;jA;~pKJ=T-XVnJJKHRncn?@V?ZaEO-)De!(_{cb?PQZM`vF>be}<$+yB>x!n%iMG>Ka&r0;UkQJwE7Mk z$`Z}Z4DInTXYHvlPzHtdM7q)!O@~4(CDCwL6=&P!6H8`ZIu8IG){ebnFOOsgJi5#J zo*23$q%3OfclD3VJx10L$%S6mR#0O{Z-fm;yH{W~(%~1?#@9nDw|X-FV4WFNNE?u= zNsUpZB9>X39R6ko>B{E@palselu!fi@;2{*99+kw!vd7==a0k1U~mtD?VxZfC+5?F zS*Nm{8|Z%mvGF+lu?k#)zW_q@WO_h`!~-H-wk-C(55!&CS9;0~tCO{qo!|0Ld`A4R z!?{Ezel$sA7!Q>QFASC6a)j3Q9elimCP?JOd_Bc7+iW%D38BRl_}=XI4MruG!$~Y! z)#3G0Ing0FLqmnq)N|04xKy0c__kp$%3zYQ=jbnv1!pZF??**9r5!AA6QQz8HaBac z-)DvlmLg^;&QlPoDNzVPj2csI+Sp_GZ>Y~5tTw?OOsB`~G>Igi6#!z}vZxRn z_mZ3%^Wj5E=1-Gbo9g3YL(lz--KY}z4P9;Rev`lWf1j9yQ{VAp+Sf5=7Hy=={c`2yJadWY-BAQd=Lk{ z_R5BjK&)=KT9B)gLV{1>rb2!28ThgAIW#%qO5B*yF`N0*A1srvHd0v*yWIk#^?)Ts zM5jSs*i*xFz2D7|(i500ZVx1J5^<9kp}e$hGHAC2LutRtBH%ytYf07!h%N|p$O_p@ zM76*Ze2pGv`4>e77PC@W+j}V~VvZ$pJA7_u0J6SUt6#Bso7y)~k6x^LN|Y_7g&3t~ zc23kDyJ8C;xg3Hmb~#>n;^|83;U1180$1Uh7VPe5U0Yj3=xI`|HIDic);1 z%Zx)#tB~cm_w^{1mrymqhd`i6ceMi`P*4dL1i~7qi~&@l{y)Y0VJg~EDlzW{YoEjk QxT*u><#`b=z=h}h2b9~@i2wiq diff --git a/visualization/tier4_adapi_rviz_plugin/plugins/plugin_description.xml b/visualization/tier4_adapi_rviz_plugin/plugins/plugin_description.xml index 0b4f00bd56278..5eaa5ec658be1 100644 --- a/visualization/tier4_adapi_rviz_plugin/plugins/plugin_description.xml +++ b/visualization/tier4_adapi_rviz_plugin/plugins/plugin_description.xml @@ -8,8 +8,8 @@ RoutePanel - - StatePanel + + OperationModeDebugPanel diff --git a/visualization/tier4_adapi_rviz_plugin/src/operation_mode_debug_panel.cpp b/visualization/tier4_adapi_rviz_plugin/src/operation_mode_debug_panel.cpp new file mode 100644 index 0000000000000..8476039b3d2a4 --- /dev/null +++ b/visualization/tier4_adapi_rviz_plugin/src/operation_mode_debug_panel.cpp @@ -0,0 +1,221 @@ +// +// Copyright 2020 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 "operation_mode_debug_panel.hpp" + +#include +#include +#include + +#include +#include + +namespace tier4_adapi_rviz_plugins +{ + +OperationModeDebugPanel::OperationModeDebugPanel(QWidget * parent) : rviz_common::Panel(parent) +{ + auto * layout = new QGridLayout; + setLayout(layout); + + operation_mode_label_ptr_ = new QLabel("INIT"); + operation_mode_label_ptr_->setAlignment(Qt::AlignCenter); + operation_mode_label_ptr_->setStyleSheet("border:1px solid black;"); + layout->addWidget(operation_mode_label_ptr_, 0, 0, 2, 1); + + auto_button_ptr_ = new QPushButton("AUTO"); + connect(auto_button_ptr_, SIGNAL(clicked()), SLOT(onClickAutonomous())); + layout->addWidget(auto_button_ptr_, 0, 1); + + stop_button_ptr_ = new QPushButton("STOP"); + connect(stop_button_ptr_, SIGNAL(clicked()), SLOT(onClickStop())); + layout->addWidget(stop_button_ptr_, 0, 2); + + local_button_ptr_ = new QPushButton("LOCAL"); + connect(local_button_ptr_, SIGNAL(clicked()), SLOT(onClickLocal())); + layout->addWidget(local_button_ptr_, 1, 1); + + remote_button_ptr_ = new QPushButton("REMOTE"); + connect(remote_button_ptr_, SIGNAL(clicked()), SLOT(onClickRemote())); + layout->addWidget(remote_button_ptr_, 1, 2); + + control_mode_label_ptr_ = new QLabel("INIT"); + control_mode_label_ptr_->setAlignment(Qt::AlignCenter); + control_mode_label_ptr_->setStyleSheet("border:1px solid black;"); + layout->addWidget(control_mode_label_ptr_, 2, 0); + + enable_button_ptr_ = new QPushButton("Enable"); + connect(enable_button_ptr_, SIGNAL(clicked()), SLOT(onClickAutowareControl())); + layout->addWidget(enable_button_ptr_, 2, 1); + + disable_button_ptr_ = new QPushButton("Disable"); + connect(disable_button_ptr_, SIGNAL(clicked()), SLOT(onClickDirectControl())); + layout->addWidget(disable_button_ptr_, 2, 2); +} + +void OperationModeDebugPanel::onInitialize() +{ + raw_node_ = this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node(); + + sub_operation_mode_ = raw_node_->create_subscription( + "/api/operation_mode/state", rclcpp::QoS{1}.transient_local(), + std::bind(&OperationModeDebugPanel::onOperationMode, this, std::placeholders::_1)); + + client_change_to_autonomous_ = + raw_node_->create_client("/api/operation_mode/change_to_autonomous"); + + client_change_to_stop_ = + raw_node_->create_client("/api/operation_mode/change_to_stop"); + + client_change_to_local_ = + raw_node_->create_client("/api/operation_mode/change_to_local"); + + client_change_to_remote_ = + raw_node_->create_client("/api/operation_mode/change_to_remote"); + + client_enable_autoware_control_ = + raw_node_->create_client("/api/operation_mode/enable_autoware_control"); + + client_enable_direct_control_ = + raw_node_->create_client("/api/operation_mode/disable_autoware_control"); +} + +template +void callService(const rclcpp::Logger & logger, const typename rclcpp::Client::SharedPtr client) +{ + auto req = std::make_shared(); + + RCLCPP_DEBUG(logger, "client request"); + + if (!client->service_is_ready()) { + RCLCPP_DEBUG(logger, "client is unavailable"); + return; + } + + client->async_send_request(req, [logger](typename rclcpp::Client::SharedFuture result) { + RCLCPP_DEBUG( + logger, "Status: %d, %s", result.get()->status.code, result.get()->status.message.c_str()); + }); +} + +void OperationModeDebugPanel::onClickAutonomous() +{ + callService(raw_node_->get_logger(), client_change_to_autonomous_); +} + +void OperationModeDebugPanel::onClickStop() +{ + callService(raw_node_->get_logger(), client_change_to_stop_); +} + +void OperationModeDebugPanel::onClickLocal() +{ + callService(raw_node_->get_logger(), client_change_to_local_); +} + +void OperationModeDebugPanel::onClickRemote() +{ + callService(raw_node_->get_logger(), client_change_to_remote_); +} + +void OperationModeDebugPanel::onClickAutowareControl() +{ + callService(raw_node_->get_logger(), client_enable_autoware_control_); +} + +void OperationModeDebugPanel::onClickDirectControl() +{ + callService(raw_node_->get_logger(), client_enable_direct_control_); +} + +void OperationModeDebugPanel::onOperationMode(const OperationModeState::ConstSharedPtr msg) +{ + const auto updateLabel = [](QLabel * label, QString text, QString style) { + label->setText(text); + label->setStyleSheet(style); + }; + + const auto updateButton = [](QPushButton * button, bool available) { + if (available) { + button->setStyleSheet("color: black;"); + } else { + button->setStyleSheet("color: white;"); + } + }; + + // Update current operation mode. + + QString state = ""; + QString style = ""; + + switch (msg->mode) { + case OperationModeState::AUTONOMOUS: + state = "AUTONOMOUS"; + style = "background-color: #00FF00;"; // green + break; + + case OperationModeState::LOCAL: + state = "LOCAL"; + style = "background-color: #FFFF00;"; // yellow + break; + + case OperationModeState::REMOTE: + state = "REMOTE"; + style = "background-color: #FFFF00;"; // yellow + break; + + case OperationModeState::STOP: + state = "STOP"; + style = "background-color: #FFA500;"; // orange + break; + + default: + state = "UNKNOWN (" + QString::number(msg->mode) + ")"; + style = "background-color: #FF0000;"; // red + break; + } + + if (msg->is_in_transition) { + state += "\n(TRANSITION)"; + } + + updateLabel(operation_mode_label_ptr_, state, style); + + // Update current control mode. + + if (msg->is_autoware_control_enabled) { + updateLabel(control_mode_label_ptr_, "Enable", "background-color: #00FF00;"); // green + } else { + updateLabel(control_mode_label_ptr_, "Disable", "background-color: #FFFF00;"); // yellow + } + + // Update operation mode available. + + updateButton(auto_button_ptr_, msg->is_autonomous_mode_available); + updateButton(stop_button_ptr_, msg->is_stop_mode_available); + updateButton(local_button_ptr_, msg->is_local_mode_available); + updateButton(remote_button_ptr_, msg->is_remote_mode_available); + + // Update control mode available. + + updateButton(enable_button_ptr_, true); + updateButton(disable_button_ptr_, true); +} + +} // namespace tier4_adapi_rviz_plugins + +#include +PLUGINLIB_EXPORT_CLASS(tier4_adapi_rviz_plugins::OperationModeDebugPanel, rviz_common::Panel) diff --git a/visualization/tier4_adapi_rviz_plugin/src/operation_mode_debug_panel.hpp b/visualization/tier4_adapi_rviz_plugin/src/operation_mode_debug_panel.hpp new file mode 100644 index 0000000000000..52eeb8da74493 --- /dev/null +++ b/visualization/tier4_adapi_rviz_plugin/src/operation_mode_debug_panel.hpp @@ -0,0 +1,76 @@ +// +// Copyright 2020 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 OPERATION_MODE_DEBUG_PANEL_HPP_ +#define OPERATION_MODE_DEBUG_PANEL_HPP_ + +#include +#include +#include +#include + +#include +#include + +namespace tier4_adapi_rviz_plugins +{ + +class OperationModeDebugPanel : public rviz_common::Panel +{ + Q_OBJECT + +public: + explicit OperationModeDebugPanel(QWidget * parent = nullptr); + void onInitialize() override; + +public Q_SLOTS: // NOLINT for Qt + void onClickAutonomous(); + void onClickStop(); + void onClickLocal(); + void onClickRemote(); + void onClickAutowareControl(); + void onClickDirectControl(); + +protected: + using OperationModeState = autoware_adapi_v1_msgs::msg::OperationModeState; + using ChangeOperationMode = autoware_adapi_v1_msgs::srv::ChangeOperationMode; + + QLabel * operation_mode_label_ptr_{nullptr}; + QPushButton * stop_button_ptr_{nullptr}; + QPushButton * auto_button_ptr_{nullptr}; + QPushButton * local_button_ptr_{nullptr}; + QPushButton * remote_button_ptr_{nullptr}; + + QLabel * control_mode_label_ptr_{nullptr}; + QPushButton * enable_button_ptr_{nullptr}; + QPushButton * disable_button_ptr_{nullptr}; + + rclcpp::Node::SharedPtr raw_node_; + rclcpp::Subscription::SharedPtr sub_operation_mode_; + rclcpp::Client::SharedPtr client_change_to_autonomous_; + rclcpp::Client::SharedPtr client_change_to_stop_; + rclcpp::Client::SharedPtr client_change_to_local_; + rclcpp::Client::SharedPtr client_change_to_remote_; + rclcpp::Client::SharedPtr client_enable_autoware_control_; + rclcpp::Client::SharedPtr client_enable_direct_control_; + + void onOperationMode(const OperationModeState::ConstSharedPtr msg); + void changeOperationMode(const rclcpp::Client::SharedPtr client); +}; + +} // namespace tier4_adapi_rviz_plugins + +#endif // OPERATION_MODE_DEBUG_PANEL_HPP_ diff --git a/visualization/tier4_adapi_rviz_plugin/src/state_panel.cpp b/visualization/tier4_adapi_rviz_plugin/src/state_panel.cpp deleted file mode 100644 index 0525f5fdc1a09..0000000000000 --- a/visualization/tier4_adapi_rviz_plugin/src/state_panel.cpp +++ /dev/null @@ -1,633 +0,0 @@ -// -// Copyright 2020 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 "state_panel.hpp" - -#include -#include -#include -#include -#include -#include - -#include -#include - -namespace tier4_adapi_rviz_plugins -{ - -StatePanel::StatePanel(QWidget * parent) : rviz_common::Panel(parent) -{ - // Gear - auto * gear_prefix_label_ptr = new QLabel("GEAR: "); - gear_prefix_label_ptr->setAlignment(Qt::AlignRight | Qt::AlignVCenter); - gear_label_ptr_ = new QLabel("INIT"); - gear_label_ptr_->setAlignment(Qt::AlignCenter); - auto * gear_layout = new QHBoxLayout; - gear_layout->addWidget(gear_prefix_label_ptr); - gear_layout->addWidget(gear_label_ptr_); - - // Velocity Limit - 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())); - - // Emergency Button - emergency_button_ptr_ = new QPushButton("Set Emergency"); - connect(emergency_button_ptr_, SIGNAL(clicked()), this, SLOT(onClickEmergencyButton())); - - // Layout - auto * v_layout = new QVBoxLayout; - auto * velocity_limit_layout = new QHBoxLayout(); - v_layout->addWidget(makeOperationModeGroup()); - v_layout->addWidget(makeControlModeGroup()); - { - auto * h_layout = new QHBoxLayout(); - h_layout->addWidget(makeRoutingGroup()); - h_layout->addWidget(makeLocalizationGroup()); - h_layout->addWidget(makeMotionGroup()); - h_layout->addWidget(makeFailSafeGroup()); - v_layout->addLayout(h_layout); - } - - v_layout->addLayout(gear_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]")); - velocity_limit_layout->addWidget(emergency_button_ptr_); - v_layout->addLayout(velocity_limit_layout); - setLayout(v_layout); -} - -QGroupBox * StatePanel::makeOperationModeGroup() -{ - auto * group = new QGroupBox("OperationMode"); - auto * grid = new QGridLayout; - - operation_mode_label_ptr_ = new QLabel("INIT"); - operation_mode_label_ptr_->setAlignment(Qt::AlignCenter); - operation_mode_label_ptr_->setStyleSheet("border:1px solid black;"); - grid->addWidget(operation_mode_label_ptr_, 0, 0, 0, 1); - - auto_button_ptr_ = new QPushButton("AUTO"); - auto_button_ptr_->setCheckable(true); - connect(auto_button_ptr_, SIGNAL(clicked()), SLOT(onClickAutonomous())); - grid->addWidget(auto_button_ptr_, 0, 1); - - stop_button_ptr_ = new QPushButton("STOP"); - stop_button_ptr_->setCheckable(true); - connect(stop_button_ptr_, SIGNAL(clicked()), SLOT(onClickStop())); - grid->addWidget(stop_button_ptr_, 0, 2); - - local_button_ptr_ = new QPushButton("LOCAL"); - local_button_ptr_->setCheckable(true); - connect(local_button_ptr_, SIGNAL(clicked()), SLOT(onClickLocal())); - grid->addWidget(local_button_ptr_, 1, 1); - - remote_button_ptr_ = new QPushButton("REMOTE"); - remote_button_ptr_->setCheckable(true); - connect(remote_button_ptr_, SIGNAL(clicked()), SLOT(onClickRemote())); - grid->addWidget(remote_button_ptr_, 1, 2); - - group->setLayout(grid); - return group; -} - -QGroupBox * StatePanel::makeControlModeGroup() -{ - auto * group = new QGroupBox("AutowareControl"); - auto * grid = new QGridLayout; - - control_mode_label_ptr_ = new QLabel("INIT"); - control_mode_label_ptr_->setAlignment(Qt::AlignCenter); - control_mode_label_ptr_->setStyleSheet("border:1px solid black;"); - grid->addWidget(control_mode_label_ptr_, 0, 0); - - enable_button_ptr_ = new QPushButton("Enable"); - enable_button_ptr_->setCheckable(true); - connect(enable_button_ptr_, SIGNAL(clicked()), SLOT(onClickAutowareControl())); - grid->addWidget(enable_button_ptr_, 0, 1); - - disable_button_ptr_ = new QPushButton("Disable"); - disable_button_ptr_->setCheckable(true); - connect(disable_button_ptr_, SIGNAL(clicked()), SLOT(onClickDirectControl())); - grid->addWidget(disable_button_ptr_, 0, 2); - - group->setLayout(grid); - return group; -} - -QGroupBox * StatePanel::makeRoutingGroup() -{ - auto * group = new QGroupBox("Routing"); - auto * grid = new QGridLayout; - - routing_label_ptr_ = new QLabel("INIT"); - routing_label_ptr_->setAlignment(Qt::AlignCenter); - routing_label_ptr_->setStyleSheet("border:1px solid black;"); - grid->addWidget(routing_label_ptr_, 0, 0); - - clear_route_button_ptr_ = new QPushButton("Clear Route"); - clear_route_button_ptr_->setCheckable(true); - connect(clear_route_button_ptr_, SIGNAL(clicked()), SLOT(onClickClearRoute())); - grid->addWidget(clear_route_button_ptr_, 1, 0); - - group->setLayout(grid); - return group; -} - -QGroupBox * StatePanel::makeLocalizationGroup() -{ - auto * group = new QGroupBox("Localization"); - auto * grid = new QGridLayout; - - localization_label_ptr_ = new QLabel("INIT"); - localization_label_ptr_->setAlignment(Qt::AlignCenter); - localization_label_ptr_->setStyleSheet("border:1px solid black;"); - grid->addWidget(localization_label_ptr_, 0, 0); - - init_by_gnss_button_ptr_ = new QPushButton("Init by GNSS"); - connect(init_by_gnss_button_ptr_, SIGNAL(clicked()), SLOT(onClickInitByGnss())); - grid->addWidget(init_by_gnss_button_ptr_, 1, 0); - - group->setLayout(grid); - return group; -} - -QGroupBox * StatePanel::makeMotionGroup() -{ - auto * group = new QGroupBox("Motion"); - auto * grid = new QGridLayout; - - motion_label_ptr_ = new QLabel("INIT"); - motion_label_ptr_->setAlignment(Qt::AlignCenter); - motion_label_ptr_->setStyleSheet("border:1px solid black;"); - grid->addWidget(motion_label_ptr_, 0, 0); - - accept_start_button_ptr_ = new QPushButton("Accept Start"); - accept_start_button_ptr_->setCheckable(true); - connect(accept_start_button_ptr_, SIGNAL(clicked()), SLOT(onClickAcceptStart())); - grid->addWidget(accept_start_button_ptr_, 1, 0); - - group->setLayout(grid); - return group; -} - -QGroupBox * StatePanel::makeFailSafeGroup() -{ - auto * group = new QGroupBox("FailSafe"); - auto * grid = new QGridLayout; - - mrm_state_label_ptr_ = new QLabel("INIT"); - mrm_state_label_ptr_->setAlignment(Qt::AlignCenter); - mrm_state_label_ptr_->setStyleSheet("border:1px solid black;"); - grid->addWidget(mrm_state_label_ptr_, 0, 0); - - mrm_behavior_label_ptr_ = new QLabel("INIT"); - mrm_behavior_label_ptr_->setAlignment(Qt::AlignCenter); - mrm_behavior_label_ptr_->setStyleSheet("border:1px solid black;"); - grid->addWidget(mrm_behavior_label_ptr_, 1, 0); - - group->setLayout(grid); - return group; -} - -void StatePanel::onInitialize() -{ - using std::placeholders::_1; - - raw_node_ = this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node(); - - // Operation Mode - sub_operation_mode_ = raw_node_->create_subscription( - "/api/operation_mode/state", rclcpp::QoS{1}.transient_local(), - std::bind(&StatePanel::onOperationMode, this, _1)); - - client_change_to_autonomous_ = - raw_node_->create_client("/api/operation_mode/change_to_autonomous"); - - client_change_to_stop_ = - raw_node_->create_client("/api/operation_mode/change_to_stop"); - - client_change_to_local_ = - raw_node_->create_client("/api/operation_mode/change_to_local"); - - client_change_to_remote_ = - raw_node_->create_client("/api/operation_mode/change_to_remote"); - - client_enable_autoware_control_ = - raw_node_->create_client("/api/operation_mode/enable_autoware_control"); - - client_enable_direct_control_ = - raw_node_->create_client("/api/operation_mode/disable_autoware_control"); - - // Routing - sub_route_ = raw_node_->create_subscription( - "/api/routing/state", rclcpp::QoS{1}.transient_local(), - std::bind(&StatePanel::onRoute, this, _1)); - - client_clear_route_ = raw_node_->create_client("/api/routing/clear_route"); - - // Localization - sub_localization_ = raw_node_->create_subscription( - "/api/localization/initialization_state", rclcpp::QoS{1}.transient_local(), - std::bind(&StatePanel::onLocalization, this, _1)); - - client_init_by_gnss_ = - raw_node_->create_client("/api/localization/initialize"); - - // Motion - sub_motion_ = raw_node_->create_subscription( - "/api/motion/state", rclcpp::QoS{1}.transient_local(), - std::bind(&StatePanel::onMotion, this, _1)); - - client_accept_start_ = raw_node_->create_client("/api/motion/accept_start"); - - // FailSafe - sub_mrm_ = raw_node_->create_subscription( - "/api/fail_safe/mrm_state", rclcpp::QoS{1}.transient_local(), - std::bind(&StatePanel::onMRMState, this, _1)); - - // Others - sub_gear_ = raw_node_->create_subscription( - "/vehicle/status/gear_status", 10, std::bind(&StatePanel::onShift, this, _1)); - - sub_emergency_ = raw_node_->create_subscription( - "/api/autoware/get/emergency", 10, std::bind(&StatePanel::onEmergencyStatus, this, _1)); - - client_emergency_stop_ = raw_node_->create_client( - "/api/autoware/set/emergency"); - - pub_velocity_limit_ = raw_node_->create_publisher( - "/planning/scenario_planning/max_velocity_default", rclcpp::QoS{1}.transient_local()); -} - -void StatePanel::onOperationMode(const OperationModeState::ConstSharedPtr msg) -{ - auto changeButtonState = []( - QPushButton * button, const bool is_desired_mode_available, - const uint8_t current_mode = OperationModeState::UNKNOWN, - const uint8_t desired_mode = OperationModeState::STOP) { - if (is_desired_mode_available && current_mode != desired_mode) { - activateButton(button); - } else { - deactivateButton(button); - } - }; - - QString text = ""; - QString style_sheet = ""; - // Operation Mode - switch (msg->mode) { - case OperationModeState::AUTONOMOUS: - text = "AUTONOMOUS"; - style_sheet = "background-color: #00FF00;"; // green - break; - - case OperationModeState::LOCAL: - text = "LOCAL"; - style_sheet = "background-color: #FFFF00;"; // yellow - break; - - case OperationModeState::REMOTE: - text = "REMOTE"; - style_sheet = "background-color: #FFFF00;"; // yellow - break; - - case OperationModeState::STOP: - text = "STOP"; - style_sheet = "background-color: #FFA500;"; // orange - break; - - default: - text = "UNKNOWN"; - style_sheet = "background-color: #FF0000;"; // red - break; - } - - if (msg->is_in_transition) { - text += "\n(TRANSITION)"; - } - - updateLabel(operation_mode_label_ptr_, text, style_sheet); - - // Control Mode - if (msg->is_autoware_control_enabled) { - updateLabel(control_mode_label_ptr_, "Enable", "background-color: #00FF00;"); // green - } else { - updateLabel(control_mode_label_ptr_, "Disable", "background-color: #FFFF00;"); // yellow - } - - // Button - changeButtonState( - auto_button_ptr_, msg->is_autonomous_mode_available, msg->mode, OperationModeState::AUTONOMOUS); - changeButtonState( - stop_button_ptr_, msg->is_stop_mode_available, msg->mode, OperationModeState::STOP); - changeButtonState( - local_button_ptr_, msg->is_local_mode_available, msg->mode, OperationModeState::LOCAL); - changeButtonState( - remote_button_ptr_, msg->is_remote_mode_available, msg->mode, OperationModeState::REMOTE); - - changeButtonState(enable_button_ptr_, !msg->is_autoware_control_enabled); - changeButtonState(disable_button_ptr_, msg->is_autoware_control_enabled); -} - -void StatePanel::onRoute(const RouteState::ConstSharedPtr msg) -{ - QString text = ""; - QString style_sheet = ""; - switch (msg->state) { - case RouteState::UNSET: - text = "UNSET"; - style_sheet = "background-color: #FFFF00;"; // yellow - break; - - case RouteState::SET: - text = "SET"; - style_sheet = "background-color: #00FF00;"; // green - break; - - case RouteState::ARRIVED: - text = "ARRIVED"; - style_sheet = "background-color: #FFA500;"; // orange - break; - - case RouteState::CHANGING: - text = "CHANGING"; - style_sheet = "background-color: #FFFF00;"; // yellow - break; - - default: - text = "UNKNOWN"; - style_sheet = "background-color: #FF0000;"; // red - break; - } - - updateLabel(routing_label_ptr_, text, style_sheet); - - if (msg->state == RouteState::SET) { - activateButton(clear_route_button_ptr_); - } else { - deactivateButton(clear_route_button_ptr_); - } -} - -void StatePanel::onLocalization(const LocalizationInitializationState::ConstSharedPtr msg) -{ - QString text = ""; - QString style_sheet = ""; - switch (msg->state) { - case LocalizationInitializationState::UNINITIALIZED: - text = "UNINITIALIZED"; - style_sheet = "background-color: #FFFF00;"; // yellow - break; - - case LocalizationInitializationState::INITIALIZING: - text = "INITIALIZING"; - style_sheet = "background-color: #FFA500;"; // orange - break; - - case LocalizationInitializationState::INITIALIZED: - text = "INITIALIZED"; - style_sheet = "background-color: #00FF00;"; // green - break; - - default: - text = "UNKNOWN"; - style_sheet = "background-color: #FF0000;"; // red - break; - } - - updateLabel(localization_label_ptr_, text, style_sheet); -} - -void StatePanel::onMotion(const MotionState::ConstSharedPtr msg) -{ - QString text = ""; - QString style_sheet = ""; - switch (msg->state) { - case MotionState::STARTING: - text = "STARTING"; - style_sheet = "background-color: #FFFF00;"; // yellow - break; - - case MotionState::STOPPED: - text = "STOPPED"; - style_sheet = "background-color: #FFA500;"; // orange - break; - - case MotionState::MOVING: - text = "MOVING"; - style_sheet = "background-color: #00FF00;"; // green - break; - - default: - text = "UNKNOWN"; - style_sheet = "background-color: #FF0000;"; // red - break; - } - - updateLabel(motion_label_ptr_, text, style_sheet); - - if (msg->state == MotionState::STARTING) { - activateButton(accept_start_button_ptr_); - } else { - deactivateButton(accept_start_button_ptr_); - } -} - -void StatePanel::onMRMState(const MRMState::ConstSharedPtr msg) -{ - // state - { - QString text = ""; - QString style_sheet = ""; - switch (msg->state) { - case MRMState::NONE: - text = "NONE"; - style_sheet = "background-color: #00FF00;"; // green - break; - - case MRMState::MRM_OPERATING: - text = "MRM_OPERATING"; - style_sheet = "background-color: #FFA500;"; // orange - break; - - case MRMState::MRM_SUCCEEDED: - text = "MRM_SUCCEEDED"; - style_sheet = "background-color: #FFFF00;"; // yellow - break; - - case MRMState::MRM_FAILED: - text = "MRM_FAILED"; - style_sheet = "background-color: #FF0000;"; // red - break; - - default: - text = "UNKNOWN"; - style_sheet = "background-color: #FF0000;"; // red - break; - } - - updateLabel(mrm_state_label_ptr_, text, style_sheet); - } - - // behavior - { - QString text = ""; - QString style_sheet = ""; - switch (msg->behavior) { - case MRMState::NONE: - text = "NONE"; - style_sheet = "background-color: #00FF00;"; // green - break; - - case MRMState::PULL_OVER: - text = "PULL_OVER"; - style_sheet = "background-color: #FFFF00;"; // yellow - break; - - case MRMState::COMFORTABLE_STOP: - text = "COMFORTABLE_STOP"; - style_sheet = "background-color: #FFFF00;"; // yellow - break; - - case MRMState::EMERGENCY_STOP: - text = "EMERGENCY_STOP"; - style_sheet = "background-color: #FFA500;"; // orange - break; - - default: - text = "UNKNOWN"; - style_sheet = "background-color: #FF0000;"; // red - break; - } - - updateLabel(mrm_behavior_label_ptr_, text, style_sheet); - } -} - -void StatePanel::onShift(const autoware_vehicle_msgs::msg::GearReport::ConstSharedPtr msg) -{ - switch (msg->report) { - case autoware_vehicle_msgs::msg::GearReport::PARK: - gear_label_ptr_->setText("PARKING"); - break; - case autoware_vehicle_msgs::msg::GearReport::REVERSE: - gear_label_ptr_->setText("REVERSE"); - break; - case autoware_vehicle_msgs::msg::GearReport::DRIVE: - gear_label_ptr_->setText("DRIVE"); - break; - case autoware_vehicle_msgs::msg::GearReport::NEUTRAL: - gear_label_ptr_->setText("NEUTRAL"); - break; - case autoware_vehicle_msgs::msg::GearReport::LOW: - gear_label_ptr_->setText("LOW"); - break; - } -} - -void StatePanel::onEmergencyStatus( - const tier4_external_api_msgs::msg::Emergency::ConstSharedPtr msg) -{ - current_emergency_ = msg->emergency; - if (msg->emergency) { - emergency_button_ptr_->setText(QString::fromStdString("Clear Emergency")); - emergency_button_ptr_->setStyleSheet("background-color: #FF0000;"); - } else { - emergency_button_ptr_->setText(QString::fromStdString("Set Emergency")); - emergency_button_ptr_->setStyleSheet("background-color: #00FF00;"); - } -} - -void StatePanel::onClickVelocityLimit() -{ - auto velocity_limit = std::make_shared(); - velocity_limit->stamp = raw_node_->now(); - velocity_limit->max_velocity = pub_velocity_limit_input_->value() / 3.6; - pub_velocity_limit_->publish(*velocity_limit); -} - -void StatePanel::onClickAutonomous() -{ - callServiceWithoutResponse(client_change_to_autonomous_); -} -void StatePanel::onClickStop() -{ - callServiceWithoutResponse(client_change_to_stop_); -} -void StatePanel::onClickLocal() -{ - callServiceWithoutResponse(client_change_to_local_); -} -void StatePanel::onClickRemote() -{ - callServiceWithoutResponse(client_change_to_remote_); -} -void StatePanel::onClickAutowareControl() -{ - callServiceWithoutResponse(client_enable_autoware_control_); -} -void StatePanel::onClickDirectControl() -{ - callServiceWithoutResponse(client_enable_direct_control_); -} - -void StatePanel::onClickClearRoute() -{ - callServiceWithoutResponse(client_clear_route_); -} - -void StatePanel::onClickInitByGnss() -{ - callServiceWithoutResponse(client_init_by_gnss_); -} - -void StatePanel::onClickAcceptStart() -{ - callServiceWithoutResponse(client_accept_start_); -} - -void StatePanel::onClickEmergencyButton() -{ - using tier4_external_api_msgs::msg::ResponseStatus; - using tier4_external_api_msgs::srv::SetEmergency; - - auto request = std::make_shared(); - request->emergency = !current_emergency_; - - RCLCPP_INFO(raw_node_->get_logger(), request->emergency ? "Set Emergency" : "Clear Emergency"); - - client_emergency_stop_->async_send_request( - request, [this](rclcpp::Client::SharedFuture result) { - const auto & response = result.get(); - if (response->status.code == ResponseStatus::SUCCESS) { - RCLCPP_INFO(raw_node_->get_logger(), "service succeeded"); - } else { - RCLCPP_WARN( - raw_node_->get_logger(), "service failed: %s", response->status.message.c_str()); - } - }); -} - -} // namespace tier4_adapi_rviz_plugins - -#include -PLUGINLIB_EXPORT_CLASS(tier4_adapi_rviz_plugins::StatePanel, rviz_common::Panel) diff --git a/visualization/tier4_adapi_rviz_plugin/src/state_panel.hpp b/visualization/tier4_adapi_rviz_plugin/src/state_panel.hpp deleted file mode 100644 index b30494772061e..0000000000000 --- a/visualization/tier4_adapi_rviz_plugin/src/state_panel.hpp +++ /dev/null @@ -1,206 +0,0 @@ -// -// Copyright 2020 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 STATE_PANEL_HPP_ -#define STATE_PANEL_HPP_ - -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include - -namespace tier4_adapi_rviz_plugins -{ - -class StatePanel : public rviz_common::Panel -{ - using OperationModeState = autoware_adapi_v1_msgs::msg::OperationModeState; - using ChangeOperationMode = autoware_adapi_v1_msgs::srv::ChangeOperationMode; - using RouteState = autoware_adapi_v1_msgs::msg::RouteState; - using ClearRoute = autoware_adapi_v1_msgs::srv::ClearRoute; - using LocalizationInitializationState = - autoware_adapi_v1_msgs::msg::LocalizationInitializationState; - using InitializeLocalization = autoware_adapi_v1_msgs::srv::InitializeLocalization; - using MotionState = autoware_adapi_v1_msgs::msg::MotionState; - using AcceptStart = autoware_adapi_v1_msgs::srv::AcceptStart; - using MRMState = autoware_adapi_v1_msgs::msg::MrmState; - - Q_OBJECT - -public: - explicit StatePanel(QWidget * parent = nullptr); - void onInitialize() override; - -public Q_SLOTS: // NOLINT for Qt - void onClickAutonomous(); - void onClickStop(); - void onClickLocal(); - void onClickRemote(); - void onClickAutowareControl(); - void onClickDirectControl(); - void onClickClearRoute(); - void onClickInitByGnss(); - void onClickAcceptStart(); - void onClickVelocityLimit(); - void onClickEmergencyButton(); - -protected: - // Layout - QGroupBox * makeOperationModeGroup(); - QGroupBox * makeControlModeGroup(); - QGroupBox * makeRoutingGroup(); - QGroupBox * makeLocalizationGroup(); - QGroupBox * makeMotionGroup(); - QGroupBox * makeFailSafeGroup(); - - void onShift(const autoware_vehicle_msgs::msg::GearReport::ConstSharedPtr msg); - void onEmergencyStatus(const tier4_external_api_msgs::msg::Emergency::ConstSharedPtr msg); - - rclcpp::Node::SharedPtr raw_node_; - rclcpp::Subscription::SharedPtr sub_gear_; - rclcpp::Client::SharedPtr client_emergency_stop_; - rclcpp::Subscription::SharedPtr sub_emergency_; - rclcpp::Publisher::SharedPtr pub_velocity_limit_; - - // Operation Mode - QLabel * operation_mode_label_ptr_{nullptr}; - QPushButton * stop_button_ptr_{nullptr}; - QPushButton * auto_button_ptr_{nullptr}; - QPushButton * local_button_ptr_{nullptr}; - QPushButton * remote_button_ptr_{nullptr}; - - rclcpp::Subscription::SharedPtr sub_operation_mode_; - rclcpp::Client::SharedPtr client_change_to_autonomous_; - rclcpp::Client::SharedPtr client_change_to_stop_; - rclcpp::Client::SharedPtr client_change_to_local_; - rclcpp::Client::SharedPtr client_change_to_remote_; - - // Control Mode - QLabel * control_mode_label_ptr_{nullptr}; - QPushButton * enable_button_ptr_{nullptr}; - QPushButton * disable_button_ptr_{nullptr}; - rclcpp::Client::SharedPtr client_enable_autoware_control_; - rclcpp::Client::SharedPtr client_enable_direct_control_; - - // Functions - void onOperationMode(const OperationModeState::ConstSharedPtr msg); - void changeOperationMode(const rclcpp::Client::SharedPtr client); - - // Routing - QLabel * routing_label_ptr_{nullptr}; - QPushButton * clear_route_button_ptr_{nullptr}; - - rclcpp::Subscription::SharedPtr sub_route_; - rclcpp::Client::SharedPtr client_clear_route_; - - void onRoute(const RouteState::ConstSharedPtr msg); - - // Localization - QLabel * localization_label_ptr_{nullptr}; - QPushButton * init_by_gnss_button_ptr_{nullptr}; - - rclcpp::Subscription::SharedPtr sub_localization_; - rclcpp::Client::SharedPtr client_init_by_gnss_; - - void onLocalization(const LocalizationInitializationState::ConstSharedPtr msg); - - // Motion - QLabel * motion_label_ptr_{nullptr}; - QPushButton * accept_start_button_ptr_{nullptr}; - - rclcpp::Subscription::SharedPtr sub_motion_; - rclcpp::Client::SharedPtr client_accept_start_; - - void onMotion(const MotionState::ConstSharedPtr msg); - - // FailSafe - QLabel * mrm_state_label_ptr_{nullptr}; - QLabel * mrm_behavior_label_ptr_{nullptr}; - - rclcpp::Subscription::SharedPtr sub_mrm_; - - void onMRMState(const MRMState::ConstSharedPtr msg); - - // Others - QPushButton * velocity_limit_button_ptr_; - QLabel * gear_label_ptr_; - - QSpinBox * pub_velocity_limit_input_; - QPushButton * emergency_button_ptr_; - - bool current_emergency_{false}; - - template - void callServiceWithoutResponse(const typename rclcpp::Client::SharedPtr client) - { - auto req = std::make_shared(); - - RCLCPP_DEBUG(raw_node_->get_logger(), "client request"); - - if (!client->service_is_ready()) { - RCLCPP_DEBUG(raw_node_->get_logger(), "client is unavailable"); - return; - } - - client->async_send_request(req, [this](typename rclcpp::Client::SharedFuture result) { - RCLCPP_DEBUG( - raw_node_->get_logger(), "Status: %d, %s", result.get()->status.code, - result.get()->status.message.c_str()); - }); - } - - static void updateLabel(QLabel * label, QString text, QString style_sheet) - { - label->setText(text); - label->setStyleSheet(style_sheet); - } - - static void activateButton(QAbstractButton * button) - { - button->setChecked(false); - button->setEnabled(true); - } - - static void deactivateButton(QAbstractButton * button) - { - button->setChecked(true); - button->setEnabled(false); - } -}; - -} // namespace tier4_adapi_rviz_plugins - -#endif // STATE_PANEL_HPP_ From f89ea332ee510d061b06dcec22caef81d42f0a2a Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 27 Jan 2025 11:22:57 +0900 Subject: [PATCH 323/334] fix(goal_planner): fix waiting approval path of backward parking (#10015) Signed-off-by: kosuke55 --- .../src/goal_planner_module.cpp | 16 ++++++++++++---- 1 file changed, 12 insertions(+), 4 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 0a92f6d99dfeb..762193ceab236 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -1602,12 +1602,20 @@ PathWithLaneId GoalPlannerModule::generateStopPath( return PathWithLaneId{}; } - // extend previous module path to generate reference path for stop path + // Generate reference_path to extend the previous path. + // If pull_over_path is ARC_BACKWARD, generate path to the start_pose of the pull_over_path, + // otherwise, generate path to the goal_pose. + const auto & pull_over_path_opt = context_data.pull_over_path_opt; const auto reference_path = std::invoke([&]() -> PathWithLaneId { const auto s_current = lanelet::utils::getArcCoordinates(current_lanes, current_pose).length; const double s_start = std::max(0.0, s_current - common_parameters.backward_path_length); + const bool is_arc_backward = + pull_over_path_opt.has_value() && + pull_over_path_opt.value().type() == PullOverPlannerType::ARC_BACKWARD; + const Pose path_end_pose = + is_arc_backward ? pull_over_path_opt.value().start_pose() : route_handler->getGoalPose(); const double s_end = std::clamp( - lanelet::utils::getArcCoordinates(current_lanes, route_handler->getGoalPose()).length, + lanelet::utils::getArcCoordinates(current_lanes, path_end_pose).length, s_current + std::numeric_limits::epsilon(), s_current + common_parameters.forward_path_length); return route_handler->getCenterLinePath(current_lanes, s_start, s_end, true); @@ -1637,8 +1645,8 @@ PathWithLaneId GoalPlannerModule::generateStopPath( // difference between the outer and inner sides) // 4. feasible stop const auto stop_pose_opt = std::invoke([&]() -> std::optional { - if (context_data.pull_over_path_opt) - return std::make_optional(context_data.pull_over_path_opt.value().start_pose()); + if (pull_over_path_opt) + return std::make_optional(pull_over_path_opt.value().start_pose()); if (context_data.lane_parking_response.closest_start_pose) return context_data.lane_parking_response.closest_start_pose; return decel_pose; From 4c13bb08455a1536185029782cfe30d9dbd34e42 Mon Sep 17 00:00:00 2001 From: Junya Sasaki Date: Mon, 27 Jan 2025 13:38:28 +0900 Subject: [PATCH 324/334] feat: apply `autoware` prefix for `component_state_monitor` and its dependencies (#9961) Signed-off-by: Junya Sasaki Signed-off-by: Takagi, Isamu Signed-off-by: Ryohsuke Mitsudome Signed-off-by: Shintaro Sakoda --- .../tier4_system_launch/launch/system.launch.xml | 4 ++-- launch/tier4_system_launch/package.xml | 2 +- .../CHANGELOG.rst | 6 +++--- .../CMakeLists.txt | 4 ++-- .../README.md | 2 +- .../config/topics.yaml | 0 .../launch/component_state_monitor.launch.py | 6 +++--- .../package.xml | 7 ++++--- .../src/main.cpp | 6 +++--- .../src/main.hpp | 4 ++-- .../document/autoware-state.md | 2 +- .../CHANGELOG.rst | 6 +++--- .../CMakeLists.txt | 6 +++--- .../README.md | 6 +++--- .../config/default.param.yaml | 0 .../doc/format/edit.md | 0 .../doc/format/edit/remove.md | 0 .../doc/format/graph.md | 0 .../doc/format/path.md | 0 .../doc/format/unit.md | 0 .../doc/format/unit/and.md | 0 .../doc/format/unit/const.md | 0 .../doc/format/unit/diag.md | 0 .../doc/format/unit/link.md | 0 .../doc/format/unit/or.md | 0 .../doc/format/unit/remap.md | 0 .../doc/overview.drawio.svg | 0 .../doc/tool/tree.md | 4 ++-- .../example/dummy-diags.py | 0 .../example/example-edit.launch.xml | 6 ++++++ .../example/example-main.launch.xml | 6 ++++++ .../example/graph/edit.yaml | 0 .../example/graph/main.yaml | 0 .../example/graph/module1.yaml | 0 .../example/graph/module2.yaml | 0 .../launch/aggregator.launch.xml | 8 ++++++++ .../package.xml | 3 ++- .../script/dump.py | 0 .../src/common/graph/config.cpp | 4 ++-- .../src/common/graph/config.hpp | 4 ++-- .../src/common/graph/data.cpp | 4 ++-- .../src/common/graph/data.hpp | 4 ++-- .../src/common/graph/error.cpp | 4 ++-- .../src/common/graph/error.hpp | 4 ++-- .../src/common/graph/graph.cpp | 4 ++-- .../src/common/graph/graph.hpp | 4 ++-- .../src/common/graph/loader.cpp | 4 ++-- .../src/common/graph/loader.hpp | 4 ++-- .../src/common/graph/names.hpp | 8 ++++---- .../src/common/graph/types.hpp | 4 ++-- .../src/common/graph/units.cpp | 4 ++-- .../src/common/graph/units.hpp | 4 ++-- .../src/node/aggregator.cpp | 6 +++--- .../src/node/aggregator.hpp | 4 ++-- .../src/node/availability.cpp | 4 ++-- .../src/node/availability.hpp | 4 ++-- .../src/tool/plantuml.cpp | 6 +++--- .../src/tool/tree.cpp | 6 +++--- .../test/files/test1/field-not-found.yaml | 0 .../test/files/test1/file-not-found.yaml | 0 .../test/files/test1/graph-circulation.yaml | 0 .../test/files/test1/invalid-dict-type.yaml | 0 .../test/files/test1/invalid-list-type.yaml | 0 .../test/files/test1/path-conflict.yaml | 0 .../test/files/test1/path-not-found.yaml | 0 .../test/files/test1/unknown-substitution.yaml | 0 .../test/files/test1/unknown-unit-type.yaml | 0 .../test/files/test2/and.yaml | 0 .../test/files/test2/or.yaml | 0 .../test/files/test2/warn-to-error.yaml | 0 .../test/files/test2/warn-to-ok.yaml | 0 .../test/src/test1.cpp | 2 +- .../test/src/test2.cpp | 2 +- .../test/src/utils.cpp | 0 .../test/src/utils.hpp | 0 .../CHANGELOG.rst | 6 +++--- .../CMakeLists.txt | 2 +- .../README.md | 0 .../config/autoware-main.yaml | 14 +++++++------- .../config/autoware-psim.yaml | 0 .../config/control.yaml | 0 .../config/hardware.yaml | 0 .../config/localization.yaml | 0 .../config/map.yaml | 0 .../config/perception.yaml | 0 .../config/planning.yaml | 0 .../config/system.yaml | 0 .../config/vehicle.yaml | 0 .../launch/system_diagnostic_monitor.launch.xml | 9 +++++++++ .../package.xml | 7 ++++--- .../script/component_state_diagnostics.py | 0 .../CHANGELOG.rst | 6 +++--- .../CMakeLists.txt | 10 +++++----- .../README.md | 2 +- .../topic_state_monitor/topic_state_monitor.hpp | 10 +++++----- .../topic_state_monitor_core.hpp | 12 ++++++------ .../launch/topic_state_monitor.launch.xml | 2 +- .../launch/topic_state_monitor_tf.launch.xml | 2 +- .../package.xml | 5 +++-- .../topic_state_monitor/topic_state_monitor.cpp | 6 +++--- .../src/topic_state_monitor_core.cpp | 8 ++++---- .../example/example-edit.launch.xml | 6 ------ .../example/example-main.launch.xml | 6 ------ .../launch/aggregator.launch.xml | 8 -------- .../launch/system_diagnostic_monitor.launch.xml | 9 --------- 105 files changed, 158 insertions(+), 154 deletions(-) rename system/{component_state_monitor => autoware_component_state_monitor}/CHANGELOG.rst (97%) rename system/{component_state_monitor => autoware_component_state_monitor}/CMakeLists.txt (73%) rename system/{component_state_monitor => autoware_component_state_monitor}/README.md (87%) rename system/{component_state_monitor => autoware_component_state_monitor}/config/topics.yaml (100%) rename system/{component_state_monitor => autoware_component_state_monitor}/launch/component_state_monitor.launch.py (94%) rename system/{component_state_monitor => autoware_component_state_monitor}/package.xml (74%) rename system/{component_state_monitor => autoware_component_state_monitor}/src/main.cpp (95%) rename system/{component_state_monitor => autoware_component_state_monitor}/src/main.hpp (95%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/CHANGELOG.rst (97%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/CMakeLists.txt (89%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/README.md (96%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/config/default.param.yaml (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/doc/format/edit.md (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/doc/format/edit/remove.md (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/doc/format/graph.md (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/doc/format/path.md (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/doc/format/unit.md (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/doc/format/unit/and.md (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/doc/format/unit/const.md (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/doc/format/unit/diag.md (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/doc/format/unit/link.md (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/doc/format/unit/or.md (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/doc/format/unit/remap.md (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/doc/overview.drawio.svg (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/doc/tool/tree.md (83%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/example/dummy-diags.py (100%) create mode 100644 system/autoware_diagnostic_graph_aggregator/example/example-edit.launch.xml create mode 100644 system/autoware_diagnostic_graph_aggregator/example/example-main.launch.xml rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/example/graph/edit.yaml (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/example/graph/main.yaml (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/example/graph/module1.yaml (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/example/graph/module2.yaml (100%) create mode 100644 system/autoware_diagnostic_graph_aggregator/launch/aggregator.launch.xml rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/package.xml (87%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/script/dump.py (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/src/common/graph/config.cpp (98%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/src/common/graph/config.hpp (96%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/src/common/graph/data.cpp (95%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/src/common/graph/data.hpp (93%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/src/common/graph/error.cpp (93%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/src/common/graph/error.hpp (97%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/src/common/graph/graph.cpp (95%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/src/common/graph/graph.hpp (94%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/src/common/graph/loader.cpp (98%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/src/common/graph/loader.hpp (94%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/src/common/graph/names.hpp (83%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/src/common/graph/types.hpp (95%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/src/common/graph/units.cpp (98%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/src/common/graph/units.hpp (98%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/src/node/aggregator.cpp (94%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/src/node/aggregator.hpp (93%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/src/node/availability.cpp (96%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/src/node/availability.hpp (93%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/src/tool/plantuml.cpp (88%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/src/tool/tree.cpp (92%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/test/files/test1/field-not-found.yaml (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/test/files/test1/file-not-found.yaml (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/test/files/test1/graph-circulation.yaml (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/test/files/test1/invalid-dict-type.yaml (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/test/files/test1/invalid-list-type.yaml (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/test/files/test1/path-conflict.yaml (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/test/files/test1/path-not-found.yaml (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/test/files/test1/unknown-substitution.yaml (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/test/files/test1/unknown-unit-type.yaml (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/test/files/test2/and.yaml (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/test/files/test2/or.yaml (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/test/files/test2/warn-to-error.yaml (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/test/files/test2/warn-to-ok.yaml (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/test/src/test1.cpp (96%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/test/src/test2.cpp (98%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/test/src/utils.cpp (100%) rename system/{diagnostic_graph_aggregator => autoware_diagnostic_graph_aggregator}/test/src/utils.hpp (100%) rename system/{system_diagnostic_monitor => autoware_system_diagnostic_monitor}/CHANGELOG.rst (95%) rename system/{system_diagnostic_monitor => autoware_system_diagnostic_monitor}/CMakeLists.txt (86%) rename system/{system_diagnostic_monitor => autoware_system_diagnostic_monitor}/README.md (100%) rename system/{system_diagnostic_monitor => autoware_system_diagnostic_monitor}/config/autoware-main.yaml (78%) rename system/{system_diagnostic_monitor => autoware_system_diagnostic_monitor}/config/autoware-psim.yaml (100%) rename system/{system_diagnostic_monitor => autoware_system_diagnostic_monitor}/config/control.yaml (100%) rename system/{system_diagnostic_monitor => autoware_system_diagnostic_monitor}/config/hardware.yaml (100%) rename system/{system_diagnostic_monitor => autoware_system_diagnostic_monitor}/config/localization.yaml (100%) rename system/{system_diagnostic_monitor => autoware_system_diagnostic_monitor}/config/map.yaml (100%) rename system/{system_diagnostic_monitor => autoware_system_diagnostic_monitor}/config/perception.yaml (100%) rename system/{system_diagnostic_monitor => autoware_system_diagnostic_monitor}/config/planning.yaml (100%) rename system/{system_diagnostic_monitor => autoware_system_diagnostic_monitor}/config/system.yaml (100%) rename system/{system_diagnostic_monitor => autoware_system_diagnostic_monitor}/config/vehicle.yaml (100%) create mode 100644 system/autoware_system_diagnostic_monitor/launch/system_diagnostic_monitor.launch.xml rename system/{system_diagnostic_monitor => autoware_system_diagnostic_monitor}/package.xml (74%) rename system/{system_diagnostic_monitor => autoware_system_diagnostic_monitor}/script/component_state_diagnostics.py (100%) rename system/{topic_state_monitor => autoware_topic_state_monitor}/CHANGELOG.rst (98%) rename system/{topic_state_monitor => autoware_topic_state_monitor}/CMakeLists.txt (50%) rename system/{topic_state_monitor => autoware_topic_state_monitor}/README.md (99%) rename system/{topic_state_monitor/include => autoware_topic_state_monitor/include/autoware}/topic_state_monitor/topic_state_monitor.hpp (84%) rename system/{topic_state_monitor/include => autoware_topic_state_monitor/include/autoware}/topic_state_monitor/topic_state_monitor_core.hpp (83%) rename system/{topic_state_monitor => autoware_topic_state_monitor}/launch/topic_state_monitor.launch.xml (88%) rename system/{topic_state_monitor => autoware_topic_state_monitor}/launch/topic_state_monitor_tf.launch.xml (89%) rename system/{topic_state_monitor => autoware_topic_state_monitor}/package.xml (80%) rename system/{topic_state_monitor => autoware_topic_state_monitor}/src/topic_state_monitor/topic_state_monitor.cpp (94%) rename system/{topic_state_monitor => autoware_topic_state_monitor}/src/topic_state_monitor_core.cpp (96%) delete mode 100644 system/diagnostic_graph_aggregator/example/example-edit.launch.xml delete mode 100644 system/diagnostic_graph_aggregator/example/example-main.launch.xml delete mode 100644 system/diagnostic_graph_aggregator/launch/aggregator.launch.xml delete mode 100644 system/system_diagnostic_monitor/launch/system_diagnostic_monitor.launch.xml diff --git a/launch/tier4_system_launch/launch/system.launch.xml b/launch/tier4_system_launch/launch/system.launch.xml index 8e8e17bc772e0..c22b8b091bf59 100644 --- a/launch/tier4_system_launch/launch/system.launch.xml +++ b/launch/tier4_system_launch/launch/system.launch.xml @@ -72,7 +72,7 @@ - + @@ -92,7 +92,7 @@ - + diff --git a/launch/tier4_system_launch/package.xml b/launch/tier4_system_launch/package.xml index fd76fd52a0f29..65a8c11feaa73 100644 --- a/launch/tier4_system_launch/package.xml +++ b/launch/tier4_system_launch/package.xml @@ -11,8 +11,8 @@ ament_cmake_auto autoware_cmake + autoware_component_state_monitor autoware_system_monitor - component_state_monitor ament_lint_auto autoware_lint_common diff --git a/system/component_state_monitor/CHANGELOG.rst b/system/autoware_component_state_monitor/CHANGELOG.rst similarity index 97% rename from system/component_state_monitor/CHANGELOG.rst rename to system/autoware_component_state_monitor/CHANGELOG.rst index 40843314ddf4a..b7e38c40b2ed3 100644 --- a/system/component_state_monitor/CHANGELOG.rst +++ b/system/autoware_component_state_monitor/CHANGELOG.rst @@ -1,6 +1,6 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package component_state_monitor -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_component_state_monitor +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.40.0 (2024-12-12) ------------------- diff --git a/system/component_state_monitor/CMakeLists.txt b/system/autoware_component_state_monitor/CMakeLists.txt similarity index 73% rename from system/component_state_monitor/CMakeLists.txt rename to system/autoware_component_state_monitor/CMakeLists.txt index 23037b1400e2d..3ca6e4f5c4e1a 100644 --- a/system/component_state_monitor/CMakeLists.txt +++ b/system/autoware_component_state_monitor/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(component_state_monitor) +project(autoware_component_state_monitor) find_package(autoware_cmake REQUIRED) autoware_package() @@ -9,7 +9,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED ) rclcpp_components_register_nodes(${PROJECT_NAME} - "component_state_monitor::StateMonitor" + "autoware::component_state_monitor::StateMonitor" ) ament_auto_package(INSTALL_TO_SHARE config launch) diff --git a/system/component_state_monitor/README.md b/system/autoware_component_state_monitor/README.md similarity index 87% rename from system/component_state_monitor/README.md rename to system/autoware_component_state_monitor/README.md index 327c7b7651caf..a7ea12624da0d 100644 --- a/system/component_state_monitor/README.md +++ b/system/autoware_component_state_monitor/README.md @@ -1,4 +1,4 @@ -# component_state_monitor +# autoware_component_state_monitor The component state monitor checks the state of each component using topic state monitor. This is an implementation for backward compatibility with the AD service state monitor. diff --git a/system/component_state_monitor/config/topics.yaml b/system/autoware_component_state_monitor/config/topics.yaml similarity index 100% rename from system/component_state_monitor/config/topics.yaml rename to system/autoware_component_state_monitor/config/topics.yaml diff --git a/system/component_state_monitor/launch/component_state_monitor.launch.py b/system/autoware_component_state_monitor/launch/component_state_monitor.launch.py similarity index 94% rename from system/component_state_monitor/launch/component_state_monitor.launch.py rename to system/autoware_component_state_monitor/launch/component_state_monitor.launch.py index 6fcb4e6f13020..0fd166bd80d37 100644 --- a/system/component_state_monitor/launch/component_state_monitor.launch.py +++ b/system/autoware_component_state_monitor/launch/component_state_monitor.launch.py @@ -39,7 +39,7 @@ def create_topic_monitor_name(row): def create_topic_monitor_node(row): tf_mode = "" if "topic_type" in row["args"] else "_tf" - package = FindPackageShare("topic_state_monitor") + package = FindPackageShare("autoware_topic_state_monitor") include = PathJoinSubstitution([package, f"launch/topic_state_monitor{tf_mode}.launch.xml"]) diag_name = create_diagnostic_name(row) arguments = [("diag_name", diag_name)] + [(k, str(v)) for k, v in row["args"].items()] @@ -62,8 +62,8 @@ def launch_setup(context, *args, **kwargs): component = ComposableNode( namespace="component_state_monitor", name="component", - package="component_state_monitor", - plugin="component_state_monitor::StateMonitor", + package="autoware_component_state_monitor", + plugin="autoware::component_state_monitor::StateMonitor", parameters=[{"topic_monitor_names": topic_monitor_names}, topic_monitor_param], ) container = ComposableNodeContainer( diff --git a/system/component_state_monitor/package.xml b/system/autoware_component_state_monitor/package.xml similarity index 74% rename from system/component_state_monitor/package.xml rename to system/autoware_component_state_monitor/package.xml index b92dd4af9517f..c57725b0c1f85 100644 --- a/system/component_state_monitor/package.xml +++ b/system/autoware_component_state_monitor/package.xml @@ -1,10 +1,11 @@ - component_state_monitor + autoware_component_state_monitor 0.40.0 - The component_state_monitor package + The autoware_component_state_monitor package Takagi, Isamu + Junya Sasaki Apache License 2.0 ament_cmake_auto @@ -15,7 +16,7 @@ rclcpp_components tier4_system_msgs - topic_state_monitor + autoware_topic_state_monitor ament_lint_auto autoware_lint_common diff --git a/system/component_state_monitor/src/main.cpp b/system/autoware_component_state_monitor/src/main.cpp similarity index 95% rename from system/component_state_monitor/src/main.cpp rename to system/autoware_component_state_monitor/src/main.cpp index c87963b1b21c0..43278c7ae894c 100644 --- a/system/component_state_monitor/src/main.cpp +++ b/system/autoware_component_state_monitor/src/main.cpp @@ -18,7 +18,7 @@ #include #include -namespace component_state_monitor +namespace autoware::component_state_monitor { // clang-format off @@ -129,7 +129,7 @@ void StateMonitor::on_diag(const DiagnosticArray::ConstSharedPtr msg) } } -} // namespace component_state_monitor +} // namespace autoware::component_state_monitor #include -RCLCPP_COMPONENTS_REGISTER_NODE(component_state_monitor::StateMonitor) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::component_state_monitor::StateMonitor) diff --git a/system/component_state_monitor/src/main.hpp b/system/autoware_component_state_monitor/src/main.hpp similarity index 95% rename from system/component_state_monitor/src/main.hpp rename to system/autoware_component_state_monitor/src/main.hpp index 73f57f56b4f87..81904553bb272 100644 --- a/system/component_state_monitor/src/main.hpp +++ b/system/autoware_component_state_monitor/src/main.hpp @@ -24,7 +24,7 @@ #include #include -namespace component_state_monitor +namespace autoware::component_state_monitor { // clang-format off @@ -73,6 +73,6 @@ class StateMonitor : public rclcpp::Node void on_diag(const DiagnosticArray::ConstSharedPtr msg); }; -} // namespace component_state_monitor +} // namespace autoware::component_state_monitor #endif // MAIN_HPP_ diff --git a/system/autoware_default_adapi/document/autoware-state.md b/system/autoware_default_adapi/document/autoware-state.md index eb31a4d41bc1d..cb4d95af14c68 100644 --- a/system/autoware_default_adapi/document/autoware-state.md +++ b/system/autoware_default_adapi/document/autoware-state.md @@ -3,7 +3,7 @@ ## Overview Since `/autoware/state` was so widely used, this packages creates it from the states of AD API for backwards compatibility. -The diagnostic checks that ad_service_state_monitor used to perform have been replaced by component_state_monitor. +The diagnostic checks that ad_service_state_monitor used to perform have been replaced by autoware_component_state_monitor. The service `/autoware/shutdown` to change autoware state to finalizing is also supported for compatibility. ![autoware-state-architecture](images/autoware-state-architecture.drawio.svg) diff --git a/system/diagnostic_graph_aggregator/CHANGELOG.rst b/system/autoware_diagnostic_graph_aggregator/CHANGELOG.rst similarity index 97% rename from system/diagnostic_graph_aggregator/CHANGELOG.rst rename to system/autoware_diagnostic_graph_aggregator/CHANGELOG.rst index 51abe33dcfbdf..c396519a9467b 100644 --- a/system/diagnostic_graph_aggregator/CHANGELOG.rst +++ b/system/autoware_diagnostic_graph_aggregator/CHANGELOG.rst @@ -1,6 +1,6 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package diagnostic_graph_aggregator -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_diagnostic_graph_aggregator +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.40.0 (2024-12-12) ------------------- diff --git a/system/diagnostic_graph_aggregator/CMakeLists.txt b/system/autoware_diagnostic_graph_aggregator/CMakeLists.txt similarity index 89% rename from system/diagnostic_graph_aggregator/CMakeLists.txt rename to system/autoware_diagnostic_graph_aggregator/CMakeLists.txt index 4f18407e2a108..69882ad10bd81 100644 --- a/system/diagnostic_graph_aggregator/CMakeLists.txt +++ b/system/autoware_diagnostic_graph_aggregator/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(diagnostic_graph_aggregator) +project(autoware_diagnostic_graph_aggregator) find_package(autoware_cmake REQUIRED) autoware_package() @@ -30,8 +30,8 @@ ament_auto_add_library(aggregator SHARED target_include_directories(aggregator PRIVATE src/common) rclcpp_components_register_node(aggregator - PLUGIN "diagnostic_graph_aggregator::AggregatorNode" - EXECUTABLE aggregator_node + PLUGIN "autoware::diagnostic_graph_aggregator::AggregatorNode" + EXECUTABLE ${PROJECT_NAME}_node ) if(BUILD_TESTING) diff --git a/system/diagnostic_graph_aggregator/README.md b/system/autoware_diagnostic_graph_aggregator/README.md similarity index 96% rename from system/diagnostic_graph_aggregator/README.md rename to system/autoware_diagnostic_graph_aggregator/README.md index 76513ca414541..892a2a381f324 100644 --- a/system/diagnostic_graph_aggregator/README.md +++ b/system/autoware_diagnostic_graph_aggregator/README.md @@ -1,4 +1,4 @@ -# diagnostic_graph_aggregator +# autoware_diagnostic_graph_aggregator ## Overview @@ -66,7 +66,7 @@ This is an example of a diagnostic graph configuration. The configuration can be - [module2.yaml](./example/graph/module2.yaml) ```bash -ros2 launch diagnostic_graph_aggregator example-main.launch.xml +ros2 launch autoware_diagnostic_graph_aggregator example-main.launch.xml ``` You can reuse the graph by making partial edits. For example, disable hardware checks for simulation. @@ -74,7 +74,7 @@ You can reuse the graph by making partial edits. For example, disable hardware c - [edit.yaml](./example/graph/edit.yaml) ```bash -ros2 launch diagnostic_graph_aggregator example-edit.launch.xml +ros2 launch autoware_diagnostic_graph_aggregator example-edit.launch.xml ``` ## Debug tools diff --git a/system/diagnostic_graph_aggregator/config/default.param.yaml b/system/autoware_diagnostic_graph_aggregator/config/default.param.yaml similarity index 100% rename from system/diagnostic_graph_aggregator/config/default.param.yaml rename to system/autoware_diagnostic_graph_aggregator/config/default.param.yaml diff --git a/system/diagnostic_graph_aggregator/doc/format/edit.md b/system/autoware_diagnostic_graph_aggregator/doc/format/edit.md similarity index 100% rename from system/diagnostic_graph_aggregator/doc/format/edit.md rename to system/autoware_diagnostic_graph_aggregator/doc/format/edit.md diff --git a/system/diagnostic_graph_aggregator/doc/format/edit/remove.md b/system/autoware_diagnostic_graph_aggregator/doc/format/edit/remove.md similarity index 100% rename from system/diagnostic_graph_aggregator/doc/format/edit/remove.md rename to system/autoware_diagnostic_graph_aggregator/doc/format/edit/remove.md diff --git a/system/diagnostic_graph_aggregator/doc/format/graph.md b/system/autoware_diagnostic_graph_aggregator/doc/format/graph.md similarity index 100% rename from system/diagnostic_graph_aggregator/doc/format/graph.md rename to system/autoware_diagnostic_graph_aggregator/doc/format/graph.md diff --git a/system/diagnostic_graph_aggregator/doc/format/path.md b/system/autoware_diagnostic_graph_aggregator/doc/format/path.md similarity index 100% rename from system/diagnostic_graph_aggregator/doc/format/path.md rename to system/autoware_diagnostic_graph_aggregator/doc/format/path.md diff --git a/system/diagnostic_graph_aggregator/doc/format/unit.md b/system/autoware_diagnostic_graph_aggregator/doc/format/unit.md similarity index 100% rename from system/diagnostic_graph_aggregator/doc/format/unit.md rename to system/autoware_diagnostic_graph_aggregator/doc/format/unit.md diff --git a/system/diagnostic_graph_aggregator/doc/format/unit/and.md b/system/autoware_diagnostic_graph_aggregator/doc/format/unit/and.md similarity index 100% rename from system/diagnostic_graph_aggregator/doc/format/unit/and.md rename to system/autoware_diagnostic_graph_aggregator/doc/format/unit/and.md diff --git a/system/diagnostic_graph_aggregator/doc/format/unit/const.md b/system/autoware_diagnostic_graph_aggregator/doc/format/unit/const.md similarity index 100% rename from system/diagnostic_graph_aggregator/doc/format/unit/const.md rename to system/autoware_diagnostic_graph_aggregator/doc/format/unit/const.md diff --git a/system/diagnostic_graph_aggregator/doc/format/unit/diag.md b/system/autoware_diagnostic_graph_aggregator/doc/format/unit/diag.md similarity index 100% rename from system/diagnostic_graph_aggregator/doc/format/unit/diag.md rename to system/autoware_diagnostic_graph_aggregator/doc/format/unit/diag.md diff --git a/system/diagnostic_graph_aggregator/doc/format/unit/link.md b/system/autoware_diagnostic_graph_aggregator/doc/format/unit/link.md similarity index 100% rename from system/diagnostic_graph_aggregator/doc/format/unit/link.md rename to system/autoware_diagnostic_graph_aggregator/doc/format/unit/link.md diff --git a/system/diagnostic_graph_aggregator/doc/format/unit/or.md b/system/autoware_diagnostic_graph_aggregator/doc/format/unit/or.md similarity index 100% rename from system/diagnostic_graph_aggregator/doc/format/unit/or.md rename to system/autoware_diagnostic_graph_aggregator/doc/format/unit/or.md diff --git a/system/diagnostic_graph_aggregator/doc/format/unit/remap.md b/system/autoware_diagnostic_graph_aggregator/doc/format/unit/remap.md similarity index 100% rename from system/diagnostic_graph_aggregator/doc/format/unit/remap.md rename to system/autoware_diagnostic_graph_aggregator/doc/format/unit/remap.md diff --git a/system/diagnostic_graph_aggregator/doc/overview.drawio.svg b/system/autoware_diagnostic_graph_aggregator/doc/overview.drawio.svg similarity index 100% rename from system/diagnostic_graph_aggregator/doc/overview.drawio.svg rename to system/autoware_diagnostic_graph_aggregator/doc/overview.drawio.svg diff --git a/system/diagnostic_graph_aggregator/doc/tool/tree.md b/system/autoware_diagnostic_graph_aggregator/doc/tool/tree.md similarity index 83% rename from system/diagnostic_graph_aggregator/doc/tool/tree.md rename to system/autoware_diagnostic_graph_aggregator/doc/tool/tree.md index 12b664ecc48d6..2bbedcce4aeb4 100644 --- a/system/diagnostic_graph_aggregator/doc/tool/tree.md +++ b/system/autoware_diagnostic_graph_aggregator/doc/tool/tree.md @@ -5,13 +5,13 @@ This tool displays the graph structure of the configuration file in tree format. ## Usage ```bash -ros2 run diagnostic_graph_aggregator tree +ros2 run autoware_diagnostic_graph_aggregator tree ``` ## Examples ```bash -ros2 run diagnostic_graph_aggregator tree '$(find-pkg-share diagnostic_graph_aggregator)/example/graph/main.yaml' +ros2 run autoware_diagnostic_graph_aggregator tree '$(find-pkg-share autoware_diagnostic_graph_aggregator)/example/graph/main.yaml' ``` ```txt diff --git a/system/diagnostic_graph_aggregator/example/dummy-diags.py b/system/autoware_diagnostic_graph_aggregator/example/dummy-diags.py similarity index 100% rename from system/diagnostic_graph_aggregator/example/dummy-diags.py rename to system/autoware_diagnostic_graph_aggregator/example/dummy-diags.py diff --git a/system/autoware_diagnostic_graph_aggregator/example/example-edit.launch.xml b/system/autoware_diagnostic_graph_aggregator/example/example-edit.launch.xml new file mode 100644 index 0000000000000..1a15bbe929f6e --- /dev/null +++ b/system/autoware_diagnostic_graph_aggregator/example/example-edit.launch.xml @@ -0,0 +1,6 @@ + + + + + + diff --git a/system/autoware_diagnostic_graph_aggregator/example/example-main.launch.xml b/system/autoware_diagnostic_graph_aggregator/example/example-main.launch.xml new file mode 100644 index 0000000000000..712da5128d09b --- /dev/null +++ b/system/autoware_diagnostic_graph_aggregator/example/example-main.launch.xml @@ -0,0 +1,6 @@ + + + + + + diff --git a/system/diagnostic_graph_aggregator/example/graph/edit.yaml b/system/autoware_diagnostic_graph_aggregator/example/graph/edit.yaml similarity index 100% rename from system/diagnostic_graph_aggregator/example/graph/edit.yaml rename to system/autoware_diagnostic_graph_aggregator/example/graph/edit.yaml diff --git a/system/diagnostic_graph_aggregator/example/graph/main.yaml b/system/autoware_diagnostic_graph_aggregator/example/graph/main.yaml similarity index 100% rename from system/diagnostic_graph_aggregator/example/graph/main.yaml rename to system/autoware_diagnostic_graph_aggregator/example/graph/main.yaml diff --git a/system/diagnostic_graph_aggregator/example/graph/module1.yaml b/system/autoware_diagnostic_graph_aggregator/example/graph/module1.yaml similarity index 100% rename from system/diagnostic_graph_aggregator/example/graph/module1.yaml rename to system/autoware_diagnostic_graph_aggregator/example/graph/module1.yaml diff --git a/system/diagnostic_graph_aggregator/example/graph/module2.yaml b/system/autoware_diagnostic_graph_aggregator/example/graph/module2.yaml similarity index 100% rename from system/diagnostic_graph_aggregator/example/graph/module2.yaml rename to system/autoware_diagnostic_graph_aggregator/example/graph/module2.yaml diff --git a/system/autoware_diagnostic_graph_aggregator/launch/aggregator.launch.xml b/system/autoware_diagnostic_graph_aggregator/launch/aggregator.launch.xml new file mode 100644 index 0000000000000..89dac8e5f439b --- /dev/null +++ b/system/autoware_diagnostic_graph_aggregator/launch/aggregator.launch.xml @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/system/diagnostic_graph_aggregator/package.xml b/system/autoware_diagnostic_graph_aggregator/package.xml similarity index 87% rename from system/diagnostic_graph_aggregator/package.xml rename to system/autoware_diagnostic_graph_aggregator/package.xml index ae9266a3bf302..33d7dfdff9637 100644 --- a/system/diagnostic_graph_aggregator/package.xml +++ b/system/autoware_diagnostic_graph_aggregator/package.xml @@ -1,10 +1,11 @@ - diagnostic_graph_aggregator + autoware_diagnostic_graph_aggregator 0.40.0 The diagnostic_graph_aggregator package Takagi, Isamu + Junya Sasaki Apache License 2.0 ament_cmake_auto diff --git a/system/diagnostic_graph_aggregator/script/dump.py b/system/autoware_diagnostic_graph_aggregator/script/dump.py similarity index 100% rename from system/diagnostic_graph_aggregator/script/dump.py rename to system/autoware_diagnostic_graph_aggregator/script/dump.py diff --git a/system/diagnostic_graph_aggregator/src/common/graph/config.cpp b/system/autoware_diagnostic_graph_aggregator/src/common/graph/config.cpp similarity index 98% rename from system/diagnostic_graph_aggregator/src/common/graph/config.cpp rename to system/autoware_diagnostic_graph_aggregator/src/common/graph/config.cpp index e622d089109f4..3b95d06befb8e 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/config.cpp +++ b/system/autoware_diagnostic_graph_aggregator/src/common/graph/config.cpp @@ -29,7 +29,7 @@ #include #include -namespace diagnostic_graph_aggregator +namespace autoware::diagnostic_graph_aggregator { std::string resolve_substitution(const std::string & substitution, const TreeData & data) @@ -309,4 +309,4 @@ FileConfig TreeLoader::construct() return config; } -} // namespace diagnostic_graph_aggregator +} // namespace autoware::diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/common/graph/config.hpp b/system/autoware_diagnostic_graph_aggregator/src/common/graph/config.hpp similarity index 96% rename from system/diagnostic_graph_aggregator/src/common/graph/config.hpp rename to system/autoware_diagnostic_graph_aggregator/src/common/graph/config.hpp index 935b65203afbe..f74f2ef721ee0 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/config.hpp +++ b/system/autoware_diagnostic_graph_aggregator/src/common/graph/config.hpp @@ -23,7 +23,7 @@ #include #include -namespace diagnostic_graph_aggregator +namespace autoware::diagnostic_graph_aggregator { struct PathConfig @@ -98,6 +98,6 @@ class TreeLoader std::vector files_; }; -} // namespace diagnostic_graph_aggregator +} // namespace autoware::diagnostic_graph_aggregator #endif // COMMON__GRAPH__CONFIG_HPP_ diff --git a/system/diagnostic_graph_aggregator/src/common/graph/data.cpp b/system/autoware_diagnostic_graph_aggregator/src/common/graph/data.cpp similarity index 95% rename from system/diagnostic_graph_aggregator/src/common/graph/data.cpp rename to system/autoware_diagnostic_graph_aggregator/src/common/graph/data.cpp index e1d053e6d259c..60fb356d41910 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/data.cpp +++ b/system/autoware_diagnostic_graph_aggregator/src/common/graph/data.cpp @@ -16,7 +16,7 @@ #include -namespace diagnostic_graph_aggregator +namespace autoware::diagnostic_graph_aggregator { TreeData TreeData::Load(const std::string & path) @@ -96,4 +96,4 @@ double TreeData::real(double fail) return yaml_.as(fail); } -} // namespace diagnostic_graph_aggregator +} // namespace autoware::diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/common/graph/data.hpp b/system/autoware_diagnostic_graph_aggregator/src/common/graph/data.hpp similarity index 93% rename from system/diagnostic_graph_aggregator/src/common/graph/data.hpp rename to system/autoware_diagnostic_graph_aggregator/src/common/graph/data.hpp index 437e3793df398..6ddac7897746d 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/data.hpp +++ b/system/autoware_diagnostic_graph_aggregator/src/common/graph/data.hpp @@ -23,7 +23,7 @@ #include #include -namespace diagnostic_graph_aggregator +namespace autoware::diagnostic_graph_aggregator { class TreeData @@ -51,6 +51,6 @@ class TreeData TreePath path_; }; -} // namespace diagnostic_graph_aggregator +} // namespace autoware::diagnostic_graph_aggregator #endif // COMMON__GRAPH__DATA_HPP_ diff --git a/system/diagnostic_graph_aggregator/src/common/graph/error.cpp b/system/autoware_diagnostic_graph_aggregator/src/common/graph/error.cpp similarity index 93% rename from system/diagnostic_graph_aggregator/src/common/graph/error.cpp rename to system/autoware_diagnostic_graph_aggregator/src/common/graph/error.cpp index 7a4336e62d8a3..976fc63aab8ab 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/error.cpp +++ b/system/autoware_diagnostic_graph_aggregator/src/common/graph/error.cpp @@ -16,7 +16,7 @@ #include -namespace diagnostic_graph_aggregator +namespace autoware::diagnostic_graph_aggregator { TreePath::TreePath(const std::string & file) @@ -57,4 +57,4 @@ std::string TreePath::text() const return " (" + file_ + sep + node_ + ")"; } -} // namespace diagnostic_graph_aggregator +} // namespace autoware::diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/common/graph/error.hpp b/system/autoware_diagnostic_graph_aggregator/src/common/graph/error.hpp similarity index 97% rename from system/diagnostic_graph_aggregator/src/common/graph/error.hpp rename to system/autoware_diagnostic_graph_aggregator/src/common/graph/error.hpp index d923e12caf783..cef345a1243ca 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/error.hpp +++ b/system/autoware_diagnostic_graph_aggregator/src/common/graph/error.hpp @@ -18,7 +18,7 @@ #include #include -namespace diagnostic_graph_aggregator +namespace autoware::diagnostic_graph_aggregator { struct TreePath @@ -127,6 +127,6 @@ struct GraphStructure : public Exception using Exception::Exception; }; -} // namespace diagnostic_graph_aggregator +} // namespace autoware::diagnostic_graph_aggregator #endif // COMMON__GRAPH__ERROR_HPP_ diff --git a/system/diagnostic_graph_aggregator/src/common/graph/graph.cpp b/system/autoware_diagnostic_graph_aggregator/src/common/graph/graph.cpp similarity index 95% rename from system/diagnostic_graph_aggregator/src/common/graph/graph.cpp rename to system/autoware_diagnostic_graph_aggregator/src/common/graph/graph.cpp index 7977209b4905c..ff6c5a8db21ed 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/graph.cpp +++ b/system/autoware_diagnostic_graph_aggregator/src/common/graph/graph.cpp @@ -22,7 +22,7 @@ #include #include -namespace diagnostic_graph_aggregator +namespace autoware::diagnostic_graph_aggregator { void Graph::create(const std::string & file, const std::string & id) @@ -77,4 +77,4 @@ DiagGraphStatus Graph::create_status(const rclcpp::Time & stamp) const Graph::Graph() = default; Graph::~Graph() = default; -} // namespace diagnostic_graph_aggregator +} // namespace autoware::diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/common/graph/graph.hpp b/system/autoware_diagnostic_graph_aggregator/src/common/graph/graph.hpp similarity index 94% rename from system/diagnostic_graph_aggregator/src/common/graph/graph.hpp rename to system/autoware_diagnostic_graph_aggregator/src/common/graph/graph.hpp index 14a27dae9a539..13362613d9952 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/graph.hpp +++ b/system/autoware_diagnostic_graph_aggregator/src/common/graph/graph.hpp @@ -24,7 +24,7 @@ #include #include -namespace diagnostic_graph_aggregator +namespace autoware::diagnostic_graph_aggregator { class Graph @@ -51,6 +51,6 @@ class Graph std::string id_; }; -} // namespace diagnostic_graph_aggregator +} // namespace autoware::diagnostic_graph_aggregator #endif // COMMON__GRAPH__GRAPH_HPP_ diff --git a/system/diagnostic_graph_aggregator/src/common/graph/loader.cpp b/system/autoware_diagnostic_graph_aggregator/src/common/graph/loader.cpp similarity index 98% rename from system/diagnostic_graph_aggregator/src/common/graph/loader.cpp rename to system/autoware_diagnostic_graph_aggregator/src/common/graph/loader.cpp index 5edef61340fe8..8a21a4f47951e 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/loader.cpp +++ b/system/autoware_diagnostic_graph_aggregator/src/common/graph/loader.cpp @@ -26,7 +26,7 @@ #include #include -namespace diagnostic_graph_aggregator +namespace autoware::diagnostic_graph_aggregator { struct UnitLoader::GraphLinks @@ -190,4 +190,4 @@ std::unique_ptr GraphLoader::create_node(const UnitLoader & unit) throw UnknownUnitType(unit.data().path(), unit.type()); } -} // namespace diagnostic_graph_aggregator +} // namespace autoware::diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/common/graph/loader.hpp b/system/autoware_diagnostic_graph_aggregator/src/common/graph/loader.hpp similarity index 94% rename from system/diagnostic_graph_aggregator/src/common/graph/loader.hpp rename to system/autoware_diagnostic_graph_aggregator/src/common/graph/loader.hpp index 226b3ab279b22..c9f6923c5bcfd 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/loader.hpp +++ b/system/autoware_diagnostic_graph_aggregator/src/common/graph/loader.hpp @@ -22,7 +22,7 @@ #include #include -namespace diagnostic_graph_aggregator +namespace autoware::diagnostic_graph_aggregator { class UnitLoader @@ -62,6 +62,6 @@ class GraphLoader std::vector> links_; }; -} // namespace diagnostic_graph_aggregator +} // namespace autoware::diagnostic_graph_aggregator #endif // COMMON__GRAPH__LOADER_HPP_ diff --git a/system/diagnostic_graph_aggregator/src/common/graph/names.hpp b/system/autoware_diagnostic_graph_aggregator/src/common/graph/names.hpp similarity index 83% rename from system/diagnostic_graph_aggregator/src/common/graph/names.hpp rename to system/autoware_diagnostic_graph_aggregator/src/common/graph/names.hpp index aa5a9c46e7b37..36645b320f496 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/names.hpp +++ b/system/autoware_diagnostic_graph_aggregator/src/common/graph/names.hpp @@ -15,7 +15,7 @@ #ifndef COMMON__GRAPH__NAMES_HPP_ #define COMMON__GRAPH__NAMES_HPP_ -namespace diagnostic_graph_aggregator::unit_name +namespace autoware::diagnostic_graph_aggregator::unit_name { constexpr char const * link = "link"; @@ -30,13 +30,13 @@ constexpr char const * warn = "warn"; constexpr char const * error = "error"; constexpr char const * stale = "stale"; -} // namespace diagnostic_graph_aggregator::unit_name +} // namespace autoware::diagnostic_graph_aggregator::unit_name -namespace diagnostic_graph_aggregator::edit_name +namespace autoware::diagnostic_graph_aggregator::edit_name { constexpr char const * remove = "remove"; -} // namespace diagnostic_graph_aggregator::edit_name +} // namespace autoware::diagnostic_graph_aggregator::edit_name #endif // COMMON__GRAPH__NAMES_HPP_ diff --git a/system/diagnostic_graph_aggregator/src/common/graph/types.hpp b/system/autoware_diagnostic_graph_aggregator/src/common/graph/types.hpp similarity index 95% rename from system/diagnostic_graph_aggregator/src/common/graph/types.hpp rename to system/autoware_diagnostic_graph_aggregator/src/common/graph/types.hpp index 6eae26a1f98c7..f7844b3d1b327 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/types.hpp +++ b/system/autoware_diagnostic_graph_aggregator/src/common/graph/types.hpp @@ -31,7 +31,7 @@ #include -namespace diagnostic_graph_aggregator +namespace autoware::diagnostic_graph_aggregator { using diagnostic_msgs::msg::DiagnosticArray; @@ -59,6 +59,6 @@ class DiagUnit; class Graph; class UnitLoader; -} // namespace diagnostic_graph_aggregator +} // namespace autoware::diagnostic_graph_aggregator #endif // COMMON__GRAPH__TYPES_HPP_ diff --git a/system/diagnostic_graph_aggregator/src/common/graph/units.cpp b/system/autoware_diagnostic_graph_aggregator/src/common/graph/units.cpp similarity index 98% rename from system/diagnostic_graph_aggregator/src/common/graph/units.cpp rename to system/autoware_diagnostic_graph_aggregator/src/common/graph/units.cpp index 5ebd603964add..3d7919027aae5 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/units.cpp +++ b/system/autoware_diagnostic_graph_aggregator/src/common/graph/units.cpp @@ -20,7 +20,7 @@ #include -namespace diagnostic_graph_aggregator +namespace autoware::diagnostic_graph_aggregator { void UnitLink::initialize_object(BaseUnit * parent, BaseUnit * child) @@ -226,4 +226,4 @@ StaleUnit::StaleUnit(const UnitLoader & unit) : ConstUnit(unit) status_.level = DiagnosticStatus::STALE; } -} // namespace diagnostic_graph_aggregator +} // namespace autoware::diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/common/graph/units.hpp b/system/autoware_diagnostic_graph_aggregator/src/common/graph/units.hpp similarity index 98% rename from system/diagnostic_graph_aggregator/src/common/graph/units.hpp rename to system/autoware_diagnostic_graph_aggregator/src/common/graph/units.hpp index 323053db08385..248f4694c17ae 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/units.hpp +++ b/system/autoware_diagnostic_graph_aggregator/src/common/graph/units.hpp @@ -24,7 +24,7 @@ #include #include -namespace diagnostic_graph_aggregator +namespace autoware::diagnostic_graph_aggregator { class UnitLink @@ -225,6 +225,6 @@ class StaleUnit : public ConstUnit std::string type() const override { return unit_name::stale; } }; -} // namespace diagnostic_graph_aggregator +} // namespace autoware::diagnostic_graph_aggregator #endif // COMMON__GRAPH__UNITS_HPP_ diff --git a/system/diagnostic_graph_aggregator/src/node/aggregator.cpp b/system/autoware_diagnostic_graph_aggregator/src/node/aggregator.cpp similarity index 94% rename from system/diagnostic_graph_aggregator/src/node/aggregator.cpp rename to system/autoware_diagnostic_graph_aggregator/src/node/aggregator.cpp index 4d2ec73bfceca..ac0fa587895e5 100644 --- a/system/diagnostic_graph_aggregator/src/node/aggregator.cpp +++ b/system/autoware_diagnostic_graph_aggregator/src/node/aggregator.cpp @@ -18,7 +18,7 @@ #include #include -namespace diagnostic_graph_aggregator +namespace autoware::diagnostic_graph_aggregator { AggregatorNode::AggregatorNode(const rclcpp::NodeOptions & options) : Node("aggregator", options) @@ -97,7 +97,7 @@ void AggregatorNode::on_diag(const DiagnosticArray & msg) // pub_status_->publish(); } -} // namespace diagnostic_graph_aggregator +} // namespace autoware::diagnostic_graph_aggregator #include -RCLCPP_COMPONENTS_REGISTER_NODE(diagnostic_graph_aggregator::AggregatorNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::diagnostic_graph_aggregator::AggregatorNode) diff --git a/system/diagnostic_graph_aggregator/src/node/aggregator.hpp b/system/autoware_diagnostic_graph_aggregator/src/node/aggregator.hpp similarity index 93% rename from system/diagnostic_graph_aggregator/src/node/aggregator.hpp rename to system/autoware_diagnostic_graph_aggregator/src/node/aggregator.hpp index f71780f19a5c7..53e2ba3562aaa 100644 --- a/system/diagnostic_graph_aggregator/src/node/aggregator.hpp +++ b/system/autoware_diagnostic_graph_aggregator/src/node/aggregator.hpp @@ -24,7 +24,7 @@ #include #include -namespace diagnostic_graph_aggregator +namespace autoware::diagnostic_graph_aggregator { class AggregatorNode : public rclcpp::Node @@ -48,6 +48,6 @@ class AggregatorNode : public rclcpp::Node std::unordered_map unknown_diags_; }; -} // namespace diagnostic_graph_aggregator +} // namespace autoware::diagnostic_graph_aggregator #endif // NODE__AGGREGATOR_HPP_ diff --git a/system/diagnostic_graph_aggregator/src/node/availability.cpp b/system/autoware_diagnostic_graph_aggregator/src/node/availability.cpp similarity index 96% rename from system/diagnostic_graph_aggregator/src/node/availability.cpp rename to system/autoware_diagnostic_graph_aggregator/src/node/availability.cpp index 60ad418799716..df232143aa005 100644 --- a/system/diagnostic_graph_aggregator/src/node/availability.cpp +++ b/system/autoware_diagnostic_graph_aggregator/src/node/availability.cpp @@ -22,7 +22,7 @@ #include #include -namespace diagnostic_graph_aggregator +namespace autoware::diagnostic_graph_aggregator { ModesAvailability::ModesAvailability(rclcpp::Node & node, const Graph & graph) @@ -73,4 +73,4 @@ void ModesAvailability::update(const rclcpp::Time & stamp) const pub_->publish(message); } -} // namespace diagnostic_graph_aggregator +} // namespace autoware::diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/node/availability.hpp b/system/autoware_diagnostic_graph_aggregator/src/node/availability.hpp similarity index 93% rename from system/diagnostic_graph_aggregator/src/node/availability.hpp rename to system/autoware_diagnostic_graph_aggregator/src/node/availability.hpp index c91db089266f5..f93b19fd55046 100644 --- a/system/diagnostic_graph_aggregator/src/node/availability.hpp +++ b/system/autoware_diagnostic_graph_aggregator/src/node/availability.hpp @@ -21,7 +21,7 @@ #include -namespace diagnostic_graph_aggregator +namespace autoware::diagnostic_graph_aggregator { class ModesAvailability @@ -44,6 +44,6 @@ class ModesAvailability BaseUnit * pull_over_mrm_; }; -} // namespace diagnostic_graph_aggregator +} // namespace autoware::diagnostic_graph_aggregator #endif // NODE__AVAILABILITY_HPP_ diff --git a/system/diagnostic_graph_aggregator/src/tool/plantuml.cpp b/system/autoware_diagnostic_graph_aggregator/src/tool/plantuml.cpp similarity index 88% rename from system/diagnostic_graph_aggregator/src/tool/plantuml.cpp rename to system/autoware_diagnostic_graph_aggregator/src/tool/plantuml.cpp index 68c0082908430..a87df3c47a19f 100644 --- a/system/diagnostic_graph_aggregator/src/tool/plantuml.cpp +++ b/system/autoware_diagnostic_graph_aggregator/src/tool/plantuml.cpp @@ -18,7 +18,7 @@ #include #include -namespace diagnostic_graph_aggregator +namespace autoware::diagnostic_graph_aggregator { void dump_root(const std::string & path) @@ -40,7 +40,7 @@ void dump_root(const std::string & path) } } -} // namespace diagnostic_graph_aggregator +} // namespace autoware::diagnostic_graph_aggregator int main(int argc, char ** argv) { @@ -48,5 +48,5 @@ int main(int argc, char ** argv) std::cerr << "usage: plantuml " << std::endl; return 1; } - diagnostic_graph_aggregator::dump_root(argv[1]); + autoware::diagnostic_graph_aggregator::dump_root(argv[1]); } diff --git a/system/diagnostic_graph_aggregator/src/tool/tree.cpp b/system/autoware_diagnostic_graph_aggregator/src/tool/tree.cpp similarity index 92% rename from system/diagnostic_graph_aggregator/src/tool/tree.cpp rename to system/autoware_diagnostic_graph_aggregator/src/tool/tree.cpp index f367ec2113808..f37f0c3e575a7 100644 --- a/system/diagnostic_graph_aggregator/src/tool/tree.cpp +++ b/system/autoware_diagnostic_graph_aggregator/src/tool/tree.cpp @@ -18,7 +18,7 @@ #include #include -namespace diagnostic_graph_aggregator +namespace autoware::diagnostic_graph_aggregator { void dump_unit(const BaseUnit * unit, const std::string & indent = "", bool root = true) @@ -60,7 +60,7 @@ void dump_root(const std::string & path) } } -} // namespace diagnostic_graph_aggregator +} // namespace autoware::diagnostic_graph_aggregator int main(int argc, char ** argv) { @@ -68,5 +68,5 @@ int main(int argc, char ** argv) std::cerr << "usage: tree " << std::endl; return 1; } - diagnostic_graph_aggregator::dump_root(argv[1]); + autoware::diagnostic_graph_aggregator::dump_root(argv[1]); } diff --git a/system/diagnostic_graph_aggregator/test/files/test1/field-not-found.yaml b/system/autoware_diagnostic_graph_aggregator/test/files/test1/field-not-found.yaml similarity index 100% rename from system/diagnostic_graph_aggregator/test/files/test1/field-not-found.yaml rename to system/autoware_diagnostic_graph_aggregator/test/files/test1/field-not-found.yaml diff --git a/system/diagnostic_graph_aggregator/test/files/test1/file-not-found.yaml b/system/autoware_diagnostic_graph_aggregator/test/files/test1/file-not-found.yaml similarity index 100% rename from system/diagnostic_graph_aggregator/test/files/test1/file-not-found.yaml rename to system/autoware_diagnostic_graph_aggregator/test/files/test1/file-not-found.yaml diff --git a/system/diagnostic_graph_aggregator/test/files/test1/graph-circulation.yaml b/system/autoware_diagnostic_graph_aggregator/test/files/test1/graph-circulation.yaml similarity index 100% rename from system/diagnostic_graph_aggregator/test/files/test1/graph-circulation.yaml rename to system/autoware_diagnostic_graph_aggregator/test/files/test1/graph-circulation.yaml diff --git a/system/diagnostic_graph_aggregator/test/files/test1/invalid-dict-type.yaml b/system/autoware_diagnostic_graph_aggregator/test/files/test1/invalid-dict-type.yaml similarity index 100% rename from system/diagnostic_graph_aggregator/test/files/test1/invalid-dict-type.yaml rename to system/autoware_diagnostic_graph_aggregator/test/files/test1/invalid-dict-type.yaml diff --git a/system/diagnostic_graph_aggregator/test/files/test1/invalid-list-type.yaml b/system/autoware_diagnostic_graph_aggregator/test/files/test1/invalid-list-type.yaml similarity index 100% rename from system/diagnostic_graph_aggregator/test/files/test1/invalid-list-type.yaml rename to system/autoware_diagnostic_graph_aggregator/test/files/test1/invalid-list-type.yaml diff --git a/system/diagnostic_graph_aggregator/test/files/test1/path-conflict.yaml b/system/autoware_diagnostic_graph_aggregator/test/files/test1/path-conflict.yaml similarity index 100% rename from system/diagnostic_graph_aggregator/test/files/test1/path-conflict.yaml rename to system/autoware_diagnostic_graph_aggregator/test/files/test1/path-conflict.yaml diff --git a/system/diagnostic_graph_aggregator/test/files/test1/path-not-found.yaml b/system/autoware_diagnostic_graph_aggregator/test/files/test1/path-not-found.yaml similarity index 100% rename from system/diagnostic_graph_aggregator/test/files/test1/path-not-found.yaml rename to system/autoware_diagnostic_graph_aggregator/test/files/test1/path-not-found.yaml diff --git a/system/diagnostic_graph_aggregator/test/files/test1/unknown-substitution.yaml b/system/autoware_diagnostic_graph_aggregator/test/files/test1/unknown-substitution.yaml similarity index 100% rename from system/diagnostic_graph_aggregator/test/files/test1/unknown-substitution.yaml rename to system/autoware_diagnostic_graph_aggregator/test/files/test1/unknown-substitution.yaml diff --git a/system/diagnostic_graph_aggregator/test/files/test1/unknown-unit-type.yaml b/system/autoware_diagnostic_graph_aggregator/test/files/test1/unknown-unit-type.yaml similarity index 100% rename from system/diagnostic_graph_aggregator/test/files/test1/unknown-unit-type.yaml rename to system/autoware_diagnostic_graph_aggregator/test/files/test1/unknown-unit-type.yaml diff --git a/system/diagnostic_graph_aggregator/test/files/test2/and.yaml b/system/autoware_diagnostic_graph_aggregator/test/files/test2/and.yaml similarity index 100% rename from system/diagnostic_graph_aggregator/test/files/test2/and.yaml rename to system/autoware_diagnostic_graph_aggregator/test/files/test2/and.yaml diff --git a/system/diagnostic_graph_aggregator/test/files/test2/or.yaml b/system/autoware_diagnostic_graph_aggregator/test/files/test2/or.yaml similarity index 100% rename from system/diagnostic_graph_aggregator/test/files/test2/or.yaml rename to system/autoware_diagnostic_graph_aggregator/test/files/test2/or.yaml diff --git a/system/diagnostic_graph_aggregator/test/files/test2/warn-to-error.yaml b/system/autoware_diagnostic_graph_aggregator/test/files/test2/warn-to-error.yaml similarity index 100% rename from system/diagnostic_graph_aggregator/test/files/test2/warn-to-error.yaml rename to system/autoware_diagnostic_graph_aggregator/test/files/test2/warn-to-error.yaml diff --git a/system/diagnostic_graph_aggregator/test/files/test2/warn-to-ok.yaml b/system/autoware_diagnostic_graph_aggregator/test/files/test2/warn-to-ok.yaml similarity index 100% rename from system/diagnostic_graph_aggregator/test/files/test2/warn-to-ok.yaml rename to system/autoware_diagnostic_graph_aggregator/test/files/test2/warn-to-ok.yaml diff --git a/system/diagnostic_graph_aggregator/test/src/test1.cpp b/system/autoware_diagnostic_graph_aggregator/test/src/test1.cpp similarity index 96% rename from system/diagnostic_graph_aggregator/test/src/test1.cpp rename to system/autoware_diagnostic_graph_aggregator/test/src/test1.cpp index ea157852675ec..30182314df48f 100644 --- a/system/diagnostic_graph_aggregator/test/src/test1.cpp +++ b/system/autoware_diagnostic_graph_aggregator/test/src/test1.cpp @@ -18,7 +18,7 @@ #include -using namespace diagnostic_graph_aggregator; // NOLINT(build/namespaces) +using namespace autoware::diagnostic_graph_aggregator; // NOLINT(build/namespaces) TEST(ConfigFile, RootNotFound) { diff --git a/system/diagnostic_graph_aggregator/test/src/test2.cpp b/system/autoware_diagnostic_graph_aggregator/test/src/test2.cpp similarity index 98% rename from system/diagnostic_graph_aggregator/test/src/test2.cpp rename to system/autoware_diagnostic_graph_aggregator/test/src/test2.cpp index 169e3017f8cd4..d0f9a8c2e2557 100644 --- a/system/diagnostic_graph_aggregator/test/src/test2.cpp +++ b/system/autoware_diagnostic_graph_aggregator/test/src/test2.cpp @@ -25,7 +25,7 @@ #include #include -using namespace diagnostic_graph_aggregator; // NOLINT(build/namespaces) +using namespace autoware::diagnostic_graph_aggregator; // NOLINT(build/namespaces) using diagnostic_msgs::msg::DiagnosticArray; using diagnostic_msgs::msg::DiagnosticStatus; diff --git a/system/diagnostic_graph_aggregator/test/src/utils.cpp b/system/autoware_diagnostic_graph_aggregator/test/src/utils.cpp similarity index 100% rename from system/diagnostic_graph_aggregator/test/src/utils.cpp rename to system/autoware_diagnostic_graph_aggregator/test/src/utils.cpp diff --git a/system/diagnostic_graph_aggregator/test/src/utils.hpp b/system/autoware_diagnostic_graph_aggregator/test/src/utils.hpp similarity index 100% rename from system/diagnostic_graph_aggregator/test/src/utils.hpp rename to system/autoware_diagnostic_graph_aggregator/test/src/utils.hpp diff --git a/system/system_diagnostic_monitor/CHANGELOG.rst b/system/autoware_system_diagnostic_monitor/CHANGELOG.rst similarity index 95% rename from system/system_diagnostic_monitor/CHANGELOG.rst rename to system/autoware_system_diagnostic_monitor/CHANGELOG.rst index 9a5721b05d7ee..3c03aaf85535e 100644 --- a/system/system_diagnostic_monitor/CHANGELOG.rst +++ b/system/autoware_system_diagnostic_monitor/CHANGELOG.rst @@ -1,6 +1,6 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package system_diagnostic_monitor -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_system_diagnostic_monitor +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.40.0 (2024-12-12) ------------------- diff --git a/system/system_diagnostic_monitor/CMakeLists.txt b/system/autoware_system_diagnostic_monitor/CMakeLists.txt similarity index 86% rename from system/system_diagnostic_monitor/CMakeLists.txt rename to system/autoware_system_diagnostic_monitor/CMakeLists.txt index b253b5dbc0529..562079abf84fb 100644 --- a/system/system_diagnostic_monitor/CMakeLists.txt +++ b/system/autoware_system_diagnostic_monitor/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(system_diagnostic_monitor) +project(autoware_system_diagnostic_monitor) find_package(autoware_cmake REQUIRED) autoware_package() diff --git a/system/system_diagnostic_monitor/README.md b/system/autoware_system_diagnostic_monitor/README.md similarity index 100% rename from system/system_diagnostic_monitor/README.md rename to system/autoware_system_diagnostic_monitor/README.md diff --git a/system/system_diagnostic_monitor/config/autoware-main.yaml b/system/autoware_system_diagnostic_monitor/config/autoware-main.yaml similarity index 78% rename from system/system_diagnostic_monitor/config/autoware-main.yaml rename to system/autoware_system_diagnostic_monitor/config/autoware-main.yaml index 26f3fee2863d0..30b6ce9bad9f4 100644 --- a/system/system_diagnostic_monitor/config/autoware-main.yaml +++ b/system/autoware_system_diagnostic_monitor/config/autoware-main.yaml @@ -1,11 +1,11 @@ files: - - { path: $(find-pkg-share system_diagnostic_monitor)/config/map.yaml } - - { path: $(find-pkg-share system_diagnostic_monitor)/config/localization.yaml } - - { path: $(find-pkg-share system_diagnostic_monitor)/config/planning.yaml } - - { path: $(find-pkg-share system_diagnostic_monitor)/config/perception.yaml } - - { path: $(find-pkg-share system_diagnostic_monitor)/config/control.yaml } - - { path: $(find-pkg-share system_diagnostic_monitor)/config/vehicle.yaml } - - { path: $(find-pkg-share system_diagnostic_monitor)/config/system.yaml } + - { path: $(dirname)/map.yaml } + - { path: $(dirname)/localization.yaml } + - { path: $(dirname)/planning.yaml } + - { path: $(dirname)/perception.yaml } + - { path: $(dirname)/control.yaml } + - { path: $(dirname)/vehicle.yaml } + - { path: $(dirname)/system.yaml } units: - path: /autoware/modes/stop diff --git a/system/system_diagnostic_monitor/config/autoware-psim.yaml b/system/autoware_system_diagnostic_monitor/config/autoware-psim.yaml similarity index 100% rename from system/system_diagnostic_monitor/config/autoware-psim.yaml rename to system/autoware_system_diagnostic_monitor/config/autoware-psim.yaml diff --git a/system/system_diagnostic_monitor/config/control.yaml b/system/autoware_system_diagnostic_monitor/config/control.yaml similarity index 100% rename from system/system_diagnostic_monitor/config/control.yaml rename to system/autoware_system_diagnostic_monitor/config/control.yaml diff --git a/system/system_diagnostic_monitor/config/hardware.yaml b/system/autoware_system_diagnostic_monitor/config/hardware.yaml similarity index 100% rename from system/system_diagnostic_monitor/config/hardware.yaml rename to system/autoware_system_diagnostic_monitor/config/hardware.yaml diff --git a/system/system_diagnostic_monitor/config/localization.yaml b/system/autoware_system_diagnostic_monitor/config/localization.yaml similarity index 100% rename from system/system_diagnostic_monitor/config/localization.yaml rename to system/autoware_system_diagnostic_monitor/config/localization.yaml diff --git a/system/system_diagnostic_monitor/config/map.yaml b/system/autoware_system_diagnostic_monitor/config/map.yaml similarity index 100% rename from system/system_diagnostic_monitor/config/map.yaml rename to system/autoware_system_diagnostic_monitor/config/map.yaml diff --git a/system/system_diagnostic_monitor/config/perception.yaml b/system/autoware_system_diagnostic_monitor/config/perception.yaml similarity index 100% rename from system/system_diagnostic_monitor/config/perception.yaml rename to system/autoware_system_diagnostic_monitor/config/perception.yaml diff --git a/system/system_diagnostic_monitor/config/planning.yaml b/system/autoware_system_diagnostic_monitor/config/planning.yaml similarity index 100% rename from system/system_diagnostic_monitor/config/planning.yaml rename to system/autoware_system_diagnostic_monitor/config/planning.yaml diff --git a/system/system_diagnostic_monitor/config/system.yaml b/system/autoware_system_diagnostic_monitor/config/system.yaml similarity index 100% rename from system/system_diagnostic_monitor/config/system.yaml rename to system/autoware_system_diagnostic_monitor/config/system.yaml diff --git a/system/system_diagnostic_monitor/config/vehicle.yaml b/system/autoware_system_diagnostic_monitor/config/vehicle.yaml similarity index 100% rename from system/system_diagnostic_monitor/config/vehicle.yaml rename to system/autoware_system_diagnostic_monitor/config/vehicle.yaml diff --git a/system/autoware_system_diagnostic_monitor/launch/system_diagnostic_monitor.launch.xml b/system/autoware_system_diagnostic_monitor/launch/system_diagnostic_monitor.launch.xml new file mode 100644 index 0000000000000..9a9fcb494d4e2 --- /dev/null +++ b/system/autoware_system_diagnostic_monitor/launch/system_diagnostic_monitor.launch.xml @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/system/system_diagnostic_monitor/package.xml b/system/autoware_system_diagnostic_monitor/package.xml similarity index 74% rename from system/system_diagnostic_monitor/package.xml rename to system/autoware_system_diagnostic_monitor/package.xml index 095d7cf040517..48c93e0b18ab2 100644 --- a/system/system_diagnostic_monitor/package.xml +++ b/system/autoware_system_diagnostic_monitor/package.xml @@ -1,17 +1,18 @@ - system_diagnostic_monitor + autoware_system_diagnostic_monitor 0.40.0 - The system_diagnostic_monitor package + The autoware_system_diagnostic_monitor package Takagi, Isamu + Junya Sasaki Apache License 2.0 ament_cmake_auto autoware_cmake autoware_adapi_v1_msgs - diagnostic_graph_aggregator + autoware_diagnostic_graph_aggregator diagnostic_msgs rclpy tier4_system_msgs diff --git a/system/system_diagnostic_monitor/script/component_state_diagnostics.py b/system/autoware_system_diagnostic_monitor/script/component_state_diagnostics.py similarity index 100% rename from system/system_diagnostic_monitor/script/component_state_diagnostics.py rename to system/autoware_system_diagnostic_monitor/script/component_state_diagnostics.py diff --git a/system/topic_state_monitor/CHANGELOG.rst b/system/autoware_topic_state_monitor/CHANGELOG.rst similarity index 98% rename from system/topic_state_monitor/CHANGELOG.rst rename to system/autoware_topic_state_monitor/CHANGELOG.rst index 1eebcd1bcb1b1..b1faa2cd63683 100644 --- a/system/topic_state_monitor/CHANGELOG.rst +++ b/system/autoware_topic_state_monitor/CHANGELOG.rst @@ -1,6 +1,6 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package topic_state_monitor -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_topic_state_monitor +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.40.0 (2024-12-12) ------------------- diff --git a/system/topic_state_monitor/CMakeLists.txt b/system/autoware_topic_state_monitor/CMakeLists.txt similarity index 50% rename from system/topic_state_monitor/CMakeLists.txt rename to system/autoware_topic_state_monitor/CMakeLists.txt index a4a040c449cdb..822560a12e3d5 100644 --- a/system/topic_state_monitor/CMakeLists.txt +++ b/system/autoware_topic_state_monitor/CMakeLists.txt @@ -1,17 +1,17 @@ cmake_minimum_required(VERSION 3.14) -project(topic_state_monitor) +project(autoware_topic_state_monitor) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_library(topic_state_monitor SHARED +ament_auto_add_library(${PROJECT_NAME} SHARED src/topic_state_monitor/topic_state_monitor.cpp src/topic_state_monitor_core.cpp ) -rclcpp_components_register_node(topic_state_monitor - PLUGIN "topic_state_monitor::TopicStateMonitorNode" - EXECUTABLE topic_state_monitor_node +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "autoware::topic_state_monitor::TopicStateMonitorNode" + EXECUTABLE ${PROJECT_NAME}_node ) ament_auto_package(INSTALL_TO_SHARE diff --git a/system/topic_state_monitor/README.md b/system/autoware_topic_state_monitor/README.md similarity index 99% rename from system/topic_state_monitor/README.md rename to system/autoware_topic_state_monitor/README.md index 28333305ef5a9..bebf096db08ac 100644 --- a/system/topic_state_monitor/README.md +++ b/system/autoware_topic_state_monitor/README.md @@ -1,4 +1,4 @@ -# topic_state_monitor +# autoware_topic_state_monitor ## Purpose diff --git a/system/topic_state_monitor/include/topic_state_monitor/topic_state_monitor.hpp b/system/autoware_topic_state_monitor/include/autoware/topic_state_monitor/topic_state_monitor.hpp similarity index 84% rename from system/topic_state_monitor/include/topic_state_monitor/topic_state_monitor.hpp rename to system/autoware_topic_state_monitor/include/autoware/topic_state_monitor/topic_state_monitor.hpp index 2057ca4c5c86c..e9a651fef3879 100644 --- a/system/topic_state_monitor/include/topic_state_monitor/topic_state_monitor.hpp +++ b/system/autoware_topic_state_monitor/include/autoware/topic_state_monitor/topic_state_monitor.hpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef TOPIC_STATE_MONITOR__TOPIC_STATE_MONITOR_HPP_ -#define TOPIC_STATE_MONITOR__TOPIC_STATE_MONITOR_HPP_ +#ifndef AUTOWARE__TOPIC_STATE_MONITOR__TOPIC_STATE_MONITOR_HPP_ +#define AUTOWARE__TOPIC_STATE_MONITOR__TOPIC_STATE_MONITOR_HPP_ #include #include #include -namespace topic_state_monitor +namespace autoware::topic_state_monitor { struct Param { @@ -68,6 +68,6 @@ class TopicStateMonitor bool isErrorRate() const; bool isTimeout() const; }; -} // namespace topic_state_monitor +} // namespace autoware::topic_state_monitor -#endif // TOPIC_STATE_MONITOR__TOPIC_STATE_MONITOR_HPP_ +#endif // AUTOWARE__TOPIC_STATE_MONITOR__TOPIC_STATE_MONITOR_HPP_ diff --git a/system/topic_state_monitor/include/topic_state_monitor/topic_state_monitor_core.hpp b/system/autoware_topic_state_monitor/include/autoware/topic_state_monitor/topic_state_monitor_core.hpp similarity index 83% rename from system/topic_state_monitor/include/topic_state_monitor/topic_state_monitor_core.hpp rename to system/autoware_topic_state_monitor/include/autoware/topic_state_monitor/topic_state_monitor_core.hpp index 4696823ffbd4b..5d72d437f7b12 100644 --- a/system/topic_state_monitor/include/topic_state_monitor/topic_state_monitor_core.hpp +++ b/system/autoware_topic_state_monitor/include/autoware/topic_state_monitor/topic_state_monitor_core.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef TOPIC_STATE_MONITOR__TOPIC_STATE_MONITOR_CORE_HPP_ -#define TOPIC_STATE_MONITOR__TOPIC_STATE_MONITOR_CORE_HPP_ +#ifndef AUTOWARE__TOPIC_STATE_MONITOR__TOPIC_STATE_MONITOR_CORE_HPP_ +#define AUTOWARE__TOPIC_STATE_MONITOR__TOPIC_STATE_MONITOR_CORE_HPP_ -#include "topic_state_monitor/topic_state_monitor.hpp" +#include "autoware/topic_state_monitor/topic_state_monitor.hpp" #include #include @@ -28,7 +28,7 @@ #include #include -namespace topic_state_monitor +namespace autoware::topic_state_monitor { struct NodeParam { @@ -74,6 +74,6 @@ class TopicStateMonitorNode : public rclcpp::Node void checkTopicStatus(diagnostic_updater::DiagnosticStatusWrapper & stat); }; -} // namespace topic_state_monitor +} // namespace autoware::topic_state_monitor -#endif // TOPIC_STATE_MONITOR__TOPIC_STATE_MONITOR_CORE_HPP_ +#endif // AUTOWARE__TOPIC_STATE_MONITOR__TOPIC_STATE_MONITOR_CORE_HPP_ diff --git a/system/topic_state_monitor/launch/topic_state_monitor.launch.xml b/system/autoware_topic_state_monitor/launch/topic_state_monitor.launch.xml similarity index 88% rename from system/topic_state_monitor/launch/topic_state_monitor.launch.xml rename to system/autoware_topic_state_monitor/launch/topic_state_monitor.launch.xml index 7304dc8c5a273..7df4b2b035944 100644 --- a/system/topic_state_monitor/launch/topic_state_monitor.launch.xml +++ b/system/autoware_topic_state_monitor/launch/topic_state_monitor.launch.xml @@ -10,7 +10,7 @@ - + diff --git a/system/topic_state_monitor/launch/topic_state_monitor_tf.launch.xml b/system/autoware_topic_state_monitor/launch/topic_state_monitor_tf.launch.xml similarity index 89% rename from system/topic_state_monitor/launch/topic_state_monitor_tf.launch.xml rename to system/autoware_topic_state_monitor/launch/topic_state_monitor_tf.launch.xml index 1a255a8a5859a..8a981d30969e4 100644 --- a/system/topic_state_monitor/launch/topic_state_monitor_tf.launch.xml +++ b/system/autoware_topic_state_monitor/launch/topic_state_monitor_tf.launch.xml @@ -11,7 +11,7 @@ - + diff --git a/system/topic_state_monitor/package.xml b/system/autoware_topic_state_monitor/package.xml similarity index 80% rename from system/topic_state_monitor/package.xml rename to system/autoware_topic_state_monitor/package.xml index 0468db6124666..d3a51620f336e 100644 --- a/system/topic_state_monitor/package.xml +++ b/system/autoware_topic_state_monitor/package.xml @@ -1,10 +1,11 @@ - topic_state_monitor + autoware_topic_state_monitor 0.40.0 - The topic_state_monitor package + The autoware_topic_state_monitor package Ryohsuke Mitsudome + Junya Sasaki Apache License 2.0 ament_cmake_auto diff --git a/system/topic_state_monitor/src/topic_state_monitor/topic_state_monitor.cpp b/system/autoware_topic_state_monitor/src/topic_state_monitor/topic_state_monitor.cpp similarity index 94% rename from system/topic_state_monitor/src/topic_state_monitor/topic_state_monitor.cpp rename to system/autoware_topic_state_monitor/src/topic_state_monitor/topic_state_monitor.cpp index ff6806e96fac9..a688bfe501960 100644 --- a/system/topic_state_monitor/src/topic_state_monitor/topic_state_monitor.cpp +++ b/system/autoware_topic_state_monitor/src/topic_state_monitor/topic_state_monitor.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "topic_state_monitor/topic_state_monitor.hpp" +#include "autoware/topic_state_monitor/topic_state_monitor.hpp" -namespace topic_state_monitor +namespace autoware::topic_state_monitor { TopicStateMonitor::TopicStateMonitor(rclcpp::Node & node) : clock_(node.get_clock()) { @@ -99,4 +99,4 @@ bool TopicStateMonitor::isTimeout() const return time_diff > param_.timeout; } -} // namespace topic_state_monitor +} // namespace autoware::topic_state_monitor diff --git a/system/topic_state_monitor/src/topic_state_monitor_core.cpp b/system/autoware_topic_state_monitor/src/topic_state_monitor_core.cpp similarity index 96% rename from system/topic_state_monitor/src/topic_state_monitor_core.cpp rename to system/autoware_topic_state_monitor/src/topic_state_monitor_core.cpp index ff58a0c6fd584..5947136b1cd57 100644 --- a/system/topic_state_monitor/src/topic_state_monitor_core.cpp +++ b/system/autoware_topic_state_monitor/src/topic_state_monitor_core.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "topic_state_monitor/topic_state_monitor_core.hpp" +#include "autoware/topic_state_monitor/topic_state_monitor_core.hpp" #include #include @@ -34,7 +34,7 @@ void update_param( } } // namespace -namespace topic_state_monitor +namespace autoware::topic_state_monitor { TopicStateMonitorNode::TopicStateMonitorNode(const rclcpp::NodeOptions & node_options) : Node("topic_state_monitor", node_options), updater_(this) @@ -205,7 +205,7 @@ void TopicStateMonitorNode::checkTopicStatus(diagnostic_updater::DiagnosticStatu stat.summary(level, msg); } -} // namespace topic_state_monitor +} // namespace autoware::topic_state_monitor #include -RCLCPP_COMPONENTS_REGISTER_NODE(topic_state_monitor::TopicStateMonitorNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::topic_state_monitor::TopicStateMonitorNode) diff --git a/system/diagnostic_graph_aggregator/example/example-edit.launch.xml b/system/diagnostic_graph_aggregator/example/example-edit.launch.xml deleted file mode 100644 index d56f76b1726cf..0000000000000 --- a/system/diagnostic_graph_aggregator/example/example-edit.launch.xml +++ /dev/null @@ -1,6 +0,0 @@ - - - - - - diff --git a/system/diagnostic_graph_aggregator/example/example-main.launch.xml b/system/diagnostic_graph_aggregator/example/example-main.launch.xml deleted file mode 100644 index b7019640e993c..0000000000000 --- a/system/diagnostic_graph_aggregator/example/example-main.launch.xml +++ /dev/null @@ -1,6 +0,0 @@ - - - - - - diff --git a/system/diagnostic_graph_aggregator/launch/aggregator.launch.xml b/system/diagnostic_graph_aggregator/launch/aggregator.launch.xml deleted file mode 100644 index c06c3d1d96cfa..0000000000000 --- a/system/diagnostic_graph_aggregator/launch/aggregator.launch.xml +++ /dev/null @@ -1,8 +0,0 @@ - - - - - - - - diff --git a/system/system_diagnostic_monitor/launch/system_diagnostic_monitor.launch.xml b/system/system_diagnostic_monitor/launch/system_diagnostic_monitor.launch.xml deleted file mode 100644 index 8e2566a747abf..0000000000000 --- a/system/system_diagnostic_monitor/launch/system_diagnostic_monitor.launch.xml +++ /dev/null @@ -1,9 +0,0 @@ - - - - - - - - - From a7d130fac116475ee3524ceccf3275f86c16dfdd Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Mon, 27 Jan 2025 19:25:08 +0900 Subject: [PATCH 325/334] docs(crosswalk): update ttc vs ttv docs (#10025) Signed-off-by: yuki-takagi-66 --- .../README.md | 13 +- .../docs/ttc_vs_ttv.drawio.svg | 519 +++++++++++------- 2 files changed, 332 insertions(+), 200 deletions(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/README.md b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/README.md index 857f590104aea..52e8c5b2a24a9 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/README.md +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/README.md @@ -138,27 +138,24 @@ The decision is based on the following variables, along with the calculation of We classify ego behavior at crosswalks into three categories according to the relative relationship between TTC and TTV [1]. -- A. **TTC >> TTV**: The object has enough time to cross before the ego. +- A. **TTC >> TTV**: The object will pass early enough than the ego reach the collision point. - No stop planning. - B. **TTC ≒ TTV**: There is a risk of collision. - **Stop point is inserted in the ego's path**. -- C. **TTC << TTV**: Ego has enough time to cross before the object. +- C. **TTC << TTV**: The ego will pass early enough than the object reach the collision point. - No stop planning. +The following figure shows the decision result for each TTC and TTV with the parameters, `ego_pass_first_margin_x` is `{0}`, `ego_pass_first_margin_y` is `{4}`, `ego_pass_later_margin_x` is `{0}`, and `ego_pass_later_margin_y` is `{13}`. +
- +
-The boundary of A and B is interpolated from `ego_pass_later_margin_x` and `ego_pass_later_margin_y`. -In the case of the upper figure, `ego_pass_later_margin_x` is `{0, 1, 2}` and `ego_pass_later_margin_y` is `{1, 4, 6}`. -In the same way, the boundary of B and C is calculated from `ego_pass_first_margin_x` and `ego_pass_first_margin_y`. -In the case of the upper figure, `ego_pass_first_margin_x` is `{3, 5}` and `ego_pass_first_margin_y` is `{0, 1}`. - If the red signal is indicating to the corresponding crosswalk, the ego do not yield against the pedestrians.
diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/docs/ttc_vs_ttv.drawio.svg b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/docs/ttc_vs_ttv.drawio.svg index 6eb1b25cf5642..b0c4a38125607 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/docs/ttc_vs_ttv.drawio.svg +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/docs/ttc_vs_ttv.drawio.svg @@ -1,209 +1,344 @@ - + + - - - - - - -
-
-
- (5, 1) -
-
-
-
- (5, 1) -
-
- - - - -
-
-
- (1, 4) -
-
-
-
- (1, 4) -
-
- - - - -
-
-
- (2, 6) -
-
-
-
- (2, 6) -
-
- - - - - - - - -
-
-
- (0, 1) -
-
-
-
- (0, 1) -
-
- - - - -
-
-
- (3, 0) -
-
-
-
- (3, 0) -
-
- - - - -
-
-
- Time-To-Vehicle [s] -
-
-
-
- Time-To-Vehicle [s] -
-
- - - - - - - - - - - - - - - - - -
-
-
- Time-To-Collision [s] -
-
-
-
- Time-To-Collision [s] -
-
- - - - -
-
-
- B -
-
-
-
- B -
-
- - - - -
-
-
- A -
-
-
-
- A -
-
- - - - -
-
-
- C -
-
-
-
- C -
+ + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ (13, 0) +
+
+
+
+ (13, 0) +
+
+
+
+ + + + + + + + +
+
+
+ Time-To-Vehicle [s] +
+
+
+
+ Time-To-Vehicle [s] +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ Time-To-Collision [s] +
+
+
+
+ Time-To-Collision [s] +
+
+
+
+ + + + + + + + +
+
+
+ B +
+
+
+
+ B +
+
+
+
+ + + + + + + + +
+
+
+ A +
+
+
+
+ A +
+
+
+
+ + + + + + + + +
+
+
+ C +
+
+
+
+ C +
+
+
+
+ + + + + + + + +
+
+
+ (0, 4) +
+
+
+
+ (0, 4) +
+
+
+
+ + + + + + + + + + + + + + + +
- + Text is not SVG - cannot display From 32e340270f4390faf4619005a9215c7a3890ee2b Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Mon, 27 Jan 2025 20:40:07 +0900 Subject: [PATCH 326/334] docs(crosswalk): fix file add miss (#10028) Signed-off-by: yuki-takagi-66 --- .../docs/ttc_vs_ttv.svg | 379 ++++++++++++++++++ 1 file changed, 379 insertions(+) create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/docs/ttc_vs_ttv.svg diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/docs/ttc_vs_ttv.svg b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/docs/ttc_vs_ttv.svg new file mode 100644 index 0000000000000..ef03de6cac00d --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/docs/ttc_vs_ttv.svg @@ -0,0 +1,379 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ (13, 0) +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Time-To-Vehicle [s] +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ Time-To-Collision [s] +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ B +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ A +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ C +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ (0, 4) +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + +
+
+
+
From 63ef9e51f1886dc8f37873514c7b7b4dd0181a2d Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Tue, 28 Jan 2025 01:57:03 +0000 Subject: [PATCH 327/334] chore: sync files (#10009) Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> Co-authored-by: github-actions --- .github/workflows/github-release.yaml | 31 +++++++-------------------- 1 file changed, 8 insertions(+), 23 deletions(-) diff --git a/.github/workflows/github-release.yaml b/.github/workflows/github-release.yaml index bbe2ac512d70d..ac4f6f05ed9ec 100644 --- a/.github/workflows/github-release.yaml +++ b/.github/workflows/github-release.yaml @@ -6,14 +6,12 @@ name: github-release on: push: - branches: - - beta/v* tags: - - v* + - "[0-9]+.[0-9]+.[0-9]+" workflow_dispatch: inputs: - beta-branch-or-tag-name: - description: The name of the beta branch or tag to release + tag-name: + description: The name of the tag to release type: string required: true @@ -25,36 +23,24 @@ jobs: id: set-tag-name run: | if [ "${{ github.event_name }}" = "workflow_dispatch" ]; then - REF_NAME="${{ github.event.inputs.beta-branch-or-tag-name }}" + REF_NAME="${{ github.event.inputs.tag-name }}" else REF_NAME="${{ github.ref_name }}" fi - echo "ref-name=$REF_NAME" >> $GITHUB_OUTPUT - echo "tag-name=${REF_NAME#beta/}" >> $GITHUB_OUTPUT + echo "tag-name=$REF_NAME" >> $GITHUB_OUTPUT - name: Check out repository uses: actions/checkout@v4 with: fetch-depth: 0 - ref: ${{ steps.set-tag-name.outputs.ref-name }} - - - name: Set target name for beta branches - id: set-target-name - run: | - if [[ "${{ steps.set-tag-name.outputs.ref-name }}" =~ "beta/" ]]; then - echo "target-name=${{ steps.set-tag-name.outputs.ref-name }}" >> $GITHUB_OUTPUT - fi - - - name: Create a local tag for beta branches - run: | - if [ "${{ steps.set-target-name.outputs.target-name }}" != "" ]; then - git tag "${{ steps.set-tag-name.outputs.tag-name }}" - fi + ref: ${{ steps.set-tag-name.outputs.tag-name }} - name: Run generate-changelog id: generate-changelog uses: autowarefoundation/autoware-github-actions/generate-changelog@v1 + with: + git-cliff-args: --tag-pattern "^(\d+)\.(\d+)\.(\d+)$" --latest - name: Select verb id: select-verb @@ -74,7 +60,6 @@ jobs: run: | gh release ${{ steps.select-verb.outputs.verb }} "${{ steps.set-tag-name.outputs.tag-name }}" \ --draft \ - --target "${{ steps.set-target-name.outputs.target-name }}" \ --title "Release ${{ steps.set-tag-name.outputs.tag-name }}" \ --notes "$NOTES" env: From 874dbddd8b9931ececd29421d5eb23e60577969b Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> Date: Tue, 28 Jan 2025 14:20:32 +0900 Subject: [PATCH 328/334] feat(start_planner): visualize planner evaluation table in rviz (#10029) visualize planner evaluation table in rviz Signed-off-by: Kyoichi Sugahara --- .../behavior_path_planner_node.hpp | 3 + .../src/behavior_path_planner_node.cpp | 11 ++ .../interface/scene_module_visitor.hpp | 5 + .../src/interface/scene_module_visitor.cpp | 6 + .../data_structs.hpp | 38 ++++--- .../start_planner_module.hpp | 16 ++- .../src/start_planner_module.cpp | 105 ++++++++++++++---- 7 files changed, 139 insertions(+), 45 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/behavior_path_planner_node.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/behavior_path_planner_node.hpp index ba3d3d5d7a4d4..d88c93712b1e3 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/behavior_path_planner_node.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/behavior_path_planner_node.hpp @@ -17,6 +17,7 @@ #include "autoware/behavior_path_planner_common/data_manager.hpp" #include "autoware/behavior_path_planner_common/interface/scene_module_interface.hpp" +#include "autoware/universe_utils/ros/debug_publisher.hpp" #include "autoware/universe_utils/ros/logger_level_configure.hpp" #include "planner_manager.hpp" @@ -72,6 +73,7 @@ using tier4_planning_msgs::msg::RerouteAvailability; using tier4_planning_msgs::msg::Scenario; using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; +using DebugPublisher = autoware::universe_utils::DebugPublisher; class BehaviorPathPlannerNode : public rclcpp::Node { @@ -186,6 +188,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node // debug rclcpp::Publisher::SharedPtr debug_avoidance_msg_array_publisher_; rclcpp::Publisher::SharedPtr debug_turn_signal_info_publisher_; + std::unique_ptr debug_start_planner_evaluation_table_publisher_ptr_; /** * @brief publish reroute availability diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp index 568d432e1faa3..38c5aa0085fb9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp @@ -20,6 +20,7 @@ #include #include +#include #include #include @@ -30,6 +31,7 @@ namespace autoware::behavior_path_planner { using autoware::vehicle_info_utils::VehicleInfoUtils; using tier4_planning_msgs::msg::PathChangeModuleId; +using DebugStringMsg = autoware_internal_debug_msgs::msg::StringStamped; BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & node_options) : Node("behavior_path_planner", node_options), @@ -55,9 +57,13 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod create_publisher("~/output/modified_goal", durable_qos); reroute_availability_publisher_ = create_publisher("~/output/is_reroute_available", 1); + debug_avoidance_msg_array_publisher_ = create_publisher("~/debug/avoidance_debug_message_array", 1); + debug_start_planner_evaluation_table_publisher_ptr_ = + std::make_unique(this, "~/debug/start_planner_evaluation_table"); + debug_turn_signal_info_publisher_ = create_publisher("~/debug/turn_signal_info", 1); bound_publisher_ = create_publisher("~/debug/bound", 1); @@ -608,6 +614,11 @@ void BehaviorPathPlannerNode::publishSceneModuleDebugMsg( if (avoidance_debug_message) { debug_avoidance_msg_array_publisher_->publish(*avoidance_debug_message); } + const auto start_planner_debug_message = debug_messages_data_ptr->getStartPlannerModuleDebugMsg(); + if (start_planner_debug_message) { + debug_start_planner_evaluation_table_publisher_ptr_->publish( + "start_planner_evaluation_table", *(start_planner_debug_message)); + } } void BehaviorPathPlannerNode::publishPathCandidate( diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_visitor.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_visitor.hpp index e2d5d276070ee..f3921e4778593 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_visitor.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_visitor.hpp @@ -16,6 +16,7 @@ #define AUTOWARE__BEHAVIOR_PATH_PLANNER_COMMON__INTERFACE__SCENE_MODULE_VISITOR_HPP_ #include "tier4_planning_msgs/msg/detail/avoidance_debug_msg_array__struct.hpp" +#include #include namespace autoware::behavior_path_planner @@ -31,16 +32,20 @@ class SideShiftModule; using tier4_planning_msgs::msg::AvoidanceDebugMsg; using tier4_planning_msgs::msg::AvoidanceDebugMsgArray; +using DebugStringMsg = autoware_internal_debug_msgs::msg::StringStamped; class SceneModuleVisitor { public: void visitAvoidanceModule(const StaticObstacleAvoidanceModule * module) const; + void visitStartPlannerModule(const StartPlannerModule * module) const; std::shared_ptr getAvoidanceModuleDebugMsg() const; + std::shared_ptr getStartPlannerModuleDebugMsg() const; protected: mutable std::shared_ptr avoidance_visitor_; + mutable std::shared_ptr start_planner_visitor_; }; } // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_visitor.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_visitor.cpp index e6ccfc74866c4..45c4f17c32698 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_visitor.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_visitor.cpp @@ -24,4 +24,10 @@ std::shared_ptr SceneModuleVisitor::getAvoidanceModuleDe { return avoidance_visitor_; } + +std::shared_ptr SceneModuleVisitor::getStartPlannerModuleDebugMsg() const +{ + return start_planner_visitor_; +} + } // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/data_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/data_structs.hpp index 5d8331318484d..4a2ca54e7d38c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/data_structs.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/data_structs.hpp @@ -26,7 +26,6 @@ #include #include - namespace autoware::behavior_path_planner { @@ -51,29 +50,34 @@ struct PlannerDebugData { public: PlannerType planner_type; - std::vector conditions_evaluation; - double required_margin{0.0}; double backward_distance{0.0}; + double required_margin{0.0}; + std::vector conditions_evaluation; - auto header_str() const + static std::string double_to_str(double value, int precision = 1) { - std::stringstream ss; - ss << std::left << std::setw(20) << "| Planner type " << std::setw(20) << "| Required margin " - << std::setw(20) << "| Backward distance " << std::setw(25) << "| Condition evaluation |" - << "\n"; - return ss.str(); + std::ostringstream oss; + oss << std::fixed << std::setprecision(precision) << value; + return oss.str(); } - auto str() const + static std::string to_planner_type_name(PlannerType pt) { - std::stringstream ss; - for (const auto & result : conditions_evaluation) { - ss << std::left << std::setw(23) << magic_enum::enum_name(planner_type) << std::setw(23) - << (std::to_string(required_margin) + "[m]") << std::setw(23) - << (std::to_string(backward_distance) + "[m]") << std::setw(25) << result << "\n"; + // Adding whitespace for column width alignment in RViz display + switch (pt) { + case PlannerType::NONE: + return "NONE "; + case PlannerType::SHIFT: + return "SHIFT "; + case PlannerType::GEOMETRIC: + return "GEOMETRIC "; + case PlannerType::STOP: + return "STOP "; + case PlannerType::FREESPACE: + return "FREESPACE "; + default: + return "UNKNOWN"; } - ss << std::setw(40); - return ss.str(); } }; struct StartPlannerDebugData diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp index 9b1186cb5fc66..3978738798386 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp @@ -26,10 +26,12 @@ #include "autoware/behavior_path_start_planner_module/geometric_pull_out.hpp" #include "autoware/behavior_path_start_planner_module/pull_out_path.hpp" #include "autoware/behavior_path_start_planner_module/shift_pull_out.hpp" +#include "data_structs.hpp" #include #include +#include #include #include @@ -52,6 +54,7 @@ using autoware::behavior_path_planner::utils::path_safety_checker::SafetyCheckPa using autoware::behavior_path_planner::utils::path_safety_checker::TargetObjectsOnLane; using geometry_msgs::msg::PoseArray; using PriorityOrder = std::vector>>; +using DebugStringMsg = autoware_internal_debug_msgs::msg::StringStamped; struct PullOutStatus { @@ -146,16 +149,16 @@ class StartPlannerModule : public SceneModuleInterface } void resetStatus(); - void acceptVisitor( - [[maybe_unused]] const std::shared_ptr & visitor) const override - { - } + void acceptVisitor(const std::shared_ptr & visitor) const override; // Condition to disable simultaneous execution bool isDrivingForward() const { return status_.driving_forward; } bool isFreespacePlanning() const { return status_.planner_type == PlannerType::FREESPACE; } + std::string get_planner_evaluation_table() const { return planner_evaluation_table_; } + private: + friend class SceneModuleVisitor; struct StartPlannerData { StartPlannerParameters parameters; @@ -283,6 +286,7 @@ ego pose. std::vector> start_planners_; PullOutStatus status_; mutable StartPlannerDebugData debug_data_; + std::string planner_evaluation_table_; // Keeps track of lanelets that should be ignored when calculating the turnSignalInfo for this // module's output. If the ego vehicle is in this lanelet, the calculation is skipped. @@ -352,6 +356,10 @@ ego pose. const StartPlannerParameters & parameters, const std::shared_ptr & planner_data, const PullOutStatus & pull_out_status); + std::string create_planner_evaluation_table( + const std::vector & planner_debug_data_vector) const; + void set_planner_evaluation_table(const std::vector & debug_data_vector); + void setDebugData(); void logPullOutStatus(rclcpp::Logger::Level log_level = rclcpp::Logger::Level::Info) const; }; diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp index ae05bcf4c084e..5ad519af20cad 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp @@ -894,16 +894,6 @@ void StartPlannerModule::planWithPriority( if (start_pose_candidates.empty()) return; - auto get_accumulated_debug_stream = [](const std::vector & debug_data_vector) { - std::stringstream ss; - if (debug_data_vector.empty()) return ss; - ss << debug_data_vector.front().header_str(); - for (const auto & debug_data : debug_data_vector) { - ss << debug_data.str(); - } - return ss; - }; - const PriorityOrder order_priority = determinePriorityOrder(search_priority, start_pose_candidates.size()); @@ -918,20 +908,13 @@ void StartPlannerModule::planWithPriority( collision_check_margin, debug_data_vector)) { debug_data_.selected_start_pose_candidate_index = index; debug_data_.margin_for_start_pose_candidate = collision_check_margin; - if (parameters_->print_debug_info) { - const auto ss = get_accumulated_debug_stream(debug_data_vector); - DEBUG_PRINT("\nPull out path search results:\n%s", ss.str().c_str()); - } + set_planner_evaluation_table(debug_data_vector); return; } } } } - - if (parameters_->print_debug_info) { - const auto ss = get_accumulated_debug_stream(debug_data_vector); - DEBUG_PRINT("\nPull out path search results:\n%s", ss.str().c_str()); - } + set_planner_evaluation_table(debug_data_vector); updateStatusIfNoSafePathFound(); } @@ -973,7 +956,7 @@ bool StartPlannerModule::findPullOutPath( planner->setCollisionCheckMargin(collision_check_margin); PlannerDebugData debug_data{ - planner->getPlannerType(), {}, collision_check_margin, backwards_distance}; + planner->getPlannerType(), backwards_distance, collision_check_margin, {}}; const auto pull_out_path = planner->plan(start_pose_candidate, goal_pose, planner_data_, debug_data); @@ -1580,12 +1563,9 @@ std::optional StartPlannerModule::planFreespacePath( for (const auto & p : center_line_path.points) { const Pose end_pose = p.point.pose; - PlannerDebugData debug_data{freespace_planner_->getPlannerType(), {}, 0.0, 0.0}; + PlannerDebugData debug_data{freespace_planner_->getPlannerType(), 0.0, 0.0, {}}; auto freespace_path = freespace_planner_->plan(current_pose, end_pose, planner_data, debug_data); - DEBUG_PRINT( - "\nFreespace Pull out path search results\n%s%s", debug_data.header_str().c_str(), - debug_data.str().c_str()); if (!freespace_path) { continue; } @@ -1628,6 +1608,83 @@ void StartPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) cons } } +std::string StartPlannerModule::create_planner_evaluation_table( + const std::vector & planner_debug_data_vector) const +{ + if (planner_debug_data_vector.empty()) { + return ""; + } + + const std::string header_planner_type = "Planner type "; + const std::string header_required_margin = "Required margin [m]"; + const std::string header_backward_distance = "Backward distance [m]"; + const std::string header_condition_eval = "Condition"; + + std::ostringstream oss; + oss << "-----------------------------------------------------------------------------------------" + "----------------" + << "\n"; + oss << "| " << std::left << header_planner_type << " | " << header_required_margin << " | " + << header_backward_distance << " | " << header_condition_eval << " \n"; + oss << "-----------------------------------------------------------------------------------------" + "----------------" + << "\n"; + + for (const auto & d : planner_debug_data_vector) { + const std::string pt_str = PlannerDebugData::to_planner_type_name(d.planner_type); + const std::string rm_str = + PlannerDebugData::double_to_str(d.required_margin, 1) + " "; + const std::string bd_str = PlannerDebugData::double_to_str(d.backward_distance, 1) + + " "; + + if (d.conditions_evaluation.empty()) { + oss << "| " << std::left << pt_str << " | " << rm_str << " | " << bd_str << " | " + << "Unexpected empty condition evaluation" + << " \n"; + } else { + for (size_t i = 0; i < d.conditions_evaluation.size(); ++i) { + const std::string cond_with_index = + "#" + std::to_string(i + 1) + ": " + d.conditions_evaluation[i]; + + oss << "| " << std::left << pt_str << " | " << rm_str << " | " << bd_str << " | " + << cond_with_index << " \n"; + } + } + } + + return oss.str(); +} + +void StartPlannerModule::set_planner_evaluation_table( + const std::vector & debug_data_vector) +{ + planner_evaluation_table_.clear(); + if (debug_data_vector.empty()) { + return; + } + + planner_evaluation_table_ = create_planner_evaluation_table(debug_data_vector); +} + +void StartPlannerModule::acceptVisitor(const std::shared_ptr & visitor) const +{ + if (visitor) { + visitor->visitStartPlannerModule(this); + } +} + +void SceneModuleVisitor::visitStartPlannerModule(const StartPlannerModule * module) const +{ + auto debug_msg = std::make_shared(); + auto debug_info = module->get_planner_evaluation_table(); + if (debug_info.empty()) return; + + debug_msg->stamp = rclcpp::Clock{RCL_ROS_TIME}.now(); + debug_msg->data = debug_info; + + start_planner_visitor_ = debug_msg; +} + void StartPlannerModule::setDebugData() { using autoware::universe_utils::createDefaultMarker; From 165be35738247398e407702f6b1d5e3d6deb9305 Mon Sep 17 00:00:00 2001 From: Kenzo Lobos Tsunekawa Date: Tue, 28 Jan 2025 17:52:12 +0900 Subject: [PATCH 329/334] feat(autoware_probabilistic_occupancy_grid_map): cuda accelerated implementation (#9542) * feat: implemented a cuda accelerated ogm Signed-off-by: Kenzo Lobos-Tsunekawa * chore: fixed cspells Signed-off-by: Kenzo Lobos-Tsunekawa * chore: unused header and variable names Signed-off-by: Kenzo Lobos-Tsunekawa * chore: cspell fixes Signed-off-by: Kenzo Lobos-Tsunekawa * chore: cppcheck fix attempt Signed-off-by: Kenzo Lobos-Tsunekawa * fix: attempting to fix ci/cd regarding the cuda library Signed-off-by: Kenzo Lobos-Tsunekawa * chore: fixed the order of the cuda check in the cmakelist Signed-off-by: Kenzo Lobos-Tsunekawa * fix: removed cuda as a required dep for cpu only builds Signed-off-by: Kenzo Lobos-Tsunekawa * fix: missing cuda linking (?) Signed-off-by: Kenzo Lobos-Tsunekawa * feat: fixed single mode, added streams, and added the restrict keyword Signed-off-by: Kenzo Lobos-Tsunekawa * chore: replaced a potential indetermination using an epsilon Signed-off-by: Kenzo Lobos-Tsunekawa * Update perception/autoware_probabilistic_occupancy_grid_map/lib/updater/log_odds_bayes_filter_updater_kernel.cu Co-authored-by: Yoshi Ri * Update perception/autoware_probabilistic_occupancy_grid_map/lib/updater/log_odds_bayes_filter_updater_kernel.cu Co-authored-by: Yoshi Ri * style(pre-commit): autofix * chore: added bound checkings in the update origin kernel Signed-off-by: Kenzo Lobos-Tsunekawa * chore: disabled tests since universe does not support cuda in ci/cd Signed-off-by: Kenzo Lobos-Tsunekawa * chore: added me as a maintainer Signed-off-by: Kenzo Lobos-Tsunekawa * fix: missedn the end in the cmake Signed-off-by: Kenzo Lobos-Tsunekawa * chore: moved the boudnary checks to only the cuda version since the cpu version uses the upstream logic Signed-off-by: Kenzo Lobos-Tsunekawa --------- Signed-off-by: Kenzo Lobos-Tsunekawa Co-authored-by: Yoshi Ri Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../CMakeLists.txt | 87 ++- .../costmap_2d/occupancy_grid_map.hpp | 9 +- .../costmap_2d/occupancy_grid_map_base.hpp | 65 +-- .../costmap_2d/occupancy_grid_map_fixed.hpp | 16 +- .../occupancy_grid_map_fixed_kernel.hpp | 60 ++ .../occupancy_grid_map_projective.hpp | 21 +- .../occupancy_grid_map_projective_kernel.hpp | 70 +++ .../updater/binary_bayes_filter_updater.hpp | 10 +- .../binary_bayes_filter_updater_kernel.hpp | 36 ++ .../updater/log_odds_bayes_filter_updater.hpp | 10 +- .../log_odds_bayes_filter_updater_kernel.hpp | 35 ++ .../updater/ogm_updater_interface.hpp | 12 +- .../utils/cuda_pointcloud.hpp | 55 ++ .../utils/utils.hpp | 50 +- .../utils/utils_kernel.hpp | 52 ++ .../lib/costmap_2d/occupancy_grid_map.cpp | 53 +- .../costmap_2d/occupancy_grid_map_base.cpp | 208 +++---- .../costmap_2d/occupancy_grid_map_fixed.cpp | 285 ++++------ .../occupancy_grid_map_fixed_kernel.cu | 388 +++++++++++++ .../occupancy_grid_map_projective.cpp | 364 ++++-------- .../occupancy_grid_map_projective_kernel.cu | 534 ++++++++++++++++++ .../updater/binary_bayes_filter_updater.cpp | 55 +- .../binary_bayes_filter_updater_kernel.cu | 81 +++ .../updater/log_odds_bayes_filter_updater.cpp | 34 +- .../log_odds_bayes_filter_updater_kernel.cu | 95 ++++ .../lib/utils/utils.cpp | 80 +-- .../lib/utils/utils_kernel.cu | 300 ++++++++++ .../package.xml | 2 + .../synchronized_grid_map_fusion_node.cpp | 42 +- .../synchronized_grid_map_fusion_node.hpp | 5 +- ...aserscan_based_occupancy_grid_map_node.cpp | 4 +- ...intcloud_based_occupancy_grid_map_node.cpp | 65 +-- ...intcloud_based_occupancy_grid_map_node.hpp | 6 +- 33 files changed, 2288 insertions(+), 901 deletions(-) create mode 100644 perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_fixed_kernel.hpp create mode 100644 perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_projective_kernel.hpp create mode 100644 perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/updater/binary_bayes_filter_updater_kernel.hpp create mode 100644 perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/updater/log_odds_bayes_filter_updater_kernel.hpp create mode 100644 perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/utils/cuda_pointcloud.hpp create mode 100644 perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/utils/utils_kernel.hpp create mode 100644 perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_fixed_kernel.cu create mode 100644 perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_projective_kernel.cu create mode 100644 perception/autoware_probabilistic_occupancy_grid_map/lib/updater/binary_bayes_filter_updater_kernel.cu create mode 100644 perception/autoware_probabilistic_occupancy_grid_map/lib/updater/log_odds_bayes_filter_updater_kernel.cu create mode 100644 perception/autoware_probabilistic_occupancy_grid_map/lib/utils/utils_kernel.cu diff --git a/perception/autoware_probabilistic_occupancy_grid_map/CMakeLists.txt b/perception/autoware_probabilistic_occupancy_grid_map/CMakeLists.txt index 28342ecb5bcff..7dda1604f10f3 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/CMakeLists.txt +++ b/perception/autoware_probabilistic_occupancy_grid_map/CMakeLists.txt @@ -4,27 +4,54 @@ project(autoware_probabilistic_occupancy_grid_map) find_package(autoware_cmake REQUIRED) autoware_package() +find_package(CUDA) find_package(eigen3_cmake_module REQUIRED) find_package(Eigen3 REQUIRED) find_package(PCL REQUIRED) +if(NOT ${CUDA_FOUND}) + message(WARNING "cuda was not found, so the autoware_probabilistic_occupancy_grid_map package will not be built.") + return() +endif() + include_directories( + include SYSTEM + ${CUDA_INCLUDE_DIRS} ${EIGEN3_INCLUDE_DIR} + ${grid_map_ros_INCLUDE_DIRS} +) + +# cSpell: ignore expt +list(APPEND CUDA_NVCC_FLAGS --expt-relaxed-constexpr -diag-suppress 20012 --compiler-options -fPIC) +set(CUDA_SEPARABLE_COMPILATION ON) +set(CMAKE_POSITION_INDEPENDENT_CODE ON) + +cuda_add_library(${PROJECT_NAME}_cuda SHARED + lib/costmap_2d/occupancy_grid_map_fixed_kernel.cu + lib/costmap_2d/occupancy_grid_map_projective_kernel.cu + lib/updater/binary_bayes_filter_updater_kernel.cu + lib/updater/log_odds_bayes_filter_updater_kernel.cu + lib/utils/utils_kernel.cu +) + +target_link_libraries(${PROJECT_NAME}_cuda + ${CUDA_LIBRARIES} ) ament_auto_add_library(${PROJECT_NAME}_common SHARED + lib/costmap_2d/occupancy_grid_map_base.cpp lib/updater/binary_bayes_filter_updater.cpp lib/utils/utils.cpp ) target_link_libraries(${PROJECT_NAME}_common ${PCL_LIBRARIES} + ${PROJECT_NAME}_cuda ) # PointcloudBasedOccupancyGridMap ament_auto_add_library(pointcloud_based_occupancy_grid_map SHARED src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp - lib/costmap_2d/occupancy_grid_map_base.cpp lib/costmap_2d/occupancy_grid_map_fixed.cpp lib/costmap_2d/occupancy_grid_map_projective.cpp ) @@ -32,6 +59,7 @@ ament_auto_add_library(pointcloud_based_occupancy_grid_map SHARED target_link_libraries(pointcloud_based_occupancy_grid_map ${PCL_LIBRARIES} ${PROJECT_NAME}_common + ${PROJECT_NAME}_cuda ) rclcpp_components_register_node(pointcloud_based_occupancy_grid_map @@ -73,6 +101,11 @@ rclcpp_components_register_node(synchronized_grid_map_fusion EXECUTABLE synchronized_grid_map_fusion_node ) +install( + TARGETS ${PROJECT_NAME}_cuda + DESTINATION lib +) + ament_auto_package( INSTALL_TO_SHARE launch @@ -80,27 +113,31 @@ ament_auto_package( ) # test -if(BUILD_TESTING) - # launch_testing - find_package(launch_testing_ament_cmake REQUIRED) - add_launch_test(test/test_pointcloud_based_method.py) - add_launch_test(test/test_synchronized_grid_map_fusion_node.py) - - # gtest - ament_add_gtest(test_utils - test/test_utils.cpp - ) - ament_add_gtest(costmap_unit_tests - test/cost_value_test.cpp - ) - ament_add_gtest(fusion_policy_unit_tests - test/fusion_policy_test.cpp - lib/fusion_policy/fusion_policy.cpp - ) - target_link_libraries(test_utils - ${PCL_LIBRARIES} - ${PROJECT_NAME}_common - ) - target_include_directories(costmap_unit_tests PRIVATE "include") - target_include_directories(fusion_policy_unit_tests PRIVATE "include") -endif() +# Temporary disabled, tracked by: +# https://github.com/autowarefoundation/autoware.universe/issues/7724 +#if(BUILD_TESTING) +# # launch_testing +# find_package(launch_testing_ament_cmake REQUIRED) +# add_launch_test(test/test_pointcloud_based_method.py) +# add_launch_test(test/test_synchronized_grid_map_fusion_node.py) +# +# # gtest +# ament_add_gtest(test_utils +# test/test_utils.cpp +# ) +# ament_add_gtest(costmap_unit_tests +# test/cost_value_test.cpp +# ) +# ament_add_gtest(fusion_policy_unit_tests +# test/fusion_policy_test.cpp +# lib/fusion_policy/fusion_policy.cpp +# ) +# target_link_libraries(test_utils +# ${CUDA_LIBRARIES} +# ${PCL_LIBRARIES} +# ${PROJECT_NAME}_common +# ${PROJECT_NAME}_cuda +# ) +# target_include_directories(costmap_unit_tests PRIVATE "include") +# target_include_directories(fusion_policy_unit_tests PRIVATE "include") +#endif() diff --git a/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map.hpp b/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map.hpp index 93e768c0f6b4e..5fe3613cc7612 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map.hpp +++ b/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map.hpp @@ -52,7 +52,8 @@ #ifndef AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_HPP_ #define AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_HPP_ -#include +#include "autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_base.hpp" + #include #include @@ -66,7 +67,7 @@ namespace costmap_2d using geometry_msgs::msg::Pose; using sensor_msgs::msg::PointCloud2; -class OccupancyGridMap : public nav2_costmap_2d::Costmap2D +class OccupancyGridMap : public OccupancyGridMapInterface { public: OccupancyGridMap( @@ -78,8 +79,6 @@ class OccupancyGridMap : public nav2_costmap_2d::Costmap2D void updateOccupiedCells(const PointCloud2 & pointcloud); - void updateOrigin(double new_origin_x, double new_origin_y) override; - private: void raytraceFreespace(const PointCloud2 & pointcloud, const Pose & robot_pose); @@ -87,6 +86,8 @@ class OccupancyGridMap : public nav2_costmap_2d::Costmap2D bool worldToMap(double wx, double wy, unsigned int & mx, unsigned int & my) const; + void initRosParam([[maybe_unused]] rclcpp::Node & node) override {} + rclcpp::Logger logger_{rclcpp::get_logger("laserscan_based_occupancy_grid_map")}; rclcpp::Clock clock_{RCL_ROS_TIME}; }; diff --git a/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_base.hpp b/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_base.hpp index 09ad0a4d554a1..c77345a973c50 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_base.hpp +++ b/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_base.hpp @@ -52,6 +52,9 @@ #ifndef AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_BASE_HPP_ #define AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_BASE_HPP_ +#include "autoware/probabilistic_occupancy_grid_map/utils/cuda_pointcloud.hpp" + +#include #include #include #include @@ -72,18 +75,17 @@ class OccupancyGridMapInterface : public nav2_costmap_2d::Costmap2D { public: OccupancyGridMapInterface( - const unsigned int cells_size_x, const unsigned int cells_size_y, const float resolution); + const bool use_cuda, const unsigned int cells_size_x, const unsigned int cells_size_y, + const float resolution); virtual void updateWithPointCloud( - const PointCloud2 & raw_pointcloud, const PointCloud2 & obstacle_pointcloud, - const Pose & robot_pose, const Pose & scan_origin) = 0; + [[maybe_unused]] const CudaPointCloud2 & raw_pointcloud, + [[maybe_unused]] const CudaPointCloud2 & obstacle_pointcloud, + [[maybe_unused]] const Pose & robot_pose, [[maybe_unused]] const Pose & scan_origin) {}; void updateOrigin(double new_origin_x, double new_origin_y) override; - void raytrace( - const double source_x, const double source_y, const double target_x, const double target_y, - const unsigned char cost); - void setCellValue(const double wx, const double wy, const unsigned char cost); - using nav2_costmap_2d::Costmap2D::resetMaps; + + void resetMaps() override; virtual void initRosParam(rclcpp::Node & node) = 0; @@ -92,47 +94,34 @@ class OccupancyGridMapInterface : public nav2_costmap_2d::Costmap2D double min_height_; double max_height_; - void setFieldOffsets(const PointCloud2 & input_raw, const PointCloud2 & input_obstacle); - - int x_offset_raw_; - int y_offset_raw_; - int z_offset_raw_; - int x_offset_obstacle_; - int y_offset_obstacle_; - int z_offset_obstacle_; - bool offset_initialized_; - const double min_angle_ = autoware::universe_utils::deg2rad(-180.0); const double max_angle_ = autoware::universe_utils::deg2rad(180.0); const double angle_increment_inv_ = 1.0 / autoware::universe_utils::deg2rad(0.1); Eigen::Matrix4f mat_map_, mat_scan_; - bool isPointValid(const Eigen::Vector4f & pt) const - { - // Apply height filter and exclude invalid points - return min_height_ < pt[2] && pt[2] < max_height_ && std::isfinite(pt[0]) && - std::isfinite(pt[1]) && std::isfinite(pt[2]); - } - // Transform pt to (pt_map, pt_scan), then calculate angle_bin_index and range - void transformPointAndCalculate( - const Eigen::Vector4f & pt, Eigen::Vector4f & pt_map, int & angle_bin_index, - double & range) const - { - pt_map = mat_map_ * pt; - Eigen::Vector4f pt_scan(mat_scan_ * pt_map); - const double angle = atan2(pt_scan[1], pt_scan[0]); - angle_bin_index = (angle - min_angle_) * angle_increment_inv_; - range = std::sqrt(pt_scan[1] * pt_scan[1] + pt_scan[0] * pt_scan[0]); - } - -private: - bool worldToMap(double wx, double wy, unsigned int & mx, unsigned int & my) const; + bool isCudaEnabled() const; + + const autoware::cuda_utils::CudaUniquePtr & getDeviceCostmap() const; + void copyDeviceCostmapToHost() const; + +protected: rclcpp::Logger logger_{rclcpp::get_logger("pointcloud_based_occupancy_grid_map")}; rclcpp::Clock clock_{RCL_ROS_TIME}; double resolution_inv_; + + cudaStream_t stream_; + + bool use_cuda_; + autoware::cuda_utils::CudaUniquePtr device_costmap_; + autoware::cuda_utils::CudaUniquePtr device_costmap_aux_; + + autoware::cuda_utils::CudaUniquePtr device_rotation_map_; + autoware::cuda_utils::CudaUniquePtr device_translation_map_; + autoware::cuda_utils::CudaUniquePtr device_rotation_scan_; + autoware::cuda_utils::CudaUniquePtr device_translation_scan_; }; } // namespace costmap_2d diff --git a/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_fixed.hpp b/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_fixed.hpp index 3301fd1987bd3..320d297e0a4d1 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_fixed.hpp +++ b/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_fixed.hpp @@ -16,6 +16,7 @@ #define AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_FIXED_HPP_ #include "autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_base.hpp" +#include "autoware/probabilistic_occupancy_grid_map/utils/cuda_pointcloud.hpp" namespace autoware::occupancy_grid_map { @@ -28,21 +29,20 @@ class OccupancyGridMapFixedBlindSpot : public OccupancyGridMapInterface { public: OccupancyGridMapFixedBlindSpot( - const unsigned int cells_size_x, const unsigned int cells_size_y, const float resolution); + const bool use_cuda, const unsigned int cells_size_x, const unsigned int cells_size_y, + const float resolution); void updateWithPointCloud( - const PointCloud2 & raw_pointcloud, const PointCloud2 & obstacle_pointcloud, + const CudaPointCloud2 & raw_pointcloud, const CudaPointCloud2 & obstacle_pointcloud, const Pose & robot_pose, const Pose & scan_origin) override; - using OccupancyGridMapInterface::raytrace; - using OccupancyGridMapInterface::setCellValue; - using OccupancyGridMapInterface::setFieldOffsets; - using OccupancyGridMapInterface::updateOrigin; - void initRosParam(rclcpp::Node & node) override; -private: +protected: double distance_margin_; + + autoware::cuda_utils::CudaUniquePtr raw_points_tensor_; + autoware::cuda_utils::CudaUniquePtr obstacle_points_tensor_; }; } // namespace costmap_2d diff --git a/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_fixed_kernel.hpp b/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_fixed_kernel.hpp new file mode 100644 index 0000000000000..d87c8eec718e1 --- /dev/null +++ b/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_fixed_kernel.hpp @@ -0,0 +1,60 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_FIXED_KERNEL_HPP_ +#define AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_FIXED_KERNEL_HPP_ + +#include "autoware/probabilistic_occupancy_grid_map/utils/utils_kernel.hpp" + +#include + +#include + +namespace autoware::occupancy_grid_map +{ +namespace costmap_2d::map_fixed +{ + +void prepareTensorLaunch( + const float * input_pointcloud, const std::size_t num_points, const std::size_t points_step, + const std::size_t angle_bins, const std::size_t range_bins, const float min_height, + const float max_height, const float min_angle, const float angle_increment_inv, + const float range_resolution_inv, const Eigen::Matrix3f * rotation_map, + const Eigen::Vector3f * translation_map, const Eigen::Matrix3f * rotation_scan, + const Eigen::Vector3f * translation_scan, std::uint64_t * points_tensor, cudaStream_t stream); + +void fillEmptySpaceLaunch( + const std::uint64_t * points_tensor, const std::size_t angle_bins, const std::size_t range_bins, + const float map_resolution_inv, const float scan_origin_x, const float scan_origin_y, + const float map_origin_x, const float map_origin_y, const int num_cells_x, const int num_cells_y, + std::uint8_t empty_value, std::uint8_t * costmap_tensor, cudaStream_t stream); + +void fillUnknownSpaceLaunch( + const std::uint64_t * raw_points_tensor, const std::uint64_t * obstacle_points_tensor, + const float distance_margin, const std::size_t angle_bins, const std::size_t range_bins, + const float map_resolution_inv, const float scan_origin_x, const float scan_origin_y, + const float map_origin_x, const float map_origin_y, const int num_cells_x, const int num_cells_y, + std::uint8_t free_space_value, std::uint8_t no_information_value, std::uint8_t * costmap_tensor, + cudaStream_t stream); + +void fillObstaclesLaunch( + const std::uint64_t * points_tensor, const float distance_margin, const std::size_t angle_bins, + const std::size_t range_bins, const float map_resolution_inv, const float map_origin_x, + const float map_origin_y, const int num_cells_x, const int num_cells_y, + std::uint8_t obstacle_value, std::uint8_t * costmap_tensor, cudaStream_t stream); + +} // namespace costmap_2d::map_fixed +} // namespace autoware::occupancy_grid_map + +#endif // AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_FIXED_KERNEL_HPP_ diff --git a/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_projective.hpp b/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_projective.hpp index 7569a60b36466..9b23b9ecf8cb6 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_projective.hpp +++ b/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_projective.hpp @@ -32,25 +32,22 @@ class OccupancyGridMapProjectiveBlindSpot : public OccupancyGridMapInterface { public: OccupancyGridMapProjectiveBlindSpot( - const unsigned int cells_size_x, const unsigned int cells_size_y, const float resolution); + const bool use_cuda, const unsigned int cells_size_x, const unsigned int cells_size_y, + const float resolution); void updateWithPointCloud( - const PointCloud2 & raw_pointcloud, const PointCloud2 & obstacle_pointcloud, + const CudaPointCloud2 & raw_pointcloud, const CudaPointCloud2 & obstacle_pointcloud, const Pose & robot_pose, const Pose & scan_origin) override; - using OccupancyGridMapInterface::raytrace; - using OccupancyGridMapInterface::setCellValue; - using OccupancyGridMapInterface::setFieldOffsets; - using OccupancyGridMapInterface::updateOrigin; - void initRosParam(rclcpp::Node & node) override; private: - double projection_dz_threshold_; - double obstacle_separation_threshold_; - bool pub_debug_grid_; - grid_map::GridMap debug_grid_; - rclcpp::Publisher::SharedPtr debug_grid_map_publisher_ptr_; + float projection_dz_threshold_; + float obstacle_separation_threshold_; + + autoware::cuda_utils::CudaUniquePtr raw_points_tensor_; + autoware::cuda_utils::CudaUniquePtr obstacle_points_tensor_; + autoware::cuda_utils::CudaUniquePtr device_translation_scan_origin_; }; } // namespace costmap_2d diff --git a/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_projective_kernel.hpp b/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_projective_kernel.hpp new file mode 100644 index 0000000000000..916cf6ed9ec0a --- /dev/null +++ b/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_projective_kernel.hpp @@ -0,0 +1,70 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_PROJECTIVE_KERNEL_HPP_ +#define AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_PROJECTIVE_KERNEL_HPP_ + +#include "autoware/probabilistic_occupancy_grid_map/utils/utils_kernel.hpp" + +#include + +#include + +namespace autoware::occupancy_grid_map +{ +namespace costmap_2d::map_projective +{ + +void prepareRawTensorLaunch( + const float * input_pointcloud, const std::size_t num_points, const std::size_t points_step, + const std::size_t angle_bins, const std::size_t range_bins, const float min_height, + const float max_height, const float min_angle, const float angle_increment_inv, + const float range_resolution_inv, const Eigen::Matrix3f * rotation_map, + const Eigen::Vector3f * translation_map, const Eigen::Matrix3f * rotation_scan, + const Eigen::Vector3f * translation_scan, std::uint64_t * points_tensor, cudaStream_t stream); + +void prepareObstacleTensorLaunch( + const float * input_pointcloud, const std::size_t num_points, const std::size_t points_step, + const std::size_t angle_bins, const std::size_t range_bins, const float min_height, + const float max_height, const float min_angle, const float angle_increment_inv, + const float range_resolution_inv, const float projection_dz_threshold, + const Eigen::Vector3f * translation_scan_origin, const Eigen::Matrix3f * rotation_map, + const Eigen::Vector3f * translation_map, const Eigen::Matrix3f * rotation_scan, + const Eigen::Vector3f * translation_scan, std::uint64_t * points_tensor, cudaStream_t stream); + +void fillEmptySpaceLaunch( + const std::uint64_t * points_tensor, const std::size_t angle_bins, const std::size_t range_bins, + const float map_resolution_inv, const float scan_origin_x, const float scan_origin_y, + const float map_origin_x, const float map_origin_y, const int num_cells_x, const int num_cells_y, + std::uint8_t empty_value, std::uint8_t * costmap_tensor, cudaStream_t stream); + +void fillUnknownSpaceLaunch( + const std::uint64_t * raw_points_tensor, const std::uint64_t * obstacle_points_tensor, + const float obstacle_separation_threshold, const std::size_t angle_bins, + const std::size_t range_bins, const float map_resolution_inv, const float scan_origin_x, + const float scan_origin_y, const float scan_origin_z, const float map_origin_x, + const float map_origin_y, const float robot_pose_z, const int num_cells_x, const int num_cells_y, + std::uint8_t free_space_value, std::uint8_t no_information_value, std::uint8_t * costmap_tensor, + cudaStream_t stream); + +void fillObstaclesLaunch( + const std::uint64_t * points_tensor, const float distance_margin, const std::size_t angle_bins, + const std::size_t range_bins, const float map_resolution_inv, const float map_origin_x, + const float map_origin_y, const int num_cells_x, const int num_cells_y, + std::uint8_t obstacle_value, std::uint8_t * costmap_tensor, cudaStream_t stream); + +} // namespace costmap_2d::map_projective +} // namespace autoware::occupancy_grid_map + +#endif // AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__COSTMAP_2D__OCCUPANCY_GRID_MAP_PROJECTIVE_KERNEL_HPP_ diff --git a/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/updater/binary_bayes_filter_updater.hpp b/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/updater/binary_bayes_filter_updater.hpp index af28b7962b3bc..fe5739f2cadc7 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/updater/binary_bayes_filter_updater.hpp +++ b/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/updater/binary_bayes_filter_updater.hpp @@ -15,6 +15,7 @@ #ifndef AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__BINARY_BAYES_FILTER_UPDATER_HPP_ #define AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__BINARY_BAYES_FILTER_UPDATER_HPP_ +#include "autoware/cuda_utils/cuda_unique_ptr.hpp" #include "autoware/probabilistic_occupancy_grid_map/updater/ogm_updater_interface.hpp" #include @@ -27,16 +28,19 @@ namespace costmap_2d class OccupancyGridMapBBFUpdater : public OccupancyGridMapUpdaterInterface { public: - enum Index : size_t { OCCUPIED = 0U, FREE = 1U }; + enum Index : size_t { OCCUPIED = 0U, FREE = 1U, NUM_STATES = 2U }; OccupancyGridMapBBFUpdater( - const unsigned int cells_size_x, const unsigned int cells_size_y, const float resolution); - bool update(const Costmap2D & single_frame_occupancy_grid_map) override; + const bool use_cuda, const unsigned int cells_size_x, const unsigned int cells_size_y, + const float resolution); + bool update(const OccupancyGridMapInterface & single_frame_occupancy_grid_map) override; void initRosParam(rclcpp::Node & node) override; private: inline unsigned char applyBBF(const unsigned char & z, const unsigned char & o); Eigen::Matrix2f probability_matrix_; double v_ratio_; + + autoware::cuda_utils::CudaUniquePtr device_probability_matrix_; }; } // namespace costmap_2d diff --git a/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/updater/binary_bayes_filter_updater_kernel.hpp b/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/updater/binary_bayes_filter_updater_kernel.hpp new file mode 100644 index 0000000000000..feef6f2815a0f --- /dev/null +++ b/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/updater/binary_bayes_filter_updater_kernel.hpp @@ -0,0 +1,36 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__BINARY_BAYES_FILTER_UPDATER_KERNEL_HPP_ +#define AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__BINARY_BAYES_FILTER_UPDATER_KERNEL_HPP_ + +#include + +#include + +namespace autoware::occupancy_grid_map +{ +namespace costmap_2d +{ + +void applyBBFLaunch( + const std::uint8_t * z_costmap, const float * probability_matrix, const int num_states, + const int free_index, const int occupied_index, const std::uint8_t free_space_value, + const std::uint8_t lethal_obstacle_value, const std::uint8_t no_information_value, + const double v_ratio_, const int num_elements, std::uint8_t * o_costmap, cudaStream_t stream); + +} // namespace costmap_2d +} // namespace autoware::occupancy_grid_map + +#endif // AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__BINARY_BAYES_FILTER_UPDATER_KERNEL_HPP_ diff --git a/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/updater/log_odds_bayes_filter_updater.hpp b/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/updater/log_odds_bayes_filter_updater.hpp index d7bb1184c06d6..d24fc7c46331d 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/updater/log_odds_bayes_filter_updater.hpp +++ b/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/updater/log_odds_bayes_filter_updater.hpp @@ -32,18 +32,18 @@ namespace costmap_2d class OccupancyGridMapLOBFUpdater : public OccupancyGridMapUpdaterInterface { public: - enum Index : size_t { OCCUPIED = 0U, FREE = 1U }; + enum Index : size_t { OCCUPIED = 0U, FREE = 1U, NUM_STATES = 2U }; OccupancyGridMapLOBFUpdater( - const unsigned int cells_size_x, const unsigned int cells_size_y, const float resolution) - : OccupancyGridMapUpdaterInterface(cells_size_x, cells_size_y, resolution) + const bool use_cuda, const unsigned int cells_size_x, const unsigned int cells_size_y, + const float resolution) + : OccupancyGridMapUpdaterInterface(use_cuda, cells_size_x, cells_size_y, resolution) { } - bool update(const Costmap2D & single_frame_occupancy_grid_map) override; + bool update(const OccupancyGridMapInterface & single_frame_occupancy_grid_map) override; void initRosParam(rclcpp::Node & node) override; private: inline unsigned char applyLOBF(const unsigned char & z, const unsigned char & o); - Eigen::Matrix2f probability_matrix_; }; } // namespace costmap_2d diff --git a/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/updater/log_odds_bayes_filter_updater_kernel.hpp b/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/updater/log_odds_bayes_filter_updater_kernel.hpp new file mode 100644 index 0000000000000..c8ff015ca27a2 --- /dev/null +++ b/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/updater/log_odds_bayes_filter_updater_kernel.hpp @@ -0,0 +1,35 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__LOG_ODDS_BAYES_FILTER_UPDATER_KERNEL_HPP_ +#define AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__LOG_ODDS_BAYES_FILTER_UPDATER_KERNEL_HPP_ + +#include + +#include + +namespace autoware::occupancy_grid_map +{ +namespace costmap_2d +{ + +// cspell: ignore LOBF +void applyLOBFLaunch( + const std::uint8_t * z_costmap, const std::uint8_t no_information_value, const int num_elements, + std::uint8_t * o_costmap, cudaStream_t stream); + +} // namespace costmap_2d +} // namespace autoware::occupancy_grid_map + +#endif // AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__LOG_ODDS_BAYES_FILTER_UPDATER_KERNEL_HPP_ diff --git a/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/updater/ogm_updater_interface.hpp b/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/updater/ogm_updater_interface.hpp index 75231089ac33c..ae9f824bb9beb 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/updater/ogm_updater_interface.hpp +++ b/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/updater/ogm_updater_interface.hpp @@ -16,24 +16,26 @@ #define AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UPDATER__OGM_UPDATER_INTERFACE_HPP_ #include "autoware/probabilistic_occupancy_grid_map/cost_value/cost_value.hpp" +#include "autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_base.hpp" +#include "autoware/probabilistic_occupancy_grid_map/utils/utils_kernel.hpp" -#include #include namespace autoware::occupancy_grid_map { namespace costmap_2d { -class OccupancyGridMapUpdaterInterface : public nav2_costmap_2d::Costmap2D +class OccupancyGridMapUpdaterInterface : public OccupancyGridMapInterface { public: OccupancyGridMapUpdaterInterface( - const unsigned int cells_size_x, const unsigned int cells_size_y, const float resolution) - : Costmap2D(cells_size_x, cells_size_y, resolution, 0.f, 0.f, cost_value::NO_INFORMATION) + bool use_cuda, const unsigned int cells_size_x, const unsigned int cells_size_y, + const float resolution) + : OccupancyGridMapInterface(use_cuda, cells_size_x, cells_size_y, resolution) { } virtual ~OccupancyGridMapUpdaterInterface() = default; - virtual bool update(const Costmap2D & single_frame_occupancy_grid_map) = 0; + virtual bool update(const OccupancyGridMapInterface & single_frame_occupancy_grid_map) = 0; virtual void initRosParam(rclcpp::Node & node) = 0; }; diff --git a/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/utils/cuda_pointcloud.hpp b/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/utils/cuda_pointcloud.hpp new file mode 100644 index 0000000000000..8c78e2ad915b5 --- /dev/null +++ b/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/utils/cuda_pointcloud.hpp @@ -0,0 +1,55 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UTILS__CUDA_POINTCLOUD_HPP_ +#define AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UTILS__CUDA_POINTCLOUD_HPP_ + +#include + +#include + +#include + +class CudaPointCloud2 : public sensor_msgs::msg::PointCloud2 +{ +public: + void fromROSMsgAsync(const sensor_msgs::msg::PointCloud2 & msg) + { + // cSpell: ignore knzo25 + // NOTE(knzo25): replace this with the cuda blackboard later + header = msg.header; + fields = msg.fields; + height = msg.height; + width = msg.width; + is_bigendian = msg.is_bigendian; + point_step = msg.point_step; + row_step = msg.row_step; + is_dense = msg.is_dense; + + if (!data || capacity_ < msg.data.size()) { + capacity_ = 1024 * (msg.data.size() / 1024 + 1); + data = autoware::cuda_utils::make_unique(capacity_); + } + + cudaMemcpyAsync(data.get(), msg.data.data(), msg.data.size(), cudaMemcpyHostToDevice, stream); + } + + autoware::cuda_utils::CudaUniquePtr data; + cudaStream_t stream; + +private: + std::size_t capacity_{0}; +}; + +#endif // AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UTILS__CUDA_POINTCLOUD_HPP_ diff --git a/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/utils/utils.hpp b/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/utils/utils.hpp index 41c7294ded849..9a9a441af3d60 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/utils/utils.hpp +++ b/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/utils/utils.hpp @@ -16,6 +16,8 @@ #define AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UTILS__UTILS_HPP_ #include "autoware/probabilistic_occupancy_grid_map/cost_value/cost_value.hpp" +#include "autoware/probabilistic_occupancy_grid_map/utils/cuda_pointcloud.hpp" +#include "autoware/probabilistic_occupancy_grid_map/utils/utils_kernel.hpp" #include #include @@ -50,52 +52,12 @@ namespace autoware::occupancy_grid_map namespace utils { -/** - * @brief 3D point struct for sorting and searching - * - */ -struct MyPoint3d -{ - float x; - float y; - float z; - - // constructor - MyPoint3d(float x, float y, float z) : x(x), y(y), z(z) {} - - // calc squared norm - float norm2() const { return powf(x, 2) + powf(y, 2) + powf(z, 2); } - - // calc arctan2 - float arctan2() const { return atan2f(y, x); } - - // overload operator< - bool operator<(const MyPoint3d & other) const - { - const auto a = norm2(); - const auto b = other.norm2(); - if (a == b) { // escape when norm2 is same - return arctan2() < other.arctan2(); - } else { - return a < b; - } - } - - // overload operator== - bool operator==(const MyPoint3d & other) const - { - return fabsf(x - other.x) < FLT_EPSILON && fabsf(y - other.y) < FLT_EPSILON && - fabsf(z - other.z) < FLT_EPSILON; - } -}; - bool transformPointcloud( const sensor_msgs::msg::PointCloud2 & input, const tf2_ros::Buffer & tf2, const std::string & target_frame, sensor_msgs::msg::PointCloud2 & output); -void transformPointcloud( - const sensor_msgs::msg::PointCloud2 & input, const geometry_msgs::msg::Pose & pose, - sensor_msgs::msg::PointCloud2 & output); +bool transformPointcloudAsync( + CudaPointCloud2 & input, const tf2_ros::Buffer & tf2, const std::string & target_frame); Eigen::Matrix4f getTransformMatrix(const geometry_msgs::msg::Pose & pose); @@ -116,10 +78,6 @@ geometry_msgs::msg::Pose getPose( // get inverted pose geometry_msgs::msg::Pose getInversePose(const geometry_msgs::msg::Pose & pose); -bool extractCommonPointCloud( - const sensor_msgs::msg::PointCloud2 & obstacle_pc, const sensor_msgs::msg::PointCloud2 & raw_pc, - sensor_msgs::msg::PointCloud2 & output_obstacle_pc); - } // namespace utils } // namespace autoware::occupancy_grid_map diff --git a/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/utils/utils_kernel.hpp b/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/utils/utils_kernel.hpp new file mode 100644 index 0000000000000..a335a4a6e5b93 --- /dev/null +++ b/perception/autoware_probabilistic_occupancy_grid_map/include/autoware/probabilistic_occupancy_grid_map/utils/utils_kernel.hpp @@ -0,0 +1,52 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UTILS__UTILS_KERNEL_HPP_ +#define AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UTILS__UTILS_KERNEL_HPP_ + +#include + +#include + +#include + +namespace autoware::occupancy_grid_map +{ +namespace utils +{ + +void __device__ setCellValue( + float wx, float wy, float origin_x, float origin_y, float resolution_inv, int size_x, int size_y, + std::uint8_t value, std::uint8_t * costmap_tensor); + +void __device__ raytrace( + const float source_x, const float source_y, const float target_x, const float target_y, + const float origin_x, float origin_y, const float resolution_inv, const int size_x, + const int size_y, const std::uint8_t cost, std::uint8_t * costmap_tensor); + +void copyMapRegionLaunch( + const std::uint8_t * source_map, unsigned int sm_lower_left_x, unsigned int sm_lower_left_y, + unsigned int sm_size_x, unsigned int sm_size_y, std::uint8_t * dest_map, + unsigned int dm_lower_left_x, unsigned int dm_lower_left_y, unsigned int dm_size_x, + unsigned int dm_size_y, unsigned int region_size_x, unsigned int region_size_y, + cudaStream_t stream); + +void transformPointCloudLaunch( + std::uint8_t * points, std::size_t num_points, std::size_t points_step, + const Eigen::Matrix3f & rotation, const Eigen::Vector3f & translation, cudaStream_t stream); + +} // namespace utils +} // namespace autoware::occupancy_grid_map + +#endif // AUTOWARE__PROBABILISTIC_OCCUPANCY_GRID_MAP__UTILS__UTILS_KERNEL_HPP_ diff --git a/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map.cpp b/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map.cpp index 25eafcd564e2d..082985ca824af 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map.cpp +++ b/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map.cpp @@ -65,7 +65,7 @@ using sensor_msgs::PointCloud2ConstIterator; OccupancyGridMap::OccupancyGridMap( const unsigned int cells_size_x, const unsigned int cells_size_y, const float resolution) -: Costmap2D(cells_size_x, cells_size_y, resolution, 0.f, 0.f, cost_value::NO_INFORMATION) +: OccupancyGridMapInterface(false, cells_size_x, cells_size_y, resolution) { } @@ -85,57 +85,6 @@ bool OccupancyGridMap::worldToMap(double wx, double wy, unsigned int & mx, unsig return false; } -void OccupancyGridMap::updateOrigin(double new_origin_x, double new_origin_y) -{ - // project the new origin into the grid - int cell_ox{static_cast(std::floor((new_origin_x - origin_x_) / resolution_))}; - int cell_oy{static_cast(std::floor((new_origin_y - origin_y_) / resolution_))}; - - // compute the associated world coordinates for the origin cell - // because we want to keep things grid-aligned - double new_grid_ox{origin_x_ + cell_ox * resolution_}; - double new_grid_oy{origin_y_ + cell_oy * resolution_}; - - // To save casting from unsigned int to int a bunch of times - int size_x{static_cast(size_x_)}; - int size_y{static_cast(size_y_)}; - - // we need to compute the overlap of the new and existing windows - int lower_left_x{std::min(std::max(cell_ox, 0), size_x)}; - int lower_left_y{std::min(std::max(cell_oy, 0), size_y)}; - int upper_right_x{std::min(std::max(cell_ox + size_x, 0), size_x)}; - int upper_right_y{std::min(std::max(cell_oy + size_y, 0), size_y)}; - - unsigned int cell_size_x = upper_right_x - lower_left_x; - unsigned int cell_size_y = upper_right_y - lower_left_y; - - // we need a map to store the obstacles in the window temporarily - unsigned char * local_map = new unsigned char[cell_size_x * cell_size_y]; - - // copy the local window in the costmap to the local map - copyMapRegion( - costmap_, lower_left_x, lower_left_y, size_x_, local_map, 0, 0, cell_size_x, cell_size_x, - cell_size_y); - - // now we'll set the costmap to be completely unknown if we track unknown space - resetMaps(); - - // update the origin with the appropriate world coordinates - origin_x_ = new_grid_ox; - origin_y_ = new_grid_oy; - - // compute the starting cell location for copying data back in - int start_x{lower_left_x - cell_ox}; - int start_y{lower_left_y - cell_oy}; - - // now we want to copy the overlapping information back into the map, but in its new location - copyMapRegion( - local_map, 0, 0, cell_size_x, costmap_, start_x, start_y, size_x_, cell_size_x, cell_size_y); - - // make sure to clean up - delete[] local_map; -} - void OccupancyGridMap::raytrace2D(const PointCloud2 & pointcloud, const Pose & robot_pose) { // freespace diff --git a/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_base.cpp b/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_base.cpp index 39855ec36260c..f4d290bd70d7c 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_base.cpp +++ b/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_base.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2024 Tier IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -77,34 +77,35 @@ namespace costmap_2d using sensor_msgs::PointCloud2ConstIterator; OccupancyGridMapInterface::OccupancyGridMapInterface( - const unsigned int cells_size_x, const unsigned int cells_size_y, const float resolution) -: Costmap2D(cells_size_x, cells_size_y, resolution, 0.f, 0.f, cost_value::NO_INFORMATION) + const bool use_cuda, const unsigned int cells_size_x, const unsigned int cells_size_y, + const float resolution) +: Costmap2D(cells_size_x, cells_size_y, resolution, 0.f, 0.f, cost_value::NO_INFORMATION), + use_cuda_(use_cuda) { - min_height_ = -std::numeric_limits::infinity(); - max_height_ = std::numeric_limits::infinity(); - resolution_inv_ = 1.0 / resolution_; - offset_initialized_ = false; -} - -inline bool OccupancyGridMapInterface::worldToMap( - double wx, double wy, unsigned int & mx, unsigned int & my) const -{ - if (wx < origin_x_ || wy < origin_y_) { - return false; + if (use_cuda_) { + min_height_ = -std::numeric_limits::infinity(); + max_height_ = std::numeric_limits::infinity(); + resolution_inv_ = 1.0 / resolution_; + + const auto num_cells_x = this->getSizeInCellsX(); + const auto num_cells_y = this->getSizeInCellsY(); + + cudaStreamCreate(&stream_); + device_costmap_ = autoware::cuda_utils::make_unique(num_cells_x * num_cells_y); + device_costmap_aux_ = + autoware::cuda_utils::make_unique(num_cells_x * num_cells_y); + + device_rotation_map_ = autoware::cuda_utils::make_unique(); + device_translation_map_ = autoware::cuda_utils::make_unique(); + device_rotation_scan_ = autoware::cuda_utils::make_unique(); + device_translation_scan_ = autoware::cuda_utils::make_unique(); } - - mx = static_cast(std::floor((wx - origin_x_) * resolution_inv_)); - my = static_cast(std::floor((wy - origin_y_) * resolution_inv_)); - - if (mx < size_x_ && my < size_y_) { - return true; - } - - return false; } void OccupancyGridMapInterface::updateOrigin(double new_origin_x, double new_origin_y) { + using autoware::occupancy_grid_map::utils::copyMapRegionLaunch; + // project the new origin into the grid int cell_ox{static_cast(std::floor((new_origin_x - origin_x_) / resolution_))}; int cell_oy{static_cast(std::floor((new_origin_y - origin_y_) / resolution_))}; @@ -128,15 +129,26 @@ void OccupancyGridMapInterface::updateOrigin(double new_origin_x, double new_ori unsigned int cell_size_y = upper_right_y - lower_left_y; // we need a map to store the obstacles in the window temporarily - unsigned char * local_map = new unsigned char[cell_size_x * cell_size_y]; + unsigned char * local_map{nullptr}; + + if (use_cuda_) { + copyMapRegionLaunch( + device_costmap_.get(), lower_left_x, lower_left_y, size_x_, size_y_, + device_costmap_aux_.get(), 0, 0, cell_size_x, cell_size_y, cell_size_x, cell_size_y, stream_); - // copy the local window in the costmap to the local map - copyMapRegion( - costmap_, lower_left_x, lower_left_y, size_x_, local_map, 0, 0, cell_size_x, cell_size_x, - cell_size_y); + cudaMemset( + device_costmap_.get(), cost_value::NO_INFORMATION, size_x_ * size_y_ * sizeof(std::uint8_t)); + } else { + local_map = new unsigned char[cell_size_x * cell_size_y]; - // now we'll set the costmap to be completely unknown if we track unknown space - resetMaps(); + // copy the local window in the costmap to the local map + copyMapRegion( + costmap_, lower_left_x, lower_left_y, size_x_, local_map, 0, 0, cell_size_x, cell_size_x, + cell_size_y); + + // now we'll set the costmap to be completely unknown if we track unknown space + nav2_costmap_2d::Costmap2D::resetMaps(); + } // update the origin with the appropriate world coordinates origin_x_ = new_grid_ox; @@ -147,93 +159,41 @@ void OccupancyGridMapInterface::updateOrigin(double new_origin_x, double new_ori int start_y{lower_left_y - cell_oy}; // now we want to copy the overlapping information back into the map, but in its new location - copyMapRegion( - local_map, 0, 0, cell_size_x, costmap_, start_x, start_y, size_x_, cell_size_x, cell_size_y); - - // make sure to clean up - delete[] local_map; -} - -void OccupancyGridMapInterface::setCellValue( - const double wx, const double wy, const unsigned char cost) -{ - MarkCell marker(costmap_, cost); - unsigned int mx{}; - unsigned int my{}; - if (!worldToMap(wx, wy, mx, my)) { - RCLCPP_DEBUG(logger_, "Computing map coords failed"); - return; + if (use_cuda_) { + if ( + start_x < 0 || start_y < 0 || start_x + cell_size_x > size_x_ || + start_y + cell_size_y > size_y_) { + RCLCPP_ERROR( + rclcpp::get_logger("pointcloud_based_occupancy_grid_map"), + "update coordinates are negative or out of bounds: start.x=%d, start.y=%d, cell_size.x=%d, " + "cell_size.y=%d size_x:%d, size_y=%d", + start_x, start_y, cell_size_x, cell_size_y, size_x_, size_y_); + return; + } + + copyMapRegionLaunch( + device_costmap_aux_.get(), 0, 0, cell_size_x, cell_size_y, device_costmap_.get(), start_x, + start_y, size_x_, size_y_, cell_size_x, cell_size_y, stream_); + } else { + copyMapRegion( + local_map, 0, 0, cell_size_x, costmap_, start_x, start_y, size_x_, cell_size_x, cell_size_y); + + // make sure to clean up + if (local_map != nullptr) { + delete[] local_map; + } } - const unsigned int index = getIndex(mx, my); - marker(index); } -void OccupancyGridMapInterface::raytrace( - const double source_x, const double source_y, const double target_x, const double target_y, - const unsigned char cost) +void OccupancyGridMapInterface::resetMaps() { - unsigned int x0{}; - unsigned int y0{}; - const double ox{source_x}; - const double oy{source_y}; - if (!worldToMap(ox, oy, x0, y0)) { - RCLCPP_DEBUG( - logger_, - "The origin for the sensor at (%.2f, %.2f) is out of map bounds. So, the costmap cannot " - "raytrace for it.", - ox, oy); - return; - } - - // we can pre-compute the endpoints of the map outside of the inner loop... we'll need these later - const double origin_x = origin_x_, origin_y = origin_y_; - const double map_end_x = origin_x + size_x_ * resolution_; - const double map_end_y = origin_y + size_y_ * resolution_; - - double wx = target_x; - double wy = target_y; - - // now we also need to make sure that the endpoint we're ray-tracing - // to isn't off the costmap and scale if necessary - const double a = wx - ox; - const double b = wy - oy; - - // the minimum value to raytrace from is the origin - if (wx < origin_x) { - const double t = (origin_x - ox) / a; - wx = origin_x; - wy = oy + b * t; + if (use_cuda_) { + cudaMemsetAsync( + device_costmap_.get(), cost_value::NO_INFORMATION, getSizeInCellsX() * getSizeInCellsY(), + stream_); + } else { + nav2_costmap_2d::Costmap2D::resetMaps(); } - if (wy < origin_y) { - const double t = (origin_y - oy) / b; - wx = ox + a * t; - wy = origin_y; - } - - // the maximum value to raytrace to is the end of the map - if (wx > map_end_x) { - const double t = (map_end_x - ox) / a; - wx = map_end_x - .001; - wy = oy + b * t; - } - if (wy > map_end_y) { - const double t = (map_end_y - oy) / b; - wx = ox + a * t; - wy = map_end_y - .001; - } - - // now that the vector is scaled correctly... we'll get the map coordinates of its endpoint - unsigned int x1{}; - unsigned int y1{}; - - // check for legality just in case - if (!worldToMap(wx, wy, x1, y1)) { - return; - } - - constexpr unsigned int cell_raytrace_range = 10000; // large number to ignore range threshold - MarkCell marker(costmap_, cost); - raytraceLine(marker, x0, y0, x1, y1, cell_raytrace_range); } void OccupancyGridMapInterface::setHeightLimit(const double min_height, const double max_height) @@ -242,16 +202,22 @@ void OccupancyGridMapInterface::setHeightLimit(const double min_height, const do max_height_ = max_height; } -void OccupancyGridMapInterface::setFieldOffsets( - const PointCloud2 & input_raw, const PointCloud2 & input_obstacle) +bool OccupancyGridMapInterface::isCudaEnabled() const +{ + return use_cuda_; +} + +const autoware::cuda_utils::CudaUniquePtr & +OccupancyGridMapInterface::getDeviceCostmap() const +{ + return device_costmap_; +} + +void OccupancyGridMapInterface::copyDeviceCostmapToHost() const { - x_offset_raw_ = input_raw.fields[pcl::getFieldIndex(input_raw, "x")].offset; - y_offset_raw_ = input_raw.fields[pcl::getFieldIndex(input_raw, "y")].offset; - z_offset_raw_ = input_raw.fields[pcl::getFieldIndex(input_raw, "z")].offset; - x_offset_obstacle_ = input_obstacle.fields[pcl::getFieldIndex(input_obstacle, "x")].offset; - y_offset_obstacle_ = input_obstacle.fields[pcl::getFieldIndex(input_obstacle, "y")].offset; - z_offset_obstacle_ = input_obstacle.fields[pcl::getFieldIndex(input_obstacle, "z")].offset; - offset_initialized_ = true; + cudaMemcpy( + costmap_, device_costmap_.get(), getSizeInCellsX() * getSizeInCellsY() * sizeof(std::uint8_t), + cudaMemcpyDeviceToHost); } } // namespace costmap_2d diff --git a/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_fixed.cpp b/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_fixed.cpp index da22ef125fb19..97f36f08c48bd 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_fixed.cpp +++ b/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_fixed.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2024 Tier IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -15,8 +15,11 @@ #include "autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_fixed.hpp" #include "autoware/probabilistic_occupancy_grid_map/cost_value/cost_value.hpp" +#include "autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_fixed_kernel.hpp" #include "autoware/probabilistic_occupancy_grid_map/utils/utils.hpp" +#include "autoware/probabilistic_occupancy_grid_map/utils/utils_kernel.hpp" +#include #include #include #include @@ -41,9 +44,24 @@ namespace costmap_2d using sensor_msgs::PointCloud2ConstIterator; OccupancyGridMapFixedBlindSpot::OccupancyGridMapFixedBlindSpot( - const unsigned int cells_size_x, const unsigned int cells_size_y, const float resolution) -: OccupancyGridMapInterface(cells_size_x, cells_size_y, resolution) + const bool use_cuda, const unsigned int cells_size_x, const unsigned int cells_size_y, + const float resolution) +: OccupancyGridMapInterface(use_cuda, cells_size_x, cells_size_y, resolution) { + if (use_cuda_) { + const size_t angle_bin_size = + ((max_angle_ - min_angle_) * angle_increment_inv_) + size_t(1 /*margin*/); + + const auto num_cells_x = this->getSizeInCellsX(); + const auto num_cells_y = this->getSizeInCellsY(); + const std::size_t range_bin_size = + static_cast(std::sqrt(2) * std::max(num_cells_x, num_cells_y) / 2.0) + 1; + + raw_points_tensor_ = + autoware::cuda_utils::make_unique(2 * angle_bin_size * range_bin_size); + obstacle_points_tensor_ = + autoware::cuda_utils::make_unique(2 * angle_bin_size * range_bin_size); + } } /** @@ -55,7 +73,7 @@ OccupancyGridMapFixedBlindSpot::OccupancyGridMapFixedBlindSpot( * @param scan_origin manually chosen grid map origin frame */ void OccupancyGridMapFixedBlindSpot::updateWithPointCloud( - const PointCloud2 & raw_pointcloud, const PointCloud2 & obstacle_pointcloud, + const CudaPointCloud2 & raw_pointcloud, const CudaPointCloud2 & obstacle_pointcloud, const Pose & robot_pose, const Pose & scan_origin) { const size_t angle_bin_size = @@ -69,190 +87,81 @@ void OccupancyGridMapFixedBlindSpot::updateWithPointCloud( // Transform Matrix from map frame to scan frame mat_scan_ = utils::getTransformMatrix(scan2map_pose); - if (!offset_initialized_) { - setFieldOffsets(raw_pointcloud, obstacle_pointcloud); - } - - // Create angle bins and sort by distance - struct BinInfo - { - BinInfo() = default; - BinInfo(const double _range, const double _wx, const double _wy) - : range(_range), wx(_wx), wy(_wy) - { - } - double range{}; - double wx{}; - double wy{}; - }; - - std::vector> obstacle_pointcloud_angle_bins(angle_bin_size); - std::vector> raw_pointcloud_angle_bins(angle_bin_size); - - const size_t raw_pointcloud_size = raw_pointcloud.width * raw_pointcloud.height; - const size_t obstacle_pointcloud_size = obstacle_pointcloud.width * obstacle_pointcloud.height; - - // Reserve a certain amount of memory in advance for performance reasons - const size_t raw_reserve_size = raw_pointcloud_size / angle_bin_size; - const size_t obstacle_reserve_size = obstacle_pointcloud_size / angle_bin_size; - for (size_t i = 0; i < angle_bin_size; i++) { - raw_pointcloud_angle_bins[i].reserve(raw_reserve_size); - obstacle_pointcloud_angle_bins[i].reserve(obstacle_reserve_size); - } - - // Updated every loop inside transformPointAndCalculate() - Eigen::Vector4f pt_map; - int angle_bin_index; - double range; - - size_t global_offset = 0; - for (size_t i = 0; i < raw_pointcloud_size; ++i) { - Eigen::Vector4f pt( - *reinterpret_cast(&raw_pointcloud.data[global_offset + x_offset_raw_]), - *reinterpret_cast(&raw_pointcloud.data[global_offset + y_offset_raw_]), - *reinterpret_cast(&raw_pointcloud.data[global_offset + z_offset_raw_]), 1); - global_offset += raw_pointcloud.point_step; - if (!isPointValid(pt)) { - continue; - } - transformPointAndCalculate(pt, pt_map, angle_bin_index, range); - - raw_pointcloud_angle_bins.at(angle_bin_index).emplace_back(range, pt_map[0], pt_map[1]); - } - - for (auto & raw_pointcloud_angle_bin : raw_pointcloud_angle_bins) { - std::sort(raw_pointcloud_angle_bin.begin(), raw_pointcloud_angle_bin.end(), [](auto a, auto b) { - return a.range < b.range; - }); - } - - // Create obstacle angle bins and sort points by range - global_offset = 0; - for (size_t i = 0; i < obstacle_pointcloud_size; ++i) { - Eigen::Vector4f pt( - *reinterpret_cast( - &obstacle_pointcloud.data[global_offset + x_offset_obstacle_]), - *reinterpret_cast( - &obstacle_pointcloud.data[global_offset + y_offset_obstacle_]), - *reinterpret_cast( - &obstacle_pointcloud.data[global_offset + z_offset_obstacle_]), - 1); - global_offset += obstacle_pointcloud.point_step; - if (!isPointValid(pt)) { - continue; - } - transformPointAndCalculate(pt, pt_map, angle_bin_index, range); - - // Ignore obstacle points exceed the range of the raw points - // No raw point in this angle bin, or obstacle point exceeds the range of the raw points - if ( - raw_pointcloud_angle_bins.at(angle_bin_index).empty() || - range > raw_pointcloud_angle_bins.at(angle_bin_index).back().range) { - continue; - } - obstacle_pointcloud_angle_bins.at(angle_bin_index).emplace_back(range, pt_map[0], pt_map[1]); - } - - for (auto & obstacle_pointcloud_angle_bin : obstacle_pointcloud_angle_bins) { - std::sort( - obstacle_pointcloud_angle_bin.begin(), obstacle_pointcloud_angle_bin.end(), - [](auto a, auto b) { return a.range < b.range; }); - } - - // First step: Initialize cells to the final point with freespace - for (size_t bin_index = 0; bin_index < obstacle_pointcloud_angle_bins.size(); ++bin_index) { - const auto & raw_pointcloud_angle_bin = raw_pointcloud_angle_bins.at(bin_index); - - BinInfo end_distance; - if (raw_pointcloud_angle_bin.empty()) { - continue; - } else { - end_distance = raw_pointcloud_angle_bin.back(); - } - raytrace( - scan_origin.position.x, scan_origin.position.y, end_distance.wx, end_distance.wy, - cost_value::FREE_SPACE); - } - - // Second step: Add unknown cell - for (size_t bin_index = 0; bin_index < obstacle_pointcloud_angle_bins.size(); ++bin_index) { - const auto & obstacle_pointcloud_angle_bin = obstacle_pointcloud_angle_bins.at(bin_index); - const auto & raw_pointcloud_angle_bin = raw_pointcloud_angle_bins.at(bin_index); - auto raw_distance_iter = raw_pointcloud_angle_bin.begin(); - for (size_t dist_index = 0; dist_index < obstacle_pointcloud_angle_bin.size(); ++dist_index) { - // Calculate next raw point from obstacle point - while (raw_distance_iter != raw_pointcloud_angle_bin.end()) { - if ( - raw_distance_iter->range < - obstacle_pointcloud_angle_bin.at(dist_index).range + distance_margin_) - raw_distance_iter++; - else - break; - } - - // There is no point far than the obstacle point. - const bool no_freespace_point = (raw_distance_iter == raw_pointcloud_angle_bin.end()); - - if (dist_index + 1 == obstacle_pointcloud_angle_bin.size()) { - const auto & source = obstacle_pointcloud_angle_bin.at(dist_index); - if (!no_freespace_point) { - const auto & target = *raw_distance_iter; - raytrace(source.wx, source.wy, target.wx, target.wy, cost_value::NO_INFORMATION); - setCellValue(target.wx, target.wy, cost_value::FREE_SPACE); - } - continue; - } - - auto next_obstacle_point_distance = std::abs( - obstacle_pointcloud_angle_bin.at(dist_index + 1).range - - obstacle_pointcloud_angle_bin.at(dist_index).range); - if (next_obstacle_point_distance <= distance_margin_) { - continue; - } else if (no_freespace_point) { - const auto & source = obstacle_pointcloud_angle_bin.at(dist_index); - const auto & target = obstacle_pointcloud_angle_bin.at(dist_index + 1); - raytrace(source.wx, source.wy, target.wx, target.wy, cost_value::NO_INFORMATION); - continue; - } - - auto next_raw_distance = - std::abs(obstacle_pointcloud_angle_bin.at(dist_index).range - raw_distance_iter->range); - if (next_raw_distance < next_obstacle_point_distance) { - const auto & source = obstacle_pointcloud_angle_bin.at(dist_index); - const auto & target = *raw_distance_iter; - raytrace(source.wx, source.wy, target.wx, target.wy, cost_value::NO_INFORMATION); - setCellValue(target.wx, target.wy, cost_value::FREE_SPACE); - continue; - } else { - const auto & source = obstacle_pointcloud_angle_bin.at(dist_index); - const auto & target = obstacle_pointcloud_angle_bin.at(dist_index + 1); - raytrace(source.wx, source.wy, target.wx, target.wy, cost_value::NO_INFORMATION); - continue; - } - } - } - - // Third step: Overwrite occupied cell - for (const auto & obstacle_pointcloud_angle_bin : obstacle_pointcloud_angle_bins) { - for (size_t dist_index = 0; dist_index < obstacle_pointcloud_angle_bin.size(); ++dist_index) { - const auto & obstacle_point = obstacle_pointcloud_angle_bin.at(dist_index); - setCellValue(obstacle_point.wx, obstacle_point.wy, cost_value::LETHAL_OBSTACLE); - - if (dist_index + 1 == obstacle_pointcloud_angle_bin.size()) { - continue; - } - - auto next_obstacle_point_distance = std::abs( - obstacle_pointcloud_angle_bin.at(dist_index + 1).range - - obstacle_pointcloud_angle_bin.at(dist_index).range); - if (next_obstacle_point_distance <= distance_margin_) { - const auto & source = obstacle_pointcloud_angle_bin.at(dist_index); - const auto & target = obstacle_pointcloud_angle_bin.at(dist_index + 1); - raytrace(source.wx, source.wy, target.wx, target.wy, cost_value::LETHAL_OBSTACLE); - continue; - } - } - } + const auto map_res = this->getResolution(); + const auto num_cells_x = this->getSizeInCellsX(); + const auto num_cells_y = this->getSizeInCellsY(); + const std::size_t range_bin_size = + static_cast(std::sqrt(2) * std::max(num_cells_x, num_cells_y) / 2.0) + 1; + + cudaMemsetAsync( + raw_points_tensor_.get(), 0xFF, 2 * angle_bin_size * range_bin_size * sizeof(std::int64_t), + stream_); + cudaMemsetAsync( + obstacle_points_tensor_.get(), 0xFF, 2 * angle_bin_size * range_bin_size * sizeof(std::int64_t), + stream_); + cudaMemsetAsync( + device_costmap_.get(), cost_value::NO_INFORMATION, + num_cells_x * num_cells_y * sizeof(std::uint8_t), stream_); + + Eigen::Matrix3f rotation_map = mat_map_.block<3, 3>(0, 0); + Eigen::Vector3f translation_map = mat_map_.block<3, 1>(0, 3); + + Eigen::Matrix3f rotation_scan = mat_scan_.block<3, 3>(0, 0); + Eigen::Vector3f translation_scan = mat_scan_.block<3, 1>(0, 3); + + cudaMemcpyAsync( + device_rotation_map_.get(), &rotation_map, sizeof(Eigen::Matrix3f), cudaMemcpyHostToDevice, + stream_); + cudaMemcpyAsync( + device_translation_map_.get(), &translation_map, sizeof(Eigen::Vector3f), + cudaMemcpyHostToDevice, stream_); + cudaMemcpyAsync( + device_rotation_scan_.get(), &rotation_scan, sizeof(Eigen::Matrix3f), cudaMemcpyHostToDevice, + stream_); + cudaMemcpyAsync( + device_translation_scan_.get(), &translation_scan, sizeof(Eigen::Vector3f), + cudaMemcpyHostToDevice, stream_); + + const std::size_t num_raw_points = raw_pointcloud.width * raw_pointcloud.height; + float range_resolution_inv = 1.0 / map_res; + + cudaStreamSynchronize(stream_); + + map_fixed::prepareTensorLaunch( + reinterpret_cast(raw_pointcloud.data.get()), num_raw_points, + raw_pointcloud.point_step / sizeof(float), angle_bin_size, range_bin_size, min_height_, + max_height_, min_angle_, angle_increment_inv_, range_resolution_inv, device_rotation_map_.get(), + device_translation_map_.get(), device_rotation_scan_.get(), device_translation_scan_.get(), + raw_points_tensor_.get(), raw_pointcloud.stream); + + const std::size_t num_obstacle_points = obstacle_pointcloud.width * obstacle_pointcloud.height; + + map_fixed::prepareTensorLaunch( + reinterpret_cast(obstacle_pointcloud.data.get()), num_obstacle_points, + obstacle_pointcloud.point_step / sizeof(float), angle_bin_size, range_bin_size, min_height_, + max_height_, min_angle_, angle_increment_inv_, range_resolution_inv, device_rotation_map_.get(), + device_translation_map_.get(), device_rotation_scan_.get(), device_translation_scan_.get(), + obstacle_points_tensor_.get(), obstacle_pointcloud.stream); + + map_fixed::fillEmptySpaceLaunch( + raw_points_tensor_.get(), angle_bin_size, range_bin_size, range_resolution_inv, + scan_origin.position.x, scan_origin.position.y, origin_x_, origin_y_, num_cells_x, num_cells_y, + cost_value::FREE_SPACE, device_costmap_.get(), raw_pointcloud.stream); + + cudaStreamSynchronize(obstacle_pointcloud.stream); + + map_fixed::fillUnknownSpaceLaunch( + raw_points_tensor_.get(), obstacle_points_tensor_.get(), distance_margin_, angle_bin_size, + range_bin_size, range_resolution_inv, scan_origin.position.x, scan_origin.position.y, origin_x_, + origin_y_, num_cells_x, num_cells_y, cost_value::FREE_SPACE, cost_value::NO_INFORMATION, + device_costmap_.get(), raw_pointcloud.stream); + + map_fixed::fillObstaclesLaunch( + obstacle_points_tensor_.get(), distance_margin_, angle_bin_size, range_bin_size, + range_resolution_inv, origin_x_, origin_y_, num_cells_x, num_cells_y, + cost_value::LETHAL_OBSTACLE, device_costmap_.get(), raw_pointcloud.stream); + + cudaStreamSynchronize(raw_pointcloud.stream); } void OccupancyGridMapFixedBlindSpot::initRosParam(rclcpp::Node & node) diff --git a/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_fixed_kernel.cu b/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_fixed_kernel.cu new file mode 100644 index 0000000000000..3614e025875a3 --- /dev/null +++ b/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_fixed_kernel.cu @@ -0,0 +1,388 @@ +// Copyright 2024 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_fixed_kernel.hpp" +#include "autoware/probabilistic_occupancy_grid_map/utils/utils_kernel.hpp" + +#include +#include + +#include +#include + +namespace autoware::occupancy_grid_map +{ +namespace costmap_2d::map_fixed +{ + +static constexpr float RANGE_DISCRETIZATION_RESOLUTION = 0.001f; + +__global__ void prepareTensorKernel( + const float * __restrict__ input_pointcloud, const std::size_t num_points, + const std::size_t points_step, const std::size_t angle_bins, const std::size_t range_bins, + const float min_height, const float max_height, const float min_angle, + const float angle_increment_inv, const float range_resolution_inv, + const Eigen::Matrix3f * __restrict__ rotation_map, + const Eigen::Vector3f * __restrict__ translation_map, + const Eigen::Matrix3f * __restrict__ rotation_scan, + const Eigen::Vector3f * __restrict__ translation_scan, std::uint64_t * __restrict__ points_tensor) +{ + int idx = blockIdx.x * blockDim.x + threadIdx.x; + if (idx >= num_points) { + return; + } + + Eigen::Map point(input_pointcloud + idx * points_step); + + if ( + point.z() > max_height || point.z() < min_height || !isfinite(point.x()) || + !isfinite(point.y()) || !isfinite(point.z())) { + return; + } + + Eigen::Vector3f map_point = (*rotation_map) * point + (*translation_map); + Eigen::Vector3f scan_point = (*rotation_scan) * map_point + (*translation_scan); + + float angle = atan2(scan_point.y(), scan_point.x()); + int angle_bin_index = static_cast((angle - min_angle) * angle_increment_inv); + float range = sqrt(scan_point.y() * scan_point.y() + scan_point.x() * scan_point.x()); + int range_bin_index = static_cast(range * range_resolution_inv); + + if ( + angle_bin_index < 0 || angle_bin_index >= angle_bins || range_bin_index < 0 || + range_bin_index >= range_bins) { + return; + } + + std::uint64_t range_int = static_cast(range / RANGE_DISCRETIZATION_RESOLUTION); + std::uint32_t world_x_int = __float_as_uint(map_point.x()); + std::uint32_t world_y_int = __float_as_uint(map_point.y()); + + // Can not use std::uint64_t for cuda reasons... + static_assert( + sizeof(std::uint64_t) == sizeof(unsigned long long int), + "unsigned long long int is not 8 bytes"); + unsigned long long int range_and_x_int = (range_int << 32) | world_x_int; + unsigned long long int range_and_y_int = (range_int << 32) | world_y_int; + + std::uint64_t * element_address = + points_tensor + 2 * (angle_bin_index * range_bins + range_bin_index); + + atomicMin(reinterpret_cast(element_address), range_and_x_int); + atomicMin(reinterpret_cast(element_address + 1), range_and_y_int); +} + +__global__ void fillEmptySpaceKernel( + const std::uint64_t * __restrict__ points_tensor, const std::size_t angle_bins, + const std::size_t range_bins, const float map_resolution_inv, const float scan_origin_x, + const float scan_origin_y, const float map_origin_x, const float map_origin_y, + const int num_cells_x, const int num_cells_y, std::uint8_t empty_value, + std::uint8_t * __restrict__ costmap_tensor) +{ + int idx = blockIdx.x * blockDim.x + threadIdx.x; + if (idx >= angle_bins * range_bins) return; + + int angle_bin_index = idx / range_bins; + int range_bin_index = idx % range_bins; + + std::uint64_t range_and_x = + points_tensor[2 * (angle_bin_index * range_bins + range_bin_index) + 0]; + std::uint32_t range_int = range_and_x >> 32; + + if (range_int == 0xFFFFFFFF) { + return; + } + + std::uint64_t range_and_y = + points_tensor[2 * (angle_bin_index * range_bins + range_bin_index) + 1]; + float world_x = __uint_as_float(range_and_x & 0xFFFFFFFF); + float world_y = __uint_as_float(range_and_y & 0xFFFFFFFF); + + if (world_x < map_origin_x || world_y < map_origin_y) { + return; + } + + autoware::occupancy_grid_map::utils::raytrace( + scan_origin_x, scan_origin_y, world_x, world_y, map_origin_x, map_origin_y, map_resolution_inv, + num_cells_x, num_cells_y, empty_value, costmap_tensor); +} + +__global__ void fillUnknownSpaceKernel( + const std::uint64_t * __restrict__ raw_points_tensor, + const std::uint64_t * __restrict__ obstacle_points_tensor, const float distance_margin, + const std::size_t angle_bins, const std::size_t range_bins, const float map_resolution_inv, + const float scan_origin_x, const float scan_origin_y, const float map_origin_x, + const float map_origin_y, const int num_cells_x, const int num_cells_y, + std::uint8_t free_space_value, std::uint8_t no_information_value, + std::uint8_t * __restrict__ costmap_tensor) +{ + int idx = blockIdx.x * blockDim.x + threadIdx.x; + if (idx >= angle_bins * range_bins) return; + + int angle_bin_index = idx / range_bins; + int range_bin_index = idx % range_bins; + + std::uint64_t obs_range_and_x = + obstacle_points_tensor[2 * (angle_bin_index * range_bins + range_bin_index) + 0]; + std::uint64_t obs_range_and_y = + obstacle_points_tensor[2 * (angle_bin_index * range_bins + range_bin_index) + 1]; + std::uint32_t obs_range_int = obs_range_and_x >> 32; + float obs_range = obs_range_int * RANGE_DISCRETIZATION_RESOLUTION; + float obs_world_x = __uint_as_float(obs_range_and_x & 0xFFFFFFFF); + float obs_world_y = __uint_as_float(obs_range_and_y & 0xFFFFFFFF); + + if (obs_range_int == 0xFFFFFFFF || obs_world_x < map_origin_x || obs_world_y < map_origin_y) { + return; + } + + int next_raw_range_bin_index = range_bin_index + 1; + int next_obs_range_bin_index = range_bin_index + 1; + + for (; next_raw_range_bin_index < range_bins; next_raw_range_bin_index++) { + std::uint64_t next_raw_range_and_x = + raw_points_tensor[2 * (angle_bin_index * range_bins + next_raw_range_bin_index) + 0]; + std::uint32_t next_raw_range_int = next_raw_range_and_x >> 32; + float next_raw_range = next_raw_range_int * RANGE_DISCRETIZATION_RESOLUTION; + + if (next_raw_range_int != 0xFFFFFFFF && abs(next_raw_range - obs_range) > distance_margin) { + break; + } + } + + for (; next_obs_range_bin_index < range_bins; next_obs_range_bin_index++) { + std::uint64_t next_obs_range_and_x = + obstacle_points_tensor[2 * (angle_bin_index * range_bins + next_obs_range_bin_index) + 0]; + std::uint32_t next_obs_range_int = next_obs_range_and_x >> 32; + + if (next_obs_range_int != 0xFFFFFFFF) { + break; + } + } + + const std::uint64_t next_obs_range_and_x = + obstacle_points_tensor[2 * (angle_bin_index * range_bins + next_obs_range_bin_index) + 0]; + const std::uint64_t next_obs_range_and_y = + obstacle_points_tensor[2 * (angle_bin_index * range_bins + next_obs_range_bin_index) + 1]; + const std::uint32_t next_obs_range_int = next_obs_range_and_x >> 32; + const float next_obs_world_x = __uint_as_float(next_obs_range_and_x & 0xFFFFFFFF); + const float next_obs_world_y = __uint_as_float(next_obs_range_and_y & 0xFFFFFFFF); + + const std::uint64_t next_raw_range_and_x = + raw_points_tensor[2 * (angle_bin_index * range_bins + next_raw_range_bin_index) + 0]; + const std::uint64_t next_raw_range_and_y = + raw_points_tensor[2 * (angle_bin_index * range_bins + next_raw_range_bin_index) + 1]; + const std::uint32_t next_raw_range_int = next_raw_range_and_x >> 32; + const float next_raw_world_x = __uint_as_float(next_raw_range_and_x & 0xFFFFFFFF); + const float next_raw_world_y = __uint_as_float(next_raw_range_and_y & 0xFFFFFFFF); + + if (next_obs_range_int == 0xFFFFFFFF) { + if ( + next_raw_range_int == 0xFFFFFFFF || next_raw_world_x < map_origin_x || + next_raw_world_y < map_origin_y) { + return; + } + + // if there is no more obstacles after the current one but there are more raw points + // the space between the current obstacle and the next raw point flagged as no_information_value + autoware::occupancy_grid_map::utils::raytrace( + obs_world_x, obs_world_y, next_raw_world_x, next_raw_world_y, map_origin_x, map_origin_y, + map_resolution_inv, num_cells_x, num_cells_y, no_information_value, costmap_tensor); + + autoware::occupancy_grid_map::utils::setCellValue( + next_raw_world_x, next_raw_world_y, map_origin_x, map_origin_y, map_resolution_inv, + num_cells_x, num_cells_y, free_space_value, costmap_tensor); + return; + } + + float next_obs_range = next_obs_range_int * RANGE_DISCRETIZATION_RESOLUTION; + float obs_to_obs_distance = next_obs_range - obs_range; + + if (obs_to_obs_distance <= distance_margin) { + return; + } else if (next_raw_range_int == 0xFFFFFFFF) { + // fill with no information between obstacles + + if (next_obs_world_x < map_origin_x || next_obs_world_y < map_origin_y) { + return; + } + + autoware::occupancy_grid_map::utils::raytrace( + obs_world_x, obs_world_y, next_obs_world_x, next_obs_world_y, map_origin_x, map_origin_y, + map_resolution_inv, num_cells_x, num_cells_y, no_information_value, costmap_tensor); + + return; + } + + float next_raw_range = next_raw_range_int * RANGE_DISCRETIZATION_RESOLUTION; + float raw_to_obs_distance = abs(next_raw_range - obs_range); + + if (raw_to_obs_distance < obs_to_obs_distance) { + // fill with free space between raw and obstacle + + if (next_raw_world_x < map_origin_x || next_raw_world_y < map_origin_y) { + return; + } + + autoware::occupancy_grid_map::utils::raytrace( + obs_world_x, obs_world_y, next_raw_world_x, next_raw_world_y, map_origin_x, map_origin_y, + map_resolution_inv, num_cells_x, num_cells_y, no_information_value, costmap_tensor); + + autoware::occupancy_grid_map::utils::setCellValue( + next_raw_world_x, next_raw_world_y, map_origin_x, map_origin_y, map_resolution_inv, + num_cells_x, num_cells_y, free_space_value, costmap_tensor); + return; + } else { + // fill with no information between obstacles + + if (next_obs_world_x < map_origin_x || next_obs_world_y < map_origin_y) { + return; + } + + autoware::occupancy_grid_map::utils::raytrace( + obs_world_x, obs_world_y, next_obs_world_x, next_obs_world_y, map_origin_x, map_origin_y, + map_resolution_inv, num_cells_x, num_cells_y, no_information_value, costmap_tensor); + + return; + } +} + +__global__ void fillObstaclesKernel( + const std::uint64_t * __restrict__ obstacle_points_tensor, const float distance_margin, + const std::size_t angle_bins, const std::size_t range_bins, const float map_resolution_inv, + const float map_origin_x, const float map_origin_y, const int num_cells_x, const int num_cells_y, + std::uint8_t obstacle_value, std::uint8_t * __restrict__ costmap_tensor) +{ + int idx = blockIdx.x * blockDim.x + threadIdx.x; + if (idx >= angle_bins * range_bins) return; + + int angle_bin_index = idx / range_bins; + int range_bin_index = idx % range_bins; + + std::uint64_t range_and_x = + obstacle_points_tensor[2 * (angle_bin_index * range_bins + range_bin_index) + 0]; + std::uint64_t range_and_y = + obstacle_points_tensor[2 * (angle_bin_index * range_bins + range_bin_index) + 1]; + + std::uint32_t range_int = range_and_x >> 32; + float range = range_int * RANGE_DISCRETIZATION_RESOLUTION; + float world_x = __uint_as_float(range_and_x & 0xFFFFFFFF); + float world_y = __uint_as_float(range_and_y & 0xFFFFFFFF); + + if (range < 0.0 || range_int == 0xFFFFFFFF) { + return; + } + + autoware::occupancy_grid_map::utils::setCellValue( + world_x, world_y, map_origin_x, map_origin_y, map_resolution_inv, num_cells_x, num_cells_y, + obstacle_value, costmap_tensor); + + // Look for the next obstacle point + int next_obs_range_bin_index = range_bin_index + 1; + for (; next_obs_range_bin_index < range_bins; next_obs_range_bin_index++) { + std::uint64_t next_obs_range_and_x = + obstacle_points_tensor[2 * (angle_bin_index * range_bins + next_obs_range_bin_index) + 0]; + std::uint32_t next_obs_range_int = next_obs_range_and_x >> 32; + + if (next_obs_range_int != 0xFFFFFFFF) { + break; + } + } + + std::uint64_t next_obs_range_and_x = + obstacle_points_tensor[2 * (angle_bin_index * range_bins + range_bin_index) + 0]; + std::uint64_t next_obs_range_and_y = + obstacle_points_tensor[2 * (angle_bin_index * range_bins + range_bin_index) + 1]; + + std::uint32_t next_obs_range_int = next_obs_range_and_x >> 32; + float next_obs_range = next_obs_range_int * RANGE_DISCRETIZATION_RESOLUTION; + float next_obs_world_x = __uint_as_float(next_obs_range_and_x & 0xFFFFFFFF); + float next_obs_world_y = __uint_as_float(next_obs_range_and_y & 0xFFFFFFFF); + + if (next_obs_range_int == 0xFFFFFFFF || abs(next_obs_range - range) > distance_margin) { + return; + } + + if (next_obs_world_x < map_origin_x || next_obs_world_y < map_origin_y) { + return; + } + + autoware::occupancy_grid_map::utils::raytrace( + world_x, world_y, next_obs_world_x, next_obs_world_y, map_origin_x, map_origin_y, + map_resolution_inv, num_cells_x, num_cells_y, obstacle_value, costmap_tensor); +} + +void prepareTensorLaunch( + const float * input_pointcloud, const std::size_t num_points, const std::size_t points_step, + const std::size_t angle_bins, const std::size_t range_bins, const float min_height, + const float max_height, const float min_angle, const float angle_increment_inv, + const float range_resolution_inv, const Eigen::Matrix3f * rotation_map, + const Eigen::Vector3f * translation_map, const Eigen::Matrix3f * rotation_scan, + const Eigen::Vector3f * translation_scan, std::uint64_t * points_tensor, cudaStream_t stream) +{ + const int threadsPerBlock = 256; + const int blocksPerGrid = (num_points + threadsPerBlock - 1) / threadsPerBlock; + + prepareTensorKernel<<>>( + input_pointcloud, num_points, points_step, angle_bins, range_bins, min_height, max_height, + min_angle, angle_increment_inv, range_resolution_inv, rotation_map, translation_map, + rotation_scan, translation_scan, points_tensor); +} + +void fillEmptySpaceLaunch( + const std::uint64_t * points_tensor, const std::size_t angle_bins, const std::size_t range_bins, + const float map_resolution_inv, const float scan_origin_x, const float scan_origin_y, + const float map_origin_x, const float map_origin_y, const int num_cells_x, const int num_cells_y, + std::uint8_t empty_value, std::uint8_t * costmap_tensor, cudaStream_t stream) +{ + const int threadsPerBlock = 256; + const int blocksPerGrid = (angle_bins * range_bins + threadsPerBlock - 1) / threadsPerBlock; + + fillEmptySpaceKernel<<>>( + points_tensor, angle_bins, range_bins, map_resolution_inv, scan_origin_x, scan_origin_y, + map_origin_x, map_origin_y, num_cells_x, num_cells_y, empty_value, costmap_tensor); +} + +void fillUnknownSpaceLaunch( + const std::uint64_t * raw_points_tensor, const std::uint64_t * obstacle_points_tensor, + const float distance_margin, const std::size_t angle_bins, const std::size_t range_bins, + const float map_resolution_inv, const float scan_origin_x, const float scan_origin_y, + const float map_origin_x, const float map_origin_y, const int num_cells_x, const int num_cells_y, + std::uint8_t free_space_value, std::uint8_t no_information_value, std::uint8_t * costmap_tensor, + cudaStream_t stream) +{ + const int threadsPerBlock = 256; + const int blocksPerGrid = (angle_bins * range_bins + threadsPerBlock - 1) / threadsPerBlock; + + fillUnknownSpaceKernel<<>>( + raw_points_tensor, obstacle_points_tensor, distance_margin, angle_bins, range_bins, + map_resolution_inv, scan_origin_x, scan_origin_y, map_origin_x, map_origin_y, num_cells_x, + num_cells_y, free_space_value, no_information_value, costmap_tensor); +} + +void fillObstaclesLaunch( + const std::uint64_t * obstacle_points_tensor, const float distance_margin, + const std::size_t angle_bins, const std::size_t range_bins, const float map_resolution_inv, + const float map_origin_x, const float map_origin_y, const int num_cells_x, const int num_cells_y, + std::uint8_t obstacle_value, std::uint8_t * costmap_tensor, cudaStream_t stream) +{ + const int threadsPerBlock = 256; + const int blocksPerGrid = (angle_bins * range_bins + threadsPerBlock - 1) / threadsPerBlock; + + fillObstaclesKernel<<>>( + obstacle_points_tensor, distance_margin, angle_bins, range_bins, map_resolution_inv, + map_origin_x, map_origin_y, num_cells_x, num_cells_y, obstacle_value, costmap_tensor); +} + +} // namespace costmap_2d::map_fixed +} // namespace autoware::occupancy_grid_map diff --git a/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_projective.cpp b/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_projective.cpp index 4f5b8b8eeabed..5bc30872fcf70 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_projective.cpp +++ b/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_projective.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2024 Tier IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -15,23 +15,17 @@ #include "autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_projective.hpp" #include "autoware/probabilistic_occupancy_grid_map/cost_value/cost_value.hpp" +#include "autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_projective_kernel.hpp" #include "autoware/probabilistic_occupancy_grid_map/utils/utils.hpp" #include #include #include #include - -#include - -#ifdef ROS_DISTRO_GALACTIC -#include -#include -#else #include +#include #include -#endif #include @@ -42,9 +36,25 @@ namespace costmap_2d using sensor_msgs::PointCloud2ConstIterator; OccupancyGridMapProjectiveBlindSpot::OccupancyGridMapProjectiveBlindSpot( - const unsigned int cells_size_x, const unsigned int cells_size_y, const float resolution) -: OccupancyGridMapInterface(cells_size_x, cells_size_y, resolution) + const bool use_cuda, const unsigned int cells_size_x, const unsigned int cells_size_y, + const float resolution) +: OccupancyGridMapInterface(use_cuda, cells_size_x, cells_size_y, resolution) { + if (use_cuda) { + const size_t angle_bin_size = + ((max_angle_ - min_angle_) * angle_increment_inv_) + size_t(1 /*margin*/); + + const auto num_cells_x = this->getSizeInCellsX(); + const auto num_cells_y = this->getSizeInCellsY(); + const std::size_t range_bin_size = + static_cast(std::sqrt(2) * std::max(num_cells_x, num_cells_y) / 2.0) + 1; + + raw_points_tensor_ = + autoware::cuda_utils::make_unique(7 * angle_bin_size * range_bin_size); + obstacle_points_tensor_ = + autoware::cuda_utils::make_unique(7 * angle_bin_size * range_bin_size); + device_translation_scan_origin_ = autoware::cuda_utils::make_unique(); + } } /** @@ -56,7 +66,7 @@ OccupancyGridMapProjectiveBlindSpot::OccupancyGridMapProjectiveBlindSpot( * @param scan_origin manually chosen grid map origin frame */ void OccupancyGridMapProjectiveBlindSpot::updateWithPointCloud( - const PointCloud2 & raw_pointcloud, const PointCloud2 & obstacle_pointcloud, + const CudaPointCloud2 & raw_pointcloud, const CudaPointCloud2 & obstacle_pointcloud, const Pose & robot_pose, const Pose & scan_origin) { const size_t angle_bin_size = @@ -67,262 +77,96 @@ void OccupancyGridMapProjectiveBlindSpot::updateWithPointCloud( const auto scan2map_pose = utils::getInversePose(scan_origin); // scan -> map transform pose - // Transform from map frame to scan frame + // Transform Matrix from map frame to scan frame mat_scan_ = utils::getTransformMatrix(scan2map_pose); - if (!offset_initialized_) { - setFieldOffsets(raw_pointcloud, obstacle_pointcloud); - } - - // Create angle bins and sort points by range - struct BinInfo3D - { - explicit BinInfo3D( - const double _range = 0.0, const double _wx = 0.0, const double _wy = 0.0, - const double _wz = 0.0, const double _projection_length = 0.0, - const double _projected_wx = 0.0, const double _projected_wy = 0.0) - : range(_range), - wx(_wx), - wy(_wy), - wz(_wz), - projection_length(_projection_length), - projected_wx(_projected_wx), - projected_wy(_projected_wy) - { - } - double range; - double wx; - double wy; - double wz; - double projection_length; - double projected_wx; - double projected_wy; - }; - - std::vector> obstacle_pointcloud_angle_bins(angle_bin_size); - std::vector> raw_pointcloud_angle_bins(angle_bin_size); - - const size_t raw_pointcloud_size = raw_pointcloud.width * raw_pointcloud.height; - const size_t obstacle_pointcloud_size = obstacle_pointcloud.width * obstacle_pointcloud.height; - - // Updated every loop inside transformPointAndCalculate() - Eigen::Vector4f pt_map; - int angle_bin_index; - double range; - - size_t global_offset = 0; - for (size_t i = 0; i < raw_pointcloud_size; i++) { - Eigen::Vector4f pt( - *reinterpret_cast(&raw_pointcloud.data[global_offset + x_offset_raw_]), - *reinterpret_cast(&raw_pointcloud.data[global_offset + y_offset_raw_]), - *reinterpret_cast(&raw_pointcloud.data[global_offset + z_offset_raw_]), 1); - global_offset += raw_pointcloud.point_step; - if (!isPointValid(pt)) { - continue; - } - transformPointAndCalculate(pt, pt_map, angle_bin_index, range); - - raw_pointcloud_angle_bins.at(angle_bin_index) - .emplace_back(range, pt_map[0], pt_map[1], pt_map[2]); - } - - for (auto & raw_pointcloud_angle_bin : raw_pointcloud_angle_bins) { - std::sort(raw_pointcloud_angle_bin.begin(), raw_pointcloud_angle_bin.end(), [](auto a, auto b) { - return a.range < b.range; - }); - } - - // Create obstacle angle bins and sort points by range - global_offset = 0; - for (size_t i = 0; i < obstacle_pointcloud_size; i++) { - Eigen::Vector4f pt( - *reinterpret_cast( - &obstacle_pointcloud.data[global_offset + x_offset_obstacle_]), - *reinterpret_cast( - &obstacle_pointcloud.data[global_offset + y_offset_obstacle_]), - *reinterpret_cast( - &obstacle_pointcloud.data[global_offset + z_offset_obstacle_]), - 1); - global_offset += obstacle_pointcloud.point_step; - if (!isPointValid(pt)) { - continue; - } - transformPointAndCalculate(pt, pt_map, angle_bin_index, range); - const double scan_z = scan_origin.position.z - robot_pose.position.z; - const double obstacle_z = (pt_map[2]) - robot_pose.position.z; - const double dz = scan_z - obstacle_z; - - // Ignore obstacle points exceed the range of the raw points - // No raw point in this angle bin, or obstacle point exceeds the range of the raw points - if ( - raw_pointcloud_angle_bins.at(angle_bin_index).empty() || - range > raw_pointcloud_angle_bins.at(angle_bin_index).back().range) { - continue; - } - - if (dz > projection_dz_threshold_) { - const double ratio = obstacle_z / dz; - const double projection_length = range * ratio; - const double projected_wx = (pt_map[0]) + ((pt_map[0]) - scan_origin.position.x) * ratio; - const double projected_wy = (pt_map[1]) + ((pt_map[1]) - scan_origin.position.y) * ratio; - obstacle_pointcloud_angle_bins.at(angle_bin_index) - .emplace_back( - range, pt_map[0], pt_map[1], pt_map[2], projection_length, projected_wx, projected_wy); - } else { - obstacle_pointcloud_angle_bins.at(angle_bin_index) - .emplace_back( - range, pt_map[0], pt_map[1], pt_map[2], std::numeric_limits::infinity(), - std::numeric_limits::infinity(), std::numeric_limits::infinity()); - } - } - - for (auto & obstacle_pointcloud_angle_bin : obstacle_pointcloud_angle_bins) { - std::sort( - obstacle_pointcloud_angle_bin.begin(), obstacle_pointcloud_angle_bin.end(), - [](auto a, auto b) { return a.range < b.range; }); - } - - grid_map::Costmap2DConverter converter; - if (pub_debug_grid_) { - debug_grid_.clearAll(); - debug_grid_.setFrameId("map"); - debug_grid_.setGeometry( - grid_map::Length(size_x_ * resolution_, size_y_ * resolution_), resolution_, - grid_map::Position( - origin_x_ + size_x_ * resolution_ / 2.0, origin_y_ + size_y_ * resolution_ / 2.0)); - } - - auto is_visible_beyond_obstacle = [&](const BinInfo3D & obstacle, const BinInfo3D & raw) -> bool { - if (raw.range < obstacle.range) { - return false; - } - - if (std::isinf(obstacle.projection_length)) { - return false; - } - - // y = ax + b - const double a = -(scan_origin.position.z - robot_pose.position.z) / - (obstacle.range + obstacle.projection_length); - const double b = scan_origin.position.z; - return raw.wz > (a * raw.range + b); - }; - - // First step: Initialize cells to the final point with freespace - for (size_t bin_index = 0; bin_index < obstacle_pointcloud_angle_bins.size(); ++bin_index) { - const auto & raw_pointcloud_angle_bin = raw_pointcloud_angle_bins.at(bin_index); - - BinInfo3D ray_end; - if (raw_pointcloud_angle_bin.empty()) { - continue; - } else { - ray_end = raw_pointcloud_angle_bin.back(); - } - raytrace( - scan_origin.position.x, scan_origin.position.y, ray_end.wx, ray_end.wy, - cost_value::FREE_SPACE); - } - - if (pub_debug_grid_) - converter.addLayerFromCostmap2D(*this, "filled_free_to_farthest", debug_grid_); - - // Second step: Add unknown cell - for (size_t bin_index = 0; bin_index < obstacle_pointcloud_angle_bins.size(); ++bin_index) { - const auto & obstacle_pointcloud_angle_bin = obstacle_pointcloud_angle_bins.at(bin_index); - const auto & raw_pointcloud_angle_bin = raw_pointcloud_angle_bins.at(bin_index); - auto raw_distance_iter = raw_pointcloud_angle_bin.begin(); - for (size_t dist_index = 0; dist_index < obstacle_pointcloud_angle_bin.size(); ++dist_index) { - // Calculate next raw point from obstacle point - const auto & obstacle_bin = obstacle_pointcloud_angle_bin.at(dist_index); - while (raw_distance_iter != raw_pointcloud_angle_bin.end()) { - if (!is_visible_beyond_obstacle(obstacle_bin, *raw_distance_iter)) - raw_distance_iter++; - else - break; - } - - // There is no point farther than the obstacle point. - const bool no_visible_point_beyond = (raw_distance_iter == raw_pointcloud_angle_bin.end()); - if (no_visible_point_beyond) { - const auto & source = obstacle_pointcloud_angle_bin.at(dist_index); - raytrace( - source.wx, source.wy, source.projected_wx, source.projected_wy, - cost_value::NO_INFORMATION); - break; - } - - if (dist_index + 1 == obstacle_pointcloud_angle_bin.size()) { - const auto & source = obstacle_pointcloud_angle_bin.at(dist_index); - raytrace( - source.wx, source.wy, source.projected_wx, source.projected_wy, - cost_value::NO_INFORMATION); - continue; - } - - auto next_obstacle_point_distance = std::abs( - obstacle_pointcloud_angle_bin.at(dist_index + 1).range - - obstacle_pointcloud_angle_bin.at(dist_index).range); - if (next_obstacle_point_distance <= obstacle_separation_threshold_) { - continue; - } - - auto next_raw_distance = - std::abs(obstacle_pointcloud_angle_bin.at(dist_index).range - raw_distance_iter->range); - if (next_raw_distance < next_obstacle_point_distance) { - const auto & source = obstacle_pointcloud_angle_bin.at(dist_index); - const auto & target = *raw_distance_iter; - raytrace(source.wx, source.wy, target.wx, target.wy, cost_value::NO_INFORMATION); - setCellValue(target.wx, target.wy, cost_value::FREE_SPACE); - continue; - } else { - const auto & source = obstacle_pointcloud_angle_bin.at(dist_index); - const auto & target = obstacle_pointcloud_angle_bin.at(dist_index + 1); - raytrace(source.wx, source.wy, target.wx, target.wy, cost_value::NO_INFORMATION); - continue; - } - } - } - - if (pub_debug_grid_) converter.addLayerFromCostmap2D(*this, "added_unknown", debug_grid_); - - // Third step: Overwrite occupied cell - for (const auto & obstacle_pointcloud_angle_bin : obstacle_pointcloud_angle_bins) { - for (size_t dist_index = 0; dist_index < obstacle_pointcloud_angle_bin.size(); ++dist_index) { - const auto & obstacle_point = obstacle_pointcloud_angle_bin.at(dist_index); - setCellValue(obstacle_point.wx, obstacle_point.wy, cost_value::LETHAL_OBSTACLE); - - if (dist_index + 1 == obstacle_pointcloud_angle_bin.size()) { - continue; - } - - auto next_obstacle_point_distance = std::abs( - obstacle_pointcloud_angle_bin.at(dist_index + 1).range - - obstacle_pointcloud_angle_bin.at(dist_index).range); - if (next_obstacle_point_distance <= obstacle_separation_threshold_) { - const auto & source = obstacle_pointcloud_angle_bin.at(dist_index); - const auto & target = obstacle_pointcloud_angle_bin.at(dist_index + 1); - raytrace(source.wx, source.wy, target.wx, target.wy, cost_value::LETHAL_OBSTACLE); - continue; - } - } - } - - if (pub_debug_grid_) converter.addLayerFromCostmap2D(*this, "added_obstacle", debug_grid_); - if (pub_debug_grid_) { - debug_grid_map_publisher_ptr_->publish(grid_map::GridMapRosConverter::toMessage(debug_grid_)); - } + const auto map_res = this->getResolution(); + const auto num_cells_x = this->getSizeInCellsX(); + const auto num_cells_y = this->getSizeInCellsY(); + const std::size_t range_bin_size = + static_cast(std::sqrt(2) * std::max(num_cells_x, num_cells_y) / 2.0) + 1; + + cudaMemsetAsync( + raw_points_tensor_.get(), 0xFF, 6 * angle_bin_size * range_bin_size * sizeof(std::int64_t), + stream_); + cudaMemsetAsync( + obstacle_points_tensor_.get(), 0xFF, 6 * angle_bin_size * range_bin_size * sizeof(std::int64_t), + stream_); + cudaMemsetAsync( + device_costmap_.get(), cost_value::NO_INFORMATION, + num_cells_x * num_cells_y * sizeof(std::uint8_t), stream_); + + Eigen::Matrix3f rotation_map = mat_map_.block<3, 3>(0, 0); + Eigen::Vector3f translation_map = mat_map_.block<3, 1>(0, 3); + + Eigen::Matrix3f rotation_scan = mat_scan_.block<3, 3>(0, 0); + Eigen::Vector3f translation_scan = mat_scan_.block<3, 1>(0, 3); + + Eigen::Vector3f scan_origin_position( + scan_origin.position.x, scan_origin.position.y, scan_origin.position.z); + + cudaMemcpyAsync( + device_rotation_map_.get(), &rotation_map, sizeof(Eigen::Matrix3f), cudaMemcpyHostToDevice, + stream_); + cudaMemcpyAsync( + device_translation_map_.get(), &translation_map, sizeof(Eigen::Vector3f), + cudaMemcpyHostToDevice, stream_); + cudaMemcpyAsync( + device_rotation_scan_.get(), &rotation_scan, sizeof(Eigen::Matrix3f), cudaMemcpyHostToDevice, + stream_); + cudaMemcpyAsync( + device_translation_scan_.get(), &translation_scan, sizeof(Eigen::Vector3f), + cudaMemcpyHostToDevice, stream_); + cudaMemcpyAsync( + device_translation_scan_origin_.get(), &scan_origin_position, sizeof(Eigen::Vector3f), + cudaMemcpyHostToDevice, stream_); + + const std::size_t num_raw_points = raw_pointcloud.width * raw_pointcloud.height; + float range_resolution_inv = 1.0 / map_res; + + map_projective::prepareRawTensorLaunch( + reinterpret_cast(raw_pointcloud.data.get()), num_raw_points, + raw_pointcloud.point_step / sizeof(float), angle_bin_size, range_bin_size, min_height_, + max_height_, min_angle_, angle_increment_inv_, range_resolution_inv, device_rotation_map_.get(), + device_translation_map_.get(), device_rotation_scan_.get(), device_translation_scan_.get(), + raw_points_tensor_.get(), stream_); + + const std::size_t num_obstacle_points = obstacle_pointcloud.width * obstacle_pointcloud.height; + + map_projective::prepareObstacleTensorLaunch( + reinterpret_cast(obstacle_pointcloud.data.get()), num_obstacle_points, + obstacle_pointcloud.point_step / sizeof(float), angle_bin_size, range_bin_size, min_height_, + max_height_, min_angle_, angle_increment_inv_, range_resolution_inv, projection_dz_threshold_, + device_translation_scan_origin_.get(), device_rotation_map_.get(), + device_translation_map_.get(), device_rotation_scan_.get(), device_translation_scan_.get(), + obstacle_points_tensor_.get(), stream_); + + map_projective::fillEmptySpaceLaunch( + raw_points_tensor_.get(), angle_bin_size, range_bin_size, range_resolution_inv, + scan_origin.position.x, scan_origin.position.y, origin_x_, origin_y_, num_cells_x, num_cells_y, + cost_value::FREE_SPACE, device_costmap_.get(), stream_); + + map_projective::fillUnknownSpaceLaunch( + raw_points_tensor_.get(), obstacle_points_tensor_.get(), obstacle_separation_threshold_, + angle_bin_size, range_bin_size, range_resolution_inv, scan_origin.position.x, + scan_origin.position.y, scan_origin.position.z, origin_x_, origin_y_, robot_pose.position.z, + num_cells_x, num_cells_y, cost_value::FREE_SPACE, cost_value::NO_INFORMATION, + device_costmap_.get(), stream_); + + map_projective::fillObstaclesLaunch( + obstacle_points_tensor_.get(), obstacle_separation_threshold_, angle_bin_size, range_bin_size, + range_resolution_inv, origin_x_, origin_y_, num_cells_x, num_cells_y, + cost_value::LETHAL_OBSTACLE, device_costmap_.get(), stream_); + + cudaStreamSynchronize(stream_); } void OccupancyGridMapProjectiveBlindSpot::initRosParam(rclcpp::Node & node) { projection_dz_threshold_ = - node.declare_parameter("OccupancyGridMapProjectiveBlindSpot.projection_dz_threshold"); - obstacle_separation_threshold_ = node.declare_parameter( + node.declare_parameter("OccupancyGridMapProjectiveBlindSpot.projection_dz_threshold"); + obstacle_separation_threshold_ = node.declare_parameter( "OccupancyGridMapProjectiveBlindSpot.obstacle_separation_threshold"); - pub_debug_grid_ = - node.declare_parameter("OccupancyGridMapProjectiveBlindSpot.pub_debug_grid"); - debug_grid_map_publisher_ptr_ = node.create_publisher( - "~/debug/grid_map", rclcpp::QoS(1).durability_volatile()); } } // namespace costmap_2d diff --git a/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_projective_kernel.cu b/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_projective_kernel.cu new file mode 100644 index 0000000000000..975a08c9d41b8 --- /dev/null +++ b/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_projective_kernel.cu @@ -0,0 +1,534 @@ +// Copyright 2024 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_projective_kernel.hpp" +#include "autoware/probabilistic_occupancy_grid_map/utils/utils_kernel.hpp" + +#include +#include + +#include +#include +#include + +namespace autoware::occupancy_grid_map +{ +namespace costmap_2d::map_projective +{ + +static constexpr float RANGE_DISCRETIZATION_RESOLUTION = 0.001f; + +bool __device__ isVisibleBeyondObstacle( + const std::uint64_t * obstacle_element, const std::uint64_t * raw_element, + const float & scan_origin_z, const float & robot_pose_z) +{ + std::uint64_t raw_range_and_z = raw_element[2]; + std::uint32_t raw_range_int = raw_range_and_z >> 32; + float raw_range = raw_range_int * RANGE_DISCRETIZATION_RESOLUTION; + float raw_world_z = __uint_as_float(raw_range_and_z & 0xFFFFFFFF); + + std::uint64_t obstacle_range_and_pl = raw_element[3]; + std::uint32_t obstacle_range_int = obstacle_range_and_pl >> 32; + float obstacle_range = obstacle_range_int * RANGE_DISCRETIZATION_RESOLUTION; + float obstacle_pl = __uint_as_float(obstacle_range_and_pl & 0xFFFFFFFF); + + if (raw_range < obstacle_range) { + return false; + } + + if (std::isinf(obstacle_pl)) { + return false; + } + + // y = ax + b + const double a = -(scan_origin_z - robot_pose_z) / (obstacle_range + obstacle_pl); + const double b = scan_origin_z; + return raw_world_z > (a * raw_range + b); +}; + +__global__ void prepareRawTensorKernel( + const float * input_pointcloud, const std::size_t num_points, const std::size_t points_step, + const std::size_t angle_bins, const std::size_t range_bins, const float min_height, + const float max_height, const float min_angle, const float angle_increment_inv, + const float range_resolution_inv, const Eigen::Matrix3f * rotation_map, + const Eigen::Vector3f * translation_map, const Eigen::Matrix3f * rotation_scan, + const Eigen::Vector3f * translation_scan, std::uint64_t * points_tensor) +{ + int idx = blockIdx.x * blockDim.x + threadIdx.x; + if (idx >= num_points) { + return; + } + + Eigen::Map point(input_pointcloud + idx * points_step); + + if ( + point.z() > max_height || point.z() < min_height || !isfinite(point.x()) || + !isfinite(point.y()) || !isfinite(point.z())) { + return; + } + + Eigen::Vector3f map_point = (*rotation_map) * point + (*translation_map); + Eigen::Vector3f scan_point = (*rotation_scan) * map_point + (*translation_scan); + + float angle = atan2(scan_point.y(), scan_point.x()); + int angle_bin_index = static_cast((angle - min_angle) * angle_increment_inv); + float range = sqrt(scan_point.y() * scan_point.y() + scan_point.x() * scan_point.x()); + int range_bin_index = static_cast(range * range_resolution_inv); + + if ( + angle_bin_index < 0 || angle_bin_index >= angle_bins || range_bin_index < 0 || + range_bin_index >= range_bins) { + return; + } + + std::uint64_t range_int = static_cast(range / RANGE_DISCRETIZATION_RESOLUTION); + std::uint32_t world_x_int = __float_as_uint(map_point.x()); + std::uint32_t world_y_int = __float_as_uint(map_point.y()); + std::uint32_t world_z_int = __float_as_uint(map_point.z()); + std::uint32_t projected_length_int = __float_as_uint(0.f); + std::uint32_t projected_world_x_int = __float_as_uint(0.f); + std::uint32_t projected_world_y_int = __float_as_uint(0.f); + + // Can not use std::uint64_t for cuda reasons... + static_assert( + sizeof(std::uint64_t) == sizeof(unsigned long long int), + "unsigned long long int is not 8 bytes"); + unsigned long long int range_and_x_int = (range_int << 32) | world_x_int; + unsigned long long int range_and_y_int = (range_int << 32) | world_y_int; + unsigned long long int range_and_z_int = (range_int << 32) | world_z_int; + unsigned long long int range_and_pl_int = (range_int << 32) | projected_length_int; + unsigned long long int range_and_px_int = (range_int << 32) | projected_world_x_int; + unsigned long long int range_and_py_int = (range_int << 32) | projected_world_y_int; + + std::uint64_t * element_address = + points_tensor + 6 * (angle_bin_index * range_bins + range_bin_index); + + atomicMin(reinterpret_cast(element_address + 0), range_and_x_int); + atomicMin(reinterpret_cast(element_address + 1), range_and_y_int); + atomicMin(reinterpret_cast(element_address + 2), range_and_z_int); + atomicMin(reinterpret_cast(element_address + 3), range_and_pl_int); + atomicMin(reinterpret_cast(element_address + 4), range_and_px_int); + atomicMin(reinterpret_cast(element_address + 5), range_and_py_int); +} + +__global__ void prepareObstacleTensorKernel( + const float * input_pointcloud, const std::size_t num_points, const std::size_t points_step, + const std::size_t angle_bins, const std::size_t range_bins, const float min_height, + const float max_height, const float min_angle, const float angle_increment_inv, + const float range_resolution_inv, const float projection_dz_threshold, + const Eigen::Vector3f * translation_scan_origin, const Eigen::Matrix3f * rotation_map, + const Eigen::Vector3f * translation_map, const Eigen::Matrix3f * rotation_scan, + const Eigen::Vector3f * translation_scan, std::uint64_t * points_tensor) +{ + int idx = blockIdx.x * blockDim.x + threadIdx.x; + if (idx >= num_points) { + return; + } + + Eigen::Map point(input_pointcloud + idx * points_step); + + if ( + point.z() > max_height || point.z() < min_height || !isfinite(point.x()) || + !isfinite(point.y()) || !isfinite(point.z())) { + return; + } + + Eigen::Vector3f map_point = (*rotation_map) * point + (*translation_map); + Eigen::Vector3f scan_point = (*rotation_scan) * map_point + (*translation_scan); + + float angle = atan2(scan_point.y(), scan_point.x()); + int angle_bin_index = static_cast((angle - min_angle) * angle_increment_inv); + float range = sqrt(scan_point.y() * scan_point.y() + scan_point.x() * scan_point.x()); + int range_bin_index = static_cast(range * range_resolution_inv); + + if ( + angle_bin_index < 0 || angle_bin_index >= angle_bins || range_bin_index < 0 || + range_bin_index >= range_bins) { + return; + } + + std::uint64_t range_int = static_cast(range / RANGE_DISCRETIZATION_RESOLUTION); + std::uint32_t world_x_int = __float_as_uint(map_point.x()); + std::uint32_t world_y_int = __float_as_uint(map_point.y()); + std::uint32_t world_z_int = __float_as_uint(map_point.z()); + + const float scan_z = translation_scan_origin->z(); + -translation_map->z(); + const float obstacle_z = map_point.z() - translation_scan_origin->z(); + const float dz = scan_z - obstacle_z; + + float projected_length, projected_world_x, projected_world_y; + + if (dz > projection_dz_threshold) { + const float ratio = obstacle_z / dz; + projected_length = range * ratio; + projected_world_x = map_point.x() + (map_point.x() - translation_scan_origin->x()) * ratio; + projected_world_y = map_point.y() + (map_point.y() - translation_scan_origin->y()) * ratio; + } else { + projected_length = INFINITY; + projected_world_x = INFINITY; + projected_world_y = INFINITY; + } + + std::uint32_t projected_length_int = __float_as_uint(projected_length); + std::uint32_t projected_world_x_int = __float_as_uint(projected_world_x); + std::uint32_t projected_world_y_int = __float_as_uint(projected_world_y); + + // Can not use std::uint64_t for cuda reasons... + static_assert( + sizeof(std::uint64_t) == sizeof(unsigned long long int), + "unsigned long long int is not 8 bytes"); + unsigned long long int range_and_x_int = (range_int << 32) | world_x_int; + unsigned long long int range_and_y_int = (range_int << 32) | world_y_int; + unsigned long long int range_and_z_int = (range_int << 32) | world_z_int; + unsigned long long int range_and_pl_int = (range_int << 32) | projected_length_int; + unsigned long long int range_and_px_int = (range_int << 32) | projected_world_x_int; + unsigned long long int range_and_py_int = (range_int << 32) | projected_world_y_int; + + std::uint64_t * element_address = + points_tensor + 6 * (angle_bin_index * range_bins + range_bin_index); + + atomicMin(reinterpret_cast(element_address + 0), range_and_x_int); + atomicMin(reinterpret_cast(element_address + 1), range_and_y_int); + atomicMin(reinterpret_cast(element_address + 2), range_and_z_int); + atomicMin(reinterpret_cast(element_address + 3), range_and_pl_int); + atomicMin(reinterpret_cast(element_address + 4), range_and_px_int); + atomicMin(reinterpret_cast(element_address + 5), range_and_py_int); +} + +__global__ void fillEmptySpaceKernel( + const std::uint64_t * points_tensor, const std::size_t angle_bins, const std::size_t range_bins, + const float map_resolution_inv, const float scan_origin_x, const float scan_origin_y, + const float map_origin_x, const float map_origin_y, const int num_cells_x, const int num_cells_y, + std::uint8_t empty_value, std::uint8_t * costmap_tensor) +{ + int idx = blockIdx.x * blockDim.x + threadIdx.x; + if (idx >= angle_bins * range_bins) return; + + int angle_bin_index = idx / range_bins; + int range_bin_index = idx % range_bins; + + std::uint64_t range_and_x = + points_tensor[6 * (angle_bin_index * range_bins + range_bin_index) + 0]; + std::uint32_t range_int = range_and_x >> 32; + + if (range_int == 0xFFFFFFFF) { + return; + } + + std::uint64_t range_and_y = + points_tensor[6 * (angle_bin_index * range_bins + range_bin_index) + 1]; + float world_x = __uint_as_float(range_and_x & 0xFFFFFFFF); + float world_y = __uint_as_float(range_and_y & 0xFFFFFFFF); + + if (world_x < map_origin_x || world_y < map_origin_y) { + return; + } + + autoware::occupancy_grid_map::utils::raytrace( + scan_origin_x, scan_origin_y, world_x, world_y, map_origin_x, map_origin_y, map_resolution_inv, + num_cells_x, num_cells_y, empty_value, costmap_tensor); +} + +__global__ void fillUnknownSpaceKernel( + const std::uint64_t * raw_points_tensor, const std::uint64_t * obstacle_points_tensor, + const float obstacle_separation_threshold, const std::size_t angle_bins, + const std::size_t range_bins, const float map_resolution_inv, const float scan_origin_x, + const float scan_origin_y, const float scan_origin_z, const float map_origin_x, + const float map_origin_y, const float robot_pose_z, const int num_cells_x, const int num_cells_y, + std::uint8_t free_space_value, std::uint8_t no_information_value, std::uint8_t * costmap_tensor) +{ + int idx = blockIdx.x * blockDim.x + threadIdx.x; + if (idx >= angle_bins * range_bins) return; + + int angle_bin_index = idx / range_bins; + int range_bin_index = idx % range_bins; + + std::uint64_t obs_range_and_x = + obstacle_points_tensor[6 * (angle_bin_index * range_bins + range_bin_index) + 0]; + std::uint64_t obs_range_and_y = + obstacle_points_tensor[6 * (angle_bin_index * range_bins + range_bin_index) + 1]; + std::uint64_t obs_range_and_px = + obstacle_points_tensor[6 * (angle_bin_index * range_bins + range_bin_index) + 4]; + std::uint64_t obs_range_and_py = + obstacle_points_tensor[6 * (angle_bin_index * range_bins + range_bin_index) + 5]; + std::uint32_t obs_range_int = obs_range_and_x >> 32; + float obs_range = obs_range_int * RANGE_DISCRETIZATION_RESOLUTION; + float obs_world_x = __uint_as_float(obs_range_and_x & 0xFFFFFFFF); + float obs_world_y = __uint_as_float(obs_range_and_y & 0xFFFFFFFF); + float obs_world_px = __uint_as_float(obs_range_and_px & 0xFFFFFFFF); + float obs_world_py = __uint_as_float(obs_range_and_py & 0xFFFFFFFF); + + if (obs_range_int == 0xFFFFFFFF || obs_world_x < map_origin_x || obs_world_y < map_origin_y) { + return; + } + + int next_raw_range_bin_index = range_bin_index + 1; + int next_obs_range_bin_index = range_bin_index + 1; + + for (; next_raw_range_bin_index < range_bins; next_raw_range_bin_index++) { + std::uint64_t next_raw_range_and_x = + raw_points_tensor[6 * (angle_bin_index * range_bins + next_raw_range_bin_index) + 0]; + std::uint32_t next_raw_range_int = next_raw_range_and_x >> 32; + + if ( + next_raw_range_int != 0xFFFFFFFF && + isVisibleBeyondObstacle( + obstacle_points_tensor + 6 * (angle_bin_index * range_bins + range_bin_index), + raw_points_tensor + 6 * (angle_bin_index * range_bins + next_raw_range_bin_index), + scan_origin_z, robot_pose_z)) { + break; + } + } + + for (; next_obs_range_bin_index < range_bins; next_obs_range_bin_index++) { + std::uint64_t next_obs_range_and_x = + obstacle_points_tensor[6 * (angle_bin_index * range_bins + next_obs_range_bin_index) + 0]; + std::uint32_t next_obs_range_int = next_obs_range_and_x >> 32; + + if (next_obs_range_int != 0xFFFFFFFF) { + break; + } + } + + const std::uint64_t next_obs_range_and_x = + obstacle_points_tensor[6 * (angle_bin_index * range_bins + next_obs_range_bin_index) + 0]; + const std::uint64_t next_obs_range_and_y = + obstacle_points_tensor[6 * (angle_bin_index * range_bins + next_obs_range_bin_index) + 1]; + const std::uint64_t next_obs_range_and_px = + obstacle_points_tensor[6 * (angle_bin_index * range_bins + next_obs_range_bin_index) + 4]; + const std::uint64_t next_obs_range_and_py = + obstacle_points_tensor[6 * (angle_bin_index * range_bins + next_obs_range_bin_index) + 5]; + const std::uint32_t next_obs_range_int = next_obs_range_and_x >> 32; + const float next_obs_world_x = __uint_as_float(next_obs_range_and_x & 0xFFFFFFFF); + const float next_obs_world_y = __uint_as_float(next_obs_range_and_y & 0xFFFFFFFF); + const float next_obs_world_px = __uint_as_float(next_obs_range_and_px & 0xFFFFFFFF); + const float next_obs_world_py = __uint_as_float(next_obs_range_and_py & 0xFFFFFFFF); + + float next_obs_range = next_obs_range_int * RANGE_DISCRETIZATION_RESOLUTION; + float obs_to_obs_distance = next_obs_range - obs_range; + + const std::uint64_t next_raw_range_and_x = + raw_points_tensor[6 * (angle_bin_index * range_bins + next_raw_range_bin_index) + 0]; + const std::uint64_t next_raw_range_and_y = + raw_points_tensor[6 * (angle_bin_index * range_bins + next_raw_range_bin_index) + 1]; + const std::uint64_t next_raw_range_and_px = + raw_points_tensor[6 * (angle_bin_index * range_bins + next_raw_range_bin_index) + 4]; + const std::uint64_t next_raw_range_and_py = + raw_points_tensor[6 * (angle_bin_index * range_bins + next_raw_range_bin_index) + 5]; + const std::uint32_t next_raw_range_int = next_raw_range_and_x >> 32; + const float next_raw_world_x = __uint_as_float(next_raw_range_and_x & 0xFFFFFFFF); + const float next_raw_world_y = __uint_as_float(next_raw_range_and_y & 0xFFFFFFFF); + const float next_raw_world_px = __uint_as_float(next_raw_range_and_px & 0xFFFFFFFF); + const float next_raw_world_py = __uint_as_float(next_raw_range_and_py & 0xFFFFFFFF); + + if (next_raw_range_int == 0xFFFFFFFF) { + autoware::occupancy_grid_map::utils::raytrace( + obs_world_x, obs_world_y, obs_world_px, obs_world_py, map_origin_x, map_origin_y, + map_resolution_inv, num_cells_x, num_cells_y, no_information_value, costmap_tensor); + return; + } + + if (next_obs_range_int == 0xFFFFFFFF) { + autoware::occupancy_grid_map::utils::raytrace( + obs_world_x, obs_world_y, obs_world_px, obs_world_py, map_origin_x, map_origin_y, + map_resolution_inv, num_cells_x, num_cells_y, no_information_value, costmap_tensor); + return; + } + + float next_raw_range = next_raw_range_int * RANGE_DISCRETIZATION_RESOLUTION; + float raw_to_obs_distance = abs(next_raw_range - obs_range); + + if (obs_to_obs_distance <= obstacle_separation_threshold) { + return; + } + + if (raw_to_obs_distance < obs_to_obs_distance) { + if (next_raw_world_x < map_origin_x || next_raw_world_y < map_origin_y) { + return; + } + + autoware::occupancy_grid_map::utils::raytrace( + obs_world_x, obs_world_y, next_raw_world_x, next_raw_world_y, map_origin_x, map_origin_y, + map_resolution_inv, num_cells_x, num_cells_y, no_information_value, costmap_tensor); + + autoware::occupancy_grid_map::utils::setCellValue( + next_raw_world_x, next_raw_world_y, map_origin_x, map_origin_y, map_resolution_inv, + num_cells_x, num_cells_y, free_space_value, costmap_tensor); + return; + } else { + // fill with no information between obstacles + + if (next_obs_world_x < map_origin_x || next_obs_world_y < map_origin_y) { + return; + } + + autoware::occupancy_grid_map::utils::raytrace( + obs_world_x, obs_world_y, next_obs_world_x, next_obs_world_y, map_origin_x, map_origin_y, + map_resolution_inv, num_cells_x, num_cells_y, no_information_value, costmap_tensor); + + return; + } +} + +__global__ void fillObstaclesKernel( + const std::uint64_t * obstacle_points_tensor, const float distance_margin, + const std::size_t angle_bins, const std::size_t range_bins, const float map_resolution_inv, + const float map_origin_x, const float map_origin_y, const int num_cells_x, const int num_cells_y, + std::uint8_t obstacle_value, std::uint8_t * costmap_tensor) +{ + int idx = blockIdx.x * blockDim.x + threadIdx.x; + if (idx >= angle_bins * range_bins) return; + + int angle_bin_index = idx / range_bins; + int range_bin_index = idx % range_bins; + + std::uint64_t range_and_x = + obstacle_points_tensor[6 * (angle_bin_index * range_bins + range_bin_index) + 0]; + std::uint64_t range_and_y = + obstacle_points_tensor[6 * (angle_bin_index * range_bins + range_bin_index) + 1]; + + std::uint32_t range_int = range_and_x >> 32; + float range = range_int * RANGE_DISCRETIZATION_RESOLUTION; + float world_x = __uint_as_float(range_and_x & 0xFFFFFFFF); + float world_y = __uint_as_float(range_and_y & 0xFFFFFFFF); + + if (range < 0.0 || range_int == 0xFFFFFFFF) { + return; + } + + autoware::occupancy_grid_map::utils::setCellValue( + world_x, world_y, map_origin_x, map_origin_y, map_resolution_inv, num_cells_x, num_cells_y, + obstacle_value, costmap_tensor); + + // Look for the next obstacle point + int next_obs_range_bin_index = range_bin_index + 1; + for (; next_obs_range_bin_index < range_bins; next_obs_range_bin_index++) { + std::uint64_t next_obs_range_and_x = + obstacle_points_tensor[6 * (angle_bin_index * range_bins + next_obs_range_bin_index) + 0]; + std::uint32_t next_obs_range_int = next_obs_range_and_x >> 32; + + if (next_obs_range_int != 0xFFFFFFFF) { + break; + } + } + + std::uint64_t next_obs_range_and_x = + obstacle_points_tensor[6 * (angle_bin_index * range_bins + range_bin_index) + 0]; + std::uint64_t next_obs_range_and_y = + obstacle_points_tensor[6 * (angle_bin_index * range_bins + range_bin_index) + 1]; + + std::uint32_t next_obs_range_int = next_obs_range_and_x >> 32; + float next_obs_range = next_obs_range_int * RANGE_DISCRETIZATION_RESOLUTION; + float next_obs_world_x = __uint_as_float(next_obs_range_and_x & 0xFFFFFFFF); + float next_obs_world_y = __uint_as_float(next_obs_range_and_y & 0xFFFFFFFF); + + if (next_obs_range_int == 0xFFFFFFFF || abs(next_obs_range - range) > distance_margin) { + return; + } + + if (next_obs_world_x < map_origin_x || next_obs_world_y < map_origin_y) { + return; + } + + autoware::occupancy_grid_map::utils::raytrace( + world_x, world_y, next_obs_world_x, next_obs_world_y, map_origin_x, map_origin_y, + map_resolution_inv, num_cells_x, num_cells_y, obstacle_value, costmap_tensor); +} + +void prepareRawTensorLaunch( + const float * input_pointcloud, const std::size_t num_points, const std::size_t points_step, + const std::size_t angle_bins, const std::size_t range_bins, const float min_height, + const float max_height, const float min_angle, const float angle_increment_inv, + const float range_resolution_inv, const Eigen::Matrix3f * rotation_map, + const Eigen::Vector3f * translation_map, const Eigen::Matrix3f * rotation_scan, + const Eigen::Vector3f * translation_scan, std::uint64_t * points_tensor, cudaStream_t stream) +{ + const int threads_per_block = 256; + const int num_blocks = (num_points + threads_per_block - 1) / threads_per_block; + + prepareRawTensorKernel<<>>( + input_pointcloud, num_points, points_step, angle_bins, range_bins, min_height, max_height, + min_angle, angle_increment_inv, range_resolution_inv, rotation_map, translation_map, + rotation_scan, translation_scan, points_tensor); +} + +void prepareObstacleTensorLaunch( + const float * input_pointcloud, const std::size_t num_points, const std::size_t points_step, + const std::size_t angle_bins, const std::size_t range_bins, const float min_height, + const float max_height, const float min_angle, const float angle_increment_inv, + const float range_resolution_inv, const float projection_dz_threshold, + const Eigen::Vector3f * translation_scan_origin, const Eigen::Matrix3f * rotation_map, + const Eigen::Vector3f * translation_map, const Eigen::Matrix3f * rotation_scan, + const Eigen::Vector3f * translation_scan, std::uint64_t * points_tensor, cudaStream_t stream) +{ + const int threads_per_block = 256; + const int num_blocks = (num_points + threads_per_block - 1) / threads_per_block; + + prepareObstacleTensorKernel<<>>( + input_pointcloud, num_points, points_step, angle_bins, range_bins, min_height, max_height, + min_angle, angle_increment_inv, range_resolution_inv, projection_dz_threshold, + translation_scan_origin, rotation_map, translation_map, rotation_scan, translation_scan, + points_tensor); +} + +void fillEmptySpaceLaunch( + const std::uint64_t * points_tensor, const std::size_t angle_bins, const std::size_t range_bins, + const float map_resolution_inv, const float scan_origin_x, const float scan_origin_y, + const float map_origin_x, const float map_origin_y, const int num_cells_x, const int num_cells_y, + std::uint8_t empty_value, std::uint8_t * costmap_tensor, cudaStream_t stream) +{ + const int threads_per_block = 256; + const int num_blocks = (angle_bins * range_bins + threads_per_block - 1) / threads_per_block; + + fillEmptySpaceKernel<<>>( + points_tensor, angle_bins, range_bins, map_resolution_inv, scan_origin_x, scan_origin_y, + map_origin_x, map_origin_y, num_cells_x, num_cells_y, empty_value, costmap_tensor); +} + +void fillUnknownSpaceLaunch( + const std::uint64_t * raw_points_tensor, const std::uint64_t * obstacle_points_tensor, + const float obstacle_separation_threshold, const std::size_t angle_bins, + const std::size_t range_bins, const float map_resolution_inv, const float scan_origin_x, + const float scan_origin_y, const float scan_origin_z, const float map_origin_x, + const float map_origin_y, const float robot_pose_z, const int num_cells_x, const int num_cells_y, + std::uint8_t free_space_value, std::uint8_t no_information_value, std::uint8_t * costmap_tensor, + cudaStream_t stream) +{ + const int threads_per_block = 256; + const int num_blocks = (angle_bins * range_bins + threads_per_block - 1) / threads_per_block; + + fillUnknownSpaceKernel<<>>( + raw_points_tensor, obstacle_points_tensor, obstacle_separation_threshold, angle_bins, + range_bins, map_resolution_inv, scan_origin_x, scan_origin_y, scan_origin_z, map_origin_x, + map_origin_y, robot_pose_z, num_cells_x, num_cells_y, free_space_value, no_information_value, + costmap_tensor); +} + +void fillObstaclesLaunch( + const std::uint64_t * obstacle_points_tensor, const float distance_margin, + const std::size_t angle_bins, const std::size_t range_bins, const float map_resolution_inv, + const float map_origin_x, const float map_origin_y, const int num_cells_x, const int num_cells_y, + std::uint8_t obstacle_value, std::uint8_t * costmap_tensor, cudaStream_t stream) +{ + const int threads_per_block = 256; + const int num_blocks = (angle_bins * range_bins + threads_per_block - 1) / threads_per_block; + + fillObstaclesKernel<<>>( + obstacle_points_tensor, distance_margin, angle_bins, range_bins, map_resolution_inv, + map_origin_x, map_origin_y, num_cells_x, num_cells_y, obstacle_value, costmap_tensor); +} + +} // namespace costmap_2d::map_projective +} // namespace autoware::occupancy_grid_map diff --git a/perception/autoware_probabilistic_occupancy_grid_map/lib/updater/binary_bayes_filter_updater.cpp b/perception/autoware_probabilistic_occupancy_grid_map/lib/updater/binary_bayes_filter_updater.cpp index 771eaabf4f6f9..cdcb0677b7243 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/lib/updater/binary_bayes_filter_updater.cpp +++ b/perception/autoware_probabilistic_occupancy_grid_map/lib/updater/binary_bayes_filter_updater.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2024 Tier IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -15,6 +15,7 @@ #include "autoware/probabilistic_occupancy_grid_map/updater/binary_bayes_filter_updater.hpp" #include "autoware/probabilistic_occupancy_grid_map/cost_value/cost_value.hpp" +#include "autoware/probabilistic_occupancy_grid_map/updater/binary_bayes_filter_updater_kernel.hpp" #include #include @@ -25,8 +26,9 @@ namespace costmap_2d { OccupancyGridMapBBFUpdater::OccupancyGridMapBBFUpdater( - const unsigned int cells_size_x, const unsigned int cells_size_y, const float resolution) -: OccupancyGridMapUpdaterInterface(cells_size_x, cells_size_y, resolution) + const bool use_cuda, const unsigned int cells_size_x, const unsigned int cells_size_y, + const float resolution) +: OccupancyGridMapUpdaterInterface(use_cuda, cells_size_x, cells_size_y, resolution) { } @@ -41,6 +43,22 @@ void OccupancyGridMapBBFUpdater::initRosParam(rclcpp::Node & node) probability_matrix_(Index::OCCUPIED, Index::FREE) = node.declare_parameter("probability_matrix.free_to_occupied"); v_ratio_ = node.declare_parameter("v_ratio"); + + device_probability_matrix_ = + autoware::cuda_utils::make_unique(Index::NUM_STATES * Index::NUM_STATES); + + std::vector probability_matrix_vector; + probability_matrix_vector.resize(Index::NUM_STATES * Index::NUM_STATES); + + for (size_t j = 0; j < Index::NUM_STATES; j++) { + for (size_t i = 0; i < Index::NUM_STATES; i++) { + probability_matrix_vector[j * Index::NUM_STATES + i] = probability_matrix_(j, i); + } + } + + cudaMemcpy( + device_probability_matrix_.get(), probability_matrix_vector.data(), + sizeof(float) * Index::NUM_STATES * Index::NUM_STATES, cudaMemcpyHostToDevice); } inline unsigned char OccupancyGridMapBBFUpdater::applyBBF( @@ -69,16 +87,37 @@ inline unsigned char OccupancyGridMapBBFUpdater::applyBBF( static_cast(254)); } -bool OccupancyGridMapBBFUpdater::update(const Costmap2D & single_frame_occupancy_grid_map) +bool OccupancyGridMapBBFUpdater::update( + const OccupancyGridMapInterface & single_frame_occupancy_grid_map) { updateOrigin( single_frame_occupancy_grid_map.getOriginX(), single_frame_occupancy_grid_map.getOriginY()); - for (unsigned int x = 0; x < getSizeInCellsX(); x++) { - for (unsigned int y = 0; y < getSizeInCellsY(); y++) { - unsigned int index = getIndex(x, y); - costmap_[index] = applyBBF(single_frame_occupancy_grid_map.getCost(x, y), costmap_[index]); + + if (use_cuda_ != single_frame_occupancy_grid_map.isCudaEnabled()) { + throw std::runtime_error("The CUDA setting of the updater and the map do not match."); + } + + if (use_cuda_) { + applyBBFLaunch( + single_frame_occupancy_grid_map.getDeviceCostmap().get(), device_probability_matrix_.get(), + Index::NUM_STATES, Index::FREE, Index::OCCUPIED, cost_value::FREE_SPACE, + cost_value::LETHAL_OBSTACLE, cost_value::NO_INFORMATION, v_ratio_, + getSizeInCellsX() * getSizeInCellsY(), device_costmap_.get(), stream_); + + cudaMemcpy( + costmap_, device_costmap_.get(), getSizeInCellsX() * getSizeInCellsY() * sizeof(std::uint8_t), + cudaMemcpyDeviceToHost); + + cudaStreamSynchronize(stream_); + } else { + for (unsigned int x = 0; x < getSizeInCellsX(); x++) { + for (unsigned int y = 0; y < getSizeInCellsY(); y++) { + unsigned int index = getIndex(x, y); + costmap_[index] = applyBBF(single_frame_occupancy_grid_map.getCost(x, y), costmap_[index]); + } } } + return true; } diff --git a/perception/autoware_probabilistic_occupancy_grid_map/lib/updater/binary_bayes_filter_updater_kernel.cu b/perception/autoware_probabilistic_occupancy_grid_map/lib/updater/binary_bayes_filter_updater_kernel.cu new file mode 100644 index 0000000000000..f4d4886eb0182 --- /dev/null +++ b/perception/autoware_probabilistic_occupancy_grid_map/lib/updater/binary_bayes_filter_updater_kernel.cu @@ -0,0 +1,81 @@ +// Copyright 2024 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__probabilistic_occupancy_grid_map__UPDATER__BINARY_BAYES_FILTER_UPDATER_KERNEL_HPP_ +#define AUTOWARE__probabilistic_occupancy_grid_map__UPDATER__BINARY_BAYES_FILTER_UPDATER_KERNEL_HPP_ + +#include "autoware/probabilistic_occupancy_grid_map/updater/binary_bayes_filter_updater_kernel.hpp" + +#include + +__global__ void applyBBFKernel( + const std::uint8_t * z_costmap, const float * probability_matrix, const int num_states, + const int free_index, const int occupied_index, const std::uint8_t free_space_value, + const std::uint8_t lethal_obstacle_value, const std::uint8_t no_information_value, + const double v_ratio_, const int num_elements, std::uint8_t * o_costmap) +{ + const int idx = blockIdx.x * blockDim.x + threadIdx.x; + if (idx >= num_elements) { + return; + } + + const std::uint8_t z = z_costmap[idx]; + const std::uint8_t o = o_costmap[idx]; + + constexpr float cost2p = 1.f / 255.f; + const float po = o * cost2p; + float pz{}; + float not_pz{}; + float po_hat{}; + if (z == lethal_obstacle_value) { + pz = probability_matrix[occupied_index * num_states + occupied_index]; + not_pz = probability_matrix[free_index * num_states + occupied_index]; + po_hat = ((po * pz) / ((po * pz) + ((1.f - po) * not_pz))); + } else if (z == free_space_value) { + pz = 1.f - probability_matrix[free_index * num_states + free_index]; + not_pz = 1.f - probability_matrix[occupied_index * num_states + free_index]; + po_hat = ((po * pz) / ((po * pz) + ((1.f - po) * not_pz))); + } else if (z == no_information_value) { + const float inv_v_ratio = 1.f / v_ratio_; + po_hat = ((po + (0.5f * inv_v_ratio)) / ((1.f * inv_v_ratio) + 1.f)); + } + + o_costmap[idx] = std::min( + std::max( + static_cast(std::lround(po_hat * 255.f)), static_cast(1)), + static_cast(254)); +} + +namespace autoware::occupancy_grid_map +{ +namespace costmap_2d +{ + +void applyBBFLaunch( + const std::uint8_t * z_costmap, const float * probability_matrix, const int num_states, + const int free_index, const int occupied_index, const std::uint8_t free_space_value, + const std::uint8_t lethal_obstacle_value, const std::uint8_t no_information_value, + const double v_ratio_, const int num_elements, std::uint8_t * o_costmap, cudaStream_t stream) +{ + const int threads_per_block = 256; + const int num_blocks = (num_elements + threads_per_block - 1) / threads_per_block; + applyBBFKernel<<>>( + z_costmap, probability_matrix, num_states, free_index, occupied_index, free_space_value, + lethal_obstacle_value, no_information_value, v_ratio_, num_elements, o_costmap); +} + +} // namespace costmap_2d +} // namespace autoware::occupancy_grid_map + +#endif // AUTOWARE__probabilistic_occupancy_grid_map__UPDATER__BINARY_BAYES_FILTER_UPDATER_KERNEL_HPP_ diff --git a/perception/autoware_probabilistic_occupancy_grid_map/lib/updater/log_odds_bayes_filter_updater.cpp b/perception/autoware_probabilistic_occupancy_grid_map/lib/updater/log_odds_bayes_filter_updater.cpp index 9f3c3c7e40eaf..b1a8ff937c495 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/lib/updater/log_odds_bayes_filter_updater.cpp +++ b/perception/autoware_probabilistic_occupancy_grid_map/lib/updater/log_odds_bayes_filter_updater.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 TIER IV, Inc. +// Copyright 2024 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -15,6 +15,7 @@ #include "autoware/probabilistic_occupancy_grid_map/updater/log_odds_bayes_filter_updater.hpp" #include "autoware/probabilistic_occupancy_grid_map/cost_value/cost_value.hpp" +#include "autoware/probabilistic_occupancy_grid_map/updater/log_odds_bayes_filter_updater_kernel.hpp" #include @@ -39,7 +40,7 @@ inline unsigned char OccupancyGridMapLOBFUpdater::applyLOBF( constexpr unsigned char unknown = cost_value::NO_INFORMATION; constexpr unsigned char unknown_margin = 1; - /* Tau and ST decides how fast the observation decay to the unknown status*/ + // Tau and ST decides how fast the observation decay to the unknown status constexpr double tau = 0.75; constexpr double sample_time = 0.1; @@ -58,16 +59,35 @@ inline unsigned char OccupancyGridMapLOBFUpdater::applyLOBF( } } -bool OccupancyGridMapLOBFUpdater::update(const Costmap2D & single_frame_occupancy_grid_map) +bool OccupancyGridMapLOBFUpdater::update( + const OccupancyGridMapInterface & single_frame_occupancy_grid_map) { updateOrigin( single_frame_occupancy_grid_map.getOriginX(), single_frame_occupancy_grid_map.getOriginY()); - for (unsigned int x = 0; x < getSizeInCellsX(); x++) { - for (unsigned int y = 0; y < getSizeInCellsY(); y++) { - unsigned int index = getIndex(x, y); - costmap_[index] = applyLOBF(single_frame_occupancy_grid_map.getCost(x, y), costmap_[index]); + + if (use_cuda_ != single_frame_occupancy_grid_map.isCudaEnabled()) { + throw std::runtime_error("The CUDA setting of the updater and the map do not match."); + } + + if (use_cuda_) { + applyLOBFLaunch( + single_frame_occupancy_grid_map.getDeviceCostmap().get(), cost_value::NO_INFORMATION, + getSizeInCellsX() * getSizeInCellsY(), device_costmap_.get(), stream_); + + cudaMemcpy( + costmap_, device_costmap_.get(), getSizeInCellsX() * getSizeInCellsY() * sizeof(std::uint8_t), + cudaMemcpyDeviceToHost); + + cudaStreamSynchronize(stream_); + } else { + for (unsigned int x = 0; x < getSizeInCellsX(); x++) { + for (unsigned int y = 0; y < getSizeInCellsY(); y++) { + unsigned int index = getIndex(x, y); + costmap_[index] = applyLOBF(single_frame_occupancy_grid_map.getCost(x, y), costmap_[index]); + } } } + return true; } diff --git a/perception/autoware_probabilistic_occupancy_grid_map/lib/updater/log_odds_bayes_filter_updater_kernel.cu b/perception/autoware_probabilistic_occupancy_grid_map/lib/updater/log_odds_bayes_filter_updater_kernel.cu new file mode 100644 index 0000000000000..16705adac31b9 --- /dev/null +++ b/perception/autoware_probabilistic_occupancy_grid_map/lib/updater/log_odds_bayes_filter_updater_kernel.cu @@ -0,0 +1,95 @@ +// Copyright 2024 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__probabilistic_occupancy_grid_map__UPDATER__log_odds_bayes_filter_updater_kernel_HPP_ +#define AUTOWARE__probabilistic_occupancy_grid_map__UPDATER__log_odds_bayes_filter_updater_kernel_HPP_ + +#include "autoware/probabilistic_occupancy_grid_map/updater/log_odds_bayes_filter_updater_kernel.hpp" + +#include + +#define EPSILON_PROB 0.03 + +namespace autoware::occupancy_grid_map +{ +namespace costmap_2d +{ + +__host__ __device__ __forceinline__ double convertCharToProbability(const std::uint8_t value) +{ + return static_cast(value) / 255.0; +} + +__host__ __device__ __forceinline__ std::uint8_t convertProbabilityToChar(const double value) +{ + return static_cast(std::max(0.0, std::min(1.0, value)) * 255.0); + ; +} + +__host__ __device__ __forceinline__ double logOddsFusion(const double p1, const double p2) +{ + double log_odds = 0.0; + + const double p1_norm = std::max(EPSILON_PROB, std::min(1.0 - EPSILON_PROB, p1)); + log_odds += std::log(p1_norm / (1.0 - p1_norm)); + + const double p2_norm = std::max(EPSILON_PROB, std::min(1.0 - EPSILON_PROB, p2)); + log_odds += std::log(p2_norm / (1.0 - p2_norm)); + + return 1.0 / (1.0 + std::exp(-log_odds)); +} + +// cspell: ignore LOBF +__global__ void applyLOBFKernel( + const std::uint8_t * z_costmap, const std::uint8_t unknown_value, const int num_elements, + std::uint8_t * o_costmap) +{ + const int idx = blockIdx.x * blockDim.x + threadIdx.x; + if (idx >= num_elements) { + return; + } + + const std::uint8_t z = z_costmap[idx]; + const std::uint8_t o = o_costmap[idx]; + + const std::uint8_t unknown_margin = 1; + const double tau = 0.75; + const double sample_time = 0.1; + + if (z >= unknown_value - unknown_margin && z <= unknown_value + unknown_margin) { + const int diff = static_cast(o) - static_cast(unknown_value); + const double decay = std::exp(-sample_time / tau); + const double fused = static_cast(unknown_value) + static_cast(diff) * decay; + o_costmap[idx] = static_cast(fused); + } else { + const unsigned char fused = convertProbabilityToChar( + logOddsFusion(convertCharToProbability(z), convertCharToProbability(o))); + o_costmap[idx] = static_cast(fused); + } +} + +void applyLOBFLaunch( + const std::uint8_t * z_costmap, const std::uint8_t no_information_value, const int num_elements, + std::uint8_t * o_costmap, cudaStream_t stream) +{ + const int threads_per_block = 256; + const int num_blocks = (num_elements + threads_per_block - 1) / threads_per_block; + applyLOBFKernel<<>>( + z_costmap, no_information_value, num_elements, o_costmap); +} + +} // namespace costmap_2d +} // namespace autoware::occupancy_grid_map + +#endif // AUTOWARE__probabilistic_occupancy_grid_map__UPDATER__log_odds_bayes_filter_updater_kernel_HPP_ diff --git a/perception/autoware_probabilistic_occupancy_grid_map/lib/utils/utils.cpp b/perception/autoware_probabilistic_occupancy_grid_map/lib/utils/utils.cpp index 9d190664b8858..6ed51f9fccebc 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/lib/utils/utils.cpp +++ b/perception/autoware_probabilistic_occupancy_grid_map/lib/utils/utils.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 Tier IV, Inc. +// Copyright 2024 Tier IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -47,17 +47,29 @@ bool transformPointcloud( return true; } -// used in pointcloud based occupancy grid map -void transformPointcloud( - const sensor_msgs::msg::PointCloud2 & input, const geometry_msgs::msg::Pose & pose, - sensor_msgs::msg::PointCloud2 & output) +bool transformPointcloudAsync( + CudaPointCloud2 & input, const tf2_ros::Buffer & tf2, const std::string & target_frame) { - const auto transform = autoware::universe_utils::pose2transform(pose); - Eigen::Matrix4f tf_matrix = tf2::transformToEigen(transform).matrix().cast(); - - pcl_ros::transformPointCloud(tf_matrix, input, output); - output.header.stamp = input.header.stamp; - output.header.frame_id = ""; + geometry_msgs::msg::TransformStamped tf_stamped; + // lookup transform + try { + tf_stamped = tf2.lookupTransform( + target_frame, input.header.frame_id, input.header.stamp, rclcpp::Duration::from_seconds(0.5)); + } catch (tf2::TransformException & ex) { + RCLCPP_WARN( + rclcpp::get_logger("probabilistic_occupancy_grid_map"), "Failed to lookup transform: %s", + ex.what()); + return false; + } + // transform pointcloud + Eigen::Matrix4f tf_matrix = tf2::transformToEigen(tf_stamped.transform).matrix().cast(); + Eigen::Matrix3f rotation = tf_matrix.block<3, 3>(0, 0); + Eigen::Vector3f translation = tf_matrix.block<3, 1>(0, 3); + transformPointCloudLaunch( + input.data.get(), input.width * input.height, input.point_step, rotation, translation, + input.stream); + input.header.frame_id = target_frame; + return true; } Eigen::Matrix4f getTransformMatrix(const geometry_msgs::msg::Pose & pose) @@ -145,51 +157,5 @@ geometry_msgs::msg::Pose getInversePose(const geometry_msgs::msg::Pose & pose) return inv_pose; } -/** - * @brief extract Common Pointcloud between obstacle pc and raw pc - * @param obstacle_pc - * @param raw_pc - * @param output_obstacle_pc - */ -bool extractCommonPointCloud( - const sensor_msgs::msg::PointCloud2 & obstacle_pc, const sensor_msgs::msg::PointCloud2 & raw_pc, - sensor_msgs::msg::PointCloud2 & output_obstacle_pc) -{ - // Convert to vector of 3d points - std::vector v_obstacle_pc, v_raw_pc, v_output_obstacle_pc; - for (sensor_msgs::PointCloud2ConstIterator iter_x(obstacle_pc, "x"), - iter_y(obstacle_pc, "y"), iter_z(obstacle_pc, "z"); - iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) { - v_obstacle_pc.push_back(MyPoint3d(*iter_x, *iter_y, *iter_z)); - } - for (sensor_msgs::PointCloud2ConstIterator iter_x(raw_pc, "x"), iter_y(raw_pc, "y"), - iter_z(raw_pc, "z"); - iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) { - v_raw_pc.push_back(MyPoint3d(*iter_x, *iter_y, *iter_z)); - } - - // sort pointclouds for searching cross points: O(nlogn) - std::sort(v_obstacle_pc.begin(), v_obstacle_pc.end(), [](auto a, auto b) { return a < b; }); - std::sort(v_raw_pc.begin(), v_raw_pc.end(), [](auto a, auto b) { return a < b; }); - - // calc intersection points of two pointclouds: O(n) - std::set_intersection( - v_obstacle_pc.begin(), v_obstacle_pc.end(), v_raw_pc.begin(), v_raw_pc.end(), - std::back_inserter(v_output_obstacle_pc)); - if (v_output_obstacle_pc.size() == 0) { - return false; - } - - // Convert to ros msg - pcl::PointCloud::Ptr pcl_output(new pcl::PointCloud); - for (auto p : v_output_obstacle_pc) { - pcl_output->push_back(pcl::PointXYZ(p.x, p.y, p.z)); - } - pcl::toROSMsg(*pcl_output, output_obstacle_pc); - output_obstacle_pc.header = obstacle_pc.header; - - return true; -} - } // namespace utils } // namespace autoware::occupancy_grid_map diff --git a/perception/autoware_probabilistic_occupancy_grid_map/lib/utils/utils_kernel.cu b/perception/autoware_probabilistic_occupancy_grid_map/lib/utils/utils_kernel.cu new file mode 100644 index 0000000000000..696466fa89fbe --- /dev/null +++ b/perception/autoware_probabilistic_occupancy_grid_map/lib/utils/utils_kernel.cu @@ -0,0 +1,300 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, 2013, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Eitan Marder-Eppstein + * David V. Lu!! + *********************************************************************/ + +#include "autoware/probabilistic_occupancy_grid_map/utils/utils_kernel.hpp" + +namespace autoware::occupancy_grid_map +{ +namespace utils +{ + +inline __device__ bool worldToMap( + float wx, float wy, unsigned int & mx, unsigned int & my, float origin_x, float origin_y, + float resolution_inv, int size_x, int size_y) +{ + if (wx < origin_x || wy < origin_y) { + return false; + } + + mx = static_cast(std::floor((wx - origin_x) * resolution_inv)); + my = static_cast(std::floor((wy - origin_y) * resolution_inv)); + + if (mx < size_x && my < size_y) { + return true; + } + + return false; +} + +__device__ void setCellValue( + float wx, float wy, float origin_x, float origin_y, float resolution_inv, int size_x, int size_y, + std::uint8_t value, std::uint8_t * costmap_tensor) +{ + unsigned int mx, my; + if (!worldToMap(wx, wy, mx, my, origin_x, origin_y, resolution_inv, size_x, size_y)) { + return; + } + + costmap_tensor[my * size_x + mx] = value; +} + +inline __device__ void bresenham2D( + unsigned int abs_da, unsigned int abs_db, int error_b, int offset_a, int offset_b, + unsigned int offset, unsigned int max_length, std::uint8_t cost, std::uint8_t * costmap_tensor) +{ + unsigned int end = min(max_length, abs_da); + for (unsigned int i = 0; i < end; ++i) { + costmap_tensor[offset] = cost; + offset += offset_a; + error_b += abs_db; + if ((unsigned int)error_b >= abs_da) { + offset += offset_b; + error_b -= abs_da; + } + } + costmap_tensor[offset] = cost; +} + +/** + * @brief Raytrace a line and apply some action at each step + * @param at The action to take... a functor + * @param x0 The starting x coordinate + * @param y0 The starting y coordinate + * @param x1 The ending x coordinate + * @param y1 The ending y coordinate + * @param max_length The maximum desired length of the segment... + * allows you to not go all the way to the endpoint + * @param min_length The minimum desired length of the segment + */ +inline __device__ void raytraceLine( + unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, unsigned int max_length, + unsigned int min_length, unsigned int size_x, std::uint8_t cost, std::uint8_t * costmap_tensor) +{ + int dx_full = x1 - x0; + int dy_full = y1 - y0; + + // we need to chose how much to scale our dominant dimension, + // based on the maximum length of the line + float dist = sqrt((float)(dx_full * dx_full + dy_full * dy_full)); // hypot(dx_full, dy_full); + if (dist < min_length) { + return; + } + + unsigned int min_x0, min_y0; + if (dist > 0.0) { + // Adjust starting point and offset to start from min_length distance + min_x0 = (unsigned int)(x0 + dx_full / dist * min_length); + min_y0 = (unsigned int)(y0 + dy_full / dist * min_length); + } else { + // dist can be 0 if [x0, y0]==[x1, y1]. + // In this case only this cell should be processed. + min_x0 = x0; + min_y0 = y0; + } + unsigned int offset = min_y0 * size_x + min_x0; + + int dx = x1 - min_x0; + int dy = y1 - min_y0; + + unsigned int abs_dx = abs(dx); + unsigned int abs_dy = abs(dy); + + int offset_dx = dx > 0 ? 1 : -1; // sign(dx); + int offset_dy = dy > 0 ? size_x : -size_x; // sign(dy) * size_x; + + constexpr float epsilon = 1e-6; + float scale = (dist < epsilon) ? 1.0 : min(1.f, max_length / dist); + // if x is dominant + if (abs_dx >= abs_dy) { + int error_y = abs_dx / 2; + + bresenham2D( + abs_dx, abs_dy, error_y, offset_dx, offset_dy, offset, (unsigned int)(scale * abs_dx), cost, + costmap_tensor); + return; + } + + // otherwise y is dominant + int error_x = abs_dy / 2; + + bresenham2D( + abs_dy, abs_dx, error_x, offset_dy, offset_dx, offset, (unsigned int)(scale * abs_dy), cost, + costmap_tensor); +} + +void __device__ raytrace( + const float source_x, const float source_y, const float target_x, const float target_y, + const float origin_x, float origin_y, const float resolution_inv, const int size_x, + const int size_y, const std::uint8_t cost, std::uint8_t * costmap_tensor) +{ + unsigned int x0{}; + unsigned int y0{}; + const float ox{source_x}; + const float oy{source_y}; + + if (!worldToMap(ox, oy, x0, y0, origin_x, origin_y, resolution_inv, size_x, size_y)) { + return; + } + + // we can pre-compute the endpoints of the map outside of the inner loop... we'll need these later + const float resolution = 1.0 / resolution_inv; + const float map_end_x = origin_x + size_x * resolution; + const float map_end_y = origin_y + size_y * resolution; + + float wx = target_x; + float wy = target_y; + + // now we also need to make sure that the endpoint we're ray-tracing + // to isn't off the costmap and scale if necessary + const float a = wx - ox; + const float b = wy - oy; + + // the minimum value to raytrace from is the origin + if (wx < origin_x) { + const float t = (origin_x - ox) / a; + wx = origin_x; + wy = oy + b * t; + } + if (wy < origin_y) { + const float t = (origin_y - oy) / b; + wx = ox + a * t; + wy = origin_y; + } + + // the maximum value to raytrace to is the end of the map + if (wx > map_end_x) { + const float t = (map_end_x - ox) / a; + wx = map_end_x - .001; + wy = oy + b * t; + } + if (wy > map_end_y) { + const float t = (map_end_y - oy) / b; + wx = ox + a * t; + wy = map_end_y - .001; + } + + // now that the vector is scaled correctly... we'll get the map coordinates of its endpoint + unsigned int x1{}; + unsigned int y1{}; + + // check for legality just in case + if (!worldToMap(wx, wy, x1, y1, origin_x, origin_y, resolution_inv, size_x, size_y)) { + return; + } + + constexpr unsigned int cell_raytrace_range = 10000; // large number to ignore range threshold + raytraceLine(x0, y0, x1, y1, cell_raytrace_range, 0, size_x, cost, costmap_tensor); +} + +__global__ void transformPointCloudKernel( + std::uint8_t * points, std::size_t num_points, std::size_t points_step, + const Eigen::Matrix3f & rotation, const Eigen::Vector3f & translation) +{ + int idx = blockIdx.x * blockDim.x + threadIdx.x; + if (idx >= num_points) { + return; + } + + Eigen::Map point_map(reinterpret_cast(points + idx * points_step)); + point_map = rotation * point_map + translation; +} + +__global__ void copyMapRegionKernel( + const std::uint8_t * source_map, unsigned int sm_lower_left_x, unsigned int sm_lower_left_y, + unsigned int sm_size_x, unsigned int sm_size_y, std::uint8_t * dest_map, + unsigned int dm_lower_left_x, unsigned int dm_lower_left_y, unsigned int dm_size_x, + unsigned int dm_size_y, unsigned int region_size_x, unsigned int region_size_y) +{ + const int idx = blockIdx.x * blockDim.x + threadIdx.x; + if (idx >= region_size_x * region_size_y) return; + + const int region_y = idx / region_size_x; + const int region_x = idx % region_size_x; + + const int sm_index = + sm_lower_left_y * sm_size_x + sm_lower_left_x + region_y * sm_size_x + region_x; + const int dm_index = + dm_lower_left_y * dm_size_x + dm_lower_left_x + region_y * dm_size_x + region_x; + + if (sm_index < sm_size_x * sm_size_y && dm_index < dm_size_x * dm_size_y) { + dest_map[dm_index] = source_map[sm_index]; + } +} + +void transformPointCloudLaunch( + std::uint8_t * points, std::size_t num_points, std::size_t points_step, + const Eigen::Matrix3f & rotation, const Eigen::Vector3f & translation, cudaStream_t stream) +{ + // Launch kernel + int threads_per_block = 256; + int num_blocks = (num_points + threads_per_block - 1) / threads_per_block; + transformPointCloudKernel<<>>( + points, num_points, points_step, rotation, translation); +} + +void copyMapRegionLaunch( + const std::uint8_t * source_map, unsigned int sm_lower_left_x, unsigned int sm_lower_left_y, + unsigned int sm_size_x, unsigned int sm_size_y, std::uint8_t * dest_map, + unsigned int dm_lower_left_x, unsigned int dm_lower_left_y, unsigned int dm_size_x, + unsigned int dm_size_y, unsigned int region_size_x, unsigned int region_size_y, + cudaStream_t stream) +{ + const int threads_per_block = 256; + const int num_blocks = + (region_size_x * region_size_y + threads_per_block - 1) / threads_per_block; + + copyMapRegionKernel<<>>( + source_map, sm_lower_left_x, sm_lower_left_y, sm_size_x, sm_size_y, dest_map, dm_lower_left_x, + dm_lower_left_y, dm_size_x, dm_size_y, region_size_x, region_size_y); +} + +} // namespace utils +} // namespace autoware::occupancy_grid_map diff --git a/perception/autoware_probabilistic_occupancy_grid_map/package.xml b/perception/autoware_probabilistic_occupancy_grid_map/package.xml index ece7ef0dec663..06c3ed75f2758 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/package.xml +++ b/perception/autoware_probabilistic_occupancy_grid_map/package.xml @@ -7,6 +7,7 @@ Yukihiro Saito Yoshi Ri Mamoru Sobue + Kenzo Lobos-Tsunekawa Apache License 2.0 Yukihiro Saito @@ -15,6 +16,7 @@ autoware_cmake eigen3_cmake_module + autoware_cuda_utils autoware_universe_utils grid_map_costmap_2d grid_map_msgs diff --git a/perception/autoware_probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.cpp b/perception/autoware_probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.cpp index 7cde04ca9614b..cf1d828493035 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.cpp +++ b/perception/autoware_probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 TIER IV, Inc. +// Copyright 2024 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -115,8 +115,8 @@ GridMapFusionNode::GridMapFusionNode(const rclcpp::NodeOptions & node_options) // updater occupancy_grid_map_updater_ptr_ = std::make_shared( - fusion_map_length_x_ / fusion_map_resolution_, fusion_map_length_y_ / fusion_map_resolution_, - fusion_map_resolution_); + false, fusion_map_length_x_ / fusion_map_resolution_, + fusion_map_length_y_ / fusion_map_resolution_, fusion_map_resolution_); // Set timer const auto period_ns = std::chrono::duration_cast( @@ -309,7 +309,7 @@ void GridMapFusionNode::publish() // fusion map // single frame gridmap fusion - auto fused_map = SingleFrameOccupancyFusion(subscribed_maps, latest_stamp, weights); + auto & fused_map = SingleFrameOccupancyFusion(subscribed_maps, latest_stamp, weights); // multi frame gridmap fusion occupancy_grid_map_updater_ptr_->update(fused_map); @@ -341,7 +341,7 @@ void GridMapFusionNode::publish() } } -OccupancyGridMapFixedBlindSpot GridMapFusionNode::SingleFrameOccupancyFusion( +const OccupancyGridMapFixedBlindSpot & GridMapFusionNode::SingleFrameOccupancyFusion( std::vector & occupancy_grid_maps, const builtin_interfaces::msg::Time latest_stamp, const std::vector & weights) { @@ -367,22 +367,30 @@ OccupancyGridMapFixedBlindSpot GridMapFusionNode::SingleFrameOccupancyFusion( if (time_keeper_) inner_st_ptr = std::make_unique("create_fused_map", *time_keeper_); + if ( + !fused_map_ || fused_map_->getSizeInCellsX() != occupancy_grid_maps[0].getSizeInCellsX() || + fused_map_->getSizeInCellsY() != occupancy_grid_maps[0].getSizeInCellsY() || + fused_map_->getResolution() != occupancy_grid_maps[0].getResolution()) { + fused_map_ = std::make_unique( + false, occupancy_grid_maps[0].getSizeInCellsX(), occupancy_grid_maps[0].getSizeInCellsY(), + occupancy_grid_maps[0].getResolution()); + } + // init fused map with calculated origin - OccupancyGridMapFixedBlindSpot fused_map( - occupancy_grid_maps[0].getSizeInCellsX(), occupancy_grid_maps[0].getSizeInCellsY(), - occupancy_grid_maps[0].getResolution()); - fused_map.updateOrigin( - gridmap_origin.position.x - fused_map.getSizeInMetersX() / 2, - gridmap_origin.position.y - fused_map.getSizeInMetersY() / 2); + fused_map_->resetMaps(); + + fused_map_->updateOrigin( + gridmap_origin.position.x - fused_map_->getSizeInMetersX() / 2, + gridmap_origin.position.y - fused_map_->getSizeInMetersY() / 2); // fix origin of each map for (auto & map : occupancy_grid_maps) { - map.updateOrigin(fused_map.getOriginX(), fused_map.getOriginY()); + map.updateOrigin(fused_map_->getOriginX(), fused_map_->getOriginY()); } // assume map is same size and resolutions - for (unsigned int x = 0; x < fused_map.getSizeInCellsX(); x++) { - for (unsigned int y = 0; y < fused_map.getSizeInCellsY(); y++) { + for (unsigned int x = 0; x < fused_map_->getSizeInCellsX(); x++) { + for (unsigned int y = 0; y < fused_map_->getSizeInCellsY(); y++) { // get cost of each map std::vector costs; for (auto & map : occupancy_grid_maps) { @@ -393,11 +401,11 @@ OccupancyGridMapFixedBlindSpot GridMapFusionNode::SingleFrameOccupancyFusion( auto fused_cost = fusion_policy::singleFrameOccupancyFusion(costs, fusion_method_, weights); // set max cost to fused map - fused_map.setCost(x, y, fused_cost); + fused_map_->setCost(x, y, fused_cost); } } - return fused_map; + return *fused_map_; } // scope for time keeper ends } @@ -408,7 +416,7 @@ OccupancyGridMapFixedBlindSpot GridMapFusionNode::OccupancyGridMsgToGridMap( if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); OccupancyGridMapFixedBlindSpot gridmap( - occupancy_grid_map.info.width, occupancy_grid_map.info.height, + false, occupancy_grid_map.info.width, occupancy_grid_map.info.height, occupancy_grid_map.info.resolution); gridmap.updateOrigin( occupancy_grid_map.info.origin.position.x, occupancy_grid_map.info.origin.position.y); diff --git a/perception/autoware_probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.hpp b/perception/autoware_probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.hpp index 0f9475e476921..0d894d99a68a1 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.hpp +++ b/perception/autoware_probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.hpp @@ -1,4 +1,4 @@ -// Copyright 2023 Tier IV, Inc. +// Copyright 2024 Tier IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -69,7 +69,7 @@ class GridMapFusionNode : public rclcpp::Node OccupancyGridMapFixedBlindSpot OccupancyGridMsgToGridMap( const nav_msgs::msg::OccupancyGrid & occupancy_grid_map); - OccupancyGridMapFixedBlindSpot SingleFrameOccupancyFusion( + const OccupancyGridMapFixedBlindSpot & SingleFrameOccupancyFusion( std::vector & occupancy_grid_maps, const builtin_interfaces::msg::Time latest_stamp, const std::vector & weights); @@ -103,6 +103,7 @@ class GridMapFusionNode : public rclcpp::Node // cache for fusion std::mutex mutex_; + std::unique_ptr fused_map_; std::shared_ptr occupancy_grid_map_updater_ptr_; // contains fused grid map std::map diff --git a/perception/autoware_probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.cpp b/perception/autoware_probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.cpp index cb1b22a519e2d..4a8c9626de013 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.cpp +++ b/perception/autoware_probabilistic_occupancy_grid_map/src/laserscan_based_occupancy_grid_map/laserscan_based_occupancy_grid_map_node.cpp @@ -95,14 +95,14 @@ LaserscanBasedOccupancyGridMapNode::LaserscanBasedOccupancyGridMapNode( const std::string updater_type = this->declare_parameter("updater_type"); if (updater_type == "binary_bayes_filter") { occupancy_grid_map_updater_ptr_ = std::make_shared( - map_length / map_resolution, map_width / map_resolution, map_resolution); + false, map_length / map_resolution, map_width / map_resolution, map_resolution); } else { RCLCPP_WARN( get_logger(), "specified occupancy grid map updater type [%s] is not found, use binary_bayes_filter", updater_type.c_str()); occupancy_grid_map_updater_ptr_ = std::make_shared( - map_length / map_resolution, map_width / map_resolution, map_resolution); + false, map_length / map_resolution, map_width / map_resolution, map_resolution); } occupancy_grid_map_updater_ptr_->initRosParam(*this); diff --git a/perception/autoware_probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp b/perception/autoware_probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp index ff836a1ddf760..ba24e29284825 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp +++ b/perception/autoware_probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2024 Tier IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -85,26 +85,27 @@ PointcloudBasedOccupancyGridMapNode::PointcloudBasedOccupancyGridMapNode( const std::string updater_type = this->declare_parameter("updater_type"); if (updater_type == "binary_bayes_filter") { occupancy_grid_map_updater_ptr_ = std::make_unique( - map_length / map_resolution, map_length / map_resolution, map_resolution); + true, map_length / map_resolution, map_length / map_resolution, map_resolution); } else { RCLCPP_WARN( get_logger(), "specified occupancy grid map updater type [%s] is not found, use binary_bayes_filter", updater_type.c_str()); occupancy_grid_map_updater_ptr_ = std::make_unique( - map_length / map_resolution, map_length / map_resolution, map_resolution); + true, map_length / map_resolution, map_length / map_resolution, map_resolution); } occupancy_grid_map_updater_ptr_->initRosParam(*this); const std::string grid_map_type = this->declare_parameter("grid_map_type"); + if (grid_map_type == "OccupancyGridMapProjectiveBlindSpot") { occupancy_grid_map_ptr_ = std::make_unique( - occupancy_grid_map_updater_ptr_->getSizeInCellsX(), + true, occupancy_grid_map_updater_ptr_->getSizeInCellsX(), occupancy_grid_map_updater_ptr_->getSizeInCellsY(), occupancy_grid_map_updater_ptr_->getResolution()); } else if (grid_map_type == "OccupancyGridMapFixedBlindSpot") { occupancy_grid_map_ptr_ = std::make_unique( - occupancy_grid_map_updater_ptr_->getSizeInCellsX(), + true, occupancy_grid_map_updater_ptr_->getSizeInCellsX(), occupancy_grid_map_updater_ptr_->getSizeInCellsY(), occupancy_grid_map_updater_ptr_->getResolution()); } else { @@ -113,7 +114,7 @@ PointcloudBasedOccupancyGridMapNode::PointcloudBasedOccupancyGridMapNode( "specified occupancy grid map type [%s] is not found, use OccupancyGridMapFixedBlindSpot", grid_map_type.c_str()); occupancy_grid_map_ptr_ = std::make_unique( - occupancy_grid_map_updater_ptr_->getSizeInCellsX(), + true, occupancy_grid_map_updater_ptr_->getSizeInCellsX(), occupancy_grid_map_updater_ptr_->getSizeInCellsY(), occupancy_grid_map_updater_ptr_->getResolution()); } @@ -139,6 +140,9 @@ PointcloudBasedOccupancyGridMapNode::PointcloudBasedOccupancyGridMapNode( time_keeper_ = std::make_shared(time_keeper); } } + + cudaStreamCreate(&raw_pointcloud_.stream); + cudaStreamCreate(&obstacle_pointcloud_.stream); } void PointcloudBasedOccupancyGridMapNode::onPointcloudWithObstacleAndRaw( @@ -151,30 +155,27 @@ void PointcloudBasedOccupancyGridMapNode::onPointcloudWithObstacleAndRaw( if (stop_watch_ptr_) { stop_watch_ptr_->toc("processing_time", true); } - // if scan_origin_frame_ is "", replace it with input_raw_msg->header.frame_id + + raw_pointcloud_.fromROSMsgAsync(*input_raw_msg); + obstacle_pointcloud_.fromROSMsgAsync(*input_obstacle_msg); + + // if scan_origin_frame_ is "", replace it with raw_pointcloud_.header.frame_id if (scan_origin_frame_.empty()) { - scan_origin_frame_ = input_raw_msg->header.frame_id; + scan_origin_frame_ = raw_pointcloud_.header.frame_id; } - PointCloud2 trans_input_raw{}, trans_input_obstacle{}; - bool is_raw_transformed = false; - bool is_obstacle_transformed = false; - // Prepare for applying height filter if (use_height_filter_) { // Make sure that the frame is base_link - if (input_raw_msg->header.frame_id != base_link_frame_) { - if (!utils::transformPointcloud(*input_raw_msg, *tf2_, base_link_frame_, trans_input_raw)) { + if (raw_pointcloud_.header.frame_id != base_link_frame_) { + if (!utils::transformPointcloudAsync(raw_pointcloud_, *tf2_, base_link_frame_)) { return; } - is_raw_transformed = true; } if (input_obstacle_msg->header.frame_id != base_link_frame_) { - if (!utils::transformPointcloud( - *input_obstacle_msg, *tf2_, base_link_frame_, trans_input_obstacle)) { + if (!utils::transformPointcloudAsync(obstacle_pointcloud_, *tf2_, base_link_frame_)) { return; } - is_obstacle_transformed = true; } occupancy_grid_map_ptr_->setHeightLimit(min_height_, max_height_); } else { @@ -182,32 +183,16 @@ void PointcloudBasedOccupancyGridMapNode::onPointcloudWithObstacleAndRaw( -std::numeric_limits::infinity(), std::numeric_limits::infinity()); } - const PointCloud2::ConstSharedPtr input_raw_use = - is_raw_transformed ? std::make_shared(trans_input_raw) : input_raw_msg; - const PointCloud2::ConstSharedPtr input_obstacle_use = - is_obstacle_transformed ? std::make_shared(trans_input_obstacle) - : input_obstacle_msg; - - // Filter obstacle pointcloud by raw pointcloud - PointCloud2 input_obstacle_pc_common{}; - bool use_input_obstacle_pc_common = false; - if (filter_obstacle_pointcloud_by_raw_pointcloud_) { - if (utils::extractCommonPointCloud( - *input_obstacle_use, *input_raw_use, input_obstacle_pc_common)) { - use_input_obstacle_pc_common = true; - } - } - // Get from map to sensor frame pose Pose robot_pose{}; Pose gridmap_origin{}; Pose scan_origin{}; try { - robot_pose = utils::getPose(input_raw_msg->header.stamp, *tf2_, base_link_frame_, map_frame_); + robot_pose = utils::getPose(raw_pointcloud_.header.stamp, *tf2_, base_link_frame_, map_frame_); gridmap_origin = - utils::getPose(input_raw_msg->header.stamp, *tf2_, gridmap_origin_frame_, map_frame_); + utils::getPose(raw_pointcloud_.header.stamp, *tf2_, gridmap_origin_frame_, map_frame_); scan_origin = - utils::getPose(input_raw_msg->header.stamp, *tf2_, scan_origin_frame_, map_frame_); + utils::getPose(raw_pointcloud_.header.stamp, *tf2_, scan_origin_frame_, map_frame_); } catch (tf2::TransformException & ex) { RCLCPP_WARN_STREAM(get_logger(), ex.what()); return; @@ -224,9 +209,7 @@ void PointcloudBasedOccupancyGridMapNode::onPointcloudWithObstacleAndRaw( gridmap_origin.position.x - occupancy_grid_map_ptr_->getSizeInMetersX() / 2, gridmap_origin.position.y - occupancy_grid_map_ptr_->getSizeInMetersY() / 2); occupancy_grid_map_ptr_->updateWithPointCloud( - *input_raw_use, - (use_input_obstacle_pc_common ? input_obstacle_pc_common : *input_obstacle_use), robot_pose, - scan_origin); + raw_pointcloud_, obstacle_pointcloud_, robot_pose, scan_origin); } if (enable_single_frame_mode_) { @@ -234,6 +217,8 @@ void PointcloudBasedOccupancyGridMapNode::onPointcloudWithObstacleAndRaw( if (time_keeper_) inner_st_ptr = std::make_unique("publish_occupancy_grid_map", *time_keeper_); + occupancy_grid_map_ptr_->copyDeviceCostmapToHost(); + // publish occupancy_grid_map_pub_->publish(OccupancyGridMapToMsgPtr( map_frame_, input_raw_msg->header.stamp, robot_pose.position.z, diff --git a/perception/autoware_probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp b/perception/autoware_probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp index 34afd5edc7c37..c985414ffdf6b 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp +++ b/perception/autoware_probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2024 Tier IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -18,6 +18,7 @@ #include "autoware/probabilistic_occupancy_grid_map/costmap_2d/occupancy_grid_map_base.hpp" #include "autoware/probabilistic_occupancy_grid_map/updater/binary_bayes_filter_updater.hpp" #include "autoware/probabilistic_occupancy_grid_map/updater/ogm_updater_interface.hpp" +#include "autoware/probabilistic_occupancy_grid_map/utils/cuda_pointcloud.hpp" #include #include @@ -82,6 +83,9 @@ class PointcloudBasedOccupancyGridMapNode : public rclcpp::Node std::unique_ptr occupancy_grid_map_ptr_; std::unique_ptr occupancy_grid_map_updater_ptr_; + CudaPointCloud2 raw_pointcloud_; + CudaPointCloud2 obstacle_pointcloud_; + // ROS Parameters std::string map_frame_; std::string base_link_frame_; From 461dbc19b416c8fbb284fdc2a65f7c93b1215ddb Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Tue, 28 Jan 2025 18:30:58 +0900 Subject: [PATCH 330/334] feat(goal_planner): introduce bezier based pullover for bus stop area (#10027) Signed-off-by: Mamoru Sobue --- .../config/goal_planner.param.yaml | 27 +- .../goal_planner_module.hpp | 28 +- .../goal_planner_parameters.hpp | 7 + .../pull_over_planner_base.hpp | 7 +- .../thread_data.hpp | 6 +- .../src/goal_planner_module.cpp | 269 +++++++++++++----- .../src/goal_searcher.cpp | 7 +- .../src/manager.cpp | 10 + .../pull_over_planner/bezier_pull_over.cpp | 80 ++++-- .../pull_over_planner_base.cpp | 20 +- .../src/thread_data.cpp | 4 +- 11 files changed, 343 insertions(+), 122 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/goal_planner.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/goal_planner.param.yaml index 5eb71126bb838..95b2095f87164 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/goal_planner.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/goal_planner.param.yaml @@ -25,8 +25,8 @@ high_curvature_threshold: 0.1 bus_stop_area: use_bus_stop_area: false - goal_search_interval: 0.5 - lateral_offset_interval: 0.25 + goal_search_interval: 0.75 + lateral_offset_interval: 0.3 # occupancy grid map occupancy_grid: @@ -52,6 +52,7 @@ # pull over pull_over: minimum_request_length: 0.0 + pull_over_prepare_length: 100.0 pull_over_velocity: 3.0 pull_over_minimum_velocity: 1.38 decide_path_distance: 10.0 @@ -59,7 +60,7 @@ maximum_jerk: 1.0 path_priority: "efficient_path" # "efficient_path" or "close_goal" efficient_path_order: ["SHIFT", "ARC_FORWARD", "ARC_BACKWARD"] # only lane based pull over(exclude freespace parking) - lane_departure_check_expansion_margin: 0.0 + lane_departure_check_expansion_margin: 0.2 # shift parking shift_parking: @@ -73,21 +74,21 @@ # parallel parking path parallel_parking: path_interval: 1.0 - max_steer_angle: 0.35 # 20deg + max_steer_angle: 0.4 #22.9deg forward: enable_arc_forward_parking: true after_forward_parking_straight_distance: 2.0 forward_parking_velocity: 1.38 forward_parking_lane_departure_margin: 0.0 forward_parking_path_interval: 1.0 - forward_parking_max_steer_angle: 0.35 # 20deg + forward_parking_max_steer_angle: 0.4 # 22.9deg backward: enable_arc_backward_parking: true after_backward_parking_straight_distance: 2.0 backward_parking_velocity: -1.38 backward_parking_lane_departure_margin: 0.0 backward_parking_path_interval: 1.0 - backward_parking_max_steer_angle: 0.35 # 20deg + backward_parking_max_steer_angle: 0.4 # 22.9deg # freespace parking freespace_parking: @@ -130,6 +131,10 @@ neighbor_radius: 8.0 margin: 1.0 + bezier_parking: + pull_over_angle_threshold: 0.5 + after_shift_straight_distance: 1.5 + stop_condition: maximum_deceleration_for_stop: 1.0 maximum_jerk_for_stop: 1.0 @@ -139,13 +144,13 @@ min_velocity: 1.0 min_acceleration: 1.0 max_velocity: 1.0 - time_horizon_for_front_object: 10.0 - time_horizon_for_rear_object: 10.0 + time_horizon_for_front_object: 5.0 + time_horizon_for_rear_object: 5.0 time_resolution: 0.5 delay_until_departure: 1.0 # For target object filtering target_filtering: - safety_check_time_horizon: 10.0 + safety_check_time_horizon: 5.0 safety_check_time_resolution: 1.0 # detection range object_check_forward_distance: 100.0 @@ -179,7 +184,7 @@ # safety check configuration enable_safety_check: true method: "integral_predicted_polygon" - keep_unsafe_time: 3.0 + keep_unsafe_time: 0.5 # collision check parameters publish_debug_marker: false rss_params: @@ -192,7 +197,7 @@ forward_margin: 1.0 backward_margin: 1.0 lat_margin: 1.0 - time_horizon: 10.0 + time_horizon: 5.0 # hysteresis factor to expand/shrink polygon with the value hysteresis_factor_expand_rate: 1.0 collision_check_yaw_diff_threshold: 3.1416 diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp index 84367fdd91b80..f2cc7e2f4ef65 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -18,6 +18,7 @@ #include "autoware/behavior_path_goal_planner_module/decision_state.hpp" #include "autoware/behavior_path_goal_planner_module/fixed_goal_planner_base.hpp" #include "autoware/behavior_path_goal_planner_module/goal_planner_parameters.hpp" +#include "autoware/behavior_path_goal_planner_module/pull_over_planner/bezier_pull_over.hpp" #include "autoware/behavior_path_goal_planner_module/pull_over_planner/freespace_pull_over.hpp" #include "autoware/behavior_path_goal_planner_module/thread_data.hpp" #include "autoware/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp" @@ -86,8 +87,8 @@ struct PullOverContextData explicit PullOverContextData( const bool is_stable_safe_path, const PredictedObjects & static_objects, const PredictedObjects & dynamic_objects, const PathDecisionState & prev_state, - const bool is_stopped, const LaneParkingResponse & lane_parking_response, - const FreespaceParkingResponse & freespace_parking_response) + const bool is_stopped, LaneParkingResponse && lane_parking_response, + FreespaceParkingResponse && freespace_parking_response) : is_stable_safe_path(is_stable_safe_path), static_target_objects(static_objects), dynamic_target_objects(dynamic_objects), @@ -112,8 +113,8 @@ struct PullOverContextData void update( const bool is_stable_safe_path_, const PredictedObjects static_target_objects_, const PredictedObjects dynamic_target_objects_, const PathDecisionState prev_state_for_debug_, - const bool is_stopped_, const LaneParkingResponse & lane_parking_response_, - const FreespaceParkingResponse & freespace_parking_response_) + const bool is_stopped_, LaneParkingResponse && lane_parking_response_, + FreespaceParkingResponse && freespace_parking_response_) { is_stable_safe_path = is_stable_safe_path_; static_target_objects = static_target_objects_; @@ -196,6 +197,21 @@ class LaneParkingPlanner original_upstream_module_output_; // bezier_pull_over_planner_; + const double pull_over_angle_threshold; + + bool switch_bezier_{false}; + void normal_pullover_planning_helper( + const std::shared_ptr planner_data, const GoalCandidates & goal_candidates, + const BehaviorModuleOutput & upstream_module_output, + const lanelet::ConstLanelets current_lanelets, std::optional & closest_start_pose, + std::vector & path_candidates); + void bezier_planning_helper( + const std::shared_ptr planner_data, const GoalCandidates & goal_candidates, + const BehaviorModuleOutput & upstream_module_output, + const lanelet::ConstLanelets current_lanelets, std::optional & closest_start_pose, + std::vector & path_candidates, + std::optional> & sorted_indices) const; }; class FreespaceParkingPlanner @@ -302,6 +318,7 @@ class GoalPlannerModule : public SceneModuleInterface private: std::pair syncWithThreads(); + bool trigger_thread_on_approach_{false}; // NOTE: never access to following variables except in updateData()!!! std::mutex lane_parking_mutex_; std::optional lane_parking_request_; @@ -433,7 +450,8 @@ class GoalPlannerModule : public SceneModuleInterface std::optional selectPullOverPath( const PullOverContextData & context_data, const std::vector & pull_over_path_candidates, - const GoalCandidates & goal_candidates) const; + const GoalCandidates & goal_candidates, + const std::optional> sorted_bezier_indices_opt) const; // lanes and drivable area std::vector generateDrivableLanes() const; diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_parameters.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_parameters.hpp index 440e57b53d07f..814cffd388703 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_parameters.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_parameters.hpp @@ -88,6 +88,7 @@ struct GoalPlannerParameters // pull over general params double pull_over_minimum_request_length{0.0}; + double pull_over_prepare_length{0.0}; double pull_over_velocity{0.0}; double pull_over_minimum_velocity{0.0}; double decide_path_distance{0.0}; @@ -119,6 +120,12 @@ struct GoalPlannerParameters AstarParam astar_parameters{}; RRTStarParam rrt_star_parameters{}; + struct BezierParking + { + double pull_over_angle_threshold; + double after_shift_straight_distance; + } bezier_parking; + // stop condition double maximum_deceleration_for_stop{0.0}; double maximum_jerk_for_stop{0.0}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/pull_over_planner_base.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/pull_over_planner_base.hpp index 5af69894c0a2e..7f404a4055b26 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/pull_over_planner_base.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/pull_over_planner_base.hpp @@ -68,6 +68,10 @@ struct PullOverPath const std::vector & parking_path_curvatures() const { return parking_path_curvatures_; } double full_path_max_curvature() const { return full_path_max_curvature_; } double parking_path_max_curvature() const { return parking_path_max_curvature_; } + double parking_path_curvature_total_derivative() const + { + return parking_path_curvature_total_derivative_; + } size_t path_idx() const { return path_idx_; } bool incrementPathIndex(); @@ -94,7 +98,7 @@ struct PullOverPath const PathWithLaneId & full_path, const PathWithLaneId & parking_path, const std::vector & full_path_curvatures, const std::vector & parking_path_curvatures, const double full_path_max_curvature, - const double parking_path_max_curvature, + const double parking_path_max_curvature, const double parking_path_curvature_total_derivative, const std::vector> & pairs_terminal_velocity_and_accel); PullOverPlannerType type_; @@ -109,6 +113,7 @@ struct PullOverPath std::vector parking_path_curvatures_; double full_path_max_curvature_; double parking_path_max_curvature_; + double parking_path_curvature_total_derivative_; // accelerate with constant acceleration to the target velocity size_t path_idx_; diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/thread_data.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/thread_data.hpp index 7173b275e26fb..af20c5f6debe5 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/thread_data.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/thread_data.hpp @@ -43,7 +43,8 @@ class LaneParkingRequest void update( const PlannerData & planner_data, const ModuleStatus & current_status, const BehaviorModuleOutput & upstream_module_output, - const std::optional & pull_over_path, const PathDecisionState & prev_data); + const std::optional & pull_over_path, const PathDecisionState & prev_data, + const bool trigger_thread_on_approach); const autoware::universe_utils::LinearRing2d vehicle_footprint_; const GoalCandidates goal_candidates_; @@ -56,6 +57,7 @@ class LaneParkingRequest } const std::optional & get_pull_over_path() const { return pull_over_path_; } const PathDecisionState & get_prev_data() const { return prev_data_; } + bool trigger_thread_on_approach() const { return trigger_thread_on_approach_; } private: std::shared_ptr planner_data_; @@ -63,12 +65,14 @@ class LaneParkingRequest BehaviorModuleOutput upstream_module_output_; std::optional pull_over_path_; // pull_over_path_candidates; std::optional closest_start_pose; + std::optional> sorted_bezier_indices_opt; }; class FreespaceParkingRequest diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 762193ceab236..448429b9a3b0b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -29,6 +29,8 @@ #include "autoware/behavior_path_planner_common/utils/utils.hpp" #include "autoware/universe_utils/geometry/boost_polygon_utils.hpp" +#include +#include #include #include #include @@ -38,6 +40,7 @@ #include #include #include +#include #include #include #include @@ -276,7 +279,8 @@ LaneParkingPlanner::LaneParkingPlanner( request_(request), response_(response), is_lane_parking_cb_running_(is_lane_parking_cb_running), - logger_(logger) + logger_(logger), + pull_over_angle_threshold(parameters.bezier_parking.pull_over_angle_threshold) { for (const std::string & planner_type : parameters.efficient_path_order) { if (planner_type == "SHIFT" && parameters.enable_shift_parking) { @@ -290,6 +294,8 @@ LaneParkingPlanner::LaneParkingPlanner( } } + bezier_pull_over_planner_ = std::make_shared(node, parameters); + if (pull_over_planners_.empty()) { RCLCPP_ERROR(logger_, "Not found enabled planner"); } @@ -312,18 +318,18 @@ void LaneParkingPlanner::onTimer() } // end of critical section if (!local_request_opt) { - RCLCPP_ERROR(logger_, "main thread has not yet set request for LaneParkingPlanner"); + RCLCPP_DEBUG(logger_, "main thread has not yet set request for LaneParkingPlanner"); return; } const auto & local_request = local_request_opt.value(); const auto & goal_candidates = local_request.goal_candidates_; const auto & local_planner_data = local_request.get_planner_data(); - const auto & current_status = local_request.get_current_status(); const auto & upstream_module_output = local_request.get_upstream_module_output(); const auto & pull_over_path_opt = local_request.get_pull_over_path(); const auto & prev_data = local_request.get_prev_data(); + const auto trigger_thread_on_approach = local_request.trigger_thread_on_approach(); - if (current_status == ModuleStatus::IDLE) { + if (!trigger_thread_on_approach) { return; } @@ -387,19 +393,59 @@ void LaneParkingPlanner::onTimer() /*forward_only_in_route*/ false); std::vector path_candidates{}; std::optional closest_start_pose{}; - double min_start_arc_length = std::numeric_limits::max(); + std::optional> sorted_indices_opt{std::nullopt}; + if (parameters_.bus_stop_area.use_bus_stop_area && switch_bezier_) { + bezier_planning_helper( + local_planner_data, goal_candidates, upstream_module_output, current_lanes, + closest_start_pose, path_candidates, sorted_indices_opt); + } else { + normal_pullover_planning_helper( + local_planner_data, goal_candidates, upstream_module_output, current_lanes, + closest_start_pose, path_candidates); + } + + // set response + { + original_upstream_module_output_ = upstream_module_output; + std::lock_guard guard(mutex_); + response_.pull_over_path_candidates = path_candidates; + if (closest_start_pose) { + response_.closest_start_pose = closest_start_pose; + } + RCLCPP_INFO( + getLogger(), "generated %lu pull over path candidates", + response_.pull_over_path_candidates.size()); + response_.sorted_bezier_indices_opt = std::move(sorted_indices_opt); + } +} + +void LaneParkingPlanner::normal_pullover_planning_helper( + const std::shared_ptr planner_data, const GoalCandidates & goal_candidates, + const BehaviorModuleOutput & upstream_module_output, + const lanelet::ConstLanelets current_lanelets, std::optional & closest_start_pose, + std::vector & path_candidates) +{ + // todo: currently non centerline input path is supported only by shift pull over + const bool is_center_line_input_path = goal_planner_utils::isReferencePath( + upstream_module_output.reference_path, upstream_module_output.path, 0.1); + RCLCPP_DEBUG( + getLogger(), "the input path of pull over planner is center line: %d", + is_center_line_input_path); + + double min_start_arc_length = std::numeric_limits::infinity(); const auto planCandidatePaths = [&]( const std::shared_ptr & planner, const GoalCandidate & goal_candidate) { - const auto pull_over_path = planner->plan( - goal_candidate, path_candidates.size(), local_planner_data, upstream_module_output); + // normal pull_over + const auto pull_over_path = + planner->plan(goal_candidate, path_candidates.size(), planner_data, upstream_module_output); if (pull_over_path) { // calculate absolute maximum curvature of parking path(start pose to end pose) for path // priority path_candidates.push_back(*pull_over_path); // calculate closest pull over start pose for stop path const double start_arc_length = - lanelet::utils::getArcCoordinates(current_lanes, pull_over_path->start_pose()).length; + lanelet::utils::getArcCoordinates(current_lanelets, pull_over_path->start_pose()).length; if (start_arc_length < min_start_arc_length) { min_start_arc_length = start_arc_length; // closest start pose is stop point when not finding safe path @@ -408,13 +454,6 @@ void LaneParkingPlanner::onTimer() } }; - // todo: currently non centerline input path is supported only by shift pull over - const bool is_center_line_input_path = goal_planner_utils::isReferencePath( - upstream_module_output.reference_path, upstream_module_output.path, 0.1); - RCLCPP_DEBUG( - getLogger(), "the input path of pull over planner is center line: %d", - is_center_line_input_path); - // plan candidate paths and set them to the member variable if (parameters_.path_priority == "efficient_path") { for (const auto & planner : pull_over_planners_) { @@ -436,22 +475,104 @@ void LaneParkingPlanner::onTimer() planCandidatePaths(planner, goal_candidate); } } - } else { - RCLCPP_ERROR( - getLogger(), "path_priority should be efficient_path or close_goal, but %s is given.", - parameters_.path_priority.c_str()); - throw std::domain_error("[pull_over] invalid path_priority"); } - // set response - { - original_upstream_module_output_ = upstream_module_output; - std::lock_guard guard(mutex_); - response_.pull_over_path_candidates = std::move(path_candidates); - response_.closest_start_pose = closest_start_pose; + if (closest_start_pose) { + const auto original_pose = planner_data->route_handler->getOriginalGoalPose(); + if ( + parameters_.bus_stop_area.use_bus_stop_area && + std::fabs(autoware::universe_utils::normalizeRadian( + autoware::universe_utils::getRPY(original_pose).z - + autoware::universe_utils::getRPY(closest_start_pose.value()).z)) > + pull_over_angle_threshold) { + // reset and try bezier next time + switch_bezier_ = true; + path_candidates.clear(); + RCLCPP_INFO(getLogger(), "will generate Bezier Paths next"); + } + } else if (parameters_.bus_stop_area.use_bus_stop_area && path_candidates.size() == 0) { + switch_bezier_ = true; RCLCPP_INFO( - getLogger(), "generated %lu pull over path candidates", - response_.pull_over_path_candidates.size()); + getLogger(), "Could not find any shift pull over paths, will generate Bezier Paths next"); + } +} + +void LaneParkingPlanner::bezier_planning_helper( + const std::shared_ptr planner_data, const GoalCandidates & goal_candidates, + const BehaviorModuleOutput & upstream_module_output, + const lanelet::ConstLanelets current_lanelets, std::optional & closest_start_pose, + std::vector & path_candidates, + std::optional> & sorted_indices_opt) const +{ + autoware::universe_utils::StopWatch timer; + timer.tic("bezier"); + std::vector path_candidates_all; + for (const auto & goal_candidate : goal_candidates) { + auto bezier_pull_over_paths = bezier_pull_over_planner_->plans( + goal_candidate, path_candidates_all.size(), planner_data, upstream_module_output); + std::copy( + std::make_move_iterator(bezier_pull_over_paths.begin()), + std::make_move_iterator(bezier_pull_over_paths.end()), + std::back_inserter(path_candidates_all)); + } + RCLCPP_INFO( + getLogger(), "there are %lu bezier paths (calculated in %f [sec])", path_candidates_all.size(), + timer.toc("bezier")); + + sorted_indices_opt = std::vector(); + auto & sorted_indices = sorted_indices_opt.value(); + sorted_indices.reserve(path_candidates_all.size()); + + std::unordered_map goal_candidate_map; + for (const auto & goal_candidate : goal_candidates) { + goal_candidate_map[goal_candidate.id] = goal_candidate; + } + for (size_t i = 0; i < path_candidates_all.size(); ++i) { + const auto & path = path_candidates_all[i]; + const auto goal_candidate_it = goal_candidate_map.find(path.goal_id()); + if (goal_candidate_it != goal_candidate_map.end() && goal_candidate_it->second.is_safe) { + sorted_indices.push_back(i); + } + } + const auto dynamic_target_objects = goal_planner_utils::extract_dynamic_objects( + *(planner_data->dynamic_object), *(planner_data->route_handler), parameters_, + planner_data->parameters.vehicle_width); + const auto static_target_objects = utils::path_safety_checker::filterObjectsByVelocity( + dynamic_target_objects, parameters_.th_moving_object_velocity); + sortPullOverPaths( + planner_data, parameters_, path_candidates_all, goal_candidates, static_target_objects, + getLogger(), sorted_indices); + + const auto clip_size = std::min(path_candidates_all.size(), 100); + // take upto 100 elements + sorted_indices.resize(clip_size); + for (const auto sorted_index : sorted_indices) { + path_candidates.push_back(path_candidates_all[sorted_index]); + } + sorted_indices.clear(); + // now path_candidates are sorted from 0 to 100 + for (unsigned i = 0; i < clip_size; ++i) { + sorted_indices.push_back(i); + } + + std::stable_sort( + std::execution::par, sorted_indices.begin(), sorted_indices.end(), + [&](const size_t a_i, const size_t b_i) { + const auto & a = path_candidates[a_i]; + const auto & b = path_candidates[b_i]; + return a.parking_path_curvature_total_derivative() < + b.parking_path_curvature_total_derivative(); + }); + + double min_start_arc_length = std::numeric_limits::infinity(); + for (const auto & bezier_pull_over_path : path_candidates) { + const double start_arc_length = + lanelet::utils::getArcCoordinates(current_lanelets, bezier_pull_over_path.start_pose()) + .length; + if (start_arc_length < min_start_arc_length) { + min_start_arc_length = start_arc_length; + closest_start_pose = bezier_pull_over_path.start_pose(); + } } } @@ -471,7 +592,7 @@ void FreespaceParkingPlanner::onTimer() } // end of critical section if (!local_request_opt) { - RCLCPP_ERROR(logger_, "main thread has not yet set request for FreespaceParkingPlanner"); + RCLCPP_DEBUG(logger_, "main thread has not yet set request for FreespaceParkingPlanner"); return; } const auto & local_request = local_request_opt.value(); @@ -502,24 +623,9 @@ void FreespaceParkingPlanner::onTimer() return; } - const double vehicle_width = local_planner_data->parameters.vehicle_width; - const bool left_side_parking = parameters.parking_policy == ParkingPolicy::LEFT_SIDE; - const auto pull_over_lanes = goal_planner_utils::getPullOverLanes( - *(local_planner_data->route_handler), left_side_parking, parameters.backward_goal_search_length, - parameters.forward_goal_search_length); - const auto objects_extraction_polygon = goal_planner_utils::generateObjectExtractionPolygon( - pull_over_lanes, left_side_parking, parameters.detection_bound_offset, - parameters.margin_from_boundary + parameters.max_lateral_offset + vehicle_width); - - PredictedObjects dynamic_target_objects{}; - for (const auto & object : local_planner_data->dynamic_object->objects) { - const auto object_polygon = universe_utils::toPolygon2d(object); - if ( - objects_extraction_polygon.has_value() && - boost::geometry::intersects(object_polygon, objects_extraction_polygon.value())) { - dynamic_target_objects.objects.push_back(object); - } - } + const auto dynamic_target_objects = goal_planner_utils::extract_dynamic_objects( + *(local_planner_data->dynamic_object), *(local_planner_data->route_handler), parameters, + local_planner_data->parameters.vehicle_width); const auto static_target_objects = utils::path_safety_checker::filterObjectsByVelocity( dynamic_target_objects, parameters.th_moving_object_velocity); @@ -572,7 +678,7 @@ std::pair GoalPlannerModule::sync // count is affected lane_parking_request_.value().update( *planner_data_, getCurrentStatus(), getPreviousModuleOutput(), pull_over_path, - path_decision_controller_.get_current_state()); + path_decision_controller_.get_current_state(), trigger_thread_on_approach_); // NOTE: RouteHandler holds several shared pointers in it, so just copying PlannerData as // value does not adds the reference counts of RouteHandler.lanelet_map_ptr_ and others. Since // behavior_path_planner::run() updates @@ -614,19 +720,31 @@ void GoalPlannerModule::updateData() { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); - // extract static and dynamic objects in extraction polygon for path collision check - const auto dynamic_target_objects = goal_planner_utils::extract_dynamic_objects( - *(planner_data_->dynamic_object), *(planner_data_->route_handler), *parameters_, - planner_data_->parameters.vehicle_width); - const auto static_target_objects = utils::path_safety_checker::filterObjectsByVelocity( - dynamic_target_objects, parameters_->th_moving_object_velocity); - // update goal searcher and generate goal candidates if (goal_candidates_.empty()) { goal_candidates_ = generateGoalCandidates(); } - auto [lane_parking_response, freespace_parking_response] = syncWithThreads(); + const lanelet::ConstLanelets current_lanes = + utils::getCurrentLanesFromPath(getPreviousModuleOutput().reference_path, planner_data_); + + if ( + !trigger_thread_on_approach_ && + utils::isAllowedGoalModification(planner_data_->route_handler) && + goal_planner_utils::is_goal_reachable_on_path( + current_lanes, *(planner_data_->route_handler), left_side_parking_)) { + const double self_to_goal_arc_length = utils::getSignedDistance( + planner_data_->self_odometry->pose.pose, planner_data_->route_handler->getOriginalGoalPose(), + current_lanes); + if (self_to_goal_arc_length < parameters_->pull_over_prepare_length) { + trigger_thread_on_approach_ = true; + [[maybe_unused]] const auto send_only_request = syncWithThreads(); + RCLCPP_INFO( + getLogger(), "start preparing goal candidates once for goal ahead of %f meter", + self_to_goal_arc_length); + return; + } + } if (getCurrentStatus() == ModuleStatus::IDLE && !isExecutionRequested()) { return; @@ -657,11 +775,19 @@ void GoalPlannerModule::updateData() ego_predicted_path_params_, objects_filtering_params_, safety_check_params_); debug_data_.collision_check = collision_check_map; // update to latest state + // extract static and dynamic objects in extraction polygon for path collision check + const auto dynamic_target_objects = goal_planner_utils::extract_dynamic_objects( + *(planner_data_->dynamic_object), *(planner_data_->route_handler), *parameters_, + planner_data_->parameters.vehicle_width); + const auto static_target_objects = utils::path_safety_checker::filterObjectsByVelocity( + dynamic_target_objects, parameters_->th_moving_object_velocity); + path_decision_controller_.transit_state( found_pull_over_path, clock_->now(), static_target_objects, dynamic_target_objects, modified_goal_pose, planner_data_, occupancy_grid_map_, is_current_safe, *parameters_, goal_searcher_, isActivated(), pull_over_path_recv, debug_data_.ego_polygons_expanded); + auto [lane_parking_response, freespace_parking_response] = syncWithThreads(); if (context_data_) { context_data_.value().update( path_decision_controller_.get_current_state().is_stable_safe, static_target_objects, @@ -669,7 +795,7 @@ void GoalPlannerModule::updateData() isStopped( odometry_buffer_stopped_, planner_data_->self_odometry, parameters_->th_stopped_time, parameters_->th_stopped_velocity), - lane_parking_response, freespace_parking_response); + std::move(lane_parking_response), std::move(freespace_parking_response)); } else { context_data_.emplace( path_decision_controller_.get_current_state().is_stable_safe, static_target_objects, @@ -677,7 +803,7 @@ void GoalPlannerModule::updateData() isStopped( odometry_buffer_stopped_, planner_data_->self_odometry, parameters_->th_stopped_time, parameters_->th_stopped_velocity), - lane_parking_response, freespace_parking_response); + std::move(lane_parking_response), std::move(freespace_parking_response)); } auto & ctx_data = context_data_.value(); @@ -935,7 +1061,7 @@ void sortPullOverPaths( // Sort pull_over_path_candidates based on the order in goal_candidates std::stable_sort( - sorted_path_indices.begin(), sorted_path_indices.end(), + std::execution::par, sorted_path_indices.begin(), sorted_path_indices.end(), [&](const size_t a_i, const size_t b_i) { const auto & a = pull_over_path_candidates[a_i]; const auto & b = pull_over_path_candidates[b_i]; @@ -987,7 +1113,7 @@ void sortPullOverPaths( // sorts in descending order so the item with larger margin comes first std::stable_sort( - sorted_path_indices.begin(), sorted_path_indices.end(), + std::execution::par, sorted_path_indices.begin(), sorted_path_indices.end(), [&](const size_t a_i, const size_t b_i) { const auto & a = pull_over_path_candidates[a_i]; const auto & b = pull_over_path_candidates[b_i]; @@ -1022,7 +1148,7 @@ void sortPullOverPaths( // NOTE: this is just partition sort based on curvature threshold within each sub partitions std::stable_sort( - sorted_path_indices.begin(), sorted_path_indices.end(), + std::execution::par, sorted_path_indices.begin(), sorted_path_indices.end(), [&](const size_t a_i, const size_t b_i) { const auto & a = pull_over_path_candidates[a_i]; const auto & b = pull_over_path_candidates[b_i]; @@ -1043,7 +1169,7 @@ void sortPullOverPaths( // the collision check margin and curvature priority. if (parameters.path_priority == "efficient_path") { std::stable_sort( - sorted_path_indices.begin(), sorted_path_indices.end(), + std::execution::par, sorted_path_indices.begin(), sorted_path_indices.end(), [&](const size_t a_i, const size_t b_i) { // if any of following conditions are met, sort by path type priority // - both are soft margin @@ -1077,7 +1203,7 @@ void sortPullOverPaths( */ if (parameters.path_priority == "efficient_path") { std::stable_sort( - sorted_path_indices.begin(), sorted_path_indices.end(), + std::execution::par, sorted_path_indices.begin(), sorted_path_indices.end(), [&](const size_t a_i, const size_t b_i) { const auto & a = pull_over_path_candidates[a_i]; const auto & b = pull_over_path_candidates[b_i]; @@ -1093,7 +1219,8 @@ void sortPullOverPaths( std::optional GoalPlannerModule::selectPullOverPath( const PullOverContextData & context_data, const std::vector & pull_over_path_candidates, - const GoalCandidates & goal_candidates) const + const GoalCandidates & goal_candidates, + const std::optional> sorted_bezier_indices_opt) const { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); @@ -1105,8 +1232,11 @@ std::optional GoalPlannerModule::selectPullOverPath( // STEP1: Filter valid paths before sorting // NOTE: Since copying pull over path takes time, it is handled by indices std::vector sorted_path_indices; - sorted_path_indices.reserve(pull_over_path_candidates.size()); - + if (!sorted_bezier_indices_opt) { + sorted_path_indices.reserve(pull_over_path_candidates.size()); + } else { + sorted_path_indices = sorted_bezier_indices_opt.value(); + } // STEP1-1: Extract paths which have safe goal // Create a map of goal_id to GoalCandidate for quick access std::unordered_map goal_candidate_map; @@ -1412,7 +1542,7 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput(PullOverContextData // if the final path is not decided and enough time has passed since last path update, // select safe path from lane parking pull over path candidates // and set it to thread_safe_data_ - RCLCPP_DEBUG(getLogger(), "Update pull over path candidates"); + RCLCPP_INFO(getLogger(), "Update pull over path candidates"); context_data.pull_over_path_opt = std::nullopt; context_data.last_path_update_time = std::nullopt; @@ -1426,8 +1556,9 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput(PullOverContextData // Select a path that is as safe as possible and has a high priority. const auto & pull_over_path_candidates = context_data.lane_parking_response.pull_over_path_candidates; - const auto lane_pull_over_path_opt = - selectPullOverPath(context_data, pull_over_path_candidates, goal_candidates); + const auto lane_pull_over_path_opt = selectPullOverPath( + context_data, pull_over_path_candidates, goal_candidates, + context_data.lane_parking_response.sorted_bezier_indices_opt); // update thread_safe_data_ const auto & pull_over_path_opt = diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp index 66192a00a99fa..b973cfd7ed549 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp @@ -214,12 +214,9 @@ GoalCandidates GoalSearcher::search(const std::shared_ptr & p (transformed_vehicle_footprint.at(vehicle_info_utils::VehicleInfo::FrontLeftIndex) + transformed_vehicle_footprint.at(vehicle_info_utils::VehicleInfo::FrontRightIndex)) / 2.0; - lanelet::ConstLanelet vehicle_front_closest_lanelet; - lanelet::utils::query::getClosestLanelet( - pull_over_lanes, search_pose, &vehicle_front_closest_lanelet); + const auto pull_over_lanelet = lanelet::utils::combineLaneletsShape(pull_over_lanes); const auto vehicle_front_pose_for_bound_opt = goal_planner_utils::calcClosestPose( - left_side_parking_ ? vehicle_front_closest_lanelet.leftBound() - : vehicle_front_closest_lanelet.rightBound(), + left_side_parking_ ? pull_over_lanelet.leftBound() : pull_over_lanelet.rightBound(), autoware::universe_utils::createPoint( vehicle_front_midpoint.x(), vehicle_front_midpoint.y(), search_pose.position.z)); if (!vehicle_front_pose_for_bound_opt) { diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp index a99252c923328..aeaf6836cdba3 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp @@ -139,6 +139,7 @@ GoalPlannerParameters GoalPlannerModuleManager::initGoalPlannerParameters( const std::string ns = base_ns + "pull_over."; p.pull_over_minimum_request_length = node->declare_parameter(ns + "minimum_request_length"); + p.pull_over_prepare_length = node->declare_parameter(ns + "pull_over_prepare_length"); p.pull_over_velocity = node->declare_parameter(ns + "pull_over_velocity"); p.pull_over_minimum_velocity = node->declare_parameter(ns + "pull_over_minimum_velocity"); @@ -266,6 +267,15 @@ GoalPlannerParameters GoalPlannerModuleManager::initGoalPlannerParameters( p.rrt_star_parameters.margin = node->declare_parameter(ns + "margin"); } + // bezier parking + { + const std::string ns = base_ns + "pull_over.bezier_parking."; + p.bezier_parking.pull_over_angle_threshold = + node->declare_parameter(ns + "pull_over_angle_threshold"); + p.bezier_parking.after_shift_straight_distance = + node->declare_parameter(ns + "after_shift_straight_distance"); + } + // stop condition { p.maximum_deceleration_for_stop = diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/bezier_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/bezier_pull_over.cpp index ec3984a6d9443..3347f2e4a6bdf 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/bezier_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/bezier_pull_over.cpp @@ -33,8 +33,12 @@ namespace autoware::behavior_path_planner { BezierPullOver::BezierPullOver(rclcpp::Node & node, const GoalPlannerParameters & parameters) : PullOverPlannerBase(node, parameters), - lane_departure_checker_( - lane_departure_checker::Param{parameters.lane_departure_check_expansion_margin}, vehicle_info_), + lane_departure_checker_{[&]() { + auto lane_departure_checker_params = lane_departure_checker::Param{}; + lane_departure_checker_params.footprint_extra_margin = + parameters.lane_departure_check_expansion_margin; + return LaneDepartureChecker{lane_departure_checker_params, vehicle_info_}; + }()}, left_side_parking_(parameters.parking_policy == ParkingPolicy::LEFT_SIDE) { } @@ -76,7 +80,8 @@ std::optional BezierPullOver::plan( } std::vector BezierPullOver::plans( - [[maybe_unused]] const GoalCandidate & modified_goal_pose, [[maybe_unused]] const size_t id, + [[maybe_unused]] const GoalCandidate & modified_goal_pose, + [[maybe_unused]] const size_t initial_id, [[maybe_unused]] const std::shared_ptr planner_data, [[maybe_unused]] const BehaviorModuleOutput & upstream_module_output) { @@ -101,10 +106,12 @@ std::vector BezierPullOver::plans( // find safe one from paths with different jerk std::vector paths; + auto id = initial_id; for (double lateral_jerk = min_jerk; lateral_jerk <= max_jerk; lateral_jerk += jerk_resolution) { auto pull_over_paths = generateBezierPath( modified_goal_pose, id, planner_data, upstream_module_output, road_lanes, pull_over_lanes, lateral_jerk); + id += pull_over_paths.size(); std::copy( std::make_move_iterator(pull_over_paths.begin()), std::make_move_iterator(pull_over_paths.end()), std::back_inserter(paths)); @@ -114,17 +121,20 @@ std::vector BezierPullOver::plans( } std::vector BezierPullOver::generateBezierPath( - const GoalCandidate & goal_candidate, const size_t id, + const GoalCandidate & goal_candidate, const size_t initial_id, const std::shared_ptr planner_data, const BehaviorModuleOutput & upstream_module_output, const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & pull_over_lanes, const double lateral_jerk) const { const double pull_over_velocity = parameters_.pull_over_velocity; + const double after_shift_straight_distance = + parameters_.bezier_parking.after_shift_straight_distance; const auto & goal_pose = goal_candidate.goal_pose; // shift end pose is longitudinal offset from goal pose to improve parking angle accuracy - const Pose shift_end_pose = goal_pose; + const Pose shift_end_pose = + autoware::universe_utils::calcOffsetPose(goal_pose, -after_shift_straight_distance, 0, 0); // calculate lateral shift of previous module path terminal pose from road lane reference path const auto road_lane_reference_path_to_shift_end = utils::resamplePathWithSpline( @@ -174,21 +184,33 @@ std::vector BezierPullOver::generateBezierPath( -before_shifted_pull_over_distance); std::vector> params; - const size_t n_sample_v_init = 4; - const size_t n_sample_v_final = 4; - const size_t n_sample_acc = 3; + const size_t n_sample_v_init = 3; + const size_t n_sample_v_final = 3; + const size_t n_sample_acc = 2; for (unsigned i = 0; i <= n_sample_v_init; ++i) { for (unsigned j = 0; j <= n_sample_v_final; j++) { for (unsigned k = 0; k <= n_sample_acc; k++) { - const double v_init_coeff = i * 0.25; - const double v_final_coeff = j * 0.25; - const double acc_coeff = k * (10.0 / 3); + const double v_init_coeff = i * (1.0 / n_sample_v_init); + const double v_final_coeff = j * 0.25 / (1.0 / n_sample_v_final); + const double acc_coeff = k * (10.0 / n_sample_acc); params.emplace_back(v_init_coeff, v_final_coeff, acc_coeff); } } } + const auto drivable_lanes = + utils::generateDrivableLanesWithShoulderLanes(road_lanes, pull_over_lanes); + const auto & dp = planner_data->drivable_area_expansion_parameters; + const auto expanded_lanes = utils::expandLanelets( + drivable_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset, + dp.drivable_area_types_to_skip); + const auto combined_drivable = utils::combineDrivableLanes( + expanded_lanes, upstream_module_output.drivable_area_info.drivable_lanes); + const auto parking_lot_polygons = + lanelet::utils::query::getAllParkingLots(planner_data->route_handler->getLaneletMapPtr()); + std::vector bezier_paths; + auto id = initial_id; for (const auto & [v_init_coeff, v_final_coeff, acc_coeff] : params) { // set path shifter and generate shifted path PathShifter path_shifter{}; @@ -213,7 +235,7 @@ std::vector BezierPullOver::generateBezierPath( const auto from_idx = from_idx_opt.value(); const auto to_idx = to_idx_opt.value(); const auto span = static_cast( - std::max(static_cast(to_idx) - static_cast(from_idx), 0)); + std::max(static_cast(to_idx) - static_cast(from_idx) + 1, 0)); const auto reference_curvature = autoware::motion_utils::calcCurvature(processed_prev_module_path->points); const auto & from_pose = shifted_path.path.points[from_idx].point.pose; @@ -224,7 +246,10 @@ std::vector BezierPullOver::generateBezierPath( reference_curvature.at(from_idx), tf2::getYaw(from_pose.orientation)}; const autoware::sampler_common::State final{ - {to_pose.position.x, to_pose.position.y}, {0.0, 0.0}, 0.0, tf2::getYaw(to_pose.orientation)}; + {to_pose.position.x, to_pose.position.y}, + {0.0, 0.0}, + reference_curvature.at(to_idx), + tf2::getYaw(to_pose.orientation)}; // setting the initial velocity to higher gives straight forward path (the steering does not // change) const auto bezier_path = @@ -237,10 +262,20 @@ std::vector BezierPullOver::generateBezierPath( p.point.pose.orientation = universe_utils::createQuaternionFromRPY(0.0, 0.0, bezier_points[i].z()); } + + // interpolate between shift end pose to goal pose + for (const auto & toward_goal_straight_pose : + utils::interpolatePose(shift_end_pose, goal_pose, 0.5)) { + PathPointWithLaneId p = shifted_path.path.points.back(); + p.point.pose = toward_goal_straight_pose; + shifted_path.path.points.push_back(p); + } + shifted_path.path.points = autoware::motion_utils::removeOverlapPoints(shifted_path.path.points); - - autoware::motion_utils::insertOrientation(shifted_path.path.points, true); + /* insertOrientation erases original goal pose, so not used + autoware::motion_utils::insertOrientation(shifted_path.path.points, true); + */ // combine road lanes and shoulder lanes to find closest lanelet id const auto lanes = std::invoke([&]() -> lanelet::ConstLanelets { @@ -289,11 +324,9 @@ std::vector BezierPullOver::generateBezierPath( // check if the parking path will leave drivable area and lanes const bool is_in_parking_lots = std::invoke([&]() -> bool { - const auto & p = planner_data->parameters; - const auto parking_lot_polygons = - lanelet::utils::query::getAllParkingLots(planner_data->route_handler->getLaneletMapPtr()); const auto path_footprints = goal_planner_utils::createPathFootPrints( - pull_over_path.parking_path(), p.base_link2front, p.base_link2rear, p.vehicle_width); + pull_over_path.parking_path(), planner_data->parameters.base_link2front, + planner_data->parameters.base_link2rear, planner_data->parameters.vehicle_width); const auto is_footprint_in_any_polygon = [&parking_lot_polygons](const auto & footprint) { return std::any_of( parking_lot_polygons.begin(), parking_lot_polygons.end(), @@ -309,14 +342,6 @@ std::vector BezierPullOver::generateBezierPath( }); }); const bool is_in_lanes = std::invoke([&]() -> bool { - const auto drivable_lanes = - utils::generateDrivableLanesWithShoulderLanes(road_lanes, pull_over_lanes); - const auto & dp = planner_data->drivable_area_expansion_parameters; - const auto expanded_lanes = utils::expandLanelets( - drivable_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset, - dp.drivable_area_types_to_skip); - const auto combined_drivable = utils::combineDrivableLanes( - expanded_lanes, upstream_module_output.drivable_area_info.drivable_lanes); return !lane_departure_checker_.checkPathWillLeaveLane( utils::transformToLanelets(combined_drivable), pull_over_path.parking_path()); }); @@ -324,6 +349,7 @@ std::vector BezierPullOver::generateBezierPath( continue; } bezier_paths.push_back(std::move(pull_over_path)); + id++; } return bezier_paths; diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/pull_over_planner_base.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/pull_over_planner_base.cpp index 31d8afffbdabe..acb6ee1926a83 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/pull_over_planner_base.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/pull_over_planner_base.cpp @@ -13,7 +13,9 @@ // limitations under the License. #include +#include +#include #include #include @@ -78,11 +80,24 @@ std::optional PullOverPath::create( std::tie(full_path_curvatures, full_path_max_curvature) = calculateCurvaturesAndMax(full_path); std::tie(parking_path_curvatures, parking_path_max_curvature) = calculateCurvaturesAndMax(parking_path); + const double parking_path_curvature_total_derivative = [&]() { + const auto parking_path_curvature_base = autoware::motion_utils::calcSignedArcLengthPartialSum( + parking_path.points, 1, parking_path.points.size() - 1); + const auto size = std::min(parking_path_curvatures.size(), parking_path_curvature_base.size()); + double total_abs_kappa_diff = 0; + for (unsigned i = 0; i + 1 < size; ++i) { + total_abs_kappa_diff += std::fabs( + (parking_path_curvatures.at(i + 1) - parking_path_curvatures.at(i)) / + (parking_path_curvature_base.at(i + 1) - parking_path_curvature_base.at(i))); + } + return total_abs_kappa_diff; + }(); return PullOverPath( type, id, start_pose, modified_goal_pose, partial_paths, full_path, parking_path, full_path_curvatures, parking_path_curvatures, full_path_max_curvature, - parking_path_max_curvature, pairs_terminal_velocity_and_accel); + parking_path_max_curvature, parking_path_curvature_total_derivative, + pairs_terminal_velocity_and_accel); } PullOverPath::PullOverPath(const PullOverPath & other) @@ -108,7 +123,7 @@ PullOverPath::PullOverPath( const PathWithLaneId & full_path, const PathWithLaneId & parking_path, const std::vector & full_path_curvatures, const std::vector & parking_path_curvatures, const double full_path_max_curvature, - const double parking_path_max_curvature, + const double parking_path_max_curvature, const double parking_path_curvature_total_derivative, const std::vector> & pairs_terminal_velocity_and_accel) : type_(type), modified_goal_pose_(modified_goal_pose), @@ -121,6 +136,7 @@ PullOverPath::PullOverPath( parking_path_curvatures_(parking_path_curvatures), full_path_max_curvature_(full_path_max_curvature), parking_path_max_curvature_(parking_path_max_curvature), + parking_path_curvature_total_derivative_(parking_path_curvature_total_derivative), path_idx_(0), pairs_terminal_velocity_and_accel_(pairs_terminal_velocity_and_accel) { diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/thread_data.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/thread_data.cpp index 89458c199c130..c334fec7a1bd9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/thread_data.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/thread_data.cpp @@ -22,7 +22,8 @@ namespace autoware::behavior_path_planner void LaneParkingRequest::update( const PlannerData & planner_data, const ModuleStatus & current_status, const BehaviorModuleOutput & upstream_module_output, - const std::optional & pull_over_path, const PathDecisionState & prev_data) + const std::optional & pull_over_path, const PathDecisionState & prev_data, + const bool trigger_thread_on_approach) { planner_data_ = std::make_shared(planner_data); planner_data_->route_handler = std::make_shared(*(planner_data.route_handler)); @@ -30,6 +31,7 @@ void LaneParkingRequest::update( upstream_module_output_ = upstream_module_output; pull_over_path_ = pull_over_path; prev_data_ = prev_data; + trigger_thread_on_approach_ = trigger_thread_on_approach; } void FreespaceParkingRequest::initializeOccupancyGridMap( From 6adf132453ccf23435114e091005424952406747 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Wed, 29 Jan 2025 12:10:33 +0900 Subject: [PATCH 331/334] chore: bump version to 0.41.0 (#10037) Signed-off-by: Fumiya Watanabe --- common/autoware_adapi_specs/CHANGELOG.rst | 12 + common/autoware_adapi_specs/package.xml | 2 +- common/autoware_auto_common/CHANGELOG.rst | 3 + common/autoware_auto_common/package.xml | 2 +- .../CHANGELOG.rst | 6 + .../package.xml | 2 +- .../CHANGELOG.rst | 3 + .../package.xml | 2 +- .../CHANGELOG.rst | 3 + .../package.xml | 2 +- common/autoware_fake_test_node/CHANGELOG.rst | 3 + common/autoware_fake_test_node/package.xml | 2 +- .../CHANGELOG.rst | 5 +- .../package.xml | 2 +- common/autoware_glog_component/CHANGELOG.rst | 5 +- common/autoware_glog_component/package.xml | 2 +- .../CHANGELOG.rst | 6 + .../package.xml | 2 +- common/autoware_grid_map_utils/CHANGELOG.rst | 3 + common/autoware_grid_map_utils/package.xml | 2 +- common/autoware_interpolation/CHANGELOG.rst | 6 + common/autoware_interpolation/package.xml | 2 +- common/autoware_motion_utils/CHANGELOG.rst | 36 +++ common/autoware_motion_utils/package.xml | 2 +- .../CHANGELOG.rst | 3 + .../package.xml | 2 +- .../CHANGELOG.rst | 3 + .../package.xml | 2 +- common/autoware_polar_grid/CHANGELOG.rst | 3 + common/autoware_polar_grid/package.xml | 2 +- common/autoware_pyplot/CHANGELOG.rst | 6 + common/autoware_pyplot/package.xml | 2 +- .../autoware_signal_processing/CHANGELOG.rst | 3 + common/autoware_signal_processing/package.xml | 2 +- common/autoware_test_utils/CHANGELOG.rst | 18 ++ common/autoware_test_utils/package.xml | 2 +- common/autoware_testing/CHANGELOG.rst | 3 + common/autoware_testing/package.xml | 2 +- common/autoware_time_utils/CHANGELOG.rst | 3 + common/autoware_time_utils/package.xml | 2 +- .../CHANGELOG.rst | 3 + .../package.xml | 2 +- .../CHANGELOG.rst | 3 + .../autoware_traffic_light_utils/package.xml | 2 +- common/autoware_trajectory/CHANGELOG.rst | 3 + common/autoware_trajectory/package.xml | 2 +- common/autoware_universe_utils/CHANGELOG.rst | 27 +++ common/autoware_universe_utils/package.xml | 2 +- .../autoware_vehicle_info_utils/CHANGELOG.rst | 3 + .../autoware_vehicle_info_utils/package.xml | 2 +- common/tier4_api_utils/CHANGELOG.rst | 3 + common/tier4_api_utils/package.xml | 2 +- .../CHANGELOG.rst | 3 + .../package.xml | 2 +- .../autoware_collision_detector/CHANGELOG.rst | 3 + .../autoware_collision_detector/package.xml | 2 +- .../CHANGELOG.rst | 31 +++ .../package.xml | 2 +- .../autoware_control_validator/CHANGELOG.rst | 7 + .../autoware_control_validator/package.xml | 2 +- .../CHANGELOG.rst | 3 + .../package.xml | 2 +- control/autoware_joy_controller/CHANGELOG.rst | 3 + control/autoware_joy_controller/package.xml | 2 +- .../CHANGELOG.rst | 13 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 19 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 3 + .../package.xml | 2 +- .../CHANGELOG.rst | 6 + .../package.xml | 2 +- .../CHANGELOG.rst | 21 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 27 ++- .../package.xml | 2 +- control/autoware_pure_pursuit/CHANGELOG.rst | 7 + control/autoware_pure_pursuit/package.xml | 2 +- control/autoware_shift_decider/CHANGELOG.rst | 3 + control/autoware_shift_decider/package.xml | 2 +- .../CHANGELOG.rst | 6 + .../package.xml | 2 +- .../CHANGELOG.rst | 7 + .../package.xml | 2 +- .../CHANGELOG.rst | 14 ++ .../package.xml | 2 +- .../autoware_vehicle_cmd_gate/CHANGELOG.rst | 7 + control/autoware_vehicle_cmd_gate/package.xml | 2 +- .../autoware_control_evaluator/CHANGELOG.rst | 23 ++ .../autoware_control_evaluator/package.xml | 2 +- .../CHANGELOG.rst | 6 + .../autoware_kinematic_evaluator/package.xml | 2 +- .../CHANGELOG.rst | 21 +- .../package.xml | 2 +- .../CHANGELOG.rst | 27 ++- .../package.xml | 2 +- .../autoware_planning_evaluator/CHANGELOG.rst | 32 +++ .../autoware_planning_evaluator/package.xml | 2 +- .../CHANGELOG.rst | 22 +- .../package.xml | 2 +- .../tier4_autoware_api_launch/CHANGELOG.rst | 8 + launch/tier4_autoware_api_launch/package.xml | 2 +- launch/tier4_control_launch/CHANGELOG.rst | 25 ++ launch/tier4_control_launch/package.xml | 2 +- .../tier4_localization_launch/CHANGELOG.rst | 8 + launch/tier4_localization_launch/package.xml | 2 +- launch/tier4_map_launch/CHANGELOG.rst | 3 + launch/tier4_map_launch/package.xml | 2 +- launch/tier4_perception_launch/CHANGELOG.rst | 41 ++++ launch/tier4_perception_launch/package.xml | 2 +- launch/tier4_planning_launch/CHANGELOG.rst | 7 + launch/tier4_planning_launch/package.xml | 2 +- launch/tier4_sensing_launch/CHANGELOG.rst | 3 + launch/tier4_sensing_launch/package.xml | 2 +- launch/tier4_simulator_launch/CHANGELOG.rst | 70 ++++++ launch/tier4_simulator_launch/package.xml | 2 +- launch/tier4_system_launch/CHANGELOG.rst | 75 ++++++ launch/tier4_system_launch/package.xml | 2 +- launch/tier4_vehicle_launch/CHANGELOG.rst | 3 + launch/tier4_vehicle_launch/package.xml | 2 +- .../autoware_ekf_localizer/CHANGELOG.rst | 20 ++ .../autoware_ekf_localizer/package.xml | 2 +- .../autoware_geo_pose_projector/CHANGELOG.rst | 6 + .../autoware_geo_pose_projector/package.xml | 2 +- .../autoware_gyro_odometer/CHANGELOG.rst | 22 ++ .../autoware_gyro_odometer/package.xml | 2 +- .../CHANGELOG.rst | 3 + .../package.xml | 2 +- .../autoware_landmark_manager/CHANGELOG.rst | 3 + .../autoware_landmark_manager/package.xml | 2 +- .../CHANGELOG.rst | 27 +++ .../package.xml | 2 +- .../CHANGELOG.rst | 22 ++ .../package.xml | 2 +- .../autoware_ndt_scan_matcher/CHANGELOG.rst | 24 ++ .../autoware_ndt_scan_matcher/package.xml | 2 +- .../autoware_pose2twist/CHANGELOG.rst | 6 + localization/autoware_pose2twist/package.xml | 2 +- .../CHANGELOG.rst | 11 + .../package.xml | 2 +- .../CHANGELOG.rst | 3 + .../package.xml | 2 +- .../autoware_pose_initializer/CHANGELOG.rst | 26 +++ .../autoware_pose_initializer/package.xml | 2 +- .../CHANGELOG.rst | 3 + .../package.xml | 2 +- .../autoware_stop_filter/CHANGELOG.rst | 11 + localization/autoware_stop_filter/package.xml | 2 +- .../autoware_twist2accel/CHANGELOG.rst | 9 + localization/autoware_twist2accel/package.xml | 2 +- .../yabloc/yabloc_common/CHANGELOG.rst | 3 + localization/yabloc/yabloc_common/package.xml | 2 +- .../yabloc_image_processing/CHANGELOG.rst | 3 + .../yabloc_image_processing/package.xml | 2 +- .../yabloc/yabloc_monitor/CHANGELOG.rst | 3 + .../yabloc/yabloc_monitor/package.xml | 2 +- .../yabloc_particle_filter/CHANGELOG.rst | 3 + .../yabloc/yabloc_particle_filter/package.xml | 2 +- .../yabloc_pose_initializer/CHANGELOG.rst | 3 + .../yabloc_pose_initializer/package.xml | 2 +- .../CHANGELOG.rst | 3 + .../package.xml | 2 +- map/autoware_map_height_fitter/CHANGELOG.rst | 3 + map/autoware_map_height_fitter/package.xml | 2 +- map/autoware_map_loader/CHANGELOG.rst | 6 + map/autoware_map_loader/package.xml | 2 +- .../CHANGELOG.rst | 6 + .../package.xml | 2 +- map/autoware_map_tf_generator/CHANGELOG.rst | 3 + map/autoware_map_tf_generator/package.xml | 2 +- perception/autoware_bytetrack/CHANGELOG.rst | 7 + perception/autoware_bytetrack/package.xml | 2 +- .../autoware_cluster_merger/CHANGELOG.rst | 3 + .../autoware_cluster_merger/package.xml | 2 +- .../CHANGELOG.rst | 8 + .../package.xml | 2 +- .../CHANGELOG.rst | 23 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 3 + .../package.xml | 2 +- .../CHANGELOG.rst | 22 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 8 + .../autoware_detection_by_tracker/package.xml | 2 +- .../CHANGELOG.rst | 3 + .../autoware_elevation_map_loader/package.xml | 2 +- .../autoware_euclidean_cluster/CHANGELOG.rst | 8 + .../autoware_euclidean_cluster/package.xml | 2 +- .../CHANGELOG.rst | 9 + .../autoware_ground_segmentation/package.xml | 2 +- .../CHANGELOG.rst | 127 +++++++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 36 +++ .../package.xml | 2 +- .../autoware_lidar_centerpoint/CHANGELOG.rst | 41 ++++ .../autoware_lidar_centerpoint/package.xml | 2 +- .../autoware_lidar_transfusion/CHANGELOG.rst | 36 +++ .../autoware_lidar_transfusion/package.xml | 2 +- .../CHANGELOG.rst | 9 + .../autoware_map_based_prediction/package.xml | 2 +- .../CHANGELOG.rst | 81 +++++++ .../autoware_multi_object_tracker/package.xml | 2 +- .../autoware_object_merger/CHANGELOG.rst | 26 +++ perception/autoware_object_merger/package.xml | 2 +- .../CHANGELOG.rst | 3 + .../package.xml | 2 +- .../CHANGELOG.rst | 3 + .../package.xml | 2 +- .../CHANGELOG.rst | 24 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 51 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 3 + .../package.xml | 2 +- .../CHANGELOG.rst | 7 + .../package.xml | 2 +- .../CHANGELOG.rst | 3 + .../package.xml | 2 +- .../CHANGELOG.rst | 3 + .../autoware_radar_object_tracker/package.xml | 2 +- .../CHANGELOG.rst | 7 + .../package.xml | 2 +- .../CHANGELOG.rst | 7 + .../package.xml | 2 +- .../autoware_shape_estimation/CHANGELOG.rst | 41 ++++ .../autoware_shape_estimation/package.xml | 2 +- .../CHANGELOG.rst | 3 + .../autoware_simple_object_merger/package.xml | 2 +- .../CHANGELOG.rst | 35 +++ .../autoware_tensorrt_classifier/package.xml | 2 +- .../autoware_tensorrt_common/CHANGELOG.rst | 35 +++ .../autoware_tensorrt_common/package.xml | 2 +- .../autoware_tensorrt_yolox/CHANGELOG.rst | 47 ++++ .../autoware_tensorrt_yolox/package.xml | 2 +- .../CHANGELOG.rst | 12 + .../package.xml | 2 +- .../CHANGELOG.rst | 15 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 39 ++++ .../package.xml | 2 +- .../CHANGELOG.rst | 39 ++++ .../package.xml | 2 +- .../CHANGELOG.rst | 13 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 9 + .../package.xml | 2 +- .../CHANGELOG.rst | 9 + .../package.xml | 2 +- .../CHANGELOG.rst | 7 + .../package.xml | 2 +- perception/perception_utils/CHANGELOG.rst | 3 + perception/perception_utils/package.xml | 2 +- .../autoware_costmap_generator/CHANGELOG.rst | 10 + .../autoware_costmap_generator/package.xml | 2 +- .../CHANGELOG.rst | 9 + .../package.xml | 2 +- .../autoware_freespace_planner/CHANGELOG.rst | 7 + .../autoware_freespace_planner/package.xml | 2 +- .../CHANGELOG.rst | 10 + .../package.xml | 2 +- .../CHANGELOG.rst | 6 + .../package.xml | 2 +- .../CHANGELOG.rst | 6 + .../package.xml | 2 +- .../CHANGELOG.rst | 41 ++++ .../package.xml | 2 +- .../CHANGELOG.rst | 39 ++++ .../package.xml | 2 +- .../autoware_path_optimizer/CHANGELOG.rst | 12 + planning/autoware_path_optimizer/package.xml | 2 +- planning/autoware_path_smoother/CHANGELOG.rst | 16 ++ planning/autoware_path_smoother/package.xml | 2 +- .../CHANGELOG.rst | 68 ++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 20 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 3 + .../package.xml | 2 +- .../autoware_planning_validator/CHANGELOG.rst | 7 + .../autoware_planning_validator/package.xml | 2 +- .../CHANGELOG.rst | 12 + .../package.xml | 2 +- planning/autoware_route_handler/CHANGELOG.rst | 9 + planning/autoware_route_handler/package.xml | 2 +- planning/autoware_rtc_interface/CHANGELOG.rst | 6 + planning/autoware_rtc_interface/package.xml | 2 +- .../autoware_scenario_selector/CHANGELOG.rst | 9 + .../autoware_scenario_selector/package.xml | 2 +- .../CHANGELOG.rst | 35 +++ .../package.xml | 2 +- .../autoware_velocity_smoother/CHANGELOG.rst | 13 ++ .../autoware_velocity_smoother/package.xml | 2 +- .../CHANGELOG.rst | 15 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 15 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 15 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 40 ++++ .../package.xml | 2 +- .../CHANGELOG.rst | 213 ++++++++++++++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 55 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 42 ++++ .../package.xml | 2 +- .../CHANGELOG.rst | 9 + .../package.xml | 2 +- .../CHANGELOG.rst | 15 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 35 +++ .../package.xml | 2 +- .../CHANGELOG.rst | 23 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 53 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 63 ++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 61 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 64 ++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 46 ++++ .../package.xml | 2 +- .../CHANGELOG.rst | 56 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 50 ++++ .../package.xml | 2 +- .../CHANGELOG.rst | 25 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 60 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 94 ++++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 58 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 42 ++++ .../package.xml | 2 +- .../CHANGELOG.rst | 63 ++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 42 ++++ .../package.xml | 2 +- .../CHANGELOG.rst | 56 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 68 ++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 52 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 45 ++++ .../package.xml | 2 +- .../CHANGELOG.rst | 27 +++ .../package.xml | 2 +- .../CHANGELOG.rst | 45 ++++ .../package.xml | 2 +- .../CHANGELOG.rst | 6 + .../package.xml | 2 +- .../CHANGELOG.rst | 6 + .../package.xml | 2 +- .../autoware_bezier_sampler/CHANGELOG.rst | 6 + .../autoware_bezier_sampler/package.xml | 2 +- .../autoware_frenet_planner/CHANGELOG.rst | 29 +++ .../autoware_frenet_planner/package.xml | 2 +- .../autoware_path_sampler/CHANGELOG.rst | 8 + .../autoware_path_sampler/package.xml | 2 +- .../autoware_sampler_common/CHANGELOG.rst | 3 + .../autoware_sampler_common/package.xml | 2 +- sensing/autoware_cuda_utils/CHANGELOG.rst | 3 + sensing/autoware_cuda_utils/package.xml | 2 +- sensing/autoware_gnss_poser/CHANGELOG.rst | 6 + sensing/autoware_gnss_poser/package.xml | 2 +- .../autoware_image_diagnostics/CHANGELOG.rst | 9 + .../autoware_image_diagnostics/package.xml | 2 +- .../CHANGELOG.rst | 7 + .../package.xml | 2 +- sensing/autoware_imu_corrector/CHANGELOG.rst | 8 + sensing/autoware_imu_corrector/package.xml | 2 +- sensing/autoware_pcl_extensions/CHANGELOG.rst | 3 + sensing/autoware_pcl_extensions/package.xml | 2 +- .../CHANGELOG.rst | 149 ++++++++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 3 + .../package.xml | 2 +- .../CHANGELOG.rst | 3 + .../package.xml | 2 +- .../CHANGELOG.rst | 3 + .../package.xml | 2 +- .../CHANGELOG.rst | 3 + .../package.xml | 2 +- .../CHANGELOG.rst | 5 +- .../package.xml | 2 +- .../autoware_livox_tag_filter/CHANGELOG.rst | 3 + .../autoware_livox_tag_filter/package.xml | 2 +- .../autoware_carla_interface/CHANGELOG.rst | 6 + .../autoware_carla_interface/package.xml | 2 +- simulator/autoware_carla_interface/setup.py | 2 +- .../CHANGELOG.rst | 6 + .../package.xml | 2 +- .../autoware_fault_injection/CHANGELOG.rst | 22 +- .../autoware_fault_injection/package.xml | 2 +- .../CHANGELOG.rst | 6 + .../package.xml | 2 +- .../CHANGELOG.rst | 31 ++- .../package.xml | 2 +- .../CHANGELOG.rst | 9 +- .../package.xml | 2 +- .../CHANGELOG.rst | 3 + .../package.xml | 2 +- .../autoware_bluetooth_monitor/CHANGELOG.rst | 26 ++- system/autoware_bluetooth_monitor/package.xml | 2 +- .../autoware_component_monitor/CHANGELOG.rst | 3 + system/autoware_component_monitor/package.xml | 2 +- .../CHANGELOG.rst | 6 + .../package.xml | 2 +- system/autoware_default_adapi/CHANGELOG.rst | 28 +++ system/autoware_default_adapi/package.xml | 2 +- .../autoware_adapi_adaptors/CHANGELOG.rst | 10 +- .../autoware_adapi_adaptors/package.xml | 2 +- .../autoware_adapi_visualizers/CHANGELOG.rst | 10 +- .../autoware_adapi_visualizers/package.xml | 2 +- .../autoware_adapi_visualizers/setup.py | 2 +- .../CHANGELOG.rst | 10 +- .../package.xml | 2 +- .../CHANGELOG.rst | 6 + .../package.xml | 2 +- .../CHANGELOG.rst | 8 +- .../package.xml | 2 +- .../CHANGELOG.rst | 13 +- .../autoware_dummy_diag_publisher/package.xml | 2 +- .../CHANGELOG.rst | 25 ++ .../autoware_dummy_infrastructure/package.xml | 2 +- .../CHANGELOG.rst | 25 +- .../package.xml | 2 +- .../CHANGELOG.rst | 7 + .../package.xml | 2 +- .../CHANGELOG.rst | 21 +- .../package.xml | 2 +- .../CHANGELOG.rst | 23 +- .../package.xml | 2 +- system/autoware_mrm_handler/CHANGELOG.rst | 24 +- system/autoware_mrm_handler/package.xml | 2 +- .../CHANGELOG.rst | 11 + .../package.xml | 2 +- .../CHANGELOG.rst | 6 + .../package.xml | 2 +- system/autoware_system_monitor/CHANGELOG.rst | 22 +- system/autoware_system_monitor/package.xml | 2 +- .../CHANGELOG.rst | 78 +++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 6 + .../autoware_topic_state_monitor/package.xml | 2 +- .../autoware_velodyne_monitor/CHANGELOG.rst | 6 + system/autoware_velodyne_monitor/package.xml | 2 +- tools/reaction_analyzer/CHANGELOG.rst | 3 + tools/reaction_analyzer/package.xml | 2 +- .../CHANGELOG.rst | 7 + .../package.xml | 2 +- .../CHANGELOG.rst | 3 + .../package.xml | 2 +- .../CHANGELOG.rst | 17 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 8 + .../package.xml | 2 +- .../CHANGELOG.rst | 9 + .../package.xml | 2 +- .../CHANGELOG.rst | 3 + .../package.xml | 2 +- .../CHANGELOG.rst | 9 + .../autoware_overlay_rviz_plugin/package.xml | 2 +- .../CHANGELOG.rst | 40 ++++ .../package.xml | 2 +- .../CHANGELOG.rst | 3 + .../package.xml | 2 +- .../tier4_adapi_rviz_plugin/CHANGELOG.rst | 6 + .../tier4_adapi_rviz_plugin/package.xml | 2 +- .../CHANGELOG.rst | 9 + .../tier4_camera_view_rviz_plugin/package.xml | 2 +- .../tier4_datetime_rviz_plugin/CHANGELOG.rst | 3 + .../tier4_datetime_rviz_plugin/package.xml | 2 +- .../CHANGELOG.rst | 3 + .../package.xml | 2 +- .../CHANGELOG.rst | 32 +++ .../package.xml | 2 +- .../tier4_planning_rviz_plugin/CHANGELOG.rst | 3 + .../tier4_planning_rviz_plugin/package.xml | 2 +- .../tier4_state_rviz_plugin/CHANGELOG.rst | 7 + .../tier4_state_rviz_plugin/package.xml | 2 +- .../tier4_system_rviz_plugin/CHANGELOG.rst | 3 + .../tier4_system_rviz_plugin/package.xml | 2 +- .../CHANGELOG.rst | 3 + .../package.xml | 2 +- .../tier4_vehicle_rviz_plugin/CHANGELOG.rst | 3 + .../tier4_vehicle_rviz_plugin/package.xml | 2 +- 492 files changed, 4837 insertions(+), 268 deletions(-) create mode 100644 planning/autoware_planning_factor_interface/CHANGELOG.rst create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/CHANGELOG.rst create mode 100644 system/autoware_topic_relay_controller/CHANGELOG.rst create mode 100644 visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/CHANGELOG.rst create mode 100644 visualization/tier4_planning_factor_rviz_plugin/CHANGELOG.rst diff --git a/common/autoware_adapi_specs/CHANGELOG.rst b/common/autoware_adapi_specs/CHANGELOG.rst index 7693074353d9f..e359542e5d0f1 100644 --- a/common/autoware_adapi_specs/CHANGELOG.rst +++ b/common/autoware_adapi_specs/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_adapi_specs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_default_adapi): release adapi v1.6.0 (`#9704 `_) + * feat: reject clearing route during autonomous mode + * feat: modify check and relay door service + * fix door condition + * fix error and add option + * update v1.6.0 + --------- +* Contributors: Fumiya Watanabe, Takagi, Isamu + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/common/autoware_adapi_specs/package.xml b/common/autoware_adapi_specs/package.xml index 5424d5bad52d5..6f02fafe11269 100644 --- a/common/autoware_adapi_specs/package.xml +++ b/common/autoware_adapi_specs/package.xml @@ -2,7 +2,7 @@ autoware_adapi_specs - 0.40.0 + 0.41.0 The autoware_adapi_specs package Takagi, Isamu Ryohsuke Mitsudome diff --git a/common/autoware_auto_common/CHANGELOG.rst b/common/autoware_auto_common/CHANGELOG.rst index 63f0fe2ac83e3..ec8415f295fbe 100644 --- a/common/autoware_auto_common/CHANGELOG.rst +++ b/common/autoware_auto_common/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_auto_common ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/common/autoware_auto_common/package.xml b/common/autoware_auto_common/package.xml index ccdcd4bab8608..f3bdd38dbc37b 100644 --- a/common/autoware_auto_common/package.xml +++ b/common/autoware_auto_common/package.xml @@ -2,7 +2,7 @@ autoware_auto_common - 0.40.0 + 0.41.0 Miscellaneous helper functions Apex.AI, Inc. Tomoya Kimura diff --git a/common/autoware_component_interface_specs_universe/CHANGELOG.rst b/common/autoware_component_interface_specs_universe/CHANGELOG.rst index cf03005715b76..50b1f1a414fec 100644 --- a/common/autoware_component_interface_specs_universe/CHANGELOG.rst +++ b/common/autoware_component_interface_specs_universe/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package autoware_component_interface_specs_universe ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_component_interface_specs_universe!): rename package (`#9753 `_) +* Contributors: Fumiya Watanabe, Ryohsuke Mitsudome + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/common/autoware_component_interface_specs_universe/package.xml b/common/autoware_component_interface_specs_universe/package.xml index 8e29921b1a873..456eca42701a0 100644 --- a/common/autoware_component_interface_specs_universe/package.xml +++ b/common/autoware_component_interface_specs_universe/package.xml @@ -2,7 +2,7 @@ autoware_component_interface_specs_universe - 0.40.0 + 0.41.0 The autoware_component_interface_specs_universe package Takagi, Isamu Yukihiro Saito diff --git a/common/autoware_component_interface_tools/CHANGELOG.rst b/common/autoware_component_interface_tools/CHANGELOG.rst index b17fa431b27bb..bbe2c681e09c9 100644 --- a/common/autoware_component_interface_tools/CHANGELOG.rst +++ b/common/autoware_component_interface_tools/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_component_interface_tools ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/common/autoware_component_interface_tools/package.xml b/common/autoware_component_interface_tools/package.xml index e38b048e22ebe..20919e15acd13 100644 --- a/common/autoware_component_interface_tools/package.xml +++ b/common/autoware_component_interface_tools/package.xml @@ -2,7 +2,7 @@ autoware_component_interface_tools - 0.40.0 + 0.41.0 The autoware_component_interface_tools package Takagi, Isamu Apache License 2.0 diff --git a/common/autoware_component_interface_utils/CHANGELOG.rst b/common/autoware_component_interface_utils/CHANGELOG.rst index d19e72f19e469..750b2b246ca45 100644 --- a/common/autoware_component_interface_utils/CHANGELOG.rst +++ b/common/autoware_component_interface_utils/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_component_interface_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/common/autoware_component_interface_utils/package.xml b/common/autoware_component_interface_utils/package.xml index 0bc51ee211d50..8a28af9c82acf 100755 --- a/common/autoware_component_interface_utils/package.xml +++ b/common/autoware_component_interface_utils/package.xml @@ -2,7 +2,7 @@ autoware_component_interface_utils - 0.40.0 + 0.41.0 The autoware_component_interface_utils package Takagi, Isamu Yukihiro Saito diff --git a/common/autoware_fake_test_node/CHANGELOG.rst b/common/autoware_fake_test_node/CHANGELOG.rst index 5bc3669a5aa27..7ba813f999f5e 100644 --- a/common/autoware_fake_test_node/CHANGELOG.rst +++ b/common/autoware_fake_test_node/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_fake_test_node ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/common/autoware_fake_test_node/package.xml b/common/autoware_fake_test_node/package.xml index 0ae881e4a41ba..039590b934227 100644 --- a/common/autoware_fake_test_node/package.xml +++ b/common/autoware_fake_test_node/package.xml @@ -2,7 +2,7 @@ autoware_fake_test_node - 0.40.0 + 0.41.0 A fake node that we can use in the integration-like cpp tests. Apex.AI, Inc. Tomoya Kimura diff --git a/common/autoware_global_parameter_loader/CHANGELOG.rst b/common/autoware_global_parameter_loader/CHANGELOG.rst index d778018320271..26f9d8d8e71d8 100644 --- a/common/autoware_global_parameter_loader/CHANGELOG.rst +++ b/common/autoware_global_parameter_loader/CHANGELOG.rst @@ -1,7 +1,10 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package global_parameter_loader +Changelog for package autoware_global_parameter_loader ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/common/autoware_global_parameter_loader/package.xml b/common/autoware_global_parameter_loader/package.xml index 8238e5852284f..9d2c5be940d8c 100644 --- a/common/autoware_global_parameter_loader/package.xml +++ b/common/autoware_global_parameter_loader/package.xml @@ -2,7 +2,7 @@ autoware_global_parameter_loader - 0.40.0 + 0.41.0 The autoware_global_parameter_loader package Ryohsuke Mitsudome Apache License 2.0 diff --git a/common/autoware_glog_component/CHANGELOG.rst b/common/autoware_glog_component/CHANGELOG.rst index e9176b6524049..2df0c43506d7d 100644 --- a/common/autoware_glog_component/CHANGELOG.rst +++ b/common/autoware_glog_component/CHANGELOG.rst @@ -1,7 +1,10 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package glog_component +Changelog for package autoware_glog_component ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/common/autoware_glog_component/package.xml b/common/autoware_glog_component/package.xml index eab95fa8944d3..f80511f8eb17a 100644 --- a/common/autoware_glog_component/package.xml +++ b/common/autoware_glog_component/package.xml @@ -2,7 +2,7 @@ autoware_glog_component - 0.40.0 + 0.41.0 The autoware_glog_component package Takamasa Horibe Apache License 2.0 diff --git a/common/autoware_goal_distance_calculator/CHANGELOG.rst b/common/autoware_goal_distance_calculator/CHANGELOG.rst index df190270e02ab..ad226c45ce31a 100644 --- a/common/autoware_goal_distance_calculator/CHANGELOG.rst +++ b/common/autoware_goal_distance_calculator/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package autoware_goal_distance_calculator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_goal_distance_calculator)!: tier4_debug_msgs to autoware_internal_debug_msgs for autoware_goal_distance_calculator (`#9833 `_) +* Contributors: Fumiya Watanabe, Vishal Chauhan + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/common/autoware_goal_distance_calculator/package.xml b/common/autoware_goal_distance_calculator/package.xml index 9b36f0a40dd52..60de6e02e7f45 100644 --- a/common/autoware_goal_distance_calculator/package.xml +++ b/common/autoware_goal_distance_calculator/package.xml @@ -2,7 +2,7 @@ autoware_goal_distance_calculator - 0.40.0 + 0.41.0 The autoware_goal_distance_calculator package Taiki Tanaka Apache License 2.0 diff --git a/common/autoware_grid_map_utils/CHANGELOG.rst b/common/autoware_grid_map_utils/CHANGELOG.rst index 7a1b19b90a958..afb807859f8b6 100644 --- a/common/autoware_grid_map_utils/CHANGELOG.rst +++ b/common/autoware_grid_map_utils/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_grid_map_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/common/autoware_grid_map_utils/package.xml b/common/autoware_grid_map_utils/package.xml index bf89abc507173..d745d007f8b37 100644 --- a/common/autoware_grid_map_utils/package.xml +++ b/common/autoware_grid_map_utils/package.xml @@ -2,7 +2,7 @@ autoware_grid_map_utils - 0.40.0 + 0.41.0 Utilities for the grid_map library Maxime CLEMENT Apache License 2.0 diff --git a/common/autoware_interpolation/CHANGELOG.rst b/common/autoware_interpolation/CHANGELOG.rst index 37fc48c525a49..e84799ae6be49 100644 --- a/common/autoware_interpolation/CHANGELOG.rst +++ b/common/autoware_interpolation/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package autoware_interpolation ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* fix(autoware_interpolation): remove clang compiler error (`#9711 `_) +* Contributors: Fumiya Watanabe, Ryuta Kambe + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/common/autoware_interpolation/package.xml b/common/autoware_interpolation/package.xml index 3bad757405ed4..0a8d103b31f09 100644 --- a/common/autoware_interpolation/package.xml +++ b/common/autoware_interpolation/package.xml @@ -2,7 +2,7 @@ autoware_interpolation - 0.40.0 + 0.41.0 The spline interpolation package Fumiya Watanabe Takayuki Murooka diff --git a/common/autoware_motion_utils/CHANGELOG.rst b/common/autoware_motion_utils/CHANGELOG.rst index 187ddda4acd39..46ebcdb1054e3 100644 --- a/common/autoware_motion_utils/CHANGELOG.rst +++ b/common/autoware_motion_utils/CHANGELOG.rst @@ -2,6 +2,42 @@ Changelog for package autoware_motion_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* chore(planning): move package directory for planning factor interface (`#9948 `_) + * chore: add new package for planning factor interface + * chore(surround_obstacle_checker): update include file + * chore(obstacle_stop_planner): update include file + * chore(obstacle_cruise_planner): update include file + * chore(motion_velocity_planner): update include file + * chore(bpp): update include file + * chore(bvp-common): update include file + * chore(blind_spot): update include file + * chore(crosswalk): update include file + * chore(detection_area): update include file + * chore(intersection): update include file + * chore(no_drivable_area): update include file + * chore(no_stopping_area): update include file + * chore(occlusion_spot): update include file + * chore(run_out): update include file + * chore(speed_bump): update include file + * chore(stop_line): update include file + * chore(template_module): update include file + * chore(traffic_light): update include file + * chore(vtl): update include file + * chore(walkway): update include file + * chore(motion_utils): remove factor interface + --------- +* feat(motion_utils): add detail and pass type to VirtualWall (`#9940 `_) +* fix(autoware_motion_utils): remove clang compiler error (`#9713 `_) +* feat(motion_utils): add planning factor interface (`#9676 `_) + * feat(motion_utils): add planning factor interface + * fix: use extern template + * fix: define function in header + --------- +* Contributors: Fumiya Watanabe, Mamoru Sobue, Ryuta Kambe, Satoshi OTA + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/common/autoware_motion_utils/package.xml b/common/autoware_motion_utils/package.xml index 029985a53f020..75dc56de5466d 100644 --- a/common/autoware_motion_utils/package.xml +++ b/common/autoware_motion_utils/package.xml @@ -2,7 +2,7 @@ autoware_motion_utils - 0.40.0 + 0.41.0 The autoware_motion_utils package Satoshi Ota Takayuki Murooka diff --git a/common/autoware_object_recognition_utils/CHANGELOG.rst b/common/autoware_object_recognition_utils/CHANGELOG.rst index 920106de22082..20f538b7c3e8e 100644 --- a/common/autoware_object_recognition_utils/CHANGELOG.rst +++ b/common/autoware_object_recognition_utils/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_object_recognition_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/common/autoware_object_recognition_utils/package.xml b/common/autoware_object_recognition_utils/package.xml index 05327766008f2..1f0a28c0db3f7 100644 --- a/common/autoware_object_recognition_utils/package.xml +++ b/common/autoware_object_recognition_utils/package.xml @@ -2,7 +2,7 @@ autoware_object_recognition_utils - 0.40.0 + 0.41.0 The autoware_object_recognition_utils package Takayuki Murooka Shunsuke Miura diff --git a/common/autoware_path_distance_calculator/CHANGELOG.rst b/common/autoware_path_distance_calculator/CHANGELOG.rst index cd4c6ae5ce49b..d5121521c3acf 100644 --- a/common/autoware_path_distance_calculator/CHANGELOG.rst +++ b/common/autoware_path_distance_calculator/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_path_distance_calculator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/common/autoware_path_distance_calculator/package.xml b/common/autoware_path_distance_calculator/package.xml index 6d207f6ed795d..150ca10754e24 100644 --- a/common/autoware_path_distance_calculator/package.xml +++ b/common/autoware_path_distance_calculator/package.xml @@ -2,7 +2,7 @@ autoware_path_distance_calculator - 0.40.0 + 0.41.0 The autoware_path_distance_calculator package Takagi, Isamu Apache License 2.0 diff --git a/common/autoware_polar_grid/CHANGELOG.rst b/common/autoware_polar_grid/CHANGELOG.rst index 72a53e6cef4b7..9f4396678ab12 100644 --- a/common/autoware_polar_grid/CHANGELOG.rst +++ b/common/autoware_polar_grid/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_polar_grid ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/common/autoware_polar_grid/package.xml b/common/autoware_polar_grid/package.xml index 16d6a72985ec9..c7ab2e8252965 100644 --- a/common/autoware_polar_grid/package.xml +++ b/common/autoware_polar_grid/package.xml @@ -2,7 +2,7 @@ autoware_polar_grid - 0.40.0 + 0.41.0 The autoware_polar_grid package Yukihiro Saito Apache License 2.0 diff --git a/common/autoware_pyplot/CHANGELOG.rst b/common/autoware_pyplot/CHANGELOG.rst index c3b1f9c17f7d5..970aa3361e4dd 100644 --- a/common/autoware_pyplot/CHANGELOG.rst +++ b/common/autoware_pyplot/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package autoware_pyplot ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_test_utils): add visualization (`#9603 `_) +* Contributors: Fumiya Watanabe, Mamoru Sobue + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/common/autoware_pyplot/package.xml b/common/autoware_pyplot/package.xml index 2f3f3014d4907..1877699b70fc1 100644 --- a/common/autoware_pyplot/package.xml +++ b/common/autoware_pyplot/package.xml @@ -2,7 +2,7 @@ autoware_pyplot - 0.40.0 + 0.41.0 C++ interface for matplotlib based on pybind11 Mamoru Sobue Yukinari Hisaki diff --git a/common/autoware_signal_processing/CHANGELOG.rst b/common/autoware_signal_processing/CHANGELOG.rst index b5b01e98e23a7..a9e05a6ff5c10 100644 --- a/common/autoware_signal_processing/CHANGELOG.rst +++ b/common/autoware_signal_processing/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_signal_processing ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/common/autoware_signal_processing/package.xml b/common/autoware_signal_processing/package.xml index b8d7c064112dd..00f934005f642 100644 --- a/common/autoware_signal_processing/package.xml +++ b/common/autoware_signal_processing/package.xml @@ -2,7 +2,7 @@ autoware_signal_processing - 0.40.0 + 0.41.0 The signal processing package Takayuki Murooka Takamasa Horibe diff --git a/common/autoware_test_utils/CHANGELOG.rst b/common/autoware_test_utils/CHANGELOG.rst index 950fdb09aa119..0eddee7112ec2 100644 --- a/common/autoware_test_utils/CHANGELOG.rst +++ b/common/autoware_test_utils/CHANGELOG.rst @@ -2,6 +2,24 @@ Changelog for package autoware_test_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_component_interface_specs_universe!): rename package (`#9753 `_) +* feat(autoware_planning_test_manager): remove dependency of tier4_planning_msgs::msg::LateralOffset (`#9967 `_) + * feat(autoware_planning_test_manager): remove dependency of tier4_planning_msgs::msg::LateralOffset + * fix + --------- +* chore(autoware_test_utils): move rviz config to autoware_launch (`#9925 `_) +* feat(autoware_test_utils): add visualization and yaml dumper for PathWithLaneId (`#9841 `_) +* chore(autoware_test_utils): update test map (`#9664 `_) +* feat(autoware_test_utils): add visualization (`#9603 `_) +* refactor(autoware_test_utils): enhance makeMapBinMsg to accept package name and map filename parameters (`#9617 `_) + * feat: enhance makeMapBinMsg to accept package name and map filename parameters + * feat: set default package name to 'autoware_test_utils' in makeMapBinMsg and related functions + --------- +* Contributors: Fumiya Watanabe, Kyoichi Sugahara, Mamoru Sobue, Ryohsuke Mitsudome, Takayuki Murooka + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/common/autoware_test_utils/package.xml b/common/autoware_test_utils/package.xml index 4a7e0f15ba74c..03846e620bedc 100644 --- a/common/autoware_test_utils/package.xml +++ b/common/autoware_test_utils/package.xml @@ -2,7 +2,7 @@ autoware_test_utils - 0.40.0 + 0.41.0 ROS 2 node for testing interface of the nodes in planning module Kyoichi Sugahara Takamasa Horibe diff --git a/common/autoware_testing/CHANGELOG.rst b/common/autoware_testing/CHANGELOG.rst index 09ff6bdc4cf04..5ee6a2c9556de 100644 --- a/common/autoware_testing/CHANGELOG.rst +++ b/common/autoware_testing/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_testing ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/common/autoware_testing/package.xml b/common/autoware_testing/package.xml index a5df1302b682d..d94b90b6821f4 100644 --- a/common/autoware_testing/package.xml +++ b/common/autoware_testing/package.xml @@ -2,7 +2,7 @@ autoware_testing - 0.40.0 + 0.41.0 Tools for handling standard tests based on ros_testing Adam Dabrowski Tomoya Kimura diff --git a/common/autoware_time_utils/CHANGELOG.rst b/common/autoware_time_utils/CHANGELOG.rst index b18c3dd42cbc6..3e4d9f7de343a 100644 --- a/common/autoware_time_utils/CHANGELOG.rst +++ b/common/autoware_time_utils/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_time_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/common/autoware_time_utils/package.xml b/common/autoware_time_utils/package.xml index 278143e9ac4f8..fccd4e158d6ba 100644 --- a/common/autoware_time_utils/package.xml +++ b/common/autoware_time_utils/package.xml @@ -2,7 +2,7 @@ autoware_time_utils - 0.40.0 + 0.41.0 Simple conversion methods to/from std::chrono to simplify algorithm development Christopher Ho Tomoya Kimura diff --git a/common/autoware_traffic_light_recognition_marker_publisher/CHANGELOG.rst b/common/autoware_traffic_light_recognition_marker_publisher/CHANGELOG.rst index 27a61bf71b1e8..3c9df1fcfd4b6 100644 --- a/common/autoware_traffic_light_recognition_marker_publisher/CHANGELOG.rst +++ b/common/autoware_traffic_light_recognition_marker_publisher/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_traffic_light_recognition_marker_publisher ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/common/autoware_traffic_light_recognition_marker_publisher/package.xml b/common/autoware_traffic_light_recognition_marker_publisher/package.xml index af670dc19baf1..b3f240b4b1ac3 100644 --- a/common/autoware_traffic_light_recognition_marker_publisher/package.xml +++ b/common/autoware_traffic_light_recognition_marker_publisher/package.xml @@ -2,7 +2,7 @@ autoware_traffic_light_recognition_marker_publisher - 0.40.0 + 0.41.0 The autoware_traffic_light_recognition_marker_publisher package Tomoya Kimura Takeshi Miura diff --git a/common/autoware_traffic_light_utils/CHANGELOG.rst b/common/autoware_traffic_light_utils/CHANGELOG.rst index 0230e43574de8..fd69102c5043a 100644 --- a/common/autoware_traffic_light_utils/CHANGELOG.rst +++ b/common/autoware_traffic_light_utils/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_traffic_light_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/common/autoware_traffic_light_utils/package.xml b/common/autoware_traffic_light_utils/package.xml index 645e92e2d992f..68a0eb05dc201 100644 --- a/common/autoware_traffic_light_utils/package.xml +++ b/common/autoware_traffic_light_utils/package.xml @@ -2,7 +2,7 @@ autoware_traffic_light_utils - 0.40.0 + 0.41.0 The autoware_traffic_light_utils package Kotaro Uetake Shunsuke Miura diff --git a/common/autoware_trajectory/CHANGELOG.rst b/common/autoware_trajectory/CHANGELOG.rst index 307dd8eb3dcf5..ba5c731b0b4ce 100644 --- a/common/autoware_trajectory/CHANGELOG.rst +++ b/common/autoware_trajectory/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_trajectory ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/common/autoware_trajectory/package.xml b/common/autoware_trajectory/package.xml index eaa5fca80ff46..230e83bbc3550 100644 --- a/common/autoware_trajectory/package.xml +++ b/common/autoware_trajectory/package.xml @@ -2,7 +2,7 @@ autoware_trajectory - 0.40.0 + 0.41.0 The autoware_trajectory package Yukinari Hisaki Takayuki Murooka diff --git a/common/autoware_universe_utils/CHANGELOG.rst b/common/autoware_universe_utils/CHANGELOG.rst index 31f45a8ecbfce..66eb541ae38b3 100644 --- a/common/autoware_universe_utils/CHANGELOG.rst +++ b/common/autoware_universe_utils/CHANGELOG.rst @@ -2,6 +2,33 @@ Changelog for package autoware_universe_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* refactor(autoware_universe_utils): add missing 's' in the class of diagnostics_interface (`#9777 `_) +* feat(behavior_path_planner): use autoware internal stamped messages (`#9750 `_) + * feat(behavior_path_planner): use autoware internal stamped messages + * fix universe_utils + --------- +* feat!: move diagnostics_module from localization_util to unverse_utils (`#9714 `_) + * feat!: move diagnostics_module from localization_util to unverse_utils + * remove diagnostics module from localization_util + * style(pre-commit): autofix + * minor fix in pose_initializer + * add test + * style(pre-commit): autofix + * remove unnecessary declaration + * module -> interface + * remove unnecessary equal expression + * revert the remove of template function + * style(pre-commit): autofix + * use overload instead + * include what you use -- test_diagnostics_interface.cpp + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* fix(autoware_universe_utils): fix bug in test (`#9710 `_) +* Contributors: Fumiya Watanabe, Ryuta Kambe, Takayuki Murooka, kminoda + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/common/autoware_universe_utils/package.xml b/common/autoware_universe_utils/package.xml index 0e7b892a8c689..2415ce6e4a8c1 100644 --- a/common/autoware_universe_utils/package.xml +++ b/common/autoware_universe_utils/package.xml @@ -2,7 +2,7 @@ autoware_universe_utils - 0.40.0 + 0.41.0 The autoware_universe_utils package Takamasa Horibe Takayuki Murooka diff --git a/common/autoware_vehicle_info_utils/CHANGELOG.rst b/common/autoware_vehicle_info_utils/CHANGELOG.rst index a02256d5f9cea..f25de9a548809 100644 --- a/common/autoware_vehicle_info_utils/CHANGELOG.rst +++ b/common/autoware_vehicle_info_utils/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_vehicle_info_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/common/autoware_vehicle_info_utils/package.xml b/common/autoware_vehicle_info_utils/package.xml index b6a2f1ad5154a..f419fb9d0d47e 100644 --- a/common/autoware_vehicle_info_utils/package.xml +++ b/common/autoware_vehicle_info_utils/package.xml @@ -2,7 +2,7 @@ autoware_vehicle_info_utils - 0.40.0 + 0.41.0 The autoware_vehicle_info_utils package diff --git a/common/tier4_api_utils/CHANGELOG.rst b/common/tier4_api_utils/CHANGELOG.rst index d9b94eeacc79b..acc839db224cf 100644 --- a/common/tier4_api_utils/CHANGELOG.rst +++ b/common/tier4_api_utils/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package tier4_api_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/common/tier4_api_utils/package.xml b/common/tier4_api_utils/package.xml index 3e7f99b8736c5..228d9d8598749 100644 --- a/common/tier4_api_utils/package.xml +++ b/common/tier4_api_utils/package.xml @@ -2,7 +2,7 @@ tier4_api_utils - 0.40.0 + 0.41.0 The tier4_api_utils package Takagi, Isamu Apache License 2.0 diff --git a/control/autoware_autonomous_emergency_braking/CHANGELOG.rst b/control/autoware_autonomous_emergency_braking/CHANGELOG.rst index 578ffc14bae84..b4cb2cbe9abc7 100644 --- a/control/autoware_autonomous_emergency_braking/CHANGELOG.rst +++ b/control/autoware_autonomous_emergency_braking/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_autonomous_emergency_braking ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/control/autoware_autonomous_emergency_braking/package.xml b/control/autoware_autonomous_emergency_braking/package.xml index e22a0f099e2f0..b7f04abca584f 100644 --- a/control/autoware_autonomous_emergency_braking/package.xml +++ b/control/autoware_autonomous_emergency_braking/package.xml @@ -2,7 +2,7 @@ autoware_autonomous_emergency_braking - 0.40.0 + 0.41.0 Autonomous Emergency Braking package as a ROS 2 node Takamasa Horibe Tomoya Kimura diff --git a/control/autoware_collision_detector/CHANGELOG.rst b/control/autoware_collision_detector/CHANGELOG.rst index a108327961ac3..b890f50c447a0 100644 --- a/control/autoware_collision_detector/CHANGELOG.rst +++ b/control/autoware_collision_detector/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_collision_detector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/control/autoware_collision_detector/package.xml b/control/autoware_collision_detector/package.xml index 680c20b8094e7..c573b811027fb 100644 --- a/control/autoware_collision_detector/package.xml +++ b/control/autoware_collision_detector/package.xml @@ -2,7 +2,7 @@ autoware_collision_detector - 0.40.0 + 0.41.0 The collision_detector package Kyoichi Sugahara diff --git a/control/autoware_control_performance_analysis/CHANGELOG.rst b/control/autoware_control_performance_analysis/CHANGELOG.rst index 55361923da83d..35d94b7033a79 100644 --- a/control/autoware_control_performance_analysis/CHANGELOG.rst +++ b/control/autoware_control_performance_analysis/CHANGELOG.rst @@ -2,6 +2,37 @@ Changelog for package autoware_control_performance_analysis ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `control_performance_analysis` (`#9982 `_) + * feat(control_performance_analysis): apply `autoware\_` prefix (see below): + Note: + * In this commit, I did not organize a folder structure. + The folder structure will be organized in the next some commits. + * The changes will follow the Autoware's guideline as below: + - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder + * rename(control_performance_analysis): move headers under `include/autoware`: + * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit + * fix(control_performance_analysis): fix include paths + * To follow the previous commit + * rename: `control_performance_analysis` => `autoware_control_performance_analysis` + * style(pre-commit): autofix + * bug(autoware_control_performance_analysis): fix inconsistent namespacing + * style(pre-commit): autofix + * update(autoware_control_performance_analysis): `README.md` + * bug(autoware_control_performance_analysis): fix critical bugs that contaminate topic name + * style(pre-commit): autofix + * fix: update package name for error_rqt_multiplot.xml + * fix: update package name for control_performance_plot.py + * docs(autoware_control_performance_analysis): update package name in README and CHANGELOG.rst + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome + Co-authored-by: SakodaShintaro +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/control/autoware_control_performance_analysis/package.xml b/control/autoware_control_performance_analysis/package.xml index 1730277a87445..a77a740130861 100644 --- a/control/autoware_control_performance_analysis/package.xml +++ b/control/autoware_control_performance_analysis/package.xml @@ -2,7 +2,7 @@ autoware_control_performance_analysis - 0.40.0 + 0.41.0 Controller Performance Evaluation Berkay Karaman Taiki Tanaka diff --git a/control/autoware_control_validator/CHANGELOG.rst b/control/autoware_control_validator/CHANGELOG.rst index c35ece2151697..994ab4f0e642f 100644 --- a/control/autoware_control_validator/CHANGELOG.rst +++ b/control/autoware_control_validator/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package autoware_control_validator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: tier4_debug_msgs to autoware_internal_debug_msgs in file contr… (`#9837 `_) + feat: tier4_debug_msgs to autoware_internal_debug_msgs in file control/autoware_control_validator +* Contributors: Fumiya Watanabe, Vishal Chauhan + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/control/autoware_control_validator/package.xml b/control/autoware_control_validator/package.xml index fbaa3f013b64e..fbd0d4d332fe8 100644 --- a/control/autoware_control_validator/package.xml +++ b/control/autoware_control_validator/package.xml @@ -2,7 +2,7 @@ autoware_control_validator - 0.40.0 + 0.41.0 ros node for autoware_control_validator Kyoichi Sugahara Takamasa Horibe diff --git a/control/autoware_external_cmd_selector/CHANGELOG.rst b/control/autoware_external_cmd_selector/CHANGELOG.rst index 2e4ee4c7d2906..e8db21263e2d2 100644 --- a/control/autoware_external_cmd_selector/CHANGELOG.rst +++ b/control/autoware_external_cmd_selector/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_external_cmd_selector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/control/autoware_external_cmd_selector/package.xml b/control/autoware_external_cmd_selector/package.xml index 86cbdf9f00bfb..97b6670e409c9 100644 --- a/control/autoware_external_cmd_selector/package.xml +++ b/control/autoware_external_cmd_selector/package.xml @@ -2,7 +2,7 @@ autoware_external_cmd_selector - 0.40.0 + 0.41.0 The autoware_external_cmd_selector package Taiki Tanaka Tomoya Kimura diff --git a/control/autoware_joy_controller/CHANGELOG.rst b/control/autoware_joy_controller/CHANGELOG.rst index 8d25bab7fc6db..aaad4c6ded975 100644 --- a/control/autoware_joy_controller/CHANGELOG.rst +++ b/control/autoware_joy_controller/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_joy_controller ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/control/autoware_joy_controller/package.xml b/control/autoware_joy_controller/package.xml index b178ec167306a..b0a128be10ddb 100644 --- a/control/autoware_joy_controller/package.xml +++ b/control/autoware_joy_controller/package.xml @@ -2,7 +2,7 @@ autoware_joy_controller - 0.40.0 + 0.41.0 The autoware_joy_controller package Taiki Tanaka Tomoya Kimura diff --git a/control/autoware_lane_departure_checker/CHANGELOG.rst b/control/autoware_lane_departure_checker/CHANGELOG.rst index 9b49f0c6c8fb1..2cdbcf9df15f8 100644 --- a/control/autoware_lane_departure_checker/CHANGELOG.rst +++ b/control/autoware_lane_departure_checker/CHANGELOG.rst @@ -2,6 +2,19 @@ Changelog for package autoware_lane_departure_checker ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* refactor(lane_departure_checker): improve LaneDepartureChecker initialization and parameter handling (`#9791 `_) + * refactor(lane_departure_checker): improve LaneDepartureChecker initialization and parameter handling + --------- +* feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in fil… (`#9846 `_) + * feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files ontrol/autoware_mpc_lateral_controller + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Fumiya Watanabe, Kyoichi Sugahara, Vishal Chauhan + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/control/autoware_lane_departure_checker/package.xml b/control/autoware_lane_departure_checker/package.xml index 97ad5eaf82e00..5c06c43ffc0c8 100644 --- a/control/autoware_lane_departure_checker/package.xml +++ b/control/autoware_lane_departure_checker/package.xml @@ -2,7 +2,7 @@ autoware_lane_departure_checker - 0.40.0 + 0.41.0 The autoware_lane_departure_checker package Kyoichi Sugahara Makoto Kurihara diff --git a/control/autoware_mpc_lateral_controller/CHANGELOG.rst b/control/autoware_mpc_lateral_controller/CHANGELOG.rst index f149921648e8d..49aa808d65d4f 100644 --- a/control/autoware_mpc_lateral_controller/CHANGELOG.rst +++ b/control/autoware_mpc_lateral_controller/CHANGELOG.rst @@ -2,6 +2,25 @@ Changelog for package autoware_mpc_lateral_controller ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in fil… (`#9846 `_) + * feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files ontrol/autoware_mpc_lateral_controller + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* chore(autoware_mpc_lateral_controller): fix formula description in vehicle_model_bicycle_kinematics.hpp (`#8971 `_) + fix formula description in vehicle_model_bicycle_kinematics.hpp +* fix(mpc_lateral_controller): prevent unstable steering command while stopped (`#9690 `_) + * modify logic of function isStoppedState + * use a constant distance margin instead of wheelbase length + * add comment to implementation + --------- +* feat(mpc_lateral_controller): remove trans/rot deviation validation since the control_validator has the same feature (`#9684 `_) +* docs: modified minor sign error (`#8140 `_) +* Contributors: Autumn60, Fumiya Watanabe, Takayuki Murooka, Vishal Chauhan, Yuki Kimura, mkquda + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/control/autoware_mpc_lateral_controller/package.xml b/control/autoware_mpc_lateral_controller/package.xml index 719d11ef7948b..b818b24786a16 100644 --- a/control/autoware_mpc_lateral_controller/package.xml +++ b/control/autoware_mpc_lateral_controller/package.xml @@ -2,7 +2,7 @@ autoware_mpc_lateral_controller - 0.40.0 + 0.41.0 MPC-based lateral controller Takamasa Horibe diff --git a/control/autoware_obstacle_collision_checker/CHANGELOG.rst b/control/autoware_obstacle_collision_checker/CHANGELOG.rst index 79a7b2d8819e4..0cf89271451dc 100644 --- a/control/autoware_obstacle_collision_checker/CHANGELOG.rst +++ b/control/autoware_obstacle_collision_checker/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_obstacle_collision_checker ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/control/autoware_obstacle_collision_checker/package.xml b/control/autoware_obstacle_collision_checker/package.xml index 334c6d970fc36..3472882c92982 100644 --- a/control/autoware_obstacle_collision_checker/package.xml +++ b/control/autoware_obstacle_collision_checker/package.xml @@ -2,7 +2,7 @@ autoware_obstacle_collision_checker - 0.40.0 + 0.41.0 The obstacle_collision_checker package Taiki Tanaka Tomoya Kimura diff --git a/control/autoware_operation_mode_transition_manager/CHANGELOG.rst b/control/autoware_operation_mode_transition_manager/CHANGELOG.rst index 3f178c04f9d48..731ce29585e04 100644 --- a/control/autoware_operation_mode_transition_manager/CHANGELOG.rst +++ b/control/autoware_operation_mode_transition_manager/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package autoware_operation_mode_transition_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_component_interface_specs_universe!): rename package (`#9753 `_) +* Contributors: Fumiya Watanabe, Ryohsuke Mitsudome + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/control/autoware_operation_mode_transition_manager/package.xml b/control/autoware_operation_mode_transition_manager/package.xml index f82d610ba791b..52e663a4a2103 100644 --- a/control/autoware_operation_mode_transition_manager/package.xml +++ b/control/autoware_operation_mode_transition_manager/package.xml @@ -1,6 +1,6 @@ autoware_operation_mode_transition_manager - 0.40.0 + 0.41.0 The operation_mode_transition_manager package Takamasa Horibe Tomoya Kimura diff --git a/control/autoware_pid_longitudinal_controller/CHANGELOG.rst b/control/autoware_pid_longitudinal_controller/CHANGELOG.rst index d63f075c26918..67c09b553339a 100644 --- a/control/autoware_pid_longitudinal_controller/CHANGELOG.rst +++ b/control/autoware_pid_longitudinal_controller/CHANGELOG.rst @@ -2,6 +2,27 @@ Changelog for package autoware_pid_longitudinal_controller ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* fix: remove unnecessary parameters (`#9935 `_) +* feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in fil… (`#9848 `_) + feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files control/autoware_pid_longitudinal_controller +* feat(pid_longitudinal_controller): add new slope compensation mode trajectory_goal_adaptive (`#9705 `_) +* feat(pid_longitudinal_controller): add virtual wall for dry steering and emergency (`#9685 `_) + * feat(pid_longitudinal_controller): add virtual wall for dry steering and emergency + * fix + --------- +* feat(pid_longitudinal_controller): remove trans/rot deviation validation since the control_validator has the same feature (`#9675 `_) + * feat(pid_longitudinal_controller): remove trans/rot deviation validation since the control_validator has the same feature + * fix test + --------- +* feat(pid_longitudinal_controller): add smooth_stop mode in debug_values (`#9681 `_) +* feat(pid_longitudinal_controller): update trajectory_adaptive; add debug_values, adopt rate limit fillter (`#9656 `_) +* fix(autoware_pid_longitudinal_controller): fix bugprone-branch-clone (`#9629 `_) + fix: bugprone-branch-clone +* Contributors: Fumiya Watanabe, Takayuki Murooka, Vishal Chauhan, Yuki TAKAGI, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/control/autoware_pid_longitudinal_controller/package.xml b/control/autoware_pid_longitudinal_controller/package.xml index 127ce8e76d69d..b685e424e8aa9 100644 --- a/control/autoware_pid_longitudinal_controller/package.xml +++ b/control/autoware_pid_longitudinal_controller/package.xml @@ -2,7 +2,7 @@ autoware_pid_longitudinal_controller - 0.40.0 + 0.41.0 PID-based longitudinal controller Takamasa Horibe diff --git a/control/autoware_predicted_path_checker/CHANGELOG.rst b/control/autoware_predicted_path_checker/CHANGELOG.rst index 2cfe80aeada7b..abd007f26638f 100644 --- a/control/autoware_predicted_path_checker/CHANGELOG.rst +++ b/control/autoware_predicted_path_checker/CHANGELOG.rst @@ -1,7 +1,32 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package predicted_path_checker +Changelog for package autoware_predicted_path_checker ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `predicted_path_checker` (`#9985 `_) + * feat(predicted_path_checker): apply `autoware\_` prefix (see below): + Note: + * In this commit, I did not organize a folder structure. + The folder structure will be organized in the next some commits. + * The changes will follow the Autoware's guideline as below: + - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder + * rename(predicted_path_checker): move headers under `include/autoware` + * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit + * fix(predicted_path_checker): fix include header paths + * To follow the previous commit + * rename: `predicted_path_checker` => `autoware_predicted_path_checker` + * style(pre-commit): autofix + * bug(autoware_predicted_path_checker): fix inconsistent namespacings + * bug(autoware_predicted_path_checker): do not change node name + * This might contaminate topic name + * style(pre-commit): autofix + * bug(tier4_control_launch): fix wrong package/plugin names + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/control/autoware_predicted_path_checker/package.xml b/control/autoware_predicted_path_checker/package.xml index f1d98673420c1..521d34455f465 100644 --- a/control/autoware_predicted_path_checker/package.xml +++ b/control/autoware_predicted_path_checker/package.xml @@ -2,7 +2,7 @@ autoware_predicted_path_checker - 0.40.0 + 0.41.0 The predicted_path_checker package Berkay Karaman diff --git a/control/autoware_pure_pursuit/CHANGELOG.rst b/control/autoware_pure_pursuit/CHANGELOG.rst index e0afa320a49a5..a36d12c8c6b7b 100644 --- a/control/autoware_pure_pursuit/CHANGELOG.rst +++ b/control/autoware_pure_pursuit/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package autoware_pure_pursuit ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_pure_pursuit)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_pure_pursuit (`#9849 `_) + feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files control/autoware_pure_pursuit +* Contributors: Fumiya Watanabe, Vishal Chauhan + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/control/autoware_pure_pursuit/package.xml b/control/autoware_pure_pursuit/package.xml index 5b61cc10af1f5..98f1e71f26cf6 100644 --- a/control/autoware_pure_pursuit/package.xml +++ b/control/autoware_pure_pursuit/package.xml @@ -2,7 +2,7 @@ autoware_pure_pursuit - 0.40.0 + 0.41.0 The pure_pursuit package Takamasa Horibe Takayuki Murooka diff --git a/control/autoware_shift_decider/CHANGELOG.rst b/control/autoware_shift_decider/CHANGELOG.rst index 2b5eda421e452..73bbcb95fbdd5 100644 --- a/control/autoware_shift_decider/CHANGELOG.rst +++ b/control/autoware_shift_decider/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_shift_decider ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/control/autoware_shift_decider/package.xml b/control/autoware_shift_decider/package.xml index fb7811e094dc2..6ae72a6ade360 100644 --- a/control/autoware_shift_decider/package.xml +++ b/control/autoware_shift_decider/package.xml @@ -2,7 +2,7 @@ autoware_shift_decider - 0.40.0 + 0.41.0 The autoware_shift_decider package Takamasa Horibe Takayuki Murooka diff --git a/control/autoware_smart_mpc_trajectory_follower/CHANGELOG.rst b/control/autoware_smart_mpc_trajectory_follower/CHANGELOG.rst index d3dc4d5eb1aa8..a18c00c93f1e0 100644 --- a/control/autoware_smart_mpc_trajectory_follower/CHANGELOG.rst +++ b/control/autoware_smart_mpc_trajectory_follower/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package autoware_smart_mpc_trajectory_follower ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in fil… (`#9851 `_) +* Contributors: Fumiya Watanabe, Vishal Chauhan + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/control/autoware_smart_mpc_trajectory_follower/package.xml b/control/autoware_smart_mpc_trajectory_follower/package.xml index 7260dee488c52..a5dff3d73da63 100644 --- a/control/autoware_smart_mpc_trajectory_follower/package.xml +++ b/control/autoware_smart_mpc_trajectory_follower/package.xml @@ -2,7 +2,7 @@ autoware_smart_mpc_trajectory_follower - 0.40.0 + 0.41.0 Nodes to follow a trajectory by generating control commands using smart mpc diff --git a/control/autoware_trajectory_follower_base/CHANGELOG.rst b/control/autoware_trajectory_follower_base/CHANGELOG.rst index 88ccd57905c89..a4b5f68e14311 100644 --- a/control/autoware_trajectory_follower_base/CHANGELOG.rst +++ b/control/autoware_trajectory_follower_base/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package autoware_trajectory_follower_base ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: tier4_debug_msgs changed to autoware_internal_msgs in files con… (`#9852 `_) + feat: tier4_debug_msgs changed to autoware_internal_msgs in files control/autoware_trajectory_follower_base +* Contributors: Fumiya Watanabe, Vishal Chauhan + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/control/autoware_trajectory_follower_base/package.xml b/control/autoware_trajectory_follower_base/package.xml index 195c077835910..e7d4bd9599625 100644 --- a/control/autoware_trajectory_follower_base/package.xml +++ b/control/autoware_trajectory_follower_base/package.xml @@ -2,7 +2,7 @@ autoware_trajectory_follower_base - 0.40.0 + 0.41.0 Library for generating lateral and longitudinal controls following a trajectory diff --git a/control/autoware_trajectory_follower_node/CHANGELOG.rst b/control/autoware_trajectory_follower_node/CHANGELOG.rst index c77e252230bfb..f9554faa7a19f 100644 --- a/control/autoware_trajectory_follower_node/CHANGELOG.rst +++ b/control/autoware_trajectory_follower_node/CHANGELOG.rst @@ -2,6 +2,20 @@ Changelog for package autoware_trajectory_follower_node ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in fil… (`#9853 `_) + feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files control/autoware_trajectory_follower_node +* fix: remove unnecessary parameters (`#9935 `_) +* chore(trajectory_follower_node): fix typos (`#9707 `_) +* feat(pid_longitudinal_controller): update plotjuggler settings (`#9703 `_) +* feat(pid_longitudinal_controller): remove trans/rot deviation validation since the control_validator has the same feature (`#9675 `_) + * feat(pid_longitudinal_controller): remove trans/rot deviation validation since the control_validator has the same feature + * fix test + --------- +* Contributors: Fumiya Watanabe, Kosuke Takeuchi, Takayuki Murooka, Vishal Chauhan, Yuki TAKAGI + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/control/autoware_trajectory_follower_node/package.xml b/control/autoware_trajectory_follower_node/package.xml index aa65e340d20fe..e12cda7d0de1b 100644 --- a/control/autoware_trajectory_follower_node/package.xml +++ b/control/autoware_trajectory_follower_node/package.xml @@ -2,7 +2,7 @@ autoware_trajectory_follower_node - 0.40.0 + 0.41.0 Nodes to follow a trajectory by generating control commands separated into lateral and longitudinal commands diff --git a/control/autoware_vehicle_cmd_gate/CHANGELOG.rst b/control/autoware_vehicle_cmd_gate/CHANGELOG.rst index 38dae3279b1c8..aad435d519c55 100644 --- a/control/autoware_vehicle_cmd_gate/CHANGELOG.rst +++ b/control/autoware_vehicle_cmd_gate/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package autoware_vehicle_cmd_gate ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_vehicle_cmd_gate)!: tier4-debug_msgs changed to autoware_internal_debug_msgs in autoware_vehicle_cmd_gate (`#9856 `_) +* feat(autoware_component_interface_specs_universe!): rename package (`#9753 `_) +* Contributors: Fumiya Watanabe, Ryohsuke Mitsudome, Vishal Chauhan + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/control/autoware_vehicle_cmd_gate/package.xml b/control/autoware_vehicle_cmd_gate/package.xml index 2fcc7d77e7ec2..ba1f31c194946 100644 --- a/control/autoware_vehicle_cmd_gate/package.xml +++ b/control/autoware_vehicle_cmd_gate/package.xml @@ -2,7 +2,7 @@ autoware_vehicle_cmd_gate - 0.40.0 + 0.41.0 The vehicle_cmd_gate package Takamasa Horibe Tomoya Kimura diff --git a/evaluator/autoware_control_evaluator/CHANGELOG.rst b/evaluator/autoware_control_evaluator/CHANGELOG.rst index 88afa49d97cc3..ec41a5cc77c8c 100644 --- a/evaluator/autoware_control_evaluator/CHANGELOG.rst +++ b/evaluator/autoware_control_evaluator/CHANGELOG.rst @@ -2,6 +2,29 @@ Changelog for package autoware_control_evaluator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_control_evaluator): add new steering metrics (`#10012 `_) +* feat(autoware_control_evaluator): add new boundary_distance metrics (`#9984 `_) + * add boundary_distance metric + * pre-commit + * use path topic instead of lanenet. + * remove unused import + * apply is_point_left_of_line + * fix typo + * fix test bug + * manual pre-commit + --------- + Co-authored-by: t4-adc +* feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in fil… (`#9858 `_) + feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files evaluator/autoware_control_evaluator +* fix(autoware_control_evaluator): fix bugprone-exception-escape (`#9630 `_) + * fix: bugprone-exception-escape + * fix: cpplint + --------- +* Contributors: Fumiya Watanabe, Kem (TiankuiXian), Vishal Chauhan, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/evaluator/autoware_control_evaluator/package.xml b/evaluator/autoware_control_evaluator/package.xml index 0bc319e485387..8d32c2cf76711 100644 --- a/evaluator/autoware_control_evaluator/package.xml +++ b/evaluator/autoware_control_evaluator/package.xml @@ -2,7 +2,7 @@ autoware_control_evaluator - 0.40.0 + 0.41.0 ROS 2 node for evaluating control Daniel SANCHEZ takayuki MUROOKA diff --git a/evaluator/autoware_kinematic_evaluator/CHANGELOG.rst b/evaluator/autoware_kinematic_evaluator/CHANGELOG.rst index 7e997e497652a..d14c5972e9e07 100644 --- a/evaluator/autoware_kinematic_evaluator/CHANGELOG.rst +++ b/evaluator/autoware_kinematic_evaluator/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package autoware_kinematic_evaluator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `evaluator/kinematic_evaluator` (`#9936 `_) +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/evaluator/autoware_kinematic_evaluator/package.xml b/evaluator/autoware_kinematic_evaluator/package.xml index f64ad900976c9..7118702290f27 100644 --- a/evaluator/autoware_kinematic_evaluator/package.xml +++ b/evaluator/autoware_kinematic_evaluator/package.xml @@ -1,7 +1,7 @@ autoware_kinematic_evaluator - 0.40.0 + 0.41.0 kinematic evaluator ROS 2 node Dominik Jargot diff --git a/evaluator/autoware_localization_evaluator/CHANGELOG.rst b/evaluator/autoware_localization_evaluator/CHANGELOG.rst index 0c24579d3004d..b21f49b633da2 100644 --- a/evaluator/autoware_localization_evaluator/CHANGELOG.rst +++ b/evaluator/autoware_localization_evaluator/CHANGELOG.rst @@ -1,7 +1,26 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package localization_evaluator +Changelog for package autoware_localization_evaluator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `evaluator/localization_evaluator` (`#9954 `_) + * feat(localization_evaluator): apply `autoware\_` prefix (see below): + * In this commit, I did not organize a folder structure. + The folder structure will be organized in the next some commits. + * The changes will follow the Autoware's guideline as below: + - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder + * rename(localization_evaluator): move headers under `include/autoware`: + * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit + * fix(localization_evaluator): fix include paths + * To follow the previous commit + * rename: `localization_evaluator` => `autoware_localization_evaluator` + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/evaluator/autoware_localization_evaluator/package.xml b/evaluator/autoware_localization_evaluator/package.xml index e5b0f3f7ffe20..69f4b4eeb818c 100644 --- a/evaluator/autoware_localization_evaluator/package.xml +++ b/evaluator/autoware_localization_evaluator/package.xml @@ -1,7 +1,7 @@ autoware_localization_evaluator - 0.40.0 + 0.41.0 localization evaluator ROS 2 node Dominik Jargot diff --git a/evaluator/autoware_perception_online_evaluator/CHANGELOG.rst b/evaluator/autoware_perception_online_evaluator/CHANGELOG.rst index c3ffd03cce3b1..551ae877439f8 100644 --- a/evaluator/autoware_perception_online_evaluator/CHANGELOG.rst +++ b/evaluator/autoware_perception_online_evaluator/CHANGELOG.rst @@ -1,7 +1,32 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package perception_online_evaluator +Changelog for package autoware_perception_online_evaluator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `perception_online_evaluator` (`#9956 `_) + * feat(perception_online_evaluator): apply `autoware\_` prefix (see below): + * In this commit, I did not organize a folder structure. + The folder structure will be organized in the next some commits. + * The changes will follow the Autoware's guideline as below: + - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder + * bug(perception_online_evaluator): remove duplicated properties + * It seems the `motion_evaluator` is defined and used in the `autoware_planning_evaluator` + * rename(perception_online_evaluator): move headers under `include/autoware`: + * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit + * fix(perception_online_evaluator): fix include paths + * To follow the previous commit + * rename: `perception_online_evaluator` => `autoware_perception_online_evaluator` + * style(pre-commit): autofix + * bug(autoware_perception_online_evaluator): revert wrongly updated copyright + * bug(autoware_perception_online_evaluator): `autoware\_` prefix is not needed here + * update: `CODEOWNERS` + * bug(autoware_perception_online_evaluator): fix a wrong package name + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/evaluator/autoware_perception_online_evaluator/package.xml b/evaluator/autoware_perception_online_evaluator/package.xml index 198ef5fae247c..b8e50f6bf593c 100644 --- a/evaluator/autoware_perception_online_evaluator/package.xml +++ b/evaluator/autoware_perception_online_evaluator/package.xml @@ -2,7 +2,7 @@ autoware_perception_online_evaluator - 0.40.0 + 0.41.0 ROS 2 node for evaluating perception Fumiya Watanabe Kosuke Takeuchi diff --git a/evaluator/autoware_planning_evaluator/CHANGELOG.rst b/evaluator/autoware_planning_evaluator/CHANGELOG.rst index 77f544ae078fa..198c6216a9416 100644 --- a/evaluator/autoware_planning_evaluator/CHANGELOG.rst +++ b/evaluator/autoware_planning_evaluator/CHANGELOG.rst @@ -2,6 +2,38 @@ Changelog for package autoware_planning_evaluator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in fil… (`#9859 `_) + feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files evaluator/autoware_planning_evaluator +* fix(planning_evaluator): update lateral_trajectory_displacement to absolute value (`#9696 `_) + * fix(planning_evaluator): update lateral_trajectory_displacement to absolute value + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* fix(autoware_planning_evaluator): rename lateral deviation metrics (`#9801 `_) + * refactor(planning_evaluator): rename and add lateral trajectory displacement metrics + * fix typo + --------- +* feat(planning_evaluator): add evaluation feature of trajectory lateral displacement (`#9718 `_) + * feat(planning_evaluator): add evaluation feature of trajectory lateral displacement + * feat(metrics_calculator): implement lookahead trajectory calculation and remove deprecated method + * fix(planning_evaluator): rename lateral_trajectory_displacement to trajectory_lateral_displacement for consistency + --------- +* fix(autoware_planning_evaluator): fix bugprone-exception-escape (`#9730 `_) + fix: bugprone-exception-escape +* feat(planning_evaluator): add lateral trajectory displacement metrics (`#9674 `_) + * feat(planning_evaluator): add nearest pose deviation msg + * update comment contents + * update variable name + * Revert "update variable name" + This reverts commit ee427222fcbd2a18ffbc20fecca3ad557f527e37. + * move lateral_trajectory_displacement position + * prev.dist -> prev_lateral_deviation + --------- +* Contributors: Fumiya Watanabe, Kazunori-Nakajima, Kyoichi Sugahara, Vishal Chauhan, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/evaluator/autoware_planning_evaluator/package.xml b/evaluator/autoware_planning_evaluator/package.xml index 4389b2e52f44d..22c3b93035e9d 100644 --- a/evaluator/autoware_planning_evaluator/package.xml +++ b/evaluator/autoware_planning_evaluator/package.xml @@ -2,7 +2,7 @@ autoware_planning_evaluator - 0.40.0 + 0.41.0 ROS 2 node for evaluating planners Maxime CLEMENT Kyoichi Sugahara diff --git a/evaluator/autoware_scenario_simulator_v2_adapter/CHANGELOG.rst b/evaluator/autoware_scenario_simulator_v2_adapter/CHANGELOG.rst index 7b583a3da7959..5bf589f24fb9a 100644 --- a/evaluator/autoware_scenario_simulator_v2_adapter/CHANGELOG.rst +++ b/evaluator/autoware_scenario_simulator_v2_adapter/CHANGELOG.rst @@ -1,7 +1,27 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package scenario_simulator_v2_adapter +Changelog for package autoware_scenario_simulator_v2_adapter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `scenario_simulator_v2_adapter` (`#9957 `_) + * feat(autoware_scenario_simulator_v2_adapter): apply `autoware\_` prefix (see below): + * In this commit, I did not organize a folder structure. + The folder structure will be organized in the next some commits. + * The changes will follow the Autoware's guideline as below: + - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder + * rename(scenario_simulator_v2_adapter): move headers under `include/autoware`: + * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit + * fix(scenario_simulator_v2_adapter): fix include paths + * To follow the previous commit + * rename: `scenario_simulator_v2_adapter` => `autoware_scenario_simulator_v2_adapter` + * bug(autoware_scenario_simulator_v2_adapter): revert wrongly updated copyrights + * bug(autoware_scenario_simulator_v2_adapter): `autoware\_` prefix is not needed here + * bug(autoware_scenario_simulator_v2_adapter): wrong package name in launch side + --------- +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/evaluator/autoware_scenario_simulator_v2_adapter/package.xml b/evaluator/autoware_scenario_simulator_v2_adapter/package.xml index 7d3fe5246c110..481be97c9a871 100644 --- a/evaluator/autoware_scenario_simulator_v2_adapter/package.xml +++ b/evaluator/autoware_scenario_simulator_v2_adapter/package.xml @@ -2,7 +2,7 @@ autoware_scenario_simulator_v2_adapter - 0.40.0 + 0.41.0 Node for converting autoware's messages into UserDefinedValue messages Kyoichi Sugahara Maxime CLEMENT diff --git a/launch/tier4_autoware_api_launch/CHANGELOG.rst b/launch/tier4_autoware_api_launch/CHANGELOG.rst index 5892c238a3bd6..3e4e35d92c0a0 100644 --- a/launch/tier4_autoware_api_launch/CHANGELOG.rst +++ b/launch/tier4_autoware_api_launch/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package tier4_autoware_api_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `default_ad_api_helpers` (`#9965 `_) + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Takagi, Isamu +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/launch/tier4_autoware_api_launch/package.xml b/launch/tier4_autoware_api_launch/package.xml index 290aa80bcdad7..5cd633a65277d 100644 --- a/launch/tier4_autoware_api_launch/package.xml +++ b/launch/tier4_autoware_api_launch/package.xml @@ -2,7 +2,7 @@ tier4_autoware_api_launch - 0.40.0 + 0.41.0 The tier4_autoware_api_launch package Takagi, Isamu Ryohsuke Mitsudome diff --git a/launch/tier4_control_launch/CHANGELOG.rst b/launch/tier4_control_launch/CHANGELOG.rst index 3f94ac4f2b2e0..c762f0fe3a27c 100644 --- a/launch/tier4_control_launch/CHANGELOG.rst +++ b/launch/tier4_control_launch/CHANGELOG.rst @@ -2,6 +2,31 @@ Changelog for package tier4_control_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `predicted_path_checker` (`#9985 `_) + * feat(predicted_path_checker): apply `autoware\_` prefix (see below): + Note: + * In this commit, I did not organize a folder structure. + The folder structure will be organized in the next some commits. + * The changes will follow the Autoware's guideline as below: + - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder + * rename(predicted_path_checker): move headers under `include/autoware` + * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit + * fix(predicted_path_checker): fix include header paths + * To follow the previous commit + * rename: `predicted_path_checker` => `autoware_predicted_path_checker` + * style(pre-commit): autofix + * bug(autoware_predicted_path_checker): fix inconsistent namespacings + * bug(autoware_predicted_path_checker): do not change node name + * This might contaminate topic name + * style(pre-commit): autofix + * bug(tier4_control_launch): fix wrong package/plugin names + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/launch/tier4_control_launch/package.xml b/launch/tier4_control_launch/package.xml index d9a2f9883cbce..8f9fec3c289ff 100644 --- a/launch/tier4_control_launch/package.xml +++ b/launch/tier4_control_launch/package.xml @@ -2,7 +2,7 @@ tier4_control_launch - 0.40.0 + 0.41.0 The tier4_control_launch package Takamasa Horibe Takayuki Murooka diff --git a/launch/tier4_localization_launch/CHANGELOG.rst b/launch/tier4_localization_launch/CHANGELOG.rst index 991f04240d04d..8e11fb9ff877a 100644 --- a/launch/tier4_localization_launch/CHANGELOG.rst +++ b/launch/tier4_localization_launch/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package tier4_localization_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `default_ad_api_helpers` (`#9965 `_) + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Takagi, Isamu +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/launch/tier4_localization_launch/package.xml b/launch/tier4_localization_launch/package.xml index e686bf627be5c..5a79e29858725 100644 --- a/launch/tier4_localization_launch/package.xml +++ b/launch/tier4_localization_launch/package.xml @@ -2,7 +2,7 @@ tier4_localization_launch - 0.40.0 + 0.41.0 The tier4_localization_launch package Yamato Ando Kento Yabuuchi diff --git a/launch/tier4_map_launch/CHANGELOG.rst b/launch/tier4_map_launch/CHANGELOG.rst index 5ba95030bf15b..beb24e7e79641 100644 --- a/launch/tier4_map_launch/CHANGELOG.rst +++ b/launch/tier4_map_launch/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package tier4_map_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/launch/tier4_map_launch/package.xml b/launch/tier4_map_launch/package.xml index ba512960af1b2..66f2f9490192a 100644 --- a/launch/tier4_map_launch/package.xml +++ b/launch/tier4_map_launch/package.xml @@ -2,7 +2,7 @@ tier4_map_launch - 0.40.0 + 0.41.0 The tier4_map_launch package Ryu Yamamoto Kento Yabuuchi diff --git a/launch/tier4_perception_launch/CHANGELOG.rst b/launch/tier4_perception_launch/CHANGELOG.rst index b8ac734476a36..f6315cc25ac6d 100644 --- a/launch/tier4_perception_launch/CHANGELOG.rst +++ b/launch/tier4_perception_launch/CHANGELOG.rst @@ -2,6 +2,47 @@ Changelog for package tier4_perception_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `dummy_perception_publisher` (`#9987 `_) +* fix(launch): fix missing changes for launch (`#10007 `_) + bug(launch): fix missing changes for following PRs: + * https://github.com/autowarefoundation/autoware.universe/pull/9956 + * https://github.com/autowarefoundation/autoware.universe/pull/9970 +* fix(tier4_perception_launch): rearrange roi based cluster pipeline (`#9938 `_) +* fix(image_projection_based_fusion): revise message publishers (`#9865 `_) + * refactor: fix condition for publishing painted pointcloud message + * fix: publish output revised + * feat: fix condition for publishing painted pointcloud message + * feat: roi-pointclout fusion - publish empty image even when there is no target roi + * fix: remap output topic for clusters in roi_pointcloud_fusion + * style(pre-commit): autofix + * feat: fix condition for publishing painted pointcloud message + * feat: Add debug publisher for internal debugging + * feat: remove !! pointer to bool conversion + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(autoware_object_merger, autoware_tracking_object_merger): enable anonymized node names to be configurable (`#9733 `_) + feat: enable anonymized node names to be configurable +* refactor(tier4_perception_launch): refactoring detection launchers (`#9611 `_) + * feat: Update object detection launch files to include input and output arguments + The object detection launch files have been updated to include input and output arguments for better flexibility and modularity. This allows for easier integration with other components and improves the overall performance of the system. + ``` + * feat: Update object detection launch files to include input and output arguments + * refactor: Update object detection launch files for better readability + * Update object detection launch files to include clustering output argument + * fix: pass ns argument to the lidar_rule_detector + * refactor: make euclidean_cluster not to use use_pointcloud_container and mark explicitly + --------- +* fix(tier4_perception_launch): update multi-channel subscribing channel name to lidar_detection_model_type (`#9624 `_) + * feat: update object detection channels in tracking.launch.xml + The object detection channels in the `tracking.launch.xml` file have been updated to include the lidar detection model type. + * feat: support even the validator is not used + add variable use_validator to the tracking launch and determine the subscribing channel depends on the use_validator value + --------- +* Contributors: Fumiya Watanabe, Junya Sasaki, Taekjin LEE, badai nguyen + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/launch/tier4_perception_launch/package.xml b/launch/tier4_perception_launch/package.xml index 613223fa960bd..41a019a40590c 100644 --- a/launch/tier4_perception_launch/package.xml +++ b/launch/tier4_perception_launch/package.xml @@ -2,7 +2,7 @@ tier4_perception_launch - 0.40.0 + 0.41.0 The tier4_perception_launch package Yukihiro Saito Shunsuke Miura diff --git a/launch/tier4_planning_launch/CHANGELOG.rst b/launch/tier4_planning_launch/CHANGELOG.rst index efa4a02803c46..92c390600ee79 100644 --- a/launch/tier4_planning_launch/CHANGELOG.rst +++ b/launch/tier4_planning_launch/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package tier4_planning_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_mission_planner)!: feat(autoware_mission_planner_universe)!: add _universe suffix to package name (`#9941 `_) +* feat(motion_velocity_planner)!: add _universe suffix to autoware_motion_velocity_planner_common and autoware_motion_velocity_planner_node (`#9942 `_) +* Contributors: Fumiya Watanabe, Ryohsuke Mitsudome + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/launch/tier4_planning_launch/package.xml b/launch/tier4_planning_launch/package.xml index 0acb4738d8068..431450c4f24a2 100644 --- a/launch/tier4_planning_launch/package.xml +++ b/launch/tier4_planning_launch/package.xml @@ -2,7 +2,7 @@ tier4_planning_launch - 0.40.0 + 0.41.0 The tier4_planning_launch package diff --git a/launch/tier4_sensing_launch/CHANGELOG.rst b/launch/tier4_sensing_launch/CHANGELOG.rst index 7e6e12e53a08c..272cd43756e65 100644 --- a/launch/tier4_sensing_launch/CHANGELOG.rst +++ b/launch/tier4_sensing_launch/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package tier4_sensing_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/launch/tier4_sensing_launch/package.xml b/launch/tier4_sensing_launch/package.xml index 6e7553ac9f8f0..8ee3618b75eed 100644 --- a/launch/tier4_sensing_launch/package.xml +++ b/launch/tier4_sensing_launch/package.xml @@ -2,7 +2,7 @@ tier4_sensing_launch - 0.40.0 + 0.41.0 The tier4_sensing_launch package Yukihiro Saito Apache License 2.0 diff --git a/launch/tier4_simulator_launch/CHANGELOG.rst b/launch/tier4_simulator_launch/CHANGELOG.rst index 569da150b16ae..a600556bace8e 100644 --- a/launch/tier4_simulator_launch/CHANGELOG.rst +++ b/launch/tier4_simulator_launch/CHANGELOG.rst @@ -2,6 +2,76 @@ Changelog for package tier4_simulator_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `dummy_perception_publisher` (`#9987 `_) +* fix(tier4_simulator_launch): fix a wrong package name: `fault_injection` => `autoware_fault_injection` (`#10014 `_) +* feat: apply `autoware\_` prefix for `scenario_simulator_v2_adapter` (`#9957 `_) + * feat(autoware_scenario_simulator_v2_adapter): apply `autoware\_` prefix (see below): + * In this commit, I did not organize a folder structure. + The folder structure will be organized in the next some commits. + * The changes will follow the Autoware's guideline as below: + - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder + * rename(scenario_simulator_v2_adapter): move headers under `include/autoware`: + * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit + * fix(scenario_simulator_v2_adapter): fix include paths + * To follow the previous commit + * rename: `scenario_simulator_v2_adapter` => `autoware_scenario_simulator_v2_adapter` + * bug(autoware_scenario_simulator_v2_adapter): revert wrongly updated copyrights + * bug(autoware_scenario_simulator_v2_adapter): `autoware\_` prefix is not needed here + * bug(autoware_scenario_simulator_v2_adapter): wrong package name in launch side + --------- +* feat: apply `autoware\_` prefix for `simple_planning_simulator` (`#9995 `_) + * feat(simple_planning_simulator): apply `autoware\_` prefix (see below): + Note: + * In this commit, I did not organize a folder structure. + The folder structure will be organized in the next some commits. + * The changes will follow the Autoware's guideline as below: + - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder + * rename(simple_planning_simulator): move headers under `include/autoware`: + * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit + * fix(simple_planning_simulator): fix include header paths + * To follow the previous commit + * rename: `simple_planning_simulator` => `autoware_simple_planning_simulator` + * bug(autoware_simple_planning_simulator): fix missing changes + * style(pre-commit): autofix + * bug(autoware_simple_planning_simulator): fix errors in build and tests + * I had to run after `rm -rf install build`, ... sorry + * style(pre-commit): autofix + * Fixed NOLINT + * Added NOLINT + * Fixed to autoware_simple_planning_simulator + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Shintaro Sakoda +* feat: apply `autoware\_` prefix for `vehicle_door_simulator` (`#9997 `_) + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat: apply `autoware\_` prefix for `fault_injection` (`#9989 `_) + * feat(fault_injection): apply `autoware\_` prefix (see below): + Note: + * In this commit, I did not organize a folder structure. + The folder structure will be organized in the next some commits. + * The changes will follow the Autoware's guideline as below: + - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder + * rename(fault_injection): move headers under `include/autoware`: + * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit + * fix(fault_injection): fix include header paths + * To follow the previous commit + * rename: `fault_injection` => `autoware_fault_injection` + * Fixed exec_depend + --------- + Co-authored-by: SakodaShintaro +* fix(launch): fix missing changes for launch (`#10007 `_) + bug(launch): fix missing changes for following PRs: + * https://github.com/autowarefoundation/autoware.universe/pull/9956 + * https://github.com/autowarefoundation/autoware.universe/pull/9970 +* fix(tier4_simulator_launch): add use_validator argument to simulator launch (`#9634 `_) + * feat: add use_validator argument to simulator launch + * feat: set variables explicitly + --------- +* Contributors: Fumiya Watanabe, Junya Sasaki, Taekjin LEE + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/launch/tier4_simulator_launch/package.xml b/launch/tier4_simulator_launch/package.xml index 030c7ab143255..85a57324b6851 100644 --- a/launch/tier4_simulator_launch/package.xml +++ b/launch/tier4_simulator_launch/package.xml @@ -2,7 +2,7 @@ tier4_simulator_launch - 0.40.0 + 0.41.0 The tier4_simulator_launch package Keisuke Shima Takayuki Murooka diff --git a/launch/tier4_system_launch/CHANGELOG.rst b/launch/tier4_system_launch/CHANGELOG.rst index 9ffb34c4599a9..1f03f4c66db02 100644 --- a/launch/tier4_system_launch/CHANGELOG.rst +++ b/launch/tier4_system_launch/CHANGELOG.rst @@ -2,6 +2,81 @@ Changelog for package tier4_system_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware` prefix for `component_state_monitor` and its dependencies (`#9961 `_) +* feat: apply `autoware\_` prefix for `hazard_status_converter` (`#9971 `_) +* feat: apply `autoware\_` prefix for `system_monitor` (`#10017 `_) + * feat(system_monitor): apply `autoware\_` prefix (see below): + * The `system_monitor` operates independently from other modules in `autoware.universe`, so the `autoware\_` prefix is added only to the package name. + * The `autoware::` namespace is not used because C language does not support namespaces. + * Headers are not moved under `include/autoware` to maintain compatibility for use outside the `autoware` context. + * For users utilizing this package within `autoware.universe`, only the package name includes the `autoware\_` prefix. + This approach explains the unique namespacing and naming conventions for `system_monitor` compared to other packages. + * bug(system_monitor): fix missing package name update + * rename: `system_monitor` => `autoware_system_monitor` + * style(pre-commit): autofix + * update: `CODEOWNERS` + * bug(autoware_system_monitor): apply missing fix + * update: `CODEOWNERS` + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat: apply `autoware\_` prefix for `mrm_comfortable_stop_operator` (`#10011 `_) + * feat(mrm_comfortable_stop_operator): apply `autoware\_` prefix (see below): + Note: + * In this commit, I did not organize a folder structure. + The folder structure will be organized in the next some commits. + * The changes will follow the Autoware's guideline as below: + - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder + * rename(mrm_comfortable_stop_operator): move a header under `include/autoware` + * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit + * fix(mrm_comfortable_stop_operator): fix include header path + * To follow the previous commit + * rename: `mrm_comfortable_stop_operator` => `autoware_mrm_comfortable_stop_operator` + * update: `CODEOWNERS` + --------- +* feat: apply `autoware\_` prefix for `mrm_emergency_stop_operator` (`#9973 `_) + * feat(mrm_emergency_stop_operator): apply `autoware\_` prefix (see below): + Note: + * In this commit, I did not organize a folder structure. + The folder structure will be organized in the next some commits. + * The changes will follow the Autoware's guideline as below: + - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder + * rename(mrm_emergency_stop_operator): move a header under `include/autoware`: + * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit + * fix(mrm_emergency_stop_operator): fix include header path + * To follow the previous commit + * rename: `mrm_emergency_stop_operator` => `autoware_mrm_emergency_stop_operator` + * bug(autoware_mrm_emergency_stop_operator): revert wrongly updated copyrights + * bug(tier4_system_launch): fix a missing `autoware\_` for `mrm_emergency_stop_operator` + * bug(autoware_mrm_emergency_stop_operator): fix critical bugs that contaminate topic names + --------- +* feat: apply `autoware\_` prefix for `mrm_handler` (`#9974 `_) + * feat(mrm_handler): apply `autoware\_` prefix (see below): + Note: + * In this commit, I did not organize a folder structure. + The folder structure will be organized in the next some commits. + * The changes will follow the Autoware's guideline as below: + - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder + * rename(mrm_handler): move a header under `include/autoware`: + * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit + * fix(mrm_handler): fix include header path + * To follow the previous commit + * rename: `mrm_handler` => `autoware_mrm_handler` + * bug(tier4_system_launch): fix a missing `autoware\_` for `mrm_handler` + * bug(mrm_handler): revert wrongly updated copyrights + * update(mrm_handler): `README.md` + * bug(autoware_mrm_handler): fix a critical bug that contaminates topic name + --------- +* fix(launch): fix missing changes for launch (`#10007 `_) + bug(launch): fix missing changes for following PRs: + * https://github.com/autowarefoundation/autoware.universe/pull/9956 + * https://github.com/autowarefoundation/autoware.universe/pull/9970 +* fix(tier4_system_launch): add autoware prefix to dummy diag publisher launcher (`#9959 `_) + fix: add autoare\_ to dummy_diag_publisher +* Contributors: Fumiya Watanabe, Junya Sasaki, TetsuKawa + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/launch/tier4_system_launch/package.xml b/launch/tier4_system_launch/package.xml index 65a8c11feaa73..318d6a2673c50 100644 --- a/launch/tier4_system_launch/package.xml +++ b/launch/tier4_system_launch/package.xml @@ -2,7 +2,7 @@ tier4_system_launch - 0.40.0 + 0.41.0 The tier4_system_launch package Fumihito Ito TetsuKawa diff --git a/launch/tier4_vehicle_launch/CHANGELOG.rst b/launch/tier4_vehicle_launch/CHANGELOG.rst index 1b5a1271e9fe3..6da13259c5612 100644 --- a/launch/tier4_vehicle_launch/CHANGELOG.rst +++ b/launch/tier4_vehicle_launch/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package tier4_vehicle_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/launch/tier4_vehicle_launch/package.xml b/launch/tier4_vehicle_launch/package.xml index 583bbf325db05..80f07dab5383e 100644 --- a/launch/tier4_vehicle_launch/package.xml +++ b/launch/tier4_vehicle_launch/package.xml @@ -2,7 +2,7 @@ tier4_vehicle_launch - 0.40.0 + 0.41.0 The tier4_vehicle_launch package Yukihiro Saito Apache License 2.0 diff --git a/localization/autoware_ekf_localizer/CHANGELOG.rst b/localization/autoware_ekf_localizer/CHANGELOG.rst index b8e74c530e059..9f520e0d9c112 100644 --- a/localization/autoware_ekf_localizer/CHANGELOG.rst +++ b/localization/autoware_ekf_localizer/CHANGELOG.rst @@ -2,6 +2,26 @@ Changelog for package autoware_ekf_localizer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* revert: revert "feat(autoware_ekf_localizer)!: porting from universe to core (`#9978 `_)" (`#10004 `_) + This reverts commit 037c315fbee69bb5923ec10bb8e8e70f890725ea. +* feat(autoware_ekf_localizer)!: porting from universe to core (`#9978 `_) + * feat: delete ekf_localizer files + * doc: Modify ekf_localizer directory links + * ci: remove ekf_localizer from the codecov target list + --------- +* feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in fies localization/autoware_ekf_localizer (`#9860 `_) + Co-authored-by: SakodaShintaro +* feat(ekf_localizer): check whether the initialpose has been set (`#9787 `_) + * check set intialpose + * update png + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Fumiya Watanabe, Motz, Ryohsuke Mitsudome, Vishal Chauhan, Yamato Ando + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/localization/autoware_ekf_localizer/package.xml b/localization/autoware_ekf_localizer/package.xml index e0e37f59d1acb..ff510862eb089 100644 --- a/localization/autoware_ekf_localizer/package.xml +++ b/localization/autoware_ekf_localizer/package.xml @@ -2,7 +2,7 @@ autoware_ekf_localizer - 0.40.0 + 0.41.0 The autoware_ekf_localizer package Takamasa Horibe Yamato Ando diff --git a/localization/autoware_geo_pose_projector/CHANGELOG.rst b/localization/autoware_geo_pose_projector/CHANGELOG.rst index 1b45974da9cc2..2c8750eb5fd31 100644 --- a/localization/autoware_geo_pose_projector/CHANGELOG.rst +++ b/localization/autoware_geo_pose_projector/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package autoware_geo_pose_projector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_component_interface_specs_universe!): rename package (`#9753 `_) +* Contributors: Fumiya Watanabe, Ryohsuke Mitsudome + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/localization/autoware_geo_pose_projector/package.xml b/localization/autoware_geo_pose_projector/package.xml index f7240c83ab152..5981e61836b05 100644 --- a/localization/autoware_geo_pose_projector/package.xml +++ b/localization/autoware_geo_pose_projector/package.xml @@ -2,7 +2,7 @@ autoware_geo_pose_projector - 0.40.0 + 0.41.0 The autoware_geo_pose_projector package Yamato Ando Masahiro Sakamoto diff --git a/localization/autoware_gyro_odometer/CHANGELOG.rst b/localization/autoware_gyro_odometer/CHANGELOG.rst index 529fe48f7b459..063d1aaa4fd62 100644 --- a/localization/autoware_gyro_odometer/CHANGELOG.rst +++ b/localization/autoware_gyro_odometer/CHANGELOG.rst @@ -2,6 +2,28 @@ Changelog for package autoware_gyro_odometer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* refactor(autoware_universe_utils): add missing 's' in the class of diagnostics_interface (`#9777 `_) +* feat!: move diagnostics_module from localization_util to unverse_utils (`#9714 `_) + * feat!: move diagnostics_module from localization_util to unverse_utils + * remove diagnostics module from localization_util + * style(pre-commit): autofix + * minor fix in pose_initializer + * add test + * style(pre-commit): autofix + * remove unnecessary declaration + * module -> interface + * remove unnecessary equal expression + * revert the remove of template function + * style(pre-commit): autofix + * use overload instead + * include what you use -- test_diagnostics_interface.cpp + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Fumiya Watanabe, kminoda + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/localization/autoware_gyro_odometer/package.xml b/localization/autoware_gyro_odometer/package.xml index 87474c0b13c0f..c05867de34aaa 100644 --- a/localization/autoware_gyro_odometer/package.xml +++ b/localization/autoware_gyro_odometer/package.xml @@ -2,7 +2,7 @@ autoware_gyro_odometer - 0.40.0 + 0.41.0 The autoware_gyro_odometer package as a ROS 2 node Yamato Ando Masahiro Sakamoto diff --git a/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/CHANGELOG.rst b/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/CHANGELOG.rst index 36d7431a499ff..9c61094b6596e 100644 --- a/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/CHANGELOG.rst +++ b/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_ar_tag_based_localizer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/package.xml b/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/package.xml index 4aab7e0b5cdaf..b69ebe21480d4 100644 --- a/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/package.xml +++ b/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/package.xml @@ -2,7 +2,7 @@ autoware_ar_tag_based_localizer - 0.40.0 + 0.41.0 The autoware_ar_tag_based_localizer package Shintaro Sakoda Masahiro Sakamoto diff --git a/localization/autoware_landmark_based_localizer/autoware_landmark_manager/CHANGELOG.rst b/localization/autoware_landmark_based_localizer/autoware_landmark_manager/CHANGELOG.rst index f6d4cf6766e84..167dd0bbf5e0d 100644 --- a/localization/autoware_landmark_based_localizer/autoware_landmark_manager/CHANGELOG.rst +++ b/localization/autoware_landmark_based_localizer/autoware_landmark_manager/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_landmark_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/localization/autoware_landmark_based_localizer/autoware_landmark_manager/package.xml b/localization/autoware_landmark_based_localizer/autoware_landmark_manager/package.xml index c33b8a751ce7f..3339070979535 100644 --- a/localization/autoware_landmark_based_localizer/autoware_landmark_manager/package.xml +++ b/localization/autoware_landmark_based_localizer/autoware_landmark_manager/package.xml @@ -2,7 +2,7 @@ autoware_landmark_manager - 0.40.0 + 0.41.0 The autoware_landmark_manager package Shintaro Sakoda Masahiro Sakamoto diff --git a/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/CHANGELOG.rst b/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/CHANGELOG.rst index a7edd5b7d2a69..d2a3371ad096b 100644 --- a/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/CHANGELOG.rst +++ b/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/CHANGELOG.rst @@ -2,6 +2,33 @@ Changelog for package autoware_lidar_marker_localizer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* fix(autoware_lidar_marker_localization): fix segmentation fault (`#8943 `_) + * fix segmentation fault + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* refactor(autoware_universe_utils): add missing 's' in the class of diagnostics_interface (`#9777 `_) +* feat!: move diagnostics_module from localization_util to unverse_utils (`#9714 `_) + * feat!: move diagnostics_module from localization_util to unverse_utils + * remove diagnostics module from localization_util + * style(pre-commit): autofix + * minor fix in pose_initializer + * add test + * style(pre-commit): autofix + * remove unnecessary declaration + * module -> interface + * remove unnecessary equal expression + * revert the remove of template function + * style(pre-commit): autofix + * use overload instead + * include what you use -- test_diagnostics_interface.cpp + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Fumiya Watanabe, Yamato Ando, kminoda + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/package.xml b/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/package.xml index c365f7ef040dc..dc0b8cf663c06 100755 --- a/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/package.xml +++ b/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/package.xml @@ -2,7 +2,7 @@ autoware_lidar_marker_localizer - 0.40.0 + 0.41.0 The autoware_lidar_marker_localizer package Yamato Ando Shintaro Sakoda diff --git a/localization/autoware_localization_error_monitor/CHANGELOG.rst b/localization/autoware_localization_error_monitor/CHANGELOG.rst index 69833a04a8d3a..8b99b4870eaa1 100644 --- a/localization/autoware_localization_error_monitor/CHANGELOG.rst +++ b/localization/autoware_localization_error_monitor/CHANGELOG.rst @@ -2,6 +2,28 @@ Changelog for package autoware_localization_error_monitor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* refactor(autoware_universe_utils): add missing 's' in the class of diagnostics_interface (`#9777 `_) +* feat!: move diagnostics_module from localization_util to unverse_utils (`#9714 `_) + * feat!: move diagnostics_module from localization_util to unverse_utils + * remove diagnostics module from localization_util + * style(pre-commit): autofix + * minor fix in pose_initializer + * add test + * style(pre-commit): autofix + * remove unnecessary declaration + * module -> interface + * remove unnecessary equal expression + * revert the remove of template function + * style(pre-commit): autofix + * use overload instead + * include what you use -- test_diagnostics_interface.cpp + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Fumiya Watanabe, kminoda + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/localization/autoware_localization_error_monitor/package.xml b/localization/autoware_localization_error_monitor/package.xml index f7f9e635e85d6..d3ba2e2852e51 100644 --- a/localization/autoware_localization_error_monitor/package.xml +++ b/localization/autoware_localization_error_monitor/package.xml @@ -2,7 +2,7 @@ autoware_localization_error_monitor - 0.40.0 + 0.41.0 ros node for monitoring localization error Yamato Ando Masahiro Sakamoto diff --git a/localization/autoware_ndt_scan_matcher/CHANGELOG.rst b/localization/autoware_ndt_scan_matcher/CHANGELOG.rst index 8040641aa2cef..c9ef88ac152f5 100644 --- a/localization/autoware_ndt_scan_matcher/CHANGELOG.rst +++ b/localization/autoware_ndt_scan_matcher/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package autoware_ndt_scan_matcher ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: tier4_debug_msgs changed to autoware-internal_debug_msgs in files localization/autoware_ndt_scan_matcher (`#9861 `_) + Co-authored-by: SakodaShintaro +* refactor(autoware_universe_utils): add missing 's' in the class of diagnostics_interface (`#9777 `_) +* feat!: move diagnostics_module from localization_util to unverse_utils (`#9714 `_) + * feat!: move diagnostics_module from localization_util to unverse_utils + * remove diagnostics module from localization_util + * style(pre-commit): autofix + * minor fix in pose_initializer + * add test + * style(pre-commit): autofix + * remove unnecessary declaration + * module -> interface + * remove unnecessary equal expression + * revert the remove of template function + * style(pre-commit): autofix + * use overload instead + * include what you use -- test_diagnostics_interface.cpp + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Fumiya Watanabe, Vishal Chauhan, kminoda + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/localization/autoware_ndt_scan_matcher/package.xml b/localization/autoware_ndt_scan_matcher/package.xml index ebd1ebda2d573..bdcee3a98f043 100644 --- a/localization/autoware_ndt_scan_matcher/package.xml +++ b/localization/autoware_ndt_scan_matcher/package.xml @@ -2,7 +2,7 @@ autoware_ndt_scan_matcher - 0.40.0 + 0.41.0 The autoware_ndt_scan_matcher package Yamato Ando Kento Yabuuchi diff --git a/localization/autoware_pose2twist/CHANGELOG.rst b/localization/autoware_pose2twist/CHANGELOG.rst index 3f17982f52f31..497a2f0cebc6a 100644 --- a/localization/autoware_pose2twist/CHANGELOG.rst +++ b/localization/autoware_pose2twist/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package autoware_pose2twist ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files localization/autoware_pose2twist (`#9866 `_) +* Contributors: Fumiya Watanabe, Vishal Chauhan + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/localization/autoware_pose2twist/package.xml b/localization/autoware_pose2twist/package.xml index cfde18d430cfd..88e046f2e5cad 100644 --- a/localization/autoware_pose2twist/package.xml +++ b/localization/autoware_pose2twist/package.xml @@ -2,7 +2,7 @@ autoware_pose2twist - 0.40.0 + 0.41.0 The autoware_pose2twist package Yamato Ando Masahiro Sakamoto diff --git a/localization/autoware_pose_covariance_modifier/CHANGELOG.rst b/localization/autoware_pose_covariance_modifier/CHANGELOG.rst index 6fc366d3d01d5..8861c5725883c 100644 --- a/localization/autoware_pose_covariance_modifier/CHANGELOG.rst +++ b/localization/autoware_pose_covariance_modifier/CHANGELOG.rst @@ -2,6 +2,17 @@ Changelog for package autoware_pose_covariance_modifier ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* revert: revert "feat(autoware_ekf_localizer)!: porting from universe to core (`#9978 `_)" (`#10004 `_) + This reverts commit 037c315fbee69bb5923ec10bb8e8e70f890725ea. +* feat(autoware_ekf_localizer)!: porting from universe to core (`#9978 `_) + * feat: delete ekf_localizer files + * doc: Modify ekf_localizer directory links + * ci: remove ekf_localizer from the codecov target list + --------- +* Contributors: Motz, Ryohsuke Mitsudome + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/localization/autoware_pose_covariance_modifier/package.xml b/localization/autoware_pose_covariance_modifier/package.xml index 7825bd59b78f9..49bf3362983d8 100644 --- a/localization/autoware_pose_covariance_modifier/package.xml +++ b/localization/autoware_pose_covariance_modifier/package.xml @@ -2,7 +2,7 @@ autoware_pose_covariance_modifier - 0.40.0 + 0.41.0 Add a description. Melike Tanrikulu diff --git a/localization/autoware_pose_estimator_arbiter/CHANGELOG.rst b/localization/autoware_pose_estimator_arbiter/CHANGELOG.rst index 381b77546e008..7fabd13c0f3ff 100644 --- a/localization/autoware_pose_estimator_arbiter/CHANGELOG.rst +++ b/localization/autoware_pose_estimator_arbiter/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_pose_estimator_arbiter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/localization/autoware_pose_estimator_arbiter/package.xml b/localization/autoware_pose_estimator_arbiter/package.xml index c6a47ae5755b3..b9ffae2137037 100644 --- a/localization/autoware_pose_estimator_arbiter/package.xml +++ b/localization/autoware_pose_estimator_arbiter/package.xml @@ -2,7 +2,7 @@ autoware_pose_estimator_arbiter - 0.40.0 + 0.41.0 The arbiter of multiple pose estimators Yamato Ando Kento Yabuuchi diff --git a/localization/autoware_pose_initializer/CHANGELOG.rst b/localization/autoware_pose_initializer/CHANGELOG.rst index 45473a9444270..b89892adb13a8 100644 --- a/localization/autoware_pose_initializer/CHANGELOG.rst +++ b/localization/autoware_pose_initializer/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_pose_initializer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `default_ad_api_helpers` (`#9965 `_) + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Takagi, Isamu +* feat(autoware_component_interface_specs_universe!): rename package (`#9753 `_) +* refactor(autoware_universe_utils): add missing 's' in the class of diagnostics_interface (`#9777 `_) +* feat!: move diagnostics_module from localization_util to unverse_utils (`#9714 `_) + * feat!: move diagnostics_module from localization_util to unverse_utils + * remove diagnostics module from localization_util + * style(pre-commit): autofix + * minor fix in pose_initializer + * add test + * style(pre-commit): autofix + * remove unnecessary declaration + * module -> interface + * remove unnecessary equal expression + * revert the remove of template function + * style(pre-commit): autofix + * use overload instead + * include what you use -- test_diagnostics_interface.cpp + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Fumiya Watanabe, Junya Sasaki, Ryohsuke Mitsudome, kminoda + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/localization/autoware_pose_initializer/package.xml b/localization/autoware_pose_initializer/package.xml index 693dcad0260b5..cff9fc1fec3e5 100644 --- a/localization/autoware_pose_initializer/package.xml +++ b/localization/autoware_pose_initializer/package.xml @@ -2,7 +2,7 @@ autoware_pose_initializer - 0.40.0 + 0.41.0 The autoware_pose_initializer package Yamato Ando Takagi, Isamu diff --git a/localization/autoware_pose_instability_detector/CHANGELOG.rst b/localization/autoware_pose_instability_detector/CHANGELOG.rst index b95dcaf6f01c8..d629e317c17f9 100644 --- a/localization/autoware_pose_instability_detector/CHANGELOG.rst +++ b/localization/autoware_pose_instability_detector/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_pose_instability_detector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/localization/autoware_pose_instability_detector/package.xml b/localization/autoware_pose_instability_detector/package.xml index 91a565446f9e9..249ea6d625673 100644 --- a/localization/autoware_pose_instability_detector/package.xml +++ b/localization/autoware_pose_instability_detector/package.xml @@ -2,7 +2,7 @@ autoware_pose_instability_detector - 0.40.0 + 0.41.0 The autoware_pose_instability_detector package Yamato Ando Kento Yabuuchi diff --git a/localization/autoware_stop_filter/CHANGELOG.rst b/localization/autoware_stop_filter/CHANGELOG.rst index f91a3b8de7f05..f3379ac25cd32 100644 --- a/localization/autoware_stop_filter/CHANGELOG.rst +++ b/localization/autoware_stop_filter/CHANGELOG.rst @@ -2,6 +2,17 @@ Changelog for package autoware_stop_filter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: tier4_debug_msgs to autoware_internal_debug_msgs in files localization/autoware_stop_filter (`#9867 `_) + Co-authored-by: SakodaShintaro +* fix(autoware_stop_filter): fix bugprone-reserved-identifier (`#9643 `_) + * fix: bugprone-reserved-identifier + * fix: fmt + --------- +* Contributors: Fumiya Watanabe, Vishal Chauhan, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/localization/autoware_stop_filter/package.xml b/localization/autoware_stop_filter/package.xml index 50ba98484f59d..b047b0cd81baa 100644 --- a/localization/autoware_stop_filter/package.xml +++ b/localization/autoware_stop_filter/package.xml @@ -2,7 +2,7 @@ autoware_stop_filter - 0.40.0 + 0.41.0 The stop filter package Yamato Ando Masahiro Sakamoto diff --git a/localization/autoware_twist2accel/CHANGELOG.rst b/localization/autoware_twist2accel/CHANGELOG.rst index 89b22e6ae4f26..d1e7bb13638d1 100644 --- a/localization/autoware_twist2accel/CHANGELOG.rst +++ b/localization/autoware_twist2accel/CHANGELOG.rst @@ -2,6 +2,15 @@ Changelog for package autoware_twist2accel ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* chore(autoware_twist2accel): remove an unused dependency (`#9881 `_) + Removed an unused dependency +* feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files localization/autoware_twist2accel (`#9868 `_) + Co-authored-by: SakodaShintaro +* Contributors: Fumiya Watanabe, SakodaShintaro, Vishal Chauhan + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/localization/autoware_twist2accel/package.xml b/localization/autoware_twist2accel/package.xml index 092b227c2ad40..1a19bb3132ef2 100644 --- a/localization/autoware_twist2accel/package.xml +++ b/localization/autoware_twist2accel/package.xml @@ -2,7 +2,7 @@ autoware_twist2accel - 0.40.0 + 0.41.0 The acceleration estimation package Yamato Ando Masahiro Sakamoto diff --git a/localization/yabloc/yabloc_common/CHANGELOG.rst b/localization/yabloc/yabloc_common/CHANGELOG.rst index 6812e5ca633ca..66c6039b9fd67 100644 --- a/localization/yabloc/yabloc_common/CHANGELOG.rst +++ b/localization/yabloc/yabloc_common/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package yabloc_common ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/localization/yabloc/yabloc_common/package.xml b/localization/yabloc/yabloc_common/package.xml index 5a8f19ff16bd7..58a77fe138f28 100644 --- a/localization/yabloc/yabloc_common/package.xml +++ b/localization/yabloc/yabloc_common/package.xml @@ -1,7 +1,7 @@ yabloc_common - 0.40.0 + 0.41.0 YabLoc common library Kento Yabuuchi Masahiro Sakamoto diff --git a/localization/yabloc/yabloc_image_processing/CHANGELOG.rst b/localization/yabloc/yabloc_image_processing/CHANGELOG.rst index bf4c1279fffdc..72f305b9ca340 100644 --- a/localization/yabloc/yabloc_image_processing/CHANGELOG.rst +++ b/localization/yabloc/yabloc_image_processing/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package yabloc_image_processing ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/localization/yabloc/yabloc_image_processing/package.xml b/localization/yabloc/yabloc_image_processing/package.xml index c3202e8bfaebf..2cc9f817b1ec8 100644 --- a/localization/yabloc/yabloc_image_processing/package.xml +++ b/localization/yabloc/yabloc_image_processing/package.xml @@ -2,7 +2,7 @@ yabloc_image_processing - 0.40.0 + 0.41.0 YabLoc image processing package Kento Yabuuchi Masahiro Sakamoto diff --git a/localization/yabloc/yabloc_monitor/CHANGELOG.rst b/localization/yabloc/yabloc_monitor/CHANGELOG.rst index c7cb3c7dc307d..fe9126f5e0442 100644 --- a/localization/yabloc/yabloc_monitor/CHANGELOG.rst +++ b/localization/yabloc/yabloc_monitor/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package yabloc_monitor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/localization/yabloc/yabloc_monitor/package.xml b/localization/yabloc/yabloc_monitor/package.xml index 1a0dbb6c7fdfa..b77f96c9dab81 100644 --- a/localization/yabloc/yabloc_monitor/package.xml +++ b/localization/yabloc/yabloc_monitor/package.xml @@ -2,7 +2,7 @@ yabloc_monitor - 0.40.0 + 0.41.0 YabLoc monitor package Kento Yabuuchi Masahiro Sakamoto diff --git a/localization/yabloc/yabloc_particle_filter/CHANGELOG.rst b/localization/yabloc/yabloc_particle_filter/CHANGELOG.rst index 935aecb810449..fdaecc4d86187 100644 --- a/localization/yabloc/yabloc_particle_filter/CHANGELOG.rst +++ b/localization/yabloc/yabloc_particle_filter/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package yabloc_particle_filter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/localization/yabloc/yabloc_particle_filter/package.xml b/localization/yabloc/yabloc_particle_filter/package.xml index 074ff19334852..244cf88da7b0a 100644 --- a/localization/yabloc/yabloc_particle_filter/package.xml +++ b/localization/yabloc/yabloc_particle_filter/package.xml @@ -2,7 +2,7 @@ yabloc_particle_filter - 0.40.0 + 0.41.0 YabLoc particle filter package Kento Yabuuchi Masahiro Sakamoto diff --git a/localization/yabloc/yabloc_pose_initializer/CHANGELOG.rst b/localization/yabloc/yabloc_pose_initializer/CHANGELOG.rst index 0b78a98bf07fd..88ee7b5b3c4c3 100644 --- a/localization/yabloc/yabloc_pose_initializer/CHANGELOG.rst +++ b/localization/yabloc/yabloc_pose_initializer/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package yabloc_pose_initializer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/localization/yabloc/yabloc_pose_initializer/package.xml b/localization/yabloc/yabloc_pose_initializer/package.xml index 4fd346f6327ad..c4bdfb63c150e 100644 --- a/localization/yabloc/yabloc_pose_initializer/package.xml +++ b/localization/yabloc/yabloc_pose_initializer/package.xml @@ -1,7 +1,7 @@ yabloc_pose_initializer - 0.40.0 + 0.41.0 The pose initializer Kento Yabuuchi Masahiro Sakamoto diff --git a/map/autoware_lanelet2_map_visualizer/CHANGELOG.rst b/map/autoware_lanelet2_map_visualizer/CHANGELOG.rst index 3d95ca5f804b2..fef302aececdf 100644 --- a/map/autoware_lanelet2_map_visualizer/CHANGELOG.rst +++ b/map/autoware_lanelet2_map_visualizer/CHANGELOG.rst @@ -3,6 +3,9 @@ Changelog for package autoware_lanelet2_map_visualizer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/map/autoware_lanelet2_map_visualizer/package.xml b/map/autoware_lanelet2_map_visualizer/package.xml index eef83f90ec142..717445bef13ad 100644 --- a/map/autoware_lanelet2_map_visualizer/package.xml +++ b/map/autoware_lanelet2_map_visualizer/package.xml @@ -2,7 +2,7 @@ autoware_lanelet2_map_visualizer - 0.40.0 + 0.41.0 The autoware_lanelet2_map_visualizer package Yamato Ando Ryu Yamamoto diff --git a/map/autoware_map_height_fitter/CHANGELOG.rst b/map/autoware_map_height_fitter/CHANGELOG.rst index d600473d9756f..8d29e1323cfa8 100644 --- a/map/autoware_map_height_fitter/CHANGELOG.rst +++ b/map/autoware_map_height_fitter/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_map_height_fitter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/map/autoware_map_height_fitter/package.xml b/map/autoware_map_height_fitter/package.xml index 98a48704c0c4b..50c4a4447f364 100644 --- a/map/autoware_map_height_fitter/package.xml +++ b/map/autoware_map_height_fitter/package.xml @@ -2,7 +2,7 @@ autoware_map_height_fitter - 0.40.0 + 0.41.0 The autoware_map_height_fitter package Takagi, Isamu Yamato Ando diff --git a/map/autoware_map_loader/CHANGELOG.rst b/map/autoware_map_loader/CHANGELOG.rst index a9e1080f1d6ec..f769ba0bbe7ad 100644 --- a/map/autoware_map_loader/CHANGELOG.rst +++ b/map/autoware_map_loader/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package autoware_map_loader ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_component_interface_specs_universe!): rename package (`#9753 `_) +* Contributors: Fumiya Watanabe, Ryohsuke Mitsudome + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/map/autoware_map_loader/package.xml b/map/autoware_map_loader/package.xml index 08d41466ec6ef..638014a65f04f 100644 --- a/map/autoware_map_loader/package.xml +++ b/map/autoware_map_loader/package.xml @@ -2,7 +2,7 @@ autoware_map_loader - 0.40.0 + 0.41.0 The autoware_map_loader package Yamato Ando Ryu Yamamoto diff --git a/map/autoware_map_projection_loader/CHANGELOG.rst b/map/autoware_map_projection_loader/CHANGELOG.rst index eef30e5c5f159..8ccadf6bccac0 100644 --- a/map/autoware_map_projection_loader/CHANGELOG.rst +++ b/map/autoware_map_projection_loader/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package autoware_map_projection_loader ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_component_interface_specs_universe!): rename package (`#9753 `_) +* Contributors: Fumiya Watanabe, Ryohsuke Mitsudome + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/map/autoware_map_projection_loader/package.xml b/map/autoware_map_projection_loader/package.xml index d3d739ea9ca7e..160cca26ba891 100644 --- a/map/autoware_map_projection_loader/package.xml +++ b/map/autoware_map_projection_loader/package.xml @@ -2,7 +2,7 @@ autoware_map_projection_loader - 0.40.0 + 0.41.0 autoware_map_projection_loader package as a ROS 2 node Yamato Ando Masahiro Sakamoto diff --git a/map/autoware_map_tf_generator/CHANGELOG.rst b/map/autoware_map_tf_generator/CHANGELOG.rst index 963e450bd4856..e856c3fef19ba 100644 --- a/map/autoware_map_tf_generator/CHANGELOG.rst +++ b/map/autoware_map_tf_generator/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_map_tf_generator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/map/autoware_map_tf_generator/package.xml b/map/autoware_map_tf_generator/package.xml index 0e81321daea2e..c9646f04687bf 100644 --- a/map/autoware_map_tf_generator/package.xml +++ b/map/autoware_map_tf_generator/package.xml @@ -2,7 +2,7 @@ autoware_map_tf_generator - 0.40.0 + 0.41.0 map_tf_generator package as a ROS 2 node Yamato Ando Kento Yabuuchi diff --git a/perception/autoware_bytetrack/CHANGELOG.rst b/perception/autoware_bytetrack/CHANGELOG.rst index 2db62f9a4e374..ec6f3f935b05c 100644 --- a/perception/autoware_bytetrack/CHANGELOG.rst +++ b/perception/autoware_bytetrack/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package autoware_bytetrack ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* fix(autoware_bytetrack): fix bugprone-reserved-identifier (`#9647 `_) + fix: bugprone-reserved-identifier +* Contributors: Fumiya Watanabe, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_bytetrack/package.xml b/perception/autoware_bytetrack/package.xml index 4dc982595c588..bc05293b80e0c 100644 --- a/perception/autoware_bytetrack/package.xml +++ b/perception/autoware_bytetrack/package.xml @@ -2,7 +2,7 @@ autoware_bytetrack - 0.40.0 + 0.41.0 ByteTrack implementation ported toward Autoware Manato HIRABAYASHI Yoshi RI diff --git a/perception/autoware_cluster_merger/CHANGELOG.rst b/perception/autoware_cluster_merger/CHANGELOG.rst index 1acdbf9333f30..a98cd3e5dba7f 100644 --- a/perception/autoware_cluster_merger/CHANGELOG.rst +++ b/perception/autoware_cluster_merger/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_cluster_merger ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_cluster_merger/package.xml b/perception/autoware_cluster_merger/package.xml index 92e1a8aadf40c..78959b657f724 100644 --- a/perception/autoware_cluster_merger/package.xml +++ b/perception/autoware_cluster_merger/package.xml @@ -2,7 +2,7 @@ autoware_cluster_merger - 0.40.0 + 0.41.0 The ROS 2 cluster merger package Yukihiro Saito Shunsuke Miura diff --git a/perception/autoware_compare_map_segmentation/CHANGELOG.rst b/perception/autoware_compare_map_segmentation/CHANGELOG.rst index 8d784ca304874..d6034e76e5ab5 100644 --- a/perception/autoware_compare_map_segmentation/CHANGELOG.rst +++ b/perception/autoware_compare_map_segmentation/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package autoware_compare_map_segmentation ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_compare_map_segmentation): tier4_debug_msgs changed to autoware_internal_debug_msgs in fil… (`#9869 `_) + feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files perception/autoware_compare_map_segmentation + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> +* Contributors: Fumiya Watanabe, Vishal Chauhan + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_compare_map_segmentation/package.xml b/perception/autoware_compare_map_segmentation/package.xml index 8c07d29156f8a..c633ebc808af9 100644 --- a/perception/autoware_compare_map_segmentation/package.xml +++ b/perception/autoware_compare_map_segmentation/package.xml @@ -2,7 +2,7 @@ autoware_compare_map_segmentation - 0.40.0 + 0.41.0 The ROS 2 autoware_compare_map_segmentation package amc-nu Yukihiro Saito diff --git a/perception/autoware_crosswalk_traffic_light_estimator/CHANGELOG.rst b/perception/autoware_crosswalk_traffic_light_estimator/CHANGELOG.rst index 34e514d13e007..c628c4d310161 100644 --- a/perception/autoware_crosswalk_traffic_light_estimator/CHANGELOG.rst +++ b/perception/autoware_crosswalk_traffic_light_estimator/CHANGELOG.rst @@ -2,6 +2,29 @@ Changelog for package autoware_crosswalk_traffic_light_estimator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_crosswalk_traffic_light_estimator)!: tier4_debug_msgs changes to autoware_internal_debug_msgs in autoware_crosswalk_traffic_light_estimator (`#9870 `_) +* chore(autoware_crosswalk_traffic_light_estimator): fix docs (`#9822 `_) + * fix docs + * fix docs + * add tlr output image + * modify sentense + * modify sentense + * refactor readme + * fix docs + * fix + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(autoware_crosswalk_traffic_light_estimator): overwrite invalid detection result (`#9667 `_) + * add code in order to check invalid detection + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Fumiya Watanabe, Masato Saeki, Vishal Chauhan + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_crosswalk_traffic_light_estimator/package.xml b/perception/autoware_crosswalk_traffic_light_estimator/package.xml index c96ad1e2135c1..e0cd5d9b917ca 100644 --- a/perception/autoware_crosswalk_traffic_light_estimator/package.xml +++ b/perception/autoware_crosswalk_traffic_light_estimator/package.xml @@ -1,7 +1,7 @@ autoware_crosswalk_traffic_light_estimator - 0.40.0 + 0.41.0 The autoware_crosswalk_traffic_light_estimator package Satoshi Ota diff --git a/perception/autoware_detected_object_feature_remover/CHANGELOG.rst b/perception/autoware_detected_object_feature_remover/CHANGELOG.rst index f0d4f1f746eaa..79965097ad8e3 100644 --- a/perception/autoware_detected_object_feature_remover/CHANGELOG.rst +++ b/perception/autoware_detected_object_feature_remover/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_detected_object_feature_remover ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_detected_object_feature_remover/package.xml b/perception/autoware_detected_object_feature_remover/package.xml index a112598728614..a2b7e89adc1f2 100644 --- a/perception/autoware_detected_object_feature_remover/package.xml +++ b/perception/autoware_detected_object_feature_remover/package.xml @@ -2,7 +2,7 @@ autoware_detected_object_feature_remover - 0.40.0 + 0.41.0 The autoware_detected_object_feature_remover package Tomoya Kimura Yoshi Ri diff --git a/perception/autoware_detected_object_validation/CHANGELOG.rst b/perception/autoware_detected_object_validation/CHANGELOG.rst index bde610a8e3fd5..0486c6cbe2a41 100644 --- a/perception/autoware_detected_object_validation/CHANGELOG.rst +++ b/perception/autoware_detected_object_validation/CHANGELOG.rst @@ -2,6 +2,28 @@ Changelog for package autoware_detected_object_validation ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_detected_object_validation): add height filter in lanelet filtering (`#10003 `_) + * feat: add height filter param + * feat: use ego base height + * fix: build error + * feat: add lanelet filter test + * feat: add height filter test + * docs: update README and lanelet filter + * fix: do not getTransform when flag is off + --------- +* feat(autoware_detected_object_validation): tier4_debug_msgs changed to autoware_internal_debug_msgs in fil… (`#9871 `_) + feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files perception/autoware_detected_object_validation + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> +* feat(autoware_detected_object_validation): set validate distance in the obstacle pointcloud based validator (`#9663 `_) + * chore: add validate_max_distance_m parameter for obstacle_pointcloud_based_validator + * chore: optimize object distance validation in obstacle_pointcloud_validator + * chore: add validate_max_distance_m parameter for obstacle_pointcloud_based_validator + --------- +* Contributors: Fumiya Watanabe, Taekjin LEE, Vishal Chauhan, Yoshi Ri + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_detected_object_validation/package.xml b/perception/autoware_detected_object_validation/package.xml index 9aa6f018de5fa..01c48bbebc756 100644 --- a/perception/autoware_detected_object_validation/package.xml +++ b/perception/autoware_detected_object_validation/package.xml @@ -2,7 +2,7 @@ autoware_detected_object_validation - 0.40.0 + 0.41.0 The ROS 2 detected_object_validation package Yukihiro Saito Shunsuke Miura diff --git a/perception/autoware_detection_by_tracker/CHANGELOG.rst b/perception/autoware_detection_by_tracker/CHANGELOG.rst index dd8a44828a5ff..78e72f5a9cdff 100644 --- a/perception/autoware_detection_by_tracker/CHANGELOG.rst +++ b/perception/autoware_detection_by_tracker/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package autoware_detection_by_tracker ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in fil… (`#9880 `_) + feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files perception/autoware_detection_by_tracker + Co-authored-by: Taekjin LEE +* Contributors: Fumiya Watanabe, Vishal Chauhan + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/perception/autoware_detection_by_tracker/package.xml b/perception/autoware_detection_by_tracker/package.xml index b9ee4fa2aac71..fccd8f32bbebc 100644 --- a/perception/autoware_detection_by_tracker/package.xml +++ b/perception/autoware_detection_by_tracker/package.xml @@ -2,7 +2,7 @@ autoware_detection_by_tracker - 0.40.0 + 0.41.0 The ROS 2 autoware_detection_by_tracker package Yukihiro Saito Yoshi Ri diff --git a/perception/autoware_elevation_map_loader/CHANGELOG.rst b/perception/autoware_elevation_map_loader/CHANGELOG.rst index b53c69f07a8a9..c967ebe6326cd 100644 --- a/perception/autoware_elevation_map_loader/CHANGELOG.rst +++ b/perception/autoware_elevation_map_loader/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_elevation_map_loader ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_elevation_map_loader/package.xml b/perception/autoware_elevation_map_loader/package.xml index 6839cd60e2990..a24bf2e0b8062 100644 --- a/perception/autoware_elevation_map_loader/package.xml +++ b/perception/autoware_elevation_map_loader/package.xml @@ -2,7 +2,7 @@ autoware_elevation_map_loader - 0.40.0 + 0.41.0 The autoware_elevation_map_loader package Kosuke Takeuchi Taichi Higashide diff --git a/perception/autoware_euclidean_cluster/CHANGELOG.rst b/perception/autoware_euclidean_cluster/CHANGELOG.rst index b7ce92ddd6510..ef7b29edf7f0a 100644 --- a/perception/autoware_euclidean_cluster/CHANGELOG.rst +++ b/perception/autoware_euclidean_cluster/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package autoware_euclidean_cluster ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_euclidean_cluster)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_euclidean_cluster (`#9873 `_) + feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files perception/autoware_euclidean_cluster + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> +* Contributors: Fumiya Watanabe, Vishal Chauhan + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_euclidean_cluster/package.xml b/perception/autoware_euclidean_cluster/package.xml index f4568baaea19b..8bac386a5bbb6 100644 --- a/perception/autoware_euclidean_cluster/package.xml +++ b/perception/autoware_euclidean_cluster/package.xml @@ -2,7 +2,7 @@ autoware_euclidean_cluster - 0.40.0 + 0.41.0 The autoware_euclidean_cluster package Yukihiro Saito Dai Nguyen diff --git a/perception/autoware_ground_segmentation/CHANGELOG.rst b/perception/autoware_ground_segmentation/CHANGELOG.rst index b23cfa4972f1f..36a8adae770fe 100644 --- a/perception/autoware_ground_segmentation/CHANGELOG.rst +++ b/perception/autoware_ground_segmentation/CHANGELOG.rst @@ -2,6 +2,15 @@ Changelog for package autoware_ground_segmentation ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_ground_segmentation): tier4_debug_msgs changed to autoware_internal_debug_msgs in fil… (`#9878 `_) + feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files perception/autoware_ground_segmentation +* fix(autoware_ground_segmentation): fix bugprone-branch-clone (`#9648 `_) + fix: bugprone-branch-clone +* Contributors: Fumiya Watanabe, Vishal Chauhan, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_ground_segmentation/package.xml b/perception/autoware_ground_segmentation/package.xml index 1cb179970e1ae..b1ef241dd52cf 100644 --- a/perception/autoware_ground_segmentation/package.xml +++ b/perception/autoware_ground_segmentation/package.xml @@ -2,7 +2,7 @@ autoware_ground_segmentation - 0.40.0 + 0.41.0 The ROS 2 autoware_ground_segmentation package amc-nu Yukihiro Saito diff --git a/perception/autoware_image_projection_based_fusion/CHANGELOG.rst b/perception/autoware_image_projection_based_fusion/CHANGELOG.rst index f0a39ef78c708..2f146bdf94bf0 100644 --- a/perception/autoware_image_projection_based_fusion/CHANGELOG.rst +++ b/perception/autoware_image_projection_based_fusion/CHANGELOG.rst @@ -2,6 +2,133 @@ Changelog for package autoware_image_projection_based_fusion ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_image_projection_based_fusion)!: tier4_debug-msgs changed to autoware_internal_debug_msgs in autoware_image_projection_based_fusion (`#9877 `_) +* fix(image_projection_based_fusion): revise message publishers (`#9865 `_) + * refactor: fix condition for publishing painted pointcloud message + * fix: publish output revised + * feat: fix condition for publishing painted pointcloud message + * feat: roi-pointclout fusion - publish empty image even when there is no target roi + * fix: remap output topic for clusters in roi_pointcloud_fusion + * style(pre-commit): autofix + * feat: fix condition for publishing painted pointcloud message + * feat: Add debug publisher for internal debugging + * feat: remove !! pointer to bool conversion + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* refactor(autoware_tensorrt_common): multi-TensorRT compatibility & tensorrt_common as unified lib for all perception components (`#9762 `_) + * refactor(autoware_tensorrt_common): multi-TensorRT compatibility & tensorrt_common as unified lib for all perception components + * style(pre-commit): autofix + * style(autoware_tensorrt_common): linting + * style(autoware_lidar_centerpoint): typo + Co-authored-by: Kenzo Lobos Tsunekawa + * docs(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * fix(autoware_lidar_transfusion): reuse cast variable + * fix(autoware_tensorrt_common): remove deprecated inference API + * style(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * style(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * fix(autoware_tensorrt_common): const pointer + * fix(autoware_tensorrt_common): remove unused method declaration + * style(pre-commit): autofix + * refactor(autoware_tensorrt_common): readability + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> + * fix(autoware_tensorrt_common): return if layer not registered + * refactor(autoware_tensorrt_common): readability + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> + * fix(autoware_tensorrt_common): rename struct + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Kenzo Lobos Tsunekawa + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> +* fix(image_projection_based_fusion): remove mutex (`#9862 `_) + refactor: Refactor fusion_node.hpp and fusion_node.cpp for improved code organization and readability +* refactor(autoware_image_projection_based_fusion): organize 2d-detection related members (`#9789 `_) + * chore: input_camera_topics\_ is only for debug + * feat: fuse main message with cached roi messages in fusion_node.cpp + * chore: add comments on each process step, organize methods + * feat: Export process method in fusion_node.cpp + Export the `exportProcess()` method in `fusion_node.cpp` to handle the post-processing and publishing of the fused messages. This method cancels the timer, performs the necessary post-processing steps, publishes the output message, and resets the flags. It also adds processing time for debugging purposes. This change improves the organization and readability of the code. + * feat: Refactor fusion_node.hpp and fusion_node.cpp + Refactor the `fusion_node.hpp` and `fusion_node.cpp` files to improve code organization and readability. This includes exporting the `exportProcess()` method in `fusion_node.cpp` to handle post-processing and publishing of fused messages, adding comments on each process step, organizing methods, and fusing the main message with cached ROI messages. These changes enhance the overall quality of the codebase. + * Refactor fusion_node.cpp and fusion_node.hpp for improved code organization and readability + * Refactor fusion_node.hpp and fusion_node.cpp for improved code organization and readability + * feat: Refactor fusion_node.cpp for improved code organization and readability + * Refactor fusion_node.cpp for improved code organization and readability + * feat: implement mutex per 2d detection process + * Refactor fusion_node.hpp and fusion_node.cpp for improved code organization and readability + * Refactor fusion_node.hpp and fusion_node.cpp for improved code organization and readability + * revise template, inputs first and output at the last + * explicit in and out types 1 + * clarify pointcloud message type + * Refactor fusion_node.hpp and fusion_node.cpp for improved code organization and readability + * Refactor fusion_node.hpp and fusion_node.cpp for improved code organization and readability + * Refactor fusion_node.hpp and fusion_node.cpp for improved code organization and readability + * Refactor publisher types in fusion_node.hpp and node.hpp + * fix: resolve cppcheck issue shadowVariable + * Refactor fusion_node.hpp and fusion_node.cpp for improved code organization and readability + * chore: rename Det2dManager to Det2dStatus + * revert mutex related changes + * refactor: review member and method's access + * fix: resolve shadowVariable of 'det2d' + * fix missing line + * refactor message postprocess and publish methods + * publish the main message is common + * fix: replace pointcloud message type by the typename + * review member access + * Refactor fusion_node.hpp and fusion_node.cpp for improved code organization and readability + * refactor: fix condition for publishing painted pointcloud message + * fix: remove unused variable + --------- +* feat(lidar_centerpoint, pointpainting): add diag publisher for max voxel size (`#9720 `_) +* feat(pointpainting_fusion): enable cloud display on image (`#9813 `_) +* feat(image_projection_based_fusion): add cache for camera projection (`#9635 `_) + * add camera_projection class and projection cache + * style(pre-commit): autofix + * fix FOV filtering + * style(pre-commit): autofix + * remove unused includes + * update schema + * fix cpplint error + * apply suggestion: more simple and effcient computation + * correct terminology + * style(pre-commit): autofix + * fix comments + * fix var name + Co-authored-by: Taekjin LEE + * fix variable names + Co-authored-by: Taekjin LEE + * fix variable names + Co-authored-by: Taekjin LEE + * fix variable names + Co-authored-by: Taekjin LEE + * fix variable names + Co-authored-by: Taekjin LEE + * fix variable names + * fix initialization + Co-authored-by: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> + * add verification to point_project_to_unrectified_image when loading + Co-authored-by: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> + * chore: add option description to project points to unrectified image + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Taekjin LEE + Co-authored-by: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> + Co-authored-by: Taekjin LEE +* feat(image_projection_based_fusion): add timekeeper (`#9632 `_) + * add timekeeper + * chore: refactor time-keeper position + * chore: bring back a missing comment + * chore: remove redundant timekeepers + --------- + Co-authored-by: Taekjin LEE +* Contributors: Amadeusz Szymko, Fumiya Watanabe, Masaki Baba, Taekjin LEE, Vishal Chauhan, Yi-Hsiang Fang (Vivid), kminoda + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_image_projection_based_fusion/package.xml b/perception/autoware_image_projection_based_fusion/package.xml index fa6217f589627..a15642728e1d9 100644 --- a/perception/autoware_image_projection_based_fusion/package.xml +++ b/perception/autoware_image_projection_based_fusion/package.xml @@ -2,7 +2,7 @@ autoware_image_projection_based_fusion - 0.40.0 + 0.41.0 The autoware_image_projection_based_fusion package Yukihiro Saito Shunsuke Miura diff --git a/perception/autoware_lidar_apollo_instance_segmentation/CHANGELOG.rst b/perception/autoware_lidar_apollo_instance_segmentation/CHANGELOG.rst index 5841ae3059503..dd8864ef5a0ef 100644 --- a/perception/autoware_lidar_apollo_instance_segmentation/CHANGELOG.rst +++ b/perception/autoware_lidar_apollo_instance_segmentation/CHANGELOG.rst @@ -2,6 +2,42 @@ Changelog for package autoware_lidar_apollo_instance_segmentation ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_lidar_apollo_instance_segmentation): tier4_debug_msgs to autoware_internal_debug_msgs in files perce… (`#9876 `_) + feat: tier4_debug_msgs to autoware_internal_debug_msgs in files perception/autoware_lidar_apollo_instance_segmentation + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> +* refactor(autoware_tensorrt_common): multi-TensorRT compatibility & tensorrt_common as unified lib for all perception components (`#9762 `_) + * refactor(autoware_tensorrt_common): multi-TensorRT compatibility & tensorrt_common as unified lib for all perception components + * style(pre-commit): autofix + * style(autoware_tensorrt_common): linting + * style(autoware_lidar_centerpoint): typo + Co-authored-by: Kenzo Lobos Tsunekawa + * docs(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * fix(autoware_lidar_transfusion): reuse cast variable + * fix(autoware_tensorrt_common): remove deprecated inference API + * style(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * style(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * fix(autoware_tensorrt_common): const pointer + * fix(autoware_tensorrt_common): remove unused method declaration + * style(pre-commit): autofix + * refactor(autoware_tensorrt_common): readability + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> + * fix(autoware_tensorrt_common): return if layer not registered + * refactor(autoware_tensorrt_common): readability + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> + * fix(autoware_tensorrt_common): rename struct + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Kenzo Lobos Tsunekawa + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> +* Contributors: Amadeusz Szymko, Fumiya Watanabe, Vishal Chauhan + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_lidar_apollo_instance_segmentation/package.xml b/perception/autoware_lidar_apollo_instance_segmentation/package.xml index 8ff7ce77d943d..7e09587aef8a1 100755 --- a/perception/autoware_lidar_apollo_instance_segmentation/package.xml +++ b/perception/autoware_lidar_apollo_instance_segmentation/package.xml @@ -2,7 +2,7 @@ autoware_lidar_apollo_instance_segmentation - 0.40.0 + 0.41.0 autoware_lidar_apollo_instance_segmentation Yoshi Ri Yukihiro Saito diff --git a/perception/autoware_lidar_centerpoint/CHANGELOG.rst b/perception/autoware_lidar_centerpoint/CHANGELOG.rst index 46f68e7462377..3978a514305a8 100644 --- a/perception/autoware_lidar_centerpoint/CHANGELOG.rst +++ b/perception/autoware_lidar_centerpoint/CHANGELOG.rst @@ -2,6 +2,47 @@ Changelog for package autoware_lidar_centerpoint ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* refactor(autoware_tensorrt_common): multi-TensorRT compatibility & tensorrt_common as unified lib for all perception components (`#9762 `_) + * refactor(autoware_tensorrt_common): multi-TensorRT compatibility & tensorrt_common as unified lib for all perception components + * style(pre-commit): autofix + * style(autoware_tensorrt_common): linting + * style(autoware_lidar_centerpoint): typo + Co-authored-by: Kenzo Lobos Tsunekawa + * docs(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * fix(autoware_lidar_transfusion): reuse cast variable + * fix(autoware_tensorrt_common): remove deprecated inference API + * style(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * style(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * fix(autoware_tensorrt_common): const pointer + * fix(autoware_tensorrt_common): remove unused method declaration + * style(pre-commit): autofix + * refactor(autoware_tensorrt_common): readability + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> + * fix(autoware_tensorrt_common): return if layer not registered + * refactor(autoware_tensorrt_common): readability + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> + * fix(autoware_tensorrt_common): rename struct + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Kenzo Lobos Tsunekawa + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> +* feat(lidar_centerpoint, pointpainting): add diag publisher for max voxel size (`#9720 `_) +* fix(autoware_lidar_centerpoint): fixed rounding errors that caused illegal memory access (`#9795 `_) + fix: fixed rounding errors that caused illegal memory address +* feat(autoware_lidar_centerpoint): process front voxels first (`#9608 `_) + * feat: optimize voxel indexing in preprocess_kernel.cu + * fix: remove redundant index check + * fix: modify voxel index for better memory access + --------- +* Contributors: Amadeusz Szymko, Fumiya Watanabe, Kenzo Lobos Tsunekawa, Taekjin LEE, kminoda + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_lidar_centerpoint/package.xml b/perception/autoware_lidar_centerpoint/package.xml index 78e900f8198f6..a4eb5c6758f61 100644 --- a/perception/autoware_lidar_centerpoint/package.xml +++ b/perception/autoware_lidar_centerpoint/package.xml @@ -2,7 +2,7 @@ autoware_lidar_centerpoint - 0.40.0 + 0.41.0 The autoware_lidar_centerpoint package Kenzo Lobos-Tsunekawa Koji Minoda diff --git a/perception/autoware_lidar_transfusion/CHANGELOG.rst b/perception/autoware_lidar_transfusion/CHANGELOG.rst index f397c9e1ddc06..f1f2809947e39 100644 --- a/perception/autoware_lidar_transfusion/CHANGELOG.rst +++ b/perception/autoware_lidar_transfusion/CHANGELOG.rst @@ -2,6 +2,42 @@ Changelog for package autoware_lidar_transfusion ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* refactor(autoware_tensorrt_common): multi-TensorRT compatibility & tensorrt_common as unified lib for all perception components (`#9762 `_) + * refactor(autoware_tensorrt_common): multi-TensorRT compatibility & tensorrt_common as unified lib for all perception components + * style(pre-commit): autofix + * style(autoware_tensorrt_common): linting + * style(autoware_lidar_centerpoint): typo + Co-authored-by: Kenzo Lobos Tsunekawa + * docs(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * fix(autoware_lidar_transfusion): reuse cast variable + * fix(autoware_tensorrt_common): remove deprecated inference API + * style(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * style(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * fix(autoware_tensorrt_common): const pointer + * fix(autoware_tensorrt_common): remove unused method declaration + * style(pre-commit): autofix + * refactor(autoware_tensorrt_common): readability + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> + * fix(autoware_tensorrt_common): return if layer not registered + * refactor(autoware_tensorrt_common): readability + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> + * fix(autoware_tensorrt_common): rename struct + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Kenzo Lobos Tsunekawa + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> +* fix(autoware_lidar_transfusion): fixed rounding errors that caused illegal memory access (`#9796 `_) + fix: fixed rounding errors that caused illegal memory address + Co-authored-by: Amadeusz Szymko +* Contributors: Amadeusz Szymko, Fumiya Watanabe, Kenzo Lobos Tsunekawa + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_lidar_transfusion/package.xml b/perception/autoware_lidar_transfusion/package.xml index d9c43bc5a1b20..f9fd376e8be9a 100644 --- a/perception/autoware_lidar_transfusion/package.xml +++ b/perception/autoware_lidar_transfusion/package.xml @@ -2,7 +2,7 @@ autoware_lidar_transfusion - 0.40.0 + 0.41.0 The lidar_transfusion package Amadeusz Szymko Kenzo Lobos-Tsunekawa diff --git a/perception/autoware_map_based_prediction/CHANGELOG.rst b/perception/autoware_map_based_prediction/CHANGELOG.rst index 55bc24894c230..0a67ffc40d586 100644 --- a/perception/autoware_map_based_prediction/CHANGELOG.rst +++ b/perception/autoware_map_based_prediction/CHANGELOG.rst @@ -2,6 +2,15 @@ Changelog for package autoware_map_based_prediction ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* fix(map_based_prediction): fix unintentional accumulation of lanelets (`#9950 `_) + add clear before insert +* feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in fil… (`#9875 `_) + feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files perception/autoware_map_based_prediction +* Contributors: Fumiya Watanabe, Masaki Baba, Vishal Chauhan + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_map_based_prediction/package.xml b/perception/autoware_map_based_prediction/package.xml index 58dfcb17c7631..fa6a1195b1ed2 100644 --- a/perception/autoware_map_based_prediction/package.xml +++ b/perception/autoware_map_based_prediction/package.xml @@ -2,7 +2,7 @@ autoware_map_based_prediction - 0.40.0 + 0.41.0 This package implements a map_based_prediction Tomoya Kimura Yoshi Ri diff --git a/perception/autoware_multi_object_tracker/CHANGELOG.rst b/perception/autoware_multi_object_tracker/CHANGELOG.rst index 5fced913f2b9d..b9d8d5f982397 100644 --- a/perception/autoware_multi_object_tracker/CHANGELOG.rst +++ b/perception/autoware_multi_object_tracker/CHANGELOG.rst @@ -2,6 +2,87 @@ Changelog for package autoware_multi_object_tracker ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(multi_object_tracker): integrate odometry and transform processes (`#9912 `_) + * feat: Add odometry processor to multi-object tracker + * refactor: Refactor Odometry class for improved code organization and readability + * feat: Refactor Odometry class for improved code organization and readability + * refactor: Transform objects to world coordinate in Odometry class + refactor: Transform objects to world coordinate in Odometry class + refactor: Update Odometry class to get transform from tf with source frame ID + feat: Update Odometry class to get transform from tf with source frame ID + fix: move necessare tr2 header + * Revert "refactor: Transform objects to world coordinate in Odometry class" + This reverts commit efca28a40105f80deb09d57b55cb6f9d83ffda2c. + * refactor: Remove unnecessary tf2 headers from tracker models + * fix: move transform obtainer to odometry class + * refactor: Update Odometry class to get transform from tf with source frame ID + * refactor: Transform objects to world coordinate in Odometry class + * refactor: remove transformObjects from shapes + * refactor: Update Odometry class to use 'updateFromTf' instead of 'setOdometryFromTf' + * refactor: Update Odometry class to use 'updateFromTf' instead of 'setOdometryFromTf' + * refactor: Update InputManager to include Odometry in constructor + * refactor: Move odometry.cpp to lib folder + * move object transform to input stream + * refactor: Add enable_odometry_uncertainty parameter to Odometry constructor + * refactor: Update Odometry class to return optional Odometry from getOdometryFromTf + * refactor: Update Odometry class to use tf_cache\_ for storing and retrieving transforms + * refactor: Update Odometry class to use tf_cache\_ for storing and retrieving transforms + * refactor: bring odometry covariance modeler into odometry class + * refactor: Remove redundant code for updating tf cache in Odometry::updateTfCache + * refactor: Update runProcess parameter name to detected_objects + --------- +* feat: tier4_debug_msgs to autoware_internal_debug_msgs in files perc… (`#9879 `_) + feat: tier4_debug_msgs to autoware_internal_debug_msgs in files perception/autoware_multi_object_tracker +* chore(autoware_multi_object_tracker): fix autoware univserse documentation page (`#9772 `_) + * feat: Add descriptions for confidence thresholds in multi_object_tracker_node schema + * feat: Update multi_object_tracker_node schema with confidence threshold descriptions + --------- +* refactor(autoware_multi_object_tracker): define a new internal object class (`#9706 `_) + * feat: Add dynamic_object.hpp to object_model directory + * chore: Update autoware_perception_msgs include statements in association.hpp and dynamic_object.hpp + * fix: replace object message type to the DynamicObject type + * chore: Update autoware_perception_msgs include statements in association.hpp and dynamic_object.hpp + * chore: add channel index to the DynamicObjects + * Revert "chore: add channel index to the DynamicObjects" + This reverts commit c7e73f08a8d17b5b085dd330dbf187aabbec6879. + * fix: replace trackedobject in the process + * fix: Replace transformObjects with shapes::transformObjects for object transformation + * chore: add channel index to the DynamicObjects + * feat: separate shape related functions + * chore: clean up utils.hpp + * chore: Update function signatures to use DynamicObjectList instead of DynamicObjects + * chore: Add channel index to DynamicObject and DynamicObjectList + * chore: Refactor processor and debugger classes to remove channel_index parameter + * chore: Refactor multiple_vehicle_tracker.cpp and debugger.cpp + * Refactor object tracker classes to remove self_transform parameter + * Refactor object tracker classes to use shapes namespace for shape-related functions + * Refactor object tracker classes to use types.hpp for object model types + * Refactor object tracker classes to remove unused utils.hpp + * Refactor object tracker classes to use types.hpp for object model types + * chore: rename to types.cpp + * rename getDynamicObject to toDynamicObject + * Update perception/autoware_multi_object_tracker/lib/object_model/shapes.cpp + Co-authored-by: Yukihiro Saito + --------- + Co-authored-by: Yukihiro Saito +* fix(autoware_multi_object_tracker): fix bugprone-errors (`#9651 `_) + fix: bugprone-errors +* refactor(autoware_multi_object_tracker): add configurable tracker parameters (`#9621 `_) + * refactor(autoware_multi_object_tracker): add configurable tracker parameters + * style(pre-commit): autofix + * refactor(autoware_multi_object_tracker): remove default values from parameter declarations + * refactor(autoware_multi_object_tracker): update schema file + * style(pre-commit): autofix + * Update perception/autoware_multi_object_tracker/src/processor/processor.cpp + * Update perception/autoware_multi_object_tracker/src/processor/processor.cpp + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Taekjin LEE +* Contributors: Fumiya Watanabe, Taekjin LEE, Vishal Chauhan, jakor97, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_multi_object_tracker/package.xml b/perception/autoware_multi_object_tracker/package.xml index 912165d7b6ab6..08f9ac89e1d91 100644 --- a/perception/autoware_multi_object_tracker/package.xml +++ b/perception/autoware_multi_object_tracker/package.xml @@ -2,7 +2,7 @@ autoware_multi_object_tracker - 0.40.0 + 0.41.0 The ROS 2 autoware_multi_object_tracker package Yukihiro Saito Yoshi Ri diff --git a/perception/autoware_object_merger/CHANGELOG.rst b/perception/autoware_object_merger/CHANGELOG.rst index 004d56c406ce9..864cc6779fdf5 100644 --- a/perception/autoware_object_merger/CHANGELOG.rst +++ b/perception/autoware_object_merger/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_object_merger ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_object_merger): tier4_debug_msgs changed to autoware_internal_debug_msgs in fil… (`#9893 `_) + feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files perception/autoware_object_merger + Co-authored-by: Taekjin LEE +* fix(perception): fix perception docs (`#9766 `_) + * fix: fix perception docs + * fix: fix missing parameter in schema + * Update perception/autoware_object_merger/schema/data_association_matrix.schema.json + Co-authored-by: Taekjin LEE + * Update perception/autoware_object_merger/schema/data_association_matrix.schema.json + Co-authored-by: Taekjin LEE + * Update perception/autoware_object_merger/schema/data_association_matrix.schema.json + Co-authored-by: Taekjin LEE + * Update perception/autoware_object_merger/schema/data_association_matrix.schema.json + Co-authored-by: Taekjin LEE + * style(pre-commit): autofix + * chore: seperate paramters for different nodes + --------- + Co-authored-by: Taekjin LEE + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(autoware_object_merger, autoware_tracking_object_merger): enable anonymized node names to be configurable (`#9733 `_) + feat: enable anonymized node names to be configurable +* Contributors: Fumiya Watanabe, Taekjin LEE, Vishal Chauhan, Yi-Hsiang Fang (Vivid) + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_object_merger/package.xml b/perception/autoware_object_merger/package.xml index 481bb0babf20d..be9dec7a83c80 100644 --- a/perception/autoware_object_merger/package.xml +++ b/perception/autoware_object_merger/package.xml @@ -2,7 +2,7 @@ autoware_object_merger - 0.40.0 + 0.41.0 The autoware_object_merger package Yukihiro Saito Yoshi Ri diff --git a/perception/autoware_object_range_splitter/CHANGELOG.rst b/perception/autoware_object_range_splitter/CHANGELOG.rst index 2ad998b66391f..b7969830ce765 100644 --- a/perception/autoware_object_range_splitter/CHANGELOG.rst +++ b/perception/autoware_object_range_splitter/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_object_range_splitter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/perception/autoware_object_range_splitter/package.xml b/perception/autoware_object_range_splitter/package.xml index bfc8470834443..8c1d17faf629a 100644 --- a/perception/autoware_object_range_splitter/package.xml +++ b/perception/autoware_object_range_splitter/package.xml @@ -2,7 +2,7 @@ autoware_object_range_splitter - 0.40.0 + 0.41.0 The autoware_object_range_splitter package Yukihiro Saito Yoshi Ri diff --git a/perception/autoware_object_velocity_splitter/CHANGELOG.rst b/perception/autoware_object_velocity_splitter/CHANGELOG.rst index ec69fb1754d3b..2c7b06c4e5bb1 100644 --- a/perception/autoware_object_velocity_splitter/CHANGELOG.rst +++ b/perception/autoware_object_velocity_splitter/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_object_velocity_splitter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/perception/autoware_object_velocity_splitter/package.xml b/perception/autoware_object_velocity_splitter/package.xml index 681b29b0c49e8..45a3c635150f4 100644 --- a/perception/autoware_object_velocity_splitter/package.xml +++ b/perception/autoware_object_velocity_splitter/package.xml @@ -2,7 +2,7 @@ autoware_object_velocity_splitter - 0.40.0 + 0.41.0 autoware_object_velocity_splitter Sathshi Tanaka Shunsuke Miura diff --git a/perception/autoware_occupancy_grid_map_outlier_filter/CHANGELOG.rst b/perception/autoware_occupancy_grid_map_outlier_filter/CHANGELOG.rst index cf7dc5752c62d..db5cf2bb9a118 100644 --- a/perception/autoware_occupancy_grid_map_outlier_filter/CHANGELOG.rst +++ b/perception/autoware_occupancy_grid_map_outlier_filter/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package autoware_occupancy_grid_map_outlier_filter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_occupancy_grid_map_outlier_filter): tier4_debug_msgs changed to autoware_internal_debug_msgs in fil… (`#9894 `_) + feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files perception/autoware_occupancy_grid_map_outlier_filter + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> +* fix(perception): fix perception docs (`#9766 `_) + * fix: fix perception docs + * fix: fix missing parameter in schema + * Update perception/autoware_object_merger/schema/data_association_matrix.schema.json + Co-authored-by: Taekjin LEE + * Update perception/autoware_object_merger/schema/data_association_matrix.schema.json + Co-authored-by: Taekjin LEE + * Update perception/autoware_object_merger/schema/data_association_matrix.schema.json + Co-authored-by: Taekjin LEE + * Update perception/autoware_object_merger/schema/data_association_matrix.schema.json + Co-authored-by: Taekjin LEE + * style(pre-commit): autofix + * chore: seperate paramters for different nodes + --------- + Co-authored-by: Taekjin LEE + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Fumiya Watanabe, Vishal Chauhan, Yi-Hsiang Fang (Vivid) + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_occupancy_grid_map_outlier_filter/package.xml b/perception/autoware_occupancy_grid_map_outlier_filter/package.xml index fba074fdc669f..113213b65e6d0 100644 --- a/perception/autoware_occupancy_grid_map_outlier_filter/package.xml +++ b/perception/autoware_occupancy_grid_map_outlier_filter/package.xml @@ -2,7 +2,7 @@ autoware_occupancy_grid_map_outlier_filter - 0.40.0 + 0.41.0 The ROS 2 occupancy_grid_map_outlier_filter package amc-nu Yukihiro Saito diff --git a/perception/autoware_probabilistic_occupancy_grid_map/CHANGELOG.rst b/perception/autoware_probabilistic_occupancy_grid_map/CHANGELOG.rst index 75d579b612168..b161d11d6524b 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/CHANGELOG.rst +++ b/perception/autoware_probabilistic_occupancy_grid_map/CHANGELOG.rst @@ -2,6 +2,57 @@ Changelog for package autoware_probabilistic_occupancy_grid_map ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_probabilistic_occupancy_grid_map): cuda accelerated implementation (`#9542 `_) + * feat: implemented a cuda accelerated ogm + * chore: fixed cspells + * chore: unused header and variable names + * chore: cspell fixes + * chore: cppcheck fix attempt + * fix: attempting to fix ci/cd regarding the cuda library + * chore: fixed the order of the cuda check in the cmakelist + * fix: removed cuda as a required dep for cpu only builds + * fix: missing cuda linking (?) + * feat: fixed single mode, added streams, and added the restrict keyword + * chore: replaced a potential indetermination using an epsilon + * Update perception/autoware_probabilistic_occupancy_grid_map/lib/updater/log_odds_bayes_filter_updater_kernel.cu + Co-authored-by: Yoshi Ri + * Update perception/autoware_probabilistic_occupancy_grid_map/lib/updater/log_odds_bayes_filter_updater_kernel.cu + Co-authored-by: Yoshi Ri + * style(pre-commit): autofix + * chore: added bound checkings in the update origin kernel + * chore: disabled tests since universe does not support cuda in ci/cd + * chore: added me as a maintainer + * fix: missedn the end in the cmake + * chore: moved the boudnary checks to only the cuda version since the cpu version uses the upstream logic + --------- + Co-authored-by: Yoshi Ri + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(autoware_probabilistic_occupancy_grid_map): tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_probabilistic_occupancy_grid_map (`#9895 `_) + feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files perception/autoware_probabilistic_occupancy_grid_map + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> +* fix(perception): fix perception docs (`#9766 `_) + * fix: fix perception docs + * fix: fix missing parameter in schema + * Update perception/autoware_object_merger/schema/data_association_matrix.schema.json + Co-authored-by: Taekjin LEE + * Update perception/autoware_object_merger/schema/data_association_matrix.schema.json + Co-authored-by: Taekjin LEE + * Update perception/autoware_object_merger/schema/data_association_matrix.schema.json + Co-authored-by: Taekjin LEE + * Update perception/autoware_object_merger/schema/data_association_matrix.schema.json + Co-authored-by: Taekjin LEE + * style(pre-commit): autofix + * chore: seperate paramters for different nodes + --------- + Co-authored-by: Taekjin LEE + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* fix(autoware_probabilistic_occupancy_grid_map): fix bugprone-branch-clone (`#9652 `_) + fix: bugprone-error +* Contributors: Fumiya Watanabe, Kenzo Lobos Tsunekawa, Vishal Chauhan, Yi-Hsiang Fang (Vivid), kobayu858 + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/perception/autoware_probabilistic_occupancy_grid_map/package.xml b/perception/autoware_probabilistic_occupancy_grid_map/package.xml index 06c3ed75f2758..b0e6463519fd9 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/package.xml +++ b/perception/autoware_probabilistic_occupancy_grid_map/package.xml @@ -2,7 +2,7 @@ autoware_probabilistic_occupancy_grid_map - 0.40.0 + 0.41.0 generate probabilistic occupancy grid map Yukihiro Saito Yoshi Ri diff --git a/perception/autoware_radar_crossing_objects_noise_filter/CHANGELOG.rst b/perception/autoware_radar_crossing_objects_noise_filter/CHANGELOG.rst index ff859a4d44ce3..fded0cf83bf65 100644 --- a/perception/autoware_radar_crossing_objects_noise_filter/CHANGELOG.rst +++ b/perception/autoware_radar_crossing_objects_noise_filter/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_radar_crossing_objects_noise_filter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_radar_crossing_objects_noise_filter/package.xml b/perception/autoware_radar_crossing_objects_noise_filter/package.xml index f5900066cb10b..04aa0db6938c3 100644 --- a/perception/autoware_radar_crossing_objects_noise_filter/package.xml +++ b/perception/autoware_radar_crossing_objects_noise_filter/package.xml @@ -2,7 +2,7 @@ autoware_radar_crossing_objects_noise_filter - 0.40.0 + 0.41.0 autoware_radar_crossing_objects_noise_filter Sathshi Tanaka Shunsuke Miura diff --git a/perception/autoware_radar_fusion_to_detected_object/CHANGELOG.rst b/perception/autoware_radar_fusion_to_detected_object/CHANGELOG.rst index f6f48dfe36231..1a78bb1f0f199 100644 --- a/perception/autoware_radar_fusion_to_detected_object/CHANGELOG.rst +++ b/perception/autoware_radar_fusion_to_detected_object/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package autoware_radar_fusion_to_detected_object ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* fix(autoware_radar_fusion_to_detected_object): fix bugprone-errors (`#9654 `_) + fix: bugprone-error +* Contributors: Fumiya Watanabe, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/perception/autoware_radar_fusion_to_detected_object/package.xml b/perception/autoware_radar_fusion_to_detected_object/package.xml index 20d6331dc8a37..e16b4a5cdc2a0 100644 --- a/perception/autoware_radar_fusion_to_detected_object/package.xml +++ b/perception/autoware_radar_fusion_to_detected_object/package.xml @@ -2,7 +2,7 @@ autoware_radar_fusion_to_detected_object - 0.40.0 + 0.41.0 autoware_radar_fusion_to_detected_object Satoshi Tanaka Shunsuke Miura diff --git a/perception/autoware_radar_object_clustering/CHANGELOG.rst b/perception/autoware_radar_object_clustering/CHANGELOG.rst index b1609dd939090..02718bfcf0968 100644 --- a/perception/autoware_radar_object_clustering/CHANGELOG.rst +++ b/perception/autoware_radar_object_clustering/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_radar_object_clustering ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_radar_object_clustering/package.xml b/perception/autoware_radar_object_clustering/package.xml index c8b5278c60292..5ec802cf4225c 100644 --- a/perception/autoware_radar_object_clustering/package.xml +++ b/perception/autoware_radar_object_clustering/package.xml @@ -2,7 +2,7 @@ autoware_radar_object_clustering - 0.40.0 + 0.41.0 autoware_radar_object_clustering Sathshi Tanaka Shunsuke Miura diff --git a/perception/autoware_radar_object_tracker/CHANGELOG.rst b/perception/autoware_radar_object_tracker/CHANGELOG.rst index 028737b0d4482..bce0d26c71f35 100644 --- a/perception/autoware_radar_object_tracker/CHANGELOG.rst +++ b/perception/autoware_radar_object_tracker/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_radar_object_tracker ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_radar_object_tracker/package.xml b/perception/autoware_radar_object_tracker/package.xml index 4868e93ba9e72..6fee7b009cb91 100644 --- a/perception/autoware_radar_object_tracker/package.xml +++ b/perception/autoware_radar_object_tracker/package.xml @@ -2,7 +2,7 @@ autoware_radar_object_tracker - 0.40.0 + 0.41.0 Do tracking radar object Yoshi Ri Yukihiro Saito diff --git a/perception/autoware_radar_tracks_msgs_converter/CHANGELOG.rst b/perception/autoware_radar_tracks_msgs_converter/CHANGELOG.rst index 9b60a1b24ec7a..d12916eb23e43 100644 --- a/perception/autoware_radar_tracks_msgs_converter/CHANGELOG.rst +++ b/perception/autoware_radar_tracks_msgs_converter/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package autoware_radar_tracks_msgs_converter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* fix(autoware_radar_tracks_msgs_converter): fix bugprone-reserved-identifier (`#9658 `_) + fix: bugprone-error +* Contributors: Fumiya Watanabe, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/perception/autoware_radar_tracks_msgs_converter/package.xml b/perception/autoware_radar_tracks_msgs_converter/package.xml index 5b2e1c7d6a039..deb438818b6b7 100644 --- a/perception/autoware_radar_tracks_msgs_converter/package.xml +++ b/perception/autoware_radar_tracks_msgs_converter/package.xml @@ -2,7 +2,7 @@ autoware_radar_tracks_msgs_converter - 0.40.0 + 0.41.0 autoware_radar_tracks_msgs_converter Satoshi Tanaka Shunsuke Miura diff --git a/perception/autoware_raindrop_cluster_filter/CHANGELOG.rst b/perception/autoware_raindrop_cluster_filter/CHANGELOG.rst index d61173ea1cfea..558501fbc9bf6 100644 --- a/perception/autoware_raindrop_cluster_filter/CHANGELOG.rst +++ b/perception/autoware_raindrop_cluster_filter/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package autoware_raindrop_cluster_filter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in fil… (`#9896 `_) + feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files perception/autoware_raindrop_cluster_filter +* Contributors: Fumiya Watanabe, Vishal Chauhan + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_raindrop_cluster_filter/package.xml b/perception/autoware_raindrop_cluster_filter/package.xml index af3a2b1e9179f..d4d237ff73586 100644 --- a/perception/autoware_raindrop_cluster_filter/package.xml +++ b/perception/autoware_raindrop_cluster_filter/package.xml @@ -2,7 +2,7 @@ autoware_raindrop_cluster_filter - 0.40.0 + 0.41.0 The ROS 2 filter cluster package Yukihiro Saito Dai Nguyen diff --git a/perception/autoware_shape_estimation/CHANGELOG.rst b/perception/autoware_shape_estimation/CHANGELOG.rst index 85af9f1cf54ac..fdd4382218028 100644 --- a/perception/autoware_shape_estimation/CHANGELOG.rst +++ b/perception/autoware_shape_estimation/CHANGELOG.rst @@ -2,6 +2,47 @@ Changelog for package autoware_shape_estimation ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_shape_estimation): tier4_debug_msgs chnaged to autoware_internal_debug_msgs in autoware_shape_estimation (`#9897 `_) + feat: tier4_debug_msgs chnaged to autoware_internal_debug_msgs in files perception/autoware_shape_estimation +* refactor(autoware_tensorrt_common): multi-TensorRT compatibility & tensorrt_common as unified lib for all perception components (`#9762 `_) + * refactor(autoware_tensorrt_common): multi-TensorRT compatibility & tensorrt_common as unified lib for all perception components + * style(pre-commit): autofix + * style(autoware_tensorrt_common): linting + * style(autoware_lidar_centerpoint): typo + Co-authored-by: Kenzo Lobos Tsunekawa + * docs(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * fix(autoware_lidar_transfusion): reuse cast variable + * fix(autoware_tensorrt_common): remove deprecated inference API + * style(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * style(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * fix(autoware_tensorrt_common): const pointer + * fix(autoware_tensorrt_common): remove unused method declaration + * style(pre-commit): autofix + * refactor(autoware_tensorrt_common): readability + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> + * fix(autoware_tensorrt_common): return if layer not registered + * refactor(autoware_tensorrt_common): readability + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> + * fix(autoware_tensorrt_common): rename struct + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Kenzo Lobos Tsunekawa + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> +* fix(autoware_shape_estimation): fix bugprone-branch-clone (`#9659 `_) + * fix: bugprone-error + * fix: fmt + * fix: pre-commit + * fix: pre-commit + --------- +* Contributors: Amadeusz Szymko, Fumiya Watanabe, Vishal Chauhan, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_shape_estimation/package.xml b/perception/autoware_shape_estimation/package.xml index cfc1d7e829a8a..54fb99ecb4ab6 100644 --- a/perception/autoware_shape_estimation/package.xml +++ b/perception/autoware_shape_estimation/package.xml @@ -2,7 +2,7 @@ autoware_shape_estimation - 0.40.0 + 0.41.0 This package implements a shape estimation algorithm as a ROS 2 node Yukihiro Saito Yoshi Ri diff --git a/perception/autoware_simple_object_merger/CHANGELOG.rst b/perception/autoware_simple_object_merger/CHANGELOG.rst index d45c6a726433d..49953813d302d 100644 --- a/perception/autoware_simple_object_merger/CHANGELOG.rst +++ b/perception/autoware_simple_object_merger/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_simple_object_merger ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/perception/autoware_simple_object_merger/package.xml b/perception/autoware_simple_object_merger/package.xml index db20c03a95640..6398e4e640535 100644 --- a/perception/autoware_simple_object_merger/package.xml +++ b/perception/autoware_simple_object_merger/package.xml @@ -1,7 +1,7 @@ autoware_simple_object_merger - 0.40.0 + 0.41.0 autoware_simple_object_merger Sathshi Tanaka Shunsuke Miura diff --git a/perception/autoware_tensorrt_classifier/CHANGELOG.rst b/perception/autoware_tensorrt_classifier/CHANGELOG.rst index 88311b8ed9515..9cba11673c1b5 100644 --- a/perception/autoware_tensorrt_classifier/CHANGELOG.rst +++ b/perception/autoware_tensorrt_classifier/CHANGELOG.rst @@ -2,6 +2,41 @@ Changelog for package autoware_tensorrt_classifier ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* refactor(autoware_tensorrt_common): multi-TensorRT compatibility & tensorrt_common as unified lib for all perception components (`#9762 `_) + * refactor(autoware_tensorrt_common): multi-TensorRT compatibility & tensorrt_common as unified lib for all perception components + * style(pre-commit): autofix + * style(autoware_tensorrt_common): linting + * style(autoware_lidar_centerpoint): typo + Co-authored-by: Kenzo Lobos Tsunekawa + * docs(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * fix(autoware_lidar_transfusion): reuse cast variable + * fix(autoware_tensorrt_common): remove deprecated inference API + * style(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * style(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * fix(autoware_tensorrt_common): const pointer + * fix(autoware_tensorrt_common): remove unused method declaration + * style(pre-commit): autofix + * refactor(autoware_tensorrt_common): readability + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> + * fix(autoware_tensorrt_common): return if layer not registered + * refactor(autoware_tensorrt_common): readability + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> + * fix(autoware_tensorrt_common): rename struct + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Kenzo Lobos Tsunekawa + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> +* fix(autoware_tensorrt_classifier): fix bugprone-exception-escape (`#9732 `_) + fix: bugprone-error +* Contributors: Amadeusz Szymko, Fumiya Watanabe, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_tensorrt_classifier/package.xml b/perception/autoware_tensorrt_classifier/package.xml index 489f5f2596e25..f752cd723a842 100644 --- a/perception/autoware_tensorrt_classifier/package.xml +++ b/perception/autoware_tensorrt_classifier/package.xml @@ -1,7 +1,7 @@ autoware_tensorrt_classifier - 0.40.0 + 0.41.0 tensorrt classifier wrapper Dan Umeda diff --git a/perception/autoware_tensorrt_common/CHANGELOG.rst b/perception/autoware_tensorrt_common/CHANGELOG.rst index ab3b7187c0169..771f9189c3092 100644 --- a/perception/autoware_tensorrt_common/CHANGELOG.rst +++ b/perception/autoware_tensorrt_common/CHANGELOG.rst @@ -2,6 +2,41 @@ Changelog for package autoware_tensorrt_common ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* refactor(autoware_tensorrt_common): multi-TensorRT compatibility & tensorrt_common as unified lib for all perception components (`#9762 `_) + * refactor(autoware_tensorrt_common): multi-TensorRT compatibility & tensorrt_common as unified lib for all perception components + * style(pre-commit): autofix + * style(autoware_tensorrt_common): linting + * style(autoware_lidar_centerpoint): typo + Co-authored-by: Kenzo Lobos Tsunekawa + * docs(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * fix(autoware_lidar_transfusion): reuse cast variable + * fix(autoware_tensorrt_common): remove deprecated inference API + * style(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * style(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * fix(autoware_tensorrt_common): const pointer + * fix(autoware_tensorrt_common): remove unused method declaration + * style(pre-commit): autofix + * refactor(autoware_tensorrt_common): readability + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> + * fix(autoware_tensorrt_common): return if layer not registered + * refactor(autoware_tensorrt_common): readability + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> + * fix(autoware_tensorrt_common): rename struct + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Kenzo Lobos Tsunekawa + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> +* fix(autoware_tensorrt_common): fix bugprone-integer-division (`#9660 `_) + fix: bugprone-error +* Contributors: Amadeusz Szymko, Fumiya Watanabe, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_tensorrt_common/package.xml b/perception/autoware_tensorrt_common/package.xml index 300a7b263c063..475332d5795be 100644 --- a/perception/autoware_tensorrt_common/package.xml +++ b/perception/autoware_tensorrt_common/package.xml @@ -1,7 +1,7 @@ autoware_tensorrt_common - 0.40.0 + 0.41.0 tensorrt utility wrapper Taichi Higashide diff --git a/perception/autoware_tensorrt_yolox/CHANGELOG.rst b/perception/autoware_tensorrt_yolox/CHANGELOG.rst index 969f1df4b5496..2b7959f6234c9 100644 --- a/perception/autoware_tensorrt_yolox/CHANGELOG.rst +++ b/perception/autoware_tensorrt_yolox/CHANGELOG.rst @@ -2,6 +2,53 @@ Changelog for package autoware_tensorrt_yolox ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_tensorrt_yolox)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_tensorrt_yolox (`#9898 `_) +* feat(tensorrt_yolox): add launch for tlr model (`#9828 `_) + * feat(tensorrt_yolox): add launch for tlr model + * chore: typo + * docs: update readme and description + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* fix(autoware_tensorrt_yolox): modify tensorrt_yolox_node name (`#9156 `_) +* refactor(autoware_tensorrt_common): multi-TensorRT compatibility & tensorrt_common as unified lib for all perception components (`#9762 `_) + * refactor(autoware_tensorrt_common): multi-TensorRT compatibility & tensorrt_common as unified lib for all perception components + * style(pre-commit): autofix + * style(autoware_tensorrt_common): linting + * style(autoware_lidar_centerpoint): typo + Co-authored-by: Kenzo Lobos Tsunekawa + * docs(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * fix(autoware_lidar_transfusion): reuse cast variable + * fix(autoware_tensorrt_common): remove deprecated inference API + * style(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * style(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * fix(autoware_tensorrt_common): const pointer + * fix(autoware_tensorrt_common): remove unused method declaration + * style(pre-commit): autofix + * refactor(autoware_tensorrt_common): readability + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> + * fix(autoware_tensorrt_common): return if layer not registered + * refactor(autoware_tensorrt_common): readability + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> + * fix(autoware_tensorrt_common): rename struct + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Kenzo Lobos Tsunekawa + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> +* fix(autoware_tensorrt_yolox): fix bugprone-exception-escape (`#9734 `_) + * fix: bugprone-error + * fix: fmt + * fix: fmt + --------- +* Contributors: Amadeusz Szymko, Fumiya Watanabe, Vishal Chauhan, badai nguyen, cyn-liu, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_tensorrt_yolox/package.xml b/perception/autoware_tensorrt_yolox/package.xml index 40da8422a7b93..5c1b00906285b 100644 --- a/perception/autoware_tensorrt_yolox/package.xml +++ b/perception/autoware_tensorrt_yolox/package.xml @@ -1,7 +1,7 @@ autoware_tensorrt_yolox - 0.40.0 + 0.41.0 tensorrt library implementation for yolox Daisuke Nishimatsu diff --git a/perception/autoware_tracking_object_merger/CHANGELOG.rst b/perception/autoware_tracking_object_merger/CHANGELOG.rst index 337e7028ee61f..765f639a58918 100644 --- a/perception/autoware_tracking_object_merger/CHANGELOG.rst +++ b/perception/autoware_tracking_object_merger/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_tracking_object_merger ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_tracking_object_merger)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_tracking_object_merger (`#9899 `_) +* feat(autoware_object_merger, autoware_tracking_object_merger): enable anonymized node names to be configurable (`#9733 `_) + feat: enable anonymized node names to be configurable +* fix(autoware_tracking_object_merger): fix bugprone-branch-clone (`#9662 `_) + * fix: bugprone-error + * fix: fmt + --------- +* Contributors: Fumiya Watanabe, Taekjin LEE, Vishal Chauhan, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_tracking_object_merger/package.xml b/perception/autoware_tracking_object_merger/package.xml index 2b19ee381258f..d61479f44f31d 100644 --- a/perception/autoware_tracking_object_merger/package.xml +++ b/perception/autoware_tracking_object_merger/package.xml @@ -2,7 +2,7 @@ autoware_tracking_object_merger - 0.40.0 + 0.41.0 merge tracking object Yukihiro Saito Yoshi Ri diff --git a/perception/autoware_traffic_light_arbiter/CHANGELOG.rst b/perception/autoware_traffic_light_arbiter/CHANGELOG.rst index 0b3182907a8ce..a086c29ae65f7 100644 --- a/perception/autoware_traffic_light_arbiter/CHANGELOG.rst +++ b/perception/autoware_traffic_light_arbiter/CHANGELOG.rst @@ -2,6 +2,21 @@ Changelog for package autoware_traffic_light_arbiter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_traffic_light_arbiter): add current time validation (`#9747 `_) + * add current time validation + * style(pre-commit): autofix + * change ros parameter name + * style(pre-commit): autofix + * add validation with absolute function + * add timestamp of topic in test + * fix ci error + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Fumiya Watanabe, Masato Saeki + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_traffic_light_arbiter/package.xml b/perception/autoware_traffic_light_arbiter/package.xml index 03d6ad5cb6cf4..abf0e2c2204cd 100644 --- a/perception/autoware_traffic_light_arbiter/package.xml +++ b/perception/autoware_traffic_light_arbiter/package.xml @@ -2,7 +2,7 @@ autoware_traffic_light_arbiter - 0.40.0 + 0.41.0 The autoware_traffic_light_arbiter package Kenzo Lobos-Tsunekawa Shunsuke Miura diff --git a/perception/autoware_traffic_light_classifier/CHANGELOG.rst b/perception/autoware_traffic_light_classifier/CHANGELOG.rst index db6ddb6b18f87..ee564098cc8f0 100644 --- a/perception/autoware_traffic_light_classifier/CHANGELOG.rst +++ b/perception/autoware_traffic_light_classifier/CHANGELOG.rst @@ -2,6 +2,45 @@ Changelog for package autoware_traffic_light_classifier ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* chore(autoware_traffic_light_classifier): modify docs (`#9819 `_) + * modify docs + * style(pre-commit): autofix + * fix docs + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* refactor(autoware_tensorrt_common): multi-TensorRT compatibility & tensorrt_common as unified lib for all perception components (`#9762 `_) + * refactor(autoware_tensorrt_common): multi-TensorRT compatibility & tensorrt_common as unified lib for all perception components + * style(pre-commit): autofix + * style(autoware_tensorrt_common): linting + * style(autoware_lidar_centerpoint): typo + Co-authored-by: Kenzo Lobos Tsunekawa + * docs(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * fix(autoware_lidar_transfusion): reuse cast variable + * fix(autoware_tensorrt_common): remove deprecated inference API + * style(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * style(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * fix(autoware_tensorrt_common): const pointer + * fix(autoware_tensorrt_common): remove unused method declaration + * style(pre-commit): autofix + * refactor(autoware_tensorrt_common): readability + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> + * fix(autoware_tensorrt_common): return if layer not registered + * refactor(autoware_tensorrt_common): readability + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> + * fix(autoware_tensorrt_common): rename struct + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Kenzo Lobos Tsunekawa + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> +* Contributors: Amadeusz Szymko, Fumiya Watanabe, Masato Saeki + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_traffic_light_classifier/package.xml b/perception/autoware_traffic_light_classifier/package.xml index d83791916d4b9..8ca6f1685bdcb 100644 --- a/perception/autoware_traffic_light_classifier/package.xml +++ b/perception/autoware_traffic_light_classifier/package.xml @@ -2,7 +2,7 @@ autoware_traffic_light_classifier - 0.40.0 + 0.41.0 The autoware_traffic_light_classifier package Yukihiro Saito Shunsuke Miura diff --git a/perception/autoware_traffic_light_fine_detector/CHANGELOG.rst b/perception/autoware_traffic_light_fine_detector/CHANGELOG.rst index 80b1fa60f9e1f..3d6d2ccedea8b 100644 --- a/perception/autoware_traffic_light_fine_detector/CHANGELOG.rst +++ b/perception/autoware_traffic_light_fine_detector/CHANGELOG.rst @@ -2,6 +2,45 @@ Changelog for package autoware_traffic_light_fine_detector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(traffic_light_fine_detector)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in traffic_light_fine_detector (`#9900 `_) +* chore(autoware_traffic_light_fine_detector): modify docs and related params (`#9818 `_) + * modify readme and related params + * fix typo + * fix + --------- +* refactor(autoware_tensorrt_common): multi-TensorRT compatibility & tensorrt_common as unified lib for all perception components (`#9762 `_) + * refactor(autoware_tensorrt_common): multi-TensorRT compatibility & tensorrt_common as unified lib for all perception components + * style(pre-commit): autofix + * style(autoware_tensorrt_common): linting + * style(autoware_lidar_centerpoint): typo + Co-authored-by: Kenzo Lobos Tsunekawa + * docs(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * fix(autoware_lidar_transfusion): reuse cast variable + * fix(autoware_tensorrt_common): remove deprecated inference API + * style(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * style(autoware_tensorrt_common): grammar + Co-authored-by: Kenzo Lobos Tsunekawa + * fix(autoware_tensorrt_common): const pointer + * fix(autoware_tensorrt_common): remove unused method declaration + * style(pre-commit): autofix + * refactor(autoware_tensorrt_common): readability + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> + * fix(autoware_tensorrt_common): return if layer not registered + * refactor(autoware_tensorrt_common): readability + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> + * fix(autoware_tensorrt_common): rename struct + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Kenzo Lobos Tsunekawa + Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> +* Contributors: Amadeusz Szymko, Fumiya Watanabe, Masato Saeki, Vishal Chauhan + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_traffic_light_fine_detector/package.xml b/perception/autoware_traffic_light_fine_detector/package.xml index 2b639fb98bebf..719d2442b799e 100644 --- a/perception/autoware_traffic_light_fine_detector/package.xml +++ b/perception/autoware_traffic_light_fine_detector/package.xml @@ -2,7 +2,7 @@ autoware_traffic_light_fine_detector - 0.40.0 + 0.41.0 The autoware_traffic_light_fine_detector package Tao Zhong Shunsuke Miura diff --git a/perception/autoware_traffic_light_map_based_detector/CHANGELOG.rst b/perception/autoware_traffic_light_map_based_detector/CHANGELOG.rst index 60f84da7131f2..c020c1439900a 100644 --- a/perception/autoware_traffic_light_map_based_detector/CHANGELOG.rst +++ b/perception/autoware_traffic_light_map_based_detector/CHANGELOG.rst @@ -2,6 +2,19 @@ Changelog for package autoware_traffic_light_map_based_detector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* chore(autoware_traffic_light_map_based_detector): modify docs (`#9817 `_) + * modify docs + * fix title + * fix docs + * fix word + * add comment about debug markers + * fix docs + --------- +* Contributors: Fumiya Watanabe, Masato Saeki + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_traffic_light_map_based_detector/package.xml b/perception/autoware_traffic_light_map_based_detector/package.xml index c5caca47a0c39..a21374652c7cb 100644 --- a/perception/autoware_traffic_light_map_based_detector/package.xml +++ b/perception/autoware_traffic_light_map_based_detector/package.xml @@ -2,7 +2,7 @@ autoware_traffic_light_map_based_detector - 0.40.0 + 0.41.0 The autoware_traffic_light_map_based_detector package Yukihiro Saito Shunsuke Miura diff --git a/perception/autoware_traffic_light_multi_camera_fusion/CHANGELOG.rst b/perception/autoware_traffic_light_multi_camera_fusion/CHANGELOG.rst index 74a7fa049c486..1f2fdfa5b5145 100644 --- a/perception/autoware_traffic_light_multi_camera_fusion/CHANGELOG.rst +++ b/perception/autoware_traffic_light_multi_camera_fusion/CHANGELOG.rst @@ -2,6 +2,15 @@ Changelog for package autoware_traffic_light_multi_camera_fusion ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* chore(autoware_traffic_light_multi_camera_fusion): modify docs (`#9821 `_) + * fix docs + * add condition + --------- +* Contributors: Fumiya Watanabe, Masato Saeki + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_traffic_light_multi_camera_fusion/package.xml b/perception/autoware_traffic_light_multi_camera_fusion/package.xml index dfe8657577582..4dd1f53a2e8fa 100644 --- a/perception/autoware_traffic_light_multi_camera_fusion/package.xml +++ b/perception/autoware_traffic_light_multi_camera_fusion/package.xml @@ -2,7 +2,7 @@ autoware_traffic_light_multi_camera_fusion - 0.40.0 + 0.41.0 The autoware_traffic_light_multi_camera_fusion package Tao Zhong Shunsuke Miura diff --git a/perception/autoware_traffic_light_occlusion_predictor/CHANGELOG.rst b/perception/autoware_traffic_light_occlusion_predictor/CHANGELOG.rst index 8dec833763cb7..8833224d5b69f 100644 --- a/perception/autoware_traffic_light_occlusion_predictor/CHANGELOG.rst +++ b/perception/autoware_traffic_light_occlusion_predictor/CHANGELOG.rst @@ -2,6 +2,15 @@ Changelog for package autoware_traffic_light_occlusion_predictor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* chore(autoware_traffic_light_occlusion_predictor): modify docs (`#9820 `_) + * fix docs + * fix docs + --------- +* Contributors: Fumiya Watanabe, Masato Saeki + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_traffic_light_occlusion_predictor/package.xml b/perception/autoware_traffic_light_occlusion_predictor/package.xml index e10dddaf40eaf..a9972c9f73d3c 100644 --- a/perception/autoware_traffic_light_occlusion_predictor/package.xml +++ b/perception/autoware_traffic_light_occlusion_predictor/package.xml @@ -2,7 +2,7 @@ autoware_traffic_light_occlusion_predictor - 0.40.0 + 0.41.0 The autoware_traffic_light_occlusion_predictor package Tao Zhong Shunsuke Miura diff --git a/perception/autoware_traffic_light_visualization/CHANGELOG.rst b/perception/autoware_traffic_light_visualization/CHANGELOG.rst index 420b4bf485eec..8429db3fca7f1 100644 --- a/perception/autoware_traffic_light_visualization/CHANGELOG.rst +++ b/perception/autoware_traffic_light_visualization/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package autoware_traffic_light_visualization ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* fix(autoware_traffic_light_visualization): fix bugprone-branch-clone (`#9668 `_) + fix: bugprone-error +* Contributors: Fumiya Watanabe, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/autoware_traffic_light_visualization/package.xml b/perception/autoware_traffic_light_visualization/package.xml index afb30d43f2a70..e55b9088a8521 100644 --- a/perception/autoware_traffic_light_visualization/package.xml +++ b/perception/autoware_traffic_light_visualization/package.xml @@ -2,7 +2,7 @@ autoware_traffic_light_visualization - 0.40.0 + 0.41.0 The autoware_traffic_light_visualization package Yukihiro Saito Tao Zhong diff --git a/perception/perception_utils/CHANGELOG.rst b/perception/perception_utils/CHANGELOG.rst index ddbe6e3f40270..23f2b8565e014 100644 --- a/perception/perception_utils/CHANGELOG.rst +++ b/perception/perception_utils/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package perception_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/perception/perception_utils/package.xml b/perception/perception_utils/package.xml index 058811b048459..07793f979fd51 100644 --- a/perception/perception_utils/package.xml +++ b/perception/perception_utils/package.xml @@ -2,7 +2,7 @@ perception_utils - 0.40.0 + 0.41.0 The perception_utils package Shunsuke Miura Yoshi Ri diff --git a/planning/autoware_costmap_generator/CHANGELOG.rst b/planning/autoware_costmap_generator/CHANGELOG.rst index 6215cd6361b49..398a155c2f1d7 100644 --- a/planning/autoware_costmap_generator/CHANGELOG.rst +++ b/planning/autoware_costmap_generator/CHANGELOG.rst @@ -2,6 +2,16 @@ Changelog for package autoware_costmap_generator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_costmap_generator): tier4_debug_msgs changed to autoware_internal-debug_msgs in autoware_costmap_generator (`#9901 `_) + feat: tier4_debug_msgs changed to autoware_internal-debug_msgs in files planning/autoware_costmap_generator +* fix(autoware_costmap_generator): fix bugprone-branch-clone (`#9669 `_) + fix: bugprone-error +* chore(autoware_costmap_generator): suppress Could not find a connection between 'map' and 'base_link' (`#9655 `_) +* Contributors: Fumiya Watanabe, Vishal Chauhan, Yukinari Hisaki, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/autoware_costmap_generator/package.xml b/planning/autoware_costmap_generator/package.xml index 9097109de0a0b..d2d0eba64cdd0 100644 --- a/planning/autoware_costmap_generator/package.xml +++ b/planning/autoware_costmap_generator/package.xml @@ -2,7 +2,7 @@ autoware_costmap_generator - 0.40.0 + 0.41.0 The autoware_costmap_generator package Kosuke Takeuchi Takamasa Horibe diff --git a/planning/autoware_external_velocity_limit_selector/CHANGELOG.rst b/planning/autoware_external_velocity_limit_selector/CHANGELOG.rst index 0dd0f835c1f53..d13758041970f 100644 --- a/planning/autoware_external_velocity_limit_selector/CHANGELOG.rst +++ b/planning/autoware_external_velocity_limit_selector/CHANGELOG.rst @@ -2,6 +2,15 @@ Changelog for package autoware_external_velocity_limit_selector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in fil… (`#9902 `_) + feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files planning/autoware_external_velocity_limit_selector +* test(external_velocity_limit_selector): add node test (`#8944 `_) + add node smoke test +* Contributors: Fumiya Watanabe, Maxime CLEMENT, Vishal Chauhan + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/autoware_external_velocity_limit_selector/package.xml b/planning/autoware_external_velocity_limit_selector/package.xml index 4a4fac40bd8a5..f7acfcb4d927a 100644 --- a/planning/autoware_external_velocity_limit_selector/package.xml +++ b/planning/autoware_external_velocity_limit_selector/package.xml @@ -2,7 +2,7 @@ autoware_external_velocity_limit_selector - 0.40.0 + 0.41.0 The autoware_external_velocity_limit_selector ROS 2 package Satoshi Ota Shinnosuke Hirakawa diff --git a/planning/autoware_freespace_planner/CHANGELOG.rst b/planning/autoware_freespace_planner/CHANGELOG.rst index ad8960a64d3d2..75774a107b615 100644 --- a/planning/autoware_freespace_planner/CHANGELOG.rst +++ b/planning/autoware_freespace_planner/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package autoware_freespace_planner ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_freespace_planner): tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_freespace_planner (`#9903 `_) + feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in flies planning/autoware_freespace_planner +* Contributors: Fumiya Watanabe, Vishal Chauhan + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/autoware_freespace_planner/package.xml b/planning/autoware_freespace_planner/package.xml index fd7e39d191647..7586d110d4f51 100644 --- a/planning/autoware_freespace_planner/package.xml +++ b/planning/autoware_freespace_planner/package.xml @@ -2,7 +2,7 @@ autoware_freespace_planner - 0.40.0 + 0.41.0 The autoware_freespace_planner package Kosuke Takeuchi Takamasa Horibe diff --git a/planning/autoware_freespace_planning_algorithms/CHANGELOG.rst b/planning/autoware_freespace_planning_algorithms/CHANGELOG.rst index 8f6b94a2e0a80..7c97be99b7625 100644 --- a/planning/autoware_freespace_planning_algorithms/CHANGELOG.rst +++ b/planning/autoware_freespace_planning_algorithms/CHANGELOG.rst @@ -2,6 +2,16 @@ Changelog for package autoware_freespace_planning_algorithms ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* fix(autoware_freespace_planning_algorithms): fix bugprone-errors (`#9670 `_) + * fix: bugprone-error + * fix: bugprone-error + --------- +* build(autoware_freespace_planning_algorithms): increase test timeout to 2 mins (`#9639 `_) +* Contributors: Fumiya Watanabe, M. Fatih Cırıt, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/autoware_freespace_planning_algorithms/package.xml b/planning/autoware_freespace_planning_algorithms/package.xml index 4bffa7bd15c1d..873e95ec42b14 100644 --- a/planning/autoware_freespace_planning_algorithms/package.xml +++ b/planning/autoware_freespace_planning_algorithms/package.xml @@ -2,7 +2,7 @@ autoware_freespace_planning_algorithms - 0.40.0 + 0.41.0 The autoware_freespace_planning_algorithms package Kosuke Takeuchi Takamasa Horibe diff --git a/planning/autoware_mission_planner_universe/CHANGELOG.rst b/planning/autoware_mission_planner_universe/CHANGELOG.rst index ecbc1c4d7feef..8965e78f50b32 100644 --- a/planning/autoware_mission_planner_universe/CHANGELOG.rst +++ b/planning/autoware_mission_planner_universe/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package autoware_mission_planner_universe ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_mission_planner)!: feat(autoware_mission_planner_universe)!: add _universe suffix to package name (`#9941 `_) +* Contributors: Fumiya Watanabe, Ryohsuke Mitsudome + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/autoware_mission_planner_universe/package.xml b/planning/autoware_mission_planner_universe/package.xml index 73da68c792d6f..804623d60a63f 100644 --- a/planning/autoware_mission_planner_universe/package.xml +++ b/planning/autoware_mission_planner_universe/package.xml @@ -2,7 +2,7 @@ autoware_mission_planner_universe - 0.40.0 + 0.41.0 The autoware_mission_planner_universe package Takagi, Isamu Kosuke Takeuchi diff --git a/planning/autoware_objects_of_interest_marker_interface/CHANGELOG.rst b/planning/autoware_objects_of_interest_marker_interface/CHANGELOG.rst index 16b583990ec3e..6491c3d036148 100644 --- a/planning/autoware_objects_of_interest_marker_interface/CHANGELOG.rst +++ b/planning/autoware_objects_of_interest_marker_interface/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package autoware_objects_of_interest_marker_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* fix(autoware_objects_of_interest_marker_interface): fix bugprone-branch-clone (`#9671 `_) +* Contributors: Fumiya Watanabe, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/autoware_objects_of_interest_marker_interface/package.xml b/planning/autoware_objects_of_interest_marker_interface/package.xml index 6d179f7872dc1..82e6637685ea7 100644 --- a/planning/autoware_objects_of_interest_marker_interface/package.xml +++ b/planning/autoware_objects_of_interest_marker_interface/package.xml @@ -1,7 +1,7 @@ autoware_objects_of_interest_marker_interface - 0.40.0 + 0.41.0 The autoware_objects_of_interest_marker_interface package Fumiya Watanabe diff --git a/planning/autoware_obstacle_cruise_planner/CHANGELOG.rst b/planning/autoware_obstacle_cruise_planner/CHANGELOG.rst index 827fee6a58039..b1922cde64477 100644 --- a/planning/autoware_obstacle_cruise_planner/CHANGELOG.rst +++ b/planning/autoware_obstacle_cruise_planner/CHANGELOG.rst @@ -2,6 +2,47 @@ Changelog for package autoware_obstacle_cruise_planner ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_obstacle_cruise_planner)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_obstacle_cruise_planner (`#9905 `_) + feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files planning/autoware_obstacle_cruise_planner +* chore(planning): move package directory for planning factor interface (`#9948 `_) + * chore: add new package for planning factor interface + * chore(surround_obstacle_checker): update include file + * chore(obstacle_stop_planner): update include file + * chore(obstacle_cruise_planner): update include file + * chore(motion_velocity_planner): update include file + * chore(bpp): update include file + * chore(bvp-common): update include file + * chore(blind_spot): update include file + * chore(crosswalk): update include file + * chore(detection_area): update include file + * chore(intersection): update include file + * chore(no_drivable_area): update include file + * chore(no_stopping_area): update include file + * chore(occlusion_spot): update include file + * chore(run_out): update include file + * chore(speed_bump): update include file + * chore(stop_line): update include file + * chore(template_module): update include file + * chore(traffic_light): update include file + * chore(vtl): update include file + * chore(walkway): update include file + * chore(motion_utils): remove factor interface + --------- +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* docs(obstacle_cruise_planner): add supplemental figures (`#9154 `_) + * add behavior determination flowchart + * add cruise planning block diagram + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Fumiya Watanabe, Mamoru Sobue, Mitsuhiro Sakamoto, Satoshi OTA, Vishal Chauhan + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/autoware_obstacle_cruise_planner/package.xml b/planning/autoware_obstacle_cruise_planner/package.xml index 807908de2d6dc..c70c8ce6f710f 100644 --- a/planning/autoware_obstacle_cruise_planner/package.xml +++ b/planning/autoware_obstacle_cruise_planner/package.xml @@ -1,7 +1,7 @@ autoware_obstacle_cruise_planner - 0.40.0 + 0.41.0 The autoware_obstacle_cruise_planner package Takayuki Murooka diff --git a/planning/autoware_obstacle_stop_planner/CHANGELOG.rst b/planning/autoware_obstacle_stop_planner/CHANGELOG.rst index 867553c9ffd4e..46abbe1a1729f 100644 --- a/planning/autoware_obstacle_stop_planner/CHANGELOG.rst +++ b/planning/autoware_obstacle_stop_planner/CHANGELOG.rst @@ -2,6 +2,45 @@ Changelog for package autoware_obstacle_stop_planner ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_obstacle_stop_planner)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_obstacle_stop_planner (`#9906 `_) + feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files planning/autoware_obstacle_stop_planner +* feat(autoware_planning_test_manager): remove dependency of VirtualTrafficLightState and ExpandStopRange (`#9953 `_) + * feat(autoware_planning_test_manager): remove dependency of virtual traffic light + * modify obstacle_stop test code + --------- +* chore(planning): move package directory for planning factor interface (`#9948 `_) + * chore: add new package for planning factor interface + * chore(surround_obstacle_checker): update include file + * chore(obstacle_stop_planner): update include file + * chore(obstacle_cruise_planner): update include file + * chore(motion_velocity_planner): update include file + * chore(bpp): update include file + * chore(bvp-common): update include file + * chore(blind_spot): update include file + * chore(crosswalk): update include file + * chore(detection_area): update include file + * chore(intersection): update include file + * chore(no_drivable_area): update include file + * chore(no_stopping_area): update include file + * chore(occlusion_spot): update include file + * chore(run_out): update include file + * chore(speed_bump): update include file + * chore(stop_line): update include file + * chore(template_module): update include file + * chore(traffic_light): update include file + * chore(vtl): update include file + * chore(walkway): update include file + * chore(motion_utils): remove factor interface + --------- +* fix(obstacle_stop_planner): migrate planning factor (`#9939 `_) + * fix(obstacle_stop_planner): migrate planning factor + * fix(autoware_default_adapi): add coversion map + --------- +* Contributors: Fumiya Watanabe, Satoshi OTA, Takayuki Murooka, Vishal Chauhan + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/autoware_obstacle_stop_planner/package.xml b/planning/autoware_obstacle_stop_planner/package.xml index 25332774366b0..d0e3a0f7e2f82 100644 --- a/planning/autoware_obstacle_stop_planner/package.xml +++ b/planning/autoware_obstacle_stop_planner/package.xml @@ -2,7 +2,7 @@ autoware_obstacle_stop_planner - 0.40.0 + 0.41.0 The autoware_obstacle_stop_planner package Satoshi Ota diff --git a/planning/autoware_path_optimizer/CHANGELOG.rst b/planning/autoware_path_optimizer/CHANGELOG.rst index 19798e6697ec6..e7b8e6b96114a 100644 --- a/planning/autoware_path_optimizer/CHANGELOG.rst +++ b/planning/autoware_path_optimizer/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_path_optimizer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_path_optimizer)!: tier4_debug_msgs changed to autoware-internal_debug_msgs in autoware_path_optimizer (`#9907 `_) + * feat: tier4_debug_msgs changed to autoware-internal_debug_msgs in files planning/autoware_path_optimizer + * Update planning/autoware_path_optimizer/package.xml + --------- + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> +* feat(motion_planning): use StringStamped in autoware_internal_debug_msgs (`#9742 `_) + feat(motion planning): use StringStamped in autoware_internal_debug_msgs +* Contributors: Fumiya Watanabe, Takayuki Murooka, Vishal Chauhan + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/autoware_path_optimizer/package.xml b/planning/autoware_path_optimizer/package.xml index 26e242c94902f..144810b545dbe 100644 --- a/planning/autoware_path_optimizer/package.xml +++ b/planning/autoware_path_optimizer/package.xml @@ -2,7 +2,7 @@ autoware_path_optimizer - 0.40.0 + 0.41.0 The autoware_path_optimizer package Takayuki Murooka Kosuke Takeuchi diff --git a/planning/autoware_path_smoother/CHANGELOG.rst b/planning/autoware_path_smoother/CHANGELOG.rst index 4b7f86361c63b..9d647e7994aa0 100644 --- a/planning/autoware_path_smoother/CHANGELOG.rst +++ b/planning/autoware_path_smoother/CHANGELOG.rst @@ -2,6 +2,22 @@ Changelog for package autoware_path_smoother ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_path_smoother)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_path_smoother (`#9910 `_) + * feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files planning/autoware_path_smoother + * Update planning/autoware_path_smoother/package.xml + --------- + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> +* feat(motion_planning): use StringStamped in autoware_internal_debug_msgs (`#9742 `_) + feat(motion planning): use StringStamped in autoware_internal_debug_msgs +* fix(autoware_path_smoother): fix bugprone-branch-clone (`#9697 `_) + * fix: bugprone-error + * fix: bugprone-error + --------- +* Contributors: Fumiya Watanabe, Takayuki Murooka, Vishal Chauhan, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/autoware_path_smoother/package.xml b/planning/autoware_path_smoother/package.xml index 75b8786877707..6d2ea76a15c12 100644 --- a/planning/autoware_path_smoother/package.xml +++ b/planning/autoware_path_smoother/package.xml @@ -2,7 +2,7 @@ autoware_path_smoother - 0.40.0 + 0.41.0 The autoware_path_smoother package Takayuki Murooka Maxime CLEMENT diff --git a/planning/autoware_planning_factor_interface/CHANGELOG.rst b/planning/autoware_planning_factor_interface/CHANGELOG.rst new file mode 100644 index 0000000000000..6a71f2cee42f1 --- /dev/null +++ b/planning/autoware_planning_factor_interface/CHANGELOG.rst @@ -0,0 +1,68 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_planning_factor_interface +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* chore(planning): move package directory for planning factor interface (`#9948 `_) + * chore: add new package for planning factor interface + * chore(surround_obstacle_checker): update include file + * chore(obstacle_stop_planner): update include file + * chore(obstacle_cruise_planner): update include file + * chore(motion_velocity_planner): update include file + * chore(bpp): update include file + * chore(bvp-common): update include file + * chore(blind_spot): update include file + * chore(crosswalk): update include file + * chore(detection_area): update include file + * chore(intersection): update include file + * chore(no_drivable_area): update include file + * chore(no_stopping_area): update include file + * chore(occlusion_spot): update include file + * chore(run_out): update include file + * chore(speed_bump): update include file + * chore(stop_line): update include file + * chore(template_module): update include file + * chore(traffic_light): update include file + * chore(vtl): update include file + * chore(walkway): update include file + * chore(motion_utils): remove factor interface + --------- +* Contributors: Fumiya Watanabe, Satoshi OTA + +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* chore(planning): move package directory for planning factor interface (`#9948 `_) + * chore: add new package for planning factor interface + * chore(surround_obstacle_checker): update include file + * chore(obstacle_stop_planner): update include file + * chore(obstacle_cruise_planner): update include file + * chore(motion_velocity_planner): update include file + * chore(bpp): update include file + * chore(bvp-common): update include file + * chore(blind_spot): update include file + * chore(crosswalk): update include file + * chore(detection_area): update include file + * chore(intersection): update include file + * chore(no_drivable_area): update include file + * chore(no_stopping_area): update include file + * chore(occlusion_spot): update include file + * chore(run_out): update include file + * chore(speed_bump): update include file + * chore(stop_line): update include file + * chore(template_module): update include file + * chore(traffic_light): update include file + * chore(vtl): update include file + * chore(walkway): update include file + * chore(motion_utils): remove factor interface + --------- +* Contributors: Fumiya Watanabe, Satoshi OTA + +0.40.0 (2025-01-06) +------------------- + +0.39.0 (2024-11-25) +------------------- + +0.38.0 (2024-11-11) +------------------- diff --git a/planning/autoware_planning_factor_interface/package.xml b/planning/autoware_planning_factor_interface/package.xml index 2d990ff31d482..1a5a4d3f9dbd7 100644 --- a/planning/autoware_planning_factor_interface/package.xml +++ b/planning/autoware_planning_factor_interface/package.xml @@ -2,7 +2,7 @@ autoware_planning_factor_interface - 0.40.0 + 0.41.0 The autoware_planning_factor_interface package Satoshi Ota Mamoru Sobue diff --git a/planning/autoware_planning_test_manager/CHANGELOG.rst b/planning/autoware_planning_test_manager/CHANGELOG.rst index f1ac0f088c3cc..2ac0d456364e7 100644 --- a/planning/autoware_planning_test_manager/CHANGELOG.rst +++ b/planning/autoware_planning_test_manager/CHANGELOG.rst @@ -2,6 +2,26 @@ Changelog for package autoware_planning_test_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_component_interface_specs_universe!): rename package (`#9753 `_) +* feat(autoware_planning_test_manager): remove dependency of tier4_planning_msgs::msg::LateralOffset (`#9967 `_) + * feat(autoware_planning_test_manager): remove dependency of tier4_planning_msgs::msg::LateralOffset + * fix + --------- +* feat(autoware_planning_test_manager): remove dependency of VirtualTrafficLightState and ExpandStopRange (`#9953 `_) + * feat(autoware_planning_test_manager): remove dependency of virtual traffic light + * modify obstacle_stop test code + --------- +* test(autoware_behavior_path_start_planner_module): add unit tests for shift shift pull out planner (`#9776 `_) + feat(behavior_path_planner): add unit tests for ShiftPullOut path planning +* refactor(autoware_test_utils): enhance makeMapBinMsg to accept package name and map filename parameters (`#9617 `_) + * feat: enhance makeMapBinMsg to accept package name and map filename parameters + * feat: set default package name to 'autoware_test_utils' in makeMapBinMsg and related functions + --------- +* Contributors: Fumiya Watanabe, Kyoichi Sugahara, Ryohsuke Mitsudome, Takayuki Murooka + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/autoware_planning_test_manager/package.xml b/planning/autoware_planning_test_manager/package.xml index 8bd31951ea0e9..af42894edf6d5 100644 --- a/planning/autoware_planning_test_manager/package.xml +++ b/planning/autoware_planning_test_manager/package.xml @@ -2,7 +2,7 @@ autoware_planning_test_manager - 0.40.0 + 0.41.0 ROS 2 node for testing interface of the nodes in planning module Kyoichi Sugahara Takamasa Horibe diff --git a/planning/autoware_planning_topic_converter/CHANGELOG.rst b/planning/autoware_planning_topic_converter/CHANGELOG.rst index e937e664654a2..3b70087c34e1d 100644 --- a/planning/autoware_planning_topic_converter/CHANGELOG.rst +++ b/planning/autoware_planning_topic_converter/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_planning_topic_converter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/autoware_planning_topic_converter/package.xml b/planning/autoware_planning_topic_converter/package.xml index e2585924a61d2..cc81643ca5a37 100644 --- a/planning/autoware_planning_topic_converter/package.xml +++ b/planning/autoware_planning_topic_converter/package.xml @@ -1,7 +1,7 @@ autoware_planning_topic_converter - 0.40.0 + 0.41.0 The autoware_planning_topic_converter package Satoshi OTA diff --git a/planning/autoware_planning_validator/CHANGELOG.rst b/planning/autoware_planning_validator/CHANGELOG.rst index 76018e5bf5f11..cb05c9be90c21 100644 --- a/planning/autoware_planning_validator/CHANGELOG.rst +++ b/planning/autoware_planning_validator/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package autoware_planning_validator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_planning_validator)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_planning_validator (`#9911 `_) + feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files planning/autoware_planning_validator +* Contributors: Fumiya Watanabe, Vishal Chauhan + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/autoware_planning_validator/package.xml b/planning/autoware_planning_validator/package.xml index 1652c2ad4f544..fd369a259bd66 100644 --- a/planning/autoware_planning_validator/package.xml +++ b/planning/autoware_planning_validator/package.xml @@ -2,7 +2,7 @@ autoware_planning_validator - 0.40.0 + 0.41.0 ros node for autoware_planning_validator Takamasa Horibe Kosuke Takeuchi diff --git a/planning/autoware_remaining_distance_time_calculator/CHANGELOG.rst b/planning/autoware_remaining_distance_time_calculator/CHANGELOG.rst index 570e7b4783ca4..f715c8102a7ed 100644 --- a/planning/autoware_remaining_distance_time_calculator/CHANGELOG.rst +++ b/planning/autoware_remaining_distance_time_calculator/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_remaining_distance_time_calculator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(remaining_distance_time_calculator): integrate generate_parameter_library (`#8826 `_) + * add parameter description + * use parameter listener + * supress deprecated error + * change scope of compile option to private + --------- +* feat(remaining_distance_time_calculator): skip calculation during parking (`#9013 `_) +* Contributors: Fumiya Watanabe, Ismet Atabay, Mitsuhiro Sakamoto + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/planning/autoware_remaining_distance_time_calculator/package.xml b/planning/autoware_remaining_distance_time_calculator/package.xml index 568f677a0c13d..25a223fbd7a3c 100644 --- a/planning/autoware_remaining_distance_time_calculator/package.xml +++ b/planning/autoware_remaining_distance_time_calculator/package.xml @@ -1,7 +1,7 @@ autoware_remaining_distance_time_calculator - 0.40.0 + 0.41.0 Calculates and publishes remaining distance and time of the mission. Ahmed Ebrahim diff --git a/planning/autoware_route_handler/CHANGELOG.rst b/planning/autoware_route_handler/CHANGELOG.rst index d70e5897c96b5..eb61d677e96ce 100644 --- a/planning/autoware_route_handler/CHANGELOG.rst +++ b/planning/autoware_route_handler/CHANGELOG.rst @@ -2,6 +2,15 @@ Changelog for package autoware_route_handler ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* fix(autoware_route_handler): fix bugprone-exception-escape (`#9738 `_) + * fix: bugprone-error + * fix: add include + --------- +* Contributors: Fumiya Watanabe, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/autoware_route_handler/package.xml b/planning/autoware_route_handler/package.xml index ededbcc9eef3d..f6f770ea59daf 100644 --- a/planning/autoware_route_handler/package.xml +++ b/planning/autoware_route_handler/package.xml @@ -2,7 +2,7 @@ autoware_route_handler - 0.40.0 + 0.41.0 The route_handling package Fumiya Watanabe Zulfaqar Azmi diff --git a/planning/autoware_rtc_interface/CHANGELOG.rst b/planning/autoware_rtc_interface/CHANGELOG.rst index 11672d2c47e3e..b2bb8027a5efb 100644 --- a/planning/autoware_rtc_interface/CHANGELOG.rst +++ b/planning/autoware_rtc_interface/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package autoware_rtc_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* fix(autoware_rtc_interface): fix bugprone-branch-clone (`#9698 `_) +* Contributors: Fumiya Watanabe, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/autoware_rtc_interface/package.xml b/planning/autoware_rtc_interface/package.xml index 861554e81408e..c6d35ea0e5e93 100644 --- a/planning/autoware_rtc_interface/package.xml +++ b/planning/autoware_rtc_interface/package.xml @@ -1,7 +1,7 @@ autoware_rtc_interface - 0.40.0 + 0.41.0 The autoware_rtc_interface package Fumiya Watanabe diff --git a/planning/autoware_scenario_selector/CHANGELOG.rst b/planning/autoware_scenario_selector/CHANGELOG.rst index 877192f0e68f9..868adbed5c554 100644 --- a/planning/autoware_scenario_selector/CHANGELOG.rst +++ b/planning/autoware_scenario_selector/CHANGELOG.rst @@ -2,6 +2,15 @@ Changelog for package autoware_scenario_selector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_scenario_selector): tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_scenario_selector (`#9914 `_) + feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files planning/autoware_scenario_selector +* fix(autoware_scenario_selector): fix bugprone-branch-clone (`#9699 `_) + fix: bugprone-error +* Contributors: Fumiya Watanabe, Vishal Chauhan, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/autoware_scenario_selector/package.xml b/planning/autoware_scenario_selector/package.xml index e726e40acecce..eabd381891771 100644 --- a/planning/autoware_scenario_selector/package.xml +++ b/planning/autoware_scenario_selector/package.xml @@ -2,7 +2,7 @@ autoware_scenario_selector - 0.40.0 + 0.41.0 The autoware_scenario_selector ROS 2 package Taiki Tanaka Tomoya Kimura diff --git a/planning/autoware_surround_obstacle_checker/CHANGELOG.rst b/planning/autoware_surround_obstacle_checker/CHANGELOG.rst index c6e1a13a59aa2..2a497056dc480 100644 --- a/planning/autoware_surround_obstacle_checker/CHANGELOG.rst +++ b/planning/autoware_surround_obstacle_checker/CHANGELOG.rst @@ -2,6 +2,41 @@ Changelog for package autoware_surround_obstacle_checker ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* chore(planning): move package directory for planning factor interface (`#9948 `_) + * chore: add new package for planning factor interface + * chore(surround_obstacle_checker): update include file + * chore(obstacle_stop_planner): update include file + * chore(obstacle_cruise_planner): update include file + * chore(motion_velocity_planner): update include file + * chore(bpp): update include file + * chore(bvp-common): update include file + * chore(blind_spot): update include file + * chore(crosswalk): update include file + * chore(detection_area): update include file + * chore(intersection): update include file + * chore(no_drivable_area): update include file + * chore(no_stopping_area): update include file + * chore(occlusion_spot): update include file + * chore(run_out): update include file + * chore(speed_bump): update include file + * chore(stop_line): update include file + * chore(template_module): update include file + * chore(traffic_light): update include file + * chore(vtl): update include file + * chore(walkway): update include file + * chore(motion_utils): remove factor interface + --------- +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* feat(autoware_surround_obstacle_checker): tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_surround_obstacle_checker (`#9915 `_) + feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files planning/autoware_surround_obstacle_checker +* Contributors: Fumiya Watanabe, Mamoru Sobue, Satoshi OTA, Vishal Chauhan + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/autoware_surround_obstacle_checker/package.xml b/planning/autoware_surround_obstacle_checker/package.xml index d92223fb2ea5d..e5ee999aa24d8 100644 --- a/planning/autoware_surround_obstacle_checker/package.xml +++ b/planning/autoware_surround_obstacle_checker/package.xml @@ -2,7 +2,7 @@ autoware_surround_obstacle_checker - 0.40.0 + 0.41.0 The autoware_surround_obstacle_checker package Satoshi Ota Go Sakayori diff --git a/planning/autoware_velocity_smoother/CHANGELOG.rst b/planning/autoware_velocity_smoother/CHANGELOG.rst index 4655c9658ef2b..82283cfca5b13 100644 --- a/planning/autoware_velocity_smoother/CHANGELOG.rst +++ b/planning/autoware_velocity_smoother/CHANGELOG.rst @@ -2,6 +2,19 @@ Changelog for package autoware_velocity_smoother ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(velocity_smoother): introduce diagnostics (`#9933 `_) + * feat(velocity_smoother): introduce diagnostics + * fix + --------- +* feat(velocity_smoother): use autoware internal Stamped messages (`#9749 `_) + * feat(velocity_smoother): use autoware internal Stamped messages + * fix + --------- +* Contributors: Fumiya Watanabe, Takayuki Murooka + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/autoware_velocity_smoother/package.xml b/planning/autoware_velocity_smoother/package.xml index 3d1252ff0b7a6..dc49d947c058d 100644 --- a/planning/autoware_velocity_smoother/package.xml +++ b/planning/autoware_velocity_smoother/package.xml @@ -2,7 +2,7 @@ autoware_velocity_smoother - 0.40.0 + 0.41.0 The autoware_velocity_smoother package Fumiya Watanabe diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/CHANGELOG.rst index 0b2d004e1f02b..83cc289b049f9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/CHANGELOG.rst @@ -2,6 +2,21 @@ Changelog for package autoware_behavior_path_avoidance_by_lane_change_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* refactor(behavior_path_planner): common test functions (`#9963 `_) + * feat: common test code in behavior_path_planner + * deal with other modules + * fix typo + * update + --------- +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* Contributors: Fumiya Watanabe, Mamoru Sobue, Takayuki Murooka + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/package.xml index 83c361d064fb0..5350adf23fa26 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_avoidance_by_lane_change_module - 0.40.0 + 0.41.0 The behavior_path_avoidance_by_lane_change_module package Satoshi Ota diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/CHANGELOG.rst index 5b5179f250d8d..79f10763f452e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/CHANGELOG.rst @@ -2,6 +2,21 @@ Changelog for package autoware_behavior_path_dynamic_obstacle_avoidance_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* refactor(behavior_path_planner): common test functions (`#9963 `_) + * feat: common test code in behavior_path_planner + * deal with other modules + * fix typo + * update + --------- +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* Contributors: Fumiya Watanabe, Mamoru Sobue, Takayuki Murooka + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/package.xml index e3aefb01c797d..bc52f39a030d4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_dynamic_obstacle_avoidance_module - 0.40.0 + 0.41.0 The autoware_behavior_path_dynamic_obstacle_avoidance_module package Takayuki Murooka diff --git a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/CHANGELOG.rst index 0a315105e5bf1..4d907f1d64a20 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/CHANGELOG.rst @@ -2,6 +2,21 @@ Changelog for package autoware_behavior_path_external_request_lane_change_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* refactor(behavior_path_planner): common test functions (`#9963 `_) + * feat: common test code in behavior_path_planner + * deal with other modules + * fix typo + * update + --------- +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* Contributors: Fumiya Watanabe, Mamoru Sobue, Takayuki Murooka + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/package.xml index af46393d9b9ae..30b1938bb9427 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_external_request_lane_change_module - 0.40.0 + 0.41.0 The autoware_behavior_path_external_request_lane_change_module package Fumiya Watanabe diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/CHANGELOG.rst index 627f216b6d7c9..f09d91b2c87ae 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/CHANGELOG.rst @@ -2,6 +2,46 @@ Changelog for package autoware_behavior_path_goal_planner_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(goal_planner): introduce bezier based pullover for bus stop area (`#10027 `_) +* fix(goal_planner): fix waiting approval path of backward parking (`#10015 `_) +* refactor(goal_planner): divide extract_dynamic_object/is_goal_in_lanes util function (`#10019 `_) +* fix(start_planner, goal_planner): refactor lane departure checker initialization (`#9944 `_) +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* fix(goal_planner): fix geometric pull over (`#9932 `_) +* test(autoware_behavior_path_start_planner_module): add test helper and implement unit tests for FreespacePullOut (`#9832 `_) + * refactor(autoware_behavior_path_start_planner_module): remove unnecessary time_keeper parameter from pull-out planners + * refactor(autoware_behavior_path_start_planner_module): remove TimeKeeper parameter from pull-out planners + * refactor(lane_departure_checker): improve LaneDepartureChecker initialization and parameter handling + * refactor(planner): add planner_data parameter to plan methods in pull out planners + * refactor(autoware_behavior_path_start_planner_module): remove LaneDepartureChecker dependency from pull-out planners + --------- +* feat(goal_planner): update lateral_deviation_thresh from `0.3` to `0.1` (`#9850 `_) + * fix(goal_planner): Update lateral_deviation_thresh from 0.3 to 0.1 + * unified hasDeviatedFrom{Last|Current}PreviousModulePath + * style(pre-commit): autofix + * hasDeviatedFromPath argument modification + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(goal_planner): cut stop path to goal (`#9829 `_) +* refactor(lane_departure_checker): improve LaneDepartureChecker initialization and parameter handling (`#9791 `_) + * refactor(lane_departure_checker): improve LaneDepartureChecker initialization and parameter handling + --------- +* fix(goal_planner): fix usage of last_previous_module_output (`#9811 `_) +* fix(behavior_path_planner): add freespace_planning_algorithms dependency (`#9800 `_) +* chore(autoware_test_utils): update test map (`#9664 `_) +* refactor(goal_planner): divide sort function (`#9650 `_) +* perf(goal_planner): remove unnecessary call to setMap on freespace planning (`#9644 `_) +* feat(goal_planner): add bezier based pull over planner (`#9642 `_) +* feat(goal_planner): divide Planners to isolated threads (`#9514 `_) +* Contributors: Fumiya Watanabe, Kazunori-Nakajima, Kosuke Takeuchi, Kyoichi Sugahara, Mamoru Sobue, Takayuki Murooka + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/package.xml index 78c4ea7e4c609..feb42cdee92b6 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_goal_planner_module - 0.40.0 + 0.41.0 The autoware_behavior_path_goal_planner_module package Kosuke Takeuchi diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/CHANGELOG.rst index 42f6ddf841fec..92affbcfac9cc 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/CHANGELOG.rst @@ -2,6 +2,219 @@ Changelog for package autoware_behavior_path_lane_change_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* docs(lane_change): update lane change documentation (`#9949 `_) + * update lane change requirements documentation + * remove unused function getNumToPreferredLane + * update candidate path generation documentation + * update prepare phase and lane changing phase documentation + * update longitudinal acceleration sampling documentation + * add prepare duration sampling documentation + * update candidate path validity and safety documentation + * fix formatting + * update image and fix formatting + * add overtaking turn lane documentation + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md + Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md + Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md + Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md + Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> + * add LC global flowchart to documentation + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md + Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md + Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> + * reorganize lane change documentation + * fix section title + * add global flowchart description + * add warning + * apply pre-commit checks + * fix spelling + * edit some descriptions + --------- + Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> + Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> +* docs(lane_change): object filtering description (`#9947 `_) + * docs(lane_change): object filtering description + * Move section up + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md + Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md + Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> + --------- + Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> +* refactor(behavior_path_planner): common test functions (`#9963 `_) + * feat: common test code in behavior_path_planner + * deal with other modules + * fix typo + * update + --------- +* refactor(lane_change): add missing safety check parameter (`#9928 `_) + * refactor(lane_change): parameterize incoming object yaw threshold + * Readme + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp + Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> + * Add missing parameters + * missing dot + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md + Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> + * update readme + --------- + Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> + Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* feat(lane_change): ensure path generation doesn't exceed time limit (`#9908 `_) + * add time limit for lane change candidate path generation + * apply time limit for frenet method as well + * ensure param update value is valid + * fix param update initial value + * fix spelling + * fix param update initial values + --------- +* feat(lane_change_module): add update paramter function for non defined paramters (`#9887 `_) + * feat(lane_change_module): add new parameters for collision check and delay lane change functionality + * feat(lane_change_module): add validation for longitudinal and lateral acceleration sampling parameters + * feat(lane_change): update parameter handling and add lateral acceleration mapping + --------- +* feat(lane_change): using frenet planner to generate lane change path when ego near terminal (`#9767 `_) + * frenet planner + * minor refactoring + * adding parameter + * Add diff th param + * limit curvature for prepare segment + * minor refactoring + * print average curvature + * refactor + * filter the path directly + * fix some conflicts + * include curvature smoothing + * document + * fix image folder + * image size + * doxygen + * add debug for state + * use sign function instead + * rename argument + * readme + * fix failed test due to empty value + * add additional note + * fix conflict + --------- +* feat(lane_change): append candidate path index to metric debug table (`#9885 `_) + add candidate path index to metrics debug table +* docs(lane_change): fix broken link (`#9892 `_) +* docs(lane_change): explaining cancel and abort process (`#9845 `_) + * docs(lane_change): explaining cancel and abort process + * slight fix in formatting + * rephrase sentence + * rephrase and replace image for cancel + * Cancel explanations and limitations + * revise abort figure + * revise flow chart + * rephase sentence + * minor fix + * finish up + * offers change to reduces for negative connotation + * minor fix + * move limitation all the way down + * precommit + * equation mistake + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md + Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md + Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> + * rename subheading + --------- + Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> +* refactor(lane_change): refactor transit failure function (`#9835 `_) + * refactor(lane_change): refactor transit failure function + * fixed failed scenario + * remove is abort from debug + * set is abort state + * add comments for clarity + * include what you use. + --------- +* feat(lane_change): implement terminal lane change feature (`#9592 `_) + * implement function to compute terminal lane change path + * push terminal path to candidate paths if no other valid candidate path is found + * use terminal path in LC interface planWaitingApproval function + * set lane changing longitudinal accel to zero for terminal lc path + * rename function + * chore: rename codeowners file + * remove unused member variable prev_approved_path\_ + * refactor stop point insertion for terminal lc path + * add flag to enable/disable terminal path feature + * update README + * add parameter to configure stop point placement + * compute terminal path only when near terminal start + * add option to disable feature near goal + * set default flag value to false + * add documentation for terminal lane change path + * ensure actual prepare duration is always above minimum prepare duration threshold + * explicitly return std::nullopt + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp + Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> + * fix assignment + * fix spelling + * fix merge errors + --------- + Co-authored-by: tomoya.kimura + Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> +* feat(lane_change): add text display for candidate path sampling metrics (`#9810 `_) + * display candidate path sampling metrics on rviz + * rename struct + --------- +* feat(lane_change): revise current lane objects filtering (`#9785 `_) + * consider stopped front objects + * simplify computation of dist to front current lane object + * add flag to enable/disable keeping distance from front stopped vehicle + * fix object filtering test + --------- +* refactor(lane_change): replace sstream to fmt for marker's text (`#9775 `_) +* feat(lane_change): add info text to virtual wall (`#9783 `_) + * specify reason for lane change stop line + * add stop reason for incoming rear object + --------- +* fix(lane_change): add metrics to valid paths visualization (`#9737 `_) + * fix(lane_change): add metrics to valid paths visualization + * fix cpp-check error + --------- +* refactor(lane_change): separate path-related function to utils/path (`#9633 `_) + * refactor(lane_change): separate path-related function to utils/path + * remove old terminal lane change computation + * doxygen comments + * remove frenet planner header + * minor refactoring by throwing instead + * minor refactoring + * fix docstring and remove redundant argument + * get logger in header + * add docstring + * rename function is_colliding + * Fix failing test + * fix for failing scenario caused by prepare velocity + * fix error message + --------- +* fix(lane_change): fix prepare length too short at low speed (RT1-8909) (`#9735 `_) + fix prepare length too short at low speed (RT1-8909) +* refactor(lane_change): separate structs to different folders (`#9625 `_) +* fix(lane_change): remove overlapping preceding lanes (`#9526 `_) + * fix(lane_change): remove overlapping preceding lanes + * fix cpp check + * start searching disconnected lanes directly + * just remove starting from overlapped found + * return non reversed lanes + * fix precommit + --------- +* Contributors: Fumiya Watanabe, Kyoichi Sugahara, Mamoru Sobue, Takayuki Murooka, Zulfaqar Azmi, mkquda + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/package.xml index cf7600556080e..40fd6fc4c572d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_lane_change_module - 0.40.0 + 0.41.0 The autoware_behavior_path_lane_change_module package Fumiya Watanabe diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_planner/CHANGELOG.rst index 654a5b4ed0d87..ce092fbe73c79 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/CHANGELOG.rst @@ -2,6 +2,61 @@ Changelog for package autoware_behavior_path_planner ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(start_planner): visualize planner evaluation table in rviz (`#10029 `_) + visualize planner evaluation table in rviz +* feat(autoware_planning_test_manager): remove dependency of tier4_planning_msgs::msg::LateralOffset (`#9967 `_) + * feat(autoware_planning_test_manager): remove dependency of tier4_planning_msgs::msg::LateralOffset + * fix + --------- +* refactor(behavior_path_planner): common test functions (`#9963 `_) + * feat: common test code in behavior_path_planner + * deal with other modules + * fix typo + * update + --------- +* chore(planning): move package directory for planning factor interface (`#9948 `_) + * chore: add new package for planning factor interface + * chore(surround_obstacle_checker): update include file + * chore(obstacle_stop_planner): update include file + * chore(obstacle_cruise_planner): update include file + * chore(motion_velocity_planner): update include file + * chore(bpp): update include file + * chore(bvp-common): update include file + * chore(blind_spot): update include file + * chore(crosswalk): update include file + * chore(detection_area): update include file + * chore(intersection): update include file + * chore(no_drivable_area): update include file + * chore(no_stopping_area): update include file + * chore(occlusion_spot): update include file + * chore(run_out): update include file + * chore(speed_bump): update include file + * chore(stop_line): update include file + * chore(template_module): update include file + * chore(traffic_light): update include file + * chore(vtl): update include file + * chore(walkway): update include file + * chore(motion_utils): remove factor interface + --------- +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* fix(planning): text revisions (`#9886 `_) + * fix(planning): text revisions + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* docs(bpp): revise explanation for Failure modules (`#9863 `_) +* feat(behavior_path_planner): use autoware internal stamped messages (`#9750 `_) + * feat(behavior_path_planner): use autoware internal stamped messages + * fix universe_utils + --------- +* Contributors: Atto Armoo, Fumiya Watanabe, Kyoichi Sugahara, Mamoru Sobue, Satoshi OTA, Takayuki Murooka, Zulfaqar Azmi + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/package.xml b/planning/behavior_path_planner/autoware_behavior_path_planner/package.xml index 3f41ebe74c86d..3b5b28101ff3a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_planner - 0.40.0 + 0.41.0 The behavior_path_planner package diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_planner_common/CHANGELOG.rst index 6c72ac310e31f..d20daf5d2a0c6 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/CHANGELOG.rst @@ -2,6 +2,48 @@ Changelog for package autoware_behavior_path_planner_common ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(start_planner): visualize planner evaluation table in rviz (`#10029 `_) + visualize planner evaluation table in rviz +* feat(static_obstacle_avoidance): output safety factor (`#10000 `_) + * feat(safety_check): convert to SafetyFactor + * feat(static_obstacle_avoidance): use safety factor + * fix(bpp): output detail + --------- +* chore(planning): move package directory for planning factor interface (`#9948 `_) + * chore: add new package for planning factor interface + * chore(surround_obstacle_checker): update include file + * chore(obstacle_stop_planner): update include file + * chore(obstacle_cruise_planner): update include file + * chore(motion_velocity_planner): update include file + * chore(bpp): update include file + * chore(bvp-common): update include file + * chore(blind_spot): update include file + * chore(crosswalk): update include file + * chore(detection_area): update include file + * chore(intersection): update include file + * chore(no_drivable_area): update include file + * chore(no_stopping_area): update include file + * chore(occlusion_spot): update include file + * chore(run_out): update include file + * chore(speed_bump): update include file + * chore(stop_line): update include file + * chore(template_module): update include file + * chore(traffic_light): update include file + * chore(vtl): update include file + * chore(walkway): update include file + * chore(motion_utils): remove factor interface + --------- +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* fix(autoware_behavior_path_planner_common): fix bugprone-errors (`#9700 `_) + fix: bugprone-error +* Contributors: Fumiya Watanabe, Kyoichi Sugahara, Mamoru Sobue, Satoshi OTA, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml b/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml index 22237a5a1d3a4..0a3d919ead23b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_planner_common - 0.40.0 + 0.41.0 The autoware_behavior_path_planner_common package diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/CHANGELOG.rst index 73fd1b4c7532a..1efdc5df429c1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/CHANGELOG.rst @@ -2,6 +2,15 @@ Changelog for package autoware_behavior_path_sampling_planner_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* Contributors: Fumiya Watanabe, Mamoru Sobue + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/package.xml index a5d78061448ed..d91c9d4c45138 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_sampling_planner_module - 0.40.0 + 0.41.0 The autoware_behavior_path_sampling_planner_module package Daniel Sanchez diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/CHANGELOG.rst index 6ed62ffc8b913..e0f4874c5e986 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/CHANGELOG.rst @@ -2,6 +2,21 @@ Changelog for package autoware_behavior_path_side_shift_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* refactor(behavior_path_planner): common test functions (`#9963 `_) + * feat: common test code in behavior_path_planner + * deal with other modules + * fix typo + * update + --------- +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* Contributors: Fumiya Watanabe, Mamoru Sobue, Takayuki Murooka + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/package.xml index 9bc2b608381fa..5b40fe1d74169 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_side_shift_module - 0.40.0 + 0.41.0 The autoware_behavior_path_side_shift_module package Satoshi Ota diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/CHANGELOG.rst index 0cb96bc9b3bf4..dd4bcb5f51f29 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/CHANGELOG.rst @@ -2,6 +2,41 @@ Changelog for package autoware_behavior_path_start_planner_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(start_planner): visualize planner evaluation table in rviz (`#10029 `_) + visualize planner evaluation table in rviz +* fix(start_planner, goal_planner): refactor lane departure checker initialization (`#9944 `_) +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* test(start_planner): disable GenerateValidFreespacePullOutPath test (`#9937 `_) +* test(autoware_behavior_path_start_planner_module): add test helper and implement unit tests for FreespacePullOut (`#9832 `_) + * refactor(autoware_behavior_path_start_planner_module): remove unnecessary time_keeper parameter from pull-out planners + * refactor(autoware_behavior_path_start_planner_module): remove TimeKeeper parameter from pull-out planners + * refactor(lane_departure_checker): improve LaneDepartureChecker initialization and parameter handling + * refactor(planner): add planner_data parameter to plan methods in pull out planners + * refactor(autoware_behavior_path_start_planner_module): remove LaneDepartureChecker dependency from pull-out planners + --------- +* refactor(lane_departure_checker): improve LaneDepartureChecker initialization and parameter handling (`#9791 `_) + * refactor(lane_departure_checker): improve LaneDepartureChecker initialization and parameter handling + --------- +* refactor(autoware_behavior_path_start_planner_module): remove unnecessary time_keeper parameter from pull-out planners (`#9827 `_) + * refactor(autoware_behavior_path_start_planner_module): remove unnecessary time_keeper parameter from pull-out planners + --------- +* fix(behavior_path_planner): add freespace_planning_algorithms dependency (`#9800 `_) +* test(autoware_behavior_path_start_planner_module): add unit tests for shift shift pull out planner (`#9776 `_) + feat(behavior_path_planner): add unit tests for ShiftPullOut path planning +* refactor(autoware_behavior_path_start_planner_module): add data_structs.cpp and init method for StartPlannerParameters (`#9736 `_) + feat(autoware_behavior_path_start_planner_module): add data_structs.cpp and init method for StartPlannerParameters +* test(autoware_behavior_path_start_planner_module): add unit tests for geometric shift pull out planner (`#9640 `_) + * feat(behavior_path_planner): add unit tests for geometric pull-out planner and improve collision check + * feat(behavior_path_planner): add boolean parameter for divide_pull_out_path and update tests + --------- +* Contributors: Fumiya Watanabe, Kyoichi Sugahara, Mamoru Sobue, Takayuki Murooka + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/package.xml index 214731f96cebc..c31707a413c6a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_start_planner_module - 0.40.0 + 0.41.0 The autoware_behavior_path_start_planner_module package Kosuke Takeuchi diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/CHANGELOG.rst index e162c187de824..fc252da9c1880 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/CHANGELOG.rst @@ -2,6 +2,29 @@ Changelog for package autoware_behavior_path_static_obstacle_avoidance_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(static_obstacle_avoidance): output safety factor (`#10000 `_) + * feat(safety_check): convert to SafetyFactor + * feat(static_obstacle_avoidance): use safety factor + * fix(bpp): output detail + --------- +* refactor(behavior_path_planner): common test functions (`#9963 `_) + * feat: common test code in behavior_path_planner + * deal with other modules + * fix typo + * update + --------- +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* fix(static_avoidance): add optional check (`#9782 `_) +* fix(autoware_behavior_path_static_obstacle_avoidance_module): fix bugprone-branch-clone (`#9701 `_) + fix: bugprone-error +* Contributors: Fumiya Watanabe, Mamoru Sobue, Satoshi OTA, Takayuki Murooka, Zulfaqar Azmi, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/package.xml index 5446e33073b13..e9cb603b5d69c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_static_obstacle_avoidance_module - 0.40.0 + 0.41.0 The autoware_behavior_path_static_obstacle_avoidance_module package Takamasa Horibe diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/CHANGELOG.rst index 0826b1f8193a6..4fe378098ee17 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/CHANGELOG.rst @@ -2,6 +2,59 @@ Changelog for package autoware_behavior_velocity_blind_spot_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* chore(planning): move package directory for planning factor interface (`#9948 `_) + * chore: add new package for planning factor interface + * chore(surround_obstacle_checker): update include file + * chore(obstacle_stop_planner): update include file + * chore(obstacle_cruise_planner): update include file + * chore(motion_velocity_planner): update include file + * chore(bpp): update include file + * chore(bvp-common): update include file + * chore(blind_spot): update include file + * chore(crosswalk): update include file + * chore(detection_area): update include file + * chore(intersection): update include file + * chore(no_drivable_area): update include file + * chore(no_stopping_area): update include file + * chore(occlusion_spot): update include file + * chore(run_out): update include file + * chore(speed_bump): update include file + * chore(stop_line): update include file + * chore(template_module): update include file + * chore(traffic_light): update include file + * chore(vtl): update include file + * chore(walkway): update include file + * chore(motion_utils): remove factor interface + --------- +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* test(blind_spot): add unit tests for util functions (`#9597 `_) +* feat(behavior_velocity_modules): add node test (`#9790 `_) + * feat(behavior_velocity_crosswalk): add node test + * fix + * feat(behavior_velocity_xxx_module): add node test + * fix + * fix + * fix + * fix + * change directory tests -> test + --------- +* refactor(behavior_velocity_planner_common): add behavior_velocity_rtc_interface and move RTC-related implementation (`#9799 `_) + * split into planer_common and rtc_interface + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp + Co-authored-by: Mamoru Sobue + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp + Co-authored-by: Mamoru Sobue + * fix + --------- + Co-authored-by: Mamoru Sobue +* Contributors: Fumiya Watanabe, Mamoru Sobue, Satoshi OTA, Takayuki Murooka + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml index dabd3045b31d2..8c2f96728abc1 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_blind_spot_module - 0.40.0 + 0.41.0 The autoware_behavior_velocity_blind_spot_module package Mamoru Sobue diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/CHANGELOG.rst index 608d6ab37fdc4..11f4bbb2b0a6c 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/CHANGELOG.rst @@ -2,6 +2,69 @@ Changelog for package autoware_behavior_velocity_crosswalk_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* docs(crosswalk): fix file add miss (`#10028 `_) +* docs(crosswalk): update ttc vs ttv docs (`#10025 `_) +* feat(crosswalk): update judgle time against the stopped objects (`#9988 `_) +* chore(crosswalk): port the same direction ignore block (`#9983 `_) +* feat(crosswalk): add pass marker (`#9952 `_) +* chore(planning): move package directory for planning factor interface (`#9948 `_) + * chore: add new package for planning factor interface + * chore(surround_obstacle_checker): update include file + * chore(obstacle_stop_planner): update include file + * chore(obstacle_cruise_planner): update include file + * chore(motion_velocity_planner): update include file + * chore(bpp): update include file + * chore(bvp-common): update include file + * chore(blind_spot): update include file + * chore(crosswalk): update include file + * chore(detection_area): update include file + * chore(intersection): update include file + * chore(no_drivable_area): update include file + * chore(no_stopping_area): update include file + * chore(occlusion_spot): update include file + * chore(run_out): update include file + * chore(speed_bump): update include file + * chore(stop_line): update include file + * chore(template_module): update include file + * chore(traffic_light): update include file + * chore(vtl): update include file + * chore(walkway): update include file + * chore(motion_utils): remove factor interface + --------- +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* fix: remove unnecessary parameters (`#9935 `_) +* feat(behavior_velocity_modules): add node test (`#9790 `_) + * feat(behavior_velocity_crosswalk): add node test + * fix + * feat(behavior_velocity_xxx_module): add node test + * fix + * fix + * fix + * fix + * change directory tests -> test + --------- +* refactor(behavior_velocity_planner_common): add behavior_velocity_rtc_interface and move RTC-related implementation (`#9799 `_) + * split into planer_common and rtc_interface + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp + Co-authored-by: Mamoru Sobue + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp + Co-authored-by: Mamoru Sobue + * fix + --------- + Co-authored-by: Mamoru Sobue +* feat(behavior_velocity_planner): use XXXStamped in autoware_internal_debug_msgs (`#9744 `_) + * feat(behavior_velocity_planner): use XXXStamped in autoware_internal_debug_msgs + * fix + --------- +* feat(behavior_velocity_planner): remove unnecessary tier4_api_msgs (`#9692 `_) +* Contributors: Fumiya Watanabe, Mamoru Sobue, Satoshi OTA, Takayuki Murooka, Yuki TAKAGI + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml index 1f0e9e68a65c6..0f0b45c2d8940 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_crosswalk_module - 0.40.0 + 0.41.0 The autoware_behavior_velocity_crosswalk_module package Satoshi Ota diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/CHANGELOG.rst index fc13807261e4f..15342f4fdc1f4 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/CHANGELOG.rst @@ -2,6 +2,67 @@ Changelog for package autoware_behavior_velocity_detection_area_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* chore(planning): move package directory for planning factor interface (`#9948 `_) + * chore: add new package for planning factor interface + * chore(surround_obstacle_checker): update include file + * chore(obstacle_stop_planner): update include file + * chore(obstacle_cruise_planner): update include file + * chore(motion_velocity_planner): update include file + * chore(bpp): update include file + * chore(bvp-common): update include file + * chore(blind_spot): update include file + * chore(crosswalk): update include file + * chore(detection_area): update include file + * chore(intersection): update include file + * chore(no_drivable_area): update include file + * chore(no_stopping_area): update include file + * chore(occlusion_spot): update include file + * chore(run_out): update include file + * chore(speed_bump): update include file + * chore(stop_line): update include file + * chore(template_module): update include file + * chore(traffic_light): update include file + * chore(vtl): update include file + * chore(walkway): update include file + * chore(motion_utils): remove factor interface + --------- +* feat(behavior_velocity_planner)!: remove velocity_factor completely (`#9943 `_) + * feat(behavior_velocity_planner)!: remove velocity_factor completely + * minimize diff + --------- +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* feat(behavior_velocity_modules): add node test (`#9790 `_) + * feat(behavior_velocity_crosswalk): add node test + * fix + * feat(behavior_velocity_xxx_module): add node test + * fix + * fix + * fix + * fix + * change directory tests -> test + --------- +* feat(behavior_velocity_detection_area): use base class without RTC (`#9802 `_) + * feat(behavior_velocity_detection_area): use base class without RTC + * fix + * fix + --------- +* refactor(behavior_velocity_planner_common): add behavior_velocity_rtc_interface and move RTC-related implementation (`#9799 `_) + * split into planer_common and rtc_interface + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp + Co-authored-by: Mamoru Sobue + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp + Co-authored-by: Mamoru Sobue + * fix + --------- + Co-authored-by: Mamoru Sobue +* Contributors: Fumiya Watanabe, Mamoru Sobue, Satoshi OTA, Takayuki Murooka + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/package.xml index 4ae1d20991078..aff8d6238f4fb 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_detection_area_module - 0.40.0 + 0.41.0 The autoware_behavior_velocity_detection_area_module package Kyoichi Sugahara diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/CHANGELOG.rst index 013fd3b9b54cb..390c1c065d632 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/CHANGELOG.rst @@ -2,6 +2,70 @@ Changelog for package autoware_behavior_velocity_intersection_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(intersection): add wall marker for too late detect objects (`#10006 `_) +* chore(planning): move package directory for planning factor interface (`#9948 `_) + * chore: add new package for planning factor interface + * chore(surround_obstacle_checker): update include file + * chore(obstacle_stop_planner): update include file + * chore(obstacle_cruise_planner): update include file + * chore(motion_velocity_planner): update include file + * chore(bpp): update include file + * chore(bvp-common): update include file + * chore(blind_spot): update include file + * chore(crosswalk): update include file + * chore(detection_area): update include file + * chore(intersection): update include file + * chore(no_drivable_area): update include file + * chore(no_stopping_area): update include file + * chore(occlusion_spot): update include file + * chore(run_out): update include file + * chore(speed_bump): update include file + * chore(stop_line): update include file + * chore(template_module): update include file + * chore(traffic_light): update include file + * chore(vtl): update include file + * chore(walkway): update include file + * chore(motion_utils): remove factor interface + --------- +* feat(behavior_velocity_planner)!: remove velocity_factor completely (`#9943 `_) + * feat(behavior_velocity_planner)!: remove velocity_factor completely + * minimize diff + --------- +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* feat(behavior_velocity_modules): add node test (`#9790 `_) + * feat(behavior_velocity_crosswalk): add node test + * fix + * feat(behavior_velocity_xxx_module): add node test + * fix + * fix + * fix + * fix + * change directory tests -> test + --------- +* fix(autoware_behavior_velocity_intersection_module): fix bugprone-branch-clone (`#9702 `_) + fix: bugprone-error +* refactor(behavior_velocity_planner_common): add behavior_velocity_rtc_interface and move RTC-related implementation (`#9799 `_) + * split into planer_common and rtc_interface + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp + Co-authored-by: Mamoru Sobue + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp + Co-authored-by: Mamoru Sobue + * fix + --------- + Co-authored-by: Mamoru Sobue +* feat(behavior_velocity_planner): use XXXStamped in autoware_internal_debug_msgs (`#9744 `_) + * feat(behavior_velocity_planner): use XXXStamped in autoware_internal_debug_msgs + * fix + --------- +* feat(behavior_velocity_planner): remove unnecessary tier4_api_msgs (`#9692 `_) +* Contributors: Fumiya Watanabe, Mamoru Sobue, Satoshi OTA, Takayuki Murooka, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml index 4f7c3aeea7618..644bcbe7a3de7 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_intersection_module - 0.40.0 + 0.41.0 The autoware_behavior_velocity_intersection_module package Mamoru Sobue diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/CHANGELOG.rst index 3ad226a0a0f71..fc7e5f832e69b 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/CHANGELOG.rst @@ -2,6 +2,52 @@ Changelog for package autoware_behavior_velocity_no_drivable_lane_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* chore(planning): move package directory for planning factor interface (`#9948 `_) + * chore: add new package for planning factor interface + * chore(surround_obstacle_checker): update include file + * chore(obstacle_stop_planner): update include file + * chore(obstacle_cruise_planner): update include file + * chore(motion_velocity_planner): update include file + * chore(bpp): update include file + * chore(bvp-common): update include file + * chore(blind_spot): update include file + * chore(crosswalk): update include file + * chore(detection_area): update include file + * chore(intersection): update include file + * chore(no_drivable_area): update include file + * chore(no_stopping_area): update include file + * chore(occlusion_spot): update include file + * chore(run_out): update include file + * chore(speed_bump): update include file + * chore(stop_line): update include file + * chore(template_module): update include file + * chore(traffic_light): update include file + * chore(vtl): update include file + * chore(walkway): update include file + * chore(motion_utils): remove factor interface + --------- +* feat(behavior_velocity_planner)!: remove velocity_factor completely (`#9943 `_) + * feat(behavior_velocity_planner)!: remove velocity_factor completely + * minimize diff + --------- +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* refactor(behavior_velocity_planner_common): add behavior_velocity_rtc_interface and move RTC-related implementation (`#9799 `_) + * split into planer_common and rtc_interface + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp + Co-authored-by: Mamoru Sobue + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp + Co-authored-by: Mamoru Sobue + * fix + --------- + Co-authored-by: Mamoru Sobue +* Contributors: Fumiya Watanabe, Mamoru Sobue, Satoshi OTA, Takayuki Murooka + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/package.xml index 3ac9bab0c2fdf..190583f583981 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_no_drivable_lane_module - 0.40.0 + 0.41.0 The autoware_behavior_velocity_no_drivable_lane_module package Ahmed Ebrahim diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/CHANGELOG.rst index 177028582aceb..eb26b4132216d 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/CHANGELOG.rst @@ -2,6 +2,62 @@ Changelog for package autoware_behavior_velocity_no_stopping_area_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* chore(planning): move package directory for planning factor interface (`#9948 `_) + * chore: add new package for planning factor interface + * chore(surround_obstacle_checker): update include file + * chore(obstacle_stop_planner): update include file + * chore(obstacle_cruise_planner): update include file + * chore(motion_velocity_planner): update include file + * chore(bpp): update include file + * chore(bvp-common): update include file + * chore(blind_spot): update include file + * chore(crosswalk): update include file + * chore(detection_area): update include file + * chore(intersection): update include file + * chore(no_drivable_area): update include file + * chore(no_stopping_area): update include file + * chore(occlusion_spot): update include file + * chore(run_out): update include file + * chore(speed_bump): update include file + * chore(stop_line): update include file + * chore(template_module): update include file + * chore(traffic_light): update include file + * chore(vtl): update include file + * chore(walkway): update include file + * chore(motion_utils): remove factor interface + --------- +* feat(behavior_velocity_planner)!: remove velocity_factor completely (`#9943 `_) + * feat(behavior_velocity_planner)!: remove velocity_factor completely + * minimize diff + --------- +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* feat(behavior_velocity_modules): add node test (`#9790 `_) + * feat(behavior_velocity_crosswalk): add node test + * fix + * feat(behavior_velocity_xxx_module): add node test + * fix + * fix + * fix + * fix + * change directory tests -> test + --------- +* refactor(behavior_velocity_planner_common): add behavior_velocity_rtc_interface and move RTC-related implementation (`#9799 `_) + * split into planer_common and rtc_interface + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp + Co-authored-by: Mamoru Sobue + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp + Co-authored-by: Mamoru Sobue + * fix + --------- + Co-authored-by: Mamoru Sobue +* Contributors: Fumiya Watanabe, Mamoru Sobue, Satoshi OTA, Takayuki Murooka + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/package.xml index 28677bfb80b15..b9af47f6729c9 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_no_stopping_area_module - 0.40.0 + 0.41.0 The autoware_behavior_velocity_no_stopping_area_module package Kosuke Takeuchi diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/CHANGELOG.rst index e74a81a6a971a..3d17b244e890a 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/CHANGELOG.rst @@ -2,6 +2,56 @@ Changelog for package autoware_behavior_velocity_occlusion_spot_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* chore(planning): move package directory for planning factor interface (`#9948 `_) + * chore: add new package for planning factor interface + * chore(surround_obstacle_checker): update include file + * chore(obstacle_stop_planner): update include file + * chore(obstacle_cruise_planner): update include file + * chore(motion_velocity_planner): update include file + * chore(bpp): update include file + * chore(bvp-common): update include file + * chore(blind_spot): update include file + * chore(crosswalk): update include file + * chore(detection_area): update include file + * chore(intersection): update include file + * chore(no_drivable_area): update include file + * chore(no_stopping_area): update include file + * chore(occlusion_spot): update include file + * chore(run_out): update include file + * chore(speed_bump): update include file + * chore(stop_line): update include file + * chore(template_module): update include file + * chore(traffic_light): update include file + * chore(vtl): update include file + * chore(walkway): update include file + * chore(motion_utils): remove factor interface + --------- +* feat(behavior_velocity_planner)!: remove velocity_factor completely (`#9943 `_) + * feat(behavior_velocity_planner)!: remove velocity_factor completely + * minimize diff + --------- +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* fix(autoware_behavior_velocity_occlusion_spot_module): fix bugprone-macro-parentheses (`#9712 `_) + * fix: bugprone-error + * fix: fmt + --------- +* refactor(behavior_velocity_planner_common): add behavior_velocity_rtc_interface and move RTC-related implementation (`#9799 `_) + * split into planer_common and rtc_interface + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp + Co-authored-by: Mamoru Sobue + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp + Co-authored-by: Mamoru Sobue + * fix + --------- + Co-authored-by: Mamoru Sobue +* Contributors: Fumiya Watanabe, Mamoru Sobue, Satoshi OTA, Takayuki Murooka, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/package.xml index 66cb33192fec0..c4b26150a6670 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_occlusion_spot_module - 0.40.0 + 0.41.0 The autoware_behavior_velocity_occlusion_spot_module package Taiki Tanaka diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/CHANGELOG.rst index 43eafef522dde..5bcc3d250f51e 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/CHANGELOG.rst @@ -2,6 +2,31 @@ Changelog for package autoware_behavior_velocity_planner ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(behavior_velocity_planner): remove virtual traffic light dependency from behavior_velocity_planner and behavior_velocity_planner_common (`#9746 `_) + * feat: remove-virtual-traffic-light-dependency-from-plugin-manager + * build passed + * fix test + * fix test + * fix + * fix typo + --------- +* feat(behavior_velocity_modules): add node test (`#9790 `_) + * feat(behavior_velocity_crosswalk): add node test + * fix + * feat(behavior_velocity_xxx_module): add node test + * fix + * fix + * fix + * fix + * change directory tests -> test + --------- +* refactor(behavior_velocity_planner): independent of plugin packages (`#9760 `_) +* feat(behavior_velocity_planner): remove unnecessary tier4_api_msgs (`#9692 `_) +* Contributors: Fumiya Watanabe, Takayuki Murooka + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml index c40d80c2bf998..d68937727773f 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_planner - 0.40.0 + 0.41.0 The autoware_behavior_velocity_planner package Mamoru Sobue diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/CHANGELOG.rst index efc6fd8e18cb6..c229807e51a5d 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/CHANGELOG.rst @@ -2,6 +2,66 @@ Changelog for package autoware_behavior_velocity_planner_common ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* chore(planning): move package directory for planning factor interface (`#9948 `_) + * chore: add new package for planning factor interface + * chore(surround_obstacle_checker): update include file + * chore(obstacle_stop_planner): update include file + * chore(obstacle_cruise_planner): update include file + * chore(motion_velocity_planner): update include file + * chore(bpp): update include file + * chore(bvp-common): update include file + * chore(blind_spot): update include file + * chore(crosswalk): update include file + * chore(detection_area): update include file + * chore(intersection): update include file + * chore(no_drivable_area): update include file + * chore(no_stopping_area): update include file + * chore(occlusion_spot): update include file + * chore(run_out): update include file + * chore(speed_bump): update include file + * chore(stop_line): update include file + * chore(template_module): update include file + * chore(traffic_light): update include file + * chore(vtl): update include file + * chore(walkway): update include file + * chore(motion_utils): remove factor interface + --------- +* feat(behavior_velocity_planner)!: remove velocity_factor completely (`#9943 `_) + * feat(behavior_velocity_planner)!: remove velocity_factor completely + * minimize diff + --------- +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* fix(behavior_velocity_planner_common): fix unregister process (`#9913 `_) +* feat(behavior_velocity_planner): remove virtual traffic light dependency from behavior_velocity_planner and behavior_velocity_planner_common (`#9746 `_) + * feat: remove-virtual-traffic-light-dependency-from-plugin-manager + * build passed + * fix test + * fix test + * fix + * fix typo + --------- +* refactor(behavior_velocity_planner_common): add behavior_velocity_rtc_interface and move RTC-related implementation (`#9799 `_) + * split into planer_common and rtc_interface + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp + Co-authored-by: Mamoru Sobue + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp + Co-authored-by: Mamoru Sobue + * fix + --------- + Co-authored-by: Mamoru Sobue +* feat(behavior_velocity_planner): use XXXStamped in autoware_internal_debug_msgs (`#9744 `_) + * feat(behavior_velocity_planner): use XXXStamped in autoware_internal_debug_msgs + * fix + --------- +* feat(behavior_velocity_planner): remove unnecessary tier4_api_msgs (`#9692 `_) +* Contributors: Fumiya Watanabe, Mamoru Sobue, Satoshi OTA, Takayuki Murooka, Yuki TAKAGI + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml index bf2a9dfc5e32e..a66faa2e0a303 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_planner_common - 0.40.0 + 0.41.0 The autoware_behavior_velocity_planner_common package Tomoya Kimura diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/CHANGELOG.rst new file mode 100644 index 0000000000000..08974b37c362a --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/CHANGELOG.rst @@ -0,0 +1,94 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_behavior_velocity_rtc_interface +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* chore(planning): move package directory for planning factor interface (`#9948 `_) + * chore: add new package for planning factor interface + * chore(surround_obstacle_checker): update include file + * chore(obstacle_stop_planner): update include file + * chore(obstacle_cruise_planner): update include file + * chore(motion_velocity_planner): update include file + * chore(bpp): update include file + * chore(bvp-common): update include file + * chore(blind_spot): update include file + * chore(crosswalk): update include file + * chore(detection_area): update include file + * chore(intersection): update include file + * chore(no_drivable_area): update include file + * chore(no_stopping_area): update include file + * chore(occlusion_spot): update include file + * chore(run_out): update include file + * chore(speed_bump): update include file + * chore(stop_line): update include file + * chore(template_module): update include file + * chore(traffic_light): update include file + * chore(vtl): update include file + * chore(walkway): update include file + * chore(motion_utils): remove factor interface + --------- +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* refactor(behavior_velocity_planner_common): add behavior_velocity_rtc_interface and move RTC-related implementation (`#9799 `_) + * split into planer_common and rtc_interface + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp + Co-authored-by: Mamoru Sobue + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp + Co-authored-by: Mamoru Sobue + * fix + --------- + Co-authored-by: Mamoru Sobue +* Contributors: Fumiya Watanabe, Mamoru Sobue, Satoshi OTA, Takayuki Murooka + +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* chore(planning): move package directory for planning factor interface (`#9948 `_) + * chore: add new package for planning factor interface + * chore(surround_obstacle_checker): update include file + * chore(obstacle_stop_planner): update include file + * chore(obstacle_cruise_planner): update include file + * chore(motion_velocity_planner): update include file + * chore(bpp): update include file + * chore(bvp-common): update include file + * chore(blind_spot): update include file + * chore(crosswalk): update include file + * chore(detection_area): update include file + * chore(intersection): update include file + * chore(no_drivable_area): update include file + * chore(no_stopping_area): update include file + * chore(occlusion_spot): update include file + * chore(run_out): update include file + * chore(speed_bump): update include file + * chore(stop_line): update include file + * chore(template_module): update include file + * chore(traffic_light): update include file + * chore(vtl): update include file + * chore(walkway): update include file + * chore(motion_utils): remove factor interface + --------- +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* refactor(behavior_velocity_planner_common): add behavior_velocity_rtc_interface and move RTC-related implementation (`#9799 `_) + * split into planer_common and rtc_interface + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp + Co-authored-by: Mamoru Sobue + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp + Co-authored-by: Mamoru Sobue + * fix + --------- + Co-authored-by: Mamoru Sobue +* Contributors: Fumiya Watanabe, Mamoru Sobue, Satoshi OTA, Takayuki Murooka + +0.40.0 (2025-01-06) +------------------- + +0.39.0 (2024-11-25) +------------------- + +0.38.0 (2024-11-11) +------------------- diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/package.xml index 3c2a229cca95a..22935a111ffb2 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_rtc_interface - 0.40.0 + 0.41.0 The autoware_behavior_velocity_rtc_interface package Mamoru Sobue diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/CHANGELOG.rst index eaf93783ae47a..8edfbd4d2216d 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/CHANGELOG.rst @@ -2,6 +2,64 @@ Changelog for package autoware_behavior_velocity_run_out_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* chore(planning): move package directory for planning factor interface (`#9948 `_) + * chore: add new package for planning factor interface + * chore(surround_obstacle_checker): update include file + * chore(obstacle_stop_planner): update include file + * chore(obstacle_cruise_planner): update include file + * chore(motion_velocity_planner): update include file + * chore(bpp): update include file + * chore(bvp-common): update include file + * chore(blind_spot): update include file + * chore(crosswalk): update include file + * chore(detection_area): update include file + * chore(intersection): update include file + * chore(no_drivable_area): update include file + * chore(no_stopping_area): update include file + * chore(occlusion_spot): update include file + * chore(run_out): update include file + * chore(speed_bump): update include file + * chore(stop_line): update include file + * chore(template_module): update include file + * chore(traffic_light): update include file + * chore(vtl): update include file + * chore(walkway): update include file + * chore(motion_utils): remove factor interface + --------- +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* feat(behavior_velocity_modules): add node test (`#9790 `_) + * feat(behavior_velocity_crosswalk): add node test + * fix + * feat(behavior_velocity_xxx_module): add node test + * fix + * fix + * fix + * fix + * change directory tests -> test + --------- +* refactor(behavior_velocity_planner_common): add behavior_velocity_rtc_interface and move RTC-related implementation (`#9799 `_) + * split into planer_common and rtc_interface + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp + Co-authored-by: Mamoru Sobue + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp + Co-authored-by: Mamoru Sobue + * fix + --------- + Co-authored-by: Mamoru Sobue +* feat(behavior_velocity_planner): use XXXStamped in autoware_internal_debug_msgs (`#9744 `_) + * feat(behavior_velocity_planner): use XXXStamped in autoware_internal_debug_msgs + * fix + --------- +* fix(autoware_behavior_velocity_run_out_module): fix bugprone-branch-clone (`#9715 `_) + fix: bugprone-error +* Contributors: Fumiya Watanabe, Mamoru Sobue, Satoshi OTA, Takayuki Murooka, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/package.xml index 18db8281356f8..761ebeb94419a 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_run_out_module - 0.40.0 + 0.41.0 The autoware_behavior_velocity_run_out_module package Tomohito Ando diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/CHANGELOG.rst index f0a53b8d7124d..5c2978b1bfbc9 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/CHANGELOG.rst @@ -2,6 +2,48 @@ Changelog for package autoware_behavior_velocity_speed_bump_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* chore(planning): move package directory for planning factor interface (`#9948 `_) + * chore: add new package for planning factor interface + * chore(surround_obstacle_checker): update include file + * chore(obstacle_stop_planner): update include file + * chore(obstacle_cruise_planner): update include file + * chore(motion_velocity_planner): update include file + * chore(bpp): update include file + * chore(bvp-common): update include file + * chore(blind_spot): update include file + * chore(crosswalk): update include file + * chore(detection_area): update include file + * chore(intersection): update include file + * chore(no_drivable_area): update include file + * chore(no_stopping_area): update include file + * chore(occlusion_spot): update include file + * chore(run_out): update include file + * chore(speed_bump): update include file + * chore(stop_line): update include file + * chore(template_module): update include file + * chore(traffic_light): update include file + * chore(vtl): update include file + * chore(walkway): update include file + * chore(motion_utils): remove factor interface + --------- +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* refactor(behavior_velocity_planner_common): add behavior_velocity_rtc_interface and move RTC-related implementation (`#9799 `_) + * split into planer_common and rtc_interface + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp + Co-authored-by: Mamoru Sobue + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp + Co-authored-by: Mamoru Sobue + * fix + --------- + Co-authored-by: Mamoru Sobue +* Contributors: Fumiya Watanabe, Mamoru Sobue, Satoshi OTA, Takayuki Murooka + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/package.xml index 4940460ba52c1..5519b54162062 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_speed_bump_module - 0.40.0 + 0.41.0 The autoware_behavior_velocity_speed_bump_module package Tomoya Kimura diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/CHANGELOG.rst index c24c67ff81108..ce67ba65749df 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/CHANGELOG.rst @@ -2,6 +2,69 @@ Changelog for package autoware_behavior_velocity_stop_line_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* chore(planning): move package directory for planning factor interface (`#9948 `_) + * chore: add new package for planning factor interface + * chore(surround_obstacle_checker): update include file + * chore(obstacle_stop_planner): update include file + * chore(obstacle_cruise_planner): update include file + * chore(motion_velocity_planner): update include file + * chore(bpp): update include file + * chore(bvp-common): update include file + * chore(blind_spot): update include file + * chore(crosswalk): update include file + * chore(detection_area): update include file + * chore(intersection): update include file + * chore(no_drivable_area): update include file + * chore(no_stopping_area): update include file + * chore(occlusion_spot): update include file + * chore(run_out): update include file + * chore(speed_bump): update include file + * chore(stop_line): update include file + * chore(template_module): update include file + * chore(traffic_light): update include file + * chore(vtl): update include file + * chore(walkway): update include file + * chore(motion_utils): remove factor interface + --------- +* feat(behavior_velocity_planner)!: remove velocity_factor completely (`#9943 `_) + * feat(behavior_velocity_planner)!: remove velocity_factor completely + * minimize diff + --------- +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* fix: remove unnecessary parameters (`#9935 `_) +* fix(planning): corrects typo in svg (`#9814 `_) +* fix(planning): corrects typos (`#9840 `_) + * fix(planning): corrects typos + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(behavior_velocity_modules): add node test (`#9790 `_) + * feat(behavior_velocity_crosswalk): add node test + * fix + * feat(behavior_velocity_xxx_module): add node test + * fix + * fix + * fix + * fix + * change directory tests -> test + --------- +* refactor(behavior_velocity_planner_common): add behavior_velocity_rtc_interface and move RTC-related implementation (`#9799 `_) + * split into planer_common and rtc_interface + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp + Co-authored-by: Mamoru Sobue + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp + Co-authored-by: Mamoru Sobue + * fix + --------- + Co-authored-by: Mamoru Sobue +* Contributors: Atto Armoo, Fumiya Watanabe, Mamoru Sobue, Satoshi OTA, Takayuki Murooka + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/package.xml index 849ab3915c649..61508e0ffd9dc 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_stop_line_module - 0.40.0 + 0.41.0 The autoware_behavior_velocity_stop_line_module package Yukinari Hisaki diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/CHANGELOG.rst index 4fb540814a9f1..42d5dde3b6433 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/CHANGELOG.rst @@ -2,6 +2,48 @@ Changelog for package autoware_behavior_velocity_template_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* chore(planning): move package directory for planning factor interface (`#9948 `_) + * chore: add new package for planning factor interface + * chore(surround_obstacle_checker): update include file + * chore(obstacle_stop_planner): update include file + * chore(obstacle_cruise_planner): update include file + * chore(motion_velocity_planner): update include file + * chore(bpp): update include file + * chore(bvp-common): update include file + * chore(blind_spot): update include file + * chore(crosswalk): update include file + * chore(detection_area): update include file + * chore(intersection): update include file + * chore(no_drivable_area): update include file + * chore(no_stopping_area): update include file + * chore(occlusion_spot): update include file + * chore(run_out): update include file + * chore(speed_bump): update include file + * chore(stop_line): update include file + * chore(template_module): update include file + * chore(traffic_light): update include file + * chore(vtl): update include file + * chore(walkway): update include file + * chore(motion_utils): remove factor interface + --------- +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* refactor(behavior_velocity_planner_common): add behavior_velocity_rtc_interface and move RTC-related implementation (`#9799 `_) + * split into planer_common and rtc_interface + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp + Co-authored-by: Mamoru Sobue + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp + Co-authored-by: Mamoru Sobue + * fix + --------- + Co-authored-by: Mamoru Sobue +* Contributors: Fumiya Watanabe, Mamoru Sobue, Satoshi OTA, Takayuki Murooka + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/package.xml index e808e7758bd65..8ece81460081f 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_template_module - 0.40.0 + 0.41.0 The autoware_behavior_velocity_template_module package Daniel Sanchez diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/CHANGELOG.rst index 669882a37bbce..b294a6f36588f 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/CHANGELOG.rst @@ -2,6 +2,62 @@ Changelog for package autoware_behavior_velocity_traffic_light_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* chore(planning): move package directory for planning factor interface (`#9948 `_) + * chore: add new package for planning factor interface + * chore(surround_obstacle_checker): update include file + * chore(obstacle_stop_planner): update include file + * chore(obstacle_cruise_planner): update include file + * chore(motion_velocity_planner): update include file + * chore(bpp): update include file + * chore(bvp-common): update include file + * chore(blind_spot): update include file + * chore(crosswalk): update include file + * chore(detection_area): update include file + * chore(intersection): update include file + * chore(no_drivable_area): update include file + * chore(no_stopping_area): update include file + * chore(occlusion_spot): update include file + * chore(run_out): update include file + * chore(speed_bump): update include file + * chore(stop_line): update include file + * chore(template_module): update include file + * chore(traffic_light): update include file + * chore(vtl): update include file + * chore(walkway): update include file + * chore(motion_utils): remove factor interface + --------- +* feat(behavior_velocity_planner)!: remove velocity_factor completely (`#9943 `_) + * feat(behavior_velocity_planner)!: remove velocity_factor completely + * minimize diff + --------- +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* feat(behavior_velocity_modules): add node test (`#9790 `_) + * feat(behavior_velocity_crosswalk): add node test + * fix + * feat(behavior_velocity_xxx_module): add node test + * fix + * fix + * fix + * fix + * change directory tests -> test + --------- +* refactor(behavior_velocity_planner_common): add behavior_velocity_rtc_interface and move RTC-related implementation (`#9799 `_) + * split into planer_common and rtc_interface + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp + Co-authored-by: Mamoru Sobue + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp + Co-authored-by: Mamoru Sobue + * fix + --------- + Co-authored-by: Mamoru Sobue +* Contributors: Fumiya Watanabe, Mamoru Sobue, Satoshi OTA, Takayuki Murooka + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/package.xml index 4bc7a15cddc48..518d3275a28d3 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_traffic_light_module - 0.40.0 + 0.41.0 The autoware_behavior_velocity_traffic_light_module package Satoshi Ota diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/CHANGELOG.rst index 731c1967b5a1d..ca86c893f97f2 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/CHANGELOG.rst @@ -2,6 +2,74 @@ Changelog for package autoware_behavior_velocity_virtual_traffic_light_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_planning_test_manager): remove dependency of VirtualTrafficLightState and ExpandStopRange (`#9953 `_) + * feat(autoware_planning_test_manager): remove dependency of virtual traffic light + * modify obstacle_stop test code + --------- +* chore(planning): move package directory for planning factor interface (`#9948 `_) + * chore: add new package for planning factor interface + * chore(surround_obstacle_checker): update include file + * chore(obstacle_stop_planner): update include file + * chore(obstacle_cruise_planner): update include file + * chore(motion_velocity_planner): update include file + * chore(bpp): update include file + * chore(bvp-common): update include file + * chore(blind_spot): update include file + * chore(crosswalk): update include file + * chore(detection_area): update include file + * chore(intersection): update include file + * chore(no_drivable_area): update include file + * chore(no_stopping_area): update include file + * chore(occlusion_spot): update include file + * chore(run_out): update include file + * chore(speed_bump): update include file + * chore(stop_line): update include file + * chore(template_module): update include file + * chore(traffic_light): update include file + * chore(vtl): update include file + * chore(walkway): update include file + * chore(motion_utils): remove factor interface + --------- +* feat(behavior_velocity_planner)!: remove velocity_factor completely (`#9943 `_) + * feat(behavior_velocity_planner)!: remove velocity_factor completely + * minimize diff + --------- +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* feat(behavior_velocity_planner): remove virtual traffic light dependency from behavior_velocity_planner and behavior_velocity_planner_common (`#9746 `_) + * feat: remove-virtual-traffic-light-dependency-from-plugin-manager + * build passed + * fix test + * fix test + * fix + * fix typo + --------- +* feat(behavior_velocity_modules): add node test (`#9790 `_) + * feat(behavior_velocity_crosswalk): add node test + * fix + * feat(behavior_velocity_xxx_module): add node test + * fix + * fix + * fix + * fix + * change directory tests -> test + --------- +* refactor(behavior_velocity_planner_common): add behavior_velocity_rtc_interface and move RTC-related implementation (`#9799 `_) + * split into planer_common and rtc_interface + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp + Co-authored-by: Mamoru Sobue + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp + Co-authored-by: Mamoru Sobue + * fix + --------- + Co-authored-by: Mamoru Sobue +* Contributors: Fumiya Watanabe, Mamoru Sobue, Satoshi OTA, Takayuki Murooka + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/package.xml index 056f84a970c58..3a1e0d9580ded 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_virtual_traffic_light_module - 0.40.0 + 0.41.0 The autoware_behavior_velocity_virtual_traffic_light_module package Kosuke Takeuchi diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/CHANGELOG.rst index 40a8bcf82e7b9..d4f846dea7a5d 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/CHANGELOG.rst @@ -2,6 +2,58 @@ Changelog for package autoware_behavior_velocity_walkway_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* chore(planning): move package directory for planning factor interface (`#9948 `_) + * chore: add new package for planning factor interface + * chore(surround_obstacle_checker): update include file + * chore(obstacle_stop_planner): update include file + * chore(obstacle_cruise_planner): update include file + * chore(motion_velocity_planner): update include file + * chore(bpp): update include file + * chore(bvp-common): update include file + * chore(blind_spot): update include file + * chore(crosswalk): update include file + * chore(detection_area): update include file + * chore(intersection): update include file + * chore(no_drivable_area): update include file + * chore(no_stopping_area): update include file + * chore(occlusion_spot): update include file + * chore(run_out): update include file + * chore(speed_bump): update include file + * chore(stop_line): update include file + * chore(template_module): update include file + * chore(traffic_light): update include file + * chore(vtl): update include file + * chore(walkway): update include file + * chore(motion_utils): remove factor interface + --------- +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* feat(behavior_velocity_modules): add node test (`#9790 `_) + * feat(behavior_velocity_crosswalk): add node test + * fix + * feat(behavior_velocity_xxx_module): add node test + * fix + * fix + * fix + * fix + * change directory tests -> test + --------- +* refactor(behavior_velocity_planner_common): add behavior_velocity_rtc_interface and move RTC-related implementation (`#9799 `_) + * split into planer_common and rtc_interface + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp + Co-authored-by: Mamoru Sobue + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp + Co-authored-by: Mamoru Sobue + * fix + --------- + Co-authored-by: Mamoru Sobue +* Contributors: Fumiya Watanabe, Mamoru Sobue, Satoshi OTA, Takayuki Murooka + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/package.xml index 857d9b524beb0..4bda6bbe5826b 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_walkway_module - 0.40.0 + 0.41.0 The autoware_behavior_velocity_walkway_module package Satoshi Ota diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/CHANGELOG.rst b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/CHANGELOG.rst index 118b555408997..3d20f11b239ad 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/CHANGELOG.rst +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/CHANGELOG.rst @@ -2,6 +2,51 @@ Changelog for package autoware_motion_velocity_dynamic_obstacle_stop_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(motion_velocity_planner)!: add _universe suffix to autoware_motion_velocity_planner_common and autoware_motion_velocity_planner_node (`#9942 `_) +* chore(planning): move package directory for planning factor interface (`#9948 `_) + * chore: add new package for planning factor interface + * chore(surround_obstacle_checker): update include file + * chore(obstacle_stop_planner): update include file + * chore(obstacle_cruise_planner): update include file + * chore(motion_velocity_planner): update include file + * chore(bpp): update include file + * chore(bvp-common): update include file + * chore(blind_spot): update include file + * chore(crosswalk): update include file + * chore(detection_area): update include file + * chore(intersection): update include file + * chore(no_drivable_area): update include file + * chore(no_stopping_area): update include file + * chore(occlusion_spot): update include file + * chore(run_out): update include file + * chore(speed_bump): update include file + * chore(stop_line): update include file + * chore(template_module): update include file + * chore(traffic_light): update include file + * chore(vtl): update include file + * chore(walkway): update include file + * chore(motion_utils): remove factor interface + --------- +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* feat(motion_velocity_planner): introduce Object/Pointcloud structure in PlannerData (`#9812 `_) + * feat: new object/pointcloud struct in motion velocity planner + * update planner_data + * modify modules + * fix + --------- +* feat(motion_velocity_planner): remove unnecessary tier4_planning_msgs dependency (`#9757 `_) + * feat(motion_velocity_planner): remove unnecessary tier4_planning_msgs dependency + * fix + --------- +* feat(motion_velocity_planner): use Float64Stamped in autoware_internal_debug_msgs (`#9745 `_) +* Contributors: Fumiya Watanabe, Mamoru Sobue, Ryohsuke Mitsudome, Satoshi OTA, Takayuki Murooka + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/package.xml index c13aedc3292ee..2e94f1d32b8b3 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/package.xml @@ -2,7 +2,7 @@ autoware_motion_velocity_dynamic_obstacle_stop_module - 0.40.0 + 0.41.0 dynamic_obstacle_stop module to stop ego when in the immediate path of a dynamic object Maxime Clement diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/CHANGELOG.rst b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/CHANGELOG.rst index c1310671d02fa..21cf1519e61d2 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/CHANGELOG.rst +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/CHANGELOG.rst @@ -2,6 +2,33 @@ Changelog for package autoware_motion_velocity_obstacle_velocity_limiter_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(motion_velocity_planner)!: add _universe suffix to autoware_motion_velocity_planner_common and autoware_motion_velocity_planner_node (`#9942 `_) +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* fix(autoware_motion_velocity_obstacle_velocity_limiter_module): remove cppcheck suppressions (`#9843 `_) +* feat(motion_velocity_planner): introduce Object/Pointcloud structure in PlannerData (`#9812 `_) + * feat: new object/pointcloud struct in motion velocity planner + * update planner_data + * modify modules + * fix + --------- +* fix(autoware_motion_velocity_obstacle_velocity_limiter_module): fix bugprone-exception-escape (`#9779 `_) + * fix: bugprone-error + * fix: cppcheck + * fix: cpplint + --------- +* feat(motion_velocity_planner): remove unnecessary tier4_planning_msgs dependency (`#9757 `_) + * feat(motion_velocity_planner): remove unnecessary tier4_planning_msgs dependency + * fix + --------- +* feat(motion_velocity_planner): use Float64Stamped in autoware_internal_debug_msgs (`#9745 `_) +* Contributors: Fumiya Watanabe, Mamoru Sobue, Ryohsuke Mitsudome, Ryuta Kambe, Takayuki Murooka, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/package.xml index 9d3796c041299..3b19c27807a81 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/package.xml @@ -1,7 +1,7 @@ autoware_motion_velocity_obstacle_velocity_limiter_module - 0.40.0 + 0.41.0 Package to adjust velocities of a trajectory in order for the ride to feel safe Maxime CLEMENT diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/CHANGELOG.rst b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/CHANGELOG.rst index 4fe77d0532fce..e0bfb818bbe94 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/CHANGELOG.rst +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/CHANGELOG.rst @@ -2,6 +2,51 @@ Changelog for package autoware_motion_velocity_out_of_lane_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(motion_velocity_planner)!: add _universe suffix to autoware_motion_velocity_planner_common and autoware_motion_velocity_planner_node (`#9942 `_) +* chore(planning): move package directory for planning factor interface (`#9948 `_) + * chore: add new package for planning factor interface + * chore(surround_obstacle_checker): update include file + * chore(obstacle_stop_planner): update include file + * chore(obstacle_cruise_planner): update include file + * chore(motion_velocity_planner): update include file + * chore(bpp): update include file + * chore(bvp-common): update include file + * chore(blind_spot): update include file + * chore(crosswalk): update include file + * chore(detection_area): update include file + * chore(intersection): update include file + * chore(no_drivable_area): update include file + * chore(no_stopping_area): update include file + * chore(occlusion_spot): update include file + * chore(run_out): update include file + * chore(speed_bump): update include file + * chore(stop_line): update include file + * chore(template_module): update include file + * chore(traffic_light): update include file + * chore(vtl): update include file + * chore(walkway): update include file + * chore(motion_utils): remove factor interface + --------- +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* feat(motion_velocity_planner): introduce Object/Pointcloud structure in PlannerData (`#9812 `_) + * feat: new object/pointcloud struct in motion velocity planner + * update planner_data + * modify modules + * fix + --------- +* feat(motion_velocity_planner): remove unnecessary tier4_planning_msgs dependency (`#9757 `_) + * feat(motion_velocity_planner): remove unnecessary tier4_planning_msgs dependency + * fix + --------- +* feat(motion_velocity_planner): use Float64Stamped in autoware_internal_debug_msgs (`#9745 `_) +* Contributors: Fumiya Watanabe, Mamoru Sobue, Ryohsuke Mitsudome, Satoshi OTA, Takayuki Murooka + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml index 8e32ca0219526..d9d2209edc6ef 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml @@ -2,7 +2,7 @@ autoware_motion_velocity_out_of_lane_module - 0.40.0 + 0.41.0 The motion_velocity_out_of_lane_module package Maxime Clement diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/CHANGELOG.rst b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/CHANGELOG.rst index b6f0fe9f9dd86..10917e51fe348 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/CHANGELOG.rst +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package autoware_motion_velocity_planner_common_universe ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(motion_velocity_planner)!: add _universe suffix to autoware_motion_velocity_planner_common and autoware_motion_velocity_planner_node (`#9942 `_) +* Contributors: Fumiya Watanabe, Ryohsuke Mitsudome + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/package.xml index 098d261210583..91d569dc3f8cc 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/package.xml @@ -2,7 +2,7 @@ autoware_motion_velocity_planner_common_universe - 0.40.0 + 0.41.0 Common functions and interfaces for motion_velocity_planner modules Maxime Clement diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/CHANGELOG.rst b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/CHANGELOG.rst index 1bafc41dc8f18..93a648302f213 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/CHANGELOG.rst +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package autoware_motion_velocity_planner_node_universe ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(motion_velocity_planner)!: add _universe suffix to autoware_motion_velocity_planner_common and autoware_motion_velocity_planner_node (`#9942 `_) +* Contributors: Fumiya Watanabe, Ryohsuke Mitsudome + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/package.xml index 43c9773ef11a3..7d9652219b656 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/package.xml @@ -2,7 +2,7 @@ autoware_motion_velocity_planner_node_universe - 0.40.0 + 0.41.0 Node of the motion_velocity_planner Maxime Clement diff --git a/planning/sampling_based_planner/autoware_bezier_sampler/CHANGELOG.rst b/planning/sampling_based_planner/autoware_bezier_sampler/CHANGELOG.rst index fa7e4a3bb0808..5b202eea4e110 100644 --- a/planning/sampling_based_planner/autoware_bezier_sampler/CHANGELOG.rst +++ b/planning/sampling_based_planner/autoware_bezier_sampler/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package autoware_bezier_sampler ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(goal_planner): add bezier based pull over planner (`#9642 `_) +* Contributors: Fumiya Watanabe, Mamoru Sobue + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/sampling_based_planner/autoware_bezier_sampler/package.xml b/planning/sampling_based_planner/autoware_bezier_sampler/package.xml index 249d64d770af5..665666a1ba7bd 100644 --- a/planning/sampling_based_planner/autoware_bezier_sampler/package.xml +++ b/planning/sampling_based_planner/autoware_bezier_sampler/package.xml @@ -1,7 +1,7 @@ autoware_bezier_sampler - 0.40.0 + 0.41.0 Package to sample trajectories using Bézier curves Maxime CLEMENT Maxime CLEMENT diff --git a/planning/sampling_based_planner/autoware_frenet_planner/CHANGELOG.rst b/planning/sampling_based_planner/autoware_frenet_planner/CHANGELOG.rst index eff4108b3fc03..ead6bb6f73a88 100644 --- a/planning/sampling_based_planner/autoware_frenet_planner/CHANGELOG.rst +++ b/planning/sampling_based_planner/autoware_frenet_planner/CHANGELOG.rst @@ -2,6 +2,35 @@ Changelog for package autoware_frenet_planner ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(lane_change): using frenet planner to generate lane change path when ego near terminal (`#9767 `_) + * frenet planner + * minor refactoring + * adding parameter + * Add diff th param + * limit curvature for prepare segment + * minor refactoring + * print average curvature + * refactor + * filter the path directly + * fix some conflicts + * include curvature smoothing + * document + * fix image folder + * image size + * doxygen + * add debug for state + * use sign function instead + * rename argument + * readme + * fix failed test due to empty value + * add additional note + * fix conflict + --------- +* Contributors: Fumiya Watanabe, Zulfaqar Azmi + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/sampling_based_planner/autoware_frenet_planner/package.xml b/planning/sampling_based_planner/autoware_frenet_planner/package.xml index cd5febc3267db..8130f47a8aab3 100644 --- a/planning/sampling_based_planner/autoware_frenet_planner/package.xml +++ b/planning/sampling_based_planner/autoware_frenet_planner/package.xml @@ -1,7 +1,7 @@ autoware_frenet_planner - 0.40.0 + 0.41.0 The autoware_frenet_planner package for trajectory generation in Frenet frame Maxime CLEMENT Maxime CLEMENT diff --git a/planning/sampling_based_planner/autoware_path_sampler/CHANGELOG.rst b/planning/sampling_based_planner/autoware_path_sampler/CHANGELOG.rst index a50f2a0ad3aed..1dad475fea0c7 100644 --- a/planning/sampling_based_planner/autoware_path_sampler/CHANGELOG.rst +++ b/planning/sampling_based_planner/autoware_path_sampler/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package autoware_path_sampler ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(sampling_based_planner)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in sampling_based_planner (`#9916 `_) +* feat(motion_planning): use StringStamped in autoware_internal_debug_msgs (`#9742 `_) + feat(motion planning): use StringStamped in autoware_internal_debug_msgs +* Contributors: Fumiya Watanabe, Takayuki Murooka, Vishal Chauhan + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/sampling_based_planner/autoware_path_sampler/package.xml b/planning/sampling_based_planner/autoware_path_sampler/package.xml index 98d0c4188ec3f..9efd0907c2727 100644 --- a/planning/sampling_based_planner/autoware_path_sampler/package.xml +++ b/planning/sampling_based_planner/autoware_path_sampler/package.xml @@ -2,7 +2,7 @@ autoware_path_sampler - 0.40.0 + 0.41.0 Package for the sampling-based path planner Maxime CLEMENT Apache License 2.0 diff --git a/planning/sampling_based_planner/autoware_sampler_common/CHANGELOG.rst b/planning/sampling_based_planner/autoware_sampler_common/CHANGELOG.rst index 7e0eaaf4e7376..261ab51ebb10e 100644 --- a/planning/sampling_based_planner/autoware_sampler_common/CHANGELOG.rst +++ b/planning/sampling_based_planner/autoware_sampler_common/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_sampler_common ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/planning/sampling_based_planner/autoware_sampler_common/package.xml b/planning/sampling_based_planner/autoware_sampler_common/package.xml index eb08c8125d3ee..a190c56969368 100644 --- a/planning/sampling_based_planner/autoware_sampler_common/package.xml +++ b/planning/sampling_based_planner/autoware_sampler_common/package.xml @@ -1,7 +1,7 @@ autoware_sampler_common - 0.40.0 + 0.41.0 Common classes and functions for sampling based planners Maxime CLEMENT Maxime CLEMENT diff --git a/sensing/autoware_cuda_utils/CHANGELOG.rst b/sensing/autoware_cuda_utils/CHANGELOG.rst index 92a99bc8d3267..bd0461582a882 100644 --- a/sensing/autoware_cuda_utils/CHANGELOG.rst +++ b/sensing/autoware_cuda_utils/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_cuda_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/sensing/autoware_cuda_utils/package.xml b/sensing/autoware_cuda_utils/package.xml index 32a29133201ec..1e0014357be0b 100644 --- a/sensing/autoware_cuda_utils/package.xml +++ b/sensing/autoware_cuda_utils/package.xml @@ -1,7 +1,7 @@ autoware_cuda_utils - 0.40.0 + 0.41.0 cuda utility library Daisuke Nishimatsu diff --git a/sensing/autoware_gnss_poser/CHANGELOG.rst b/sensing/autoware_gnss_poser/CHANGELOG.rst index 8195195c9b15c..d97f28dbe618b 100644 --- a/sensing/autoware_gnss_poser/CHANGELOG.rst +++ b/sensing/autoware_gnss_poser/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package autoware_gnss_poser ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_component_interface_specs_universe!): rename package (`#9753 `_) +* Contributors: Fumiya Watanabe, Ryohsuke Mitsudome + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/sensing/autoware_gnss_poser/package.xml b/sensing/autoware_gnss_poser/package.xml index 0a3d6391ac598..50f9a32156f85 100644 --- a/sensing/autoware_gnss_poser/package.xml +++ b/sensing/autoware_gnss_poser/package.xml @@ -2,7 +2,7 @@ autoware_gnss_poser - 0.40.0 + 0.41.0 The ROS 2 autoware_gnss_poser package Yamato Ando Masahiro Sakamoto diff --git a/sensing/autoware_image_diagnostics/CHANGELOG.rst b/sensing/autoware_image_diagnostics/CHANGELOG.rst index 1486e459e4754..900bdce1670cd 100644 --- a/sensing/autoware_image_diagnostics/CHANGELOG.rst +++ b/sensing/autoware_image_diagnostics/CHANGELOG.rst @@ -2,6 +2,15 @@ Changelog for package autoware_image_diagnostics ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_image_diagnostics): tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_image_diagnostics (`#9918 `_) + feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files sensing/autoware_image_diagnostics +* fix(autoware_image_diagnostics): fix bugprone-branch-clone (`#9723 `_) + fix: bugprone-error +* Contributors: Fumiya Watanabe, Vishal Chauhan, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/sensing/autoware_image_diagnostics/package.xml b/sensing/autoware_image_diagnostics/package.xml index 3140b87e1f1b9..91edff5213f2a 100644 --- a/sensing/autoware_image_diagnostics/package.xml +++ b/sensing/autoware_image_diagnostics/package.xml @@ -2,7 +2,7 @@ autoware_image_diagnostics - 0.40.0 + 0.41.0 The autoware_image_diagnostics package Dai Nguyen Yoshi Ri diff --git a/sensing/autoware_image_transport_decompressor/CHANGELOG.rst b/sensing/autoware_image_transport_decompressor/CHANGELOG.rst index 57968c49291c0..358abdb5ba7f5 100644 --- a/sensing/autoware_image_transport_decompressor/CHANGELOG.rst +++ b/sensing/autoware_image_transport_decompressor/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package autoware_image_transport_decompressor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* fix(autoware_image_transport_decompressor): fix bugprone-branch-clone (`#9724 `_) + fix: bugprone-error +* Contributors: Fumiya Watanabe, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/sensing/autoware_image_transport_decompressor/package.xml b/sensing/autoware_image_transport_decompressor/package.xml index 0ee5a60b2f46e..101090e2cfaf5 100644 --- a/sensing/autoware_image_transport_decompressor/package.xml +++ b/sensing/autoware_image_transport_decompressor/package.xml @@ -2,7 +2,7 @@ autoware_image_transport_decompressor - 0.40.0 + 0.41.0 The image_transport_decompressor package Yukihiro Saito Kenzo Lobos-Tsunekawa diff --git a/sensing/autoware_imu_corrector/CHANGELOG.rst b/sensing/autoware_imu_corrector/CHANGELOG.rst index fe36ee24880e0..79a35f67a3daf 100644 --- a/sensing/autoware_imu_corrector/CHANGELOG.rst +++ b/sensing/autoware_imu_corrector/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package autoware_imu_corrector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* fix(imu_corrector): remove non-periodic publish to /diagnostics topic (`#9951 `_) + fix(imu_corrector): remove force_update() in timer callback + Co-authored-by: Takahisa.Ishikawa +* Contributors: Fumiya Watanabe, interimadd + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/sensing/autoware_imu_corrector/package.xml b/sensing/autoware_imu_corrector/package.xml index 94a2e3fe83071..c4938585b9275 100644 --- a/sensing/autoware_imu_corrector/package.xml +++ b/sensing/autoware_imu_corrector/package.xml @@ -2,7 +2,7 @@ autoware_imu_corrector - 0.40.0 + 0.41.0 The ROS 2 autoware_imu_corrector package Yamato Ando Taiki Yamada diff --git a/sensing/autoware_pcl_extensions/CHANGELOG.rst b/sensing/autoware_pcl_extensions/CHANGELOG.rst index 56c9f0bdff0dc..abf97d3a3ef80 100644 --- a/sensing/autoware_pcl_extensions/CHANGELOG.rst +++ b/sensing/autoware_pcl_extensions/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_pcl_extensions ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/sensing/autoware_pcl_extensions/package.xml b/sensing/autoware_pcl_extensions/package.xml index 840bd976b5b5f..61e76007e2927 100644 --- a/sensing/autoware_pcl_extensions/package.xml +++ b/sensing/autoware_pcl_extensions/package.xml @@ -2,7 +2,7 @@ autoware_pcl_extensions - 0.40.0 + 0.41.0 The autoware_pcl_extensions package Ryu Yamamoto Kenzo Lobos Tsunekawa diff --git a/sensing/autoware_pointcloud_preprocessor/CHANGELOG.rst b/sensing/autoware_pointcloud_preprocessor/CHANGELOG.rst index ad1ce2aaf8464..def8780dc20f8 100644 --- a/sensing/autoware_pointcloud_preprocessor/CHANGELOG.rst +++ b/sensing/autoware_pointcloud_preprocessor/CHANGELOG.rst @@ -2,6 +2,155 @@ Changelog for package autoware_pointcloud_preprocessor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_pointcloud_preprocessor): redesign concatenate and time sync node (`#8300 `_) + * chore: rebase main + * chore: solve conflicts + * chore: fix cpp check + * chore: add diagnostics readme + * chore: update figure + * chore: upload jitter.png and add old design link + * chore: add the link to the tool for analyzing timestamp + * fix: fix bug that timer didn't cancel + * chore: fix logic for logging + * Update sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md + Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> + * Update sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp + Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> + * Update sensing/autoware_pointcloud_preprocessor/schema/cocatenate_and_time_sync_node.schema.json + Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> + * Update sensing/autoware_pointcloud_preprocessor/schema/cocatenate_and_time_sync_node.schema.json + Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> + * Update sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp + Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> + * Update sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp + Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> + * chore: remove distortion corrector related changes + * feat: add managed tf buffer + * chore: fix filename + * chore: add explanataion for maximum queue size + * chore: add explanation for timeout_sec + * chore: fix schema's explanation + * chore: fix description for twist and odom + * chore: remove license that are not used + * chore: change guard to prama once + * chore: default value change to string + * Update sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp + Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> + * Update sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp + Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> + * Update sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp + Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> + * Update sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp + Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> + * style(pre-commit): autofix + * chore: clang-tidy style for static constexpr + * chore: remove unused vector header + * chore: fix naming concatenated_cloud_publisher + * chore: fix namimg diagnostic_updater\_ + * chore: specify parameter in comment + * chore: change RCLCPP_WARN to RCLCPP_WARN_STREAM_THROTTLE + * chore: add comment for cancelling timer + * chore: Simplify loop structure for topic-to-cloud mapping + * chore: fix spell errors + * chore: fix more spell error + * chore: rename mutex and lock + * chore: const reference for string parameter + * chore: add explaination for RclcppTimeHash\_ + * chore: change the concatenate node to parent node + * chore: clean processOdometry and processTwist + * chore: change twist shared pointer queue to twist queue + * chore: refactor compensate pointcloud to function + * chore: reallocate memory for concatenate_cloud_ptr + * chore: remove new to make shared + * chore: dis to distance + * chore: refacotr poitncloud_sub + * chore: return early return but throw runtime error + * chore: replace #define DEFAULT_SYNC_TOPIC_POSTFIX with member variable + * chore: fix spell error + * chore: remove redundant function call + * chore: replace conplex tuple to structure + * chore: use reference instead of a pointer to conveys node + * chore: fix camel to snake case + * chore: fix logic of publish synchronized pointcloud + * chore: fix cpp check + * chore: remove logging and throw error directly + * chore: fix clangd warnings + * chore: fix json schema + * chore: fix clangd warning + * chore: remove unused variable + * chore: fix launcher + * chore: fix clangd warning + * chore: ensure thread safety + * style(pre-commit): autofix + * chore: clean code + * chore: add parameters for handling rosbag replay in loops + * chore: fix diagonistic + * chore: reduce copy operation + * chore: reserve space for concatenated pointcloud + * chore: fix clangd error + * chore: fix pipeline latency + * chore: add debug mode + * chore: refactor convert_to_xyzirc_cloud function + * chore: fix json schema + * chore: fix logging output + * chore: fix the output order of the debug mode + * chore: fix pipeline latency output + * chore: clean code + * chore: set some parameters to false in testing + * chore: fix default value for schema + * chore: fix diagnostic msgs + * chore: fix parameter for sample ros bag + * chore: update readme + * chore: fix empty pointcloud + * chore: remove duplicated logic + * chore: fix logic for handling empty pointcloud + * chore: clean code + * chore: remove rosbag_replay parameter + * chore: remove nodelet cpp + * chore: clang tidy warning + * feat: add naive approach for unsynchronized pointclouds + * chore: add more explanations in docs for naive approach + * feat: refactor naive method and fix the multithreading issue + * chore: set parameter to naive + * chore: fix parameter + * chore: fix readme + * Update sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md + Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> + * Update sensing/autoware_pointcloud_preprocessor/docs/concatenate-data.md + Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> + * style(pre-commit): autofix + * feat: remove mutually exclusive approaches + * chore: fix spell error + * chore: remove unused variable + * refactor: refactor collectorInfo to polymorphic + * chore: fix variable name + * chore: fix figure and diagnostic msg in readme + * chroe: refactor collectorinfo structure + * chore: revert wrong file changes + * chore: improve message + * chore: remove unused input topics + * chore: change to explicit check + * chore: tier4 debug msgs to autoware internal debug msgs + * chore: update documentation + --------- + Co-authored-by: Max Schmeller <6088931+mojomex@users.noreply.github.com> + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(autoware_pointcloud_preprocessor): tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_pointcloud_preprocessor (`#9920 `_) + feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files sensing/autoware_pointcloud_preprocessor +* fix(autoware_pointcloud_preprocessor): fix autoware pointcloud preprocessor docs (`#9765 `_) + * fix downsample and passthrough + * fix: fix blockage-diag docs that page is not shown + --------- +* fix(autoware_pointcloud_preprocessor): fix image display in distortion corrector (`#9761 `_) + fix: fix image display +* fix(autoware_pointcloud_preprocessor): remove unused function mask() (`#9751 `_) +* fix: enable to copy all information in pickup based pointcloud downsampler (`#9686 `_) + enable to copy all information in downsampler +* Contributors: Fumiya Watanabe, Ryuta Kambe, Vishal Chauhan, Yi-Hsiang Fang (Vivid), Yoshi Ri + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/sensing/autoware_pointcloud_preprocessor/package.xml b/sensing/autoware_pointcloud_preprocessor/package.xml index 525b1f3eb0699..ab345f03bd694 100644 --- a/sensing/autoware_pointcloud_preprocessor/package.xml +++ b/sensing/autoware_pointcloud_preprocessor/package.xml @@ -2,7 +2,7 @@ autoware_pointcloud_preprocessor - 0.40.0 + 0.41.0 The ROS 2 autoware_pointcloud_preprocessor package amc-nu Yukihiro Saito diff --git a/sensing/autoware_radar_scan_to_pointcloud2/CHANGELOG.rst b/sensing/autoware_radar_scan_to_pointcloud2/CHANGELOG.rst index 4d92b7237c281..a719f7d396b19 100644 --- a/sensing/autoware_radar_scan_to_pointcloud2/CHANGELOG.rst +++ b/sensing/autoware_radar_scan_to_pointcloud2/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_radar_scan_to_pointcloud2 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/sensing/autoware_radar_scan_to_pointcloud2/package.xml b/sensing/autoware_radar_scan_to_pointcloud2/package.xml index b14615cfb68ea..f95a95a27abee 100644 --- a/sensing/autoware_radar_scan_to_pointcloud2/package.xml +++ b/sensing/autoware_radar_scan_to_pointcloud2/package.xml @@ -1,7 +1,7 @@ autoware_radar_scan_to_pointcloud2 - 0.40.0 + 0.41.0 autoware_radar_scan_to_pointcloud2 Satoshi Tanaka Shunsuke Miura diff --git a/sensing/autoware_radar_static_pointcloud_filter/CHANGELOG.rst b/sensing/autoware_radar_static_pointcloud_filter/CHANGELOG.rst index b66f99ba578a6..ec5c7dfc1c19f 100644 --- a/sensing/autoware_radar_static_pointcloud_filter/CHANGELOG.rst +++ b/sensing/autoware_radar_static_pointcloud_filter/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_radar_static_pointcloud_filter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/sensing/autoware_radar_static_pointcloud_filter/package.xml b/sensing/autoware_radar_static_pointcloud_filter/package.xml index 943bd71f29da7..4a5186a6a3ec1 100644 --- a/sensing/autoware_radar_static_pointcloud_filter/package.xml +++ b/sensing/autoware_radar_static_pointcloud_filter/package.xml @@ -1,7 +1,7 @@ autoware_radar_static_pointcloud_filter - 0.40.0 + 0.41.0 autoware_radar_static_pointcloud_filter Satoshi Tanaka Shunsuke Miura diff --git a/sensing/autoware_radar_threshold_filter/CHANGELOG.rst b/sensing/autoware_radar_threshold_filter/CHANGELOG.rst index e217daeca5a35..b5f3328d7e164 100644 --- a/sensing/autoware_radar_threshold_filter/CHANGELOG.rst +++ b/sensing/autoware_radar_threshold_filter/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_radar_threshold_filter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/sensing/autoware_radar_threshold_filter/package.xml b/sensing/autoware_radar_threshold_filter/package.xml index 5e2a5395168fb..69e6969e5a429 100644 --- a/sensing/autoware_radar_threshold_filter/package.xml +++ b/sensing/autoware_radar_threshold_filter/package.xml @@ -1,7 +1,7 @@ autoware_radar_threshold_filter - 0.40.0 + 0.41.0 autoware_radar_threshold_filter Satoshi Tanaka Shunsuke Miura diff --git a/sensing/autoware_radar_tracks_noise_filter/CHANGELOG.rst b/sensing/autoware_radar_tracks_noise_filter/CHANGELOG.rst index c11a0fde76832..8cb85424b9874 100644 --- a/sensing/autoware_radar_tracks_noise_filter/CHANGELOG.rst +++ b/sensing/autoware_radar_tracks_noise_filter/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_radar_tracks_noise_filter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/sensing/autoware_radar_tracks_noise_filter/package.xml b/sensing/autoware_radar_tracks_noise_filter/package.xml index d674e88e19a1a..3b95b33991640 100644 --- a/sensing/autoware_radar_tracks_noise_filter/package.xml +++ b/sensing/autoware_radar_tracks_noise_filter/package.xml @@ -2,7 +2,7 @@ autoware_radar_tracks_noise_filter - 0.40.0 + 0.41.0 autoware_radar_tracks_noise_filter Sathshi Tanaka Shunsuke Miura diff --git a/sensing/autoware_vehicle_velocity_converter/CHANGELOG.rst b/sensing/autoware_vehicle_velocity_converter/CHANGELOG.rst index 004b045a12494..e0f48fb9122e3 100644 --- a/sensing/autoware_vehicle_velocity_converter/CHANGELOG.rst +++ b/sensing/autoware_vehicle_velocity_converter/CHANGELOG.rst @@ -1,7 +1,10 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package vehicle_velocity_converter +Changelog for package autoware_vehicle_velocity_converter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/sensing/autoware_vehicle_velocity_converter/package.xml b/sensing/autoware_vehicle_velocity_converter/package.xml index cc5c555680562..9f27b5ca8d9f5 100644 --- a/sensing/autoware_vehicle_velocity_converter/package.xml +++ b/sensing/autoware_vehicle_velocity_converter/package.xml @@ -2,7 +2,7 @@ autoware_vehicle_velocity_converter - 0.40.0 + 0.41.0 The autoware_vehicle_velocity_converter package Ryu Yamamoto Apache License 2.0 diff --git a/sensing/livox/autoware_livox_tag_filter/CHANGELOG.rst b/sensing/livox/autoware_livox_tag_filter/CHANGELOG.rst index e9e42a6e4e629..b3ad06d1f3ff9 100644 --- a/sensing/livox/autoware_livox_tag_filter/CHANGELOG.rst +++ b/sensing/livox/autoware_livox_tag_filter/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_livox_tag_filter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/sensing/livox/autoware_livox_tag_filter/package.xml b/sensing/livox/autoware_livox_tag_filter/package.xml index 61555e186d1e1..bcc8ae86afeb3 100644 --- a/sensing/livox/autoware_livox_tag_filter/package.xml +++ b/sensing/livox/autoware_livox_tag_filter/package.xml @@ -2,7 +2,7 @@ autoware_livox_tag_filter - 0.40.0 + 0.41.0 The autoware_livox_tag_filter package Ryohsuke Mitsudome Kenzo Lobos-Tsunekawa diff --git a/simulator/autoware_carla_interface/CHANGELOG.rst b/simulator/autoware_carla_interface/CHANGELOG.rst index d71cf66049c9d..e869e6f62fdd9 100644 --- a/simulator/autoware_carla_interface/CHANGELOG.rst +++ b/simulator/autoware_carla_interface/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package autoware_carla_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* fix(autoware_carla_interface): fix lidar topic name (`#9645 `_) +* Contributors: Fumiya Watanabe, Maxime CLEMENT + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/simulator/autoware_carla_interface/package.xml b/simulator/autoware_carla_interface/package.xml index 1ea183cc86eb5..a8eeabc5f3398 100644 --- a/simulator/autoware_carla_interface/package.xml +++ b/simulator/autoware_carla_interface/package.xml @@ -1,7 +1,7 @@ autoware_carla_interface - 0.40.0 + 0.41.0 The carla autoware bridge package Muhammad Raditya GIOVANNI Maxime CLEMENT diff --git a/simulator/autoware_carla_interface/setup.py b/simulator/autoware_carla_interface/setup.py index 4f06766582f6a..50f6c274d6740 100644 --- a/simulator/autoware_carla_interface/setup.py +++ b/simulator/autoware_carla_interface/setup.py @@ -8,7 +8,7 @@ setup( name=package_name, - version="0.40.0", + version="0.41.0", packages=find_packages(where="src"), data_files=[ ("share/ament_index/resource_index/packages", [f"resource/{package_name}"]), diff --git a/simulator/autoware_dummy_perception_publisher/CHANGELOG.rst b/simulator/autoware_dummy_perception_publisher/CHANGELOG.rst index ada832a084f22..819303dc2c3c4 100644 --- a/simulator/autoware_dummy_perception_publisher/CHANGELOG.rst +++ b/simulator/autoware_dummy_perception_publisher/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package autoware_dummy_perception_publisher ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `dummy_perception_publisher` (`#9987 `_) +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/simulator/autoware_dummy_perception_publisher/package.xml b/simulator/autoware_dummy_perception_publisher/package.xml index 6c75a9b3c0277..e9dd3cb1614c9 100644 --- a/simulator/autoware_dummy_perception_publisher/package.xml +++ b/simulator/autoware_dummy_perception_publisher/package.xml @@ -2,7 +2,7 @@ autoware_dummy_perception_publisher - 0.40.0 + 0.41.0 The autoware_dummy_perception_publisher package Yukihiro Saito Junya Sasaki diff --git a/simulator/autoware_fault_injection/CHANGELOG.rst b/simulator/autoware_fault_injection/CHANGELOG.rst index 6116bafaa2088..132cdb733c271 100644 --- a/simulator/autoware_fault_injection/CHANGELOG.rst +++ b/simulator/autoware_fault_injection/CHANGELOG.rst @@ -1,7 +1,27 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package fault_injection +Changelog for package autoware_fault_injection ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `fault_injection` (`#9989 `_) + * feat(fault_injection): apply `autoware\_` prefix (see below): + Note: + * In this commit, I did not organize a folder structure. + The folder structure will be organized in the next some commits. + * The changes will follow the Autoware's guideline as below: + - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder + * rename(fault_injection): move headers under `include/autoware`: + * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit + * fix(fault_injection): fix include header paths + * To follow the previous commit + * rename: `fault_injection` => `autoware_fault_injection` + * Fixed exec_depend + --------- + Co-authored-by: SakodaShintaro +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/simulator/autoware_fault_injection/package.xml b/simulator/autoware_fault_injection/package.xml index 15391feced80f..a0479ff49ee50 100644 --- a/simulator/autoware_fault_injection/package.xml +++ b/simulator/autoware_fault_injection/package.xml @@ -2,7 +2,7 @@ autoware_fault_injection - 0.40.0 + 0.41.0 The fault_injection package Keisuke Shima Junya Sasaki diff --git a/simulator/autoware_learning_based_vehicle_model/CHANGELOG.rst b/simulator/autoware_learning_based_vehicle_model/CHANGELOG.rst index d58a509138a83..82757278b719d 100644 --- a/simulator/autoware_learning_based_vehicle_model/CHANGELOG.rst +++ b/simulator/autoware_learning_based_vehicle_model/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package autoware_learning_based_vehicle_model ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `learning_based_vehicle_model` (`#9991 `_) +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/simulator/autoware_learning_based_vehicle_model/package.xml b/simulator/autoware_learning_based_vehicle_model/package.xml index b6b381801636d..6f48df3364a76 100644 --- a/simulator/autoware_learning_based_vehicle_model/package.xml +++ b/simulator/autoware_learning_based_vehicle_model/package.xml @@ -2,7 +2,7 @@ autoware_learning_based_vehicle_model - 0.40.0 + 0.41.0 autoware_learning_based_vehicle_model for simple_planning_simulator Maxime Clement Tomas Nagy diff --git a/simulator/autoware_simple_planning_simulator/CHANGELOG.rst b/simulator/autoware_simple_planning_simulator/CHANGELOG.rst index ac6e093ea55e7..8e36793315331 100644 --- a/simulator/autoware_simple_planning_simulator/CHANGELOG.rst +++ b/simulator/autoware_simple_planning_simulator/CHANGELOG.rst @@ -1,7 +1,36 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package simple_planning_simulator +Changelog for package autoware_simple_planning_simulator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `learning_based_vehicle_model` (`#9991 `_) +* feat: apply `autoware\_` prefix for `simple_planning_simulator` (`#9995 `_) + * feat(simple_planning_simulator): apply `autoware\_` prefix (see below): + Note: + * In this commit, I did not organize a folder structure. + The folder structure will be organized in the next some commits. + * The changes will follow the Autoware's guideline as below: + - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder + * rename(simple_planning_simulator): move headers under `include/autoware`: + * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit + * fix(simple_planning_simulator): fix include header paths + * To follow the previous commit + * rename: `simple_planning_simulator` => `autoware_simple_planning_simulator` + * bug(autoware_simple_planning_simulator): fix missing changes + * style(pre-commit): autofix + * bug(autoware_simple_planning_simulator): fix errors in build and tests + * I had to run after `rm -rf install build`, ... sorry + * style(pre-commit): autofix + * Fixed NOLINT + * Added NOLINT + * Fixed to autoware_simple_planning_simulator + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Shintaro Sakoda +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/simulator/autoware_simple_planning_simulator/package.xml b/simulator/autoware_simple_planning_simulator/package.xml index 47dbb3c0a422f..47ca399a9ad95 100644 --- a/simulator/autoware_simple_planning_simulator/package.xml +++ b/simulator/autoware_simple_planning_simulator/package.xml @@ -2,7 +2,7 @@ autoware_simple_planning_simulator - 0.40.0 + 0.41.0 simple_planning_simulator as a ROS 2 node Takamasa Horibe Tomoya Kimura diff --git a/simulator/autoware_vehicle_door_simulator/CHANGELOG.rst b/simulator/autoware_vehicle_door_simulator/CHANGELOG.rst index 3def98ed36995..30e09a8236754 100644 --- a/simulator/autoware_vehicle_door_simulator/CHANGELOG.rst +++ b/simulator/autoware_vehicle_door_simulator/CHANGELOG.rst @@ -1,7 +1,14 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package vehicle_door_simulator +Changelog for package autoware_vehicle_door_simulator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `vehicle_door_simulator` (`#9997 `_) + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/simulator/autoware_vehicle_door_simulator/package.xml b/simulator/autoware_vehicle_door_simulator/package.xml index 2a92e6240eba3..d0ecdb3c8f529 100644 --- a/simulator/autoware_vehicle_door_simulator/package.xml +++ b/simulator/autoware_vehicle_door_simulator/package.xml @@ -2,7 +2,7 @@ autoware_vehicle_door_simulator - 0.40.0 + 0.41.0 The vehicle_door_simulator package Takagi, Isamu Junya Sasaki diff --git a/simulator/tier4_dummy_object_rviz_plugin/CHANGELOG.rst b/simulator/tier4_dummy_object_rviz_plugin/CHANGELOG.rst index 1157abff775ab..0c2a51543b7a1 100644 --- a/simulator/tier4_dummy_object_rviz_plugin/CHANGELOG.rst +++ b/simulator/tier4_dummy_object_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package tier4_dummy_object_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/simulator/tier4_dummy_object_rviz_plugin/package.xml b/simulator/tier4_dummy_object_rviz_plugin/package.xml index b73d3a1cc15c0..6174317813b59 100644 --- a/simulator/tier4_dummy_object_rviz_plugin/package.xml +++ b/simulator/tier4_dummy_object_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_dummy_object_rviz_plugin - 0.40.0 + 0.41.0 The tier4_dummy_object_rviz_plugin package Yukihiro Saito Apache License 2.0 diff --git a/system/autoware_bluetooth_monitor/CHANGELOG.rst b/system/autoware_bluetooth_monitor/CHANGELOG.rst index 25b55a9bdcc6f..3f01329d06120 100644 --- a/system/autoware_bluetooth_monitor/CHANGELOG.rst +++ b/system/autoware_bluetooth_monitor/CHANGELOG.rst @@ -1,7 +1,31 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package bluetooth_monitor +Changelog for package autoware_bluetooth_monitor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `bluetooth_monitor` (`#9960 `_) + * feat(bluetooth_monitor): apply `autoware\_` prefix (see below): + * In this commit, I did not organize a folder structure. + The folder structure will be organized in the next some commits. + * The changes will follow the Autoware's guideline as below: + - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder + * rename(bluetooth_monitor): move headers under `include/autoware`: + * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit + * fix(bluetooth_monitor): fix include paths + * To follow the previous commit + * bug(bluetooth_monitor): fix a missing prefix bug + * rename: `bluetooth_monitor` => `autoware_bluetooth_monitor` + * style(pre-commit): autofix + * bug(autoware_bluetooth_monitor): revert wrongly updated copyrights + * bug(autoware_bluetooth_monitor): `autoware\_` prefix is not needed here + * update: `CODEOWNERS` + * update(autoware_bluetooth_monitor): `README.md` + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/system/autoware_bluetooth_monitor/package.xml b/system/autoware_bluetooth_monitor/package.xml index 8f5c8d2d6ab77..12070b90f3d2a 100644 --- a/system/autoware_bluetooth_monitor/package.xml +++ b/system/autoware_bluetooth_monitor/package.xml @@ -2,7 +2,7 @@ autoware_bluetooth_monitor - 0.40.0 + 0.41.0 Bluetooth alive monitoring Fumihito Ito Junya Sasaki diff --git a/system/autoware_component_monitor/CHANGELOG.rst b/system/autoware_component_monitor/CHANGELOG.rst index 339f30f9f9f80..ad3fbeac76c35 100644 --- a/system/autoware_component_monitor/CHANGELOG.rst +++ b/system/autoware_component_monitor/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_component_monitor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/system/autoware_component_monitor/package.xml b/system/autoware_component_monitor/package.xml index 27432bc1fc0d6..965cef269d971 100644 --- a/system/autoware_component_monitor/package.xml +++ b/system/autoware_component_monitor/package.xml @@ -2,7 +2,7 @@ autoware_component_monitor - 0.40.0 + 0.41.0 A ROS 2 package to monitor system usage of component containers. Mehmet Emin Başoğlu Barış Zeren diff --git a/system/autoware_component_state_monitor/CHANGELOG.rst b/system/autoware_component_state_monitor/CHANGELOG.rst index b7e38c40b2ed3..f7c729718af15 100644 --- a/system/autoware_component_state_monitor/CHANGELOG.rst +++ b/system/autoware_component_state_monitor/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package autoware_component_state_monitor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware` prefix for `component_state_monitor` and its dependencies (`#9961 `_) +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/system/autoware_component_state_monitor/package.xml b/system/autoware_component_state_monitor/package.xml index c57725b0c1f85..91e129f0b8cf0 100644 --- a/system/autoware_component_state_monitor/package.xml +++ b/system/autoware_component_state_monitor/package.xml @@ -2,7 +2,7 @@ autoware_component_state_monitor - 0.40.0 + 0.41.0 The autoware_component_state_monitor package Takagi, Isamu Junya Sasaki diff --git a/system/autoware_default_adapi/CHANGELOG.rst b/system/autoware_default_adapi/CHANGELOG.rst index 438ee15f16f61..0bfb5137f9f23 100644 --- a/system/autoware_default_adapi/CHANGELOG.rst +++ b/system/autoware_default_adapi/CHANGELOG.rst @@ -2,6 +2,34 @@ Changelog for package autoware_default_adapi ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware` prefix for `component_state_monitor` and its dependencies (`#9961 `_) +* feat: apply `autoware\_` prefix for `diagnostic_graph_utils` (`#9968 `_) +* feat: apply `autoware\_` prefix for `default_ad_api_helpers` (`#9965 `_) + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Takagi, Isamu +* feat(autoware_component_interface_specs_universe!): rename package (`#9753 `_) +* fix(obstacle_stop_planner): migrate planning factor (`#9939 `_) + * fix(obstacle_stop_planner): migrate planning factor + * fix(autoware_default_adapi): add coversion map + --------- +* feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (`#9927 `_) + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> + Co-authored-by: satoshi-ota +* feat(autoware_default_adapi): release adapi v1.6.0 (`#9704 `_) + * feat: reject clearing route during autonomous mode + * feat: modify check and relay door service + * fix door condition + * fix error and add option + * update v1.6.0 + --------- +* fix(autoware_default_adapi): fix bugprone-branch-clone (`#9726 `_) + fix: bugprone-error +* Contributors: Fumiya Watanabe, Junya Sasaki, Mamoru Sobue, Ryohsuke Mitsudome, Satoshi OTA, Takagi, Isamu, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/system/autoware_default_adapi/package.xml b/system/autoware_default_adapi/package.xml index 5125844cbfedf..7442710a81741 100644 --- a/system/autoware_default_adapi/package.xml +++ b/system/autoware_default_adapi/package.xml @@ -2,7 +2,7 @@ autoware_default_adapi - 0.40.0 + 0.41.0 The autoware_default_adapi package Takagi, Isamu Ryohsuke Mitsudome diff --git a/system/autoware_default_adapi_helpers/autoware_adapi_adaptors/CHANGELOG.rst b/system/autoware_default_adapi_helpers/autoware_adapi_adaptors/CHANGELOG.rst index b0d8f9b49cd59..488e0dc01c50e 100644 --- a/system/autoware_default_adapi_helpers/autoware_adapi_adaptors/CHANGELOG.rst +++ b/system/autoware_default_adapi_helpers/autoware_adapi_adaptors/CHANGELOG.rst @@ -1,7 +1,15 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package ad_api_adaptors +Changelog for package autoware_ad_api_adaptors ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `default_ad_api_helpers` (`#9965 `_) + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Takagi, Isamu +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/system/autoware_default_adapi_helpers/autoware_adapi_adaptors/package.xml b/system/autoware_default_adapi_helpers/autoware_adapi_adaptors/package.xml index fa2f632f445a7..2febc33a7db47 100644 --- a/system/autoware_default_adapi_helpers/autoware_adapi_adaptors/package.xml +++ b/system/autoware_default_adapi_helpers/autoware_adapi_adaptors/package.xml @@ -2,7 +2,7 @@ autoware_adapi_adaptors - 0.40.0 + 0.41.0 The adapi_adaptors package Takagi, Isamu Ryohsuke Mitsudome diff --git a/system/autoware_default_adapi_helpers/autoware_adapi_visualizers/CHANGELOG.rst b/system/autoware_default_adapi_helpers/autoware_adapi_visualizers/CHANGELOG.rst index d44fe830e75db..85f8701a228a7 100644 --- a/system/autoware_default_adapi_helpers/autoware_adapi_visualizers/CHANGELOG.rst +++ b/system/autoware_default_adapi_helpers/autoware_adapi_visualizers/CHANGELOG.rst @@ -1,7 +1,15 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package ad_api_visualizers +Changelog for package autoware_ad_api_visualizers ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `default_ad_api_helpers` (`#9965 `_) + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Takagi, Isamu +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/system/autoware_default_adapi_helpers/autoware_adapi_visualizers/package.xml b/system/autoware_default_adapi_helpers/autoware_adapi_visualizers/package.xml index a51e5b0b80b32..26da09537239e 100644 --- a/system/autoware_default_adapi_helpers/autoware_adapi_visualizers/package.xml +++ b/system/autoware_default_adapi_helpers/autoware_adapi_visualizers/package.xml @@ -2,7 +2,7 @@ autoware_adapi_visualizers - 0.40.0 + 0.41.0 The adapi_visualizers package Takagi, Isamu Ryohsuke Mitsudome diff --git a/system/autoware_default_adapi_helpers/autoware_adapi_visualizers/setup.py b/system/autoware_default_adapi_helpers/autoware_adapi_visualizers/setup.py index ee38c2feb0670..57d7adc3ddd35 100644 --- a/system/autoware_default_adapi_helpers/autoware_adapi_visualizers/setup.py +++ b/system/autoware_default_adapi_helpers/autoware_adapi_visualizers/setup.py @@ -11,7 +11,7 @@ setup( name=package_name, - version="0.40.0", + version="0.41.0", packages=[package_name], data_files=[ ("share/ament_index/resource_index/packages", [f"resource/{package_name}"]), diff --git a/system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/CHANGELOG.rst b/system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/CHANGELOG.rst index 819a580c87f43..2028d4b4cdbcc 100644 --- a/system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/CHANGELOG.rst +++ b/system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/CHANGELOG.rst @@ -1,7 +1,15 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package automatic_pose_initializer +Changelog for package autoware_automatic_pose_initializer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `default_ad_api_helpers` (`#9965 `_) + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Takagi, Isamu +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/package.xml b/system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/package.xml index 606d0237b2d5d..7a0613dd1168d 100644 --- a/system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/package.xml +++ b/system/autoware_default_adapi_helpers/autoware_automatic_pose_initializer/package.xml @@ -2,7 +2,7 @@ autoware_automatic_pose_initializer - 0.40.0 + 0.41.0 The automatic_pose_initializer package Takagi, Isamu Ryohsuke Mitsudome diff --git a/system/autoware_diagnostic_graph_aggregator/CHANGELOG.rst b/system/autoware_diagnostic_graph_aggregator/CHANGELOG.rst index c396519a9467b..79b2dd9ff7345 100644 --- a/system/autoware_diagnostic_graph_aggregator/CHANGELOG.rst +++ b/system/autoware_diagnostic_graph_aggregator/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package autoware_diagnostic_graph_aggregator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware` prefix for `component_state_monitor` and its dependencies (`#9961 `_) +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/system/autoware_diagnostic_graph_aggregator/package.xml b/system/autoware_diagnostic_graph_aggregator/package.xml index 33d7dfdff9637..24a850760153a 100644 --- a/system/autoware_diagnostic_graph_aggregator/package.xml +++ b/system/autoware_diagnostic_graph_aggregator/package.xml @@ -2,7 +2,7 @@ autoware_diagnostic_graph_aggregator - 0.40.0 + 0.41.0 The diagnostic_graph_aggregator package Takagi, Isamu Junya Sasaki diff --git a/system/autoware_diagnostic_graph_utils/CHANGELOG.rst b/system/autoware_diagnostic_graph_utils/CHANGELOG.rst index 857671f77fd94..e4c93b3283b6c 100644 --- a/system/autoware_diagnostic_graph_utils/CHANGELOG.rst +++ b/system/autoware_diagnostic_graph_utils/CHANGELOG.rst @@ -1,7 +1,13 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package diagnostic_graph_utils +Changelog for package autoware_diagnostic_graph_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `diagnostic_graph_utils` (`#9968 `_) +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/system/autoware_diagnostic_graph_utils/package.xml b/system/autoware_diagnostic_graph_utils/package.xml index 57e35d149bc0a..527fa1a201e05 100644 --- a/system/autoware_diagnostic_graph_utils/package.xml +++ b/system/autoware_diagnostic_graph_utils/package.xml @@ -2,7 +2,7 @@ autoware_diagnostic_graph_utils - 0.40.0 + 0.41.0 The autoware_diagnostic_graph_utils package Takagi, Isamu Junya Sasaki diff --git a/system/autoware_dummy_diag_publisher/CHANGELOG.rst b/system/autoware_dummy_diag_publisher/CHANGELOG.rst index 4652837056220..dfbb265f511e1 100644 --- a/system/autoware_dummy_diag_publisher/CHANGELOG.rst +++ b/system/autoware_dummy_diag_publisher/CHANGELOG.rst @@ -1,7 +1,18 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package dummy_diag_publisher +Changelog for package autoware_dummy_diag_publisher ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* fix(autoware_dummy_diag_publisher): add autowre prefix (`#9958 `_) + * fic: add autoare\_ prefix + * fix: add autoare\_ prefix codeowner + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Fumiya Watanabe, TetsuKawa + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/system/autoware_dummy_diag_publisher/package.xml b/system/autoware_dummy_diag_publisher/package.xml index d9e212f922102..0b45cc9643df5 100644 --- a/system/autoware_dummy_diag_publisher/package.xml +++ b/system/autoware_dummy_diag_publisher/package.xml @@ -2,7 +2,7 @@ autoware_dummy_diag_publisher - 0.40.0 + 0.41.0 The dummy_diag_publisher ROS 2 package Fumihito Ito TetsuKawa diff --git a/system/autoware_dummy_infrastructure/CHANGELOG.rst b/system/autoware_dummy_infrastructure/CHANGELOG.rst index f42190ddc4b82..f59db749a4bc9 100644 --- a/system/autoware_dummy_infrastructure/CHANGELOG.rst +++ b/system/autoware_dummy_infrastructure/CHANGELOG.rst @@ -2,6 +2,31 @@ Changelog for package autoware_dummy_infrastructure ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `dummy_infrastructure` (`#9969 `_) + * feat(dummy_infrastructure): apply `autoware\_` prefix (see below): + Note: + * In this commit, I did not organize a folder structure. + The folder structure will be organized in the next some commits. + * The changes will follow the Autoware's guideline as below: + - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder + * rename(dummy_infrastructure): move a header under `include/autoware` + * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit + * fix(dummy_infrastructure): fix include header path + * To follow the previous commit + * rename: `dummy_infrastructure` => `autoware_dummy_infrastructure` + * bug(autoware_dummy_infrastructure): revert wrongly updated copyrights + * update(autoware_dummy_infrastructure): `README.md` + * update: `CODEOWNERS` + * fix(autoware_dummy_infrastructure): fix package name in CHANGELOG.rst + * docs(autoware_dummy_infrastructure): fix package name in README and package description + --------- + Co-authored-by: Ryohsuke Mitsudome + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/system/autoware_dummy_infrastructure/package.xml b/system/autoware_dummy_infrastructure/package.xml index fd710eb1efeb0..4bfb322dd7fc3 100644 --- a/system/autoware_dummy_infrastructure/package.xml +++ b/system/autoware_dummy_infrastructure/package.xml @@ -2,7 +2,7 @@ autoware_dummy_infrastructure - 0.40.0 + 0.41.0 autoware_dummy_infrastructure Ryohsuke Mitsudome Junya Sasaki diff --git a/system/autoware_duplicated_node_checker/CHANGELOG.rst b/system/autoware_duplicated_node_checker/CHANGELOG.rst index 605012c898598..8bad33913194f 100644 --- a/system/autoware_duplicated_node_checker/CHANGELOG.rst +++ b/system/autoware_duplicated_node_checker/CHANGELOG.rst @@ -1,7 +1,30 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package duplicated_node_checker +Changelog for package autoware_duplicated_node_checker ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `duplicated_node_checker` (`#9970 `_) + * feat(duplicated_node_checker): apply `autoware\_` prefix (see below): + Note: + * In this commit, I did not organize a folder structure. + The folder structure will be organized in the next some commits. + * The changes will follow the Autoware's guideline as below: + - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder + * rename(duplicated_node_checker): move a header under `include/autoware`: + * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit + * fix(duplicated_node_checker): fix include header path + * To follow the previous commit + * rename: `duplicated_node_checker` => `autoware_duplicated_node_checker` + * style(pre-commit): autofix + * bug(autoware_duplicated_node_checker): revert wrongly updated copyrights + * update(autoware_duplicated_node_checker): `README.md` + * update: `CODEOWNERS` + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/system/autoware_duplicated_node_checker/package.xml b/system/autoware_duplicated_node_checker/package.xml index c49d8304f1968..eab99982cccf6 100644 --- a/system/autoware_duplicated_node_checker/package.xml +++ b/system/autoware_duplicated_node_checker/package.xml @@ -2,7 +2,7 @@ autoware_duplicated_node_checker - 0.40.0 + 0.41.0 A package to find out nodes with common names Shumpei Wakabayashi yliuhb diff --git a/system/autoware_hazard_status_converter/CHANGELOG.rst b/system/autoware_hazard_status_converter/CHANGELOG.rst index aca530f3acf9b..176d49e24579c 100644 --- a/system/autoware_hazard_status_converter/CHANGELOG.rst +++ b/system/autoware_hazard_status_converter/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package autoware_hazard_status_converter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `diagnostic_graph_utils` (`#9968 `_) +* feat: apply `autoware\_` prefix for `hazard_status_converter` (`#9971 `_) +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/system/autoware_hazard_status_converter/package.xml b/system/autoware_hazard_status_converter/package.xml index 457f98725843e..ba501e70003d5 100644 --- a/system/autoware_hazard_status_converter/package.xml +++ b/system/autoware_hazard_status_converter/package.xml @@ -2,7 +2,7 @@ autoware_hazard_status_converter - 0.40.0 + 0.41.0 The autoware_hazard_status_converter package Takagi, Isamu Junya Sasaki diff --git a/system/autoware_mrm_comfortable_stop_operator/CHANGELOG.rst b/system/autoware_mrm_comfortable_stop_operator/CHANGELOG.rst index cf423a3d7b158..d4d3af9f3cf56 100644 --- a/system/autoware_mrm_comfortable_stop_operator/CHANGELOG.rst +++ b/system/autoware_mrm_comfortable_stop_operator/CHANGELOG.rst @@ -1,7 +1,26 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package mrm_comfortable_stop_operator +Changelog for package autoware_mrm_comfortable_stop_operator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `mrm_comfortable_stop_operator` (`#10011 `_) + * feat(mrm_comfortable_stop_operator): apply `autoware\_` prefix (see below): + Note: + * In this commit, I did not organize a folder structure. + The folder structure will be organized in the next some commits. + * The changes will follow the Autoware's guideline as below: + - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder + * rename(mrm_comfortable_stop_operator): move a header under `include/autoware` + * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit + * fix(mrm_comfortable_stop_operator): fix include header path + * To follow the previous commit + * rename: `mrm_comfortable_stop_operator` => `autoware_mrm_comfortable_stop_operator` + * update: `CODEOWNERS` + --------- +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/system/autoware_mrm_comfortable_stop_operator/package.xml b/system/autoware_mrm_comfortable_stop_operator/package.xml index 8437a4c926b2d..33746a7d2dda0 100644 --- a/system/autoware_mrm_comfortable_stop_operator/package.xml +++ b/system/autoware_mrm_comfortable_stop_operator/package.xml @@ -2,7 +2,7 @@ autoware_mrm_comfortable_stop_operator - 0.40.0 + 0.41.0 The MRM comfortable stop operator package Makoto Kurihara Tomohito Ando diff --git a/system/autoware_mrm_emergency_stop_operator/CHANGELOG.rst b/system/autoware_mrm_emergency_stop_operator/CHANGELOG.rst index f6dc5499bcb74..125eed07658a4 100644 --- a/system/autoware_mrm_emergency_stop_operator/CHANGELOG.rst +++ b/system/autoware_mrm_emergency_stop_operator/CHANGELOG.rst @@ -1,7 +1,28 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package mrm_emergency_stop_operator +Changelog for package autoware_mrm_emergency_stop_operator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `mrm_emergency_stop_operator` (`#9973 `_) + * feat(mrm_emergency_stop_operator): apply `autoware\_` prefix (see below): + Note: + * In this commit, I did not organize a folder structure. + The folder structure will be organized in the next some commits. + * The changes will follow the Autoware's guideline as below: + - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder + * rename(mrm_emergency_stop_operator): move a header under `include/autoware`: + * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit + * fix(mrm_emergency_stop_operator): fix include header path + * To follow the previous commit + * rename: `mrm_emergency_stop_operator` => `autoware_mrm_emergency_stop_operator` + * bug(autoware_mrm_emergency_stop_operator): revert wrongly updated copyrights + * bug(tier4_system_launch): fix a missing `autoware\_` for `mrm_emergency_stop_operator` + * bug(autoware_mrm_emergency_stop_operator): fix critical bugs that contaminate topic names + --------- +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/system/autoware_mrm_emergency_stop_operator/package.xml b/system/autoware_mrm_emergency_stop_operator/package.xml index fbacf7f0ae063..169c3569b5da2 100644 --- a/system/autoware_mrm_emergency_stop_operator/package.xml +++ b/system/autoware_mrm_emergency_stop_operator/package.xml @@ -2,7 +2,7 @@ autoware_mrm_emergency_stop_operator - 0.40.0 + 0.41.0 The MRM emergency stop operator package Makoto Kurihara Tomohito Ando diff --git a/system/autoware_mrm_handler/CHANGELOG.rst b/system/autoware_mrm_handler/CHANGELOG.rst index d9e6990373f6f..9d39ce3ed10c2 100644 --- a/system/autoware_mrm_handler/CHANGELOG.rst +++ b/system/autoware_mrm_handler/CHANGELOG.rst @@ -1,7 +1,29 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package mrm_handler +Changelog for package autoware_mrm_handler ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `mrm_handler` (`#9974 `_) + * feat(mrm_handler): apply `autoware\_` prefix (see below): + Note: + * In this commit, I did not organize a folder structure. + The folder structure will be organized in the next some commits. + * The changes will follow the Autoware's guideline as below: + - https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder + * rename(mrm_handler): move a header under `include/autoware`: + * Fixes due to this changes for .hpp/.cpp files will be applied in the next commit + * fix(mrm_handler): fix include header path + * To follow the previous commit + * rename: `mrm_handler` => `autoware_mrm_handler` + * bug(tier4_system_launch): fix a missing `autoware\_` for `mrm_handler` + * bug(mrm_handler): revert wrongly updated copyrights + * update(mrm_handler): `README.md` + * bug(autoware_mrm_handler): fix a critical bug that contaminates topic name + --------- +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/system/autoware_mrm_handler/package.xml b/system/autoware_mrm_handler/package.xml index cf70663b81122..92cfef1634bc1 100644 --- a/system/autoware_mrm_handler/package.xml +++ b/system/autoware_mrm_handler/package.xml @@ -2,7 +2,7 @@ autoware_mrm_handler - 0.40.0 + 0.41.0 The mrm_handler ROS 2 package Makoto Kurihara Ryuta Kambe diff --git a/system/autoware_processing_time_checker/CHANGELOG.rst b/system/autoware_processing_time_checker/CHANGELOG.rst index 39bf68af5f415..71e10ad7c579e 100644 --- a/system/autoware_processing_time_checker/CHANGELOG.rst +++ b/system/autoware_processing_time_checker/CHANGELOG.rst @@ -2,6 +2,17 @@ Changelog for package autoware_processing_time_checker ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_processing_time_checker)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_processing_time_checker (`#9921 `_) + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> +* fix(autoware_processing_time_checker): fix bugprone-exception-escape (`#9780 `_) + * fix: bugprone-error + * fix: cpplint + --------- +* Contributors: Fumiya Watanabe, Vishal Chauhan, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/system/autoware_processing_time_checker/package.xml b/system/autoware_processing_time_checker/package.xml index 37f53c94de0d1..ffbdfc85c3cbe 100644 --- a/system/autoware_processing_time_checker/package.xml +++ b/system/autoware_processing_time_checker/package.xml @@ -2,7 +2,7 @@ autoware_processing_time_checker - 0.40.0 + 0.41.0 A package to find out nodes with common names Takayuki Murooka Kosuke Takeuchi diff --git a/system/autoware_system_diagnostic_monitor/CHANGELOG.rst b/system/autoware_system_diagnostic_monitor/CHANGELOG.rst index 3c03aaf85535e..59495adc1b2fa 100644 --- a/system/autoware_system_diagnostic_monitor/CHANGELOG.rst +++ b/system/autoware_system_diagnostic_monitor/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package autoware_system_diagnostic_monitor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware` prefix for `component_state_monitor` and its dependencies (`#9961 `_) +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/system/autoware_system_diagnostic_monitor/package.xml b/system/autoware_system_diagnostic_monitor/package.xml index 48c93e0b18ab2..92e869001ddab 100644 --- a/system/autoware_system_diagnostic_monitor/package.xml +++ b/system/autoware_system_diagnostic_monitor/package.xml @@ -2,7 +2,7 @@ autoware_system_diagnostic_monitor - 0.40.0 + 0.41.0 The autoware_system_diagnostic_monitor package Takagi, Isamu Junya Sasaki diff --git a/system/autoware_system_monitor/CHANGELOG.rst b/system/autoware_system_monitor/CHANGELOG.rst index 0ce1977dfdfa8..226e1c44a292b 100644 --- a/system/autoware_system_monitor/CHANGELOG.rst +++ b/system/autoware_system_monitor/CHANGELOG.rst @@ -1,7 +1,27 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package system_monitor +Changelog for package autoware_system_monitor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `system_monitor` (`#10017 `_) + * feat(system_monitor): apply `autoware\_` prefix (see below): + * The `system_monitor` operates independently from other modules in `autoware.universe`, so the `autoware\_` prefix is added only to the package name. + * The `autoware::` namespace is not used because C language does not support namespaces. + * Headers are not moved under `include/autoware` to maintain compatibility for use outside the `autoware` context. + * For users utilizing this package within `autoware.universe`, only the package name includes the `autoware\_` prefix. + This approach explains the unique namespacing and naming conventions for `system_monitor` compared to other packages. + * bug(system_monitor): fix missing package name update + * rename: `system_monitor` => `autoware_system_monitor` + * style(pre-commit): autofix + * update: `CODEOWNERS` + * bug(autoware_system_monitor): apply missing fix + * update: `CODEOWNERS` + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/system/autoware_system_monitor/package.xml b/system/autoware_system_monitor/package.xml index 23add17adbf6f..0212b4ec61751 100644 --- a/system/autoware_system_monitor/package.xml +++ b/system/autoware_system_monitor/package.xml @@ -2,7 +2,7 @@ autoware_system_monitor - 0.40.0 + 0.41.0 The system_monitor package Fumihito Ito TetsuKawa diff --git a/system/autoware_topic_relay_controller/CHANGELOG.rst b/system/autoware_topic_relay_controller/CHANGELOG.rst new file mode 100644 index 0000000000000..e08d796d12b5d --- /dev/null +++ b/system/autoware_topic_relay_controller/CHANGELOG.rst @@ -0,0 +1,78 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_topic_relay_controller +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_topic_relay_controller): add topic relay controller node (`#9964 `_) + * feat: add node base + * modify: include guard + * feat: delete schema + * feat: delete config + * feat: add subscriber + * modify: add include + * feat: add publisher + * feat: add service + * modify: typo + * style(pre-commit): autofix + * modify: add include memory + * modify: add qos setting + * style(pre-commit): autofix + * feat: add enable_keep_publishing + * style(pre-commit): autofix + * feat: add readme + * style(pre-commit): autofix + * feat: change qos name and add parameter type + * feat: add config and delete arg from launch + * modify: typo + * style(pre-commit): autofix + * modify: add comment + * modify: modify comment + * feat: add maintainer + * modift: change readme param format + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Fumiya Watanabe, TetsuKawa + +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_topic_relay_controller): add topic relay controller node (`#9964 `_) + * feat: add node base + * modify: include guard + * feat: delete schema + * feat: delete config + * feat: add subscriber + * modify: add include + * feat: add publisher + * feat: add service + * modify: typo + * style(pre-commit): autofix + * modify: add include memory + * modify: add qos setting + * style(pre-commit): autofix + * feat: add enable_keep_publishing + * style(pre-commit): autofix + * feat: add readme + * style(pre-commit): autofix + * feat: change qos name and add parameter type + * feat: add config and delete arg from launch + * modify: typo + * style(pre-commit): autofix + * modify: add comment + * modify: modify comment + * feat: add maintainer + * modift: change readme param format + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Fumiya Watanabe, TetsuKawa + +0.40.0 (2025-01-06) +------------------- + +0.39.0 (2024-11-25) +------------------- + +0.38.0 (2024-11-11) +------------------- diff --git a/system/autoware_topic_relay_controller/package.xml b/system/autoware_topic_relay_controller/package.xml index 771c7e632f49a..09cb55d3e250d 100644 --- a/system/autoware_topic_relay_controller/package.xml +++ b/system/autoware_topic_relay_controller/package.xml @@ -2,7 +2,7 @@ autoware_topic_relay_controller - 0.1.0 + 0.41.0 The topic_relay_controller ROS 2 package Makoto Kurihara Tetsuhiro Kawaguchi diff --git a/system/autoware_topic_state_monitor/CHANGELOG.rst b/system/autoware_topic_state_monitor/CHANGELOG.rst index b1faa2cd63683..2eb63f5be43e0 100644 --- a/system/autoware_topic_state_monitor/CHANGELOG.rst +++ b/system/autoware_topic_state_monitor/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package autoware_topic_state_monitor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware` prefix for `component_state_monitor` and its dependencies (`#9961 `_) +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/system/autoware_topic_state_monitor/package.xml b/system/autoware_topic_state_monitor/package.xml index d3a51620f336e..a932d01656ba1 100644 --- a/system/autoware_topic_state_monitor/package.xml +++ b/system/autoware_topic_state_monitor/package.xml @@ -2,7 +2,7 @@ autoware_topic_state_monitor - 0.40.0 + 0.41.0 The autoware_topic_state_monitor package Ryohsuke Mitsudome Junya Sasaki diff --git a/system/autoware_velodyne_monitor/CHANGELOG.rst b/system/autoware_velodyne_monitor/CHANGELOG.rst index 67e7f7732653b..87a23f9e4b660 100644 --- a/system/autoware_velodyne_monitor/CHANGELOG.rst +++ b/system/autoware_velodyne_monitor/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package autoware_velodyne_monitor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `velodyne_monitor` (`#9976 `_) +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" diff --git a/system/autoware_velodyne_monitor/package.xml b/system/autoware_velodyne_monitor/package.xml index 677df93ecde43..daf843c09ef14 100644 --- a/system/autoware_velodyne_monitor/package.xml +++ b/system/autoware_velodyne_monitor/package.xml @@ -2,7 +2,7 @@ autoware_velodyne_monitor - 0.40.0 + 0.41.0 The autoware_velodyne_monitor package Fumihito Ito Junya Sasaki diff --git a/tools/reaction_analyzer/CHANGELOG.rst b/tools/reaction_analyzer/CHANGELOG.rst index f2f1ac255fc06..b1bd59f3f33de 100644 --- a/tools/reaction_analyzer/CHANGELOG.rst +++ b/tools/reaction_analyzer/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package reaction_analyzer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/tools/reaction_analyzer/package.xml b/tools/reaction_analyzer/package.xml index 540376e032743..9d1928813f07e 100644 --- a/tools/reaction_analyzer/package.xml +++ b/tools/reaction_analyzer/package.xml @@ -2,7 +2,7 @@ reaction_analyzer - 0.40.0 + 0.41.0 Analyzer that measures reaction times of the nodes Berkay Karaman diff --git a/vehicle/autoware_accel_brake_map_calibrator/CHANGELOG.rst b/vehicle/autoware_accel_brake_map_calibrator/CHANGELOG.rst index cbd3907bd854a..3936c60ca160b 100644 --- a/vehicle/autoware_accel_brake_map_calibrator/CHANGELOG.rst +++ b/vehicle/autoware_accel_brake_map_calibrator/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package autoware_accel_brake_map_calibrator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_accel_brake_map_calibrator)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_accel_brake_map_calibrator (`#9923 `_) + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> +* Contributors: Fumiya Watanabe, Vishal Chauhan + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/vehicle/autoware_accel_brake_map_calibrator/package.xml b/vehicle/autoware_accel_brake_map_calibrator/package.xml index f166bd119ed6a..78c3b518057de 100644 --- a/vehicle/autoware_accel_brake_map_calibrator/package.xml +++ b/vehicle/autoware_accel_brake_map_calibrator/package.xml @@ -2,7 +2,7 @@ autoware_accel_brake_map_calibrator - 0.40.0 + 0.41.0 The accel_brake_map_calibrator Tomoya Kimura Taiki Tanaka diff --git a/vehicle/autoware_external_cmd_converter/CHANGELOG.rst b/vehicle/autoware_external_cmd_converter/CHANGELOG.rst index ddbd655a9c34f..dbb5e1d429613 100644 --- a/vehicle/autoware_external_cmd_converter/CHANGELOG.rst +++ b/vehicle/autoware_external_cmd_converter/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_external_cmd_converter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/vehicle/autoware_external_cmd_converter/package.xml b/vehicle/autoware_external_cmd_converter/package.xml index eb44058775a3f..b28b9b6f3dd24 100644 --- a/vehicle/autoware_external_cmd_converter/package.xml +++ b/vehicle/autoware_external_cmd_converter/package.xml @@ -2,7 +2,7 @@ autoware_external_cmd_converter - 0.40.0 + 0.41.0 The autoware_external_cmd_converter package Takamasa Horibe Eiki Nagata diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/CHANGELOG.rst b/vehicle/autoware_raw_vehicle_cmd_converter/CHANGELOG.rst index de088bb8d5a76..630698c89bbbe 100644 --- a/vehicle/autoware_raw_vehicle_cmd_converter/CHANGELOG.rst +++ b/vehicle/autoware_raw_vehicle_cmd_converter/CHANGELOG.rst @@ -2,6 +2,23 @@ Changelog for package autoware_raw_vehicle_cmd_converter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_raw_vehicle_cmd_converter)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_raw_vehicle_cmd_converter (`#9924 `_) + feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files vehicle/autoware_raw_vehicle_cmd_converter + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> +* fix(raw_veihicle_converter): fix too long line (`#9716 `_) +* feat(raw_vehicle_cmd_converter): add vehicle adaptor (`#8782 `_) + * feat(raw_vehicle_cmd_converter): add vehicle adaptor + sub operation status + * feat(raw_vehicle_cmd_converter): publish vehicle adaptor output + * use control horizon + * revert carla + * update docs + --------- +* Contributors: Fumiya Watanabe, Kosuke Takeuchi, Vishal Chauhan + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/package.xml b/vehicle/autoware_raw_vehicle_cmd_converter/package.xml index 0abb77644920a..2a200ea92967d 100644 --- a/vehicle/autoware_raw_vehicle_cmd_converter/package.xml +++ b/vehicle/autoware_raw_vehicle_cmd_converter/package.xml @@ -2,7 +2,7 @@ autoware_raw_vehicle_cmd_converter - 0.40.0 + 0.41.0 The autoware_raw_vehicle_cmd_converter package Takamasa Horibe Tanaka Taiki diff --git a/vehicle/autoware_steer_offset_estimator/CHANGELOG.rst b/vehicle/autoware_steer_offset_estimator/CHANGELOG.rst index 4e4f9c1a39a66..b2e8e642f936a 100644 --- a/vehicle/autoware_steer_offset_estimator/CHANGELOG.rst +++ b/vehicle/autoware_steer_offset_estimator/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package autoware_steer_offset_estimator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(autoware_steer_offset_estimator)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_steer_offset_estimator (`#9926 `_) + feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files vehicle/autoware_steer_offset_estimator + Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> +* Contributors: Fumiya Watanabe, Vishal Chauhan + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/vehicle/autoware_steer_offset_estimator/package.xml b/vehicle/autoware_steer_offset_estimator/package.xml index e098fbdee6f28..5673025dbb54a 100644 --- a/vehicle/autoware_steer_offset_estimator/package.xml +++ b/vehicle/autoware_steer_offset_estimator/package.xml @@ -1,7 +1,7 @@ autoware_steer_offset_estimator - 0.40.0 + 0.41.0 The steer_offset_estimator Taiki Tanaka Apache License 2.0 diff --git a/visualization/autoware_bag_time_manager_rviz_plugin/CHANGELOG.rst b/visualization/autoware_bag_time_manager_rviz_plugin/CHANGELOG.rst index b9a32e20f76c4..226a8fa910ba8 100644 --- a/visualization/autoware_bag_time_manager_rviz_plugin/CHANGELOG.rst +++ b/visualization/autoware_bag_time_manager_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,15 @@ Changelog for package autoware_bag_time_manager_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: apply `autoware\_` prefix for `bag_time_manager_rviz_plugin` (`#9986 `_) + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: SakodaShintaro + Co-authored-by: Ryohsuke Mitsudome +* Contributors: Fumiya Watanabe, Junya Sasaki + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/visualization/autoware_bag_time_manager_rviz_plugin/package.xml b/visualization/autoware_bag_time_manager_rviz_plugin/package.xml index 916d1b4674620..481eac1ac8f21 100644 --- a/visualization/autoware_bag_time_manager_rviz_plugin/package.xml +++ b/visualization/autoware_bag_time_manager_rviz_plugin/package.xml @@ -2,7 +2,7 @@ autoware_bag_time_manager_rviz_plugin - 0.40.0 + 0.41.0 Rviz plugin to publish and control the ros bag Taiki Tanaka Junya Sasaki diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CHANGELOG.rst b/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CHANGELOG.rst index 91b2ce31af3bf..01fe650191a47 100644 --- a/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CHANGELOG.rst +++ b/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_mission_details_overlay_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml b/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml index 82b4c10194131..7323b3b6594c5 100644 --- a/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml +++ b/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml @@ -2,7 +2,7 @@ autoware_mission_details_overlay_rviz_plugin - 0.40.0 + 0.41.0 RViz2 plugin for 2D overlays for mission details in the 3D view. Mainly a port of the JSK overlay plugin (https://github.com/jsk-ros-pkg/jsk_visualization). diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CHANGELOG.rst b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CHANGELOG.rst index 44c9901bda3ec..0f3b61630d790 100644 --- a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CHANGELOG.rst +++ b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,15 @@ Changelog for package autoware_overlay_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* fix(autoware_overlay_rviz_plugin): fix clang-tidy errors (`#9627 `_) + * fix: clang-tidy errors + * fix: clang-fmt + --------- +* Contributors: Fumiya Watanabe, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml index 86bab15660d4d..fed43c91ddcdb 100644 --- a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml +++ b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml @@ -2,7 +2,7 @@ autoware_overlay_rviz_plugin - 0.40.0 + 0.41.0 RViz2 plugin for 2D overlays in the 3D view. Mainly a port of the JSK overlay plugin (https://github.com/jsk-ros-pkg/jsk_visualization). diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/CHANGELOG.rst b/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/CHANGELOG.rst new file mode 100644 index 0000000000000..bbcb0616d9ca2 --- /dev/null +++ b/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/CHANGELOG.rst @@ -0,0 +1,40 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_string_stamped_rviz_plugin +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* chore(autoware_string_stamped_overlay_rviz_plugin): fix version in package.xml (`#9874 `_) +* feat(autoware_overlay_rviz_plugin): add plugin to show string stamped (`#9683 `_) + * feat(autoware_overlay_rviz_plugin): add plugin to show string stamped + * fix + * better visualization + * update + * fix cpp check and typo + * fix + * fix + --------- +* Contributors: Fumiya Watanabe, Takayuki Murooka + +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* chore(autoware_string_stamped_overlay_rviz_plugin): fix version in package.xml (`#9874 `_) +* feat(autoware_overlay_rviz_plugin): add plugin to show string stamped (`#9683 `_) + * feat(autoware_overlay_rviz_plugin): add plugin to show string stamped + * fix + * better visualization + * update + * fix cpp check and typo + * fix + * fix + --------- +* Contributors: Fumiya Watanabe, Takayuki Murooka + +0.40.0 (2025-01-06) +------------------- + +0.39.0 (2024-11-25) +------------------- + +0.38.0 (2024-11-11) +------------------- diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/package.xml b/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/package.xml index faef2f674832e..a7267c3dc2896 100644 --- a/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/package.xml +++ b/visualization/autoware_overlay_rviz_plugin/autoware_string_stamped_overlay_rviz_plugin/package.xml @@ -2,7 +2,7 @@ autoware_string_stamped_rviz_plugin - 0.40.0 + 0.41.0 RViz2 plugin for 2D overlays in the 3D view. Mainly a port of the JSK overlay plugin (https://github.com/jsk-ros-pkg/jsk_visualization). diff --git a/visualization/autoware_perception_rviz_plugin/CHANGELOG.rst b/visualization/autoware_perception_rviz_plugin/CHANGELOG.rst index a1b325e441fc0..6f585a963c1c8 100644 --- a/visualization/autoware_perception_rviz_plugin/CHANGELOG.rst +++ b/visualization/autoware_perception_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package autoware_perception_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/visualization/autoware_perception_rviz_plugin/package.xml b/visualization/autoware_perception_rviz_plugin/package.xml index b3d2d69a34f35..000a50c8c9428 100644 --- a/visualization/autoware_perception_rviz_plugin/package.xml +++ b/visualization/autoware_perception_rviz_plugin/package.xml @@ -2,7 +2,7 @@ autoware_perception_rviz_plugin - 0.40.0 + 0.41.0 Contains plugins to visualize object detection outputs Apex.AI, Inc. Taiki Tanaka diff --git a/visualization/tier4_adapi_rviz_plugin/CHANGELOG.rst b/visualization/tier4_adapi_rviz_plugin/CHANGELOG.rst index 32c8d0a621304..41232c228872d 100644 --- a/visualization/tier4_adapi_rviz_plugin/CHANGELOG.rst +++ b/visualization/tier4_adapi_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package tier4_adapi_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat: operation mode debug panel (`#8933 `_) +* Contributors: Fumiya Watanabe, Takagi, Isamu + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/visualization/tier4_adapi_rviz_plugin/package.xml b/visualization/tier4_adapi_rviz_plugin/package.xml index da1af7b150c70..eaf02a0653d49 100644 --- a/visualization/tier4_adapi_rviz_plugin/package.xml +++ b/visualization/tier4_adapi_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_adapi_rviz_plugin - 0.40.0 + 0.41.0 The autoware adapi rviz plugin package Takagi, Isamu Hiroki OTA diff --git a/visualization/tier4_camera_view_rviz_plugin/CHANGELOG.rst b/visualization/tier4_camera_view_rviz_plugin/CHANGELOG.rst index 99d51e3064524..3dc5b3cf668f3 100644 --- a/visualization/tier4_camera_view_rviz_plugin/CHANGELOG.rst +++ b/visualization/tier4_camera_view_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,15 @@ Changelog for package tier4_camera_view_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* fix(tier4_camera_view_rviz_plugin): fix bugprone-parent-virtual-call (`#9815 `_) + * fix:bugprone-error + * fix:fmt + --------- +* Contributors: Fumiya Watanabe, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/visualization/tier4_camera_view_rviz_plugin/package.xml b/visualization/tier4_camera_view_rviz_plugin/package.xml index b25aac8a74570..0a1d30c509aab 100644 --- a/visualization/tier4_camera_view_rviz_plugin/package.xml +++ b/visualization/tier4_camera_view_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_camera_view_rviz_plugin - 0.40.0 + 0.41.0 The autoware camera view rviz plugin package Yuxuan Liu Makoto Yabuta diff --git a/visualization/tier4_datetime_rviz_plugin/CHANGELOG.rst b/visualization/tier4_datetime_rviz_plugin/CHANGELOG.rst index 155d36c369d77..76211d6be48f9 100644 --- a/visualization/tier4_datetime_rviz_plugin/CHANGELOG.rst +++ b/visualization/tier4_datetime_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package tier4_datetime_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/visualization/tier4_datetime_rviz_plugin/package.xml b/visualization/tier4_datetime_rviz_plugin/package.xml index 80c19ec0957fd..5ade60b0d3f3c 100644 --- a/visualization/tier4_datetime_rviz_plugin/package.xml +++ b/visualization/tier4_datetime_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_datetime_rviz_plugin - 0.40.0 + 0.41.0 The tier4_datetime_rviz_plugin package Takagi, Isamu Apache License 2.0 diff --git a/visualization/tier4_localization_rviz_plugin/CHANGELOG.rst b/visualization/tier4_localization_rviz_plugin/CHANGELOG.rst index 4e9985286862b..7d7ab591b1544 100644 --- a/visualization/tier4_localization_rviz_plugin/CHANGELOG.rst +++ b/visualization/tier4_localization_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package tier4_localization_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/visualization/tier4_localization_rviz_plugin/package.xml b/visualization/tier4_localization_rviz_plugin/package.xml index e3f200aeb7111..2c3fef66f43f3 100644 --- a/visualization/tier4_localization_rviz_plugin/package.xml +++ b/visualization/tier4_localization_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_localization_rviz_plugin - 0.40.0 + 0.41.0 The tier4_localization_rviz_plugin package Takagi, Isamu Takamasa Horibe diff --git a/visualization/tier4_planning_factor_rviz_plugin/CHANGELOG.rst b/visualization/tier4_planning_factor_rviz_plugin/CHANGELOG.rst new file mode 100644 index 0000000000000..e62ea3267b362 --- /dev/null +++ b/visualization/tier4_planning_factor_rviz_plugin/CHANGELOG.rst @@ -0,0 +1,32 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package tier4_planning_factor_rviz_plugin +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(rviz): add new plugin to visualize planning factor (`#9999 `_) + * feat(rviz): add new plugin to visualize planning factor + * feat(rviz): show safety factors + * chore: add maintainer + * feat: show detail + --------- +* Contributors: Fumiya Watanabe, Satoshi OTA + +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* feat(rviz): add new plugin to visualize planning factor (`#9999 `_) + * feat(rviz): add new plugin to visualize planning factor + * feat(rviz): show safety factors + * chore: add maintainer + * feat: show detail + --------- +* Contributors: Fumiya Watanabe, Satoshi OTA + +0.40.0 (2025-01-06) +------------------- + +0.39.0 (2024-11-25) +------------------- + +0.38.0 (2024-11-11) +------------------- diff --git a/visualization/tier4_planning_factor_rviz_plugin/package.xml b/visualization/tier4_planning_factor_rviz_plugin/package.xml index f1d2ce7df6ef4..6e703458782c4 100644 --- a/visualization/tier4_planning_factor_rviz_plugin/package.xml +++ b/visualization/tier4_planning_factor_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_planning_factor_rviz_plugin - 0.40.0 + 0.41.0 The tier4_planning_factor_rviz_plugin package Satoshi Ota Mamoru Sobue diff --git a/visualization/tier4_planning_rviz_plugin/CHANGELOG.rst b/visualization/tier4_planning_rviz_plugin/CHANGELOG.rst index 8faac0b6ac8e7..5d6e8fa8a819b 100644 --- a/visualization/tier4_planning_rviz_plugin/CHANGELOG.rst +++ b/visualization/tier4_planning_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package tier4_planning_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/visualization/tier4_planning_rviz_plugin/package.xml b/visualization/tier4_planning_rviz_plugin/package.xml index d615878f91354..352e3bfbf5840 100644 --- a/visualization/tier4_planning_rviz_plugin/package.xml +++ b/visualization/tier4_planning_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_planning_rviz_plugin - 0.40.0 + 0.41.0 The tier4_planning_rviz_plugin package Yukihiro Saito Takayuki Murooka diff --git a/visualization/tier4_state_rviz_plugin/CHANGELOG.rst b/visualization/tier4_state_rviz_plugin/CHANGELOG.rst index 243d3c28733d7..bc1cc3050c97b 100644 --- a/visualization/tier4_state_rviz_plugin/CHANGELOG.rst +++ b/visualization/tier4_state_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package tier4_state_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- +* Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base +* fix(tier4_state_rviz_plugin): fix bugprone-integer-division (`#9628 `_) + fix: bugprone-integer-division +* Contributors: Fumiya Watanabe, kobayu858 + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/visualization/tier4_state_rviz_plugin/package.xml b/visualization/tier4_state_rviz_plugin/package.xml index f5f5fa8b9c0c1..7b1f08ceef6eb 100644 --- a/visualization/tier4_state_rviz_plugin/package.xml +++ b/visualization/tier4_state_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_state_rviz_plugin - 0.40.0 + 0.41.0 The autoware state rviz plugin package Hiroki OTA Takagi, Isamu diff --git a/visualization/tier4_system_rviz_plugin/CHANGELOG.rst b/visualization/tier4_system_rviz_plugin/CHANGELOG.rst index a895b7135e0c8..91792789b5d42 100644 --- a/visualization/tier4_system_rviz_plugin/CHANGELOG.rst +++ b/visualization/tier4_system_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package tier4_system_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/visualization/tier4_system_rviz_plugin/package.xml b/visualization/tier4_system_rviz_plugin/package.xml index 5b768aa077120..9493e5b1c45a3 100644 --- a/visualization/tier4_system_rviz_plugin/package.xml +++ b/visualization/tier4_system_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_system_rviz_plugin - 0.40.0 + 0.41.0 The tier4_vehicle_rviz_plugin package Koji Minoda Apache License 2.0 diff --git a/visualization/tier4_traffic_light_rviz_plugin/CHANGELOG.rst b/visualization/tier4_traffic_light_rviz_plugin/CHANGELOG.rst index 72e4ec068910b..cb9a5e8225c04 100644 --- a/visualization/tier4_traffic_light_rviz_plugin/CHANGELOG.rst +++ b/visualization/tier4_traffic_light_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package tier4_traffic_light_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/visualization/tier4_traffic_light_rviz_plugin/package.xml b/visualization/tier4_traffic_light_rviz_plugin/package.xml index b6645782290c1..3741d1ea0c46b 100644 --- a/visualization/tier4_traffic_light_rviz_plugin/package.xml +++ b/visualization/tier4_traffic_light_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_traffic_light_rviz_plugin - 0.40.0 + 0.41.0 The autoware state rviz plugin package Satoshi OTA Apache License 2.0 diff --git a/visualization/tier4_vehicle_rviz_plugin/CHANGELOG.rst b/visualization/tier4_vehicle_rviz_plugin/CHANGELOG.rst index 45d81a4646466..9deceeff4d0b6 100644 --- a/visualization/tier4_vehicle_rviz_plugin/CHANGELOG.rst +++ b/visualization/tier4_vehicle_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package tier4_vehicle_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.41.0 (2025-01-29) +------------------- + 0.40.0 (2024-12-12) ------------------- * Merge branch 'main' into release-0.40.0 diff --git a/visualization/tier4_vehicle_rviz_plugin/package.xml b/visualization/tier4_vehicle_rviz_plugin/package.xml index 4124ed2d514a3..91c34ec8ca5b4 100644 --- a/visualization/tier4_vehicle_rviz_plugin/package.xml +++ b/visualization/tier4_vehicle_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_vehicle_rviz_plugin - 0.40.0 + 0.41.0 The tier4_vehicle_rviz_plugin package Yukihiro Saito Apache License 2.0 From fcd1c7bdbb7bef749b57e8c13ba255fa4e7de2ae Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 29 Jan 2025 12:15:31 +0900 Subject: [PATCH 332/334] feat(simple_planning_simulator): change acc state calculation of SimModelDelaySteerVel (#10030) Signed-off-by: kosuke55 --- .../vehicle_model/sim_model_delay_steer_vel.hpp | 1 - .../vehicle_model/sim_model_delay_steer_vel.cpp | 4 ++-- 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.hpp b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.hpp index d878ef01c0536..fa3eafa78a710 100644 --- a/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.hpp +++ b/simulator/autoware_simple_planning_simulator/include/autoware/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.hpp @@ -79,7 +79,6 @@ class SimModelDelaySteerVel : public SimModelInterface const double steer_lim_; //!< @brief steering limit [rad] const double steer_rate_lim_; //!< @brief steering angular velocity limit [rad/s] const double wheelbase_; //!< @brief vehicle wheelbase length [m] - double prev_vx_ = 0.0; double current_ax_ = 0.0; std::deque vx_input_queue_; //!< @brief buffer for velocity command diff --git a/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.cpp b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.cpp index 66d42d4719bf0..89d9b573fa96d 100644 --- a/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.cpp +++ b/simulator/autoware_simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.cpp @@ -83,9 +83,9 @@ void SimModelDelaySteerVel::update(const double & dt) delayed_input(IDX_U::STEER_DES) = steer_input_queue_.front(); steer_input_queue_.pop_front(); // do not use deadzone_delta_steer (Steer IF does not exist in this model) + const double prev_vx = state_(IDX::VX); updateRungeKutta(dt, delayed_input); - current_ax_ = (input_(IDX_U::VX_DES) - prev_vx_) / dt; - prev_vx_ = input_(IDX_U::VX_DES); + current_ax_ = (state_(IDX::VX) - prev_vx) / dt; } void SimModelDelaySteerVel::initializeInputQueue(const double & dt) From 73988a666a07c42958f6eeb0bd310f20f84d07e8 Mon Sep 17 00:00:00 2001 From: Yutaka Kondo Date: Wed, 22 Jan 2025 18:52:38 +0900 Subject: [PATCH 333/334] chore(sync-files.yaml): not synchronize `github-release.yaml` (#1776) not sync github-release Signed-off-by: Yutaka Kondo --- .github/sync-files.yaml | 1 - 1 file changed, 1 deletion(-) diff --git a/.github/sync-files.yaml b/.github/sync-files.yaml index 4c09e072766fa..8afb7671215f4 100644 --- a/.github/sync-files.yaml +++ b/.github/sync-files.yaml @@ -15,7 +15,6 @@ - source: .github/workflows/comment-on-pr.yaml - source: .github/workflows/delete-closed-pr-docs.yaml - source: .github/workflows/deploy-docs.yaml - - source: .github/workflows/github-release.yaml - source: .github/workflows/pre-commit.yaml - source: .github/workflows/pre-commit-optional.yaml - source: .github/workflows/pre-commit-optional-autoupdate.yaml From 8e97fd67828e50b9fbbf62f3341043bf69c039cf Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Wed, 29 Jan 2025 14:20:55 +0900 Subject: [PATCH 334/334] fix CODEOWNERS Signed-off-by: Fumiya Watanabe --- .github/_CODEOWNERS | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/_CODEOWNERS b/.github/_CODEOWNERS index 92f9e70eb2e6d..f9e39eaeb63e4 100644 --- a/.github/_CODEOWNERS +++ b/.github/_CODEOWNERS @@ -198,7 +198,7 @@ sensing/autoware_radar_static_pointcloud_filter/** satoshi.tanaka@tier4.jp shuns sensing/autoware_radar_threshold_filter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp sensing/autoware_radar_tracks_noise_filter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp sensing/livox/autoware_livox_tag_filter/** kenzo.lobos@tier4.jp ryohsuke.mitsudome@tier4.jp -sensing/vehicle_velocity_converter/** ryu.yamamoto@tier4.jp +sensing/autoware_vehicle_velocity_converter/** ryu.yamamoto@tier4.jp simulator/autoware_carla_interface/** maxime.clement@tier4.jp mradityagio@gmail.com simulator/dummy_perception_publisher/** yukihiro.saito@tier4.jp simulator/fault_injection/** keisuke.shima@tier4.jp

3EU}&_!zM$N0ulV&3`ZJP8wqw7Nvj=eR32P`a z8C+fnC!Fc*vD+SaGhLs*SX6coC|Z|lAvJg=d=Q;#GBVB9PRx*muqR(tdVnd%nuN1K zeqnlgp>g@l3lE41T-_ezI6n#cif0mMRuWx2Y@8l5zEderNO5&$JQ1tU(RS4X<5YtG z9ylm5Y;V}%J9zJ7>&q=fU3ci{$(nd>-M~NW-D{Es0Nenu)XrvL%}gm zrj+;%pH=n*)u)G|(OlIA9f1Q~lTj}8+w~r~ha#RMP)6Uvfctag9IFYTzelCj`Y!Z? zJD@r~a^$zovLlPJI&JRubEnc=?MF6Io}cW0Hx2!f_Z`0+Xlq`x+7! zzJ+x>UL)J^#|O33LL5P;55=YpBFPlJsAcp+Vtup?$=TZE*$NxTg|;Td?aGS%IGxAW zB3&)hJ2_?6>*8Ns6TL+q9!|T5zroRuZ05!V{-!_n9x_z;vX^Q0)X%nmyFJ+sqPS0$ zLpSzUUtK2UJ)dox1+!rho1L`czN4HHNic93%l+ll9xi}L;bq4v$DR0a*{MrRVU_>v zMl$S+dLd_WvN?{F%isWQZS#H!j1=M|MD%>e3QF4y+{(6=2Ra{_CZes%Z7nJVNZg*h zTfSql4m{H@AQ-GN8ydI(rlN?HdNL-&&kmSYkM~xGp(f21NK8phe!yiN9EnHyyPkrO z=`JOt%<3V|wJ-G^pIF+cX=#jUX72%kawvYX9Oi}CvW?}^#kolrKe}hJoz)z}#J5pm zk2WB$-3@QgbnCiUf%~8W1E^E-KltgFzIvyVD8HS^a=Z~!gm?Hab32(#fBc`%k5OhN zOUVOJ?(=04q_C~ci@`v4TxeQH!#0tBkE`GZ`+KJuzO$ik9ppBW1X(XOB%XT5of6(> ziUwN!qxWa&zrhA^oH-+~z!QTj`S)MB)+2(GhsnyQ`#TN{O-D(}D9o1(8t%*rq#WuZ z0c3NM5ozw1j3|dTswf^rmtJ%6*J;3=mrKpp=|x;@EA=e0Lc%pSQ=OA37vh4DyALZj z%KR+1H>?w#ZzSSUsmjj{mN{gxyk64G4G9?8YW|(Mu4>+mwYK6fdT#@u;C*}2n{{GAnlGY7#$Gy=SW zKEVCWobrlHh>@tiX-XtOch%8dJ#2sah_!M}dP!v>N2vW*?YwLBZc!sg33dr{mve-T zTjKM~Kl0V(;j4D9inrbr zODDpmN)NghjUR0L3tyf)5uA1QyU1k5;vetf87;{kM(;Yij5Cf-n*|MH9Lk3>`i+8Dpe zJc#z$qKE%JztB5oOYm>Lr2^dcC3Ki}VJnMt*u+v3yTuG_9YL8^@IDwEt}+&6K%s2_ zD=m}eiPNO58!}s{4Y>m4d))=@qrz%MNa&>)bz6+8PHgkxhq7XuK50;G5MVs|JA)WD zp=8BlEl@01Q0UvcbXfUB!7QyQozORm74ZN&MNzM_*|Vw4O7D3LkP1f`I{Oa&xgAR zi=T?35yFIF1B%%$0*I_CDj!EEVJ(mzCK5Yc>y*OXoT6{zeQCRr!TX{#aZpt& zhx9eaLLfvqKYU&lFfXR)M-Al?b4JZxUYWLP+_V-xwrY>p4!%IoNLs+(69{|lku<}n zmbDz=_ei?8u|Z${)zyUgWNn5Alt(iH^y~xF%wdj@0M|ew#i<7E zT#t_fXO2dmXCg@SxTEKX1P{!70#)8Vsr&!PU(a*?!EZ;%m z{EN_tlG7a!_`vQvJjQ_94*w6%ijOw$b1J2UgPK>DAUObtveW}O4M@N7z zAvn5_hJ;64F{KnY!Vd2;IfFJTwvSK<(T!Wu`DCcGO2Kekg#ev4MM8e*3=Bd4ZF~M( zSKWIg^jWjk5ZaLdogaxI3Y7YCI<07Rf|GjcHVLK26=r{Qc1KEa9*zE+78inZTeX4b z184yNP-}C%I%3{P-gk?R?$>=Iy&L+{VkUOr6@H&!aVeLSp4AI;-bGgu}=TRRnBaj z%~iBeB|Qa!+_n+p(f;nPOiSe` zt?&Y@h_a)XO{iY++{+eHk}oaiYIh5_`Cllt({8dFYtVjlr|>lPK; z+<)8w@&~BNU%o!f2?|xKc(h@1xQL$b+g*9Qc5Vc175}|3JVNnb97H43`W9aBxoBRX zSa*7UjqsUKPA9MWHnxD<`XyBNs@>$af_->K(g00&JJR^#FB%;y9=)SG{7kH(WNP|{ z#*-fE4p#q3{omsAr~bC#uU>|wQr)iyMzdbJ4*lk8f>|PV{a)@9PEjdqOh_BUzaA~-Ge{!^1f%~;dC^7 z+ryW$yzB4|2{m!O`HxY)g}UAzKEX?AkhGbjT9CjDxO)31sCkjV&A$tz3t!tl(%iiN z$lDhFlysb9m>NF?I&fONon0n{^w8Uz%&+n*=_(mI`quFJoEVLkF@$bTHIA@{|5b?XoAFmbbCHvk~aMp z^VGdi=TyN5W2<4-+yy;k4?g$wpKoOLx&5Md0fzg>(RcPz&!meqW6$WQ`ajZ_S(8Im z;p6YTiwc=KPrcAvT4SijEv?gczHMUn2W;+Xi1A#S|2?Qr7%Zn43mgEgpZT`CJ|zm7 zZ2|Sz3^Gdkf?jm9NkGVp2pnZlPe$EI^SP9wZfjLq`K3v9_6M2$Ar3N0I~2CeQB|7r z5!AIh68y|MxGmF*B5_yK0=5WO2}{X3FP}2?8dF|7J`Zj6j?(tBVoSY*gKFwFrIo|u zX(^$I{Fhf*RDUuXm2WI?FSZ$w@iMcU#Q2-#k*`B5Vub|(_&_ysvn~`yf(tC~rcIQP z=r5R#(Ymga65;!#5Fn=nHcZ@VD_2lk3LHJUff5D&1!!%psb$4bSt@e-bDAFDS(AzV zZWZs2 z1DMI_{9Dw%Di&%&*Vo-=Uk?3f{anEUz-hm4b@f|!@OrRMH4(txA#7X?OV}L}Pg#lt znT$JUDH=yA$Vbg27H&yA9?xI7#JqLH2`eNXxp~3no5f!9{)ze8DKu0Yckod*29Y>O zxYbx!r)KwgcLDbP@ecuO`_|a-ChYy)1K$%}J|x}4_2t$X5@^{?y#eLSqAS6L9wbjr zGs<(aJA%m|@|qhLLFc+Yjk(!EKkS6RIW#DPiDy4EOX6kQPu0i8dm9Y-1xrIcgq;c+ zc1;!*OuONOr}aKv^ldF9Yw)1Ab(0DVlimpZ6wvp;R9bf;b4G3-qoROfD(Y;wo&8=2 zh_hEclNGs0Ga;YFFAr>_7*u2dS}Zi|Fc;%^2IN@gQ@TrE-S|Vu9uGt$Z#p$77_& zSAYE*=NCVU?I*Nw#)(}c!=a!?+DU4zrZ@skY(RI@I(N|-aTl~|Y=MWM3N)C3m$>g* z6e}iM+&Yg$+`|8fk5Wk>wat*YtutfYv%;ej^b^|#{I@CJQ$6qm$zT2oh+?N zF7LWl!3_-pX;lTuENHyG_UHEQr>-=g&_^sa(0km9=a_}1jE&2yAd#DId#WG`5rV4dwH%sZ?GdsH4$&MT(i z)T@&Ib|@ZYi<^1Zv{E0Ks{__}75F*Chh+GGcbagYYRaDQ{s*eP1efK!8UP8G-IKBZ z_T|N+p7RSN6YAYQd4(LtgiVzqq1^>Uo@rG8n!{Pr`i|gY5CWK@qu5wz@IHe`h^gIp zErR5&|AxgkJNa)hxR7Vr!d z5`zKH)Y;Q9|bNaC~MV$x9YVZE*4Vo z_e(`Q>)Ql#kP>L42zh#;}gauVI|VjC+lG_bUNkn01vE_6*r_1 z;;!$?g!dq70Oz<48;x&!ZPC5+w&P|N>l(vlQz@xM$HaCU@rFU|F1dm)9l&|@dfZ8K zpU{e>KPAbN6!5e$ZA32%Dt<{ba*V!KuQ&0c_jl{36{Ap|$O352xgF1}Rq$(LzHgkL z^SA#olNGDq51&Y4+I)7Pg&Ap4cVs6?)2)!Xd=K0^0O!JTrWhXFTGf5p#|X4Si^X5X zB5NA6fQbKYr({=N0n?;lQ>jB+zKUVDGw83TC z=2XhjaKvL0OzZy!;?R%PmEU(?loa)bSwD?o~Udp8MEh_bIU;Xk~gZsm^J*10b^7u5^nOHJc z`k%7QAa?x7#Qd}F<0-|36+`v`^pLJisvP=zK9@-2jh47Gz|ofw;VJN|A;mxNm1*=E z(OHaHQ!CY3K(FN?C%;QIvE8->^(Z50xPqB@T~kBqr<}14%_2QD7w2srq-V#g;_${; zX!vF!_GJ(le%D1R_(PMHkf+=lOR=ldW=LER7g`((j{2p~n0lcF(bpfakQNvrm}kYi z(KAlLi`z6@$Q}?Ia8tN6SIPK+qCC6u-5^yKtl4TiiTi8Y5LC(5OK}`VpLeK6;X0IN zye_C>__IgnI603WOiaqczZ%>JOo46xT!|N>8aaOz2cJX7J+3EFw1&?=I4aCazjL<| zR1dZo@;&6Zn}{$nbSg4nmv^2SzZXq=ubYKk?eVmZ&vJ~&u4rSyK_JBcSzzN~26HV< z)0MaObKcvm<5OGbUv}5BcQ=dZhn2qaKRY+QKiW~=XM4u#{cXp_$M(AONP!>Z0tH-O zaffEtec=QKVlpmA$~$Ya@A9E3XH~JTU90*>H&_c4Mo@A2-*J(p#Z&!nV28i26qHFd z#sUgY2_1uWQ0ytGeSJ|R{VqtkOM5A)rM{ZN!>W)!9)H9#d3Z8*+eGb?d~F)w>Ib6s zLda?7uoUdDl-Hj`Q+H%UTg#3DKNOxgQnzK#x*1e*ZH~1zu~D6k`%Zy(`!V@|P>s0B z(AkNt4BNl%Q~j)z26Xh~Q*GUe4kr*mxpSR+*%2OzjmCtH!6ug-mw88W3>%g5T&@oX zT5J0$dPBSRRxXz3KwE<`${~@k{AHWJ!RzMaG#{!>3@}(|h^w@Xi1TZz2~LB`LmAN8 z8Ng^G8FFzS{e`J*m3LhQyV4~KT*zQHKT*6{Ry5evAqB~+fUFMTJ$9;#MKEIu?nfs& zXhkh0+@!nft1qe}WD9$~Cc4iBC(8cN2(@6T`eF)7=7Nwk z6%ZTY0;3bi2u6R<51+U2gG7;0SZ`byjdNZ}-987Nzv=E+sMMUY#FhGFtHHugkjSvQ z+gt*yo&=B8{r9zxfB63n0OQc%y{cblpi>XtJw5f||Id!UkJa-u%2S|JXNALV!tG6s zGxL1tdDBp;_Gotk;9z;pZ!#8qA>lTueBOe=Rh8$HhBK#tk^2)bE)-Gl^2&-3Ay;K* zxg{|zGv5i~rzo4RGdDjluW4t}_-t~nA-IU?K9`tWK4xr}h(kp6t_{Bk)ng@6WuFBw z!Kd}|Mj^SlEOM30sn!IMzr4%uLilp!=sMC~L^Dg6|L%M<>yObJsZQbzEd0=D^$qi5 zVd4p^S>IH)V9l=;5YYeoS@m8lDB7cv60h0b^*LTZ23EC#d)AY4q1+ftll$+eu%Esc zstK!y>|0E(vKc^Uz5dJLUfmRdEoc!lY0E_fF``x3w0Tt(<^l}Hon290?gK6gQchfk zZZz-NQ-0D9Q;<*h=M0Tfw@g-~xw>}9b73Tas%41&cp$*`S_!q0a>YxCJ|Q|5q_VYq zO1A9{fCm{u|0*mgIgI#Ws^+aJ`*~hlq_g#D!h6RpG+%R%v{p>7Fsw;yyy=UaO#xUL0{&pcSFWBIuqyG z+Xx*?#o~7bCJl-RXQ}>EM9Q|G4J}uOvwv2RixILKQ5C|y;~5eSd1OJh2==iA$1%l! z-3>CF^y!X;+JsdH8J@$hGC9_W`Vz=@xi)*r0sRfHj+86dUe6mqc2fu%uJ8Wwq_n7o znW%B4=mOyI7@_72PS~8$apLa7k;mlfm>?$HrlCZ-%MN_nNI5??s|9H=mm-`Ra9PuD zza*6=#k1e4!^CgtC|L8G=BUmnW=l{Tz)wg+2!!_sGCa1=!MUa#=@=O-uaMtIdkdQk zg^EG0-P(5~I{?_i|EE;6{A;3zjVBnuaPw-|hn4=1w)}8v`19%oaWKAYX`D?EqvFX& z;2HFr>9W#?bg2kV*sErZZ2g(7do9eB0QRikYWOb7Jixu(z%t|b+gd?+MpCoSmcW&u zXqwh-wWk_28xFH}#vB-vr@6B)#v*4Z?#V$7@v>Uj=-@{Fl%B|4ReWQ&g6bSDy}=Z! z$|8w4!%zHNt>*KywY0TNn?4^~In-iEykkhFUp}g_(d*^39^n2x|Jsua=&g4^$_cA( z-4&sT;+N-Dy9jP-%763+vL_VOZFBLqH%rkcT?iYXk26>NXUm_d=*z*P&VPJLa-Dd( z&id-bH9l)VrU}8gT|zSZndZHYA2=9*aB^?h{<~;9Xqp>yu5*KznysQZ35r^{V0~#= zAHbg;JPc?q4PxXRtS*ghx0XNR$C=HumC`%E=e0as_Vge^jfn9Z+nD2w<>FOZ7#L4m zJ32iVV=8ZWORhzQ94e>$%o%6^2IVICa9fS2{ zxXSZ-Iwcjo7s?Y4o=uv z)5_8k`ws}(x>TFU6oP9~wNCBRS*rjTyoCv5&ebU>>clOOuv4D&DK7(ln6&2>a@-* z<`bZsf1H>+8sAeUs=lO*P9XkIWppVG>E`fP)2P2sDVwb)063cSLdxSS0wK|Kbo<>W zzA0xf-MZSBcGj7E;@`h-{%d3gc*d?-mb*xhI?WieTK>qJwPw6|DKwm22@RXI3{|st z{S^G8+zL!wnV6q@1Df0Qf$ya`o~NwF>k?C#O^=@JP6`+|oOQ4e_A;3w+Tm5MNmydHe+3F|fT9`Cc`dmC1niXUtk{Y$@Z|1-iUbgD*`+8NMBIUEC@+1Hof$Q4DRsoMkf8ZN_n*qP} z$apqO&m}Q6^6Ly;g`-DkLyEi7p7LMh+2mvqF#7GmcuRlYYy|c{WkhQciJo|a`9Gh* z+x7l*J3O74_H!=g#oTI_+5mQa6Mansk;ewFlRaEMq}oHEEwOlH3q|B%srHZw?1e(YJ*hW5 z@ULDFpVi+(TJ#m>O4Od^GjF_%5NHN1P7HyNN1d0D;ANc3&`p|tVAu5#aG;P3vnpuPVf9T!Qf~4lj)EbDSbWecYxlw{ zZNeqL*%g}aJ}$WNDhw}%rjG4(;aVR%`_a~)`j?~qqfWILz49+lOYL^a5vq-1))o72 zXlbH%1n&&G6So=DXE9Wl9j?+<2W1_&NxbN^gLCp+d>!E$0!>-7694 z4Jrswx7$?*M@yV~1n(-h<01TwYH5}qa^a{zFI5Sb{vvVd!3CA#voXd~=JR4WLNw~z za&Eujr;P@2FL+PdVMF7kFadhxzPq!!n60o9R%zL0H0!^Fia_FF!L%x)+jp}`5{@re z27*n;#I+>Z{>mjc$WjFrPU-a=zc0M1s}ICZgJ|skMIZ5NQ{PbLYSQu!jZv6r(9Zv= zjYU4SLlZ%+12xneQ~cf3(9{O(6A`-E*0jeN&^QnS+EESFdS%>j_vB6^?M};?3|v)1 zii}@&q=p*Qx0>d=&%HKl-SS;z!%P*VH@e|GDkw85GG25JpK<+{jSnWf0UY440k+(K z(pYKTQ~NQE?K=1AIZ`Fkyh{TAm5QOfzD_ zn{xGn5_TmYBDQVora+n(6Jw##+!pm@5rKZgx5s4qAFFmKUzfQ~*Sa3y$kMNEHINW! z2Y+#!ARY7}9beg8rkPy)eGv5AvpMM_Q3>xzd+3iS(?27zD~?7}-R?Ma`KSq?agVfA zxg4aAMZDs^o_xRsLK$MJPP&m1f}7pb*x)pnUv&qn#^8fk-_3u@s4r)?KEcJcj>(33 zXxn$C=9Dw=Ylet-JA}RxVw{RP{G_Or2=~+^RR%e!U=@piX8=ivIsEkCiHLJBGdT#g z@m-6an1hk@u`8bYsz+_cxy7?C!n10WGB)Dcp-(dgSH%c>}j>At(0j zJB74-_oLE)Ud$m&+3((zFVP%SoMTw&m%-w`$Su&c+jyyQqR`ZvuYN8regFWDKR z<9p*t`836oJNz*D8zK8dhyKi|AS`t33T_II8DgOl@Dx)ly+MQMMDkwd8FEOnR($!TFn zV1S78bfC(s8^I7yMo|^N>MMBJs#&*F)$<2c&WO~Sgpf=zVI4$jmcO{c5$j+!gA9DfVY4dhejKSs}sPRaZDm|tf^A(tzbZFCjM z-dog@ixe0;ke~+Px+lJc^{#h=HZ&J#2>Hwu7eX<&Yq5?(Q*gp+ZX6z?1)%Ig%6)1~ zqJIgjdZnypmi3vdoejC(k>okQ{aNobXrsZ?9Lfc=F;W!2CR!)Nh)|-+{JFXQPg4V| zNoO8YU$B`RV*L63FmxF=Lin8<;h3`_=F)uVOo##VrIW3IPHvkgCeN~>@rnn3`3sSl za;Izi8Go8O5C3xm^YG{eRy^LPjFU{6I2txX5awlDu)V+M9xrY zW_!%d=F>U3OCH*WZpx9G`XsxFL!AFc#vd#boqvYEO-^{mgu(RQ&h=S$?5Qc~ju;No z+AoSMvULUPMuq%1in551FL1zHL1%JOigNOE+uA+vH@~$$nM!cY-haw~P@FBIFO1mB zrI^HoNy{*p^~5#>MOBU$*!K{MT5v^pVeCm`h6J{|tN0v_0$If7^H5Ro9VxX)S*J*P z4!c7{jO-hnW7Px%hHa+rvpL05QP>nIbNrJ)!+MJqxHNtLlhVhA*>htqHCCF9@*T8R zu9^mSeUr(|I$SPu2FZ-W^*tgN9=2rc7!yKLtMUU0S9esclM$<$Y<#$P2ql>1V)_3h zk0|?ukl5hE$3E5QZm%MuQ$B;At&o<1^za!>i0t?h7tl%=5=(L@O0)LdB=yzWDz0ob zj!#HBtiX4SZ{ZwkP15Aw`2%NGJBCs$w+xJk$N1OYSiU|4=z4h(I5CU{15Nek`ettZ zpAE+4%?0wnaM$S&e5`xFW7aaF`;ti>3Sd7oI!Kq0z3Z)bXW?$s>EEab!(?K9Th@>Q zOz^9>xiriYWvUwbk{FA4I!SpPX4Zq58&X?}TNxN<1Dr4?ksHa6RYc+WCsW}!6dwZD zl&%jne^2*@fJyW?Mo}pCy{lF)oi-#QUcjGl_=R^jPG7xjahF6GIq!XX#Nw0Z@4}rm zA>lq+F7F;=|mMY%78KKbH5e29HvOW@mzc?hBLH6rls!)!N)t&PVA+1_`Hi+rSJ zQ}=jP`vVoTn*u4h`A|RP(_K#f$8sC$PmMQLiul*-+!}o*dOpWVXnvUABf`A)z&epN zL&DkRONH01_J^cx@E1=!%#f$#>z*7@?oU~RV}?MWJp^rXLNONrBn!L^%2)H-sY@ng#4dQNMowSPgG zz4hA3~VWZO+Xc=1_ z!#LJ6I>&lNu`1icjJUo5l5PRWLrLsVvf3vyAhXX^_)$&2Dc(_`)R48WV=7L9OI6$;(P(p?DGLp$<@euSv%aVHj!uz=J+I7S?sskF zBEYYI*?Pfl{GF?zHMRU%;Q!Hd=J8Oz-~XS**v6K^8)Yf`o?Z4Op)A?=CCb=kWS2om z60#K|TL@vYW*?+v8H8*ZWSJovHTGrv?moZA_aA@F!(;Bbuj@MJyk5_9F2uE`k?(C- z2WKO|o*l3g2aUtJ!NZFMBHBt^;bh4l>;ds`q~i`tUj`ppwy4@16FL&tT>!Gn0>?$V-GJ%`Lk%q&RO9P7J3LVf=D`U>WotLCo~s`es~rk-)-1!Dg2a|Nm6c094@nop0(5>p3dY1KcjQA}9(YrE_T7iBlWJ=2puQ5Tk^h1^KL`_Qkc zIVEGeOG-u~5s{_ih&Jegjql}zeb>D_VHIU4(kps5l|Sa7Y}fPQa`VsL69EKNtbcSP z^J6gpF7FvS&TCt3tVYpA>@9si=x%O1{I*kcZ`T=2$g*uZQl>k-2;#tW7bM6{n|JkF z$jX=+#t*-&n)u_1>PAzYm(`YhLm0slKEr~8d|BQ;G(Jk<<1AIsvxL!J{mJ{vWQMlRu7z_%w5zb4|Ug?k~?5VUPf7RM+ZdMYN!00QB&e;Y{QqRv1N&hWl2UDJI$7 zm&7jKiIcpz)NL5o{R(wf<7;_Y_eCb=od4fF2>1w&({QV8|NXL*)~EA?MF)i-wAK#DbJWGs?q1Qns*r87??iw;mgoUgC(=4x!TDF*h=s=TmRj+96G+Fe z!A3^LPwk>DcL+kalh>!)iqguom~#1O9)LhmKCBO1xMrkU-fTIJzXWCM+~Y}1{LG(Z zlun}dTe63rb_x(DD$8qK>XsxCls|L+W0KSZ29;-{3Q*Qxz0V#g-qm|U!k7FAXFKR& zsE|B$nBab*-ES{1Efj^g|1Eerd0oq0E#jA=;3I9R@vE9v6X^=ijgD-&2V?3P82REGL;zc)8gj(Yg37uNi>YkKTwelR6O z$8SD>RfeMs4Blz6dczd`359%J=KFw00lR1dT;pMVUS6KPu#%WHM^k8XGN2}16O5NV?&qqGBn5QHhk^fENu>C7o(jsL&)g7_So!WRqMVe)J=qP{jL+jx^ z%I6jKJO%Dz#MIOg6af3u0a$cp95933rRK@`rJ zW?hNHU8Mnas{d+zU5MMF7&aZjSk0=$!daJtW%X4^q3CtI#z2yv=dY%(T*eN)29zVy z&sE5Ne6=#Dw|!v*#?)V4qo;m)EkQs+d`YJ~M3&M(SJUZsuiFxa|H zgzA%;G~;n2_&5tp`EqKa9Q_TYqQpoF;=t{(A37LfR7ThsJH`LP<}q_>4CrTli?`n` zH~E2PyW2lWAzN#I(qx7Ge&5mN_gdvphx=zEUlEmJ{hE-&+lE%*K*Bx1C$k%L z+pfIh6;;f21XQ?8yHFO@4cn?amJzOS!Rc3jY({^2MuoY8Wry$N#_jwNw!EHz^s0@1B-Ny4k`-Pz+Yeb+o8nOwmrSqZ z#JsNBNw_TL=A1<>`}FU#0R$&ort&m33AS7`Lp@bNIS?S~Qlot&!=_t-yu$TOS&sH= za8&s-4QhH-Ll2Jf{?=oVWL3{fXP8!zE3>9~1T=g(#%?8vN?Kz}4#=JWnVa#gE`Brg2d~ zGgpPcR=_bZT_V0f*wu8Whjbef2{M4}^J@&(A>8yPRMS@kh(g!s$zD`jQ5R;K-)f=n zOtwm?o;iXk)+HWTgxu59VdyV*kgF$LS&3Q+Rw^(+d|n?I-uUnrg887Qg}r5@*!Xs_ z(`_RBYdKx^lTJpN+{P~TU)Cg~mLK;5Ag>j*h`-VKa2xJ45^qea!`g1EHL*+Gc1GmA zN5enjwC?Wwv}Ir<5_p?g^wfe$24e&UK{V-gs(#R4CCE^=fUAjNyd-O&REyDiY4{>? z`NxCGs^5@~Jt-noH2q9ghNFCWVLQ&>2$=6mr6L3+(8GOmSikGeaOzmqkv97r(-T80 z;B6{p&+chJiD&wa`0$};_n&}44q{6ZO<@Vr#isojGX1>tXyJ{VaV+i?9 zZSnWcz_QddsM<=j?@}^~)2N-V&^Nox#0Bq^_>wpRS)pb*oE7T?bL?4t@t2+g1CNpzh>gx-(%h z0vD2l@!V3t>?$>7#%66S=d?z5rv3yI2Bvew`*~5-1>4$o+WNERk(@C+lCF`}kzY9SKAKx;J$LI0L3WOcUsLrdc=35!|kC^8KqTCVkt?x^hyST-*2G zDKmcv-ED7^op)IB7S9FA%Dy`c>yC^GNY%GcFE-$LwtmCoW6aDGE#lTsF|r98t~15) zRqmP#Y4#G>vj7&53ipL#)KTZLf1&3$={>TzDxdP3f%5|d$a;TubTZTgE;Z^F=U)KR z3eM!G#Eob4c&^gY9RtlDvxcnui=MGDREIfK1H%kNW(&;0pnh+-!qsrqUK7^9-@l$e znnL^xt}9i*1BVnxj-{ykFlG2H;u9Yq1K2TUcVjH;~o8tf#M{@h4Z@C<8ZfQHQ(Qm zIrU5i*8#t-C0A z5BcEePXi8bkOeSBxt0Z-Hyq!jEkg|cm!Jbu$01yc*UGJAgk?lG4H;zX%gZZ9R>SFz zqoZtkI|LYyOD}Z@Zm+O$JzL*@(f{~(0oAHj)29n1vR`8zS$WgXm0BK3I~px(uAjYD zY+HMiJQ(&V0hu;6RiYw;K`mSBGNp%?w01_ie*No07bXrF2Xfj%@TsZctCVk;gMnTk zfmV@%9;3j=MRx`AB137;I#%M%ehmGMiHzjU?pt%b*K_jbFFoPB;He&YM-IgIr3#(@ zF{$;eOyV#`cuArG*blC6vZy;ppLVUBjiu@#gG$~T$shQOECM6qe)XN-?vZ+zM!>L- zC=?he0eU656Hp!6$3{-N?Hdtz+h<}p?vZ2QDEZ|}{x-ZB`b}7S=&&W}@#;-dp|o}# zE=JSQGboYD$%67kK-g#|$#Z$Q5mRJ(kH`zuiV^wXkOB||G_w-@YVqk&OU*^h!CtIO zshjgCmvQ^uYJ#h+wlkd~un7hs58u}Ngn#_BGlEQ@XO0%M`*5$*`I7ZZo2&1`(rmUc zDi9n!e9I9`h!Ag6DM_oCE15$V@Grgpx~M@iXZ!8#{C2*Fw}UCxBhF0})@&7^HWP!-Cx_xb3RXzZmE3Z+kAe9#&Vd2%){F#3D zf&J$!wh>c_f7f-#bbYj7t3^7>dk#&7#CUqtKFjczUmCWY0FENNv37=~Qdb_NN77)&%!lP)CS7`P8@Hi{5-hn7oj5y7|+Qtx;0F2!IYOS5>JtX4Bnb|1+JrX@sf4``nO0D_C1b=4WuD^~^O5(-z;bOcllPRn zM{v>Rm66K(a?7TEf;>8_Gp=T@&pD2k9E$GF%UDgYBF0}B0Xsdc-B4?@lBcn^xfu|1 zv#HM4+%K9Xvd*`AqH%)OAH;ZJgj->;7*vwZ*v4;l0JHr0$z5`IL%d7GSp05=KWP!K z`;**z%Vc0th*Iq_9+{Bt#fpP8Eod&7w_OW~!nh1fGR)kB_`XJ|$TCKOu^eFXFRz*N zmA==$v4F02t_UVviUxm2puUAj6}y@!<#rPrV36J78K~4%trw!rL0|Jp<7a5nS(FCL zPwVS9hg8L&K+<{q9IU8>AjQ)M6ZGNhmlaOGJItP@RH}D;^katV6gXI&to?8U7giRf zgstsFTuvy%AMA9?aqK_W4|pXMEY{HWz>M6T|k<;Q#X9y)GD+HB z)qoAtwYv8@)Rjvz96ZnIZrJ3w(Xy(M=DB<6=lkZX;v9r#ZTjhl+R+BdkLCrtM~w=% zoyW~eH<*L84xD-Wn!DI`&MobWkT!nXb_(Fn>-E1oHI(uaZJX3O?3P}MZQF|36=ucz zT?#but>L>qJih1VC;ZmC5vZGt< zU2qa&*>S=leMOK6r5>=QJ9a%MAfj$Wn)3PK_RC5@PC&3*R2&RU~v3T)wJZI1$&TZ^5K! zI4MDYK>slEzo2x>QdCtDSALGnp`Dye;=X3`y^!R=oghoV4=P&#EAF{ZeFOHWR(FZY zYk{8HEn&=#4ww|q;ZZf$f|pyX=GclcH~qMgN=+=kw6$!v!z<{fszK}*bv4DlS*|w0 zUDudV14_1t_};;sck#~mf3b5+ANhPWkoSbU_bGfCB%X%=P1sog0FOGq?jlc#RbJk;%<2~BAkQWIySSnDJt2!VovsBzis10Ps} zqv>%65}1jb83^YY-q0@3SPfUbW~qcvP|b~K{ncXU7nrJob8EV_^~#NxCE-8(1@mGu z0nOcBetMTGzEW|zBs?4t#f@35fJ3e7uVP&;!h~sa>({cDSA;U6ePYY#Z_w#MlGNii z4LZ*ku%Ifc&b|Sw0@IwLP_7-Gpx87J#fUY^2jXEz9p%n?cyYT zije~c=~17a381stJA9m85fox*ZHQhx9HY0biXwC0fy9u8C(Lrc$_B~lm^phI&-Dp7 ze>j(Mg&T<&A5(N|nBh{|M<>6p<_6U|KkdOPwsCg`-rcF;2T}CTMqS{z+-(r$S(U(n z;zyY;Wj#{tfl@V(&z~&9&&v-gs%n*`?H5T#W1gvbRo{V?>@zmCp6!+iJB*|o<9MDY zhC3;BB3K0s^sw$8eSYuYlt4~Wgg>t=o^#AhJ8)0ecSdFrhwOe%of}!W~5dEFjxRo>ea6YBz!Z%n5Zx;W96A<~ZRGd4?6ss5XUyS5F5}GPlPvNwZl&x4v~QijW>R~`+T!c^JPpFSk=oOoOR{u9VbnM(_&VM@;#e2z;ZMCEYxnA; zd|BdyE5L=43^`Ws{L@Vy_PUO-B-sO&QL_Q+dG^ltwv795P}na=vj|Skd{=5de)<>>#ROl&oVkz}N@oNM5mRpTU+xmdY)xR$ZtldKfEgCPL z;FR&qpAUg=_h+tFz{F9Wv|D`6Wvp5nH3ZG?E4otdz#y5&obFtIAKX?ET?^b-Cl;lC zxr>+DXU^ro%Ebq4@2tfcO(nDL{?-c4m(;f5;v);{ z|IY2dz9JFE+$QtoGwYB`NKfHyNH@))58aqCHL&lZs3nVhZoH)EJhcZuj6+t%Z>9eP zm$=<*35|!7(ZLgimS4mNfe3)(g5wXIUU9q~G9fr^LUcjo5?tHH_%brjh-eg?TCTDC zSA;iJ$RwsjrAQ1{p!!}dMN`oR6a(Hmi@HDkx21~jlLH}+!e{lpPxbu`V1c6N#Sb3+ zw3g&b)i3?3&6HInJ^4LJ^!~%DN@lz{$NIP6qi5uxl5iJB{$eiFLi)L00sh{lWWaNy zq-?4^SNYyMLt>9HAt_>|*mr&h0}t!k0$++=di9WfMhqNLS7m+h_;*|ln@o2ebv+8% z%9fnEdl$NEP?W#%e=NZDQa`cV3VHSjj&bye4WThKze<@TFn)P}nT1grv#zpHZ(8Le zxGP@g?R1YL%rn(Kq!@uKPwCh=%r|u9UUIV4xYK%tu8$BQsN8tzVLO$vMiw_F>1gNa zyh8R1F5?E^FyG%4DU7&iU%z`V@)EUIi0l;LoM8bCY$MHT`Pb@ybOK;XJJsQk;f|(2 zHp0Z|mBlv{U3y>87d=}Q9Q!|gPZJ1PcH>bpY=qTSysEWA-h=C}WX5`;T7)^DW`tZl zzkf|^WHzhEiJRN$0$yaeY%@YZB#lg?2)|sXK2n`H!Vy?2*4f<=>hwyLBlIfI4~d-# zULh@#=o{WV|JwOeJ$Eu(r9xRrjAalE7c$@y|Ry zJ#r^)#CPXB0YuUmNzR0%i0Xx_-QD9{8d0%>1J?>Gjb9!NrfM6$qfm5ML4uBZ7bQ{$maUQu!MHdnC zel)6{N(0a$1gG87@$0~%n%H;(p7aG?z329JaZ7K4%B@AE$^5Vxgj1ikLVOZhT)R$s zxuL@u%NYTVswJJQ3Y5GfKVV505t$q=0sJ5s>@o1F=v+^J zngKtIg{p5Xs-Z(&^~|>xg>>Ruav}7hxt}uKGH~Sv?16-aK}i0!rT2(YKao!k>v0;n zkZ3$;)+OYQ8RD{{N$^{urfp+toPKF#LSUAObaQUrI`Gszi=?RY6SJsF>Y#M0v%6+l zEDheta2UV{G}CO=JpgkooxcV}{}^iqaT%xG9fGzh|Ff)eyB<&XYVE&fqV`jR($jSM zAPLNFK5V|JW_?S8zyY|5KJ_AI4?at{{5lqy10$%xPiq8-R-%|8*nrMIQeG4|#yn8Z zGXiTHv+fVsG`Ny?11iTEsGDVk^CFc9Te@Negb@M2NWZ{(Iwde;*R%7hRIbRBJJ7mv z^e8{Mo{Uf;Hi)K^s@(bufb*1SH_z@@S~QM0j(?tY_r##(El}ucZMh9{m2ybh={%Ke z*O3>d8K?qui6Tu|tPl-hw)DfV`r<9xPHxAU$OmrBLvh_XsD|&5Xh*xpbBlL-^6^e( ze&pi@V^KDys&T|zZY;2mxP*>TmB?FD zNi~z!k?yFYBrKGGm_T#wgANjshKZ#??F=2p73hpuki*v$prW3O3 z4c)EctBItQfxVg%g3nGHOs`@IK~uLg=mO7MVp|Ho%M!+Q9W^E7097b|7Pr>A=b{T zr`3e9y??()W?_4?%?NsRcUWSrfRkfl`$_{~T6R`M{73Y~Xzi0a;BrOZ)!z^7vhO;> zLPT;lHj%024RrlMiYBYLU-W)?fIM~!FaMvSHujpo0PDd$q9^}y7jeyq%yO*ryM0R@ z+^mJA1hF5oqJRY0nsq<7L8jvE^1@cH!|ynMS*;htq<}v**#lZ8Tiv|Ym2(|=Bp@qU zzs_=@CF9LH^s&KA;w68$ip@((NYA@1#cRXE2&$1wYfXXpa^Dw61F99an1fyI zbwkWNY)0^Zl_^5-aioLOQXT5RhvN_mOyi__{W69nV+C0^dl^hA-(1?6zTq?TMBhT( z4Hl+==_;ZZ67o*sSuW#q7wl+~`WKmOY|A8_6SM53zoX&#p*5_M9n}CglXN)`oG-bw zK#Y6-QikwWTYso6F+L)9+J!1LWdnDG9pi+9fQXLWNIshkFDcRjy)T)*fO?U(t*pv? z;xXnS#Mvb zOU{E%VXks84C9XfLv1BM4Zr)^VK><|_*7>D2mOAPa0AW;rC-QIv+@9|1tvuoV3nF{J~m`XL3 z#N&YK2W#-CuMI6e#b}^%H~)F|QL_XymrO+&*_q=4+UE~xD$~4c{oycq^7u8OqLlke zgEXUO84Rf2_Wd`7k~F+`RqO0!I280HzLIam$ik3@T&wM6)9n`GV;g|rIvV)_a>XpW zy7L%Rj5qUNg@Njmby7AS#a$KyL;=@^Hcw(;%%^!P%45iSc8|ikkz{(y#pBDPNye8j zp0km5BLu$))S<(&q6UoYr=g-jIFG7!t0CVt9D&JJvR<@4L$`~*A zPEISP+dN`1k&Rd&Qk0aP-)SFf((+$8GfN|_yz);l3b&B+_XZQyuK(W@Um*Zd0?3`n zG>I*z=rEghC()vYhmidjfI7^>J3H~UG^&jgC~_^VoTSn1HMN{SU8I3thmL+JH1Fy@ zJQ|Pcba9Oh&4xv`NNg=Yum7N#xe6H9tfx1pLK(zyU;miH5?>4yb~g+|R19;PJl$?{ zEk1Z@5l4S;Vq^zcPD9X*2nf0*mI@Q#J_z$Lmi z|D}Q}vc_?>3R*%2W0Ci+9yrpSGVytOYT1-$c|J@KKHhhJyn2h~Qxw_))F}<4BsK?* z2Qvej6Y}PY|En3u-Rr_A<$AC05`wugZ=Y9#D0oHl9XAEQY!{kD;q{ zLK0C8pCKxi>_-I+8&~P!ds2^L{ZOrM|3-Xxs1vynBIEIP7|zs~bd>Smdrmdq5|sLI zQg~}ES1mh716yFv{NmTu8IEP(Mz*11!Ppb%08o>4)ITpsM==U+dkniP`Vn zeugoBlu08!Z+0m4QrbMys^cVY3mGklGqVRI!;!E3nO6|Y9V2|g24g4UyoVkoRW}ZJ zLba#g9v4z1pQ_KGg3?l&Tw-tWc{fBD@3|5*PfxZtv+Hm_G9 zIr(y>e%_MYqicGF1~+GE&K|dbIf$`RxyDv;yyv4H0_CBqz8$EBE~VzC%M0sP^HNW& zlutXK;9J;49$mY|l*5cwezV%rVbgm)GNV;Qsxjn>xOKiENV#@W-Uk{7D} zc4%F0IoNk2t>nI^3SdvYv;~MKkv&4miPX8x^g-#qKKblH7~iKHDyqh-sjs}{=c>w> zhJRNt%G8-rc`|45@GScU$9CJq`^;_*pq-J>`OJWu4b z1fVM|1qd(yaLooZH_rY=c>k}D(_z;{nzqdEsmCaR1%QZHLToS!t`Gg#fQN8PUtQdE zeiC$z^=V`3?K9eKhM(3_DEyZMU?1Pz3EIVzsfXbcTHNRyj~LE`ke3;+2WrJG4Q!Y` z7fH8GSucR+^ZlLE0m}OE4)#Hybk!=9%VKnc$c!37S+(e0$xxr(6~Tdrtfy)H(RIBt zW}bFS-41+aWSf_gY$LJXk7`=z|N2EsP6spXF+sQWfrgrx0J1(TOwmG~rZLc&!#d~B zwK}$D(H!5$QNOh?-7E1mtgcG5V>IU2q*l_-bY_u{#kdbLiVHY62|osDUIITI>Guy~ z-WXxJDAxBh7ckxBr`wIAt>qJ<3~O(h%l^91bW#4eFSNEDp1Q#Y;r$-(B{rg+)5u@i zD?6|bIO_zBg7YpU^3T4ql3k#+0{}DhJb z`HhArN+T1ZB4aUeImt&L4 ztc(8DFoEY^@F^``f5uECUxade%HeCC%#j#KeMxr?D3yNc@nVgyd7(4T_m=H8`PI=cXnu z<{nOp1AD7g_%wUx_d_=mgLo&Ar6}o`h-N;FPq>+jhr$9Qr?~cuukXe=pid-Omb#7g z09#T4&MD3v!n8*)WCHn?qZ;fB=2vCtjvFtWF@shE>4JQzcb6{_R|NGdK6Nd6)7RMR z)FA^tY%=^=WFD?98`EsRxRL1hj$>}6-$WNA^9DVj$;nye3`OE2NkX{>hOPnLXKsLvZ1Da?DS?!-6A`;SMr4L#f6e#Vab^~ot8CUnIo*6He!1P?0E zV#&{B{q|V3(No({_>AhIOxgg)VMm42&bdL{Ie@T^KRsRT#pZY?L!5DJfwjz#QtMWk zQE%RE6QE+S9E5--cPt52vXr$ix5sE0FaZ28L^sp^VA;{#N@1~nC|`WZar#xh5J00w z%VHAp1OcK7rOf%N0X~;44%I$R6*&B^HxWGoPY8lx>|HdvmWzUlS&;^A~2cJi?o_f-yzvkS@eTfYzgSP;(>Y=q{ToZJ4-rVL* zD0o36$EPjn!AY7DR1!U%Y!}U{H03(0BV;(%eq4yh+q}O2*G0Ie_F~}rIukaK2Or?{ z>g26kOrK3b4oYUbgLUnbilPmclE(}Xy)%jRamD%*HRKY+rpc+kOIQ$jb}FUNu$5 z@4{H1_N8{MXbALg22iIA!IaQ$c-sv&HV@0*_EA`;DD2qLy*X3zVqi}2;)lD^GY=s+ zq0Sij?Uc}BI61N)(sUu&GU92~*Wv{7jf>WApx6$LWFP9~7!x5QU;u|dt(dMf2LN57 z@b1{iA=qNplL^mQv{-C6n3x)`IkT-EjXAnn|K3#(b$$zC0GUaAsR1OmN)rav**&Z+ zj+`RhHGxEB_HLCnE>eqm$R!nnqS)kiD+H>umKG9fE-fsCEa(G;&Jp8zci}a z2`NbBX#3j%I@2nC^r`cUgCtdA33t8-c5$Njt$wMOdJW4+XNnWhFp^=*YE4@|3&9z| z@qV@S2!6==WU#!LO8pVTEzv^3rT6A%sezx6Q@;WW;bZ~HmtOL~HycaMUgy7YxsmA; z)KsYdbgcTq$aZuTMxp;RWh(?6(E@JkK^+7PO7+-z#NtcWyItwyw>T3)CJnoSVqV zk6cstNXxlsJP*Dbu$TBtR8-_?^KX=fIsD`=+qHx4!l0)M0v-3`;W2dLxDEEwl|J3s zL!8sOKA;Hs#^I$$5`(TCPj3c}W6TwJ9#@Swaw%$~j9DZ#HRsp@?jFF}!A3GPo7{0W zlIvvvw)*bmRzM|p@|9D~i>@5>07YK5bPYg8fPRs8($ty>$k(t)X-(FVSPHpmX7a~g zt|S|v&XXv=PiqwNB3PO^7Yx*)YVF~gO>(K1Mmo!CIu(h}$cl03%J=-lRO$gy)?GZd z5D9bvOrbjKm;rd4$OXlZI_>0UdJ})}7DbK3@GYUO7kcawsu!rcKB$u_+yw z=UF%ylZOUjE@Pa$g^Lo%LOaseqECZvKk9|G-@&%N3l>gXxTJP=P8-NRS$C0>nmfl) z=mHSZNDnwpw*?Nllbf4r#t?bQp-FJ^B=+08JJui-01T7;NG{_czw=g6h{z{Iw|rHU zyg$97MHl2jy`Er?5=mh9d`1_45OH&0s`15`O@T2(NA;eu?`Y}#>b*8AkpPXa+vRpycuo3s)?I!mUQ&v9O%zz>ZFxrEBL4pgsST=!Zv84C%q-+TdgbZr=~Y@g zE38HJr@w)%YdIuIWUPd%v-PQcQ%!V zg;n$Fe+mJz){(co+EOThn+kwdLB4^`mlyB^n2IHY4pngR$H%%x01}D4%=WbRz8-lj zK^!R?nMfK98)s+2&A;sLcv7-tP3W)5`;1qD=mv4`E3Q+9cM!K!wG=z&4h;L%9 zopAzjBXy@(oLd_3)0KZoF0dc4_?B#@r9%Y{Prfz-w-BQOj8Vp-8T=QYYpenl-aOUt z#KcmaV2{)#zFS7G;NOav|HE`=|AK#Ls3IXh^rw>KBDnYV94DMHhBaTOHw4E!W=}q5 z-XvR}B(%V{8aLBkzo=3!oDlv{qW`Cr3rEbfmBSv*o&StKuRmsDaS&g+Q{CBc=YheR zs8V0tS)In=DEH#VJpy%KvJ$5&flhhazV%@7wxysfptMn|n8f*Sp3is^;L0}4OOCun z_n&pUsc49b+_LzKE=C z$wEB73rzF`Q9>a5xLKmY!{A4G<*KyRpT+N{BA8sY08kEm@|>)c$yXY`M%Fa8X)2S6mF`k3v+APo`K~h2&mipyMSTP+yAzN}H}vbr$yWqt{>gXo**r z&0Qv@KO;As2>AP^BX~TEvI$!N+OxaKEp(vEvBBl*IUrBhrWn&XV+8gL@k=dk=}Azj zOEo|DYYC3D;oY6RL~JmowZ0O&cf%3NW*`NP>{m)Hx z;n7pG!`SW)E%~%avk39{ZCkh4ZnVfOuJPI*dh!^dW9Rcw>jESSb@`Ro;EhKq2owFm zcl1t~rhw5+CwS`W-pmUaH%Zs<0Hn1QaDwU1NI1C7;cG>>0$(){%$x6vo@u8B#%K7Z z83bx_c(q1s!3jz>K`t_m%yvajp!vzc&8&yb~mB%z=q9A%oa zKGh>cFPYZ@-pBa%k0xL1!Cmyu`eTMwll!MVM(VMz{|pA2UCP&6(tHiq_P@1`d@E@! z|J@jm;IZy#DVb~MxJiz+-ksKIPrXNEn=_QBx$*XAN5SiPVREk)y!Czq_PINm8%LuA zf3Du#{5fklqe%Q&Zl6C(Anq>ts)ZnNdqf30qXVWyKsx;Y(+=Aa${r4D2m-qZP7c}mINdJpNtTJ^!Ca3jL5s6t+d zD`x8N-n-@lso+SlJC+k&@@;cbd}I=^_{@hz?;b7C1IZ-l+5aLIxr=`O6358b4euKy zg4AIO-JWwS!o7o3>^<%{aochwLBot5n6l#UUKo^FDnRV3B$7Jrk0M5e zx7M#t;h+2u1HKG8q@fd}63T0FE`AEwxTqA~NhJry=R-{ueX(QuXO-q7hB&7)e024mkxu?d5I-Zy~Dw2FKf(>MCF z*Mr^N^>)Wt+3_X57j4Sp zU!D*2!a!&T@7?G^{0~Jw|9SKOSd9whEVYQsugg*CRqY`8D zzg4K@N>am&{eGYma2*?yP34pgIe(ow^-K4PQ z>m!GL9VrVP%^xo!g8AOHHa=v2NZt1Pir>*l|YFE1e(+BpCSDYzkC06m6XAc?-(uY4%5fI_BZp(2`zy8GQT3cEya$RHA*uq z`U*ab%z0d)Ze}N?+~OeF#JfTL>tX;;=0C;S6ZC6O)Hw*M@nXwYqx_Oy#^=7d&Bvs=r^FnT;pvQ zFu+8Fk6JSk_=NDl4JIZPr#Sor>`5h@tQvn&Y33f7@X}HDuA!wT8MYIS<@w#Grv6`j zD1e;U79Ii=d(VU94y;+w$A4oI0HN=+01$t^F_UKi(Yb2B16(VxnF$5r`C$93Bbu69 zc*z$r5`y`oL-S>iZ{aFWxMpbf!I4tb7`KHsTLe4K&PakeUTHfT>4pT-0R=JtyeDV< z5{E7q883{@+ClbdU0~7HdB1(ZgwJu@G4BPDu*PGyItjoj2KF{I{ zq0Um0zF0a>yKM`o%1-0!d$%f*jrUC+-wotbF^HqQ`>PnH)QVyTT2z5%dx||I*y6DW z;=gBCG<=`uw5Bjea%i%C{R(t<;O&%$+RhKh5XYqxb1cRy<6rb5C#-tIt6jNaZw|vD z;xwXj4Zo<+t?b9g9(MCN=IIlHGL0WgQvPQK;Jy+TwjsQ0?;QXoBJysS?!_VJuXtABX>sv&>{?t ze4sSri-F%mC|y;GD7E)D0EDXdbUJwV%~>m7AoBhRDJAS?ga|tK>U&ojkfH^uJAaIA z;|dk0D1dBiCgtV5iN7r3#yr}4r2XeZ0BK9SSPdQW-jdyx#$#~5No?6^v$x};`f(c2 z@NhWCy=&jE=0OL^Y5<+G`^v`YAJtkES{4M3cUK)MH7wom z*m4?bG5&)s2e9|w(Kr`Vh;Eja2awr0TsU-~j@AX9LZk3m`GHhGP4`1bdEq1@pfM!l zOL+0lYWS;T;RO)g6pF@-&m-O19%a@L%gv%97YeQa*%w8w+J1 zldL9rLUlCEg=K-epvHQETWbnAl(Iamm)Jrdt$j|Zm6N$f%TiX&n11wuyLn=AacJo2 z+P;#Hsu!_F|4kUr&jp9_Ou2z2vt~2Y^Bg{RSuOUR?;kU?%3uKf_a_U$}S^3iUi8(d{LL`|1_wQ$xf&xp(C30Ihp<9TlHSq$P2({Lriv59SOZW#kfa7 zMO67{Ri@c3H1P`kN`fYAfebg$VE&+lBO!HLGpk*^A;@u5S+ zLhB_-^KGXYd?@nJlQv(ZMfvAoklf zMQ@ex>7B~_lj?n|%wmg@43t|c*S?$$>t4SC+KLW3tADUc#N3W3bt$Rj#oyF+nAXQn z#IunU*1XobBs*$9@w&3JYM>|Ob89i)UQb%WTZ>FX>QHA_cynv+ELT0wQE4~*IdGnv zfQ-u*#*{!@3KGZe5+~iDUi;OOdww z(6veHUh=8fe{(IW+sOYOdQVz7iKdUbQ1NP-b4cyeIBl@il<{W|ps_6xD7QVcVU!21 zrepd&#r!v|rEWX9(z;4{b?+NQ7W&BV#Tv7VHU4HcoKZcJArNo}L6C5T-td?wWI#+v zzstFF5xeEn-CWK=S7QqzhBTXm{p)o*`2J_XtE*vZ&hSYHa{{<<*+Dcdea`_S{{<$ic2(Pk}G&Ml+v-O6{xrM@&FCtY>Qkk8$x^y4Yd^_oclMA`$ zD;v83M)BQ^n|L{?Vcn^}TLFiBa&mzHWei z`#r!d^MC696V|2uqoL!{!S(}h>yqA>iu({?57LHc*5GwQ*Ns=VCoIO+5r$QSBVV6;a*l3>|CK1o1OLK z%VlvdN02_6`d{Di$;-df_iUg71it#$ta+b{cy$zW{ONAg=2*i;p=CLH4}iN~+x{O- zR~Z%6`*nvIVWbf$B^8ivq&uY>qz42+x{(}0kPeX_(k&<=9g;%{NDZRWFmyP;ATi(! z@LvCGz28`TnY-?DpA&oUb2hEoEx%835>!Q12FUHP`CBZBKDjso|8!ia(~ zzmwx%ox;Oy*vG{M50#G&x>ldgg#EA{nQf-8T=0}oM_A6v&Mrx%(oI2=THQWmw!2+W`jDPhU&yP;!w9*s1{Cr>)RKpeeo38U3h!;&(34 zLT$!)OEW73AYQxv=ARK3iURPRI60>v3$XC$Upw(9rU=khqa73grNUe%RP_xoCOUii zf#$-R7*ng2QO+?}@QXZ*T>ZmE&~WXu0_)n{mM>DZF|``bypuDQ-YtU)ab6;24^V}N z5q1<=@58?KsLwpzor$NODi(oFnjBbgXY5?2_kQrmSFxr&`fF4CdSX(M4!Ge>}VNOP!wr9I<6^8O**%L|dMZ;-uRIe<%(Q9!pVMK#$wAOkeJJD5NiKThz9E08^T zpH39Hm58!CCGG2Kck}MnF_mScpXknCnE9p)blMs!6mJ7h#y`JyWm%XMf1^JNca@Fb z1gofq0#j1R{{WqH+{s6PZp}CrHRw8D@oP{ue8G}52f_?fnw2+4Hi4uSC9iN^sLa47 zf)3sr*qnC-WoT@sON(fL`?U;`_3g3J%`XI_)5+UtGw@s(y-=1dx03!yqA{?M=B2x> zl!X<{-%J&D^j?)h9C(j7MFi z9|Y>pxTMG(%X!U$K^Ic=7?U*fL?L`cAoCv4(TN`oQIcE7Ys~WxmXdl~AHQt0@;R(% zGobF(Jp#a`Nr1|o&XqgvGISC;D|F3e4}ZLL{@+UX+6(dHbLsI9xA`VIBR2J$*jiH- z_Utf1lnKg%OVU;4V7pwgp0vm;oaM6Ea@!sZBXJgF%@ zEHzklTf&~BvaVNv1w#v^?R_2YO^6C=yM5nn>}cfGkHtG0w=TS?OVSwtIzwvpcR^aU zMmbOVKVhMqR#;0ZW)YtsJQ_8EWpP#6w?DhKf zaV1lP2fGhM|K{tNVUd-9Od~I-#MaYrA+Y<~bfRaqh6$-HSAir1n3Numn8C34_TBIi zyJ+uCf}~AiRy9M;QUus1XVG)EYosJoCmh07061y=7L?rRY2psD*R zXKzcLd^|njzx&rxaIW&#i!NCk7$A=gqn`9zw*2ne5sjoQEEGU3&Dre)GTi<)N#*nF zDW~GeKjfA|cXJjHXO-s+<@G6f03eyiV&cyK*6RG8O-y+Md=Dt^M{A#&|EL}MsmMg= z60RS&Q9mZ$4LKo}n|plu%F`0=d7rV07kzOvwURqLVf5qj<}U2(Gb{UL^yj9-&xvIT zQEc2LDt8WblK9p}^q!1pQQxNGre?bpP2&Q7#SW!P(hJ@GEgh2^{;X6H_lb0`Z!s@4fdKUM7kB!iv16;{ovLbGi zS$epMXFg?lpr4HhlhN)|fV;*@-Pll`Z`HDb&SPJCF({;P*GKr*=d`WK%8VdhNKKA( zq*um}cE6z#+}6oBfMAZCK6Xqm&(8R)KCuY+Z?*#-OE<8$%qfj2CQ;HL@?CuNRVyQt z0L_;&@{2bGwo+JTP@ZlHq$O|v^5)e$eCG*J~?_T%HBiWWT!m#!T1J z3~L>GXAI{0D3#{Fn%az-91Ug@F5-*${e(p7rHSTG=}UVFAN&w8KM$57fj61@O3zG* z0)@?%d~!n1V`KlU`5Wxv1^lLOfQwhHD*)UQlrh-vBaQm`-rs50`y=rdnvAfg(O*U~ z)0O4H_7h}&L1VAxI`zDQy*~kp+b)jzlafL{)OL9;sMJ(gXz@m!1)~77U&=jjd;C{R zPLkquZAM@D({!1BOJDIjp|zf(?*~(76eBy}gv&^e!=n4lZy1QULXO<% zc7!)G38=?BF-gC2-D=NFQ?fhf!;RAe){mi^myX-qoq$+kNSQ|MybdcU|5K|=l zGM{5IqlAwUJ$D@szQNu%fAh+69nD7AXu>k5ZE(x+R)CWZ`Cv8b@8c&fV`OTl3{vDPj&6OKDT7PI7Vx=1Nq!E#YlCo?IG1)>3%*wY^^7p<3|7t-&dF+9d6yRP^d8 zl$8F%TtlROB70%s2ly%u6OL!HcaC25ie4=yxHRtBJ=-z&ZJr`4#=>h{1Rnx>A1YB9 zE=|b*P^?}iWlt}oemG)^590zX1twqPR7kFgD4lR}b4FLPovy;5sHXzTK@=!OR5aSm z6}n4IF&Ggm+rS76{cpvzy(>>=_bb+H@BP`daVXn?VOg1(YKrySTD)Djf9=eIAM3^h zlAuxBtpw-m{Bz225y(J_3+!3LW49ptlpOW++88gtP&>o-jLC}S@2bTz$W_^?Q9#A$wZCzy28vzyl!)xeUVUU&e>5Mik%SO<)nBb5%rYU zeSZx2DdXwz_L>{A_)=k;>4H=*G`7`R?L-4h|9VCfEgrw1FKHrPH}qmz?`=o_?>iIo z1jO>N+hx))rk#P9!p}-UQ?dF2zR6y15J#ZU=j4LtUr6v@OKpWcK7#G*R(~rV^sRI@ zorupHY45x$;*0hKVduq{+JL}p3D|*RymOUvN_#P@r&0Eh5ikS6ob2nGCo=peOx#Xc z77zW3AyM!`diq61e($bnH5^|A|B(GQf%UTyb(NaK-c;#L$Cz8obIi;~p(2)D6IIrQ z@3i)PQ)W*VDr&k}N#GiXzSw2)rPYd!RrVAmFW~^i>o}HrTA00QH>+CEZ8rU!j*Cu0 zApk0y);Nuu4REr~|CEzF=akQVJT66%1s1uYIXL5ok!?T!+mf-&OF} z*u&{7_zj9c8nwsuy<~>BcNM-A8(~=Lz|jfyDgKS-?Q$&rA-yxYGs)+)d5`QW>FFco z92pFJmtYZm0fDg^QcaC2T;@Hrj#m-L;hBa1P2cq67}wp@--(&;np0zcxyS&R~@9@f#+hVrCPeMW2pb`d(LuI z+6H#OpfVxr0McGJ%OIWMQ)sc+E2S5+f@GeBiLcR1kERN*bPJa$X>4^yQh&M=@Y@N- zM|#*WP2$w~r=1R-3Jr~e{3|0k$s5b<_ME4_Uvc(vELoVqhPPqGHesyVHvGy$=$@Oq zs@U%@GWoS+F6Vfscdtu%1V0|(p*Cw{e=&54W9d3eJHTgzQ3(B2I-P!r z($Mvm^RSn{BVkIAbO4x7d#v0f!advjE7cH!6AG+?fPoiI%F0{5f`MIUoMDqC8LG z$G0q49`^hP&d-R&%>)cdv=)*1AL|i^DsN3KjvRmJL*Bm66A+y5>gCF!dL@|ff%@WU zh|^lh5$TX0d)};p0m)7wNY*ym-n#wv$Sk;BktbLT@U_HmF9`mpedq_!$@2n~*j$xQ~@-l(c{@%q{c|q&rFHR1I@GL0)9*WXAin5P}?D46kE7@^YRX8+K#p#2+Rues~JH&H#=M3){Vah002qO-xBckXhI z=r1^1>G*ysMNaPi7s>hU^f5Se;{iLQ{V3?1L{f>K;Qep6&i6X(*6|P9E&O`2rU-pj zU6;OSldMM3O|d_`BY$agDz_+GaM9lBzhF0jNqBU7Ld`+i=-LZdgL6$yd0ttY4|2fq z)Itij!&sErq*?h|ZHE&iKRknS_#z z4YeA{TebY$3%jEuUWH2@M5=|twWbVBZx|GQfb-)0WbCA{M_3r^s=R*E&6PLhVx;5l zFs}FJU@gh{9)|Jn2I*v)DQdM9k!Ff87na_M?@_lARHh(9DO5MH|DKSp<8mu`zmdzi zb}d7AZA*G>#)57d;Oy|{%$OZ|%sw5CIN;AHnU(hR|2jNu^l&N507_N$1j8kUGB}Ow zobi6B)2!ROsu0|3$gA4~G1K|H@#Jaxt>7CO%JZ1*Gb4A}p3y3Bd#{L!snFdP=jHp# zj=M}F)u7E8<$1S~5nmShzcuph-WAF{3?Np}A-p0v>APkOnd}n+354WpjU+~S443F* z*{O|#$8&?uyY?yNogzS@UJAZ1)#_0?w!<8oX(M_6R~G*r7Q0+FaA> zAGt5ops$Sx1^Ex~;nL(c6qM(04|BOi81BcltHgLPM)hX!Sk- z>m{^}f#omheE+*O&k0(IWhuAYj|$h`DZKjz+FkMY3swk=D4vK4=cf#HKmI)uq&%d+ zDQg&wE{1j^MILsPR=HNd#x?lrr@s`X=Ak9=C-N9p=e+ywuC8Rv0tHRPB;gy#9yROM zCrn`;A&{0~1%jdoUUJ{cTed$gCjV>Kj43k31Mz6V)I zG59FnwZ)L;$WfSK!9a`&_ncPg*^9R`;njz~Bb{o3SP@EUWtR%LTYqd~zmTC``TXPQEiP3)j2$)y@1dy?HHGgG24pM$n*@sc7rcSYB&J`rK~?M`^k0z zB~6=(LS2*a5K}kv&DZ{xsjpjzwBMiH^A%r2qYc}86OOYL;i}j@D>n8sg>tz=^EWgT z5x=g(p714>S%U=181pn`fghu$bc|fP$+kN(rI}!t1n{~)9F=9#hCYRhq>buF0?R@C zc?LhqLf*F7{EbF(sQ$ke!1nH4XM6!e6>F-i*OTwwp8mD(f;uAyE57ZF_XCV7xfWtiBm%{U+NMZXz|ZAfLR7?~Cm=p>x!86qalahdnxc zgQ~eZq}Iy#yrbtz^SW(dv~^kEIZMUFU8e>rpIqG4%CllIChM%^;xb>qnL7 zcX!rE6$)O~-kBzkC%983dHA==o!5Z7QLDxF^=1YLsFYq!fV;l}ZlO?kEEKm16w9IY z9CU516G=?^ch-LlUa!u^FoKYJ`Z|Lr)d)vZR4rg`wHOT66Zg%anI`Whfb*J|I80Tb zY_+(BoY@+fkdx;R`xI<`QVj{e{p?r5Sa2b2(mX?TN3R;(;VD5wb(eFl=i4WSkD0FD zDU^Pe`QxE+4fo)4F*vvT=v|-2BPQY$5b&v|Y%2v(Dz#1xKT39Gf+{hVtZ45=2>746 zZPW{mQW(}xjrQ+!6!%e>!l1l!I^)M=!g;aeYAoc&N zh=su`|B~M{@}3E`E8U!jXG_EaZJ%PYvCYZ^Kq@W z_Pqx>PFC56bQ|O+?pTO^$1`^8tWn~WgAmV*!dk;#^Vk{<aT*=p55t;jFYfQ@-v# zL~N2mT%NVYxV{i!tVK{v^hL;$hw4bpEdo}QKRbe|iZ@Ki;`PgoKbdlA=-mq?6%_>m zku^-2c$uYPOXwJ8zaUfEUW5)1QIA;>!F-{0(L&ZR*Q*A0GfMD4yOO2e#4*>cKP)i{ zQ2IIY-xkZoMsAs_QkJuqFqv-6L;VhE?aH5z*%#DBiR!In7jNThzr#_tF!DtFxw1pyyL9+(2 zf-`~v*h}#x3u9FNB76czAEMOZmx(k_-aYv0QsgUpza!o%IY@$~Ypa`mMJ6lpN&iYW3cR%(#@i)|DJmVzP&z^Blmj|{dDT<# z(k@8XAwFdOWW%gWB}{k(==pPW3$jZKH0YMa8Dt9G&in^o04?_iDN!VnDb!rbn}(E* z$0m3S+4G8&o`-)~78+?lgg=aKdmxyN;3AL_ped9XllrbM$EG|i1#{uS)O6xvxM_d# z1-9b#ST3$|)2M!s#Yb}b739cIaW2stBUYOSY;1U<<&@}Usm3^#s*KriTgo|7u-C8k zPlp2>o~}o0B=VMxc&W|*k`tr;Ni~*ts-o62VpPQqqCm!tN~jmR%YuyTu48E zf^3PE`uJYE`^QU0QzjHa?Oo*1E#i)b2`@a7z`FnwZ>Kb#^H{x|fh_)f=78cP!93|E zm3ntbg}9@vp7|z-5JLmcZvi|*}^uJxq!|J)wiNp@Ws9YQIl{s`ZU)r7R`W&sO-w5O|A@j zuP~Qiya?Mho$DjPhtbWc5%xS_!Y>{DyBL3lK!@owKJaXCeo<`1Q#y}=e?@sjz}$a@ z)k+0&yKd0UCW1jZ;=||7NLxR7%FU2Q zZGN{~*T$41;Pa*Rqle`rPE~Ti=Qj6%1ii_$TS+nKNPGcC zVzAOFAKLLs(-Uc?`!f$Z%rAtm@)W*1(6F*&GUd;bp=={A=&bf#l&^KNW^6O1I4HLG z(^26nc*q}Vz>(L~G=RMYD%@52lv9tLikUEi-KD{-Mzz=ex&B9489vI>9CF!pPP;Qf z9#8k+`F`u`RC4u`20{Q;FhWRxY&WA;GYJ&R3OCLjEbFsqMg&9VG=CQl852j=(RThC zYN5tYlg&9uW1s>FC!F}Oz&`F9mO5asnPe!2m6ylr(jqG58w3QPq8M2LX6&Evr*GX# zAwhl-*eIuILs4FkEWae`_rX|`@3Ems>E)2uf~}mmOnf9Co7*nsV9ejTwP>{yr)a}i z0wgxkiGws)fIW{=Niuoc!~Un=w2kil(EMjYWB&nMBO(q6m9Sw~fBIgoa?+1Cw9aMH z^E|-9a<1gp=Kb)JkO&g?JjMm(a`i*=#O+i;sfCX!B?!zyuU$+k%S-eEPe7+DMYFP0 zl@2o|EN_OvCbE*y7k;VE@wxh@pI5%0m{#-~0qiG8L@=Nc;;VVtGin!-fOEEa^;Vy} z?TQQZA__pSioV<03pO+pr&_er#iZ^XY4;GR^7-CW$GHX-^xVl}{)0K1jb*xyBE-#o z3M%n#jPg7Un|n$anNHX-7=4pb1*c%ooiim2s*llYg1OLp9ftc8ohMo*kOE!#3>Cfh z1@oY<*A%zo77aX3f=E3+dI{mTh9F`h}HFXrTM2jWsHUYB`j#Q1$U~QRv@3L1*q03)%nMB6eSZg8_6#)7-Q1&CJqnaVz0R<==3(&iXZK{v)26j=V2`Y!iL| zRjt`I&y4Mdp}vKB%Re(RGwy&C6X!2$9!cO{_6MT6=4Srhj1yl4MCoR+D_n>fgP%t- zR9KyMg9?OqGfHuzZ)Gfi|INJ-$A(+ofJvR`BtO#CN~EvT}ofdq|ULeDf(0Sd#^wcq-g>iwzk1}Lsyg*Az} zWWB&2q4t3xJ{}$o#pS>ER?eHfG`agT1 z!#Y_-@cZoMC0_+5fSFesa?IBP2>OwnKkB_rT5F#!%+4mZ8*+cTaL!x)^`25Rs^>EY z(E5oX97ouGu2!RkL;M?-BgB>OeY7cIk0_);Isl}5WIr6(=u`49AZ$PUoB_m(5kZ2% zN>RImzONtpr=HQ`H37kv^YB*G9U1y8xP|O@0wrC5Z$3eI6Le9|L0#7Bj+MR=l_WDE zohk77@&FNrqI{}e_T}PvS+_1EA#b!7kT#-v-u)`Ol;qqUqQDeg`#+wR+momRR;Ph% zcR+OO1?@qa6{h7GS&KazIwTvJCc^hLkso#@VGO+Jg#FbQ*UV#s&8PP&4}5++xVRfM z6p%@I^2_o=uM@7Vjm7Ex$9jv=$b|(v_Pm@K(={8+xx}MW^g3zssvR5?%D6?I|@%TNk;lf*X$oV}+i`(`as zi~`68ijf=$#`mI!RoN;Z#_g?tcSKV0Z(6kd#`TOmt<(=%ds3Jdnp2saM&x?rypFIURQ9_CK)8_18#F6HV+2S- z1RC@z2B2Fz`lGwsJKo(JYR;JAAam4F&G|djxYkhXn7ikG$~%p1xg)MEl{UC;u8|eM z+ig53p7#!|ffnOy8=C%B!hxUud)+(8^kEo7JojKZ>~p*-5N^cp-}q9VE2rl6Ii1j6 zoYDSwv&yN=6(@GlM0+u@rW?i}%l=EJebpekun5wt0Ex7|zgA0{Ndf&;^JMx3hN5M)(xe`}2Fv%U?f#rCrd6Dt)Ay75%ZB zX|DNSMyB#G$=ydlGc6pzr*NXHJmr9-a0x2cO8QlsLhP!^5#75GE6-<5LyWRNAOK3Y zXyf))1rn8)oD;8g-7P`}!3wasD?(l;@>qS6m4-P7_|I(NDGulT)b!`Vot|+bzkz zD}W(PUjfmECR4QAQNSGWNB;8m@BT!wrB?}K9J}jp!pHbHcgywpnK&0mF~FA-DTJe!3x z#QIFL#^jN0gc26YpE62Fnc91`ql;Js;YZZdOw~4X-fYuymeJh{{!YUyqiR5FLfG)h z1}OE+0DhCFo|ptbPqu3Vy|8Xip$9pyg|!ml1z2`}Qp`!x>|RogP!PPq7xk4N1aDK$=W`p>hTw|(j@bn9w{;McHXa7y@#gx zr=Lv+85q*S^^NP=Cn$a_9v`tvP0l22$Lm+lulv(*&A3|eM%q(=1I%~n^Jh$6MrX43iOFquWVHR)kJ*)IB?PGMW?0eqWnkD&YJv@AilC&xz zRc#25t@IBIW9s-6-pXly`%kF-%01b_#6ak z)-!_5(9UrX`o;pyjgO=Mt4Ox2F|Hlp{4Xd2T{~}@p%S$hOh5Sy+rAUpeeiLq${1IW zWY~{enZ9%^;GtfKFy+O}kJbdski&hstK)qib+hGhZ8%#oXZN3*)eCv9G@d=t^@kVo zT1`Mfcn6)G{B$z5$t)^=&?>n(y*2<>!&G*2;O@kM1xCSAS+2C4aK5#0>M-m2epH1HdJXy^BB|U3D43v)m zF8geEzb2ze*7T!ivYx50x%c!5?SDa;^5FKV_#ru$j|9o_zf|PEbQTij(+BZdkc;xv zo0`*%kQ1r8!-jcaw?6(Np_<*x7M$LQTGVcyx)zf;p=O1mnVYC;IF@!yd^<;;b7NY} z@!Z?mfT-ny^qxS*4Fv+%@mDgx3PCZ}r@%{kBSCrU2t8bUalt5m)ge!Sy%q;d9%z(Y zes7$zVw$TX10>RR9K~qnj-@d;F_im2m=?o;dJtvv##OEOoH7YIys%ea=yrLFxfU{H zt(EnBoheYlHaeWMZuxxFpFRmdoEnceLdr3RQKcF3F-Ce4@A9N zAdS}+|9IPl>rKj2%s-Zn_E7rTit^C<#lJWau0R_CYyr7rmvA76Jbe(+8u~hh* zsOa7u$=5jjgzfe3lev2LZc8W+#pyxsPDJ}bL)h75b1&#(OX=o(Nt|}VGhGi?jh>!A znj}>}aX(|1t?Z{>9Q5}HDkX2megoeF!3ps>@<2_NA++Yn$xh{ z2-hDUcrnpU5#h}p%FW^vpPOnf&I6Oizk$W1sB8QChnnB(HC>b`D5F;C0j+=iu+y4C z7E%5u7;9c!yT<+%A?T9+Ak+nDUv~z~l<)e%T=u7w(k3C+1gBul&bjCq*J}aFmv)r= z^Wua-ZWIBZAq~7X{k;!Uuq4chOD+3;C7O8+&P|MPJLSPj~yQcdxI9&88u^#O^Es4p5e? zN3}<(rT!Qp%sM_&bz_$^xRuAlje&xBN6MQsHgWs<$}ZP+Qs1yaHhk@2@AQq6Sp)AkU}?BMj?#^OGI{$G%?k=`LfVcS%#sbwqeuo9bi| z;O?z$+>ApMD&Qk;j;aiS)Kqy%ZzHATDJ8qF#T)K+9f8obq;9o;a z&rV21|Mv5%iKal>Y@H_&!ew2<%Y8#d2$`HVX*U39S`w%Fmk#RX zManKQ+yZ~+-2roH4r|^#F48m!D{=ZPXETR{8zdM$2)^8rySSTs5rQMTnm>49Sq~J> z^nXx_$U0!z)g^>(E;DqC#daI9T2c4-&vCdz7(LA-C%hk=UogY>rOk6`N1Q=hq%6eW zHQRNCq^%3Eqkvon;D*x=O6uZH`kv4+CI0uP>4h|svxC6Ww~|oCANBQ>KB;VOn{|Wx zG(F3OjIBp{(P0!iH$Co5|MjXAh)G*A_;(BHZLM>nyTj-Xr%c!uiAt)Z zQ0}6~K?H+`k3c@~oOpmLxsj#}59BuNElUo3Qw~nZr3OlECb9%VVBMl6>Ld=EB@eC_ z`3DZ-y~AM7Xa~2b*8#ZAfT-tpAN(62KB2piLZr>a%3`rR7nE_sO{tNn^xqGkj{F{t z;pUC6YheR)J?@}Lg8D>hASF7r$<3YCSN{?+ffOy4CW!;#jC%PsBv=5T?Ddbgo@VT^ zNrrcpGBROU&w`YHMw94W(*Kz46+UInRAOn#pMKW7KitffT56FL`RGA83FO9{4s@3D zQg4y<9<3?ump5f^apok4ve`#B=)nTJEsKtWsawbG$#z?aoxclB!@u2ASFEnY=1m5U zn~j*s$SX4Ac&*J&8}Eth_;>}Pb?Vv|a0J-dLa|5>&TTq#cD!I=)^k>)MUO}GO~?n& znrH_-sh>bR3S#t<+mv^tQEkEcJ4LA$u)8&@O1soh4`uGMgQe?v+fc1`UF7X;qJbz5 z+ZlWxvM<74LsOu(Md_T3S(P0WX+64W*8cHTss$#FMfl59#RKyvnBTSS8ISBe_xkhf zfAwa;`Pwr^dWn1#pA2;KkZY(I;aA7EUcz*ws7ke95H4(IG*a+mxP=wvPvka>STVq~M^E~p6s^Nk8$PTd z&|kzo@_xp}aB(B!N|CY#|1QH(XhXteb&Tx8fVXf3&^0Z>Itpjc1ET>5z<)w9pIws| z83*9{^6a4SUP9oni}X;Gr1L-I5YTY=Rd|IBnyn!sfg7Smh#eIlbR))o2(T%ck687Y$<?+pDG7|N-dDNZ9&keJ!Fsm;x(#vAyBH~* zm=#nMa|x`tC{9XeAAhpNf+n^EII%)Fi>LdiB+_WGjJDWi7>`rcc?zpe@~gbE()j1f zN4tk%CN&$ndELF{w@*gHwD~NATVkq9{Cj~@JPq_kS~=XMy&xj>cmwVQOo{T*_h?9W zZBuSKpkX-vIXS`}-jpZvY-M(XwP#I>a^xB6r|ITMT;p0m4+bW(t_TyQh^o$0_Z!iF#As; z=ny;8kZ)wesXP_5?vJ`b#CF3y1x0VrjEB88POI;8#OGRDeF!49uCIrsm(M3Hp;B((U)W z8<-{G9}&EKDh{QZg_krHNYTZkGt&X>D$v8iRt;gpuci&e8tbc^qiYF7B|y@0pj@gb z=Fg~}BBDz+Q11j7Kvs+L;&7o>$=e2TWtY6f9)$IlYoY^t6mucc2{oJm41l=Vz4}^q zNld~}>TZ!?3%LjmLAXbCYtmiZRSLSTq`-`bXk*L6DV{4$1)(}S%n9?~y8(t*2)m-% z#SoS|TbHd#`o1MxrGOv+A86dATeGIvm~`u&h!NctJg|dLeouJ+w6FNiM84)G8x(Z2 zw0=I3usy*=9Ta9O?(H1*ZplJyijT3@%}Z8?Ip?3AW>0SJdTS?+IV<*^P+yuU##`Se z%V=qNyIv7HAFc=J;Gf2#tz>^AQhlS*nUVGQu9Y%yOhn}t>z1Kg{sHViANJ*G z%@Xg#w7IZN9gz*K@qIi}YrJ*!eKd|}{>tmv zPvOrc=se9bLAFBhGgRQmG^zF5xWMrBi($GOCfd&gDG6S?l)IKgvxV?XWd60NF1+;PPBW(A0vZ$n zN~9;~3t`^v()tKn-o7+*AH^b~YcS@w7%Eu|u@it!l4mbKklGu3fi#%+Upe2u)^WHs z761)zA(T+3v!Zc%3aw=^Q(UhOvB2!WYJ~&q+c=!Y{ear?XD|h#x!3!j0%siaFPpv9OnW^8H<4Sv?RT z)%C-#*=sh2PB>}>RerjTqh9!EFK=IevCEY5viEw#Z57?y&K7?j3tRD+4c@!9Y7i3T zt>#-PIc?b#3qdY2qaaEJ)aRr9nmr@reoTNX|(Ksnu#GmBpB7gQxHaJ*2+Lzr=+3V)ZzR83b@A zw?MMI(Cb375sQ-s)Z}v>%+FYO={$h8Db%2MI?_C=K!;;PlKerRz^jh;#Z=*dCMaV% z1OeSurvU1_`t)&?PZ_>MA$p6s)PhyrCUyM2@Ha_Z~qBA7@$KwTz-Mv zT01{Hh83G8#6IYRqE^SF3UeWF;qndZNJfb0rNZTj%y#&l|8kqXrU>fV2`|l2~*#BwyTUvMl8{lNJI{QkFju{Rghne?(=` zWmijfa9;Pis=m_U8mcEB$J<0Tk0`tCR;$e2X%oyiqv) z-wPHZTEDW38514O5@d}`Nr9+x#lXdP|dYay+Z({*%nO4@dJ0QJR) zeqYAdmqe=UT3-hP?@q`aRx`U3E{9(0>}5|mR8z7S%=W=z{5g07*{|7I&;w17?RKt{ ziFq(#q-`8=w4q^*BxU52;Q}h;x3p)v4Y(!PuI3yKVPja&qvL`J69g`S>u=ct1qju< z(Z`bQ<8EMqYI`Mk%*e6(BD>8X2tfVc#J8));Cn&m=s&+7OMlsg&q8{6Awf12=Szl6 zz3MUg!MumBCrn_PTTyT#w9wuxEE{QuSk923vd%J1V3a(>Fz7={oi1!Il0QGobtu+nm#ades)I z7&LQK(K;f+T#}?kX4<{4cR4n~@10qA7r3`qZG?n$j)Clo;?fv|&DoONF1_7_b^_{D zigVM5gUq^HFn@m;gK%^1A5((9ES%;$YO}om251@`gR`VG`>%RwE&|Q@f8YRoeTNMF zm2OstiVFl6Hu0%XH(`6dtz0Dy^Ut2ty&0BUTCGHQ3tDOg#HB2La{WolSapi>odtzI z2#*MsaUlf*$LhD z22jf-$#ImE6vxR(s^Q9)(?yQ=?>N?avfOkSe|k)p7ah#*M>&-bBy^EX`hq&nCx9tI zY3jNAKK9ztiZ*@RwD;cRPyBUd zA7J}cTG(guWzz@KfI3F4r0t)LAqU+}FfJ}4Z6lW*_P;j>_yDAL5huMv-xaC2XI0nzOQj|FYTt8p@j+B|%r$ zqt-=8*1x^6If+XQLIsiH6ICQ+E<-^w^89ig3%qv$6iVL@vHg11`DN{!JE5zaCV!{N zjgNWhunrMjhri=C=-N0*=!$tBOy*$VYtd-xT`N-f>|x+d2qoT&bhBJ0KmQq*!zGkYSn?< z5~xf_SyHMyM3DzuarhH+nu*QNz<5mh`Eug?E|K2j=tM7{B){qM;!YkR+wmNA#U}Ps z-%js}M}zwiCfcS7+B9&iyGJA(?{`>Wvl;N4I=G%XQBnR zDkq|&`#A!4c3T?%nr^P=%SU)y)$_nlE3_0C1*KL#!Tr%R(j!vJr_L>vc)cyc@vO9f z$T~A~$tn{VGxcb-dztT z4%LE_bCVH)*g6S)ZpynhI4A!ru^>0DT6;fGmKzF)!ou|F9J7C@zvcU6emwgUHRT4C zlGP@-F^=&2+^nI_1I$&O5Bi9Db)82Q}0%CjQVqUOds*hJS31b~XlCxlm^WF&U zsu)64PQt`2MT)^oqp005#?IqDlPX*#h!UkhukpZ)+l`Ekt~l#|lXq)_PZ^d6(~ME8 zAN{TbO;LPAPt(FOU*U8~MoOwdG_tlsj$wPh_tf>fJn_s8Knngh3`BQ5!Lo$?j%Wo% zQV2Z1F(3iB_%ydavmppYNVx6$YBpinf0KTQN7YhZoR(Dt$h+ZqmKyFRW~3*rAM!5v z^?pq0#bX4;B*7xV`KxbdY}#Dh_l*!@3mURX(GoFsG!kU-R=dqzTikAODdVwT`vn`K zWT}zV-`E%Kje*5)B7Y^}oH>5L+)Zg1095(nKeD-LY2+9)fJy+YBU|y*u=LLHv3bJi zEg}}uBoodN7x0`8?~kq*$Bkh@8DO}aL-;=!_k8xTv#@xw9nF3|!DRpyy@N!6goc!) zDF^ktK_C%mg>c27@9pAOtv@wlIqtY~?xy?-QX!&Vzv`5m%Tlp;p&}*D@HdXTSG4Sh z2y?F>KSM#qo7;!IYkgNC_fIPfZy6*YePtW%`XeOFekojhhUU}APLEO$pv9Un-p4Ql z%DSI!grKQxw#DCQM?W7B4%OfKO~HjbAX)bRX!;7ED7*LVT|#GEwdIXGHIq4bh|D+AOuJ@vz=NB~gV5zP+f> zWjlCd3YZd^FPjh<9=N8nP0v|nPCPaTruOhwRHf&>Srvh%IXrzO$A>mrxE{;_lhCjZ zLLo|kxeCwigYw1lM+%(1$Jh8*Ve)I-8-J8PAN*s+ziYE-crrY?;9q%L?8N0>Te;sY zV3T|CZpYR>klZAZ%|DjdjA6-HnueWA75zpZw_y7!c@7sC!D+5?ek(3%a?z!0(KV;- zT$s`#Mofq^B$6ugg`4ZQ?&XPgCgfSDDeV5lYdwRXbmah*{y3o;YJAnGN_4!d<)^Ci z*{;|}0?^vlUIg_84x^f+gY!iZagaeN@Sw?`u1IjpaIwMm1YlCXb9iyVfB|3zKFzD1 zBq z#W6K-IWmqHKA{Q2ajEhg{clqv2ZIj<7P$kX%?fW)3K@5% zbHMy^&`dJ#EIKdf7br_`1r(oB41OK5c51DCTZ6%?<6Hak^gS?;+e=L!f7@q#mme?^ zU=I7dw=<^Mu_88m4|xmj*z^0RPmQllO9?~%LK*PH4T7cZx;sZg0d0xd9ccbpRZ-YO zJ2TP6I}E#69!!Hnkr?WqfL%eCv{W2SJoyoDOA?QLe9kjA&PK}vYyiLG06$MQv4_nb zJGa$JHo=rSkRq=~p!>G1Q?hF21pKED&X#DZcvoKAR1{c*;p-xFy#39dxB3VH7%$bP zhK!=8uz0Fvdi*8O18mvaSg|3xJ%OvJlHFjtAb)m@7K`=6_nFMW)Sxyjx=^n_6;>Hv zysPlp9WdT5CH~YaZqn}o(qUZuXv~&CS4#R(l+63fJ+=!S*nr`8(D{GT<1!b`hHW!b zYtwhHNq}QJLbNNAA*@lLzb|UY1OO?q$w(seWX@nra%h_hBUfYCoHvQ+rX{jbXB;V6{a?}*eN7>4be$8xrL7#xf{ z^mXL@B$Kxgy}GxLk$b3x^W}OnlgyG7;qlW68aRG$6)ujR_@O& z5Z4lrGvAsi$4I9JMmq>E1apv$Jt$*1DlcFaO2hVP)9KS=*vA|P78N)dRROf%u>k$0 z{(nLXh?iBUC2NsDxAF;hdzUMGtn9uo3VSm;13Rt~NNhV2L>JQUUKPN(E7d=ZOBt76 zV>D@qd)FN|Hr2WG2JcvdV5CI&_UJ}KQQ2+k-nZ>@WwrX-Cidg2x-GX_bfH2gyN}K% zt1#S%cfUUOTxT5_{Cz#POIm>+kc2J-SU`R~_N>ndWErpijjHL}TB9B6S~YeY@i)RB z1sH`J&)&HQ3OW<)b?Jgi_v@YH096t8{&-E;7U@x1i@nR58Y*K??6_0SC~5e$ygg`v z(HXLeEj_(gOTfu=W1!r+Gp7%T;=2oXp;tH;H9Pp=V@7L4ALQmWPI7pTvt>~1pxg(Z zdIA?~wlK+@XKP=hCzvzJXers_HQkm&H zWp3M(Vt@5Tz8-{R@xh}~)~3N~;&mx~^vhmCr~C7fJ{w?*zQ>@5dhgcS+vyl=d=PX* z(B;pL4#?Ohiq<C>Kf+pE_Z$_4u4pQ><<#Vm!^Ce zMDZdViYV01U+)#*za|l#LEb6yCu5E0%1YU8+Kb^mKKwWLBiiPG(Pl`124Xe=I-cl> zpXHU9H{m&9dYGVIs-&Y}WPKXtEgF3G^|10p8b3%zjb9Lr{0UsXghZPrM zluo|dn~8&#pvz0NR7VY1cjFHpXf z%VJ4Co&@;OZluovwdynD=@aEyHyA6&x+5s?=l$~q8SMKrrzPn#SfHw7lAcUoFpPf> z5Z^k0m!A|vRo|HtKT~?qEEp(4v5Sny1k6jzp6~6+HE|#C#ARo+_yqroc{Ig4m%L)l zLY8;s2(6t5{8+KKZ#BJ(xJ+2|f{48mD%02R)&$E27GwD8?^J&m(M4ed#j;&gGbB3u z9eJVq1$o7?{4=^gd+IFHshfuFlc#S83McTcDCKV%%;#d?Yo1G5kpW)!H-bPo5CIV5 z4GR>-arQlnrKYU>4-gmp21X*Vk&US zTTmm|kG|SJAxh!zHExx-n|~E9xd=c zW(BB?;;!fcp1;2?pzAN}{|GYP=>ayL$x8G0q|4;fbgj=|TO`jl4Fq#apjTWbY40x< zDA{P36wZBCw%tOB2RiC{qtyWZ<*O;xeuRgns-Sv*Q*uYV^v4!9~7)Jb)-M< z{-wD0*3X%*VNd$8o$-FGp-Qwej^PyW$nTKua=9P`?Wi?d1$fB{O3Q!^4_>|y zfB9kNx=2fPz*^o_uJfIv%({b{$lhNNUYyN8Ci-Phv#G`|FNcHTuf7@a z5PV1W`!VFXEI<460#icd^{M9}0 zmvyJA2808Z8oCiG^S^uCd)1WWE6O-J6Q;tML-P(ecsBL1O@vS5MADSgNDlhYYmS<| zG8)7C3LEf0H_($Qo(49;a#G?HI3AnO?~?SR?ud~i0_aYpmKLX9H~5XJ3vf(BMw!sRHuuQKiv2{*E=K)92QS)SE_6* zwFuvE<2wmto>rFwX?+s{?-^a0cY@WxohF-l&(+KxKma_9O!YA>2m%8QI)1-+dUugc zFJF7J=j)DTd7*}3X7+99{u<B>ot9gJ0gl@-{z;Th5oS$D6j>;`c1(H!_U&$G13knE?)u z4Cp?l-bL|aIxtt#>_?p*=Tmx+A?iTpde>_GhvfL0FGEr?nb9;@fxXU5xLOBUaqP#- z3h~%mLc$j)e*Pa}u7-FoQCV5h_6&zjXvJ%k*BYySxqF+KYQK3`P_%|ydDhN>kN9;^ z^VOQhq1Ru#kv;(q0Uc3pJR0LRw)TMk+R)g=dgKZe()IyL07~plDlA_evKtUV7_bL3$Qd7?)_v>(2x`#&eKc$<6V;FlOLM~gl?*AWwhy`-|4&O^u)v;2CM-wnk3$p zQoAF7-P(nqNKS(nB-t{b>Uc=rdf?GjB*T(^2Q{CaiQ*Y;$;Ew8BEk{^V3qKt*JLlL zv44ciw;FlvN|yvOTt6@a z;qJo=U>d|JMtMo|D9}!M-K?F%Xg{n$)%mcF(7rz5{2Q{A`5i-YAvo|0#$5r|ya;-L zXKo7k5f`x7fByI(=u|9_1CUG-N#gq%J-cD+a;&G*QCfEl0*2D~wF5I@gJS_;l~p_SI}x{YW2&%)`KU%p zF)Pjj1#Vm(#X{!C4z3v0;#ZB!u%G1rXU}YSDZ{!Gd8aHfpDJXjec-fMsna2xmcgTz z0&h&kBI|>tXQ{>Z-<8HD*(VKFzzmJ;Ax}Lz7wr=Hh z8!*_-!C}pywN)+4XM9iM3zoSDEGV1S^}Y#Z{}U?0gA>J9MBvl>hhyEGyFC## zD5b7j&+8K{(-n)5M;K`P7s|dQYDZKh(lXR&z_cwTJRo4uE{i2ZBBQTmFwDigM@Wh; z&lg2W7>l_*==#x9PSIEz8c&G0ilP}`IO>p~XICjm#l?^C?XqNEd44>~a-O37o%M&l z^I*$-td=x)!kl;qkzbyD-(bC?sUjuzsnY5>K<+qvidbQm6<;bYyqpM&ZyIqFvIV3A$bR6Dm>yz7X^#b;@(FnfVqlRVkG z61**>%Oq7NZ@D3RI%TJeoxxytJTNVwpSBhjI_|7Dksfr&BzH0r+#v{Z`2g-;qS&w1 z(yL78`+O|4+|bvuhUPDZf&3y=H_;+vxkd?U7r@wQntB{!+PKNG1U>kX9@!Z0O5zLZ zwy%`!ywMPB!HZL+_P)&q~+cmcQQqWUQF&H<7rZUxaY%!`ZWofbF!9j78$h zOt>5v9uwF#hHQ*yF+CqnYXCAPnjY7%?1}0KJ*G*&Y0A6uzYf!Bnc8zv%Neq2hG)jHKvF>3e~qoPHpI8w9Q#S4dZk$bVf8Gh ze!vW?9_>(Z1=mWv6G1b(`;*89->!Z^f>SPq^D8>e@kmj#L{NK?$EQAr zUA};1>*tVt-azq4sm9-$hJtKPTj^Bua#XiNkAl^|=ZO;cT1xgQfx{i~HlV(0h+ zSl=y8N1W;G$;C1y*3l1OBL*@~3aT(fFWz%-si(NEElFSl|J(4?DP@Oy=z*TBYJ;iW z5K76R`Z3ZL3&Y<9)URGz`5p@Pj8+g5I(g&aBhhGK1HmDPTr$FYAyd657{3@md@ z;fU6S+C6{DLJvTHK4A%uo#j>coi07EJ&A7sb5R<@~u^Npo@XiOFgU z?RB3zdxz40kZIoa+C7WxQ2J(XgONbG*PDzHv5d{FE67^A!jY~-N;+>@ngHk<;!XZu zO)0L%*)Df=MlOFIYeu;(=9p((#z%W4H3}6UjJS-O)$uw^EiupYuHs)=v;eO47Kl5s z@^$Col4YF8-EIzQJAb)fbFrftA)dpwQr&<(p~;$4@Tx6qPBz4uGC z*(|qnk(RwT+Oy<<7~)3%S^txT={+CnmNb9YUMAAYcLC9%V?$Z@#U4frT^eFHEb`p# zV#8Pw0^R1I1}tHN`o9S9tzx3F=@O8PmE+_$Mw)Nr7@U*xbpN+!Q3C&Am7N)YDT~)@ zaO_u^K{|Gb?)EG+obycne0UwfCX;6!9{1KKbUl_P4~soL5}}&sExxF1tAD>o!v9*3 zIUO~Mi%X%{sb1%MZl36a8stV2Ua4bxzbtCZi!p*@j{$Od3%-4A`QQVD(8&gk?P{d# z$n-ZqME9CgawPovv69z37hmVn`6#u>mhQ=qR!0N8Z^nE-Nyfw@%S2Mc{&W!x6mOw2 zxYBu5l9^S5+Ubp1)5|vy{qq`-Gtayjcd%8ok- zR@Rfcujgp{^#>m)w-pKh`+_Ah%e@FzfU!cC79whxjD2OsNf3`6m=D;bc6gCe``J(C zREvA|tRF7Cz_)skMdJp>{?=UhHW%2%3p~soJbX4ob^DHVTM*1&4%#{N);m;1SYp8A zczV2;QT?#tlqlUpbI$9edr$qW6bN6}ILmvcvUvxEAC0VUnMmK7U3&AkUB{{J!YA;% zZumG$B|Z_ArNsX6VeFB8?Z2TkHSJX!AeJUMIp&rh>D@Txwr&{vc2tBEX~%)#!4b_D zMBGvFo^+OlxPPKHV3ydh$JFmDn7U+A*wxi;&=e(IhwEJOy6PuZ_%@}_>Fc3i35raK zO@iWEtVnu3BrK>@-B8M-4&5?E%LL1)Hf{dX=`<{t{2c%sqLIG`syolT*+{z30m z)f_7~>^r`pKA}G66$v2(Ro#hP2rMHy=TzB%JT!^aEJ3Bt-V~Sp(nD#lALdJmB#s|{?WS9u|$%z45jJkIF=Z+TLJX;7|G#a+b%`Rz_{#o4p zX;Eo5t);PuvzW4^nNuOyJqykQ6{#I{WCy&bgN1GuH6F9vza2B{CmnJ48q2IiKZ`sN z!a>;|dEgNr!r(JF9qd&YVzeeixL|FN#tjgd4WxYr;62wys%A$C-^VMb&}=^5ef! zRWoF9?;;$nj_D(Sm7GGxFh*x;D|*39KcnQCu3<5IEivaig?B+-GlbcGU2Ybj8_G>&Fgxdtg#S+Iy9Xmvh62U25s~R#i)bPVX z$K534F8^}Ob5r%lq?KU19!e1pQ%s5vth@`SAsKCdQU+F_T3*zuCi+Fwhz|9LERUS5 zFK!-|731fcG3;DJ%lfJziOZ@9zI4$ik6mH;@&a5MVo~`ZDP4a*JNC#koo5%6qF?i~ zU>f(rL7mROoXtJ_2rD(eHOn&`K*YX@Pum!{8y82fzgqmH#XMpc~?urizNW*^Ztxv$(`W-bVgcqKQ9H=(|_k>@zphh)1uYU<@ z=*05_X?y~?$wACofP|qsUea9TCpn5#jMfxXag@c5@e{Ke&`NsDC4BX_oIfR6!q2-Z z9{$`9?6f6G3>X|@ktD;u#3$(qI$ZS!LX*q1-|dsEvdyHe(U$v2Kj!h6G*eM* z9ZHwn|Fz|Sp#3;jt-um8(fm*qgc^uP7gJK@4uYMFTwHPtYNA{$5#I3^VIl5X_gYyJ z6b;@K$*Q%I3e9ANXCyiule#MzL;@Esr6kU`*ew)$Vp(mb0V}6`cDqk7fc2_mEHs73 zEF{Q7k?>YxU=t)R5?p}H`;$3R@{V^SVDD=t7aU1_yvCZ~#`tY!f@TcY?+2E6Qm>aV zs(k@*Niot!PT#;p-aJF(f};M*zk@AJqaCkCKB&SS{W?bUf-^5ix-|)v3Nhho|0CN? z0$R_z6oihzcm_Qg>~8su#;;}-!+L7So1p<24jm?=NaW#r*#eI72ZlS%UJnue}sV<;kIBbdjWRE-Qp|29k`W$%AWF zl_fcR`&;6Jf9u>nxY9d))dUE`5C4Z8BvMXF@4Hu5qEYe#EOZ_!kh zJ^@#FkPzjf7?a^l6J?$_;L>YmZGsep0lehk5JN*dk*E?V2h=}NgMd_x; zu0DYDFcbC;S%K|SXaC-_V6ob>;A(F|UjuXH!%H~ciHaofylXm<=zi;x2b7WRH90!? z`liQ-=qo;l`j5*tzg~Cj)rZK8G@OZ2F0Kkyp+afn&)Vwx!}#@j|F{Z82E0*7(CX>o zjxNaApDQ_0L(6@wG#T^qJ1{PtmY197rEpc>vSO{Cr zXX6lZ_{8sy)p;F=e~rORLlrvJ4KCaS(PV^aFjFNia>@grKD`Y2wgZChViA;sZZ|=7 zk}(K!jKx0M?;0J67@{A#ZdA$oGxP(gNx=6&Dimz8k2%Zw82S~3oLJBJ+XBsQIKx?xNHaaNt-P&g#|P$fBtko=w>WFu37(q-nH4YX|eKE2=V#F~!5`9jYTDh)a!CTa|nwk+Zz3%j>$6!g`)X&khO> zptuK0Qqgv|(OWapZAGwu3${>>c%ZZa)TC$@z^z@3uYA)w?}|ngT#=ll_9MKYL*H>< znO#xsy^B^_X)*Jo(y<)_~dl{D3cbO8C5>{L9aMZn`YV5e@nO41WpL-1?UU{^l3#AEP1~j6o z3tmgd3?ct=?R&Zwt4ylO30lU848H6E{)$%g?)LZXoP3h8rO1YuX&&XtHlgmT6xB^5 z&U9aU&BmDBY;te$s+2c}8P<%;hjbAHI_dxdZ|*~LB(Wz@eazpT;>?Eg$2_mOLHA)# zKq&PN=vUa&m6@pfZQm~fmg(Y$nKjGzQ_{39QKd4k*wbq%W(Ho5mv@+;BlZ8?whpUt znr(Aw@cIvO0qqg|H)ef*`B?XvJItd#y&be75;Y3?@Gj`=1KI8UViqm`dyu$Th#&Vn zHC2Bt#adx_COg!TliRV~LUv(|G~=05S)YXXcHrlqHMl9ho5(Y7@d6cnswU`&h`l+J*x1w4ic>%2MGqc zBT1A8T(eJsTMxAT$R?|C9`3jXZ>hiw(*bD;aku||G9@~d;gwg?;pbBT;h#p59OJvL zRpC^#ua5uvP5d=Aqn^y9LYB$J6Tu4H;tcScNlE8+x*Bx9bk&m5=l@~Ftcn31VUK%n z1iE+xcew!s4n4-wsHuOiWFaletfwks$%QX_ENIMq&Yu?0pIa z!%APHp*w>RuNUEKFWAVtQ=OikE(}HWgwr0MLPJ`GYJT&+TpbeB4(ExE*HwUs$Tnk4 z%BNX2lZ@F;R36SS~`}KJ9ZuQ zFlJ82Zw{QcETNmmj(=rC%g8y-T&*v`<|LN|1M#ytA$~F#2XGN{_(_ZXs-C6{3UCf@ zoC2zW^i0=ka*&T9WR{X8+5e9=;I51?8qPI&aViSAVO3^AMyQa%4e#DdRLy?pTb=0f zVtr5g+-Ai}RzLYVFrwlq1aN)Aq8xWS^mta!3}Dz(m1OudZz{ED zt~ehgi0N!*yv#{kglhD(t5>Zgl_c8Uy67vcN@NYcjFM$tOjWD5cIF%n-X~2mHFa?| zoff?qyKFQq7naF+4iaqvnH#TSsXdv1P=Wkcd|#TH*$j={=7+4W8XD2^QziwILVZ8x zILC(cz_%;2)K9u^7Q7Dnc0=BU3N&>}4EN)6Hh6Z!yJon z*miFF{%ePipLudzFR&mol1%Q8cp(1il(UyO#KR8YNp=D{18Za=$)PE++Z}W|82%2L z>c%L8Q}}C1L?=j!#-GxTJF(WB>CuNs7YeqXO#v^%I6=56^<38)to1UKid6na(5&gz=zSUvbPR%%}Q?C*b0Ghg_ zvyEibR0!pMpvy^OO7uXC*(VfG34KEq2i+PC-O1RIMRrs_-gavsUaL@&G?l73+wETg zb;G6T*FKbsh{wlcrP35r+*WAbk(*oXe{rGtLPWM_ehm^6Ns=(jw0sF8`v-8D8ROf5k%SKOA=f%sAbbTbLx-2*@vd z;&RV6B_v9V_Ko!`8BVaRzU5KMqD*?8sG-&)HRFIsjulN?VF<&j6VX_x5T_jj#w(YA zC3=PP-6|fAdeW6yk7rADYE*`qwxccc-n4Nh7N2m`Rs|oM4y_rFQuNromT(Q45qqw9 zz?RyzCWd4KS@J!_RJ1SqQWR}c1vRwd9f}DnJ`DcZVvQ6{(Q)w5u@#Gfy=#t0>^ zkNQ?jgmG%`yKC9YLQg%5dc7_o*RK>P{qM)+Qm*P5E+|SI7v43Wlw9f#*y=5q*QYkp z{N%Rq3fQ~l_)EZ+AQ*F|Mz;O?PyF|Q4D5!fc1>C%P{xD|gd7%=HCI=tsdmygn=@EvtO!ZWrAtf`cZf|!27xMaEQ@xH_tY_ zQT)*6&3sh_TRkPv5x4VVG_agPTg%V0VlDg;pmea@_j>X6Fyy?Z}Jfim-1g? z+@m?`VpUK4I5_FHAQ#L(-c?n;X^c)Q53%aGW@Swe0tOLW!yi7A3}*}k=Ddk%SoBq( z7r|TtCP!KLjczTLphZ(|9z?5XD)`uXw*_lCX1HUp+l~s%Rq84u_f0^Wjn7t?`{%zS(r58Vj&;;^Rv(%m)4~D;mS6v*D zQs-v$9Fpk2P!!ivZqr54=kO0HM~~-S+*G%>izlG~o*IdPr=`1|x z>>Zi3N4T|Alise??S4S5xPsz**WgNib;UtDZ~tD z!4Ej*@u-gaPjTLx{D=L?_AqP_odX&tEbuDzy;}K7)nud#EG#sW&1|OGY@VoXJOnAv z5U_V&rIYF~c*{I~Y3G*=_5ke*i0%vjgyD!JTYEo0`NjcnM@V-OZiaqLt)C2&(ne3) z824yiB=se4BHcMu&Vq_1qo(n~?nkNHmd371|Aq>f)EU`Zu`VIvx!sSFu`04gRT^EJ zUt!prP~O4~ShC+R7e~FYlvF=G7V2(TiZ3EXLwCi$m95|%H_|`IG&C@d?>6Kup6O1J}OcXPPdY{L{!C; zaL2$kER?Nz5*j5l4ji&}iHGh410 zjGN1KE+d7TJNAr!coV2EpZSf)UE4_8DlsMAxaIxVx)QM4&uh3=gjri}bMQz+l0+pj z>^&~w9 z%Pn-eeYw5-GFD@`zjdWkB`6GfZP0 zKZq8y1o^4gtJk`V41!H{8P0H_&q4EiQ^dXPKMeHW=Wk5J*sAi;J8NobjOS^W27}c> z{vOEwkWm772GI?1Hct@smUd7LDb=mH&BDnIZIO)}14aD*AnjK)!w_=3(%3-?lpE?{ zF7kPFhouXx%NF1keML`3|3TU4o=-%tlv}i_nd&tQDt{?xi&ftedh!~A3F>sBAv*AML0r|E-WSwF|hn2&?Z=`Cx>aEGspA%Ks%}gMgIRGdGn!A8kM87?gV`SAqN(YK5-!i+UZS-XoyF@i?_3*J9ASb`R4Cj~}IUlOmNdsaUF3!N~6HcE=Iuc3`5|q^l;rJ1q zv`1W!2b~3DMWzRN*2OM0v@cg2p`j=_peB}IMVa<{UVGCsJ>Deqp;WU)K|_Rd%&y_m zs7qT%GQkpLd^Ndou8<}PrOiZxAj-5;5@jcUMkR-rh#x$;2~Ok;pH{&s*Z zgi_tIbEH79%PNRp6X0Gjx>DPcZ1r))3fEM1ILeAPUBJ3$o%Ta__DF^F5V*#eYV#+v z7R19B$3BPz#amL__5&5pY%(iUGAEd@WdpVpXrEZL>K}YYq?5WbmaEQ9J`ozyf|14u zr`8ISn!ua)nF(`#Pj<^fdh`O~hr3TM5;)yq)qCT7Cyt{O=A>SLNzC~I>-h>x+ckqr z6`lU6<;btIC{yot#WX9aV7ax~oV|rHCM=(0G^9i7Ab_UGR~P#O($U6GfzArWObjXR z(FYSK97`!n#x*!1u{jpd&V*8%Ltt}@NDFT$!n4m|xcElu5AQ|WuN8f=eD2({%uJ-@ z3F8(vKRjP*rKJP?%! zjldJM_$hnQs#2qq4at}QFX(e#zqPcQYsq{AXpON4($oTLy%RNXezN-gY00W25H>m9 zJ?pwY9j~Frf~hyr5}<16O80){phBSM3#--AJA4mzUci|IUCK9;%m>(!l?TdGmV`RW z2}WX2*{kvT9q&}i&he1dLlxTE#~HMx%{p*DF~!#vY&uplXgpb$CF+tZYUBbn6;OkF zD7#bcg`0xeqIb{VlJ4EQkgHSIf1B_Qds&Pwfd zs$cllSNUI%bD8VHAz>nqkUQI1IsYc23n<3hSv)0we{ltKIB^D9FRuh$`kQ*oXohrO zQ7mWR>h92mfa>;qQ_40 z6Dzm80~Fup<{iTfK(mV+oucIRyAuQPNdZ323DcFWtJXRO;2o#7O_6S0!Zn+^S>2u3 z^;1883yc9yxPTbn{dSn7vdW=WVFlQ29VWnAt@Sqp;6I^%*H}wBtQ;OQuo~LiBr8|} zIUq2+>D}taEj{G0k>#S9WB-<_!X&A;l~Tby>=BT^;=7d@cFIuXWZ@_2|@=Rk6zp zSg;AA<1WK86}oLgAiZTEb+d)I8A66ly#sw$8{1R9;k5Ib zz1S?K5AaXb5fU|}`^5s5kF21ZZ>=JR%z?JJ_;lC~#r?+}AZ?c77pQrP?ECpxm7T$!bOAE&4Q z&bd16m_QX_CSUyN#XwHF{E|Cvv*go0XMoQFex^=07QbUUq3afEqqN-f%C*ZP_>;8y zUZT5|g4UHTZO;BfwPd^%u|y@4*M#~vsXYL)g$alb(yKj%2lUqOF1KO=y#CF+aX{o z?lv&2=AOMOu6ZbDW;aeZ_dYa#!aKbB7WbOsK_mEJOM8GKFGTXOy64$t_Nt$8^1lzh z2WMn}P9KT*++icxw`rk7f;tu8RD@luk>{GgbyUI8A(x-Ac9drr;YS|Eq)u-OaS&so zdg^H!@rsVWlQY?%v{))eqF?0h^6<<{>TD7&Sd}Vf3aY*>i$XAff57IP_xDQZA~6wrZ##9Tknhiu5MTCwk6kR@QG34S5`7J& z)OY)%Dz;5MPImqa#kUl5@uwGxi2qAni+UnIqbW&|+VIat?1>mky)T%tX88pKxkNd} zd`@i`kLG3ER;8Bg(UZ_BO;DOPc7TrW^-P+%CF&x13|~NIaDye`?F-UvEAVaDQX$$S zZP?guz>Os{0CUF*`wsN#FeE50f+;v{B3?yy)2t)ZwYx2x_A`hK+UzzEML$KHlH+tu z>?(||`0*r#AkL#DnnUBq0R64=glzw!a@65^VrB78Bo)MFq*xx5$#{>@JVYhF7zQrd zmF`?#|JGr}e$F-;g@fHiK0~zTsSA(nYXPEbS}nET_*P(PEH!o;VS}hnfJ) zX<@7QB#{!YCMRy%*akxQXVrHsg$Z$~JzCUx+AejFAEavnY@ds_gA>d*nW4gla}LW8 ziM6LFde^@2DHC8xhl9&E`Buk+V%W{|bhA|y+tV~{LCA)v_+SA~#ieOC! zppfoA)c*=Vq1jaPLh+U+W9wqqn@oF6S@nm*yx9NaNq!*FdKJJy<$D41#`~gSTCO#h zR2L1w{4bY%Cd2qS@I3?~&upH#eM+J}QWm{X)~*7`L|e|QK&;3!gJ+Az3IqM-Z-S&2 zSK@-@r`YGkApXJFhaAMi;gfH&^CMKeN4&wIvpU2#>U)m;K&H5}dOsF{QCDsy&KixV zEQk^06SE3sOf z4_+q}Q+_E$Qd&d(PHoskAfE(i85id=kol-GKe~J!B%1eIK7o&oaE?>15YPQGzA zO@plNQHrL{5MYZ{iQ+N}sYHV`E}L z(@uTf;#m5w5D$>;P#JY?wOYQc9zZ+$Ip~Ctip)HIHl#wPo!3l$Mez#&V8=EJAM8rc zTUgV1JwoLjOTPb+IT;GhWtgOg{mOn6=9JpM7V{q8WCEZ&6 z103|gKKOW5nj$`>&jUa(0{>yW()zq>3eL;6Qd1*~Z~UYFfzaRDF@j!^Npt@h@cjMI zW?%p}Xnzavw_?D##^pK{!kq)3&E`9J4MTqHBr5^BDJ^M-kPFHEhFZ&W_0O?p1d3`sEs6;ff{e$nnnHqWdJj z88k}gjF!Cqm>0D>>r!hSTnM1{v4jA)hXk$*1b>htyqE;4?q?P2^QWf|XQ2m5koO=pX+ig&#Wy??s=}3Ia8_5tW&#)T()eRn;7YpmI)bwTV@ixLz zh=5U+W1_U7Hoh0oI<>ItHb7bv#HIXjIG&L@>>?%{{1_2ez~Mp4Lss*z`_a-f%)-_= z!ra%r*u%^;^UC!HbUy8749y-vc*v6@{tROH;%xzuO9X%|`9u!nvBW+N%bFk?v=2pN zF$A|XPle!>W&RHa6KNWdV(zkpNt8vJzWHDtYhO5O{9s01OQnu^ zeVHQf8%opASRUwFiN}oZwCcc=k_1??gj;zG>E*$#>h-5aKqS`0ya2W;N1z(?qPZfI z`ggfkZidnlow}K|&P^2$0L>CQ5|kN{?mEv_TDQKlq_lexd1l&wEnImkzQGruQS*(F z6$=r`NTZ%5q~VjI%tWO0O4EYTk!Dk`(E_y9VHaAV>U09^`HonlVN%LLtLeS}^a<=< zS-u8v0CU`uY;>x7{Z$Z@DFvh{t5&GEW(u%XnW{ok@tn){H*MU3YMOXZ3+&?=u2Bz# z-q{e|7C5Q9!nbMFSa1;Km%J5yz#bO%AqeP%ZQnuYf1;-`!;wZ|0TtK{33554x%uLT z(4~6Jt#;h~EUZE{qn=Wj%?c)p4ca?x9%b&NO!Dk!RDm`=J#xEA1@F(Hr(JGDdRODsH9oyDVJyJ>4vG-Y^`v z-&XtMOpWc$sfbwZ)N+byY2ii8*1B0gLvjMuNpizs^xC3>P^?K)-d|^w3(Cof@}<5% zbU?Mk1fVDZmmXv0r~}yA92|8oaH@8FJ~?ab(p>0;*we@E6Uw-W5vI zQf8;Wcj8?UzykHLgqSt3g@gNlwt@cboDCpzO`2IU;u}d=Tax?zc+qgAd2|8kS68&U zCvKETl>Tc0_}m^eo*e#VhVZxJHsa9^RTP?LRK&fw6meF#^isqq$iZ_dLLfY;h;I%H z%HoQx0V!FHcmIZU57y9O>3lRKq+7IKU0#vrL}OJC!~cA?BEd!!DJY+2P}egcp_mUt z3_mp9dNHkpy60l;l&t>O=pL#^^QH;^GgTIeM4Nx(;qyiR3OljLj^>Xk$Y!ekR*KG? zZ7kYZNtS(7RKyjhY^Msk;qZgL9|#H|ekC{2-dQb5bsNzo_RP5tOU^iuW+-&b{HP%kd-&H_w z_BPR9*tN`#Bl1j!D*H@;ijJ&MFGXEf^EhGbG$Na~B7w-=uE$@QUL0t}; z2y&s9vO>By#)q?vEXl;2Xva`=f5wT6h?!EH=1*grI(dXfK`QJ}(G}8do=raEk)TZD zApY`3j_*u~#`%-D#9f3Pr!S#7qkTl(b-Y07GNkj6W7M0QL%V7WEQ`gcT`ofoB||n~ zSH#@ZZxYO#{-`dXnA`fmL_MFVXfuf)u#@EwlW3q>FRK^L_@0q_%Pa#|u!HOf`?sPrdUswda$GC!bP z)(QQtzGn8W1cI;Jj*&bgE4bsnr!yfwC+YD<@M=L)z@Ue0bQ1f%Y>6g#ps>l)_5RM8 zXky6#wiH0)5>8JCyR$5Jxm4}L-p!f@#%`c-42*oZlbFn&Q?MI1&|95g*#WJJblza6 zkMPEmMjw{m>^BHL(Dx|arg&ZX`pFAotU~XLr_*>TxPp#n$_M3vX#BSYTrIVi?#hf4 z*`v6o;4_NnfVk&YK@j6pudnG_-hmY3;etGJ^EwU!7P~g zQ$Pm7e+Smqiqy3^jOXD?-~Gf4Fn$nvDPqr}k|-c*1nS+#d-q&tcG;w9c`rsOnn`JC z=%TTK%N8dr*<(-s_{^y=>qvN}m*pF$0Yd*Wb6UE5XxNM{$Fm8`(pPed6Rgc<-KOGh zpNeIfargOE!fd%vI-tfD+^rXSjtR~BBmeS7#(^3adMeyKxENGVGr%bTCXuGv5ifO-@J=0 zxH|!YoW^HM16N|cra0!wF(@aPWzE?Ge??Sdtq_3PTf8J0qxk$%oqo2`(v*G z-$v-NwspR_jC44p$ral2R1+#5V#kV0{6Np+0aKpTjzdC8tM)s6GW zw4(s|Ffe!|yOP`?yE1V!wbA5Tg%BOU3W38>^=6xA)WLWi*J9o-rG0`Hm5wJg=%ni& z3gqD`+4Xi@j6YW(7rWL}a ze6C*SekUPGZPf^{+>xwEB>4>e6$SG@U+*@q>}GLYiSNDUTTDsgnvws#lIyX59cJO1 zd`C>l_}Nu#WQYyRwP&-DLG@)J*n0SHnWywPjM;8+Vz+Vr`~;HHJ+z_@fh$s_VSxp6*bhXnjKDi04y-;>F5(_^+CO;>-i@;BtSpUEM$9x+25X zswkn$fb_swApYq_hodeaX8e--mRf~3$Alqi>Wc~aL*_61Cj0>VWq^0#E#;f7)DDqC zr@56x-+hMyNVEZTX(KjY6=)O6ZRg^6gj~h)&g*gs*ZFZrsv8t~90pSn zFJRsk%SxNucYMi)momXHbJ;Ro^J_v>&`-q7U1WgX^GG%1B1|V)oAz~R*Jp$FOJIb? zb0eLktIfXW7;4cJn1F3}4ny(Mx4ciyDgKI&_m|nRvimS5`3oR(7!Y}fnEz&%RJdJJ zaYChg&SO9O4ik_0quft;V)d5ehaVdib?7Ikh6QJGQ-tnFpHrH61YROG>&ZRZh^D zs(SWaOtLi&Dq-;G|7+|Ql&2hQEx+YEH}b>aJ@#2#J~)*&(kuTZ$dGsC&CT0^wok^r zho>y(13!V0s5xE+oAfbv0AV?+I-6qO!AZ5h=y~)qdobuCU>VSm^96oivXTZhzG$ex(b;b@9v<;P- z1_@5LPT;=~@n>aQRvZ?h;|7%`0v|wPX-Ary|Jj2!`3Rq%Svm3-sIg1&{%5A}O-zX} z%?E)F)$ksKz*+?%ip_vjkk@bGV{3|D`gg4l4Uf4B|6DOm0(l4xnQg2hCGOSp4ziO> zQHxDAZRTbaP)n?A-b{x3Kf_vfzKsS;l-5MH8aC~O`D~*OB{k9Le0l48Z4-F;HI0K^+)`Bd37_9yvONc)?J`swgf1lR5llvfGb3`sv@1y-=Ody7Eu zyjZ#o9Lu0t;IYhx*F_A4ir4Xq{8tZI6)|n@zAbL(GoPWRRwytDzb7;*7Ivubr@+)By=lDf=$y2Vs z&Qng6Yq757%Co9oEO!*UsBLL^p3XzqW5pFiXUU;SC6{%IPrp3EY;gi$GZIH2;w98- z<9N(?wz}W_`-yZvmz0TA0uIUQ5r)y)j|I?eGh_V+$^QtH?6ol=|38J9rwtvotJc}H z4tSNBN&lK|jLI{^nC;X26-pau;1UP?L)7->pYN$V2kttT1ASr@TeDq>T;0JoNAq=w z@`WD@MFH0(b9Zp#4~I`Nm=~(Em(}L2gpXS9^qWjCt|rk=tfj^BF&`L6fsyZP9rJrG z9JglBa&B1tJgOJ=@gD#<*`Qi`CNf5tDvy0|*-e*s#+U;xbn55EZf9)bK%7OvY>3pTgTFjdHJ(LIn(I=3&-$h z8|kO0uLKOFUucK7>%fPh!BmVE7@p|n0JrjDs(E@d`6yI(vwfdnc*x7VQEccOas>f=S|(vZEfk8Pj2=F%bn+tFqt@;7;UhFdixV7PtaFKtSO zIk^D+a+*f>CS!A-t9KYLqP-57VU!b>QWq-a$Iwy$t zP;ut3rNy?w*K-P6z}Fk-7@g()s&Wu*+)AQMKg&4_Q9dAXZCS9qXjEQ0n4?_RJRLnBkbBDRR#2eoyzH_ z-VtNFUJm|#4XEJvLZ%dMCJEXnFWK<1Up{C(sP$n2;}v8v5r}`N?3O?dS@JDXLsU1Q za|JgqH4lc@@X;1yOV~y<=@yvOAA7QVLtCD%KDMkgrn)Q9FiiXTjFLMa{`Szv)AzYW z(`-XEySVFsb)wb7@CJ?I%R=8wrY1!uvXSMB0eT?$w(Sw!aHyd2!^0z?D2!0z-}}v5 z`A1JmK3G!Ex&gj+^k{dHx-Xut4A5}GliXKCAi6MQ5A|a10EeiJ>zEjKw_H%$OaNIH zYf1Q_UzM2XdB)gforJ@`9yp#Te+3UZUtjQQR3n;`8da^`cs5u8jSp(knC|nEW4UT}?jxu&<tPy7C}}9)PQ}94Ku#hTxV*Ny>Hb$C8v3>2PRA}tw`xkHw>MM^l0x71LIP+0sqd-g zu<=}^A;p)MfUIJKtHVbE=b)_r#XqL}bEp-|l4050kuw_qiEg0XD2zpE z`T9@Rde+zPDB<)*R7mDy5sucjBwH>^{=*8x*93w5tHw%o62M~-3_<>yUXzcH-{G^k zcUb$1>elQD2K-AtbRTU!llK6M05IIO8p~7YOLH+}%8#ovuj1MTqnou7TR_&)+5Km0 zt@pG&sX}JE750bIJmp7!u3H(9!cr{)?H1tz^nE{IuC^`n9sN<#`jvo-SZWhdB?K=S_@5R)6OVMx z)s;~9%XM;|6q`#NC*9K%z-ip&WDWG)dJ_*ll|ur%cmCFjegzA7rrTnCN&>Z2xAoIS zxJNUgdQnEUzbU`*r}z}JSd9O^B&8Vn+(}oiC0Ro8egaGY#tzQMj`JWpo~pzNDKIsORp*Q zzlxJxTt*LYqI=8AR15+rvby==%ViaA*FN&(KCJ#9fo%rZ3Sx5Cx#8wv)SZr($=Af> z@LDh3+cs4L{E4OZ#H52^l{3Ci1J)j`NIhP4LCR?Hg7M|^j)~Pro+Pq@&K~Wq98_(R zDZ*I^Q~+769UfS_Fkbk}&X69e^>@RF0Z4SQlb=3tc)tFf@a4cuEafh#|EyXah$DXF zYg8TB=BMAFjCa9j(^B#c<+B4&s|EW+@ja$P2Fc*WX|_7Dw9`+ zDgJK0#C<3C2WXzK^`NhJ1}k>*4c)d1Z|ahP@QK?dj=2k}A%2Y?Z}J9^P>yJ&(5h17 z`67nh|b>%e#wOPLVTlh)=`>m7R zk7nepbfdRz>yB-Mtiu)&R?BjPsVP(#Sq9B`8!_9q`nA9-zvno9yv-1+1QQj0ZMv~i z2p$g1+rtkAI_JaPk!D8LG{76>RtGIQql_tE{|EY+EYCx2a{Jm&3kv>9#Eb%xC%_h$ zEv&cj*h2fO^cVBs-$KppeE9w+Xd+`Npy?iNvxa4q0t<3&R0Q)R^d53&iAKTr%m)xf z`48Eu3&{V}i%4^X<3%1&6a@mupcj4i6R%Sb0jG}i3y%ZP?hI93fCGhdV;YA&U~aaX zuep`4;0`m)7^>Lr0A>HYxpOlUcG->9(bLT2%N^^wW<&Xmn)nU}fB-|b54xl5NleTm zQ1O{tMa=OcJ2gwZK?yT!cM951`P4?|w4ixpyu;{BNvG;~>#}#F6-HFYubpSInn__Z z%L3()>8g3ETk2ne{*`|#*^d|akr$#YW*3@znDqiyW*%5@LFyM29FoIcALbjL$9~t^ zJvmJI>8O)RrYzAKR>$DYFm|<^)im|hXL%4CQP+_2`;{uQ`OA=f^xTxy08JvV%B(=rdJlyfe55~tUfUkqO|cS|!9MWY5!($r>94aMwUEh|Qf z>&za?;5~dpy&ASfZlTfdxzn`HrkwL`s8C;#>~ZzWvAb6Y(tH7s z6mNGX=;MhOu9=-kWwKJg437bNQRMbuVb@)pX#v9JT01PB;R<(jlHER}#Fsc4Mdzlq z+LnvMLuI$-X;pcUXaq^P&xilF;IbeSA=vv`)_k@^7ArcXMq4dJzx=BN44GAU3d(Ra7N7u;m*P z3TS2;NVq|!FZ`PVR1!hD(Mxcuhhb-TnM_C=cMZFFmgqlWH5r~bzD*t=7&oOr*(%81%cD>K`g11fY&cF9)V;rjFbq_SHbtDJs#6z&h_>Y2zY z29q#DbpskWz?Gcq1FHm3QfHP?fgzl;9bBR`_d9&T;lfw=eI+<$ZCx35;9-batoXM< zaL_N;Who}VK}7J?Fk3;9^OF1JO6flf@gR)Ttq>H@6QF?ozS!P>jt^FD-0S4{sz9yc z(E&(nxjj4inDn?q6#a9uZXZVE1@-w9wb2t(IBCYVTPPFq!jLH~#T|9vC&0CK9e4io zIkHmP+>wOf4jGX)N4sO7RoGV_Hvv5WH|yT}L=y%*d5vw%#CbF}j9Hstr>$|Q8>cWw zk7z>-3MB}+qX@Kdfjh89ahvcYj+sK{i zT3aNL7fzot#Yk1s5arC$@iL_pPPxcNyN8?N2p` z;KGMkYTKK9b)4nIFgF*PPierrMr}htvKa~h@ZI6}yQ(@APq`sNL+Al?KxB~eN+FyY zej6jZ6=pPb!jbPGZdrKa*598ZnS>IE0R%0;*?%C$o!u}x+D%*nHOS3or|?*cg+2B4 zGcY8*()}ed9K&DqCDTRq5eH^Ht3K^P6Joy4writNs6>tOlbn*Vi{`2a=u(~OnIX~} zz2kJS>FwtVhqlJWKk^Gm)ie%%&7I;i&2NLcaNugHf|cNMrb6E-(4^NYnkV{`rXW)6 zcb&?EtCH>yf>#wN09IXOez?=l90zo(^6vKfd+wU5z#yWqs$+w#M}NjXrR~mwXzqP( zv)+o@D+?o}Z1t^ZfZuMIBCDdL+8qCTyx`BY- z-f~)s3+iYt@d`FJ07NG>Jo4_*KfSRU(r?|W-E%@cvhwcvBm^o} zvri^EG27bpZF~Ubs7(4mLaJNwg3W)_ujPXL!}G+KD&)D=;8j*EUa~4ZIKs?Z z>Pr6n(n1auyjEy{{s^V?;7*s_#E@LkSu+e-Ci{W|>w_7F{8pn5yzQ+hwfLBU1%y?w zhh8L~P!WXP4lRBb(}gs$;@A6*l=nRw243 z57fcpVv1X&Fh(9KaX@OfIrK&%vXmJoYqRc`jI+z_8@#^A<(>M4k@`WF^rKg{k%7pk zi$VDwv@r{TzO%`*EUc&97ni?QfT0JKaOy0;4-_5!9@ni4I^pHPdIhS+DfIe(8$ zzOx4Owc#y25(NlixFvraeFI5CdEDd)O2KXzpyqSMAWy|Hd@5sj_{*FOV;!9rXv57K zDu~0pTD#;Jd0KpsQ2S#{PB0ngy?@nI{z45hioS}U{dbYWK^`nJtVUJY<-?A%Fmv00PXFB{ZD+llV z{+7u96+AS-3$Pd<_m2h{zaWUu;@fb>_>>81E4@)L2Apnis&%tAn>Uoqy>8J=>ScFo zY}Vm={5_a>7onA9_G)Z9JLbmrZ$vBW)DQTH&qI*LxkaT=MJRBo4t#Vow9=-XF z8928{i<`I3qVTmH%hl4`EMUI)q(*=0-}&2x0x}}_(1b4EW7UQJ0HG*F4Jt(_f+gJR!p&+?(UhZzEGvQ{@dI5S1bkJ=IXwzr5ivzByA#{!6DtE@3<>X=v161-A4 zsZSF6wt>(XIOgxte6IOC_f4Lyc&Mp<1Wmmk@2+eXOYScvDnH}k({|#~4_%aykuM*T z{GXi9_4f>?IKHXU-D0yH7q-bWJ`-p#pu$O@&LRVx>kCQ%NeMhI&bvKa3>~L}&MYGWY?+bzXt%Xt z$c0VL;EP*6eNC_kX2xPb>pb@V^eVN=}^~85*yD02mOj|a%-SzG;pe*X>SP7M52SLGZs9-u2a z!II7c;$NmwA5kf!0Ee^i#?KT@9*Gk_9VG3px-!me$B7+ui|B;q4-qg<^L*uEojpQ> z`3aN|-?lfFzdn`^^;gZ#Tfn|8tF~QCJ}%9n;ss=hgge@^LNR!hQb9pBGv!UF1=EuEmKmIRY(_Kr6 zxB->w448ZW9YlqoCwOAm_2Xbv=xN)fm37SzlClTvSJuy_1CCFz?9lmG^eNF)b8-I^Xtx#vx7}@xhF5t6g&BH>oDFq$V zS-tXb&eNdQz8-i&xgK>q?BBw^|1twp>=Km`3~4m&l5BCsV5UiS$)!bxFg9s)w~V3% zSy7D8g!ww*!BBWc=EDvSnW8=rs&#E|^_R}knL9hcnSkGl@C_Ug4GcvNT42ld372JhbM#N96z>Ck+&^5th(ljn*O4mI}l&vx%3Ei0w{SDa!p7V3!pQww! zK1id(EHpitY2xFhbr|hg5XRq$Ti8)>NJ72@U2~%cHZS&K&?1d6i;4?!n5&O$B&>j7 z4~%AP_}?Q1|1^0vAVZ}1ct(I@X%Oa_8WOCO7ddFn(&__FLxy`Io0}W@t)>X<^2X1^ zJtO+i;mH$*;F;6M-o6p7diPJSn@wxEx(pX;GYX|(Y85Mi+@%7=O@tRe)iSTP_##2d zHH_=ub|@*wjs>W57J1!R}f?m*X6;;K;E6Yvv5|J%fp+&CsselIzN(Kq1S^*mFQLjyrAg$ zHoenuC*iJ*Y_z+MGZO`FnGen!<{T>r6tNSXO)}-~aaSLtdRdZeGzjE^lF=uOu9j!x zR7PGzKeg5Z7JAT33)-r>6ye&2|CSlg>D3^<>GQ6;6*Sl#9^WR?SUm2W?ZvDnpw?I* z8x7f4L-@5;FGjR+;hY9TXxq|ksfHwA=R;O0@>EKWI$zOGjQlv3}?uMG;epqcYDp?^+ypWjxq4&q!>E=J;GS_WgkZ ze~tW;@nt3>@HNA!I*x%r5{6Hg?CMk@@||@Xx#vPHE+&H=?Uj#rU3d98_wG4TOT2di zc&|rUS#M(l-BM7PU6%|ux|XO`BAVhqMNe8Dm3x|-%meB5Z*@^@jH?nB+2=|h-?eNm z#w|t2RqtRu;w9gfoTVL9!a=cLriP@W8OxilcmCJf z+=PH~tWc@Kee4H=;dLy!7N~Xj{-dY{xPc7Y!1GS0dHiB!v_bdgw(gy#V1fr8ZAC{O z%@@ynDfFnD`YS~r+V@8ZetGqQlbPBv6lEm3mL{9Hbryl zG<}A|=TLfWF^vhMkz{%E`gapXEz?MK+?l##(ssXj6EfjF5ZgLIJR5J5?7}7y!-iL6 zwnZ(k3Lf-%3|jXh03qA9Iwa7IZ{tFU9CrD)J_6kRWNh^Ob7iRUU>=o||1xGMT{6Qn z;JaIvo!uMlRPb?PX`!Ds%m7FRrc6C)H`(u>$3;VIi27(YUhjRRtitJYnT#>d_H!Ux zY2ri?V%48m@_%hmd23p_NUNAh+Pw&nq;A>7o&@-VX@!dDaYKbjqaNZ0ANve^t#A8daQ6nUD_jPYiQ z9j$xh)+%GqNTP{2<4$w^WF}J)seCp)D#F|D)gFGK>-+u1eIP4fZ8+W3(|BGj-PJys zC({v66V}9Hl2nwD^5|rZ>z%x}=)9|MQXlm?ZTC7xL9x=Me^<=9$?IEx&da0NP1)+L zeEYc_k}@o`IsArM-uGi}dt}N@DE@GP<9&f0rMbmg%LhR*l@KY~<4fis&tI%ECk8*^59qHO%YZ*q9PlfTpKA(Hs!f}yQ^Mu z#Rt#&$5yS&&o2v`e9AtH0XH$^>|yNp&B4z7XUt3aN5l*ksp#l2TDES0qPSSVS2=f! z{OD%s(h<%CqS4qfHqiR-zsEUI+ZL8Lr(+O@4p>^mMG|sP&8{T0UBZw#GZs-|IvlSR z_zFR;>J5Wq)KH5qa};~TdheT9MV6)^rZCX%#{S}lS~)KWE?+*3T2^_BVYKNMHjOc9 zK8G_oGi9PYyi6(7}GT{X;o0{Eszw0xu*S5_`H8N8pM1KDhC+@85VR@ z3eyQGi&Wxv-s&M;F6=k-JjXiN@I8tAVoq%o+~#{fMno6o7p2O4$hjaU*~5W#x3GUz zLrii#iQdD2)d~$7YnL<}x&Oq9fqeb)SD-A{w<>4+p7E%!i1mZ9qz-?=49|+?-px0( zpPS)Ktad+gUZ+kCo6Yu5`G_|3s9`1m|G?!1Ke?P~aU^|Edtp%@?kP>Om$624ri)+9hpvTEh#$u_kzTgi?1&TCi^S?~USJ0^%;oknrqw6X-T%yHGk%T!v zQr@jWDP(0qMh0-<^5JvlxcGNP*zVkm|ABx;!iF{bdKIvCXd{CqkS=fdzvG0ZEJ8Wm z@`*Qy0?gBQ1>$urLq$MQy+oJX1zFawQ0rAXjmUAHeN-Qi&1PL|O$!Oo+z3q>Gt6j^ z4^^o|FF6eW%AoQ3kPv;lp)RYL3Q;Z zIKVgP+*^C+1F8%z%SLZL0fs{+a+VZ2qLB(%A-hwrrY_4RW`J}Dy3ZZEghw!9&oXg! zDN(Mckyfc}9`sY$vFQB;bcg5e@0ndYWtC$(`1cTz7B9;~P)p&SM*m zcgT1oh}3qyvd9TXbkm>kQktcZUfYCmfhS4l*gv|MjMl-qj#0f@&zw!vpNAn3xQB){ z1msF0mG~h+ueyFUYa#n1UzXR;PA~3~y&UtGFDi7-l#>s5yBzBoqdKBI`A7ww^2o!# zRwuGzcj;%7yc9EV&=}IsJ%85Y)qAah_Qh!@SGaHzzPH&3pE8EU`4L)Fga7%D+PyrA~Bt%Qd%$J;RE<$-|0SXnj8EtIPUPr`D6Br>SPh z1-MKW3Iqj(P}5#AEdQVPo~gBwz;5|_>{ZPo#AnSV7W2H79BA&pW8xPmtYTi*pfLP( z65Wl%7lbkQ(vCLUqNwcd$s`fte7457_Y=%k+;F8=gS%y*wwze#-*R45qu@qsW=GP!F^<=Y+|`*b8cvXvI6Afsq=fOQI14orLwEDkv;YL*!MChKqo)) z<37G%_gX}|^K~8QAXq&6DK!MKKrpBLQ5u~Os-D0YMYq5#Ud!-omwhC2XpW3}zAIk0 z3XiR$y=guE(G`0pFv4P{sc(T7f9K+_{BIG%uAB6N-?4r=<<{xH%kV>^a)Gc@Y9vaFYL1^^xS- zeNWVz36nwc_H=>q$djyv>9BYd?0xX3$50rr^VSFHQhnsG&c3FYj#RM;8941y~-{+bXGKq zO6@t=8<=+~vhQ~nwOH?RQzH_8&}GB(Sz%SuYjyNF6|}${ZSQO)Mh92Etm`zNSzoB0 zA!C%}wygh+_uL`-d~@NAJY&h>F>n0Pz%2aF>1R%nmBHW@$BuRp9IwC|w{p!*B+%z{ zB-bVgmyjc_4}|t($eOg$Y^4<6%IPhE9IrBv7MRbL8JpU9>XRJW#Drm$a0AUVg|UV| zReZI>dK%56M1S4dTP}~hQ;yp+pL3-imo{0sdjV#-ey}uNV_$puhe@jFREY|B(%Xqf zJts7**rO_fUqp2l8Xo5oBSb-~a~flk+Ptn7)c4$xe7I*VU<|B%QrG?aQi(`M{LNrOCs zQQ^I|Aoy~)+b9(Ud%CdcJMHrolT+Gj&&Su7DK>c5p}tFnqSEp17TMKqa%;`csYwmX zh(re%(n$%Y-%>u?XoGhxiD9^=hf6>hw#}1}A@%DIMeHZ6D3NxF@@zawRh2_zi2UA& z8ok{}I`n7GEjaEPw{qNGp{Ad3p3vsN(~^(-mO1`e#^3GNmm7XkM}!^fl_^$(Y-u&< znb&`15x#zHVVStRaWNi$)>t#wR?joS>2B!GWuTh&D8lz{hvtZbP;=VGEPMjp=^G1 z#Q2ekw>`IJ%i1e&oJzJSt<5;a)Cp+C`dT+!j%swwql9?l0%a_u@ihFMYmMvr%b z)+u(hcWY14mPGfqC^PLh9242phJMsyJO+ZZm9BwFA>I*&7f%{4upts-ALYg@40%Cb zcXQNmsg`wj(g=kOqR|aE2O{RV!Op8d`3q}%_zFyf@`m$joFffmJzn8)g7*9Pt8nA;7TwZd@;P{Q5Mh>ckp+50>L$yklwA zQQHe}Sh3Am{CgJ@+7drW@pfAbQ3257OP_eB-+CL#xHD^0 z82Wl`r=ffLHNXe*pujmRl)8Z-W`yJq5*AKUF$-t_wNHZ}6Tw&ZV75$@U%)Yw?h);7cgu2u$K;(Lb2<^V=JU2aXFM+Y2N-Nmc22V3ih5Yrz6I68lq7(G%3RwR0W=*&r74J@uQDeg!Pz?Wc04oJDrSv;r zmx26^$zYy5BdG=J5h?Gh2k>PGmSxKlt16*gErStFbrP;Ci-$Ye2RM(z$E(_u{%V>WEkI44wbg9im$Bso#ob!43sg4?_U!-;}x)FDl(G^c6)obhzjF z%v2~cw{PICWeUyw%A*JV|AY@5nNnIC8Y`s`ug(t%sS^Fpd<;2TSM`bJV`=qXtQz7J zZoy0X?b#|5M%Fooc>`fVy}@lfIIhtEht>-Ki63ZHgPTT7QBEICkFQeTfD6m4VzARF zE9_$JjZrCSG~xrx2e4@+R;(=S7th>U38U`M_+hNrZ40keKZ(~}`s6=SOh?jsEeRhK zIrEIa{rKGa<0_(!(L}M$tK86khnRe{zO?n-gm`ucOr=xHK2$2Ohdwj%u0cc&A=o%w zKisMlb92BSy}e*blWv12IQC~6ZR7^gUG>-iIz(E1LY@gh6M>vke;MPwS3JlUpCkNO zC0a1^U3ewcewuW^0yU6v=EqW4=cY@r-{86PJ-D*~in{*5PR}8lK0PxRFhV z+?v4_uyAc>FYy6kTm`i530`L7*}S_JOt%%GATsZgQITo1BFPIhm+ zc65e%9d|`y6|ducvq7&~TfgxMb$7c+JEsU%ZefQ8b(knC#xWB4{hGO69v4aMBY?eW zqeO}3h^vm_N7bdh+4I*4SdvH*k&>_jsrWl8t_T;&ttB=ce9uHG4s ztGUT5J>l^6s86=cG0bY&r|hl(*xFDo@?b~TM6nF+l4QsLeK z6|8I(BH&~`JlL;%A!ZUHMNCp*$Yj1^;Mb-{*W%Tk2M{n?f0(Okb+GRjeEL3d=hn(| zG=G7CChQ8PRM<))b}6cV_`mDdRaBGGr~D`r+9>Bv4etU|h`h3?rJSIWeh0)ra99nI zr8`4>{qXLwP)2y<$Eu(SH)HOg?L(@Q_P0GaK)FN`GwNKBTJfBqViT?5#4&xlrb3&t z)d8{XXzd|)uCu|DJ1%WxFj5lK6kdb2p6QtrhwUc0vSh|))KDZ4u{cc_^%wfsuXC3e z;ZWxh@tn<9*w8qYrrx{dljs131{EUV9ghAKuhW^EJjWKGM|)Gxm3cssDguZP5bJpt zF0hd)lF_z1)&5BD1e~3`$W@8m(17-H39mo_RH0W<=pyZfv|<{a{!`pQRak9ZQ*4fk zAUZ^yPP3uW3C;pW1dB|rIovN=&Yg8Xa}@MUvCLXDwJ~Ptsl||$cWXGiyWjI%7P3JarpWC>T8JZ? z$VL`zRf8bw1S9p=V-VXOo=oorVf$(-8&kg72Pd(0Z>rEH8s6lnPtk9(-}z_rLwVq` zh$X7IP5!xb>rM#CcXy4;ANpmGbHwS*OY~Mn)jXu2nPA`FD_^d{53G;cH}ar*v}4`3 zO1{Qq$EUjpa(jq)&(^PtpX-aLGCxB!`a66HpA!TXxMo>TPZVAYg?8V(sX6Zw%(je-Ono)bW?gRBw=&+#92>1hS(Xlk<$AxVM|T zYj)(yJUB28xN5wgz?sO-F%2N!4@LL>?FT$qIlH6pneY%&AS3a@j_p4J6Gn%2-L8$` zV{z+u_ZO~#X~mi7A6KYE(!40EBr}1G!19Dm^ReN7W1ax?r{8Pjc|Rvw=u=%m%P!vD z>%VbhCv5>XJJE)QF^nzKp0%mo+jd6&Z~WQGF~EhW2+s1jJW%Y^bZK*y*XClktNES*D0a+k}U$cYPqIPnUsPQn_ynBIKjDrP+DDOWCh3hTJWP^HIFZ zOCTF<<22U0tEV{_CPRPuL^ef(B2@RM;1^o+Im=rlNO^PE0vTav4F^F*I%>jt$PtZ? zcleC07fx4OJL7c(H~RIZbWan9%avOBiiV{Jj$wX>Ghgru(qY%z_@;}3H(Q3P#~FK& zcy%4KB92vKX`_AcfupA8A&Lw^oOvW?)sMdCkVLlbb}2)WXd>c?E2ZE1p}V986thX3 zYdgWoN=L0ZBcn8zqB_jUx{owFHNkF4MmURblHD=~F)C)1x`t;4yXYW9jM=R_#!K65 z@R!$4KM3J4kI4rQDq#Zu40F71s0gN)BQMM=t{}V?o-VMU791X27s4eEBJ@UzFW%`= z#M7_&@P(9-p5PGEopgKe<_$a$ zR(ozQN_eotE!}A$$5z9n8kE{D?eNMKVF>Mt--0)W=l8VtQzM31VFc}+UlZ9^#8N?i`bI}yUz%`v>+hWeHYGp960&pTzgszdQxhW**U zM;apz+0b?{+8fJz35-EgEwgCApjr1zC+*ACdj^z)cW5Wh*Zc{oCyLMJ4r*65F)p$- z#!#MU42}fRj-$6LIeUITde9P~@>7K04KY<8L*I;~>IuAkGFUr=zBgKYhNS7pZ!d*dGc1S6B!_MB$y39m)$4v!M5@25!sF>MQ4QdeAqfA@Xbw-0Y@+uY zx!LUze-wT5!lLv+U;6&b8Gk&tt`0QyAt(bGQoSy*Q(97o@sDgb@Y9&>FjIY>`o|;| zg=PCxMJ+;P5>pg7O`>?aVv&?#-pELfCrn6v+virI?As`(R(k)$rv>+`YAktmZokK{Af(VF8Na`RV z-Q5yOHv>Z>Lo>k8`5vDC^?m?gxZ&Ps@3nqwpSQujlxGV2vSfp}EP4}OnN_S`L+7x& zN2UHwF|fgwxkrPUhfqqW0^7IQ`1o=|=?Z$c?pS6^UmXZ5SfZatYm3-(5D%?0+5K6` z@%sW%5E1D4@pi?0U{LPpIaN2p!#vQ`C#`OX$iOy{HY3!bJ2hZ(ehG%? zc`sg3`KI~bml2_k^*c|rp$(AyP`)2Pt68!T?b`wyT5Ok}A|f)iTS|;Ys8UiwL(f^2 ze>%7YLl0ae{PZPHxa3F_O@S-;1bm73?x(HRQJ}wqIeKCBwuSd6^#Lux6+(=^EAC0g zKVUh*o94Mk-~5dhNOMk+kgCuXH&*dO538>Vq_z&(Yye}{F~!B~N9-rWO}OCipld__ z`TgQ0pEt!3Qtu2A zGBBX#EpG*DSnDr7R>qgpyLJ4d;v>`@-AN$BZC z?Z_wl{|b2VHnaf-)$Z1Qu8(~(#@kgwb^_&viD1=w5FkcFI5t|AG1_p>YM0Z-onhbb zuCy_C*svak9UEZ5rtO%g{uVy4i(ndiUt_@loQ(#4V>Z>MjTw!V1*#o!tQ!|jqM{-4 z6SvZ7|ESF3_BLzX>jm}3>lr7{=4qCIRFPtZrioaS7@iO8rT3HE-b{~882I|E3gywE zLL%sM+q1J07|DcC?8S+;oe&De`_QNB(riiMaC$CCG;03QNP&Nc-D6 z>Pz=`$6&nn(s0d`)}k!8ryoA_iAiz0JMK^s756?o-6HGMn+nnE6;gY_5cbqrum}5t z6LX^)2lSlz!M4_RQ&acGSCOSRJebG;s;R$NXsz3(b962AE=ds$5F*6lnx(*C=Vd8= zkT&IlGyfT@GI+yK~ZwvXWRN05!b%invNuH z#0H;asS*|8alLHrY`{~@9iyNR^^_8wSj#;;ffij90c0RFRSgW8D%z|GFxXFUcYBg)A_K zqOZqsW*Bq4`w8_E+Qe_`#@Dv(g%YVTeeM8d9JU^<`IE@ zzYIB+-#FhFM7vSKw9a{ZJSsg<<&_xx<3Hzf%NfhBGUE6L#*UQrM}sHInOl zQg#Fj?+|p!Knfmudi`8Pe+7loHOLM+RaP{wY1=HtZ!3 zqjdKh1{ZN}TBY%~%Q1@ExZ0cG!$M-ieI4*U3?w=r2>k3u7+>gl-0+EfIZm}i^kaa{ zaf#4|`pScw@m&LXs05g;?uCxF@8*#0a7KBXj5O~3`%NOn4lA@YebdtpG4ES~Xb~?j z_g=~P&Hi)I20jN+8mP=NsK@}gxA;1YPu~*%`s7Z|O;$oB<&a%DV;4Wgw;hI~uKWa2 zGmgE7FsmJgl7FHkzf<1*5#%{ay$3dG%E}y88K{P|gv;yfuAir1w6`V4S}QhaMqg%}c*x!}HjC zrMXgbmzpy-8z0UIeEa9wRJZC@HXiXq`>5aLhxi4b*SG1s%w4iOq_PT(DomKSb0HI) zQwS1gwjD4?k5d#UP=-O!n^$9Z8X3sYq6x`PdJcz^>5JOi7}B_W!DK5LEg`8r`UEKI ziqXndQT&Wah6agBGOmitiO=kva?QURa)&RbK&u(3lg>JJ6_zYY_EK8zPGh2byP_9+ z9*c{-Matx*^VXKH6|IgBh2AVF+#DJtaJs~eOd3zZSKa|C#bBw9hUB!b_AsuI52P$X zi3v-ueQ4Ql0;>(hgb`qEe_7kx%Tq+TPC^3?Ld7m`S5Ju|2Z=J6ETa8_009S#-7X3; ze}St9c4$C~$=oMX#2fv#F1bC|Dr{10G=lq2#+}ePwC$F^kqdv{3<9wYCVk45R#)X- zb0+d9Tb&1BVX$eO^LZ|^!R|vEaQEn+aq@B78CJ;0E^tHMqiIdAmbvO5^lQ(!nxyys ze9@dmO<{lg&YTiJ2l}aBi=}>H9L#CGdMM^OeGX{D-gY2gTK=RhQFW_(bN}2cjU0iC zCvm{85YE$`$0O@U^c-d8;}?~>Rg2GNTBCH6Vy`rj|L(psZ$k~edzQ{(!IfhM$ z_>K^doz3Psk%p?8ri6k74%7Y2-*f`tZl566P6*AI_?#6uRj|TNZ?Y?Q z{K;a5Kx5iVDqqJoew8`h9aFEe5|vH7oOYl2szW=*NXR9K3@Gv&k|*ag6CV)xPX9EX zu>O|~#(A0SSqj=@uy_|O^>TgbT9TzrJQ4~xS{P1G~} zUXg=I;tP2(CaRpMPoemE8R{KVbQtrq4BFv}LM(?HXkr@oQOyX(%e1+fla`r3*UAlt zYvKa-?GT!!1m#%7&cBnkAeUFtizZKRY8v^EWmcg@(pIC=I}=l>2IuP!9UlzlWc>5| zfM~of=V_*2Hfic#r5ya?ljK|-`IHEFFe$y8h6#~!pbnCEABrn_dzRiyH}(34GHY%6 zBx}T&j14l^3@^a zPuG<5$YzKb?>mF6VW-jNL*L`n38w68D7FdN1C9S@0dDJt2UpVguv^8A=TGy2?F?}K z=*N35UU+|=lHvrihLHKZvsOO};=zXoLfMkj83`We>!+C8Xz+$*QZ?Rh9!E>hUwUJ6 zA5qaT=C$QQCiUyhx2s>@4L6FYmrlbZWDPQC7*j|^k_OlE>D;O^mirOWwB9bU~+aqLnyf0CMapH1T-2UvIOBx^8bVb{tAZ&8ve3u zEybD#{Ju666~8wgQeHn)IZ_vDqnH;{t$D6nLPUoIs~ zE@ZFZlbv)wapE!KvMSSXXH*0fA0;f2`*3#YD``}|@gL-gxwlnF{W&U{jm0pFCdtE` zrjY0JZ7*o9Xd0>a|Kn7v&Zg)2Yt5g2hT_awVmJrme1gwM28-pM=b^4#Y@|f=$>sKO-0-O z?%SB4!KiFIG>bz(AdF#+zzP_^hMaOFn?0{3#NCM~R8FdUi`n8DxTYyoAZw2Y;v~oh z)0seAthM~N-Nhb?O%YXKq?0-D6HjXD7{cUar<}hiCzPWrs4Kg*IL?_?w|eA8Mc+ZT zK)lP#(}%^#A^8C-ditFH5wFX3uQ=4=!>Ab-3GnOR=X+x70Xqcp4gV$reO=||G)zMu z6s$0)gZWf`CgqW1ku$k$7B!tPk}K3aBc(N19Xv|xGkoPqm&qn&TZPf9(hol)1EJ@i zNuz>z%!k{Y+JnZTAg&};wc?yaw~ z4#+6`XO>4joM8?~WWC^yB5u9@j>vfNkecCY$fvBbiqGUa~4Rn?g{e_9&>eEw$e zyd_j)wK*|7m7^bO-09FU*D8bWr!1JW_V>FMJS{5NlX9wcjnv`Ids*Q>0e%HL0hjR` z!Tol=>&hWj2ZEp#YiVz-Yfi{mR5VpRd$O>`4;!tylvq7&pZja%Z%}WW*nE{|m0A?B z{oCZ~X8tOD)@F;I&^qR~#JU%xM)@_pF^#ZhdPaA@+{D1vhv!tD7OUR(Py)_n93~|m zYUQD|wM(<^IAE;qdFm40`BoK+w{YAuVA1Q~ zGOZ9-0J0Ryo0$oZu zT-JaikDdJVPrSj>aP>E5S@m#Pm~1c|I95LMKGd%Fjt!q-#Us{rP*PVWcO%L&0fw^; zZA7^tr`4i4jeVCjuCKI*{&S?U1k~f-e?~NxNnX3V2+(V~90|LwLKk;ehK(n>h|*Jg z>o7~4Un?ecSHG>{BfLYb-Q5RB;A}hiE3%Smx33g z0-oa=>D)1rS3{PQ(VaCW1fcq4OSGV^=Q1~+)`bjhgQE5iJ2RzTr_=lsmPzsco?v-z zDEgH$W`sJ77ypi{3N7cCxz7?;&Fa(JN~FTG=o^A-o6)Pvdce%j-3^r^O8{;4NiGFP zPyVG?=nQD2IPzDeXxUp6AdP%G+b%wQ$&fS?emhkd@uN?S^EtGpo*#}p-4vu;+2_{@ zUojf1@>S67+Zch?*E9ZYu!T1qIltEl=556HSdBYO7Cfd)%G<;?aRO0$f+1PLaM`gr z`$0SIefk^cUm;j>B&*ay2Ko&{=$5Z_t<}GuH`l_u-=Fqb?L~LCgtrgGzgilmwe02E zwcqrFn?m|sshdDTD)ZsOS-vsL!= z+4qSkqFLjfJ8E`nu|Jt-pH?2SwfCib_%Ef|W@A0)Qq$PEtMWm`uM-|g8>A!^qR%Iq z=APU{Z_`{jXpB8jAf4cGAE$BjTQ_!fms(OIx_Q9ez zd$UW4=@P@Ou4!3BepYi_*P!1q(yPL*srB+@{zq{9vDV^XNv0&(D-AMggFOrplHJ$~ zx9&GK6(gPaYZ6-O@<=losD~D(FgI@+KL2v?WGGUH&?~nZsK`CT36=4Kzb{MhK~Y#Z zod?bEcg|!KoWL+Nz08fb@cM&PDqGqEMelN()xXo^>yTu8lceAD=%J(0E(XOD9y^t>x3pg1if>M84X?|l`Lc(zu**zlZ37pp3^neF8crOwBCWI$7F-~3WV z0{`4($I>eywC^wLXT>mg#-cJOV3lnaEYHr6Qm&;13%L3DHrTi!daqgH-u8G@W4zCu z53<$tx1>!VY*CV6y-CRY-z=W#SBU0UPfe1|-c|k=%3{sfF(F<*rXvPlE=eg=ePi&j z8Y0@Vzo&CH!zSB`g}mrYctrPOWqzd->=rteI^aEGSW8t|OYBXeTDZS^HZ{tlN~S`m z{#D^AP=q*r>;mR`8=o)}JIl*ViM9aTt$+MUk53VUQdt4j;46Ih9DHvDRQ8utf#s`g zX2VczK&HjXXA`nuptZ@?-Pt|kR~4+KpUVZfT4aU{sgSBv2uF!>$HL8MY9JSjJLVB* zgIe3yg<>WL{D~Vt1fktr_N;WwoQ(2cYz46^~)x$*sw_#;q;C8Zjk zDTwW@w7p6qrHszVBhleY*e)nLySt*}`yp}&z|O6?y8Z52Xw%id;`At4Z0{!gjz&J+ zr8-EN1;^dN0&~J@tvTtq1IUkL`+r}VHgo(QoD&+iZicakLjbn=a#=?A^;f3*@~jAT z!%Ku!sm5^krGJE*a#^M1 zKyvZDU5P*r`X&zhfVWZHVgLTu$DQ44WOp%c#;rF&Gd>jRQg@=1#O+0MEHPcu?*Y;% zdJ}@^B(f9VkkFecH>w9)_m?~?0~M{D33|qqtYmeW%aW8pD)gKxM>Yif?+<)Xo1p1@jM7L!Nu2Cff(A~*5kZJ zy5*_QgLoVu)N4tn*nA{$2E~zA$TkT+98mUeV1iwFhu0l;+~RG#F^Hs9OY()BwI_Y^;)y{&=#QpSaRe7-E{INJO;rI~ia^vJ_hEv;&V_D9F6lcLok`3SWufTz&NL41b&SxA&3Xv{Qcix0SCJAnQ98?cErhAS53+0V1>Pz;Q~(3?W>U1VFZrw0*&|p93=5JJcS4(hHx>${GWAZWezC4 zu$^4~vlc4X*$NAdyHub;>Y%mRJcMB`!C5uksJP12do1@dBVp`TS|uKteELgupMoNp z0^`KBI$Lw3SafVf2&B|HE}o;GWX{0MLKIOx&Wpqs_Aa~G?nMvnO_7Z5M=U3~CYpzC zLquqwy;CqZKf0?G3aE|0$f{p8oc$}{UejV{3KrJH6(_7OUy0}l!!rQ4OK$-(mzUWM z^~Rm&%P+ZCbvY4HOwsk0D!=le#xyPN-O-)LLgMvp;@qB2;#w_n8;i=)Lfk^RgOXuZ zAcqqIL0(vcVCTJ;kJ1bz2hrP}IW#H8Ac%E!wWffs^Y2CyXT0ynC!QFDbk%l9q-<$1nRU)*RP?s{RjJYrNk7Hd<<^oHvCq~~ z;s{9nsfbd81WdE|l6j=Ow-@T-O5666%48??`_>z^CpFHJh8g|zx3uPHbLCS%pYmI< zc-Y!z^Q-`P-RK^3dpPi|Bvu2Yyn+KDy%M6THJMEd-2b_<^$lZd(5zX#tk-q{V#(SGZtFid z*7&uc^WvGyo=pSe;+pIgnmd1aC-)(M>L%BP$Ax@F+R|b<20pRZJds{1M=nOrs$`W{fY&M*V2KC%fnhZ+)cl> z4Kdr#0`M=I_+pHoKUx@UVeZ5jXJRO)5J#$_&FuTVQH^GS3BSLhebUH(!HA0t3+AV9 zTlckcgd0e&_hgV$7tR&U(*PcBqBvj0&dA1zKaeU+i0ZpS3C;tX(ML%HsM0_!KWJ>? zncrSucbi#!_E(Rg?mNBT7mk{bcFBZn>(Fp;Z~CpS^SZ5K)JPI=fbN{ z*-9PqGo8UQgC?SbK;#3S*G31U^=2DW3jyNpy+L!1y@6$O^9wXo2s^KMzYl&Xz4YB= zmlX_=m{M^=UK%vhB}u$KqDJ8f*kXOt&td7b_o-9VVcV7acMZ`H1^pI4q;E_~a>y=% zUmmm~I;9gYgn*s@;O-#jp*^2d$RQiY)Rx+6p1Q2SM=cFqwz)O5-*FDOQ1qSVGc&>~ zKg@&#wdkTEWbH1kSL%CY{iahF7{|^~FoPJTX#SBx2Zj)>r_+JDmr8ZhL0fIT0X#ZB z=g0Ub*E1`U9J?8(_4qf%%j=Vj4;KBuPs2?XjZPpO4$K;5>U5W57lzkY%0cRs)=KAI zUAeh!-FUb+U(qW{Pa4ZrDN0vFv33KI__2sg-WQVP0uf2jGP``wQAv3ud&OYps;Z=)lgBBJ9^1Xq%GmvS*<*fSW%WPo?nHG6IZGI zr@5Yk4Rge^Hg9kk8v4l4dlqlyFZBjw<-7QL8i57AkCcpUe%zZuKYb;>`EDAxFEVW3XhI1&T+j{Mq`Po?GWUM^23rDCv;)|5afTd`meDN~_AR98W*xuTuR}w)4 zL(bGNlS`yx$jH5JbETFED5z+ZeL>7)5H&JV{R`}uvdV!q5&v~z2d)+^ESW7~^d;?W zqyy$b16ZLh53fcodqyAO1_jspkLwgCd4x#ZyLleou`ZbK58xg|Grk8aTHpeNdrEjfnd^XWbj}GHLU~88Gfsax zd~M+oeGa3&43$ck``?Vrk766e@Dxvxc7*r}J9GqonqTu=bWnu~JgiQaJC26iX8D1r z?UiSap}M^Nw;r;hGt%gDaOXoP@)!-&Wwt&nU2Zv3A7{_36jku_{K zTz@B}WBPr?2$lIJ!=B--DMD-uG6Y{lzW5H!c>JCg>94csTQay!Yu%9rfQ+2bZ|S!~ za#Z*VMqVOg#B9c#o=!FD4TG{y3-$>-pYGSPzWm*r`=n!W-ShrfBLg7tyC0>!cc$xNPotVf zMIRk&S;x1zfhI50E)}yCMZeE#z7j@HKOrZcGr4%0wOIU`T<|s zwv4nUw-U-@o~h#JrP05#oju}~Si1FlqpVP)LmG`>`k^6|wZMN}`& zcMKspl7m-VX(u2n1TD8WR(zcJw-rfZ%dswX<&(Cer!03^PA#wW-ecK&HTDC_A zT2jS6YB1D|eZTV!y1swuS@D^TORSamPz;6vNMPiX3L(nRMTfaR?WEa!>eq_EiXv>F5J%aKI z>_P4GTBeb{AW<|Xy_0y283kZ5cvsGmi)ArD%|v~XAZ7+bXPV-FnuR3E3>j94w*&Vo z7T%k5bkDfA!B)GNC%`cnry+lRw%gWt7E64_QB$NsUi^I0OoE&hyjIH=w^@0dlxQ(jl)L$z->$1m zRY~oSQtCRQ8Y-&3iQf@;5!!EFe74IkF<3w&Pf>#z=rSq*Yl|dBJ#~B=i3$F}rThpG z-Q>qg;3u#VrgYB~8aJa4BA+lLsYZe-X6ff*3{#ZF z0@5=78P_N12qutabi3eQhQB_MBXi~0M4NWaFJVwh4f(@>{AxG1wZo~$D`HTUSwnV` z^y8*zsNO!9jd(p}&87@+6~t&KvmFbIcY^;r`m*+H)%AL*KXd-zQaO!1{dbC?DJ#WdIAJ#!Fz7HyP*^FE6?$?z6l_>F06M=;M9OjE-?68SJkd zm(71AkcRoZ%ho(ufFY;cY=9=4&&C~YvYsvch&gS0z<=J429zut29vLS8AF#Lo|?_8 z@7>C>?&6psFZ#`E;8r^1U1^_z3rysMt{aWm`8ehY25QVO)YeP0(PnMFWN|BDXjx>j zmgrE+ah7L?-MB9~aJ!;pZNlgo=e1(+p_j&fJ}k8&b7&+ho7;7C8*Jc^qP z;9HKjmS#TY1g}2%wZvqg3{e^d<+t2E26P`YFyrB8Gz5cE;5%u37g>V*f}bh5em9$) zHOu;1pQ+olvSZnz!+oFgCS!&E39Fl2)bvbRj6aUSIFlv9M9WAK*6R!` z1Lm(1xCoH$qctc@pnZnE5Zw zIzDje(R9K*_`OWypDJ^33nfQ_bAj5w>wX5V>>px^5_F9>?w+fcFAcw`4WtW2AbbXBgcC_U?DPO%r zHpLMnYo5-r2KLUK)FciTww=11EScJn-II&9-IUJW6XOKI+gE*Cq?4bciO_cBu|hPK zCQM7(>+;6YL2w57+~(1af22(0Ys)XXT2Z?P@k6hO*Ncc*RBfRg^L}lKin5OX`I+mF zzPSC1@5Q}y743oDzVzS71k0Io1m6`nMY`9)rEn)o&)l~ywV@{za^NBB{x|rb@9k|l z=9d66%p+AVO<(n{lxTmlga>U1KYwQ)jqvQbFQiVfYEaw~gq$i?vAu`)vhNizKT20E zR+zXcm1Of*4Ohr(dF)HsnA4o!2YgNx@FbPV`nat+>XJW#)CO!X3iDLZ5$}+sq9v= zsm(=C9oJ9&A<3~4l@D#Oy4LTx`vtUsdy0JjQ^p(C?(;8S`Tr3hZ^W?-ZbS>R-QNCV zSD5x~SwRj@w->TcCPhRoQ+qI&lscBp`)n@7p(uDjh}zs|bcHCv0I z&tEcI8>X@Dtrq1^bXbtKw((j_^1}S}gnM zrM#(GU=~u4srKj;#$S7Kdhy_%kjyAZyk_}S)`JFU!{jV(^%9yxIbBV9AWzb@l$a-< zR#QMOyz;SS0~^6E0p>vfF16o;20>`}R00-ouLKfJM1CJN+EG?{ z#NTv$hrWK!Xsvz1Sh!$bSadpjd3!lF))L%QSkzS1czZp8qT7`pko|PRO_AKd-uj&@ zj#9vgVBq&`*+!UTT)QdV=2YZi!DcPHYPG;C3)|ujn&m&4-k zg5JgOeATK{lOgg9Wu}=75!(uDYJPGfpzHf*k@931eE_HBl2!AdRx99Kq|4s)kNa09 z&EuiZuf}d4@7|-D8h&KuR`|@!Ug5?8&&vXL#gNJ=_-vJX>^{7gp0Q!K}m>pd(*j3*7#q&?M$UfejhTm+!EQ>+pX z#a1vWIv_yQ>YB+>#3|rLeAw;D|B-mOb51YZa7})Xt0SP{!{L>qxPYFvxgg={{1d~r zlgo8}f--py78Y(6{fq}saPbGxm)@DN5BxL~qE~Ss3i}~JI{ImB!@xv$Yi!^3n~wv7 zfnLzWj{xu3B+I5G%ja484tu6Lt_}BAT-(UV4ID~~ruwG?mvh|W$m|`mrd!uM-y^hj z%eSj456ROoA99OO**88Lj}cj!$h)2oMISJu5FgeL55>x`ZyBLO>%-4u9`a(2cTZau z8nuS5%z%NU^SHv-O!;Y*e35j%u*JJ~Q$~3};T4(B8A(zFjO-hgf^#@7Oi{ zn6p<-ob!shGm8p2ks0p}YH5lW?aB&`=r;4F7|nG0T~mYJ7hUa%y-ui#c>3I+a$O@I z@2UWqa8_-S9V0|g(-;4fU44pYvRk{<;L)i*nm5{c?vyV@Z&N$nvtk*v^Br;zl1~=A za`V=|=U#?4cE3B`#eEnm1AqKb@$Ox;tS$;aKOz7~raS-}g=4Irunm-A*rVn%Wvfqmj zM1L}!3pp*s<`1i?rtT{d*$FsG>>_d2be(Vb*A%7M)&Y0nA1|%&ZF{LG;gCj=oRqGkQC zvMP7>QVmyqt6ply>tBCvAZWbTa&NXz>f*K^hDw^;))}tK%NSwYB;4Ls5j~T6g%KhK z6Z~g4RJzP4R*{j-6CKS-Yv`%@)rwIH`Y!t{c=~j=uA*A~+0AdUqO&fO7P0PPUJe@B zV#$OAH~5N6k$i|f-l47AdI9zOY0GP;&wBr;nc{t{nq5VYe?S}4nj1P>o_FP&8oIym zDsZ6E&dOYMDSqw(N%LjrI#Dn2ONo&t?tgkEh^$=9=bQ8+( zuXxWwS=0;|qziMa`O6S~2SQJ3t__BV| z=5b9WMhQJk7HqNdGomMVYR<>ro_vGlFu#HR^B13NC&SwO#?6{4(b_*cMT~`4e}i5<*lfUKa+{neekc zzR9A&ZZ9e?_nTT$Qc`W%hoDxHYC9d$s5uNB>lv15bT-#Lxv~jc_}19>u0fa)uIyTF zwea|=5$|_YwVFq1A+)*5e^>b;7xQq5J&uw7vy=&V-m&XX66>zrWnJ|?+r25k-d=BM zW78Fz6)gKR)%bu^Te|BFgx5sBQV$>e%-l!AKP1o$+Z>1o(O*BRruO~hNOyq?h?Xgx zXOp!KNR_q{LuFiW@w@Q?N@{4tv`!TFrtN&aW1Ec~=Ev?&-Tzp}q3xB3>W&zcU~p2c z?Kpl>#twE}=EjjHu$l+|(?yyl1;1b%;F_uzTzKHnJNEz8_aSxf2%V*erXs7c*lOjX z1Sv(<9)w{+%Q=HB5FKJIvr=L~iFxGq?@NjMz#w1TZZSXobt{2zShWs}0V3<;`O}2> zyRViPnn&qLgwT1*)Ft$G@d~x%yYe%+=0rUqI3T3WEBKqD6#44z!s?RCAwy(yORMDQ zsRB}Lg~V2!l0J3&`mFY7@UAC*ir%nZ{bj4p!tZx7-Uq}tRDumEiz@iKT(WZtutlW^znN2m0r0QmWf@k2e zRW$^pq=Zg;y+&MW6N!N=neJ2AxP!yQ0fe&6ZN4o6bW6TNTb?Y?y$LK0iW=s8UOOQX z9B9cAol@C|sq22xbI6(A&k%72aDxx4NJ3L!^ZFrSo3Fw+)*@>e}v*#9cH z+&h19Xe~jTcyJP%cI7Q5XQ&^|M#a`V#s=>@1e!@d3F+t(;>N*1l-Nnp$TEu(nO=0P z!F+tdjJX{oZ~mJnrMmQ#9aK#fNmU-nRKm!d2hc z``<~QVGF!BZcS>jDR-+QBlz>h<#w!6hP2LlbXQf z`Kj@juK8s4LO)(fPGp@xLk76LZU(Fjj(C2+ttbl1Yx$d$X zYH5`GhYCgUm_p9O&@2PHM8us4>4QeyyraxlW5Pd9S| z(IVm~9wLv;L#H6k3&@VX<67V5GT(q5Urj|trS_!^hZje92&8?kgtpx#abEz@h_9Z7 zK0Nj1i3oAgcCNwxyz_Sl@7#dTyT)Tqe_s*zT`$QP>Sdi>oXIt`PE5{E(O%2qV4LZW zZsP48o}8UF4BA_M2f!V+%M#K%R_#qAC5|ij3*pmzw%Fzg{1ls#OUV`oZLo#0 zi?hwDpnu~x!DnCg`pNL;M?RUh8b%mOGL(sd7L6Z!UC}JM|8qdq>8ZP2J_c&v2$Fh5*Yr~DyDc2)0 zoMb)Cvm?vT$Uq%G%zbtJxhJ-9f}x?UQE;y7GKJQ?sN=#lu#Cs^C;oX0*~DY18Z|!+ zzB;SDl4o!F27}8E1)ZWY{hhxRyz@~GHUXqu!>3T4LJQ^Y8GWSy^=f;(Xe|Dh=pXxB z9Pp{^wZKI$*L*q|oANRYA)%82q60xKa4LMWS_xJb=$uWrgf{k0%=bPi$KUS|RFyQD z(HK4sS(8q#^vUa7B3e+fqwj~tSmJ69=4Jcw%p#Cdw-UTbiusGjB_pN+vb!e&&vFXq z=CzFE_LkMJBG8wnopHDu6pC`}00ev9Z39{Z=x{)az>UtkzbKCxw0D|Y!F0(9Dc?(p7PIfpV8LGevER{2nJKLLN4MtBcoR;8 zBWII_S1CzJmEMEi7Yo%MLc7kZiol%cqoyLR+RBJ#$$H#4QJTZRMPQ5aATQ1e-ZrJFA9_?u?qk?7XDg zcV|PyQlt+apC;M+&Uidmpn)+BzpCPmw|zJMU@jr5Q0?h|ZPxF1VTJhDcvn>FFV|;2 z4JRARd;5l*1>RHeMvHk5@@R~peVFU6blDjPJ){)qAr)i%9opiaX#9`~`uTt~j-zJq zT?2cQMf^*9qhdD!C*OwT*Wjw*ma$$vGJBTewEiEWvw{%a*}}h*>#nI{XGw@@xM11N zbp}bS=^v`VMaEUuCx)_vdoLb<#+nH9-HV6xih1Dd)2;p)P zc&lu7J`-n1V>p%3MM;mpy1#Rrkno}O@t&@BmYu_%3jxx^?B598^SnmWl6?mEcZgkR z>HX=J-Y?=0ewjG%%WPwO2}4bC7iWV^SjOd57D`OF*$Vp1;s;o2D({U(Fc=ff2?704 zoMj%kMP*PVC2J`G*bt;^L*e$@6VqM;$;aC5vp6m83xcCBWdq&Hyt3FTm|sl{$} z6Olh9{(OAovzX}U!;c*jqxbzNeop?e4KWNpMVnmUVZ9j(b2W*kS=kCmyVtTeGS=HKWkou%7=!nD<|_w(20hD%xt3TBM1QK-U}eo4 z;Q{-+B;X^{`TSo?=N(Vw`~PuisEiX?AtWMO$=;(rD3WZ)D%oT^w&V~QNmf=Qo1|lN zY{IekIAk1ha5&=NIQ%YsfBxYw?#J=Iuj}=CzFzlz*}&K=(*La1H#w77?z*yWo~$*? z6;3hv!N##e&mYRp9Ct~6S@PR;A9Y~GJMwgwCzg=*v18@Te8 zqYk^!Pf|nS0e4I-I?p6*0+e?yPA)p|*XKX%E9y9X_QaPsyi`Y^A~=ug!=T*yO8Zos znV{P(f`4_XaAm0CrKjinKJ#D8uMs`j73`y6C8!f*3}u~|ISS7Sb0Xy~E|DrlZHR#e z_a*wEn~K1b$H%RnN^7a9iC+eLjC{ZgWQ^X!%WfhWZf+jR#f8BKuNbnn!|)yeTUZPd zHPlAqxZ#anxxnXq8Z_q7_PT`}uge(KX2s}FSr7#EdYw|@4DN9xo)0l`X`AislGT~G}%nAcQZ+AF34t9#Ul`T-PByKAR`$Fb%LgYViDn^ zt|piGM5%>mxu-|Osfh!BxSk=byc%58HQPGAtOwM`G@=R;l!zhtt`UMg?R@Es3e-w9 zeGTEJ@wv`kZvT&(+VU@JI~q|bUKY*Cr-NFQ_xKXQct0Uvo)l5P^)MuasHYD}DRfTF z%r@j9MGc^7aiR|?mRquCXD3+VZ3}f^qI?tQYMTW81Q>6|W6c*$=m_<&R9)nL*m=cA zwImGtEb3I)^-0<0C#jy8l8D+Sc~118Md^Oqw$SexjiB5LClA|;>t?}7EB26Sr?y%1 zP(a>NWcm5BRxYmh-_|b>nQS&?seXYr3Y9t~Tb_S>j*M;0BE+TP{*ee*U#}^_c|9p$ zqyAlFfzf19cw}T`0c4%6ewFj7t>c3svV!EAnFoIx*+cgQJBbe8gKj)|ohOX2LeCz$ z{n;ayJk@eeA>xM|cqSDyN)3l|4JJi7eplfhjWYbMgKDP3jcwhMC=ZRU^pEH#>fmD^ zS-+!nTR&%X>PR;p$Gh$fZMSB^Yaj!A8CfwBu6zYB8;LAE>ra%mw%<3cj@7Bh6(17R zuh7!QFoD&zKHMI^)g{Ss~@l+r4z!;d;U$WJb$)Bf~sidMyi@x4gUF%Uj|Dzew zvA5@`UhC#7^p{}#q5)+w5IE(C$ob>o6IeJ=VZNt;`2u4pHTo$9RJ?KKn72+_6uf*SK$g_itC-v6+gmchyC1D5s$dqjYs8QeGO>Cbab2i!Fa|Q9;=F%?J_3{$ zUw{2~uQ67{)(X4Jb#N+0&60NB(hg|K+g2UYXQma>@1>tuo(h-h3=dH7Z+SIdxGAyi z8giFac_jP1ve!zDn=kcv`9p|G`#a&~`+ww@WiqPu)mG?KWLGE{s~f-)9%iDm;zI9pNaw(zx3DZ; zc0obsO!^8a@jEHQzSyy&+mNW&97jWU#VHnVUQK@F@QrXX0n6!nI&{ILn5vR$ZtG!n z<>e~G+9(b0B!*kyub;iKDe~)unbHfVSuepZx<7O6fqwF%8&0gdCKS@04Bfnq7A4hB ze;M1ccfHoF7)7F7A1enTE*yGZS^4GJ_ybX^y zQ&-K|o?3A2OgDTuoTPnlyi9D%@@{hJ?3k;rEe|SHoJsAnC%F5i5_(CqCl^nB#d#1mpbk z?w3}k@>Gwcn*I(~r?xXWIOI`d_ulmdxkW3ZwdLAfRX|$-a zZML?i1PMmt z+zHcCjAQDh+kGc9d6&T>GJXEBF)V&qB*e7I<#&!S>SWhgsM1u}3(K%Oq}jVt6M<`0kV;^3jf&?@b)r8p@HxE{9|EXr4sh=V)TUmyQ2kblcLshdnSV*XcC3Dl?cC<lAD8Okn+BJH`9t8kBjU_ZWho5GS|7w7kjSw zeosh0$~Aba*ku0}lQGVtIgUlYPpuI^j!>aO5BBq6G^kHb!9h2I7q{=tMtnFRXZ6>O)^ z>31`I5q!53@IqU+ay9lv zb@b2!lN#2fPd}}$1|Q&u%6uOC!M@u>U37UB_oBa7KXFxu(8LACkLn+Lqor2Pux)Gb zd8;?)!G2j?1Ny3M7P?VMFMerxN28uP+Qdo~;8)-~DuiwqX3K3VnOA3i=^x#bSf0~! zp3#6%2w9Al6q zcw`T`hs-e4UPX-+4NbeOeNX>#xcxVKV4->7=gjw%xaZbaP@gH>?l8RKy_rT~VF;rJ z@MQ=Y=R7VKGSl#5xGDpfP>kxQszI~#-|`WD;TUUW;!gL})bvALL4s>Eh&pIvLj7JV z$hSe9)x=Zk_p5`tjcHqgmU-vnPQnrb;I13*a+=rId_|Q8m^^fN{!&iqp7&aRLa`#l zsZ(FarX;v&losaBiM}?IV(4gU&eA6@=G1k8Pj3yt3@C1`9>BZXF_MJy*;jzrswI_G~N!Nu6Lq^m+cEBNArSnod?eZ6ctCHp=y zN{bEmV?bK>!ld=v0_D;lFRqXZZf!COD%~s98g_|Gpr3>1UGAboOvieCUlXks!PM`u zuR3(XYm3Rf%BXiwevgm9s-o~a86IzRXOa+eXlIGOXj506Ifu4}w?tzwM(A0d`@)$f z&#b`a6}~t-EmiuQZPlmBp2&eC zhV}XeB!m(b1Az^k=V={CqNQw{v7&N*;KikW#pJ5`llQ>!uj_L$F-lF2brYZ6k1#_bJQjIH!zg zauNN}uAt~iA7$QTZv#}6c_Os7c7n1i!LEaDBaZzzm~PRDK-U>CX{tR;+^Rud9woMN z@4q{0YG+8nDmB$6!xZ}>8uoNo4}@Nvlo4MzHBrsFKdoSs;ldU!~Aipu|{hTWw=KV z${!d74-kO(OuXsgW!EIgtN#@+dV8RNRaAGs7rDbRiHtYXASUV$|6Grr^<&7Ay5o;a z_Ds=x`!wH}Wo&6K>DOSu>;8x39Uscr22{Y#sads2H&`I3Q^XUUWMG#$Iwh*{^XG8a zMh&6d@4$96xVQ?Tz}N!rp{-V5TYoG&cH(-VkZjSQ*&N2O=e{^ESI+y?;?tcq;UH$t zoS}@2FCxE}t7|NBH|{!wm@j9};=}3sD2^HF29h}$ZBCmQfA0)B8@+G)i0xu?BB_K8 zZEAa3nxj9&+|Wch8}&@wsn%W`2{MHs8MMrVj6HGgLZ#<&Wkhuxj9k*Kyk~`s*L!zV zT@N>Z z*i5Gh^nRp5g{dkmT}63atWWX=+3JraG>(@cjTiP!`}vpJ%0|RqywO59X7PD28O|Oo zBY{nOMx6b2q(%_5BdSQgw~*3ff$}cf<82Mq95d!`GO=T;iFd5(RIAN(&%}!DZ7OZm*D3jx6=|te0#*rSf;uJ!{JkHaw=X?P z*T>AcSU@f?*aG|JaBS{eVda8t$kMBKHVRfeS6fY#!B$FTK=l)CJFzfLAl4-b5w3Vv zD=z*!b00rMK9uZ>2)yaH+&J%@h%I*&z|C+&JnaHc8b3(W)&d zE{V>3j3kxlC-K5MHJ|BkXhh}2!Q#crNwt#!#QtQKtesw49o2x&@V!cnNIhue2x)I> zrZ#F8_T}pCkE_dQy3r>=al0!qt9c%ueTWW?P{rtvXKOtJE!Z#ZoC>3z7Opin*vOry z%TbOo5n6RB&S|h=aX{Q8HX~}7aV5$bFI1b>F4DB^e|Ta-TP!*9^yg;Eo+e&9{mGab zJRnM^{vFMO>5nY?NK-^f9AQPQwjvurN5*K*bpJ}5#R|PFIJaIclY>v zvg{j@+J6Zz>zyRW3Yc|2k|{?Tt*JB_rIT)fJus!#(bi~3O>IdPx?zZ7!vafuq0f~6 zT9=#Rf1?nR6||JS?C5(#2k~{8>aLY5?~`%Ik9-#L)JuVtAKqd#^xYZnZrmIf{j{pw zSoOkSfP3)Ma!YSX1O_GF8~RXWr$%MhGS4UBi*&r1y1(L^8LosGC%-`MLzAIi_bQnF zup17tS0U6h*kCwTM}x`;)Q{9*vpa6xnXoT~;%w2g6AjY;sM|SDYScL@`m|{EsaZ)n zTH3vTa|L*~M0-MjK@hF({%q}h=MmMG-smOSpLJ&GYbpwDPv6-+bt5>USlr%I9tOw- zntd!27cyD#oR!(r8d&$H+UFa%zH^tUvterTlGCeD6Z^IRsm}zFGJc|4!MC_2ry{Gk z%9bF^d6ILSrpIare-C9PDenwEKgY27P5y161cajHT%ejbynRP_xss<~PoiZ0v64bp z;4Rt*k?O+Bl)s4=SC9C64DZQBCP@7X50Jq)4E6%5r@x*IyA$hq3u)+3-}gBOLip;* zJ;o@AwcwH^7V(K>z^Con{JhBVy}z;i3aj47(B8eIx_F}IwcfeRFx4}Xu?)J$FT*HL22P=<4*-hh~`egirbho*+@iW)j+0xDzM64V=gJxz; zlu8Xd*N)zTZQmym%2uoK?1EtpT?hCuT z8UwRG)Qy)rcBeNkuVW3DnSjGi59GfsaT|q}%~Y;s`8Z76<6qi*VC4F?`g^zIMc81C zL1MHH(b@LiXcEsK2{DbT` zuU85$8?q=G&XCqU4HB=@4yAmi6cy*qv37U)Q;t_>Gc9rO*UUO;E-oJG45vXw`yy|o zF=f%9_O9vPOu%M6x|xP8+R+AsO1g^IexoWsav3#JBxoqWYAf1}OMC`F?RgI};M_{% z*ge_UeAA!DXSDxVG>=vAjs*%p1-6}z|oBJa##ah&V}x!WfoJMW6< zg-eed`LAyA_h2WRfRl@|?f(+-ghMX4vqS#O#)y3r{$YjA%z!iiilkv}$+ss`>};4| zUjFsXA7!4gsE#QUb(o`!vi)o*Y@?dP>M0uM{I1fhyUWjFptd3k&wySk5(a_yg9DFW zzJ}D}u12o`f$R`96tn>%?j`9}&WWqr8&gI7tV{Xh%eI5;y77MP@M)}kL`QfjF?8Yd z^9_!2gxNFCht#OOg`uB?Hiy%aMJq9T&Mu7!p9bY(yg?8HbqxeRn^nVyu%Dhgrut=a*Gh+P^x-LF?q#=|c5JHV_{hoenoa|0Po6UH_$Ts32;Y{PJxCDq zHZEi*`2llQNy|aI;QP4#Rv6;yC|O@9p)zhFoBhY{V-E)FxpM_wP6ZLpk$b|gBMpCV z9hV@LJ4sh*R(p#JRJV?{b&%wNiJG3!)FP3L(y=71Y+b9&Js_@KY^77Q{pN;Q1gB%n z^S@3!QS3r|RrPR7WHkkfZP&aUw5-5}^~e2hYM>RUDJ)nL<2>!kBH-h}?BG^V|2-gv z=vS=2wH;&}aH7;ZAN9fv4z$m6W{)a!MX&fXtiT!Tb1Q3aKfSTWKJ1&^Fk1o&SE8LJ-#j(~6B4IWoJyIzIX zhSdHbM@+zL8_3-`Pzh5;&CH2}0{vcg=Cd=~&Qx8aWiaQ!yAGAciIi#RABz-?vH)Od2l@1rOKNFTzz; z=uS&`WKQl@rBzw!XqzvY=t{F1ZDZ)fJrI)rG%{>JVQ3_(Z66|GBRDgXyMUhb9awdXcbL|dDk6!TRZkDh^9M|p70~b zFI z>`}yKzW|ssQuPr5^(A22_NcA}856dHHgT$^CTpcqbde(D5m+w6=TV9iNJpA>F9Ajp z?&q4v^L0-h@c}$kC2XFm$-RP;caB3xYq|1^M3dq zWQ&K*+vSQCJ>j!@Z)E1-FdYetF5nC_KzCM+eqq)`{g7_oh5PDtAIo^jeuRFaBsCIw zZM8n0KyNGC`Cv_)y4CZRz8nE`^sE%pkd~Sh$Hvq>87Te4YFpv~$|`Fo8r#$vINRIv z)JtCNdHM$VDSVP53P>iKsecatV1*>1P|ZyW6Q|W3=d)@{oK<{Qyb!Tk5-^$fQeB=b z_9(v$tnMkT3+-nLrY+*X#s8S_{#0Lb5)k}&mjrXevn?n;!Ot>t89&lgZhw7uuF60N ztjHK`WJb?j;blq9*ZT&b{CCB}Un0)JI-K&b`#>QUxJDrlv=?c#MK3m`gGAN;F483O zI<(uiL2?VVY0_?8?L0|GEAahYPHvbRNWywnU)8@!Nk~R$5=8A0mP4U1mf@>qOXe=< zSe$hQCEMk4dM4hQ_<5?s+WBwlzzn1$BNXC*^J&aK(;PJ^#PWL01HO>m2)3_})DqQ` zAAZ*v0n1fNwc&c$5_4LYDrBOkc;V?2ei}C_j*+ix=d$b4=ImP@CctKt`fnF?V;j)7hJv|h*ri;5I02~u%f0G>o#8^h;_UwCHl`MRz$RAy-r1I-Owu-&g$ z9I1BN5yei!udt*NH0Sv1nR(_0al%Fa&pHh&CcFdI1j;K=Yo3aXwhpRhC@ae@&J436LW?w*q;3zH-4a>ud@fAL*%3ULC%omvIIf?4TY- zhBwWd4aYdt5{|tj{BV0-HZZV2?ff}rGyQ082sJLty9r*WZdgrGt^9ob6E?_*9rSYr zCP8WNTysFPzufXf<6gCS>f4sVJL`p20g)M-+96JKBG^~E&4>* zcO|Hz?PjG-i}_qL%Bo*?s|ZAJjda1ECz0+-emv)^yT&Ny#IU4M$D=hXg#5eNg-91{ z2>#d8jbchGMoIK-lI8{$;-7-l-%V0-lYx^f%GATog$;d}I40UJufK2&H(z(Js{wVo zEyffM+!9T_;5~(JxxI_cgLngE&LpIF&t_UbM`K8Tb#9unAa%Rvuhq0`2W=Xbe`mqw zdzxJD7uat6&_eT&AcXTG%ch~H5vWaM=6OGG_!K;@q5^83#kb1_%{YjEHy<^!f%4}o zJ7LCyO-pn8pJ8IvhMd~F18P%aq>c3NfF6Gog1(Ei3#eF3k1U`7EssN|Zi;s^#m(Fe zmZWRh4RtlQj--YeUO2=+C&$G!s8w>E_%tv2nT09dWq}pJeIyKZ(F)XvR`}t6Vuanc z|NJayeZs-}s%n1D^NP_78s!9$zLwAjFG`j%RF)1OQHDJ`BSO*AqH(6v zILaevlL?^I_2h1Kl)xQ}mdE&fj(%a*y;`fo$(3V$)~XcG)@E2+;zM1N7gBE;u(Ejk z6{_)Q>7POo;~2RAFE4AE(5L8wQKuPylCLY-d#qFE0~`Ld(b>RKG7;_5KttKr5x|r} z+08UlT`n~je(bQcy7-t0zq8$?40Sor(>%+liX(^--9G@~9}2YA2c7f*Kn3|-soNr5Rp5I zvAz9+O*vTc_DYU0sv|03DM?}S$Q3Ofa65T6##V}1l&6+Jwl^Y7hK`PhzId51?Ak|Q z{FJ^o34&aNGii{`j*9dctF>$n+RU>YcN#{+VO|#|MkT*?6ObqJed1Tn5Gj-x%N6X$8v4>WirJ{Ejkh1E z&v?)?VXCgS+Y4_$I>AZ$ms6fimWVAjn3qGS<-oF(w66jW?XlH-y;Z1^KG^i+i27HD z*x_U*kP~De_N0w@%!VV6Aba*{VFO?$asOKyLwWMq(UDPkdIMf(QSBYv>c8f5K!(j% z3cq2yQB77%+ovNNgEdA$`)X?qheJ0A)0292V`MLrmKifgdN>Svaq+$|Sj?Sqa^~uX zkArx&?luiByX{2bQ%K}$zIR?db| z^nzGozQ_p6)>J_1Mbto-I0*KK$nR_onjy!d*wY{*EDwQ_utYyCjKElb@i86OX*8w+ zbtO>+DM~Ejid3AT6?(zBH;96**H-Jb%PzVtYRN3}1(X?Q_cKroy-Av>EhGiHjCMV# zxF=iw=>JQa^!2jdFph%p6+xw7>tKIoyl3|SS+idUQHe|c%J;?|_U2;oiRGI-k-JbM z#T2E(uqCgefZ;aPcR7{~jUKOsv*HNSrC|j*6l%a69<#k9v!m}>)t=zEZu^<(vh;BM z`$e&Jai!-$)fW&A52VIRBpb2?nYmXRAJx+2hk-RP6y_mSX5fd-j`05`zg%g|c=U;N zR|a=G_iNa44#0b)jr_gzqkvVBjrPKr)$eYJOfRFCAW8w_^Re~(@j6NC&SrIGBdz;^ z&WF}G+_DExx9cZMw0USf1AHQBUNkP*r6f3JQ5?h)vu-BUH`3NKI1jnN@bg3Vx*Vw z^4t;uZjs^K79gq^Crkb9@VQ$Qqv`dRVIIK2%Z9Q(s!u9i&^7 z0Q&OXTlFdAJ3XK+)z>hFpiccQ16N#d)czi4$-gP!b9^Ex@MDuJQWu)lh?`NAQ08EL z)?UE!RCnKud^r@&Pu26GLbVm9zBHW@2jg=IG>`m0xj|5ECYjuGmw2?C4O=}OsKse6 z6*jOx95=B9U65j-C;AgQNt~b=x7Ya4PFR~zmF3Ym|7_*uM6syFeQGy2(iu70fxk z%bcT^-Ukh&s?@3})#7!i%^*tfldi&tTiAbF3F#!bge8EpVNjlync)V48kc1swnJ?) z2_jr5=O^lHhSS&b{lg}`h>R86WMtU^d8ZelBZn(ip)kqC_ATN7-lo)oJZj0b+#>7Z u+lQ9I$gz2uzawq44czl_Jiz+QpHkf2lr`t&qHZSxUmEJ#YGo>xZ~hP5(p?4s literal 0 HcmV?d00001 diff --git a/sensing/autoware_pointcloud_preprocessor/docs/image/ideal_timestamp_offset.drawio.svg b/sensing/autoware_pointcloud_preprocessor/docs/image/ideal_timestamp_offset.drawio.svg new file mode 100644 index 0000000000000..0b8eca9dd75aa --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/docs/image/ideal_timestamp_offset.drawio.svg @@ -0,0 +1,784 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 0.01 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 0.05 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 0.09 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+ reference +
stamp
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 0.01 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 0.05 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+ reference +
stamp
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ minus offset 40 ms +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ minus offset 80 ms +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ lidar_timestamp_offset: [0.0, 0.04, 0.08] +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ ideal timestamp +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+ first arrive pointcloud +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+ reference timestamp +
+
+
+
+ +
+
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ minus offset 80 ms +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ minus offset 40 ms +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + +
+
+
+ compare with +
reference stamp
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 0.09 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ compare with +
reference stamp
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ compare with +
reference stamp
+
+
+
+
+ +
+
+
+
+
+
+
+
diff --git a/sensing/autoware_pointcloud_preprocessor/docs/image/jitter.png b/sensing/autoware_pointcloud_preprocessor/docs/image/jitter.png new file mode 100644 index 0000000000000000000000000000000000000000..c984e940171a647289e71323849df461021cac54 GIT binary patch literal 118229 zcmbTeWn5Klw>`Yrf+9$#gp_m(NW+#8B?RdX>F!q8ASor%AfbeGO1HF>G)PHEcQ^kF zz3=Ba=lz{e@BX0dT35{&bIh@Ju)+%|3^Won2!b%4Ka)^|pu4INgtUYT1Fw*`{#XS6 z-EtIru8fL`Iyoo*3p~Ykl2mt6vNdsXHE=M7l+2u+oQxd|eSh4AAWG=D#1mz=pBvNO zZe$|~zs@UjYerb_YlO>Lb?L)710;fo$zBgcl&VPQE-bmDH5a9<>o=^-RbxRPGrE^4ncvJgeOyoTWfo~{w(;_4!ZcNQK&>SKW@Tfe+IYG# zQRWVlHb`75)TtfK*T4&VT1^6((Lz5IptMgATpS6Z3WG5GZ80z~ST(;s%WR>;?ZZ#Y zz2^5kvQk83HsZ?3$(5P*XKf?HnUN3y;Ik+YIQg%*kQu{8(TTmAfc&lh%o3X}1Nyre z;3b3t6$Xn|Ih-KQ+`2%){8bN3GW$JRf;+Rc4yZ*N!0QzaL9J$|X^?R_2BaF97V zI;v4-!m3rVVJdol-xc#eS7yk*&Db>bMV?)!#;H4&)llSmdfV&x>U?{))VO=UUv&28 z&l-=zwYfQi!%X%!t1?9mXKO`Xhk0?j9_E*4hhuu)m+0(uO}+o!mi9a_yUm~FuG7wA zXNT+csZM0eK6f5eErbh>7U|7SOq~7@#|jG#6}s4IS9g7-y)(W7dMkz7u1@ka@=bWv*ypFUCH zaLNsF%Wc^+4*SnLAf?4H3>XH^)>?KjUy3JqeQ|c#=-Z0W^BjN`-ZNt`WBAvMZcO8| zK%W^n?-SHw_%cffLjSx5YSF?f7JeH$9DZ)v2>hZJ8w`S@+57$Np%%byv zi+o1ycGAKno?@j12)YI{|p-gBN{ z#w{(+L95LP+$`#+_hOaS^-wp?DyeM4PT$V=wtY8cxOlVkALj)QS%3_YynA=$8|4+T z6_r|EUteEdJ~ADjAf1`=dasMQuu7~n>Ath@aXLwW!Q^9k4k+#Hb^xBSH^Dy^pPPQW z7LrdEIBX}i&5rQ&^u&4~#OJy-<=Dr+yp&|yu$#pj^c z7Yh`k*BAS?b-V4`Z?--6mwG)HBc)unXD<7%FZ!p1AoyXgZFtdbND@63el|r6m)b;HT+=E*n*w6_dcL zUDt+lfb(5{3Vg7(wY9W_1m)VgpHEf9x?Ssk>$Ca!6x{U@R- zI10ppD8{(DW;I!3py4P~8Jbm2+u+<%TG;oP?caDI8e|6|czkYQUj@x}>Q#S4y~j*l zmgktagZsJm(e*#ka0lxqsztX{kmDo_4HrA?3IVJ6`_TJ@%>Y5aIjp55HpIS6{xdk- zIub;_G_qK0^#8=o1_=-+5e^xwQW924%>P`u$@M0bDui?U!~c2Zgy7~I-yi95} zzpwmKyNSFEcm6vd;Xeaf<51oDC*n5+{uvUp9R0^D_;4f%SLgS#50af4(Oo`F~GA>Sw8BYu0}+AAEBZ4B|gsB>dzMf4-|6Z7g{1A%E{4 z{St2nyKrp+It-$v{hD#RsT9KhrmQqvmdS~_dQ;i)f-AS< z^dfcSMTq16A2SdqfR*3nhak9ciIwSgO{Xlb8-$8Ht zE*lPn-=P5(6a7{!4T92ULixjT3TPYbb)?ixN!4yc3U_a{1eZ3VLD()gc97D;27d%T zo+c718kXbDVLw!HOAzbO-X4NtI2!qNkJON$n{W^Jj-<~Io#*XW0>))gj z;7hXa{tU5`0d;{@Al@%<(?Re8C+CXG%fq;!XA)yqt9fzPOR@c|$x_6a5bcd2HAVA> z8{P~9IU9Z+isz23h~@jji3Bl8C%1euF9klf<_&|d-q<0BvAO)AJldbtI?5aFy{OHN z;4NI&e@qA|yo_B43X(j*fRz5Y7o&{U3_j%(V8*DT&Lm2fGKEW~mNKu`1B`W&t+mM@ zxTHob4NDUWB8TSB95SsZFURT7fbSiC$}8Jkwbd)L8X&`|t}tvKnr#TUpn%fQ@;3&x zV0KVE?#=1TYFq&~1jsI%D4;NTfS4dMqA&dAH6EluZgW>5L2%<>@ue4KP%s== z2|4FbMUeVqHE_JNHfZl5GAQfeH(JO-(05|Y^OZgyXCr?@-5a(%GoQ3hW@Kq(5JJ{$ zDHl1wAIdUpC}!wUrjUYwA_CsKAv9d+?kPX3FLqh-$B6EjnnOPC)lj2pcYw{LWUxpH zm6bq{a$+U6nIAZk==|IM@MC}>ZKi7g_OwVm>ZFONN_8bO9m-7wE!WpZ@&W?`N8*mQrYA>6 z%1wF`-<%%_gIuI{eKzKttaJ}&!>1bX!MYfv|C#e_( zQefSx!SkSi;y;k!!*pr^`Y5;Tcs*$U@y-LcU*UpV>WyCYK|%*V#L)>^+)m~KL7sbx zb2?ht0J56be#NAX(rlek7w#4r%o@1q_EqCl2<0Ge{5Uv~-}CO;v`zhcE=Y=~_z*OV zr$hiV#ssEzNIX?aj>F^wgXdg05bE37+5#+^$YVK7VOTP*qNa1$!_`0Kwh(sf)~$Zw zocdK_mU-gT!Ur+FA*bsQ zrj_#@r`@8&C96VQGujK5$R3?{_|q6SFhAgP;g;b~T%7LGsu+O$6$)ahlF^%-lL7p1 z3C8t)(wG6ApPx$_HT$A$nG&+7+a0XD#5rxDxT2&6ne%MsxWToHHtu3U^lD*Q^!ijh z5HoB7-EF)6*k-0~;yeLtArBAFZdIJk@z%7q-`Yt_8r>_|laZD?u66q`wYy(&y^fab z3b8JGZM_8>BV}NJ3Xp7~mM<7Mo70AG1YPR7M?i6bU~WiPwjCmYOycl?!}p5f#=UodDLJ#1y@jlwhkr7`!=q(X)Ywt@>l#?Q75T&B|Ga zZq^$}`$;l{umBk4kyV9aOe=RUfR{zO^#UYe4m`O{rOBypy!$=HyEw}oxg$YL8Y{Z~ z_(^F9Ag_js>y_vH2X$vBWvR6myHck1a({uI^Q--BZ<;KA?tJ7d%6s4C9t_O`91rBdpBVq%3P*odisfWVaPRV%&7 z?x>b+*eNLhek_FhUUVd3gLtxc)$%>!G>wKDt5>qD?{MSrqGx~bA|2DgkKnNjhBME( zYTD2g*$`_Jf`Sb3KQdfgWj||aR#*V_%CH6^9Q7C{lmSu>q&bU+KK?moMK8f=dQnS& z@hmO#YB{-Lq=ioxqtvwR{ewP&Is-WLYk z!9QBOEbD7l3-i!bT!rPC4>;D+*g>5ITp5W!AiZ%OC_tD3+&f*pT)aLJQ`wx z*rjARB~}4&2*FfR%2`EEcn6X#{QrYF%@U7zz4v)Zd2O_7oK|V$wD&;WRKNF~S@e9O zzseo827s^;@&fORWBK|i(F=MRq8aZ?+Tm+tU$NfTI6feAQG+Q>f89jzk`IfBv#s776c@8Q&i^CFu`t5&eez*04%JA@TuT4um zLHE7IcLdBgMa$Gwe#0gJ$}b+`&Yq1{zWB&j0)iK?GIrg%_@qE=4yS^WX6(pOe)~Od zI3hzhN_PV!tzoWim&dl-_lJlCs1rLuw8|6Iy#G5Obb-%;vK1Q@QfS)^kb^KG<7`kn zf>`?EQ@iHS*FPZkYtFB0=Sl0zX_rasDGt8~foCly7_8U~<{>u_At-2LU3h>up7`2b zD#Mner0BR6lnhnUb0K1MfAb&uvHvP!EWo(wWw~_}maS>S--h{QyFo@o;=( zIL|{}Vqn0lxq*YqqPM?*I4ygZ5uVmwddHl@7s;2vtM~>p;zXYI?v^&bgSWG<_H+i~ zU_)sZQ@!4gEmx5AnLyg*i7g#wgTu@ypAE)xiQpqaX_&0Gsgt9)6y8&*bc3UR@jCva ztXlN9U|7h{#ZN~9{v(6+CgZ;!7@4R5pnWt}ySINd_5>I+ zfFV_U24pBDShqk>o(a@JKnk&_aZolZmo>VI6QU`ALJW-pf+GLgQ`~g<`C`y1Q7Zp- z`1<%YktX8})XMGay#VL~!Dv84`6~oF5g&%l;%QN@w~)VKnaJA?k$rF{xWVj^0w}OIoS&hp)bYC@|cz8h-_QRSbenEsuWn z*$)$|x%H;JXn$6UUfd@}+z0y@WGo2g6Iv}09z<8_?%BT-|< z^5+t0PHadD;veI26EXWY^QJIump_THy$Evehb>;BKyW_l!mFoGFnK*-pzLrGNEq!OrQp(kUop*li%+Q_W0I)2aQo_ZRwH0c z`Bjy#dTe|4O?7eO=nOT_^40K$L`&}Ov`{h)opboy zK0(y}dfvTFow6W`ek1Rff1$~=nFUo(8a$`1Ox?V@iE_r5f~!8mP1 zw0juK+nn9GS;|&jg5>tC6O-(+KY?h*mi*R3$>iy!-hFy|oP5|VOGs8RoTz^Gj)nWBwJP+;}5TMk+g1{CYs=`e>fAVmxGS4As~=KFHS9uy=hP4f42 zEG;-BjJEEVJgVsgf%WQBYnI-jc4_wSNu5-6z})bU-0xt6a|C4nE*S@PW2io?Pi|h< zqfcrjZ*4i8msnt%9nx2Hc0i2+38@xh#;rJ6r0k0RGRXWkO;Hz35%I)yMYHvXL!2+~ zw`)-4|67IW+Fd{SSxVc8{p?rvD@*VFvRN$p!8NV|9_#0bM>9iKV=Zma>&L&IPd*C6 zb!B=xj%`q+nfV?jQJ=RN8k*qZisZoj4SPoB3dbImlL!3=_5f|yOJoS~e7K8BmX7%| zQ+hxLp)3d5_e+-8O$iK}fmTl6pD3N`1II<<8H_IFZex{|4ukkvgCi41XH7ZV+a8-e zTqIZBzz-?{^mj8Lb7dqwOtU5ZEVyaGP_Z1%Tg&^Pd|(Kc2I%K z$P(Q}gq}UxW`Pqn5?~#x)2-NM zeiJ+}*wCqb2m65pW9rRa8isW>>)5+<3SKOAq$9)8&JX)*Z<@_NE6fJO6 zW`#50Yz>OkPdV58UVIXoX17O<#(k+HO2l|7x^&UH1)cn6qvKy4Z{9Tm1FM$*RIhyZ ztNjnf)R8m7Jrn6r_&BE(QJpm@dCq@x33 z@6HHgUbYybqeb`*R-bo^wJYkn8xW=GRWrI2?J^!k>-BFl7{=KRenr*9Q2^n^Nf`A} zx69E3{;Te{+grj8LS$vlL))|}*aQ0SvvZ>X8tjxTQ!VeFueHpakis?1eO4xUMvVIMOHWu>8UwBm2 zQB@JPZVw}eMJK1Iy}<)vFOV61F&pU(kD6H`A*aE!_pto_C29+^8^FrZh9th?iu8yq z7g>CaTMjR>fGnz71Zzr_`nTE*t;Yph=HazScxfAXc5U z!Q-bG$6R1Cc>#%caD5iYH39TSDhIA6H;GwwDvGm8Aq(j8CNMjnt9k$$7$wn)zg3kY z=o96}?1(7e#uxh?_q-jx!{a%L&58O6z`&sQLkZvKKFNM8t}2-Ck1#)-+w;KknA4TV zr7_x{H%<+IyQWZ}rX+3zEOJ3`sBd3V^^=1~PMz-?nJAgR4m%}LDt;`sT4c6HO}`lj)>_*#p1Rd>q*afg}su}{r$cm z0$BsXP%ZOpoUd`whGsZcH-PT=x|%Gqp}7^{-a|52F?#Xf&8Sn_wPn!#RzLbW`smzS zTfvqd-t}5o9N5#4Uzo@ z>za|D^NM}k&v#|1-fN{sL= zekiRKmA?|5!;ePP;(;okUFYy--l-WEyWgBDkvAg?n3y?J)5o;UJ$EXFlKqx)v`Nic4=7fczTrCV+}Hsd^|vp!aI?DfBRzBi_(%i>tV+>ajZ z?X+Ok&hE^Iu+Mm3U*6D3Ri@cS+?F!VM8;o&QpJg8w2Yv2gK*08rQ9+oVFekAW-zaD zEc!Hq(pg-AixpwZW(&aSmh*1yQd}!59qG&@^(&1i0@&fYwQ}(3R~~<{G{VVp9EMX+ z#(3Ze1r%Cqk8v(VG0{{3LVwp#`zGDhv2~< zR_#(zp7plm3JJwVC?fngXxmY>v*Gu)d+&ozNC%xPF0X8F6GejlZdIyAv3~PFy3|O=4f#=6HUCcZ zG)k25=qqhhmyzO4XZ0a9U?{V?gxMJ1amgJw9+E1X5*a7Os+7w_erH1`h%{m{eyp(e z7)<@>lym6Q>licIx~EZ$IKd=|d=)|Q=7K?L?WM_=Qu3Jh=$Cmr*aVMhd~}^|lb})B z-RhJ0&fQx)QnOnal$gz!_K9I~bwKuOQtqp-iYIiM6+seCtk#0heYb)$3$z~#CCrPR zdPo>#vGNG9okZj|H>L(&TDm)^jmi z7;UR}62s$^SbV!cpZi#igO>gd29CAeit;W+ze8&&SO4M`7?-zQDWJ*Cn|thY!~T(A zt!rbO9qbADz~MS|jpJF%0=ww>c(=hx80PEutF%(MU5`ATyINH*SITosC8WidMn*+8d<(O!d{4JQMQ%RaK>q{bb8_SZ*csh69!-s_j7Hve}+ zKQ{A!HuS&Ruzw4r$=Wy%3wmudlQ2CUr?N~@Ut}8b5O-}sMNMyL6nEMDUiKYbPtB)K zB^E#Th19YOCaF?S%?NpE>YnJZkX*KQOkV%q9P1bGeCc{DiF9^KA$Tzpaon&XcZ`ws zm7>w)BF?+=;AaS-o%hXI^m%*zX1q^M5ZSL&zBc7kK9>7^s};Ln=k+ViOLGtNQK?+{_5E}O^b8d};TU>1EdBUL5Xc1spVqhWrJVAHXh zu7UjJ#%UYXeLgzsF&Agab^_`l%){=yMxw|G$0aA%q8-EKy}bv|AHE8co1RW(-Lt02 z`6_hocXpDil1KQ)PjVkMRJ6`p6Z7iDo2eSRxwVm0eLf$AN7c3a>CR$ZMBnz7E@Akr z*+En7-kAYTutYkZKP353PA28DJjh9}wuWCM%GN2ll{}a1kMN_SvJymlAe=ZKlwl`` zRAxF{jFO*moqa>?0NBdQ!0R1~sqMOx`H<_a?JLkwat56YKzfJ#W;J;CH2nZsNpV@N zXP``~Tu`xm{rw*P`j}JtNu%ZeW|?w+E;Cna<*ZYAMVP5gSE@*S4j>FBrk)QXOzVC% z(Kj8@AYf9PO7l5*>T)H|Qq-N$8r_Tmfrd#u<(NiKdV+FRndHPLC;svU)|QcgnN~)C z8vCY^Zy5q z7Jv69OgwM=0#cFEmlyTB?WAi9Gcz-9?_l*M3m$)T?5jRqO4_boPN4-71&z|h6wj?2 zsmwf4BLg)MlUPKgt%DDl+uDBVYPu&?Hi7?w2aC|9pMVIbcEx@Q5Zl%>Gef-b6OYD6 zac8RvX;$vE2jrnw=3QT;smlH#4^&Ef?0ubvjt^7pv_90`NBRfJ+)zb?x8VL&fgJu0 zP5Ps+_;doX3ZDw4|3$(Jpz_1{7+EN&G6%$OCRQexdy=D8%okg>b{yA9r8A4F-Mp z@fw5s8t_?XH^TIR9VJ(O3$vOmRg62USy=bzzh5yyX%#r7v)+RJ?--7aTzl|S7bE0c z6X`yqGd2y{Bm|9TKyT8Xsc$Z|uyixxR-8XZ$rgxvP9GhW<$C2q4|_8I=3L#}4}pcn za(C<}C2tcWd&A3X&*2|V(uyjw7>bBI)dHp}1F`?m@F&+>*oJ9h16DT1sXA@mPJ8%i ze@I09{GXuBdcz>*9-Zd3q=)6+vX~kDF^#YP-s|KKenNxdBjX!4P$&9XCU?V4tflS+ zWXHI>SqPeDTse!6Q3ufVw8RopqSiu}15XL==CNz?3F3VsvPiZp)pmP_haMhXOu}QV zVMt9v2`{qSGBnY_UcpH=541v#`53H&utLgbU}NKOLDnwU(GFjTA6X=Y@(wSCD>h!6P(>H!;Zv3)ht%Vn53-6V3fVp2oYtv0l8C53ajyO%Si-S7|KVZ( zL*KMt3CRHL?;cP;q!B2~kR(M4gRx8o%a-7R&Cf%Gpc{4cx|F-xS6gN-ycDM^ydyc% z&~)gc{r-p2fV0HdFr$>uWamFE2K9%$x6Q1B9V2vn3 z1|pV~dLXDU7K8JEbvN@@Sa$WikK@DIdxiS%re)91Sm3-QJgi?%eo71u?ua^@d~xkB z6e!zI;0^cGR4&AWu|!sgjiS~X4)5I-Vv?{3dY_p~30eg_q@&A#xDv-0L-$I`{W&HY zPrPp|ml2cuMr3u9Z#lis4b8^_w}(F&kZuHXwc?FXu@n}9TZ1p7G;p_jlxA!Tb`IQ?p`cf_<%Q&$* zSo66`xqLeclh}yJ^?^%DS~p#EZr~EN7OHZ+H&PfJ*IY|N(&U` zDqB0G>1&Ns9LEM9wpkXqsasF9S(qnYu_3P|d$L~P zfzG>#8kia07bT&3R3$#_Tph&FB+(}iPBb4?d?F&d^og}?SWjzzlnJ~89cK1CsPgOxDsb)1Zz^IBcn(K;3;1ho+KoL8MN5-9Z0?m{O&Anyb+?{ zsI&pgX8=sXmU{J1=JTEn_b(Rba=TAtL9;cT{qSbs8kYJA1c7Tr!yaAiU9hvVo=_HA6~i8?=)XBVT4B<=Gz z%@^uLl4t7GKoE4ap_GP2t8B)+NhyOQrPVv4JISWn)H}TEliMu53s|yQNl8%G6rxmP zoB7^oSaeP$9lnA38n3<#Fa-Vb*5@|P>C+%A+c1;Rytmn1CLWKque}_UJU*@Ff9#EU zzQ3dkdX?1U!wJb{3)OG)!2d+4!X1~PEo*qlu6#u8I*8Ml7YxX2QXf%JtKME&RDP=t z{xCSdyzyFipHXCEQ^<4Xe(0#A36y8oj~4nPeg_89 zdw#6e+KnLWW{10g!=behK)e+O8}Y(l#|cg`(Pj+jU4A$;h7tcNn6r_K3Hrrbl{S| zQxLI4t<C}6X#K^27$6*yq=ANM#+q0D%h1MTjw8gLlSWmbhzb<}uX>#Bh&&V?k1 za45seX9pL*B}dHsdpCj^HO)zbpYo$~pw^R1dae1?qASRGp_E_-FAGtr5*An&lJ8%HtoOe*!=)Z$r2 z`yT!@gy^(iF!h5eu1MC5QU^}A3-wbQZ5$q_Lw8DK!&}Uuj7^Vj3o&*B4In{#TbsIb zt;lr#S%&OUYxKrbYR?Z8@|Vi^utP&zDXJd==}V~89yzC;qV39zu8D8y39~=Esi&`7 zVE%7A8UHF?)RstpTva~<^qdF#BSc-05))o39Pv2@G(`D(Vg#@m2wiclY!Af0pM6t+ z)}UuH5{Di~9!8k@z4QFVXXu1qo2R4D4c}62 zzz+I}$9tLG#JoD}ryizi@S&)$8F=zUJPna2a#Q=P@R87KDMf2eWN-pB205`0>?o~N zTFE+IuFH_52guT(WXH;W6054}RO(+JQsGV_A5|;DHsh|1%03Yl@WQ~q81*NWbsNFp zG1gy6h#R}R$kt>f+lGg(+R1yrRm+mJhi-Vk^J#vMHLZr1y&~pUC9pmZm*YBwbGN+gA#6f zyo0J0?}`ddFnnEyggFU-d0ZKY>8U zP$cJ(FA#QQ7c8Py+NojogJ}8yr^C%Ti}rH&A{*mAjyUh5bV{3phn!;CtayuJr$+Za zmbN!a%@F14=O-T>vo$GqIZKb2%=bLS&@@M;(k2J_lnV4o)KCqG`~1_%UA$>{elZ#< za(8JUVu)w<%;p&HaFuuNZ7M+hyJhTzbd%0iV`ugw0vz!c+z;rr}p!u)pQ< z!e|-LF@SCi0Pw04Y2A)}ckVZNyzhIknD89wwjIfsC-$?SE+n18kjg(0-}Y(EN@X|8uiogV^mCjohFFv5J;QcH<`wUQV>7VL%sItOItW$?y@`7# zz2+oBOW2j0nR*#5Yiv{hw`?zY!dcXv5pKCBmX=`pL6yYIOGRlx5doC)IJfU|S8P5n9eVn~hM z`)qP-So{ssQ0|df=x{uqk~C-#=+~#+1o21}n-hk=qM*-%l^+Niz&<_sU@iy(7B&qw z$V5CDiU_(Q-OJ}5mB{{1MEbWt)9-Lcoyo5A!CU2)GKh;RG|L_oKbBd`Q#@?Zq7Q}I zcBZE#myA?gx^>yKlT~s7um&w@6RhH234ZdK`BMx0PpA~waDB-!L*47%UVeLV&VqQz z*z_F;u+d26CM>KpMGtfKu%PT2wkGZBhuw@kss@9_?|tSZCiIdcF^f3Am#j6bdIUe< zIW=BMv><=$hX3T-J*~sLl<*hyL*H&s)hx1-VmExBW9$yQw)~imw%dXiLL9ppq|&|I z(UTIC|D6X+_zk0S&T~+Ub84<&)7d^05lM6;>#&|xT+NBGPjQM_11d$6wSt3oM!c6H zcT1Vj76j@yTALVnqI)3rq7L>o6eFpZ?xg|5W1P z>toRv@`Ed>Z$%#nlojP>(w(g zU#Wb!SgITrrkyZ-B*q-pRQF}#j*2rc#z&MOg;0$4V-X*U^cU&UswNbl40ha9fh zM2&zaIH)I`!wSi(TNX@#{c0Q_%{9yaiLD$^6SS z(o{dv60;>D{#E2~CVd)_))Mc>w1-urb6CmrBhsE}R3vs&qNrDLdLQW*zu$s!!>0Jp z&gM9|*3(DGvMKst!~E!WgK^YKj1u*G+E}S|(kQXb?t0m~^<}jkg(c0z(iva49a7eq zMh5dfgxY#>iEg$ghb-`YG>Cu`C!YxS62gA3N-EHbRW{Q&66$l8$rgli=GKm+bfh~} zRWVpSOgL(1J#1ppyiBL&G&rIRQ>2sL>ww>LMdSEa-Q}JH)Ll%P{f}cR{B#gc9*?|z zs6rwF=sPx0^qVOneqxk7vQ1^Wji~vsXVr+Rhw_-qI^-F*qSr+P^)TUJJUd8apH(?c zMm-!I(H!%n9tUu*>lqtwgfR=FV9X0F&4szQ1Ze6IEG65|H;=pYz2 zoGuAqa#|xc{#-I<(|AfDx~mcv?W4i!6=gtB+hq63%TdV4RM^G2;-a+4!+ppsf=7J^fl?QzZ z=x(1DOB3L&adR>^B@8y!buS#^j;`b_+#%-Ev2%S{!u4b-*w@YIdqJgUrpJxWQJzpc zQ(z?b;lk|q_S-Z(7DO6ebA5t=&a`M^>H7I=(%^>4{W()8Jjj1T@vxr*dt*Q zz)@f_!{Q$WJ^*=5UNo#n5WU!qAX%a&WB$R&z0`{waQDhvr5r&D{)g1w-Yv9aI(5Zp zSQffe3Sv1>qDAn75eW$=9rO)GzI2lusQ@VZ2R5@Ln%$#0QuhEslz2vaih+9|H!aSU zNDyd9ug$+LgVL2>Cv(G}MNHUBCh2)Wo;R~!mfZ}yxt;F5!G>9G6Y=<@ZkQhFmv2Ww zg_8H=vKri86e!+E$epXvW;g0@^4lG%(tKWhbP#In9Yg?PjwrZqF^NkL;%; z0@-r<#6zTHEEqW^H?ha}(gKcT6k<+l4}L@CN(-@2e0|!RwSNJ7Jb`1hq9g@0w*n)R zC@U#IH$v#;MCXFkXLYi;u={FB)0xdGr_bpVNO-)6d#`^i@KYwf@FO9l!Wp4q8nrl`Q-B@E~ytRABRpZMRhbeI6hjaeApG8 zJ2CtEi)#XVfF{?70YpNJ!7|7ng@J3V{gJ7Pu?15Wqe;fo4ZHmI7sgB~MlXU>)({=N zfdAjC$+!Fa2ZhtzYmvBer_r=s3v4auo;KYBm03txf zWzv_cN>ihO5s4+$OpXO%MpJN0YbZp?I(zsyks?osKK*{z@e{1&G6)rhnq5 zniWobFN6=@0uoFeaKDrQ<1tGUchQVrmp}pTor-o(JDqql6;cdsjA84q=?vY&rf8+&eKeYa(ZNYw||?P(^O^B?pLU~Tc1&{6Wj0D zAo&lld^Dh4w2NAtM&Vmv-oAJqgA^XOjSSM1A}ll7Os(qnL9 zdU=SS##E2nJA9a%iV^qZ{?FKxRuHv-bW_Lvc!A>Mi#KO=5f_Wzdi(>)iuOT~{Ae8S zcO9Eou^<(W54lIGhfR0aJBR8Q45m?59^jY~|F(^OvU?h-&Yk3zcc_8DzzNeqMAh%P zhs;+i{7&ebse0bBrtS0O2FSi_k@JjeL@$2!dQFvf*Q@jyFzid23P;9LbPlCFRxwSI z=3tfSJ1X@a_^@Q09*q$fK6>i1S9ARId_&a|&WDrHmFPdFAG}4oAs=X-RmRC_9EBFu z?bGvYsnHv%EjwX=)9HCa614$iv3uZf*zyI=f-ex0>w?CS(3tIgn^zm$9Cg-8Qj;aN z!u2YWI$ie|pN!{}phqk%Gty~u;s9qm_c5p^F~1E{5mo;; zhTC@;q*4^1Cu(3Ao~GMhTj)ReE+|^5QS$6ink$T7IqgJLlS4Jf;RHYWoAwr4Q-%t- zAvAV#`1$D6^>?>d7smp=XqQ@!$~iX{kT_Rsu{m4_`m}gd*F6zU}$PsO*)_vVi6L^ksAQ+!?2c zsYQn+qD76A(`9MDuz2ofTQ& zmC4l?#n|i`pXfvSwx(G-Nm`O~i_v zSn)8)=uvmrsmjUlPh58P*J$6xJ}HgJA!$~m-%e%nwi4W1-4{{B(r~9;VF|# zRl3LudG=5Xb=al#t}^n63agRO>@NHd*l=elja5!Vtk9R$k<0(Lq+Pk}L$ww?SF{S! zG{MVi4F{0P=TC!4MEC%U{msm%;@$VYp!-Aoa7-KG+POW);SSNWefhX55bMfo&3a1Q zXFB+-<rxIHuJ?c29g)$bgnvOgq$RLn`QE+d)hmp295 z{DpN`LRLs|QwNdak1MH!NXdP(YVL#!1W)qb=Oi(!7d`XtN@%IRr3%^K8R3<$GTuFm zF}JB|4P^kE{37~bCw@Z7Zn)Iu?oWF}@P@7HQz0Rg6`!WiQZzY>o-~pzhomQ5wael; zr|#|5n?$)mPE}cjQ_W?|l-Rn*(y~R-8b;>r;_=T4-{0jm^(Cef_E*P>!qO{45fUWo zV|yS^uzhD_>+{B=syfissPek#j_J#)@Af*MIvKX7yPo|*(jyR_-rzWDq>|M!Y_X8w zXZxE7)+;kYTBGW6f6eaR2h-Mr5Wi17b01gZ=Co;V3q`JOz!q7W&_agw=NArEGiBnu zelzQxej{r5b@}hDwb#veDC&OsqHoo#7mnnqHJ+{IfuEo02qy=>zA%2=a9j`Wc}tgy zxazn*p@<+Cyph|4CaLj*DzohWQS}v2QAgdkGXq1Xq_lK5(lAJOw{(Mqf^-a`bW4|X zcS(cNozjhTiFCi8-~a#C``%itHLNuYCeFF{p0m&1`)-W^UI>!Y9d~Qb+EPzXYepYd z7>I&PbY0So8sf@?(78S!+av!+_0u49%eyXSeh$yJ=9ejQ!~69n=U>AUV2o#X zIsGQ*?Tl9DeTtv#42ANgKuPm(=i~N9;70zPC7`|r6e1IrqX;>X4DJGPE6|k2aAa)i z7o(L>ozp7zK)V+!R*7{ar5<-o@DVuy{U1i~|Alv~n-@PVUjpoCa?iu==f+)Z>JQ`3 zQ(lin7o zap@=bC^zXemZI?9%K_MV{|sgLS3NBNg5!9=lk25p1QAEa{YfkTyZKm^BAPgq>#8?@ z8H&&ndY`41j$$j&-tVq!&7-`QS#0SfRK7^MsG*_R6_?c=lnKVzS-HZX(u+TmeX%0T=f7LjKNht zM^%o4!E68TWDGFBc!MXhm;-yrPs=32VtWQ{)0|(CYOTv{L8uMGY)w|A%UF*Vl%f`C zetY>v-IZ@es-`-lZHRO)hsJaRSTji%xSK`l#$ya#Q&gPQz8@YNX_2YL6P*@RVO_?n z1x{#vrne3e!6aEiS-(@4VoUG43El;1nn znSV{V9+<@&%YY8>pgsqem5ey8Y)CDR1gK&vPk+R9u*Y_}K^o-A1*pltzMP9c1svnY zIf#iphde)V@06GFWJJhDaUS>SgdDY4XpKQGinyz)wgfr>URvjQ=IO(>$w$)%;GwY5&`QIgAkJy!Q$+Pb3WBRpH3t}ZSvS4RuKpP5D4u2fXE zGtu`lf1=FQOFyx9l`4gn1FCS_}~{$Boh$? zbDPR*2l7=ZLa2yoC`0>Kp}F}&jf4PJ@c1!=)q%jYZ~}NWwDb?uj)0%c=@Y;*+n{{f zxH;Pb$jPFI<#i;aq-%h@UY5e^cbUoK0ie8px^jNL`a8_=?Z5u7A%&gPn0@KUSy5T(s_8NG%_aP5;T!(@g^r8{<}$ke5(m zYek7YFN7v6;oz8z#pi?16fY)joD}o6zv_fZDp!RR-1q4xkN9Q4+oye>02bB9D+Q!v@>b$0Cj+hk=jKMY|KX8GfO`;=INrW1I}C7-v05 z#TQ%zoqUQfEI#pz(O4LI2VJU^y3(;v(_DS~V_j})$-vsY7d2x{hmMKsvq+{~m_cBU zAho&5a&z%*Msbedw5L}fvs#tC>j+Mq)|IGsGpxVypLD{qbY??}5qXejTgu&=GtOKk z+Z$mgIJ7ihEoyL=Sxs{`c*k}#G&D79k%O=FuFy`Eb?zKdnyGU=VV8xYY5fxci_XJ3 zvUtHfr2{ZV$1$;=3ZsrS?`qX6h;N_*=8Ar2wkOLcBs9 zYSXPn%N-dE?6&*)F>}({>&|p9VVU@nuvIK=G&w2%^PZ|a@13p8nB#EdBDdSPSGZyG zB|ScV{Zbc_AwKTDo+&CgA6M11M!Vj3AD{Z4|JHQQ;Nl55?(~l(ZHxMTSh5@4N!I4H zcib`3;C*F+O>)}Cnb|qyZmAM21tz-#gQoa5*WDa-j5Sd#a>2C-b{MCKryLQX83v*O?GanutA2-81mvK3;Q> z+j~7196S>{Y1R77S%j$AQ}-eF52G>~Q_kFlpz-QQ%K;8P!>S(acBl^nx4mM@Jpy7A z&lj5gQq*BmL*rEs5&aF%w}nq;%+q_Lb}qBu_$vsV`(*L`PHntD7kyg_xWg=J^Z%1T zs?)i~kxS`+yG<@BO8sHaNV!KYDvNMZB_=YuSrhpl;DZMRUdvEZ=XQ!*nm#l?EsrABgP)1IfF+^(#4NPb;|5bP6gl8Lxv->`VyI2uWv2J9X`<~fHEQ(|F;l#sqD zmKkQiz#S!fNjMqZ=H=EOZH#;C0%#DQE^l{_>)CTfA6wVhY+3CDaEB!RDtR4h6>9q) zu5^$KuWm1t)%%?~Q1|^A+;V1!iP)=Zf9i{#agcZ}xLf0ws+Z)TAd?FXJ=>Wye+3KV zzYtaK0pO$i#KZVElpc|hkxF->nkrziyS=>3%uHyf+e!28s{j3Qz~fwisQ>k9zJZ~k zbpC%h;F=kZrlwu3OfH_DO=V?=kvwBJfRh{-{blho@CVOV4s`} zqxri6o;p{jVS9`5F`4(v_s-urjHe!N{|2-fiJr=jM^H}*lr^{BhjTv#Q(l}T=9mpn z{*&m?Yn$}7H(lTRNX6fNo8^s@U2|x;92evNby+0pC;9hhU8+pUqs58?d-28A#k~j8 z_VqX)KcBJ3%I=f*n$xhmj*(wfsmSezwd%GeT`3_U@rCxIa+mrSEx2dnkc}7Z%lxd! zSK$NtyBSL>k74F(&G#R@%5ERy8za{#xEMNt!DE>ObYuD=S1{1J93lr$C{d$%6Hqq6Fj2s1o(%Ga*iy_|e}Jm$UtE8XAoLjNU&LGxzq z9J0#exnUKDNSO-?XB^&mJ6(Y1_EF>P$%$f0Hsg6S2}#<8PhkcmgYkLS-quzRa2C{h zUIdIQ0Y^?i7-QnSUqBuIKjwu%t1|wmT-koLsKmlW0f-;ah|6R87>)( zw5-zmsfoY(;yp)RB9jP>ogw;31Doej8_5^hkL|Bs;Nr?&05zBjw_&aL>;z6!Xy}%b zr#72>n4HCons^r5bjwrG=*T0VV^LeD4PzW3?h@{3XmMT7P~-E!`|m?KtC#=fyjXZa zL|?I7uJe&X%WztnmXI%ZvN*>f>3C0u_Waa323bkiKp-uT!C3e`;P@8p<@XQ(zmi+@ z+bOt-6385CODWuzqK^CY@CB;P7dx=W9L9UHDfA86C5g#CgTyNfWe^F zB+bpHYQt}_6_vOf04Bf^)BobvCu#jt;GyB0NLlbo$oCxL!RV>4`#*JS6Z|=kX{Bf>_{`NMr817D z4@23hqcDR*^|m&lhP=38(ln{xoeyYs)yGTx8;PZ#JWfjjb?jc{=e?w!GTl21E=HST zxa(9h{K6R*yhpo+I-~Ow=zs#QR(VIF%S4DC?U!B0<6GDkl0?j;wouimh#^RyD)D&e z$lkd?29=xMJ7H;}#G)GRioIX|`@5?daYP9#xyJ=Tz!Zi171F&YK82+|p{e1lDX-pv z*EruQrAdW$S)Y-1t37tb<0IT1@L^pon>ARw>EMVYvUJbOy)iLvq&@UB4kcD8AEpv) z@98lhkUp*ZI)&*vo>QRtYqn3pzrV5M@=om!#n^C?#=<4cwr=OQsvn#hr*)gyPPFLGOE_)L>z{y1+ z>YcFFblraH$G_%#4!Hg_0%8h}_Cupy^D{v8Bn;9j`?dBkx>i1S_|H*uZgy5BO9XHy zk~f-@RpAmYLoU{yt};BRt_+AhdQc7UA_39n4wPDPphW8C54egrm%I#NEPPEs4*FY5 zg-V9g{I{oZwqD@VlKi*4M>K=)Qw>F>6+O=+v3v^{0}86_XkP|Ow-9>gzxWN6u+C7; zTSP1eJoZ_vZq@lbhk*lj-TK|zT1(m7pNS=EO17<_S$zfFbkxy@vB`+<%O9qDGgl;)_nGx zuYGTrof%j!2R<95+bW}u*}iI37mD>hUf;jda|HgC5J&Nu<-l2*h1ZCh;4ZBUw3TvV>O}->^F|mHmtH zAe`a^`PDqOxk(NcD)o5XV45{CG3ouz;%p<4pxFL?8ILimh_sa=7p|sU%QPo}HYUwO zZW2`DD2$Y3Vc>b=B%Ez>&d=aK(hToz=ExJ)0n>z_<~r({dYf__^!9F z&HJnnQ8xYE^1$*>EJ=4^=RnQv>Te0*s(wCMwYa8yOIE+M^nqR8HRCm&VKl3-Vn;{7 z8BstWXLmnkz{5X>)ql3bfLt$F<9+Zvpk8&m-A<-iJVl_q>Do>2VJ^OdlnIN>{9IoF^%S5u*qvp{J`7X~y`VtEl<^TTp6e&ity zzT16RW}7qN5_W1GTR408_v?+GqY01l*H5qJ<86~=OzfSgPYo~RMY-Q^e;3p!7@c`P zp)jO-B8nk;wo;FTnGY36#f0Ud8x2txL3e(+C`~lG|$sK;Mf3>Hkx0Mw{!eY&T z9qU9tMH^-lDhm@2m3-adUu_rjLy+Eq%WpUW0xHg8_>$T>z|h(55dG4D=dY@a133QY zr+K@^stSWSlvG;c0uT-9o?F8w1XoMNL(51CewXqZv^Fy9p}%)1@tXAwI^R(OwQ^@k zy}7Gi6K`aU6(Zo4wIZxi_m0w_qqftgOGUB@y!Hqq?_e_O=Yr*%biRJJ=NuH zF%vQW^}EU>se=@84`Orsuioul=PSsEGyN=K25?rT(tC+lWMHgKOF2%+TZi7Uv~1yM zR(JDWlD`FPu)klp9~iqrqFJjLGfvNbfH!)2Y(=9Sghf%@eUPOsJVA7U-A|O`fo4Bl zZkaORg?To4%*O*VJGDolwrPm1oW`+m5V}Tv=DBNCn{D@1%xd7X*ZnsmLCrzTeNEd^ zq06F%3j_F-njDNb-P>{#i@0_-qf0?ypv-2YmAu<=8O0=C+ly{aax5Os9kuU05w?+~ z7kfM~D%=*lZ>&-svZ*|Mq#+}UKJ0Yz$|wfb>BQ)L({Z;wc)$?wfDc-JD7^iCED-W> zGXWK0Y5sz2!!I%Uf$QZwegY!J*E3o+*lTIb%%`xYuaz0PgtyU=5)_G>JwHy4^e=cHu%S$*AKsW1aCc;YshO_ILCM78+E8* zVwnP&ZT#KOJyVq4ARL!^OSLUfv{4SZD8vye^5S$mBs5+}6K7*j#M*w)5MIm5Pl5@$ zIg1H+xbJ+v2XXT85lH*HSOz&0Ypde_-kn`6<-px@d6OnI#;Ne>3xwBO0`VX#@gx+& zD)%X&PmAyJY>>pWY?Rj!E&%cEo})DDTo^^E4(fYtU@%=EX|~YsVkB)EasghO;F^QY5Q;_P;D2H6}Tn%^8OjM z51V~9al;W@Yc+vy2qzDDV{7>nw~H(vQAGnKE-$4%G@~hg3SsS78hnuVYD}wQlH>t^D_6x5&jB%jDSl#^>HfamZw&*68 zp@a7u?|K{ZTnv;@um3L>0H=uREZ4P`u_UdAGQfgSz zU^K$^kcIcESCMynN{s*_${L}nVEAO=6&95=c@_rgKaXV{(WBXQ7}heId5$0^ws9mM zEJpU46;T(ki87aalOI-@V;iUO_A@#_BdI84n)=`9{IgF-7W)&J-1)E#cre`V@OPqu zRK;$8C$SmIIJ974(9E3WA}V1cqy#HC2&lu!ZHT407v|8}VAh`-^NL}^xkuGh!bUn6 zj`-P5#KD98Zp34Rrf8$4WZ6ADj{_=qr`&rSYUD3yX@2I-nV$%h*q_ z%BujwxEOF+E-w&De+3^Gs%jgKr&nM&%2Uhy;O`rjQ41MG$&gZq`%Y1R;7?2__xsMb zOz*-=Mv?=X=F_0u=RuqJ%*o7v$eJ!@$kMq{eAXMFx1_ z0`xbZRUV|>H()g0#pD#HiiTq^v6?3 zU$u6hhJJecM>{M}CZeyARvN=xNNA>bHQFoT;&y_8;A{Yc8~H9`JToI!d2Ne_pA+FH z?&cyEws}Qw7S=OmU!Z>A473IJ=YH}ei!@mdNOtzL^arej(Pqo#AQYcI^=riypOdf-h*XKAyolDaPdZN?boncdOZ)JpPunhk6 zV4?7jP)Fx9s%rq>5$MIG+**(%^jQD z>#?7nX6-p@SWhkQ<@gY%@%yGUz6m56IjX82S)fgf< z!UR0W%hXTUyE$uyBLDhJs7B#;mV@ZdaLmQGR7#-&Bwz~t&N3u~0{e*|CPj28Bf1n= zEQl~04=T_m{F%UJG#I5`vcRImDJneK)tuQ$<*bXN76<82k7aPcW2>l+c2j1I&XEUW zdP+a%UiOp)4JS-#3dgS=y>`)?WuQ@1Dm%>#guyueYwWf;Z1d?$TCG*>pRl!dw+T;l zeGd5fP|iLx_|Ef_S2zSeQ=e4jW*Zef)t(r-Bd<=ahH>*z)C}FFmXU2HVWt68@-uWs z{`Zo!%2J)qaw zJJV%n{B^ZhbsLTFFr+`k4}?r?K8uX7mB>V$y6W&aE1Q+d(-O_1tJAg4n3~D7N`&rL zt%JE3?9^(&H&p-hf`P1PnEMe+MZmb$3IdYK!fT?C?v8$F)0_2<7!I zO_D}et64i&%L5sbfFg-#<-S9So2P2j9KJU3XZFur!9LZ_?@Qzp>EAm+B+cY;ff#LX ze*xp1{Y(iwzI4CM)}3{hNTNV9MCTk1nWY;V;#Gdvza#ZzwTt~WBKL>smQXGz4=1pN z-hqz+x43LjHVlS0&aX9?VBgjkqY9wF;)oA5{zy7lTT6A>fyWp zqvNZw<)eHnhly#WJ>C_G6Ml9qFW96Kc?>zD#`+M^E_fj(4e1RZe55!BbEn*k+18o} zt$OS5bM*oy3OP}fx+}G__KY&HghpqzWRo)KWWi#p zl;>6tn(hu_|24f~Su8tNr5Ca|I)W=)vq@5HsRqv!pHXwk?tFr#Uy)b&Z=BeG*3%Ss z#6BKxOLBD+<3d9--^i~sd)eg_G6pijg2Ws^>r zlp=|y)b>zYGcgRRLS+nq?8?ESzb)f;=6Tw3XNpk)ODPLMa z6))3k3KNK<=oI8Aiq2$B{3b}e3AhC0r1i7|XySGzawIPTWF3T#3ipxRZ|KnuaiF1% zQe@AFahXLaBDv5Mubm)_GF*K(PNbo*&lv3yrYoEy_DdUE79l7Vz`1c8SbpM8^a-g@ zQQZ*kwiDW*hn4tIw~{cMFa*U-PhdiK@NI=sZU3uqhi*#5*)RQnUnK1WUBy_>hY+EJ z&yi{1Q+?CMGq*(jPt-_POC|VcfjyAboX`pveNVw!Dw}7U3_}>#*0B2p$XL@37n@Tm zTU{M)CoSx#Do#a%h@_)oO*|FReD<(p?E4x-OmF$Sl`T!dff~(p{?FO_ivAXzCNEDc zsjS1)4_>fRTL^q0x+8Tz8#MQg8*dcX)1Z26M=k$TtpW?t@PG>($;j|VEz~Zp><8p4 zA)1<7Uc?_*mg)=wMQtq5XHges=@%w_W;=hbfKM znHRbI-|Ex_TXF6Ips6@YjJRtOFS4zjgTm&69p>GfO2Q zJ_&gn!qx@l#$ThR`CQs-*L|sE)SUyJ-#_RF^(qEub=iMDsE#KpV`BqHa_~@3xXHjB zMnbK6rkI6hp6@tfrdI9CQ}Y@TCI;*FMaeItYR9^N26o70&6xYycG2-xVs^ITP#F$J z-0&uX)Pz^Dd0h#ohyzb+UY*MunI|dsl4kv07D>a6^5o)#$&rxDIDZqFK`R0g@ z!>Z45yT~EJshK41w?ZJ?sQh@5T-0$pQP*i;XGyqF`w)AWVbyZoqGNfELe_t&Yp-ra zY{G_bs$c*gy;ML97licN6{hyasiIp+yVm^h#gU6?u89|}SwxcsH);j#z*m=Am8b1j zH@+|phIF}Rw{qABu}7}O2(!O+ER%o|R+$C4<}z0B&V)8MMnURd?G!TJtkSj&W7-8X z*$7Sx;*0R_8>nfV3g!6Gwh!EWbvNm-#i3SPcu~PQF=v`6y&nG^l+1L}cKBxYF56lC zV^F*LQW_T3C5v%xqKrBYQq(h#G%t@d*r0%z#(wg{lG6U=w>uNiA486e$AHRKbC;yh zZRtF}Q9Zj$6zDuD0J~IqjXF^H9Mw#sRf;ga<+Wu&PhZXv4ut9q; zQZ5Mdt{e;}eZ$t36a_i5dHLRQLmpZl0p9pi`U6x-vaS|7kWaU-@}C1T#SFbV2Li;O z8RTML;fTfdVt5L|ssNSGR-9{JkbIR{DqbYIVb1*WL$s}$6}ii%ihxgPXsxj!eFW%F z*|xPzKxKts3wgD_I^1uvp%(30BflpHnJLm%nF~@*gKv5;pmOwj`=JM-QD3j7Q_sDs zbqRJOi)usyg$5S07z_ya2&QB&rQ1h_srX?sUq-EYc-g!G|D^MY-s@DTjl~mg^;fbk z3g?Q~Pm9uskI$Yru4w@IYy_KndOB(FnwasJkX~Wgy1#HDw1}b&#c&k6Ke-ExT@)n_p0c)*e|H-T44ni~8_=^f$owf;HUteZt~+-asLBSaUXZsz=Ykd zb4?+}VCK#M7XHdW*c&;-w}TO$giAS6*={3AyWVl)MGks6gNh>lgpN{(Li6&yYS<_t zx|rO(OLUDu$6#^WpG=j4N6|1`)f8J$s>?cWhq<4PBHaU}6+adFU;vQ>1daG6fKG(+I^bG=u?aX?6_s_ZN8kjKv9J^J(+O8vP zK7H+BXEF_|^%Yum0-n{RD7Yy0bzgNJ$nNlyd-^*zScj~|aCi`V2||QQ8e>-y8pz`F z0cT*0EdIKu#HWk2AHinq{8O}$C_VvHkb^R2o!fNeBT^e9EEpxh7F^2pCp7sT#kGGY zGQy5}47Mbq5dQj${P?^$nSm@58a9|bhUP$>mW$_bAX*aPI_FBD8^pkTsx+=5Cf|Io z6iFQk!RK8I@Cw>Wnz&+#n-O_mhjh@ZOH9Ay#^Zt4n;XowA<{eb3dYR4h%Q4kA5D%z zUv%fIAS$TAMf%^15>x(A7{Uj_;<{<64uM;+q=LZhG+lk(@4#1zbKz`Nv4qkAzWjX{ z++TmXy@XUqiN!DI%M7S+)7ujD)(ZRuav|xZcMMqTv5S3CNiZZR?NyUYBXmz1+$d*o z4A9)8*igwLgmPsZpo1iT1iUqd^ii8iQ_02mwU|)RVr5t*^p(<^UbR9~&Zx3E#z*0i zzEU_(=2wOZ-msjreFn~*G zkx^IgtrL8siKJWk6KuBaP)@Z?3x4tA<`01j5>G|*%`f`IjYH<$cMd{gLnXBsnKG>U zd6p(HDiW?KpUl)@cNNJp;4SsNsd2WR_^F`H&*-09K!Rz7QVEgjP$9HpefjxaH8UNA z;Abf8V>jVnMCQ*HSTtyAf7o0j-xYri&nY8$*g=22F*o;?o1g0E=`bb~+l^3{tOF>s zEtL_4j1yi*ZkwjG4(vG%3D#r~1!_sR@^*7N^bCizTCZ^KbAC_+THIm;GiZ-sypo?# z^pR5HhYMjsqCE|IHrP++A3s`Tz*i2oL4=XnYZ?*6O?4X6cel0+oeY|1D^6#Iva`g{eXo zQ;7ypg?z%mAXRTQmI1+-4cdg8PqBx2WiMX-=B!aL=#nb0)v{ReN528sFEf0bb=|oN??XfM$QzeI~2;S|qc1k6BG zbwdcDawoszSs^gKC_>YQiquJ&=p<6K_Bn!4Ip~DU22m^>?SQsCaAtt2y>daRIUwy7 za;yqPrfGjn$LjQ=H3K*XF5{ZSaCY8)u-&lhRmtyU^4jTi8cT_m6v83!)>|AFwdk*M|1PN=O7@7z+Mo9w@MW*H0GF z){KGSOiGE(m0Il|yzja-dwH{wIZhfIS5=OQP<_sy9&)?I@H*-or95#A2C^yS>*ynG{*w#J_&EtCHvV8t7QCVbwAzpIDKB-L=~dv#|tA!6XimW|+E!xT6%@?2jB$^`RyrCpKC} z9sc1pBTSpWTKlzn0#~aTU%gZ|A9a?NJT`RT;AKb*S58pgR&j}1W9@B4il|C-%e%Ww zwy#jo&94tM=?`n}(VKUU{}!s`*l{tngS=4U|(k$#&%$4B&0f??ys{X;b?Pq_PET zcpj0KAdv!2!=I`P);;7R?mvjLA57D(F6j+c-LEHMzPB0r3!qs(;=TmzH$_#gzKkN6PO zC!0x_w!o{L3ms^swG(zW-CRK$m1Q}K%p-Wo{Y)b9UVc*60N&2Yb>?jBHYpu&n;hT; z+?3S@xPT_m8frX=o_dYj>W3_{;%6V>oUUnjG8Iv zMk(?*wE7DT0`$RlqFfxP{W@vy5?)sW5%dZ(aSX-_q{aq(V-ZUQ)!|YoHpOc2v3iAH zvW#7Ua?GpGqy4rpap9~^VAO5%GnBXeB8xPoW&zqq$A^#E;5^N((SxsxNWeV-$!Dvq zX$$QZ>Q+Lu*QQfwo&k`AaaXbwYvj4e?)!8G^zn>Ji=LF^7INi}*`O~Y+smH};V*MQ z%DMvi>4(+OP)SmL-$&eN7wI>u!LRkg^DVVL?~B^D&PCJ?thnS@Na*|)#K#_X{j&mgdJg{vdcm zqm1TJj%l1cSI>&t*oHlkWzOQ%4u4ElC)VB@ZL_>({14jF$Z*IjK#|wYt1RL%00}3a zotMhSB+y(hER|)l>uY%ygfB>ag|%LPoBwzZM&r*obi|TVr1NwwltWb5qMKv>(xVvh zQC1ym>p4(io?rE0bHW?}^t4Oa@p}mUHLbuf?`2+j^Q4UeV`M|zl!W4NdAKbj8qR6R zCswx$^MAX?x8i@d`EGx>t!(|LglRoGA9q?| zKGT%MahYx2fP&Euvk#E`KezQ%S!DN3EC4G{_3@^}B%>VCRmPrn`?u9S1C?f~#cayq z_sq*rkas}6Fd~PJgLk7~j1TqCD*zB&MwkL(8s0uZrb2;53oXYC{tBn|N-X3KlbCoU zYBz@UwOhB6)m_xD7NVw(Y*0k3K03}q-NJx-yAToC;!S$MlB#Ps1%@M)uQUS*uq-t9}kEf(2P^oO3!fdnKe3t_x>is5usODH0>Khb7 z==@pV^#9MAp^#!F3^pcI6a>G~{!%^EX~){BrrAc>^M+^;qHc-p=J5!3BJyUm@wXq%k}(jmFo37b(Rg50 z`hFZ>u_Je2igFkFRw-cslqgef-7^?I82k(JZ|#_g7e(vTV%~@n{3dTp@_b=?{e<^# z6SKZVY}D=P8)?mbbi;Npa}Y+Q=x`jO&$&K_1ByFWIks z8!H9UE5^pewe5{|kW~Bkd2pzJ_to>}k9bHlN&-cV7QB~6@vK?IuQb>s`F!f-o4ERA zwc^vVh6Zm#($8M1ub-95lFaUzpba1+^fg3x0_((evLqATw&WJQ_@k%sQdE7IN7;3936e1si!y@@ZSvn$bRQchpxwwc zd3*^vniujqY&A)`ELgD)h257!LjkaX$czi^MU$m&5(I=N?Nw7*&zHwR*BKd`iKe*| zbfgaN`eQfu!i!xBOf5#=);3Qx622|!`UdE_>@_8@Z+g!7PNVJhE1(p3_KONdE6_nz zhV;MJp+=1$;T%v&k))Z=X;a1NW|`8N78(U^Hbl#9SF(!n%Yt2g?_#wIeJ>w6R4<1O z2G;mxKw7VgR+0yjuSCmdl|R)8R8&E1v15H6c_TU$gz}@N{XTICz{;v@73mjfW1Ui3 zoy6DgaOgqE)rVIIRZC(^LB6rMpfEzyA!Eq)17ZmobLu2NIzy# z=xI)taC)^@Oy*@~<9ENO>bFTUroXSq!Ac{{#(i--k!w5gXqrYJK|`kR{@P$I&a2x& zOB0W-=poDj$&oXJI~SP|I3;d!{y1r5e)SWT1XCyTjxW*Fzw)R4hU7pg4c>&3C!^r^ z67-=nsiK;VdChv}3|D+%Z>Eiy36Oe#7nQLd8&b2uWTnTWAfE@`ISX|8Y!nXthi&6o zyMeF4X_N#uwG#-1vHdlCZ3dl5o5W--XROiaPLocbR)yVwT1*|Vdh;ak2*0Ovn z6^zESm9MOhs71*veQ`V2X+S3SR`bz%-Oq7_y3m*P;jVBR8+aQ*E?a7=a|K43eA~S`6e;& zD#{lLHnJ}rN28_E&R9hi@s66WwjSe|{UA#Hx5=hWRBEpj*Y?KGreL`*FAFo~{MMDb z<#tm{gH@v-6))62?+1s4j?~fr#WC=a9zk=I0RJdIS`DCHB7tsr*Qmi2Z1A&Bk$((l z#BUsqw9#|cQh^QNZ)*(#r4iG3l6 zoQ)5YZ_>4qan=%dx!v%(#?WEqGm)fkH8o|tEJG|8Phsq$YPUDQuRtDQXx77%Ny_Xs zUi){|e3Z=m-d+&4*i8`SgK2$jw}Wz-fK|}RughN$DLQ*C$sEd_q#MG!Y$&746^bJa z!*ZKhV@^<<`jN#eA|yYv8k+JU6s8UbO-!}Cf;7mmmOQIn$dM9s>-b`=*n(T8d|vxR z3Y^KJN&+i><$R-T)ono^^yiM~9SP2Y%Wsr4=Iug7ZVc2o^e~6sHa_o?kY`#^a*1^0 zZyeBQ9Hvh>%?K575cPEdl@~2g!WdSzrGR%){wo5mKpssf$oy*AokhykZOU>z)Zr+@Nzy>3ZP$mv`q5sO=lMCuA@i8S%zTzEC+Q}E@4~V?H6CytHB*b zMT|0~SG;$lxs|79A-~D>e9MtSMRwDjT0>z`mW;4;P_`s`wbGzs3Nmi(jcR6TU=#$< z^6N)K@eqDh&-utA8pI+B0IQCL`|xp&3Ab2My7itYe>cH;InBuq98XH{V!3$Mx66|P zq{MR&dIi)9L|J^%CePpbJK)~P-qTrp>T<79@x=<}(qD>kv$45nB&nRF%lYe~M88vQ^IL3*=5t)@@cZ_7Wb;qS@wn(vMGgqJD~|qr~%ZE{=opbf;3MobhqgQ!I_W<9kDf)3$1!|_1oEpnwC$x?1kzQ z*tsSt1hYQ5vU{PB41n4y9;(oS;uRK}g~L&f7pG{F@l7GvWJ^US5nu-T z>fQL0<-n#eZ2kwrD0>ZE+-W8um30%*sLpz%1h}*%@bV55AIkWJNg1PoO-oZ}vN059 zC9%#{-)v7T6a?w{N}L>w{B2-aFN?NU{af$*4;PIp$;BSom=!&6&WvA*S5+m63TasJ z)vN|H41)(>Y_ta;X?R}wRlrUpK!9%wT%>|cgM`GUZ8K+?JsU!ii+lyyC1M3{nFd|fs6panmpM||xA8a;@{|>CML1JWylTr`5tqeD5=Z_?MkEMIS zk~%-2=d(G_3~KW{#LrNd%9e6+%+@;mV=ejE>;}M!?&@(aZ2A6otY#ITK2w4vGtGWO zdQ&l2FR7cv2~LLWhYLc<_Ke@>`xUb8=DXQqFScNTM0Sgft>&=x{-S_$9a9-0pxQnw z+yx;u_>Q+bd;JToLuGUqmwJ%;h5EW3%FJlGz8y1&Q$IoO)53UYauSoKg!^5iA@?i< zs50lX92PcjtG#O^-ph4zvXo!54!yZ)mc(DD?<6!;w3xQ1Nbyo$p3m(H8=Ix#Q{ zCm8nN&3=4OEGu#_6+^iy^+b|AYW_yFf)#7wwz4h|fU&e6QP;HtNu4?I{f*{QE5geB zDwVgM$lmC`;#(rgmkM|K&R4zg{)fE1q{X2?*GOopW01&@mjgN*P)fFJ`)xP`$^|V| zwh94EzC2K`z#vu2YoRP&H30T@jVY<=tr=s4F*y7jsO91Mar*YdAlDt*v)zhuPCpQ(v;}32`dg8xo%390Z5$rWSGu$`>~_Bnbg%Jrq-UWZwEnA*aUVmA=5!A2knF|`^L)Tl%d;BQ_L$Bc$!qWoJ>f4z#4O$%?p z)-c4$a@9{`Y$7-48b7&p(%X5n!C#^j@~HWG9|6W?^|x>g|!w*54ol2vU8w#c#mZYkfF=7ZCg4Qyx^S@B)lQaSiS*?9*@J3&$>!%SAWdU?e0 zUHZ#xum53n-g1BUHS?fDP3M@NiU}WRdr@S-8fHE%uE6B%{7u4kLnus?O=&J`WWfO5 z82oth$l$)>52pwO$O%z%?^M-4{~wyJIw;C6Uhgg}4N{Vl(jna-ozmS6(%rd$(xG&B zcXvr6Al(fjT}tPDzkBD-Ftfuy4D;@J&w0-Cdjj&9fEC^J( z$3Sqs&W3E8H!rTGmmGII+5mp1%OuFOxTwKKWp$V9^cQn)8GD)pp&hPqlP$Bzg>ty$ zau<$dTiJnv23aZKKWX`X5TFYqQHE(oat4De9Y<4AcUwQPbX~hXkLy2;|fqT}hK@p75|-c!UGlrnJ;x^Plv4S;W!xPT+ViAX2gNn<4}6&wh&7pU7aU@k9%mXo&gnMnr;H z1;?obUGEwUD)PxaI%AI>m=T}_97kcU>G>b$YLk6_Fb|si6#Q;wd!dpD3~*^^=2mAS z4Amfzs?k{Z`+}RRvh;kyq|Uoe1v4j_JdhGjoSijT^Dz!m*f0*L^=qI0lJ{(~DTN5@k=ZE}&Ge@%|(0x)4O`5;0{oDX)9Y%@t;)li|!*z0o-tB^+B z-6ju|$;Q(#$oSbv17@AilTbw4l6oBguYl#YBP4m1hp8_+p#N5;U!F&PVbT;&`5S!f zE)se%wT=YslbFo79d2&61nN}r?a3Di)4qf*TG74C$j)v@y)x{FKFtSn2J8G@V3qyH z6EKY(jLt8h8wHvJ3_{uIWD_?ivnB7#kI6I;yxYXJ>g$r`qTY(+Pg@syp_Q9ZNqCzU zS=@CI>5!rZhj5YMvIjfPIM+-HMdJ>CZj{=nxK03GHk`Kx3oSP6-UBmH%0UFbM6Zl# z$T$p%b7chAp|DJ~nzfW!WMPtq^wq|@5#((Aq3=usWSmczhx4v9!epV%IBA^Io=@cH zYlx+%w*24-d($*_+&GRWB?>F;4C|mIyj*c!7?+1=@3Q>zPp1nYJ@e?z$K%N8z?bn^ ztQC=;vB7q;3o!3XkhKFE2uV0-gtba;!c9lYn?jPO{8TiIQIe{)#8~uTPIw^| zS%TaSZK&1;{MYXO{Rn#z0#TYn>Zbn{0mv?mY0H%_xh*i=XEcU#*f|2W?%NRg`V+V=#-b*EbtV%gfIe4*%qw{r(Y!rv%SfShkbi z9mOr4BhJl&3%3@fUTkxn%sz;~T2O6p{(4gTx~*$eF_O>W$Q-q6&y zi#)zCow@@y3ouBI-3I*7)33pJf?p?dBv-J+#{2zhN!c{S&Td0&n#~h`0;#aD3Bpu6 zg_m3IX#@TvDO-y<$LX3EHR+8TOxrI$$^tG^p{uC zhX(lKN4$#rnnBQT?p#6hoW{_T^tOuz!m*`-NMbz>G}LlNax6OFW{fk-sl|MB=ylY< z7MzqRXeNf)aev@Dn@N0^ugfL1H>3Gn@CL5b)3#`OI z)VUIb=Dmwux#y+{GHg_xStzE>jo3X=3n4PI)Pa=BgP>4^AcdY?q8qW=I9uygDoJoL z0p*rpRIjUTYM5H23R6WyQYMoNX2UP{au}>lTg$>fHV$00s%pGg;55qn(mr-~a@#qvc(@f6L zW#^*O(C@p?$lmqE2>ksq1{*m!rG}4R5ka|mN5`o`lPxx|g69&1Vkoac^A|dz)9D@vHY6dc1fR_uRZvtUKwJGR&bB9O~5E3MH@(Ud4b3r7O@_wLT zeV%dPlvmWyBWAn@;0$)k9R72-i08TRCC_U!87SMp#_)C!ai(k1IrCT2YmL^od)=`a zi7j4Mh0-Q2w2uu;HA{~rJ-RRyj=^vh|zljc~xKcOC**IfAcEh-8Ea*3jen+ zB_G$^9k1T7#N!ctcmeLVQxi1Mgr`RvFez`{(3#((JzS=?{V8ALRsFw`j&Z1Nc`VnL zn4~pz`r9>K-%H@SK{<+<-uX)f#<$jWT^+Vxiu+vy+|UFHLLj*7sWXiZ&EMTxhbQEZ z&^F`i?rTSwe_JND=(iPycXV~^S{xuasE+Cc=(~C&nqqZil?Bg5z$}RyCZYvDnljQ;kvN=U2%Z%@ta&yhHZ_m z+>}C>7>S!e(toOy>i!#+mNr0n3+qs+@6zdY#uZbMOBEx|v-3a}w&4-GZ6f3t$5eC| zG79QyI`4UDt{IEgomkT0QxU^rqFQGNUGoJ$D-R(B^20!Hz z%g#|$5p8w(m#>`pp5tuJxY6TRb0>}yMWSoqb5KGo8bM&=VoJE){;-sD;npPu;j%ZR zB^K5RQ*YHc#iye`{OboE5^jzhiSq-U$OfQ^+8Ozpg2Z|J_-@}){|OHev{&|5oVYbX zL1x}qpaossrXqWyu^X293le+``l@DUi2`H#C#9fWH&z_a=5U}~&1uy^k#6I4X|A$K z1LhYgZMf9{eW65g@(_%B?{nSU927(**~-RL9_ZJGz1;sOko9{4RKSwa-X3(Nce&BgK zQA)q!H67^Z_uUG-bInz&3tQz*#K_dH2)*$a-|?=&GnU8+rr+>VVOW^SQB`0Y#u8-E zn#)0$KvW+3q2f+wOU!&Z(s@l!GSbV%s4h-R7{>4MV-9#t>w@PktO3y=V?DkPmsUmV z-~Fvo zx5mVBrvBL^0wdpT!axk>Cc3gB;!Z%nzX3ilN_P;G3`>w?IN)vp7_Iv0 z4u~ha47v?4b99X5OUoz>Q64QIpXEH96VpXxt`llmU|0Ai8Q{V6MzOi&jM3Di`m=cp ztsbb>nkf$7QvY-0;AL4nuH=_PR<+s<_IcFtNMI9&9uz`H_r9y~M5E;6}#I%E>w-YRp=AwP+W7@UBnH7c@U%y4<4X9;-dQW_Gj zBlfs|uw8ND@rEb4o257((1k%L0k7-2f6d3%gmn~DKP#b5T{V)nA&jS!Z|vU0mftI+ zWa(sS8}b(&n--p}YdwHMx!`h82>w zC<)j>7z?t~=s0h#y*Y|5dRYXshYeC(A%gjLiU0BM#fFJxCY~_r0!!C-M}v?E5oYGz zYvJcL&*Nt3-PNqprt>h#ge6XBB!ay;MOtbR6ws%%DZ}8x$6_^Bc6nnJxSUx}ej9PmhxO8XkxP~5_Z$@8r!V_sJ4^k77V!20@aLscv4h-}n6WCI?ef~c$kQu5`5LkV$PJ0e1i#mhx29O13iwD?xD{kz4BzY;H(Tm)d`cP}s! z@Nz9d^fqB|QMd1OQA!Yq_$C~fth}d5y)2#AYkFP!XG*ddMxi>rvthiU0Yk{wzvre% zs!S%zY9(^54N2NfRLJ7+&Buk8t#=$AWc^#a2$@BG4lP@REpaON%LM0v>$)6zrw?p|#Efk&`5vEk{-R7n8s(l2n_~)! zS-Vw~^Y`^_ZChK0fg#7Mm8BEm{?I>dv?}*a$eh0neuD&9*B4t4=Da$Sm{>&ai7@=m zz^1mk6Q56Jl{6Q5_`obFuyZR%Yv;-)NPb~P1x>fCP$KuFD$1M3aK+S5Y%zVXjtWUo zTE`|>?sHQ!#us>jQZu(Nm4Sen+tT=PA{?Ur+=)OVTHSo*&9T>Z+1U~`1_lPcK_O@U zVbt!z$pwao(d3Y-l?Dl`Hc_Heh3SJibzNPUIV4-UO-Im;6qkHJp;wDAJ6b!B#0G3A zs0XH`pI9KwJ+9u*8w@>G2n~B!FLm)jA?Mzcl43qeFc*Z@H0kQ0dy3B%=_kr2Zmg=V z$0G}Sw&P;oxkv9WyY-HyO#9qnxNFk-II4-%x+kRKhEw#*wkIq%3wJoPPXrI3i#tVf2)KG6;8^YyGKlYnsVYmJ( z^b=(*nvuR&cXJYEKd@3I_u@0k*1CX3{PbG~qA@MKCNa#@UgkkYpbH4V{uk}14Iz_AKLJ*a*2Y#YB__GJ-0Y4s`J8oh0ONdLHGL3p zy#pGqL$Igabl1t#p;u8P5rS6R#@hZ|oUvoZKA-yb%;Mpf(yx%p-%hC4pq7a~&v4fG z=@heAwdj0~ud+9}b$SUYcb!yM{zJIyXD8aE!g9Bhb2cqVU1DI(RpUHR0>~K&MR~}M z)9-2TLahH9vw>TzV4VAI3+&te@Mmr96}o zVYf{&?WF&$(rhxN%oB^uz!5}&Pyq5@odG%Ra;-W7SLqWam*0=5dC^%|{=?Sn9HKa* zMcwrySD}JwMK~g35ouGxSHjt}YHEY}a5J#Mj-N&c4xH-)tFlh&2Bw=XIM6iy*>F-s zJs7@yIf#SAG@S-rPE8b?&78!i+}s z2fn7`Fg`l?SoEZZWY?Ria6e5JH;YjGuro+Daz$A+R?wgWHL0BPjI%OhkI9# zTh=4^Ta+fEvjlv47q!vOZO`j-J{^$V(WuR|+ZqJ$8Y@VO`fQwG} zPjlKlJVJyGw?RM364d{qqyet4*7+ur<%SiEEF;9GY^=SxJnXwdA(y$or0U+8H5`FQ zE`hUptXyQO3p0pq+zO}5FqQQ7MO8;-{fJ)1GWtg0{q(9yD~>GcRNwpd2oc1>-7`wa zVBb!ku`S=X<`yImLY_>dL~AgDAiG~Tt}vkcHGQKv#^kL+i~7xx4AMpz!t`V$y)fN} zkBMl#*z!F-$i2vpXbk*g;fhPK_ODW9J~z8KSXWZ2pL3=|s1{c*{%hA{HJZSemZ7y# z5uYG~g`|t@&t-WbN2n(k0fzFQuO`Ht+ZsW#jcE>1)kQ~3j>R7Yjvq7mu|}CaS{3zR z9v#$Qvk0wUS$EhV6bvV0Y@S#_e+`@{wAa&vtDsXe4@(d`aIX%|S2^0k;3Ni*VAI-G zZKQ9n^3zPXTdB~2vf;#C%0i}OIy2sk>g7v8x#yxCfs4KYvY{s|Li`6)q4!ER*g-pR zx?#F7F2q2o+wUCR!9rk1=y>Q*^tQ_angceaa_#;v0izLH=C=jXs8AVxZH4)61OU8* z-l5KN)HXAYJR1+R(T#CG`_^*h!?R)fOIs^su$~QBrI1(o% z<;+_AEtCeJl98S{U}3Ob_kEqCpYfw*x9=+KE^FQW!C8!}jo zN>(1Jw7~;NlH5#rw6s6-<40~3%=g&YA@NKzEi0Na`D^p4OxsJ=b*oQ3Rfh)#+GmLb zbRsj5=rD*|JL5Fpc2w1#s-k`+Bfu<*2s$We@F*ngKA^3XTEEjoyb%73od@#e@I2i3 zhouZlWKSHO3f6_uuriB0y_!%$nv`K4_XSmi-ATd!Hv|Brwbg;UAj`;wb-n-B0u28H zj7l+?mOOZkomQ)sa>oHs#YNrTacRf$-zHAsBA?oV6EU*B@8VgsEzslkvby;3gArBc z;}^kS@XL}JB%qj4D+c)>dQ`fkAmsLaW|NG1G;UWdemW7FeNU%}qSgHV{7xz-GkB@A zYk$RAU)`-gd>FlRSBAX9q+xg>E6jjv40rDcpe8Gz1Vmmy^Dq}cYjFI4bHOuz1R_SR zBU$rNrNL4`rmaCeggk>-Y3|OY>&WnZzw9FQIG~?RpWy*hh^vCp z1N9r}J4p`meSF%+6TDnU_ElB)=tP>x898wS>(ZNRfU8+Q&uNo-CxiOkSsb_u*)X4m zY_1>zU42Kvx7|0CPlaW77$_MC?5Q&>l*&x58NWgTfh36^0iVl@NX^>vARGr${~ns# zKQ@7Q)R6+E1W1^BJ5LC-G&phYaj{-$2TFcli+w2|-%zYxwb-c4bjnP$RM&1;(YcV;$1c{RUzW$y;zcq_g)UszvqF@Vl!AJM#)I4r3u$5ldG zt++xh{QlG-#IB@={0{R}yxZyS3u-;kg(*@h2fgHV&V3GAYbV1xFnvdvGB?Udd2(M0 ze+v(_Qd&pAy0UJ616{yW$*McSY0TgDEkY9X1WvwJDj1Q~MFc$Jnv-|e_$M0ImP$te zUvyn^#{yoi$#wd2LO@NYR&}zQ`xcL_Y**QxBL({p4zchq)S5)ZYgvGB#7SvQDyrgg zOY3mTKk#_O6fQ(+oz=B04`fd%tvi#ivEruZ)*1sy4Xc!AQNs+`4>$HX*YdYmzwfUI zrNtfkTm8@s_9=yiUyy)Leuy57v1w(x{Au+RJF2C4V^w5rpabkmBE!3z&Ix2j){tJE zUGGd}RBN!*31#b^@Gg$bkZdsLmpoNRe1cD6&{%RD)&R zoOYNN`AGrAd@7~}s{WIl;Tpfe%Br@G109`}m{Jk082nHD_gmJVX4M4MMyLN_<5mv+ zCE@)J(}i(70Arc%w0CGDgR1Q6$5h{@bhYFt>*e-r&{`D z<|hC;GhR>9wnAC`5MuIfsi`in<%QK3All#sLd)=rh{c!`_X|Wm>%+zat_-&3fgp3% z5^x%MeH4rz#*)|hJ;ui-P}SiuUOty308o6<`#nA9yk5$%@)F$L7!y|WbUHcfANB%g z)dvC!m%n)%Yer4A(&aEwoC={!?>}`9)cEZ&_S`hp=yas*qV?Ym(0;r;((3W~Z?9f@ z>P31BG7l<1thWa&%FZWZ$}qJ3!g9EfQ8Qc}Ur~4lfD|jhPv5wSwkG@NM&0RN}Ql(b&}^>`9aE>@FKyJ^b7X_V1P39MHe;@htbzd z4k&mw3;}6$>+iQ^;Rb5s(!=W-7R0~vfIQ0dKu^pd3@ntXf)H$vqLa*=$1FzfhRwV= zk@s=SU8lhB37fo|O`Z65bp7PAxh0GO=T{>bNw|RFq0fhG!ZeS5AE1KL-}DhRx`=@r zuNw0-kqZ(2DLK+d!KD&oBRNhKK#|y_$GXgoJYRNjm*%Ek`tR=aw9TIH&WsH2F9qIY zSBnxAIChTzXXI&@lgv>1Z&EEaNiM^!5u@PGZUSS@>U=VQy=DKwj# zC;Y90ka{%yX?Hw}yi6QqKKtmT0q60Ee5MQiJRB^mrXo`@|HEY*P;Djy3ah!d^Q7pUFtb@D~g06`IEc#61gM|XqrnKEoNVE81@zMX``?o zo|~)TK*Q6wlW?%3ILOs*0gZ6kH~rrE9Pv$+Zzn&uL*+gspF3d(-6){engLZWUIgN6 zhw5Dcdod;fcXtsM*z84$@I?Nv@Xv*g zy&-1QcAgw`RUXd|BlQix)rNC`wQP7@t|fFeB_5gYcOXvYvlBs^oSb~tb-Mu=>zZ@~ zAK{@RVkWrpt2lvtnRFsjYt+N$yy^?ViZ>R(AR+63je7{?fP|ZQDCqiUGsl_#mq^7ovuu-`($lQ}0+&H}f80oq)Bxc_jx z*?uR~a&~&jHcU6tl;9td8~bLY44RrgBf(zXv&+aVD7~!57` z#){+PRG^&m#1h_-*Fw1r;wQ72RC^MVznWoLUDhSyq?eyP5-uW9aDT%STaAJwl2|v% z0m=dIKO`+pBfb(HqDY`=Lhq$&((J6_@-SO)Xf8-4{Bo@f`{h_pEw5mlHwa6W(TRdt z-#7jx&qB$i1sFD*2VDI7oRV>u^ZMMQ@3Z%n*z`ona>Tto5e{afhf1M1KGJTTKM)h9 zBWYq&--^)$x=c_^v54LM7Fjl}2pF08OWK13@b(p#NX37XFBg0yCWN+nQ!2$dH5Dl& znN#X8Gqg`raqJ;KK~caCS@b4k4$L5EDpnWbH1f|#B)7a`0-A6^9s`=J2G}JL{I7Zk zD^@)iE|7kNuEDY|u{pL4OhddTtKw$bP`CjqZQl~fSTNQR?O(~Oo&V>2I{dvvmH6pf zr75NMa1m!sgs6OmhJxT38~lcq|6Ywxo&JwEz|ZMY-L89$uR)h#;F#XV--CjFbardtaa3K+`cz^cO~I+fC!^DKHq2Rks9a$_Sw$; z0CM5iE6;dJDJ>O43-kFCtpgugrtk68 wNgb0RjeFxaF_1%Nq)_H;E>UUjtih8@< zWr;(%Ab}5w4yjS3%TDE5oJb0u5@1FC2$7T{xkP4M+cWmTya3u$y{+Uabeu77fWCI` zAGna@k>9ND1md#3#xZJ&a=af%5~%unkPH9(^j=yM1p1^qV#KN3;u9?U8dM+lh6S#7 zK4rY?vVMX^AaI4Wmkfk_HMh-GeX4Nuo?Vu~Wy+CRgnyCUAUP^NJf$<Vst$v|p{j z{MX4NNcBHR?Lpdq$pv!sY=t`3e)D-vwf+^J`){XZcP-(_16r$w`}w z*BD~)w%Vy67PKc(ZAgPd>MoPpc+Ls{Z zF{vto8erIAzH}<=`F`|!i#`r<14myF3^fK2$koFhSqGiBbJyScm$dnKF>$5;nS#vu ziAQ0f)P7z_x*0h+IRR|efDbc!TnzljFH#K{KJZuWerh+_IrXzE$|EkGw>OOtsp?Eu zbLUX|PgUT++zaGB;M?YGEzpMV?mCYT7vr%hOrfbo(pYSXfs5HkEYttg54I1XnOl!G z{s;F-@FVv^lc1z~gz1rr!ZhoG-K_5iYx1RK11@T$=OFqHbfL)a_N$lQQsw0xgiN{B z*n-edFgHsqQvt6wPMp$0*|*n z@SiWoSZ&bT6bXKVY=ZB_xg*s1am zTu1K-jD(ERRoWDj#?fJC;xi9)X*6DT=;YrNBW&sl==X_44=%9eR4J~=xJ^8qjql~^g zNl_9qOhcVrG%TxIUDzmmf)j>3-hElTKJq+cc`t792iRQUeyzmg!Cqn#$g zPa_LN!%VWh@>vL@-^_ma9J?WVuE+@~P);e1Ww=VoolRO16c^N-Y=7umotMJLS{Ako zp>X=~DK78mBWLF{OG`QqG}WxuzgjvX`ar~7$6Q!Bc0M?Z!PMTrsH~la6@H^fQ)Hh6 zkhr<^<9fw{xMVhnq9ISq+ti>|FOL)G=NKVBbHYvWtC63qLHkTkWW&yC)c5L5UD|4Y zhETiy>m)goiVictu=pW<3Ku|Ekw?Q$(S+-pJt+qE0CwGU7;Ud6hTS_sm7Q?s@1dAM zp@K;8;W=C?Aefw?T{(a9oN_=@CjQ$fe07CCES1FW#a}KBo2s@i-JV%ze4k|DHGXMl z{M2D^MjTpq{FP9l09xX7cr3Od$0{W*pC(erB_DR)>ujA-*2<8Z+H;ycMO2J0TNrHr zS)CpA4f)(eHxgONB(i?MSs(mH*XMY*ql5p9^K+~jhsM+c!4224itg-}^|VHQ@l8{U;h9=zH-x38_f+^|>oFTfD1C&%Md+2TbPqFlPQAs|~v^gP{(o zSHTXpDzYp(ZN`qc87E~`O`Q5MvL1gE;bZFz8;(qLf`IhNN`kk;&XRz(~#sS{`7a@kn-75R8b}%-T{?wJ>j6E>r$Bh6ZQtP{lwj5PL9v@Ao1hh zJ107LX;t&@DgXKU+Go6fQsjSENy4@C@v~1VbC^0XHKX>l$_x1AHtH#h*zoiPXMvjX z3>CC}r2hfcQP8P3$aQJi-9rpTbv@Ph1V5+S@{7nDrAp40iA3yoN@DQo|NLp!orKyJ zY|5#+?&~Map!c@7WKuc*Wd-++A$FNV_6huz+IbgDp``2jsYsfZSXvPgBJbM+eiDXH zcdUP@O&zr-jryu9Ad1SmAe4)>AgX!*MuM5TML%n%8|pSYocEi@n5-eY?s~`WUNq~N zIS_mJ8@iqSUh~@U1$7y~FQyt#wbFLq1-|3GPx5^u{)K$XbJFklyBVlTmsi7u{xP?iecjFd%G#63iUH$2%)XTfjjMtD; zMjTx7bGZtQWTd%*q7rtAT(Kv-+$bb<%IeKWx=RNvuj4GU*=ctzHC*z5K%gr|@$T#I zmf0oZa}Hs?yDaJ0b*~AJX+Wx`0?WqR5)VrO8v{|>|M{SK>*vBh_Xoor?7F~$In?Ou;R7?1oZT8i2dJxwF90o@e`DYdaBu@HT z00bD>ES5 zzq(nkZnIjh=o+B=57NQ^1ukUn$ zQ0b38=7fy+cX=rF%J#M=>egO#hw0iTU0K$;+N%17MQSxyZu1k6pO&c8dNAa^EV@r! z>RN1^Oza@p^S)sQQXrAx8c zdi%a)wLq?G0dub?z{87B39+M)sxpoT8LQ>%_{M4P53#CKpJ(k6g9i+jP1Vb1JqiU3 z`I`&8zVoN)Mbaa$ZRtSOx?oHR@XU~`C|+Xmcf9FHhg2`bkFM=6$NQ5=f}iVximIUD z^XQAQf1hzhQvxd!2reTAG7gvcXDZ9omJfxOCV*^5NPwt3(M?D2Uc87lFI7Q4o z=WU-uvKHF#bOJ(9QZK82cPX)aAycY=YGa6iY4-kIRL`p#JlAvd7N@*E4squCfwY<#cgxmO+O}n)$Nxe`ZqA+L+aL9< zOYL6bnHbS@P|7`YXk1H0>3ZiwBYlw_y&R3&svh#9&_bvQaG^X{bgSgQc|Q&Fd_b8> z%5TP9f21qxsB^I&%^E)ny|1vSfJUY5%86SPq5M!9V?7w^|D<}`24Ttz$F37G; zO5>XWzJ(jX2a#OG}FqrM`y4#gBmrIF#=Q;Oj48#l+g_OM(Cpa52oMC3-*aqBx)j?KwPV>Bih* z0c`;r#SRPL$NDDOO^&RfVPtDljYt0BWx9yJ?>X=>zU};6fGu!g$@BH(XDrv`g}154 zKn_A_i?GKN5F>xwK?A}Rat47U`X=hTn@B`amHz}?sJOnvZ;|+BJmy}V(89%(q*rHT z2oJ-_vMiWfRpvLa2awxL;@6$cYYuh&m{p{Dl?!@rVYMA3`7KT! z7IOJ4{sDh4gNaKc#;}#(^0B;0`j%3~v@F^5c`z)F37BFNGSut|h#dz<;!ME^g@kTm z>|Q1Vy(P9pdHN#bx<{8z<46JzE@l9cf62raT@vnQOA8RW-_va`45Dj~Fx%BKWQ7AU zPsk`|dH?6g;e0!jhxVb$=U-%wp!dU1z*-6L?_Gnp7ei=x76hEMN~nfcgjl$_N=B|8 zOrGnpuFby^E#=xCvkiOo=OkZ@(aR(=7L+j0zA#-MH&4zG?2INFy z2~=&(9eZ7`S-a^PR+JEqQ2C`8e*W)SdA=D1BvTizdDE{8%{s^(f?FAMHJf|isLou9 zMEsjDI96#GwXN!Y9PMib@rz9xVVB%5QYE)mQHfkbbJ;}ZQ{PGWDqLwR>-U~@y z*#3Ym_Nk%b16rJ&0UqQqJc|4crGdoR4!hb+B+%dn$ZWM*gt~uA=O2)mTVpoPzL!o0 z8X<;|Z8e)=+{gz;=dCIQp5n`=mtv~@K3B_0TEdP6y{=-tqlSUEQe%zwI+|JJ^H=))Fys1Ws%XH(M>f5HK}Z zUFyK;d#0Z+4pv?d^?FAAA(%0f{z1SbyJ*9lMKPQQ1*3(**!SQt)z_`y{k+1U9@L1Da6A za}m0vl2h?=9a24?|IP*N+Jc-0`4YT7#4;_sA6hE?i2%Z$oJGS&tg781>mppML&lme zpeQ|l3p|vX68xdRGeTtD3_H=4H4}+0WKRobL23@aq+$n8%84jmuEuUjU;cK5CAjbA z3nyx0@T_%YSt`Rus6$=MLp<2`<`@0^_Y8o^icoe3+(eeJH5JkeB(}Dy$;0( z^(K+^By?{tKJ^;_Ytg@xoJ+$$sW;c(cN;QE!J{NTZ7s{(`R6bLt^FrtGKaXJwXx^% zHs`T=RJ!}$osIZuDsOEO0To3?lT0}^_nCXvY)FX>Z(uGl&7Zzv>r0hkW-N&{7m^Ox ziGajTSUywkEj@=z6-Bc}J&>&z<-Rv1w(bDtSAkVu=3e0bIVqzQA|mlU?M4n5hK#(q z$y%zjM=6LM`<2~!JPJ5ecVo$S8>v_S3&h&zwFCR4;ICgHL3yW`dt-=s&Q@C-j~9U3 zS)9<#(v{nO#3PUv`-lUu=>2bm{dNW-RvkJ{6&!tVBHYJ;9$5cvR3mLe!hXB+}ALdZI=7xXeF{@5D+OP>t5Y0zu7BNXbKQ{WjdQJM!Cx8<3J5B)0f zZ3M+!5PvSGG6=XC2z=RbQ#QT?4oV;C9DR-?OfcfVd{`$JL3daOQ+@f8;Xpb;V> z@9xdyR4@eJ5we@LztZ(OAl+jd!))}rCv;GaWZ+_qTDygJ#!eY(LE$XiEhPYhTYrS< zlihnaSezt3Z+bqlcV3<7J?a4)2^%#N4(E!lGT-C-&4AAM6hohlM#e8iLDOA`_;qRc zUm$3cjK9)H8ZfSdKI4gtjRv;gVjg{9#pwo7+ot^ee=Pv_pLKG;45zg|EM46se7{?= z1gJ-sh`Ixb61O6vAjoo5-)@qEBu=J7ad~Mz{he^k z_LS@u4QSH*k*s*zSp7vyBu_9Hf4+X|T$^biyhMRtF)+a0j*HX;j6 zC_Bl1}AdXMQ(yEV;@*G4f4Chiu&5AQFPan^lpYWMh=T$ksMN@tmyS7|Lh zBLdGMH}k%4&Nl*QxNylTN`8fgZ*T9^B^5iQ^4?&5X}nl3z01b8McI?kv9+FnsZdF{ z+hu*&rfyhKPa$T&H2$C=9GN;sW@z;^79yQpfdJ{N_TDa5GPup(e?4_DPK^wf(qnR$ zh2V|*=3*-h&O;hgS>Mr#DAD)MKycHxg@sOBT$zcA!>;}g>whc-4}G-iGcpx`n1k2Z zH88y}oW&~CQKx7i?%{r6@`O7-58B21N#jh^rcvuV{=NvbtlfTpJv9Ys+gewkCuQ** zX%_@uEx%3Q-tmfL%twt(q2#6r4i-s~e%x|2yt?>q0lGWjS~Yqt>sZu1GVMCeP5mC!)-(2sX0@~2 z>*hCf>$X6AGSIsJG>^W%1+LUF*EG0}rOkfqAbVl=lYPTHchPe5v7^&$m6O{T$PAYe zyh!rR{?Q|be8U+1z_L-7lo>wQ-c(GauHFW0upqCAe>@+3+`P-GU;57tb=5dG3rVM4 zcz?Y6jp*M0G#8iCcaLp;azdc!l_2V3M%KG^)3v$wShwDDci`wKZG7u$Yrn~LY5BD~ zqW^VrBPC2$#qc<%{OHL2hS0KjIV{UW8y<>Mayg*({u{rmez_R&$f zBj3Kz`LYZH!e_M2F-mhep_0J+(w9?z=34^+9cnRQ!L@8W$=cF-!M)_!4#{h9O8Rby z>Zd&s)`3lt|phgpF2A{{~cyP&em$1D{X(~CfV{k-;UDFr-1kQ9$XVq zCr|>d2jhgV4a_2{o~g5UuQJA$GtFwwt9u;kB>H@uMl7-PlrwVgmrtYVXiL|4x>*v6 zzZOGMEM7kvTlVJSak@q2w-Xuu1}C`4y0qpuJGPmNB7bL?q9jF$*I|wc!smG7FrZa^ z9u4ZvTgc_Qek#)GZ?tR0x|RN@sz+|=F}Xo^+tlOG5L$cpu-R5AcHUPf^6ySHH9zmq z=F?8#t==O6E8h5_%uk4f&|(hszzt^6g>TER=d6!Rc;}-=c|u8Mix;#(yba>*AAWp6 z?Lg_Q%<4V}WoqDe=yGe^NU~z9&N=JZEt+$N`(3az=n`iu9r!x-=1ogU^fBj}@KH-Z z*U{D{&tk=kuPEm=g#pjRtE_*EA@4U1%PeP&9asC0E7l1$S|%++vb8tH8F|m#9x@mQ zC_y$JD~m79_V@8WO`zG$BAsPC{QeT6x>6lObziVRRF9g;$7r+?kE7JQ)(a{wLfc*2kB&p*5@(5|dhS$PCLW}4adCdP?h+P2cF zFu&eD?ADyw=?3`QM`MG)zczoG_Vc)BR5Ilbmn_>3*? zVHwLbm%=Y!_9#|Y_)9kTxYhD|yLt05ilALyT-AB>Z!DpF$}%GB#QhG(9O1K|z{Me^ z{u>37()Of>;bHXi#U^Gw)d=oD>+G>_AHOXo79$n^fen_;@$#{rwATqxMstt6A$Q%W z3JFuET?m%7&{K4?G&a(P`HLocygRR-A{pga?h&dSoh9u5$Mh6PpSON%xRl4O(f~mF z(F9%28UCUWw6AQ@-R$3DezcOyJ=_tj9kqss>cHrE${AR5UhmA?2@J{fLP_H7XjAws-wbpGeoGCCjCqi%n!4mSE_TO`C;K&y0bD`>O_%y=r1k;&F)GIlIe-0`pxRS%G ztOV4fg6QNv6h^R!Np%Y99}p1g{&T>XlWEvo zi2Yu=>jTYRzQCT<$;)D*8f#RiSGv<*^bW=HNyk%enp>*j+a489s=C*3(XXLoRci_R z9`L4q;+|gVExo}}wOa?*A4GtPn?B^rvB0w)Q?bJaVkPa6#tx%ZL=cXg>rl#`X5w9} z=a=JjxFVeO^aOS@i6AbwJlwG>M3(bruPyxMEM4DHgF!PJ?g(l=;Hsx>`+L zyReahz9v?-5kBb_H(&B%8b`2*w)L$At(T0F0J-_PbA85D`oG}9Of@(7pInVM9x9Xm zojgTy{-zTu`WDfJZQH>nAk06NB3m_DB&rH;-Hi7!i+bve>|$4g%-8E;zb)%iG&H*X zqN5e>(OdP&rLHv{lNG0gK4M)-^4Ug2ZczBg#KmHCo#Wl@{2;%zL`-!D5%pgG30*WQUZ&)+ z@w}E$rSYrzmJCaelTxd7KGR~zQ|moJ9XRlF-8YyCp{4L;Bld-q&Tv*i+eWEzZULDE zA9{gSz}CFH?edCh7v6Uu^2i;Y?#mcyQg5m~{F=5u>9*BvQXQYD4ljqvdVu}gq4QD- zbT=&gqN1sJGxLeX|J--;`1ts76)38E`Zvj<---z`^xFQ4^F`ya_boX+6;!xKoS?nMWqqp=zH7rdV$Q^ zi>XwOzRSe&F-YIeaZh&x7VcuxL<|Exw_)P0JvXA*#bVycXGE;HVmxEfoqB=z+OiC; zZqAlA5=DemJw%Fh3On)F91{K|r~U-2D-Z1x1!)1JC7++ausqnWc8$_rrUVd+uE^ek zFq+|??n$|753-*Bho-BHs_OaLhn7Y}x&)MNkPfArOLv!acZ0M@cXtR#cXxM#baywr z=l8Dl|902yb7s$;Jx|Q07w~ebsMQvOkV;Ar5srGEBu3DSK6Y5Tw6<2j(Q!o=&JlUI zc?2xRZhI_(fo>5?C2>G8amH4&GSFl2B5QFJzIxkLo}7yWWJypmZYI6K3qt>Vh+iPBFCGuElpI#Q8Rp% zV9Knzk~%z)^DgMxk3zBD?y0nZn`@V^2`%xdu;T3L1wrh(w?_$k>WioW* zjx%D7%AM`1&++EVyzDYi5h+F%Q^x}ZpQx*EZ>D($Gm(MZuojaG5(b1{;pKzSSi%Qe zAJTz!#|bd)w@!kD^h%SIt;!GJ(gSZZYbe9MfBgz!&}3m`%%KQ1(MVPZxrw{}p9|xvZq*zJj&V75V3l@`Ck3 zEv&y0{i7qNQuALWei(os95ODod*Xc_>uk3w=?DC&D1|qnw@D)g3E8c9m$=R*orWt^ zY38W-crHi{@QA-*t#L{$FY-ctU#q?CeSO}rBgJ=H5Vl@m1hhG6;5$A{#)c_1-u-&1 zrbU9%+loeG?U(o-1!Qr=xZ1B)#<^Jn=ijs~G(LIZrnyY+lT}ZTA}=bpBW1Wft?LSu zv>%mR02mQ=!&ZT1J{^HrFwTQ%)P0S9=stSC1}S3uM!|&1Z@t&Qx@D*Or#tZ)R188~S&eHp6H^1IH!U)zxNiES<2w z*ax56(M(x+7Q`mUnt^I|Sctn?@BrkpTwtc0Sfdt$YOx=;AE557=HdLdEliC#N9ods z|IW6OF~ly0UZY3g8XOnv65YDI7-I$6&>DF|iq68LPMIo&h2vo}er4_`BSXo_9+?HR zXA@!IqFvi-;Wh2p=1{0jP2yebOuf8EV`_8^_B;3|!G`z>fwtWu5nngIU_P<286w7$ z!(U4*s$g!k(m8OL{K>D{XTRJ0Rz010rc$cOdwZH4XO}L*Z)!@Ft#F0icDq{W0k!Vv zLb26fEvq3p{5&jpzs_^%|Isbj#=VF=#DvwTTbo&4b2B}_XI1H~^oSVg+LxmOwwQyT=ukA*JWXAKX2!p3=nK8pj-#S!OGALGmHQl(XYD)nJ+O;{w zze8H;CU&v=-8{TFUO)1M+slW*ny`BgU9HxSlb*f`9-Uj9NR@E~(GcN`Ya_<(@kp$OngS?@#71QQp0?*E&b zySR_?c?r65wa|UUywli%?N%5La@jalS8#Iww!On@7cB{%zV}924OnR~s86z#Ad)W? zafcY*75{6E`{q13uCrFy;zSqz6qO^0u_5S?`JzB5;OSN$P~Zx=uc+T2_(vP zC8cR@P_oee!8Mn;YEAXn#%{v~^o%^ssiF=GRpX=j^!>r0%2WdTZDF;Kl9pybb56eR zOV9fK*1>FSM$8`?yFd8-bxJ;Q)RSp((h`od%+gn>(`Ft>YRc|CdjS=AAlR$WaAA7HiVJjQkIQ zuNRD|$bLr+Wo-m(KLuCm;PLXVztq7Q*qmBH`5F>YE2NvJ9!t(_5pC4y5C&Y0Y(_nX z6K-=he-Ayj9-C`hXtg;O<6Jc-x77a0cJMk8HhL3KzrppbE2bpmJ>!( zVWaC?JrY#GUSPD;W>@#PE<-*uim9A^5$;ljx)I=CjG8JMD?h5 zWo3Z8ib{dEf{M!A#DuSpJ$L%gpFg)V&)w~Nwk}+?zQ#iP0e~%dNW#hkyDV4TtV=!o zCem3tg&VWlm$3`N{$4I(02hNO4i;dRl`pK%=XfsmuwbvF?F*k&g9g-6x;VN@pf6zi z?b1jkt-PXHZf^kP(lEji^?6h z@;X7@a4Nt2V#`(5j7d?xg}4lA0*QC2ziUQ`G*MyzAdM7svi}<1fhLR+j$9z2Z`F?+ zc9_Bf2(4u<#9JpFL{=7kFrQR!h3|#vTVZ
)RW`jf(;((Zie-(n8^Oq*N`xDS#XyfTQEBSi>*xtK<~$T&$vH# zANg2=CvuA= zAf2+AOs&0t7`oq%Ed+?d=m{<_d+r=+H5w3r-h3)grb23=0$^AmFPiuWA!UhfTR z$*6=vL$(nRJGRDA=xsS1MYgyd=sLsEThuu)xK!5dT+<`|t(KB4oAUD(BqP~jpq;nh zvf1!WI{A!J6b8(>pz*VkV<#4>(z{PC;n3f5k3GlQh9SnByT;BlSa(Vx)1}js>IM1zUXQ0UH_$9B6whZSW z+};9>tuQt18XSH}pK`jU4{6>I{u7vStleFBay#Bs!u}nP1t`%cE3SXkAB^eX0IU$g zem@H6>nD7Av(ICMP=T9W-I>$=9dQHn7!u$t2>AkZYytHF&_F`AZ=4Q*vXWvz-n#elcC%~eueg_)-C_080E!L4(I z9`+lC${)2#=aZ$|Tjyvh(mLzarV%^hXw4D{b{TFOQJ=?AkfT@+K#$36d3$}*slXZg ztz>9Q38&YKm|<3y-|-u4sYal?;@fhnNl`ue&|qqc+`2|$YqOwY80v+c>5gr>ay zGUb~40pa$K`O4})Ntg+Q-1&+v^bAMj)h6F(C&hGcP7VDVle|MQa^($8- zTYs+v9*+sqAud=ub3$dyvd9;ILn&9L;e-h|yC?uC!y-*+)?R0%J#c`nFqa+Jp_)27 zJk>8ru=RN|dydJf!Ij?YqEJVjk6*WLk)Rt`e-}tbiFQ0l?0Y8A&gplgNe0Z^$~pJR zT|2;m$g!&IgnkD80O75un^5*ADCvO@NA3qW^%=aZl1O)jsqg?zV!Z!Ka)Jhdz+(|V z0tF&wi{;Fna6`e1W_24xG4h1Rx$o#RkKR-3Dry;INO}lmYC$0p{;w)g@X=T666(U^ z1@hY9$R%FM+I|8}n3~$ZM5(ky=u^FD*7N1sJ_0d~>~Y`LQ0>{$`G349#E_M1E-xWK z!AM~WMt^Afa6XRO446rZUoSgaVF35_EB?+kzq4&jOMX zZk=x)pw=}%6sgKheBzgo^*`t0n1U{WFpXk~FF4U=!26tL&OnnkG{*4^RE!>DMN4ss~7vMP2?lj zhY$60dzF~J_8H?&tzV>-27h5{x4`agSyyrHZizSV0bsbV)e+yr;E= z?sTku%l0({5>FuW;C*PGtj^F1oa?-{OPN~bCU`h@SxE`Y)$Ah4&dv@nv9xq}H%y&* za&nS{1#!SHxElI#)gLjuE=Mp z%FkXib9v|(sPGju6j`qrQ8ho|Ch_cbm1MiUHG05MLguv`Q1j#XJYVhzs#6iZx^5*j zlHcRlij4imgC+F^3?Ce)i>vH||H6lXtUpE?WD91(!AV5+Yo7ZDR z$`5Z~L1k^VdDa$E6!;E^5-_5wsWpBMfAzfcnwNIBmJ*sT{#O#ZHP22WcjpIHBt?m$ z?onhY+?$lin89=^#6tCnzSRR6o4~>ho~{-Cc4)NOC;KaN^Ic*KbaUek*Z*k& zIy2~r3msmKtBEUChniN=XQZo=c|@QvN#@||N>hSf#`61!iHp<-i_KR)oL; zK0K|p)R^a}sS_Rpa|aE!LkrW*sRHx{QEB=(QvIBE3OjKr;bLtrStlp0PIFFTPq1S5 zghgo*Xx|=Z2*$Ug*OnLVlvck6FJB4P5|VmGT9&*Q`8OSK06lWYIm@K))Al6A8vGyS zV(OwUzwsD0oSjR4M2jXULp5GzfryPx1Sj(=;2KR;_iG_NhR;sVYfD#5DIcI-*s~3UFn;OX1tS@(1r4-mV2wrK8rlTHyXI7fPa8eQ zVgj(f?LH2>pA8>B?AksX?4{sR>hQk}Z6f*|?+T(5@wXHdAOV;jDH~>1Za*YsM(LiX zg`Vc%44)(Lrgixt7L8wLw2>)!Z~sN_QW<`t?~{&x{{Gak_PE5~YZ5Bn7eU zANKe_=Je%`k`fB=ybHVV(Q-H*5w}G0Ef9>-8(WbwiJ%fcC$rQJkRz91viSEL+z&r4 zUDbwvRK`$)w@?5`+NTj^3yb;JW#n~IeZ!8@!kba5Xj;#qr9?|^YriR1y~~fHAs0&w zUZ!WFfs5L5hBa(qY=8GCJ*k&E?|$P4v=1+zs#M#RgH5cX==j+aqT%m z?PV!8|%8^F!m@8 zi@6IXhBJC)GL8)V4|@6_f}_P$j}2`+g+>1^+pc=hVH1*DBRp z)TyhfuK$qqy*QS(Vs!)jdbm|~N@3l?a{^^WQGv(ba42~(UIX@bYT(_KjSbNcs+WZ_=gigf<#U#p`Tm~Y)z z!`1nxvkFK!TAWW+7oYD!rt;fg{!VB0ZwP);sT^MU1A~*|VQ4QWk-8&#PM^RO%sh8DbE! zYW-A;o9uI7B>8GBIhqy?L@8{L;p<-535f}v zUE|?sDJr8qX>JU(O~vGdVXlph^&!*rll=aw4h>(z0VPDkn32o&o%nv8^Av3Ep;lw| zez@v0)go0l)D>$2<-_%C72lJu$ZGu zFrF2tt*M!rn>*C@Wk{s`jSF;SklgmI*yZoIF|;y^Lg~3M>%^%g^v00tB(nCCyI^8c z!=J4?b0z8u?5t3>g?o*eCX8vlHWnw!QaLoI>C_`jJ>*83;Nj~cAn&*TEn_yW|4Ube zV;Hmz027z2jv@-{@D;2M8#f)bu^cbYB}XPG{RuN4h3uanPHX-Z@vgmGPbJ5`JOCZx z9aYCptU*3rr$tb*B5rL@+2b-$zPOa@d~eUS>RFB+vM!P!LyQJs`WIO{ft@iJ*^Skp z0IWx?gRxLLT!A0ZfCO}cv7ZUh(K*3i{{g^kab1nrkYh|&kJ+lZdLB-YwrftK8+O;G z1F&{XF2w^n{WkbWTJ4smrA*O2J%%mXh=wS7?c^x{N!)Y-JMkQ2_-KGfDm3`P!33(T zh=0SGXBj-@O8@B55P)mZpK;ZG#-m_Y!UgTU-42PQuXH2;Mb;eg>3<-AiI)MD?asluEe=sJ+DUAynb*4uIld7;}uO7lRYEb zwsXM&gWmp(NcH+Zb$|i8>VTRG`GOtyGyr3xr*TViJepeOcNP?ge2|!-4$C+SOU~}b zofMzH=WA_y_^qw_x{+IU(+ZGE3NoW57=OTo17s0e^{PnZ$hiKxWdK+ilKs9giqyVZ z^)SYaudqQZ4eFvVlU2MN01EB7#-9{{{~wgxFb66ck)r1Ij>3O<(Vl5I)9DhUuD3@x zZO^OWnGHYshSyqMuNbjkjV|&COn(VSj8@SNGXX%&vnbov{Y`T)Lbn>#`CmqFQ#7*W zca-T5FQF3X)1p}Xt&S!?bb?+~!ae`IjKToDTns>#S&*@Mbc}JFz&I*Er2pE4*X>j1 zx|s~o`S_XtM#9$9>6WUSmZYVPX8vS75X<74B=Of^0(LGibhW|;$M?RRjpHOg^b&Kp z%ApUfvO&PPpKI}BCE$0@03tRp0KTrtmK?`;i*?_5^yfyypnKA3vbQ*eVwNq5tG_6~ zIi~T4MRsT~6LB;i-DPqBmdy6bZ5u3X9x}f!)QG-bf>dRyOn48CUfERf#U=~O2vlH2mzSt*!Gh1 zSx+qd9DG`us?}NM=ijbQ7V%aTqXcuP0NW}sB0wt+^Nio$LO6q7pnIGq- zLSn#|=#4vu3i0{{XdT|1fq*WO;_CZ#EH1I7s46IWOfsqt55e|^%~YI?C1V$1PCsLH z%g+b)6Apb~(Yp%+iAC~Gm(!UVJnk!AE{?TNebCn<$4`H~fNDN%+)j5uA1GG5| zIr({)O3J>Wy-jOul<=}HjUkDOAcqe+RRbNNdI(I8BKODceCuyP!BjgvCf+e=vU?47 zTP*hmR9H*ZrsElW9za%Gn>YBNP&Pe>>hM1$6Zvo6%Wbkny1WoG;_g0QIPgY=i zZ*R^0sO-Pq(Mz=!E@%H*9S^386$=?aDtzoW9coa)X+?5gbl3eEqc%vebLv3nf2*1P z*8Fk$vuvKHvg$)SpUpMbYr&l^kNUJa7JZr?%J7F$z8Y#^pZVEw<1a>Otcbr^>u`h&$0!DPbO^ zl&F{v+S)r6<(KVuxx*LTd+mHra=NKMQVTWZwRbXE*hm0q=GW8GSp1=cy+-gWcpIk~ z2$f-hCwz~)uLaf!A$jIVD{dDcf>{r8-YE}$%gYws$1SeX%$EbR%CCiqVxwM4 z)Rm2n-!Vu$OUGD}LSjTY<0k{Cek<9I%ne17&wRK=A< zdFl2%yF_}56jH8xbKMAJ`4AKbO?6(ygYOP+1O4)F8s3kcyAo-eLm`18qrPA8y+S*u z=QSQ%q4)bnLGxo?pFSQE5cJW#>NJ_$7{Bh%?=P@N)O?2I{k;o|gDI255g_RRV1x~d zbr%Grk(JCA=hiabPS0->^D@f<`R!5}p&<^{Y=B;Iz#)ymrK3Qr`(}9knA_`e^@&(V zRB3fX6^gpav;5D+7jedMIDly59^`ss5T)7<_K-otP@=Os8+z{*dum9&)8M@fTbcyV z7|hMc7?I|4BVPAzFQQuUzGu1!$VmJD}+q67+x4($|cQiqS!tKZim0Ie$@dcO8UbU9REgsBSx$VDq>_L_V3L#-SILpfEDra!s1|(MoX1XY6%J zNLj33v|DVzwkRiyoq~-C`AyqBZ@G!G-rX*K6fsc@yCRj0S%e$Nx%3ZFArP7d*0X*n zaDoC#3<1@jntdgBtOPTL;Y(sRO3)ogJOn3clGjCC$}|B5${SHVML{0``E7?Ec{M`< zdQuRI&+c7><Lz@f%_{y6AyTS z=Tl=td3Iq=%M18Mh6Le4U;Msjo3+67&4UQ69}j38$S+YO=T7$hR+LyZ~WBx zm;>gAVT3vXkF6DQ4kgH9WVFb^>iaOLjwmhFd;xR-?JI(;lNg|96ulB}=@=@<{uw0_ zMGD53${+8gp{PpfWgCoS-N%Kd*;@Jm3~vvepULN-V~?xE&t~no>1wF5p>swq2)h9) zt5LNahRs4LJDXLxn>E%vPEj19)DYc(LjPyADL;VF?b*lKXl!TI>uyz!_o7EpjxXN& z;{*|pvzA-_h^hX;7>GEh(yIJv*vs(9ncP3AU;8&b&1yQ9cDLpuz@d7Y_ykIrCO2$7 zABJ@!MRQfPoo2&6(&7ejwY#blf>nT*hkrxKY$-Mq^|%Wt!5W;n*5xk|Q-QWCiOnWr z`&kA`PomIY9%m2q0KJXvsc4aZpaAbwr3CN(YL#k?7|cvd_l%cZgEra%t8d4B?&8W2 z1QJo@U#t3KT9s~WnGI@RaQ9#!XjtQ!L~6P*N8i_{!ak9Fv8CD3T;sO6?i#uT!xu%S zwJA56LUJN$a*f0)-u63&uv%T-CCG*5H_zq83OUJSW3_GdY6tl>VhMtE;&Ni-SJQ6}_94e%%qc)1+f4 ze??^tDpm{&qsdNU_ouR|IMb+lEY1PO$YqQw6=fR0s)>&I6j)=e468vU5upX_n`<{e) zhl{K~iZ}5_l-*E@oxrIxk40yF-uj>Sjj_XSB&{+@MaS?aRGM0bW}4xRrv2$UPQe&~ zs(+?5UJ3$$pb2dzs>9#5ja(gcq)P&rr#_k?!M@K}w1oz=(87#yTRS5NoVv%$pYz(D zz&JaYFKRF734tD!PM|y!iVr4&?AN+due9cF%Un7G?GtLV1pZzosAQ=o5CtfaBcTd@5Z`d5H(1Cf++^nj_-i8ZJIHT;v)fob z$2Sqz8ZD2=qx|2M2yklobSJ{nr9qkSM)7u(%0v~*OMc#c z8M#>@=N+c}4-80g;ajQESKOgP@iZ|=fMSVmKZy=IsM;n8x!NS>kY!K10tKtqyi=vT zI9}N=F&OflHv+^$PynOZw97ej7~-vp9aPx1g#it#j+XWgiMr#xna4dSX3*i+4{72i z4{HI3O1IIhCv%E=!Fw-$3%ro5#(=+T{A3p~q>^*+1#w8Qhu`qWW^SfmDm@yl{o{uBdau1ElGiNJ{2MO;<( z&o+Y0e+v7?|6v$qeha^K7Y$ENo8FcNLH?Q`U7DCOAaDAdZ2VA&2w9q(p8oV}@@bS896)?olE?&@&x zA4&@aow8I^ANmuCORdm6_o~85zr_DA%5CpJ1*|%8DMO+ICsuH}n|G+=MKG4E`2HDN z;aFt#4#~-u)+lp!n(E;^@7*X4UGcf2g#P9)XWP@0V#3<9N#o+}-%)$4Kgn+_r?hU; zn=9%{N9Ciaaka1scNYWzi&BR6w#zpw&S(Y!-`BiG!|-Y2sUiFHjX*PTZhbzZ6?mdf zSRih@;mgw%xB;V$_%;aYPS>gE9yjfK8UnpNR8dFQCMUYXF_+9-+MDXz`}qAJv!GO= z`Q)ee{s$2Si^WugB`kbh8_OI&8wbh}0uJGTlaHnjSO8c8^WLkZ>+J5IK#MerXKjmc z;x2`U@qGHPw8@CohOp}K@^~lU+XjJ6i~dXR!_}UY zXm$yf2)%Bb=fmX=d{F)J%XX|B|HF3d9**UC-?hO(Mum1;GqbqlKhW9%1CS}rz{(=X zK;lx3$q+wftlXc-TL8eW9G$lNMbT4vnXr9u;3c-C_|7SN&Ks!Z?&D5k`Y8TWzYj5G z@cr*NPm3Tk|Ub;5x#m<{qsC73>YWs#v7y^` zqi-+d`L$07Hz}VMXGkLPhhRe=z4nFkLNR&(ymS~;8LU*{!^bhNc0gx z=2lwz45zavGj2^3bM$zY%D@z;ITwwzt$Q<5wyR zDF3Qlr6ifAJ>@%?f_AO1<=f#nUwVh~q|0bIVz>?~dfeVy+%U2I+;`~<`Cb^1!BgjY zy08h>#Mr_~wS+L**jY}zHkD+eY%YHp`;SfW4mX-irem_vC9kyJE&O4x zf;Y@1RD0cp>Q1oFtCru=SMFwu#xy?(hwg~3BL$?X#%I;A<4{*kgEmMS^-KB(&9d!vP}({T!@{QlAV$TxZV{OTQ#mqFC*2K@5j&r_Jf)<4$6B z4$1TLArhK$jy7dy-|MY4nIcam>}3WGIsbG_&k%UIEg#6IF%H^!JKc&e4J0^HNd+N$ zoe@0En$cWJFRl%mxQ1pIf7FzP?&!JXl^F^4e&TcAQhJe^Wk(Q~v$6?9@b$o!^Ypd| zFv$T2`u?UQpfx&>LSnQPA{(a`^w_rop;Dvs$Dv>G-p2hN@+*%{5C=xsz24sWkWKFr zOe^TmPlD2+&a>kWb01a-emjEOVKE5_-7F;@+1p=;m+#3(Z}V|}d)k9CbW&lF-NV#V zn?rK?ecKXVf-x%DcY79{c?z@5TT0)zXZOiQz2fKu3%%uHDncWv{sdDYA20BxR= z@BR!URPpU_&ET)N=L{Dh25gr0RNMiYDp!oL}{s&E^^_S?8 zEM%ZXcRmG!0&w+GB?lUaW~{FIe>hjc&1Y}OVaU3wAtVL+lApR?mf}pX<%bd}ea@(@ zwO_5l7OIAj50>HVzgkePF*&$OM$|v3CDtNibo%OW-j5O$wZ6CBxt(q)GJ?XCls6uy zhyqB*yZ^&WDjC+hCsv*2hxl5k2GxBbXu#zP9rfPLKp7tfjIVqedJiXvqVrIN4LMbc z!wF;hkM9Vox%T#aQk7wtZ4ak_f+G#7I(iYKy`yVy^P!*cE7aJzUnO9`4eE^@fNVN& z;cB*UrYb+PX6>Wht^o0Mzg1-f>n-y3w!lq`Ty|i0NR!wWZ;-Hc?bSUPl6dctiozNk z&qrzDyjGCou6dP+IYE_|TdCj9LEU)WNIt*7Sb?~ft$>p1g8=u^!)BdgIPI`?vZ~*J z;?yEz++}W3JyS8S&FdMzv_GvNeBH`!Ei7u;^@k2jc!uSJX4je>Bp87|{y^2Git+VDQHX8*Aq`%b9rl>oC zzSz@w3o-n-=(U0p!JKl}=6_m%UfK+L6)$6<-inP^w(h}+Bxua7KwggU3w~Vm9mfe1 z3Z7)m0@H?n|K>fxSlA8>+om9;Dyf0rPThCf#1=g<4co^8zB*M*9W|OVP4x8Wguac9JjIRh?xO*VxPF2M!hOC z>F|9f_YFo3HPzy=y>$}=)xnp->oXtE#rHs^JY6#XhM-AvM&CY{cDKAX#&G zlOj?XsdPU*%K9UPWqB$^GnwnltbV6kv5CG-Ak4mtgaL32@^LDUR}fFW*LXaWqo*@I znK?={nCyXl!Xq`p_z#`oWqg|AKXDn!;(J=ZxNd#VI`MmrC?Eb3XO@%rhbYQLhwHXK z{0lxcr^XAU_6y-5XB8w_2E+OUdRuX}9?0)VnJ%J;^5Qa~FTl`DA(BAOHtO$bFms#~ z6XS{Q7sDY{nVLR&-_6GU5{qkMXkm$m5Z#vh_`5QOfEd;hN|tW8HY(YqX&k@%sKFiy zh^!Ard0z}WF@>}2-ZD%l7K^gwVSOcm;sf`Fis>>M8nh(S{%%zw*?gxz^?eR)@<;{BuAd+ zG6yT{in6&20L|o5UnhvNaP63x*w%g_G8ox;i&R`}qstKJ*be3%Q6cHHIE|$-_oB$$ zh;Yi641=@wDQ9K;&E;+Taz&Ru*&qFHbv8n#?iho?BW=w(K z7|w<)d;UQNoWEW}`!0V2fr~$nb0*Bn;I?(w;}25slpvI#NT{4okEMYna!a<@7k7j7 zIPoO4Kke}uu)i;+wk#q+Dsgwk2-dpbv63@N10I{`1UKG# zLvt&w`YXJmLCb&Ul#V@6Gu+8dwRT*5O=2LTB^%|sNnt?Etz2ywLi{?oq(Zi;?fG5s zQxF5+pY9)(p5p7`F@KIAQ%&ml9~y-0{_WZ8>Fap9jy8MB&zFQ+S|j&}LsP7UGYHDY zHhqfYyH^Y+rF%NHt7x^cf})Txq+DN(b+-L_6N25jWTe$76PVr^N_))> z)zvC_HUeUV(G_)kN%se{A54GIuxU98DZs;|uz{Hy=~u*gczwY)p)I(I6EmfkxrXL} z*Mi5FSb2@lG9)_fFGk}Wdyyc$Vd0JZR!pqJmZu)Xk}6>VgPy+VjAlO+U)30wbjC?B zZ>&#OY(@-O&z@VKyd?#mPo<{SgR10q)L=sv+?1YH%p^BrMGn$0GY&GSQwmn-h_-}{ z)@*ZksTl;rUvd#nll8q`SeHM+4OF^HF0xMtsf)HIjUnEKLY6OXMKN9LP@ei1bo)o@ zdLD&NO0J}1C?eKc>~?J}<)iW5$I_WnDP)Urz6W-H5yZ>|NpSteFpK-}w}y@?S}r9g z5&v*yX*#V6n&JV8`g6R9eT)d+IKo|Y+K zl#TG>`pW#&OsOI-%{|q}NC%~VAx|_l&Gb`pkA9z zo!qP*hNU)6d>1w;#FJ?RIjq=NzN~HgGM<&Trn=qm`(vMMckxhN;T1+DFHidAq#`8y^ zw_&L}!%MCOWgy26IytaGO;~=|Td)b)%=IP)Zsm`>XrJ|EFGwczl*AROVM}hId*);? zPX{eB7F_e_jc~0kzWb6zm79%5>~J&7Xeh z(w4N)kvxK)F@`eN^1T-~XB3o(`I|dC;rW|;P?Vo3`r1!j?PzWSnxG_^h%FU&ImHt4 z_E_mQj~OTa*x|_Zn}*5oqqMKCPr^q)_(O}k9xLh4)MknTu~4dOpZnM(pHJsN*JwYt zVhYXIvhOv@ZV;?cOYM`>cw~d=TdU6;!-4UC;IYu$ioe&a(w$_1#vfb1338CCi5#B9 z*#UK9Y^q%YWm8%>3n7w|7^Dj~OrJvRbb3tuxERDT`f*bpuO{JeMci#;1UT|TQ&`YK zx9_4>XfL>Ugb+uiB?sUBwzt`@^|+d^h6O`sQ^N;=#u5`9?&*~_%kz<-E`-JkTuOWY zA`_?_a%a#O3j6R=r!bw9;!EQb-FH&0kho9Zs05q3?S5I3+{?=MM-k$rpqOZDH+8R! z1rb|$z3YONcZV8M_q`t(sH#G7+8Wu&Y}a$uh`4yLbJp?&ICqYLrDNt zhu7H5yJ@lj2G2~uqT{jdkpU=5-lYs^WAEkLUSLibTfd3^p%CUZ>`p0%qh)xQVozZO zGqZy~t^$9xWyb=M6*csN`TI5tXT>^%H?{nRw6s4jZKorcQKMEUKMJ^uNQ{w}qJ=8> zV3Q8ZqlvR1(!=n!4-jF^ z$hDm96^Q7cGKH#xGh~((wALosOs|BQ+R@|m`~BgD7Yj#ku8yQz9w5ayu2WCkiSr+b zB&^N|lj=(}GG4)Rh+75MjR8*gbShe1*tNfLc?>T0((4v1@PQr z_6M2;hYtv-59~7MVj3yE_(B?QA4R?ijw$W$Ij{?zp&f+Vn*0=H%eT7;ZJ!Iqr@Jy{ z7s9@|%!mkpn3UAg7hp#3t134B5Gq@p!Z`}1IOHJ*n3@(6wc(hX7Mc&#Z~(_(On<5k zHh1+}9q2PhPKge|sVs(I4Q@;C^0TnC3B&}ZGIl*&OxO|2NZ*Gio%oR2r--tseVe=W{6aO&l1MY z$}7nTBn|q|b#VF)03C^H_e{1?{7lF$=|7uR9Gb?vNTRe?GLmio+H`1KP+Ee?;u;6q zc&r7AQ+xrP+0-slaXQD6bday;Y=%xS=oqd@ZM|jF5f zwby+Bsj5CdIO)T#vN?Yr6W-29gH>Y#p_*nb%Hzwx+~;_Bfcx*SBymjO9L1u<9#5X^22rwyPQfx^Ex7nkH5 zGsIqxBHRNJL{))k&HVEmwzJCGAig|yOrcymakdPWu=jB9nx;XZ_fvWZTXI1`F=*I5 zI5pE?iDiRQQozai+q9ciDx71*E$hq&r0E zlm_XL?vfOgrMpW?I;3MkK|rLtTaa#0x&(c`_y2c2yxLb>T5(Ev+;{(UZj*)&nxM`S zy1@EW%L43`QD`EJtvXi?G3Al^bHz0lk+WzTp-z$GrubC)m&2#0;itqPP^__~8%NIZ zXu~z#5li`T*ygikl)Twq*9o`NN-6;{ zdCJGiRhtutmsrXnY8|yl5iV+v70eLbRhAtjp(?!S$#1whq!;o2{O~7yDl}W}Vvz@f zsHvWdOa$Rgd+b3X@{mPt4SMdXi-VIbO;Y@>`h`*n(j_^CNDmoj)*xBMaumv0xP%|G zCG&;K@FLkl1w1g48gp_VsIKU<)_r1;gx1Hx3_>2Lv}W)bqhZQVY!MGK=hN?%ee70&j2|xIhx`#WV>KGeAqe`n4A~Q8pqS zxvBg;kk2gaxDB*}XK^Bv_*C+3ftcTp=Gpw=(wl+wvUF)z`hoEeANZ|8(u$Hj5Gqe& zTjHd7q#{=k^#VjMCd0xkevv1o-ZBBto`ic5*imq`EmpcGRDW@*_%ls`_B~0Z41%FT zui0VO{a!70n^`9@P&+_OB63;WT=?M5^l=w^^Kg1a@VX?@06yCdqnVG3;MO!j8o<50 zl!Z-^!0nQV#!xu7`H!V92L`M$uVRV}vNz=p0H6c3W1^o;+g`$BicE0D`=hNnl<8j= zil({SF(VTp#b$5YwKrs?$CZ^SJ;WS(YEPK}x4c~E#}@!eM{!NEM2kVM=REV9VWv_` zv$8qo9k+83Nx^(LCa8$5u;JD5o8*3ernzDg&9CfPd6=URDnlmy=VVH@E-K!4KZAwq zy}-5})+|)$1bPTTM$VI+HEBev#LbjNc}G5%3fBK}DO4l(`G~d}ub*YATt&B6RvO#-|DH?5m;!n&?_b!Tk8eRKKEqw#G`&nCEDFn3UodES zp(T4EInOQCG0LO{x^tcu#KH))%|)fGG+C|xGpEUF!uAE`fZ?QOUjWwLrltSd3NYDP z0~`^?Cl2f!M5#TaIfUd^m94>*&oMPA!0IY`uuBuleYs>ra3xnKrr_u#QAlXz>$^}D zzL_B{KT!R*Pdxq6;buO84(j~q{DY9uxW=iQKV#lG6n^ODnMYB>#M6M@ihv=JUC^LL z*R*o#TQmVdRygpAdCrb1vSI?&XKHE0``B5}t$3suKF%H#^k4?(I!fF%GSL(4rM%_7 zH^CiK$>VYYx9S5z4>EX9M(kInvzAQB_e2b6{Rxh8PPkDQ(dt=c$^zLk1u;hpukuUY z&~GXyRO>Fs0u#c=g^#-v6J+=4u?j}M-{1qVCe0gx9{0?@b z^kG^siezoC3=`ysq)2?w$!;_q8Xujqf+*)g=&&aVoth3!Ml=(&xj|=`Q!3|ph+K5m zM@CYcqQmy<&9?;_Cq%CnW0>|OX5!>+gGXNc01fbk_&nxNJP2bdtZ>^1PSOnJY_m^wPdI)bKV%2{I2!&>ikFGz zw7`ab(n}`<1>7k$g6IP{pJl-evd2GqrLH(J$=`<;HMhP^l_?-kyun31KEiRj2&Wl+ zfJOG-t@9X>n-)6v$L}LwX$`&cSQQJUQ)f|;HoBx1br0OtyHsZ(6_=0_>Ah+_(pa@x zvf1B|ZCL!JxLj$0G8z3vtB&z;*2#L={$ z3Tz~$59*5b>(aBOnIW-r1+0*ZiGr^uX@wgHC8Sd0(?@n$?ZA$RU=|zjGGCxle5lx( zzpzrd2`K{41+!O)ts=%mkR*aE9K5vh;*O?8q#IUbqN70sa2&JSK#zAcpxcs8iCnx~ z>^$Nn)oV;FJa-XeSgEH8C)*?ZbTD%#rxo-k0DL`6FTI!Xm2Kf9Dv|)G=+Z@XznxR2 z@7mfnvz?t+lGxZdWkLX6fQ#sKaE9pu9p%Uex9lU&_3owQtP;$wAwEIDHt!vRo$pXK z9HNOt0hLFahcUGrVV9rnO9#hmcEt+uj*gDvFUs>v=}93w@! zVM?}O@n%D$3LSdpPQAUA0%NOH44q2di6{OPUGgutN4Z_L(G1 zGUl)VMu0ZpX7e2uWk0I$NkM{#OdZZFHeRdQ&C+|*_$Wq84xJs$QRId$C(4=Pq9b(< zE6X#v4*=bDgRCb+1Q zsNP0MxXkY}5X{(>{^`3*u6>NFry;M3>sxP?#abk0e_qbctxnz)~ zsqO?8Wrz%=``Mwc$V5*!2WRO3#eW}Kx^6Z;LgZGV+RT%_-Ymtl(uplDp-AbpK(rm_ zZ<#;-GI4M;I50)JX0V?&0-KMXWZZh}rjd1L@zmt@?Bpc*FICXb%7$_>s`K{xLVFNl1VMb%c)Qq-Zu%&!ccKp4^E1#8cr$c zG#WE+r3?D;)qg(>G~P$O{|=CN1>?v)o3KHVIl~or6~|m#JGj4y$ZVz@5W!_lY4hl! zwaJ+_nih_KNJYs&Nlfd|p@V|Uli@+ZrN5j~;+RHB_8bd4bWOzM;zNc}<{skvGWkud zJoD7b>)8pM8K%gk%JJ?=UA6Ro1D9rIX>E*{E4g-@?-{KA@4=`&#CPKDxALNgJWd+) z<5Dyx+I2Zq3bLjIfHyJw9)Fs{b%}zN=9(uO24OVLsp@2xGev@jjPl%-*u2rCsMerU zBw@IenkiBiu>x{ONrvSXh7LjQq^8?#-F@j~#~^7;pH|NYN3JRe%fi1;+@H2mr9JJ)n&hQdbkw0y>3d%V#-A~I zxR}olpQ!l^Z$t6_z5e2eT0v;K$S1YHJX>}GwOLfs2!rh#Ll|u;{`h-mtp=ArPoaw~ z%p*)rRKf~$?XL%L7)G?g0ukgytSVfpA?^vQ5~f+N!7hDh670h|a~l1A(FKkS@0ZL9 z51f`J&_ptqT_I0Wj(XJ}SZlyg0p8I*RU@dgljw&OFzp|NsNUZb7}J;b5xqMeKkCe$Dt#A6{FAggk1Nee=^`$k?^V_igh}lK zz~A+rc>uYe%mSz@;0$2iYffcTiz+hw{8?cVx(P7O#*i6~5aM~b38 zS+Q3t;##x*Q6jbAJt6W5l_}VzgE}lNmpwO2Gr?WXXC@uLzW+5ZwbB+_5+e^@|Ni+9 z7y$A5fQPx}u716YB#7!Ed_}puoHF~(0I2ffwR9aa1(h$*(rT5=GJ9mMD(pk6xDU>HD>R zg(rLpsLeus8n8-;CrHZEus!VBgESYQmL|o(Una_86CE)}3K<)zMNIb5y;-DIUr)(8 zVBsh4(AV#|Ga=i*ae2~ToNMvV_@3A<%i5W4!B6$@wh17-~ z{FBOtxcBxLYUxZ)c!;baJTkpG&gabX1}P=u7u;PD;D21>+zVX$O!CS?BYu~vya}`ptt=Z8qB#CM!S*F9V z`_wRf?-=0d%owAuHjG;vvXGT0Q@|cT$NFw{u*T+FLd7SbHYr*edVt3%OfP{8o14xC z^PM!V;e!eR@-0|tlPg7bG-pLoZ)!?(ld|{RNwR%^f;9f`@fth&&DN_(=1Y_RtjAqIstB9OIt4uz&ykW;1m>+7gYm?q5M4@qasfhcu8fMW!Nes_@?^^Z9gJv$NJfW5B z{x#F_-|R!tPC23^oQsd)#4iBu^*YKL6lpS>2FwzOtVz5Kfni)MgY1o>s{Qn_Tn&P^ zgHx(BAwh3Hu@ZkXH)+dr|3^BXV7Lw1P%L#^OA>p91H;f^inE+d%e(LFjyS#b%Z1Ab z-mi0p5u|ScHhjEfvSBfntOw0S|M&+4ufPWHDMLrLr4hcXCP!C(AE2k@iqqTGzGN(J zZ^*UyBM7uZVKgi}0bmSl@njw66C#Lr6GzgkC&k&K39oXp8Z7Mo(NQmu0&M~AXEvzH z7f=T$W7KpPeXgoL6Q@YkS%?8#kZ7+###=cdRY=+Fa{o|kFW;(#w+++)5x#~Aer+7w z(;fM-ub-PxkmNwq73H+c?Ej{ct2bc`?CE!s^4`>UG0K+^>N&*x8gbsXFih?BGe<^83uTIA$ZTG&DZlEmKQpG&iY8*7V8U*YRtUn z^d_GFIaX%P^BUp$93^zZY9;w1_oZF3%}xP^g zCxZKG`?3m!T$Pm}pw-4UtPv-5&lENkNX)XTorj3daaO2*52Lt(mEY*P?e#`Eq8J#> z&D&58kXH4V2i@K-S;?BWZ+dh8iYX*}>Ma1`|DnkB|G5D8Z1d9Cv3N4KO0#@gdKVa9 zN~nE%;^GKa=zCxseRHM`W5rk)9CiTXLbEucPP_)$s+&zj@Xhdqu^pbw?z4J>kVS_=q6AMDMe++ae4uDT#H5{?}0K2Wt$?;`s!X1Y%hm z%yEi%6l}j*X45*(mngQJsfi2Ay%R!2$h#);nWW}X&q3K~)tx|gOtjO=lS?YF?6@v5 zemgZwq1$hO$u;C9O;0O>NV$A-P)sY^&%)ni1a%>84uvGkZR1I}zfbU*mH*CM4$vHo zI5TKo^a50xD5krosHtU!nvO$Iy<>qDUWm&w8fy{^MKq@f$1}FhhfJ#A1*1i^>TFhMOm_D_-LRCZ@@npr#TTJ$Qem+;yK`XzE1*o- z!6Dt;Z=WQzkgyuS#H^yo)D8YAAsijE;yU?zl*}#)#Kjt4QwLoE&MU9P-G|(!SQsYz zvZb{a@_LZ9e=r0(ml_jrbV(T|PbO%re(vp3^Zb0AojOf7crQHud$G-T4P_vd;AK^D z-KUtReyneg0x3qGN63rELsxGOKEHTt(K18mRs|a@21!&uxn7P}5GK-)aPf4!uM6Vu z3(R0r)msg`DZ4VQd*$=&q^M$aeSD|Q{~5X`_3MwdGhHuQ0rDu|(6I^}1|~kgudp!; zx{VCFEqwB>!hkd8fA0bMefxMCWTvb^mHqF0;-+nVuF);9P|al?;$_j0N)M3~)%nH2 z=|&hV4jJGzLV6b){$8+qjH=6%U;lt;`8I$X&jd?+<~}gr$~|sa9QrG`lT#I@R(trW zRb2}SMuEUx48pYG3{9o|hlS?2e7Vsq(8IEH{q&vcW>C)2)$=HLihkCn$VvOrmwYss zfv*Jh;y2dbg94z@!zK!=dyUC<3MJ+C0X@lxqSM z2Z3#=IHO&~qys14MbZlk0~SbTW>1&q^uGRs}ZvEc4i;L>5dmDIcIM zKAwwnO&E)-F@x2P-(0`oxl|QI$BtU{ea{?HPj?bD{!vzkuE+*Z5~$3SbVsm`-xD0s zYN)IIyXoQC5TVMgaqZmr2vra`pd+g4VKC#E^x1K+t-y6vVSZ8e*#3LJaYW#14%gx7 zzpPk0%Q%AId55g4lJD(2S#0gJlQyF*M^(*lT~IScXdgcY-Dfv!JZywll5%Ti6CK%B zDO%)I7Ug`|bZ!aoFm4orv`kZff6J+iD1W{OT`Vepp&=F{_Dv3S!l z5GXQP8&^H;?(=}r2NG~ZbT_nyJ-acOf<&VAcI%7WSMzKPq<#&%khDdyrJdn7z+ygf zm&4*FCM7FBYWp51x66kPa*|I%hn~yk8c({lsI)lXn6HD-VERkwYa@VPQAbihy{vaK z@?G^^1P{DE1bfTOhaPhEC5X54-LL%=2YkH@@yE*A(bpR{y+Z+A6r?~VXfX#B@-e+AG>%`3&0 zE&P~QJ8qPon&E(2oL8-kN?4!MnIGFL1xkF%s*J`9-sEbvzrbk`vX*ne|Akcr+o$_; zy|v{4u`u0n@YQ<=L0i?CQc@4VqE;tV1>j$sL6#4v{K39CNa}Qx;70yJ1*r;jiOK4Au37zm@q69 z(HL9^y67mE4DEyT8U>r?;HpEH`G;mdab@o*^c7RYzRImeHfOx=+Md1q_jOA?P*T#| zMLPo5;lY~VX=86NM6g*>fg zS{%&P-1$2#FLMwjQ6~1%;If@RM26jz=dH!6lQ`2;9Mdz+4CvIzZ(3RL5Wxg4^uqcU zd2-GXh9=W!DKX^wffEKpAT&tw%;M$er(w&n1!B*nTl zT@rudV}!(hw%75hi{HLp3t2i|OB>{}isERC4r;&*9ardGG_$lC6IbkA5tc4aWrKdp zdgWka*liaxCdL8zwXUq^@as0~p&IguI9h+Z!u6z73Gp~b(Dm)jOCC_yZKceQ3mc;n zt~X?1wY@Da>slhVP|ot7Wi?Jff0Igsi%a8v9LBi=eF&`cvzy1dMx*@&xsKeIkAhhZktxfn#v zCFLwH75iJd-AE%)isoQia4Aw+m>zm@D8s-e<;zQp3;sl<@yS*DXNm=zl-a1;_n;?< znQZ1U+;UwBq_W@$<-ZqL7;i2gey9kCKVo9pUuI2PHus!Om$*;L@B8@FXi41CW9*#w%_4H52BdO;1*@U(J*LrkYll717^l?o=+ z0v5vJnakD+mJ@h0u3WxCUxgNCFEY{Q`3EZYPDymMFkZFQVA&ImDi8O9Q8wJn1#B5! zYWu-YEYcp#G5VR?n;xR%_t6DWz2Vke1`=$2X< zJH%u}$p=LUy^bNCfk5?=>k~`8XKYd+zrCaRcgI2`K?VJaSV4hP2ijkwQQz)XamaXt z{GsT~-;N07<87SRrNBx zvr`{gAN8UR4h>KsOe2UB%KQDHzu;AOHL> zN@~gC-lR0a(|kkX>v3+jNtKz0dj4rRsrf`vWscvMi1x9(3#*mmtAZLB*>l6LxF?jV ztiB&I-`f9+lXzpWzn-)JiJL|=c@AF;WUOv6t3WH?#EFv2f;VRd)Dprnekz8DhrbC+ zsuam$?I#N(9?4};e7;0(o1?X7DXfWv`}CsT7FJr>)1yGCpVz-`r{+Iwbzu@8-$fgBTT-D{t!PhlmH6l`N3ajh$$HWk2@q#MMtceTy|?Y+Kp zxU^`FU{CTW$=xku1YT-BJX*@3(pGK~f-2{v43jYvly{DFoU|Sy#Y)Pd-07f3GvO94 z8zuTZP+!2l)8wYQWi5B#aAt+DP<;Qjz#Cc2#B0q8$0L43t6= zE2;3M-|Kqyi`901F9WxID1+|RepQkhuOdp82xjmh>sP+9YBF<4#j5XUydb~jT8*IH zQ{q(@L4oH#y#pt4#Jzex)9K7eR~@p@Gs$puSqSTDKH-@ZcV==~Wg()IJoms4p593B z3BDy>($kz$i-8;;hx-GGF}VcJe-AwZ-a^FJBRjOOacOl9So!IFhVROPEw?q1 zF2(F-`6(EVr)$^4LLR{_8iuA2q-+zh%wX~z2dJ9TkdI5Mr<*H`=N=RGLFZG{MnNkWgOlpj`p^13tSowRxGX^Ix#b0>1im;I-OB_kT&U&#$ z2`$1$U??-SpTr`3<|)M}!CR|2WQ&1-dj{((vCaMS+I}fR)+}-i)x@Wk==ow#-}ALy zn6+;EyS~nd^?{JE@~nN~uh~wM3$I8g<9Dr6S=Ju=U|9Rjk}c8B-R12{H+)3G-I9Dl z9>th}3-|=axwH}}LLCjQKmGh6R}i`91VX;4t5R+4a^6_+N|?%?_}s5*5FO>XtLz=J z&HL*6=UMMl;Rnf;BG|t2TPAm{(9R$kHvIj{?w3KUMri(kNyo1jooNOHC8CYQ0xzjq zONP|-MnK++WkdyzA5?|Vf?j8{bwPG~!=t*CRU{hjzGx!Fh%biGSck#aB@C(tr8VyB zt?Fx|5xnP>R2T>)r|oD$2V-B_`-^|ec{xJEcd$XDQ5T=+Jww0x4q%pDg2 z6?DJT3F+5iKU^VG;b-e=NDkqY9;;8_nM+;^aQ0(HfhYyaoLw1N(4%G<_Wr~2@Io3& z?y%o4E%2x7mkU5OyU-PVL{bV`v)cSYOKFD%QCBzgwmXW%VS5IVC0{?qPg=$#j`?;1gnc7CF6aY=U(V&7CWXN_Qtu znY3>`u*X@z?6=8h_#&E!kCAEr4QH&wc`ujWWGkS7c>^fj{|?-f`0u6;f4n#QI*VSF zm>J?-1VWq)wj{^Wo;fawVBl9gI#}1Th5psZpkS9a$!ez#Vf;Ze(Kp-M61jmJaWE&& zHIIR)amK1fpI*~XH%uvMZvvt-O*46}bEME1Ni{mvu{P88baz;sKkkkZvZIM?LxU;x ze6oncf;DRenv8#pAY_S&YAOj;GR)h5z4bmU$$vtw;Mbt)kl{n)UQ|E?Jgo@CrMR+W z*J?jO-s8M6d9NvLs)ba2X|+4-o!i4^@5$G3XWy&cj?|mo2n6C%ovVvm6RDXW!U*9y zBFdbLl`AN&fPGn%0@ngJb|kJ}ZCQXiM>T{7WQ^qR6k4%-bdyEQVg@!9TO%@Dlqr7V}~=K^|SqW#lv32`YpZ%Hp7>)V8v!dT2WB>Zh?opAMqk9)>#=sz0yzxveax zI`i?o@TJPcU)zYrRe@e!3y-$?h!VUCXm(0V5m>eT+J=K)(HD>SL!iAAt#EvhpYUQ_ zExAQw&M+spIh9%2F|W&B13G+x`Q|MuP)Mwk#6ms20qkyHOMqRw9NX^%&Tt9ewa;@q zj9`TO-N_aGwilQeoorK?xr}a#{awy!!F~I>XH&j7CrZjgj?=oa>+=(hUz3n$|1O2L z7{f(58mhn889~!k7&S=TrzX+bnn5RFaK%k)_BRd)^8`e(!@|dq+OH%9am^4cqo~(^ zpN|Ub_?>VRODBi>|B7WDrV9hf1}9rL-eollW$%VGXu|0bL#%<{?&lG?XF)M>X=zaMnvt- zTM}fZSJ|f5b-Wo_pV-4Mq9K3lbfiPM3YI~VGEVVt`>5qEjqGdCZj8~KR-d*%?L^KxFjoApduTZ zeFp814c0 zwRvdXR6n6Htq6&SU<=#~N63(T9ik@{G^1i>AS#$HqeXhC241Yz{KWgG94$5Hr-g)r zpE>ZZ1##O(#p0#VLtJWBpX|=2}RObKSbSmCp)RsXVQMeOd0*Zd1Wywus7?6|0!4*qgy; zvl3ay0kQ3DNrQKZuL0K>aWnf41J7s$ zqEH1O2Gzg>xNXwUfJ_%jvVO1k&R{z}=E?ByzZ+V}%v^!tN`X!eq2y=w*SU;zkmhF4 zw9TU>sSGO)A*D6YP`12}5!j-<)E+cy9cy5`I0q z8x7cF18}O3q-Se~vP-$G=Q%5^nz+hw9W=U1~Tfe02bF71d`)XP$!1@zrLW~ zKLdLtqq=8Bq39saxwsb8p=jU!EF_Jkyo~2=`Q32<_v65yO5Y+E{iUo-CG^ML}_xooF2UWQJCbH@d>$Co}_}W6bv_acIY?#sw+FqOpvDS+GD&Fw+wLsTG%D{PH2%2#kQTO%65$*tBQ18^dT$*Vn zE-2`=6)*CtYA)z5GYEfVStBCzIf)_}KHEiRrVG`#yYFZ}@+Cax?&{h%amM_bk8=oN zixF%2^K!F`i~_BOw2-ILDiW+ygUaqSyu7j$bx=Z-kbLnXd?zH<=j&4$E-9J8+&xE` zWLYpeo8$;T5;H||6!HBY|<9?+AhhehR=yG_J9%tsjFb9y)5ZfF)=MI=?TAe$n zIp>u08hgYGc9fKZ4x6&?xa-H%S76gh8;b05cpLb$b1Jj`?;?TR74@`6q~!Rm798&b$+}EB9zUhgBf|uG*Vh`%9o9(){8uRqe%fB^qb%7y z;`|DTvoYV#@gPGa{z9!oemN=?Yc~*2E^O%Jf7^8}SCG+1h#f)*8{C&#n%Z^9b^2@EdR(}m zhA78Yb^RH+%UIK9!p-*b;|AJsbXHNBp#1IPh@6m6rMkXIs+^By5h{bPOo` zbo{gV47alb<0NZJ3wQBN?~u15V$!qzs`4)i#IAZ8LVNg$J_nvww}7 zdJgT>py8nL^T8It>tPs-g$GATH3X8p28^by!7*|O_g2^J+Umr1Er!WfB+*FLK2YJSSIW`gqoJ#wCo#+8tEBIKeznY7%Qt7}mU$@~$Hn(qO&E>Q2D>^jYr zyF*PbDWk^&6upcd+z zI9rY7%y!Q2%ija*?L6#jmk+Ylq#99G^r}A#Te14FCtcaX8b%m?)@H$pvUt@({ELRs zLmZr)`Dn*}JAQmI!veWFqgwhsrG}VmF|k!yeD*Z`X;UkfL?JKpf2mQ>f!rrV={&CN zb}W*#GVlFfDP=#yHw|?|Qz%l=Jh!hzBI_>Ni)&&iZJpPbwg~iwLp7dJ8r&EkoTlWL zIjqj0X%^gPXV`UUL}GvR>rN^=^8))5b=9D@dh$`3kcsBkk8t^nBI*_kE=T9sem<}9 z`I;(qCVB9gIoi!!pr?6A|y*?4yjO$6Q=fu-!pp-V(#_#E2cvVLM>?6bx%uig}Z zO#2@_Yvc<2fui#2!I6XEQi`g}17SrdQvjN|Q4{Nr1kNUuJZ$i7*3?t{4};XZ>AbXCi~?_uNM{$kp-=G2hL6^;6$&S!Aat%V1{=|aidTOiz0MuQ|9GU z&V)*wx6~G)w*JO*4OqVmPes1~*W!*QKjHDRwov^qkn)~sTaY5CvDjPjf?Hm{8Xz6RlltQ|i&J%Usi9Ll)}APV_2vYL?xRNT9A#ZjLRSYH zY>TM*CIHY|2!d&fISZZ^QRQxV8L;K+tf`ruKh}F|p+Llj-L4qpvQ`am3HfYhIEli>YA1WZBBM2VnT(HZSsaptGYVhtk#HuYK&vuah93w_!<_b?f zl@B|n)PPbD7;tiO^eAdZZ&Dn~8?SbA<=WCSl4i9lvPLEpWO;HaD1RW(fG&@)N!bsA zUunomL6@0ks(h}xmHJ4OQCpLqO{$}6!L%)Jes(y#tK#?C=g^>Jn6%eIs`a=`PC||q z88j!DYwX{BCX7r|UoTWrC$g~Tk^+ggYlZ`YUSTd3cxM8oh`xSFtM`tf8_U!3D$tlG zMQV5{|EpYWP+=^0+g5aLxq^u3ivqPMg)x@V612cLxUMS;M9(JLCi&sx6JBo45rV&k zZ4T*9AGMI`wKBfB%&z?NZXXSQ{e)N-oT`&xG!lB`w!iruU^Q9`(wzSTY}qmH9ThAoK2lb}Aq3!s1UO1t#0j0aY7oF$MW8FfEH`i?W8&}-_g4fh6_zr0Ym2Ed z3iR$G$$BGY;GJGAf?@Kd!Bm+Gb`Z{Wk&qFR{EPPO^viZ5WZDxB8X~%171@~AFMBKs z^+o0?Rw21Kd6)cN^7@{$?KtY$7douxWL$VM1}8$9L^u?G3ypy1M&W{}-!Pd>GB4z5 z24RS~z`F+qx&e^~X_L@Wkmh*!6d+LNF0!^3DUZvOVn z6(hu8$G?`deVX;tIAO+RX%W33ygUHg$SU#4gQv3!1AqMZT4~%w#ImS>nB-MXP5RKC z{0rsN?EkaHqC9aJhYUJUjnP&Ns$nTe`J zJD1c)_-quuYwTz%e8i9MS;*zhxlkVc^fNuWmgNICG9yfLE^g32FwH z8W>RHhyeT+fgU(9LIGHPxjfKaojwgng`wDgI~IV%!0zUuWLhQR83J6o%d6!mOC|WH z2$JOf7aoBPxWQ%19;%$Lyhno=vSL3AQC7o^ka6(Yi8>C?U_X$dM4v1CfQlk6{Lgny zq_74|-dM)j+T(lN+>u=qFkY!tMVMBq`WxrTi$n)_e{uLrZAD$ zM9;wa)-@Zr1|;ycm20NX&b#lVcj9h?;g*p_u3kj% zqHHx9Ni5(*bSx!#wT5Y&J6E~=3RpnL+umz`q;9D9f6LNJS05Rf_2w26f%@S!D0AUG z#VZ7srUPJbnuKwkxBe}@j`-FFyD{2vw3bZ@ox%yi(OS%l0j#`B!o$^Nq5~hL%LBVT zQwGP|D|ypSRHVU-^64Gz@{82brc|cGaC~~aNJo$pgiF`^#t)NKtDfnLxD{6y&>qHidh&GsYzPv5 znY2C$DXI6=@P%k+7S>P?zLJQqOC-l7DzFEaIe&NiPbkbE@D9rVds+VPHu2wWyj$Sb z+P}xO7uSnc#l^*zYJWyOPf(zx!O>U&n|(uiDQs$kj!^s?F)ieoy1nq;#Puz8S-5`< z7ruS5tuCh8N?6dQfhMhnY*=5LDL6U=uA2(BC@k7~dGEeYVlf6lJ_8jtkE2#$Hmu2d zc%4d~?=T$auDXLCtI;Nhom=ONF(;0oCNgx%1zgz}_SDy_5P_9s>g(Nvm~e@u5Cc;_ zP7?N~QtLtS?SUKf#@}Tl!*37`?7ETn)1?2Bpe*G`xQPU`Ivh_6%zhHF%;kLju;z zcy*KabdeS2=C!X|~;bY@`_@l=%Xs2U^#)zge+vt=A!SK^8My3ug6?0;H_$#zH2# z7|tlma&FRJ6+nA_ZVrHQ$vioDQqtzvAdD)BG6AW-ckumMVb*NvPO{;v{(B8p} zGu5>x08bQ{W}v#Bimx4GAi_cnyiwa0e@N)m>53_rzq}_)k@xxN{5gp*Cx1}J1!qrq z_-(!;c-in}n2TxW=SaP;ERH*ELAZzQH6!-2&Z{zCYuO|pW*eazv}V}#sjJaGTLl~5 z<|HZvBv*Kc|NR?&zsEKI_dDRGbwE}Aml^dC0lqydttNZgB=9;GqHDvRvef&*QrC;y zPk6~ah0`WmtU7Vbchdi-|K8a6IHW7H^O9L+a8BR+@jvf18iPLjTm>--Hv z`S+D9TwRr~J4AKBNd4M_4aJE=YMf}dPyV&S!6j{&O1c8#W#Jt9eAQvNRA(B{>$AnB zZd%&Ws^o3-{ZV%q(~$4yY9Xge%6Tf{_ZQo?w|@tg>Hf=ID89Ii&w7}lb7m*>LT}gu zWRMn#Hgjr-ov5ZbfEtf^^pQ+Cz!6MA(p~TsFPH!rEQsb1Qq0zxH{cj^8!ij321`K zuot5G;Y4eaOzPW6Hd|xZPpSdM2!vKKXlxsppu2Bs%-w1t!{|Kb|FzkWemnx+>~Crf znuDA_SWl%z9Z5O~wtfE1r5m2l5Nxv{2Q3zOPsG){-KF( zXdOiwA)obpa5@osKBUc~B^fg$`OXjj#teYJ!d{VBj)W{j^9%0Su8ombgTYz<(LH<_ zgW7JWO+(7i+b3`m%e@O_{9gl`f|rQ;tcYb;_>ds(*^w?=0~$VCBIKF(i4>5pfV9#P zNqTnm?dQKh{tH5Oz&)t5Mf>-}kZJ^kiZZ$yRx#|U<0W0LK>=VBZgW}~NslwZva{1K zwhp(S7b{jgV_>BGdgbq9I1pV2vV>b?cE&`?JP{0PBoFH2qENv@b-ep;hy^1-W$G=sXF-;5o=g&g2hHCLtYw$!+@1sI%s z(j|ypTr2a)QbvPSaQHo*yy%2>#6fzi-r#yYH*^uuuj;4CI@<~ho3zyYG0#{F<6bJWUZCK@Vv*=o(fK#oycT{e);q zfc^EGSNSZjHuTAJwf^Ia7O2nN^QKpm+cB=2qV*#gn%2t6%rgwYGQ%xYedK3uuqd#d zp~KZ=!z5TVLPB64+LZs-3^*k6R9BN&@Rbt@wpQvK%y^Y!iHeo(&$yBJ?MK8z;`ZL! zy|2+0S+%2RbTb%#@AwuU6oIHDDLRo(b{EeXpIV`AaHSY1k_De9(NX{Jv4)vm;O^k` z7RDafg0388W;xE_Svw>9T_UNOygvN8M-jJ0a`oF{05sdE)d-KPtJSmPO07lB*0>oo z#r;F{{Xs-S|fF@%W2(IM3~Kw(}PQ3OY0yYNiP+Qcz;@zb+*hMUF89{Ud>R z6;S40+K#{S!ld7M&J2kMzFto@DX$<;s~bzUod9&wI>ai|;&+c5(O;tNK@WWbc&@CB z&A&J99B1+v!Et@EJx87LC+8N{Lo!Ie=ob`K{IYcT{{NN6O94vV&1DC}uTUeyvNL#- zKk0W!cE;WFY2e!x_}!uYH*rzX#Y-IX+iud{#_QCxf&d@#2HuS)x(1=c3VvcZRF0y%Myq zNcxr0Tu7duD}>s0|5?$X1GujBR;#SKQ}^x>f6$K z9svHMC~Ciha->cnvS>oj;H-g001F^gWHTJFupgnj_+I%T+#77eG~Qka54Dgk zg56$}pIx`VIN=l@g%`eb{f6(E3agDxA6UUn^S0$NZ^|gu<}JIcL-!PC08xxVliIzLR(V*`c2-H^2C^ zG{L0Y_IUjx=okgCZ&(2cCG>KmiRfA$J2RjSHt0Uz3J^sS`x0J!$}nD3EbNghWYEd| z>}t5t4Dx4~lwy;DF{Jl97@Z`AyD5A-K)?o{rIsmymy2G$k}i)q<99ETK+NF*t!`^r z(b?T-Db|C@Np^5xOJZQ?w3B3G^h4k+R z!Ss66kr9V@3t5&Z){g}i`e>Y7A+aw;?Q#VKi+Zi|F%u@HZ@0Ug>(+GHV{TA~)!TEr z03Gn1gfiB6c$ZtZZkOFzLqkJ|Q0l)hzxr>D%7}qR!5pjm#nj-yH!b`Q#5r!Tq3^(2<21t^pklVj*7+dAS4seUrWupX zs@e9O+o6zU#Crx{v0|#x2A|*sj4I+>Z@onDazuXj(br{@Vw$-i6F()I1KT%?5m_)2 z^tFv@k99>JeKs|k1y*(nLb(PA%?t~@7JSt}%{kx+aDdRu#<+Jp{~uXz9aYsAbq$|; z;UeALUD8OWbT>+Oh)B281rZ4a0SO7|?(S}+yHiS#l&<&qd%kCkZ@lk+3>gE@K4 z*P3h2xe6(83X1-!p=me{L{1WBNJ4D71XvDLFv?o;4oS(}zH-zLf@zyay;ykpvCr@M z9kQcSw44)cYef&dArHLPZpnA?8Cq)J%lG1&8t1nR;9y1rHgf!=7+XuMrH*~(_&S|_ zgh$;N#WJtd*v0$`CqL(J1|F-6`d=cldK5pKdH;~7q}lR`MO``@mK1gD`4(c3B#M-f zYo7hRhz%o0lO#I&i)sQxOEY?8-{&fPF*_NZ^&*RC>>yfH?7K7vyY8Ecb^_P{Dg_@C z>bNp7RURa|cl@Smb>?_?I+SD1`Q?Ro6<3}7VXx~*$4S6iW$x=TmQ%6}h+O^3*981X zMevC48$>O+Dm;y=$0eS|G@rd@AUsGCq$V6ie`1!@PjHR+9QWM#;Cq_Jd-@)6r`n!3 z-mN`-*ep12;NFD;y$B16hO}6?*zS(5*LcwgJ|$^&p48dQl2f#y+O)z{2r_y}?RwM4 zSgBsCKGoILfHSDfudRZk9!R)>3Xs5#Aw)5DL}a6Oc@M2XGgd=oRPa`cDC8pzR!+;n z!e@8Hm4SqQr}(MO0@WcxE`SlEFYIh*hV-=k!WZrd`My!1j&D}6Xc5<4-D+$(k9R+3 zQmOO0Fl8P(oDqt*g=}Cv1Zr%zMH^=QKb)$MY{&571-b5x{os1F!{y*;o(W50S$m;1 z{VSe`syf&*f?bl$id?^dkAR1k#MV(ppLP4XisCEjK@{s8h7$8iHM68{42kb>au9L> zbRM=Ui>9G18jzn}lO7eAI}X)J(ST2=w|K~Q_rEMlQDP{#a8m-dxFfGlghAbkF|CFf z3pxz<;~s5=s^BC>9L`#oiB~UD1nnSGbO8}RF95d*=)>Y&4^+AQGwRNm$u*HI5h0k#- z&gnC%QLkgm%mU_N4DvLC*?^nZ_-{{Vxi4gk_EL~G%kHMxW;9^6df%$T_AyvY>C0P; zy>Znw8e6&xJU>+`O1iyn_t(f;ZfZ^%?DHGM#V)qt0cwR4p-F0nGU z8D#qj*8+uCr#`p~vb(3w#&s@!ceWgD+ly#zk3p*SM!ubwV@CJ+MCmiOB0|T=UUY6f zkWGe5_o`5tXnuutMGC)6K!|qya~6ORw|7~xvEm!W$ff_hGLPH&ANE|P4$3_9W3V}5n!GuTsbj3_O^+W_X z%uqH_Ijm%{Q#*ZnK)e+N76y4P5lou#+Mps_vM^MeFkF(ib8**UiuG{ZV`Ej*3P{RD zbfIX+!^57%?TCQSiZFvlX*&8mY+dkP*&ygJy!3={J-H?y6lzUTwx#J%*|&qZ zL7rKrA-lQ~rTQDf&q%{m-wj z+nvZ;xfcAJK@A@eO|Xl0KE=`fYwfpAzPM-+-!h!gES)4hRWMv~|KJA`wAM+lG>y=VkA+qvG#&{n3o6K(l|ooL zCqE5EFM)*-nwv)0LQrdc2}qcazi*t@tE#C6x*SmYJskKmL764EIUSv|$7$voGqgs2 zY`=dMF8K%Axj3wR=UN#+B#ZG5$!jKTb9YT2$Y*ZF?=Oh3(vuOO0|?O~hXocGGB*eo zpuga~`x-FDJgsa^;UnQ57Q_MEUQjW%Dft1cVMPZSzozP!ebR~TP$CD=37RU~OlswsgwcBo-e8AuN%;zS7XSz-S1V4^Sn@vNJEH%Cw1gRqaCV;)M<@gaUX^rx( zFp6=D>ASb0!Do!vRC)#b09udk52n0t7H0%xGQgw#mYrF0$Cev5w|`ixp2x7X6%u}M z`;O_nUjNs5aN8zB6!MEmN9H1G$i#dI+z!VS^P{ds{%*1U)Qr8Bu!a@O_dx^mm8+CB zD#5$MYNytVSHM^6o1^AqN(u@B5C@q3j$C7^0l%CX6lW zw_KM=()ebnULs)k(Xim`=}Odn&7!3{Dd?|Btsi$K(@pjPw zPP|8`iuUO>>IA56c}rJvecyNCHKP0XX}6Uu@JYbb`g>m;g1?7#?*zx0jtTevPE4-G zd@~oL;+KiR6Pb*|jMCrzr$oIA4PUbD$p{)Eq#-sBFH=RO4B`ERONlShlA#%1w``@Q zu=PF%5S%SS=x|DJOh|Ld{qjZun^ptAhrK~CF=P=~y z)626WUt#?Cvp5TZH$M2(61!xn$kP=G_9QdTq?Pi!Lms?R@g?4y2Ib9>bzhrtf-K&B z#y0s$d%f@b{HT9vjEjX%^<@pfYgR%FPO^W!Xq%pz-1fMO|K))Si(EmLU6ebX)Ruy) zFZ)WDjL)!5&fvV{GTL9=@fJCz#gn%8zsbFmuxn?jkL+9*E~W}Y5j0fp)W}E z!!6gzlc(4(Z&X@)FHP~=Nf1QNol;1Mi%g0jT%jrxba4i(z6U$frs1f~q8_xZ-9L6X z)USBnY$w_$doDTD*FJb${^|IQ%?L3jAV%odW2RmC(GIdhwkXlq=Kq#)f9M)_ zvP)WP-q)~*RNs>LoQ$g?#X;8#KV$gQDe=r$!U4e5<)9Eh)s8N=^%+KZ|8S(~C5~;5 z74WsQrOAkQnMNO#ecIq#@9X%NdiSG5z;Aw>H{5d)j@;r(Ds9E3^V~_aib$DL_1^*% zPeJ{!2Ao#VuFWlU(j-o+E?hDj106nP<-sZ5AA=$5$kzFCOiN?CbDp}Z>t2ksUE<`& zRm<+lMmN~ZIrbUzHF$a*OF#9Z7X-1k1-(+Vw`Vo(2Bc7H8=2FLvSG}8#(LP_mg!Dr zoF7c!Y86PuKdZ{K&xKY{o74_dhZ2FY^jgkI@moSnz zV2wavVY+AGM4i+LCay+6DT3pz*Az3R!L?hq)t_RX!5K zVRNXPNS50IR~NHfkcDB&ZCP|VZj);oWGdA=s+Ol%V11d{N_;|>RucjD&Bt`{@bbWh z^Y!v8im~-~=~wVh3Q+J#tdk6iYUg={??b=sZ`(j5Rk6B=d-4m8KHz|QC@fkH6d>Sk zxYkSDC*;dU;F+MCQ) zNT&&%T8bgPtz1knz$U@|dzwr*HC~OpI(nR%WwXdP!K%zXI_d9Cc81okZc@C`;yMU2 zLX`fO3t&}RaTMKmjK%e+UYr*GXxiS#%$67y!osaR3j>8Zn<7?^%O0uN-M0*eo6W>9 zRA=UK9bXj#xJw4moPe996<{$b9_ofKyxTZBZ@8dg5e0pS1oKxKm1 zPlElnE$`WvFlJPGR2=9<{bh8PLR5Z&Vh_RSC5`@{>KMXYl`8US%b- z;V`d3-RYq5)_`7(Av`loQhymw!7+kLGrR(p6s>^VGXXse%?VfPBAxP`szD!;2fO4t zk>c=JsuT^8)i2+8?DxHpjuG3LC0~GF05F6-`w3asVcQGxHA#S&HQKCG=YlBCkU(ic z<21SrpE(@=hZ@zZU=1`b6Z{M)(4Y9e0Y*HNqqd~<=@VfFIirbd_(Kxmzn9;wC0#w# z>?dqBC`UM+%32Jyz}5HZ4Tq|ff2UVYP4x*efcHMiLU>^PhZLWFnEi`U>-)@a&OVHd z)mX%)f*l(*>h7w914c%7KiWZ4N1YcvyAOj;6G5rJ85|%I#;A;>Akp+RxXHKCF(6I0gjqiMK&zM?V7~yVFJ!ucM5= zApfaz9i}D_Zii#|k+s3qM9%#JKhN)-!7xKFA`amW=Nqg`%LMC(yY{EM=GBX`FJuCs z9;^|Z2)}*R{^TzerZ+C`UT+jK^gQYoqledCu#i>xWc{3XKFG~;3s(xlnwqLNXGPhc zL0BX#_uIToEx`|S`@{8hQkW!;KLbRCA{FZcz4kUzRi(WdQG5uWxYF>S8+bfg{xlGc zB7uDLC205!(%&9@Ew_?m1lT|=AVP(0a8C<>g*W|6C)kT5PIevIe;NC`?8T+yaid20 zmzR(drmAGYVC>K35e6m9lJP4#VvEoo#kARGT_`bD5&cHmYV~Q_4YDTOlc@g%&1ryS zR2`s7?iE=G3;Wopv;xq)AnQLfs4O1xC}(u`(FQpWq11kMb(4W@(PFhaO^+sQ_Imdx zkZv${irTdW%rf8loh)J1Nhy+pRCGKX=9iE0sjNf|m9GsY#_)X9=kUAJkY5m^YE;)s zCEEA7t{}p(+HQ0mX!MI#MyD~L-`^=;rJJh)e2mJ;xbaQSfn*~2_mnn54UQscBlU!4 zf2WMa+9fR4Td%BJ2Y3jCDZU2LK|Qbrwgy5iB0N>9zZ0=zhE;F{zVwBs(}WoLY{!Gt z*^x}?PorX2%X6(q9?vkzulK;g)T>u*0>7H|jg0QkC7#Z~S*W#oY>%@}53}7^5}!>$ z2<3K4;$cc#O(<87?T6c_kid$2oVV*B0kWXP(3a-|(&j?V|FGPNq@N`a6tKfvr0!uZ za*5~|_!*l=^cq=gR$>fP97o|FkljJ(=ui%mt!Z%D>5I=+QO7HOPO9f?A5r;$Z^0+9GuL+P6u>hBe$cFbQgwDWrmRmkcP)tM$P9&xiX=63 zeAX=#MQoKe=yF}5vig#*6UpC`h+1k?P>Kf1DV3G2Wy19SmcbM>;R<^OLo8{r{fw># zs??LQ3bLAr2G8IYYVJSoDM;keG;Ek9yL{y&US@y{2k+gSkI=(R#cyxugu7{Vv3hsG zOQ*p?N6J~;L_@{4Klu6@l(hMRlV_hm>E*+`W%PnbQv6^u=ezL z)!mX}U)H!&)_io^i4}0tgQwoIMRDBlD^?j~8X*Gdx6}EIOiWH~H#@DqR{_7Z({Fz< zN!(1OKkA6KgsiXwM%TYOMq@p@#pi8hb|Qpq9zsdI6EOp%G0fO5Q|oEdK0Fc zXj=)B@m~smyH7LC3JbK0c7Ez9?Zjv>x18aLE0J$N%0TVvhisrzKZR@nY*G^)T={X2O0TR{>HyHs8ijy;hRHAR;L zf_C%2DlU`NKOomQzK^9ux!>nX<(N|iWg)VqyuY{kO8|_U#+WI-br12iJvBpBH7*DG6OnazsB5+=+{y-7#J|I`i^=q ziXVt$eCcuV3u*VIo-49Bjzlsb;Rb#fzazJF-@B!?(ZJKqNY2ON_S@p8`>`kV`&X>- zL;rqS_TKtJWb8ii-S)>#FR0`BJEbn)v4(&pdJ+@u_shY_cgZe4?NUDQue_6YHyNeR zFPzhpSZ?tnwzo=a(>q30!A{E$Yyk)~-;9~cdjo7MU!t6FsfBqlzlDT4LPDi(cg3Q| zKKU^RX+8~qC_5WY!^KT^tOpFkB>&`6qR&Hh=3|C2T{Jjn5BzHYU9fkLk?}!of7G`W z#;mMq%+kfd-)sw)jI}_lRa#2zcMXQ6D0a|LOt}fDfEEWm5vobY z8pyD|748Kizi{n$AUc|Qbt1*ezle#VgxDnIN5%13u}T?n(XiV82=YOm8ATc*ECV4x z0o)_04K3pYTP==#q{2WT;@EYIs`ajSPkAN_$6$WMMh4RK*KvV5o6=xFJE{Ea=R5sp z@K{DhOHny|p7fft=0xnFq2j?R&Q~*F;Gq&dp>2Dd2T6NEsn1uSTYF5aeha8NA0-7s zaz@r27&#Z;F^8(lw9;cji-OO2MWPuy#zY^lw**$bEf3~6+wadn8Wma4T7)@qo*g)r zgU*Lo#uBo*nYpwneMamy*%*YKvlw|c;;;_X`6|j9sn56 zc^DIo%|~uX)f#hzCmj-}@Y8m2+BO_WA$`c*EmC@G@*L5QK_SQGi- zG_wUaAl$Pd?=6<7*WZyxUiE}Q^k2WM>Ix7M0agzR1nsF8D&Wi&0hU57xL4O(Hv}Pu z`0CmHguOb3*mQu%S;qas2npP9g{F(d0>DO?qS$L+$(1GfL%YEL1^)UI^O+VaJv`zxqDD zntmT3w)VHk9BvL&sC4suc%tOr)IHou)?K2LAyzXp(wO>E*Hvg`UwHt~-WE|z!xysbxfEqTV?zYgB#hN`ni z=C7Y8raufCdMSIN5gsnIjhO~`4&3oag>^BQCH*k;yy@I;v^J))!GZz!M=oak`D8oc zy{y1ze4R&!^&bK%_Mq%cJt3)$G8am?d)vHx@1tAxJAv(`+L=jA1(4yGH05Ruc=wu> zx#_;_5({^*BVlvl?WepR?3gSIR%mXSEeZ3FlHPcHkkL;FI{%b>9LNGrdCAPyf@?CmE0Ao_IYBgX z#WSN{{4l$p0jNJkm0GWJh`U}mZoMmOaDn$10~xaiw{;FnKi)fczguP4= z^DC77_8*BZ3{N|CtxsHyyH{$}s}*$*ecl^pmeP*xS4V2nO@B{*|9eDCb_Dp_-*)2J z0Kdd@gaP$Gz7WaTY{8#hJRTS}yICh`IFMAJ!O}@W;xrL!=yTjwVPSv0>T%Qo7P~;# zBhe54w@Y0nF3Z4rF46w2y4a<&b^4N*xLv>UUHWRZ!{wmD^v-e_X95^(mT zkg1NsN3?P*U^5Aw`gr*vgcSkKBjLuj_%l%P88Ab8a-QzA~Am+FXKXB;2AjXXz%{~hm+ zJ~I6V{F3HGQf$MmC^n^g*n|0$sij!b37z@o>)Z8SQgTMj!Z&Vw>Qyi9JtO7y`Gs^%w&S}HBqgl#bK$lZmqE;2T;H|^e)hfgXEY#{cg*@ z!?uj;?bw>X=Yi{(BoWvpGRdFgit$_+#Fy%|<^c*J9scc$m>IZJCk;u2LF^&~&<TWRYBVDdJim!xKD`J;cxE9Rcgho=P?&cmH&+Z$G!o*6?y*Z<6zh>TX`jYNB@| zpGO6re4z3>w4^d@4`|I|-c9pb)qQPT>$a-~T=xmIovwetS_R><{2%XsKU}RnF$JD6 zZEbBO8o8o8Ri{53+CFV^K0-}7+1Ogn;>-Q|MOL{*McM9i^Ofc2j++k3lsQ{S z$0+r0hqj)mfNy7w;o`@PZxQ>lz#XlPs6_Dqbc_}9l#ha#tc@+o2P z^HKjlJx=L6SN$k7PghaR!1}jJ4X5s((mwr$tK?>g*XikZ7pIm#fs?3u2XR|4M<}gz zTheY9KHGdgn}*(xxy$Eav6*&#kv?|3$m@jiv{p;}4rz165*m ze+vJ|zbU(1F(O_c$s&2I^}A7lF8BC96WjairFQ!F?kAA^`#U-KCcFUL&mu#m@seKUVq;pBcQzf8i%V)Fv$@v*V$@kag#2KO@YTnPV!)zy}-CSvVpv5B#n71pE1 zHq&;p=T8_j`u-2n{L|m!tN_1NhpWz;z~n_uWGc5-mC$wfgRdH?u|U%6 zjqUyOF)`mw_Wb&XQ70W}yT)4_)u| z^!Qk)HZ3Y&9k)NMR|8yntZFJoA*L-Z#}957MKI^b6wVN1tVGlsaMSzTIEY-14U5gs zZYj8Vc=v{)-F9ywR?pn2-T%~%hITZ)cJkg$F^wPEmVh{~#>smp6rRR(?Q#Y>v_oG! zZS0$lOtY4+TqAkEFG{kX#`2vbEWX{PY$O6kg?Bwp?zIp4`xzPe!=bXvq3%gXggGz; z(H?lapZ}UQe$4;KP2%x1I`GOX zkO(k&x}7^-tUV|;eR!*l#+5!M(8{1XC1bJwbFoaXQqq?|NcSlJqUB_G0(?M_w`l*W z!m+{GI};V~P=Eq4g%!r-~2sKp_RySbtdZ;Fx5 zIs??z;txXkw1z*fQF35ezsqsn_?``s!tS$a^K3{OMj9k?0h7dp1|@v|=o4C~VJF-ed$7QbhnF;dyq{ z&w-4KMThVd&q5ohBuhE!+;`PA{A*HtBH0A?F~z?aiD##!OU{Lw(`bjMcVkL*v8TT~ zgYS~@UH=A}niLF1kPa&9Xo@Svdc*;e-08|^jrixR05KtU_#^LPyGg|qkD_KV5(Eyh zwR+AG;rvs%74fY)k!#`2kth-DyA1eBcJ4<0emXulA}4?WlCRLEwuXl(AsA-o_B@*J zF#I&%0H!Tx9_bA}w$BUqJzlqzndNr~iRk{S=64@q4Ek7v0@!~d$Aqo~*#)t%0AIEJ z=1?PU`kcsE2(0G*e9^pB80;7R#drG{%{d1#^V2Py8q4Y-h5QahLKSjhXTtN&SRR%% zxqeAy*tDOz*-3-=23qE=+M)gpUu%FDjQ5TE%K;3DvzX}5QBhGf z^Lu-HRQH`!A%SZM2ngVQ18GTK%P#$(Yl!2wzj51rhPwE@psg8l9CzNUw3oeSTzLbN zpe7ukymxAUT<)Z%IYfnXTXpVz0SNi>~n%_gc#9H%Bs4vJE?SAt3+^G_2ww~ymllGbbC`fsw zT7S(&XD|i@2x;P*PyhrUoDP}x7Et%I@&cn$J*jIi50;8qf8y_uo*X|JV;bZMB9|%R zeyhaK?8(Sj{zH)?_|X=1IqbVRf9LVNo`9I?a?de3)GM?aj;?Yi)(7T%)BfeSBvL*I za2cI!G@PQ7G72?mAiyUwgPX~UNMB8n;Spw^&s=w?=NPYUGTeEe?ZV>O*rklI0z+0t zwq@KO*2L?;IufKVgMPMY{;&%ix^V9gKEr5ZdUr>v2b`jo4uSa{doBs~jP$yGYHV_) zzw^qgS=cT|2-j`f?pBWb{yH8tY+*_bEZC+$fM|^W?NmDGUtC?@cKcR!YV~%uJ^=g| z4#LQPd4&Jf%GJYh;FG=SU9z|LAn}3uU( zaf*o8w~lUka1gyUOC>UyHVa$9X(_d8JRljj4Jx0Ix%zb~t}+WUVAa`?y6sOt9VM;^ zsg+_ZPk&ahtqUKt#=RN@D)eS#Ig+i{z73)0Ra|G6gr=-FyT=&5+%|-FMUOM@*?Wma zmY3f=(rr;-lFrIpUsBJ?B>x@=vXtls$peVC5`vI!!D<`5`K}Ewg_@gobDYlwkzMUF zBo31+!S*R9J9dd(z&v}0QHH^o(ux0a3=w`Eb6BZ3arPOjJ(b?i^Kh?30dI(-Pu^wkD?D(Hx7Q9U{C!883sg&rGPh1ZtDC&brk zeLyLLxgzf2eU5P@6IkncfAneF{`Y&_KVX?XnVoVf}g>roSPcF z5=;}sctsBDHNfkfAFC;8vU`~!>{@_KWe9HyhiLth{Um2)kMnDW8ReS~`Zj@#UY;Po zqZI*8y2Qv`shPB%y4B)Y#b^rz6%!bX70S>km{+*gT!*)k zL$Cf$q3%Qc<7Z^UYN%o?zCI6oRjQfRh#-cb7EbSqVg><%E_!!j%_dpIadOekZPI-I z489QV*DSA3w!R`lMYR^_#!wjXF!b}?wywH;lzJ*QbqIB|(b)EwDC*ZjHPoNUPPnuE z`sw~NJt-HJgc&DvtJxWP_Oub3W^u}Buz7qN8Sn57v`{EpIKU{?@4)G#uigk7aH9dS z`;7*~yQM2`d^7ehbetv9=xhtNN{+W#cA&>Zj3=`se;rwdMX`@0By^DKv|45CH9(y| zM3=VBgFenRPJys0(qB7#lh8M^5K#QEH22S@r-DaN%U-s^VEv>iia_oY>K$p zUDGi#HF4kN=@KN9`jI_kF<3X*jnuFsN1o@c%kGCle;tjRF?Rq>Z(2Nx(jfo1n89|a za*p7pN^xqi-HmhuxWr7qC^hz5GKLFfvMOtq64;}F^q3C$;qqa0kq^?8VUiH|bt3J+ zu$a0%37E-*cSt5x{QA7Y8;dW7XBo%+*=f18?=a~I7JB$e4g>amIcmc`hZFuBA z0e#%-|KCpNbA7j$dvtkkbkHiIdTkp`#ql?3lV@T=a#O{_7_fIHR>}$psZI10vjCD; zi#1Hr#*bx;=gb|{PMlVX&#j(uL%KT^A5|IiY)S^eUPjS?W~uH6BjDLyl<$kvK zc79Mm&M>io@8k8Pwfj!pg4bDd7fppi(sUCdZpXFKjJ%4YuQu(t9@5$5Md>$ERRVK! z8~zkMsQD42;(xvywOPSZl&~a~+|Rn}WO12kPmbRBW&^RW`of`;y1XErfg3kI%i#HC z1}w;s_?&?^?pzL$b)kQPR;Jz$l%6vk$>3$-cZD$6y&GqRM9GxAz(8TzWI{!ir2VsX zWX&we`-L!r6+v>P0zFbv6wj#&-7FY%A^mqpq?PV5vg8{#gBlzd>i9v7I>PnyVKJng zY%lkb{=@_ChU6oT%e3u`t*#qK131mOd|TT7(XltJ294VHujeyeuUucb)(od>D-EK- z%|El|sdvfZOHpz6_C8BNt{LaFOvdz}2Wgw1!9$sI?V|XFn4DFBbrG0+DmV z4LXa522El!vMC-6ArWS7>=VA5Y|F|3=qJJHINkJ3iqtUn4)1WuPL7%HgoVgBLwbJo z=pcn8;#;f=5eD$vMxB+Gss2@gk?bVo5!IgR53f6pSNfK{p9&pAX}Cfh0j~qC##(-~ z*saQZ3@`HTTb+Q|w|&#k4K6BwGY6hZMCtuVvQ=+PMauhLxWA;R!z~mk_OnVr)_Z z5_CW`3qY7V=>Aq?K@oxFv>%Lr6J5@trDNZ#0k;SfZ$uvv|8SH+!cX!J$07+aRcc$z zT+K&QGYedD=TyGCIYQ(RnD5quHirP_sIEAu`vt87)S;UVB%E&E(ZLo);q%NKQ=Y=% zChdD$Z$nAwP&G1{J6uN)AzopAJ~xCJ$uzVYpk(m}ou100_HeK5AX+gT$D77A& zA_`JBMS#uIl%jo?5Y~i$ESp2#ev3!OL$mwS4iYh_EOCkp46yG`(*}PKwvb@>i-YGS z4Z1!)WdPO{E;zJ{gX6}m|89f-9Me^abQh*L zJRpRCF4>mYf4-BcgC7D#neX63k|rFyRKOCB=@<`d?6ri;`6z+f@z!(Hu4IK@K~&D{ z9U=bDKzdOHZxkW51LlGO907WS-TnBIwM)kk4geuQB|(fV#q2{2$t$mkXXYq24_fwI z!)twXy+%{f3b8o@pjEw6HyI*KA+R0onRn8CjKqf(4R|VHhF~L#km*ZAQc;7Q=j`8* z@jI}|r@P)u@avUjqUx??01)796UfwH+rd$$E-5w-sDf(3ttke@aGO3_D?+LBwq?;O zPE9{L2U#Y?zDmNhSdQkD<+EG}hkgc+{M|vdJmDA#6(O&_%Mw`e5Cz=QgCs-WA9ows z&qS{@`$W8|6T=4PXuVbZD93tR!o(b8&UFq<(sdnq{Fi-iP#p03ti)u zb(TYotoXW%_FYt43hU-+W)opUqEXwuCOgIJA zX$iU5m-6IM#{Zg??2?bjGi>mWKK;m~zJ8$oaOL=Nov@z9VrS3di$4s9*C8=YOl6AJ z#%Z+u{45I=1jT1$8=SK3CzfR|t84*lXD)Pz6QbGsw%hSXl2d#w^sJ7u)*U=Aa^kgF zjABwURBVZL3)TL>2%NaE#Kh-bdEwAs4cLfeDT#RIdMh4l9~q4HfL$P61czDqiWPM3 z0#){Fu3N3ww-S_s>px~;KdC5~J2w30>~pfvP}g$O%AF(IN`htyWHP#LoqXL4>!UT` z1u*7R<-Y&9+WLgGj-=oEf6vUMwHN26)hOg1K6v!v1KIwalTenkK!#ZJ7cbWn?sIq1 zxVxRn2q7y~8P8@0Zq(^rHO;$XYY=NdTGcCrr}7H#sS2HNayL~2_**0Pj@%*$5R3ma zU2oy;Q!zEkTjrG`i?bw~03S~}#V3=h0YGvA@CQtzu z96hNhk+V>0o0CjDDV1s_ABF30id>V(cnL%Mk?LsUX^6uQfgc&Lxe&W!LIgfL6*uXA z`SQ=H_8;cJCre1aQwd8IV&GdFd9$DrxhM5?P`d0jFPjvI*hhpl@T`B_<}ZakUMOfD zq}FA-$IW4+>lyU(#DH#5M?~erctH_yDLU)@18lO3+X4ojHDKBYB2?y^=wlp6Qi9_X`P1`cU-W8LQ6eS zp!L7l0nqfhS}`n23$ZmJ=;RQOL3JDfTvRF_NC7P5B6eUMh@(!k z0?$k}_@^S@7Jj?eBPC{44|rhH*>gWjEyN9)Bx1~5=bun;4zyyM!^w0c-i{j_BY znhs1ZExA1xsH};);9Jp`B=gn!SGB6d(*JFbVB79V_FbL?Gc-N1>JY+=ihzaHadmdd zJ8vkQQ4Rnvqitk+r|0CpIRiWZ+uSg{llgbFPPYg)MJ-#V7y@=l^ECeGG~LivOE8~0 zBLukVD$#ptl4IjmnFCL$bJn+JgV-jMS0W{VHBRaN*? zT=Fp)@;5!5uPpfyhP@7@LroyDa{^5ymmD>BZ)kh76s<4$>wtg*>3@n1_5y@nPlfJ*ljedr|9r@$M6|ivmkHH*%-m9yeU5NqaI;&=_AI$|F;n7{8YB!EgXYm zoFM)oDq4SBMz)11`SQphL2j*oMv`cSB)+>;~>S&~^_DRdLIoUD<%K8%jbkGP0S?)ZOeC{NV};a60bdfe!qPQ?`!1^tS5|58Yaf^VNbWlP3qmsh*F;LrUjZwVVCh zdlC;Uo8ymFJdE$fY$3wF=?jGs?jHrwu=)2#eOCCFVG5u6MH_JUOkjdxFV4EfQV6tF`+DXG6kb0_B|DWadIlQDHCtBuzxo zA{V};&WVU0gIWo(VylDytF_a+8Iz~L=XIPuPD~!YS}x=@k~wOG;KHi9kj4^Z9 zUaTxm)jNF+m$amqg-O5lu{JKBAk&q>VJR<3i9J3b%Ov-M!>+7S->{3D&zbiWJxhZX zl#1h^RNf-iHMI81H3JmyxCM4cj6qUJax{{US_dR-){C0+O#B=)-b z++T)c?79@!6AIpEFbh1t{q$OQCWBAgtg;9QlW-_(b16_WEE>b{A0#T9R0T_k@R2AVTife&*v%f8}_m(e~0fazy_k8SBuHFT0BqG-bXEz$8x($ zq1Q({)zQV=((2hd(2L}J9Tl2@9Dgk<-V&DK3xl78fUTK@AQJL&@*91n?otT+Xe)o9Md;0yMA z$`Pap7wdoBJpO0H82ievw4D<5 zr;Gq_=>M!{BmRNv$e5Cla(jDTy<5o4cU)D_()*n7;@b&};LAuRs5KEaHr1y}9jePC zE_$m&T~p_saMkVd-g{q>8WzdLM7+7wlF$1Ad!j%lYZf@b5i8wD&yv-r!6?vYs8NBhoAt^&thhl~uwq>yQ^f>CgO3fvoQ51)&VHA)*eKWS?B* zMvi?!WGq9UQ)K)~6>;(5BS{u)bBinCclRnqXb9Wg3=>UDSrQ}E8kMW=O1*3Dvwbmf zZ8d<`#xSuA$)lycLwH#^p%mzAguib~ltD||kM4%0=bK`CZe*^OC(*q$Ke_t6A5OdZ z^Mr86O78mnqcOZv9_c#MS>)U3hhx1z+&a1_hzl@ekr&dq)!mJFKs*Pa5pqucob-LH&8`VH< zoM1zc`GW7#ct(Q*c#i0@Mm`we?gCuiKRReU7TCIWI-mQa9l#?b*%G&RpX*GU+ z3EVe+;b{k)X0p#58)`GtK1#FAd}uHLT(L zLc~$H8R|IOMMd=$M@P|OXgJ#IKMPdYG4&ERo||2||6(Rb?wkr;9Rut!LVwGjL<}w5 zk7N}&Wf;>jG|bTQO$Yi3zNVFd-=E)c$T|eF%H7=^Xz#Ew=NYBpr#|$G<>6&$vcO-w zA;v61PZHc9IZQNP%p;{t9zGB6F^ig(p=`}Bk9#S zawz4H#2|3DMAg4kw~WaEzpk;CO-r2icj#x;b!tXIUA4Q1MGi@%_gQ|lq8vYv-Tnr3 zdzHMRk^f#aVZEuWueF{YdkjXB<>}cUX*=x0gP+F>ow?X4IIZARu5r8AIQix#orNJ@ z5Tt*bBm{vn(O;{OOyJP5Pbb zI4W&XdElt0+tEc$t%lV6?=(6v3gQ$z-_eG5+nHLtYGGV}&9COBSxe3d6fp(ka92-v z-*QOih)5$>i{$_SB}>^-ta*^!aGN6IF9^SnRw{r;Zw{LcTJ z=bYy}*Ex0W`*z=-YrV(oJ+AjvUf<%0_0KI;QfLW|#zJYy*vj{R>e*()?d=I)Jc&$< zB92FtzP=^C=`Er0v4QWBZXw6dJMFMrKRzbUVuZ0lt6CbLxap`J>A!4_;3DD?T{53A z>hEGLRfF<9T$fM2nmN1r$n@`e!yX%HfB>&TyRP>G93 zv$k~4K;|qV-J8#%r(1<6dn5WwN#Al+OhgjLYd6}eec1e}FSndTf5Ndah%cb6hU)k* zg|E;63q{OID?-S-pAU2?%1j{f4hcAJ$4BXn8-oywhuUDk_rSbbKQH>$7X^TKrGyQ zot;Kfs_7PO^`n*rX5&vA)XL4>0}3?$5=rz&jz3FvJMp@iTU7mL=Q1EbB?hO*YL+xh z9{9=o0ItSa-sE5SrZxFOCKu_KHT*j2hA%pcX`u{&@~0tH=2gF6pn$HiV5w7PF{!XJk7g`pSMKg@9Y)tX(n8LumS0dE*Az-F zLg#u}5wB)$cj2Ov4Gm~8B0kO+TvAI{cY0Ixf|BT0O!=!9)p0etxT-XP5CeJMjMV8o z5sfXAN5&DWD&k1O%9D;_J4X>xRei#V`24%c5)`tCOyUdmQ4zw675)OAQ}|q{uvcGn zOFbo|!NxWAQJ&s~Rn>wt;>8tH3ymjPw_0xt5WxK5D7B9agN>*Ph?i@HL(zfKQSL7wn*&adMZsu=KRpg@fICLbV?8we&VUz9KP%>*2b=dPwK2b2hk^2T7z|A zTi;X%BMm$x^yKf5Dgc>d`O^cFH?wgyv6aUoA6{2j{^R2q(^m|}fxsIv!gr?9m-H*m z!V>1?HBO0@2*k_?TRm54E19!K(pQV#<8gOX!s>^#xqD#4SruR0XY#sfSnWV!9j)Q) zza`}_DZ6d1;Tfy1KwrW}B|)0$N*k@gN(sVM>T93hy3<8h_atpeQi0FKh-V<7a4_JP zwUcK0apD!&VHTzhEbY>$w{VprolCdn3J|7i08g1f_}34L9xwB)bke-mg-ST?A35r; zs=}&jX>dEB%%WoI$hGp9?$qx4SEu&O7)=G8$0Sq@mDy>Vc-B-d@{I9R z+%vnj0)m58#&>4-9xMl&@bCN$KB-bs;a8v{OFV9TILxPKvUUd-XT%^-!A6yMhfMJ3 z)nIB=@*WdQMCpp^r9{7;eh!L+%FXY|t;uGXlhhG*AIR&~OrkQQJWKlq>YIXWJ z)wyGQhbXxc{l;S-c3t-U67g&n|I#Isj^{_1Xir~SX2Z-%_*Bq$MSx&6cscl#%^db9 zq{bAht*<7>+7db_c{ob($1OoeQxm+RiOs7kbwY%px1}4O8;0WYoB5>T5yLD0q6%(x zx8s8VFs_qqYqcFERsq3*y_Mlv>ex?MN7WjCPKj%Afo5i*x(ZJ` zu9aCyyVp_ts3c79acjErQlna*f5hiT*&pBwM~=;!Papoh9aFD_rAZNpi+NSCQ^D?`$dgj=IcawR>N!*;((Zrq(iFtYo@B$A1hI_ZHnDupxZg zIO=C|Nn1MXXjpiC-;2b?Z=ScXuz=*awTae`>gwwJ1;bC_ypjH%DI^|i>N;p#y?Rwk zt9N5OsvJ^d`IwAOe5)zcX5Nv1+es95er`RspXc|U;=pk0QKf+Rn`$y_bT^&__rj4Y zu0I)D-#_sWx$MrTGpsG9jiYZH_waB@BJNqL8hzID+a{x`0R3LNZXUMgFf}jyIk)-F4ZC|LcqmGT7i4O_Kr#Yi5P)S~v)Gn@f@ zVG7TMY7UY2&1RFTMg=R|h+tn(BDZ2+N1B1TMUWXSYLZ-Yx_@M(N4U#Duvznx^>788 z&tKe}&QJ*xR*-=V{``kM**-o#M9h!>>~76Ri8xHf%KGL;iEWGp7TS8*@P5FRcGtY^ zk-lvT7tC^1+$$XQ@sc;uT*F2OPLm^a0%Ss|wBF-Y3IcJ#nw=}xJQ933|0)+bb6&4O zx@=Mb_BEA)$44cm<9|`lOt4a!-X!dB>+o7p9L{X+vhIPBs%FVl1}#n*(rk}uSd=JI z8wP~dA6DidkIsKTCK@`PV(;KU`0Vn})w1^Xc8BTC7gu7?n-O<(A5{^Vq33NcEhN#yivIfB)5j!X3BRpfo%>L=~!_3fSb*b?Q`*(#TlB;VM? zeGYTP`^Ndob9NtN!l(PA<)~?C>6w?3t(v(NX@BXMrTp!*t49=^X`{m#=xFA?znC_x zzABy=DPcaUUC-t%8oPn7Bup3@9DM8MO<|AS?X0`CesqGPze4o&%H4O85+Zxs+jF5D zsvI2b`a;C4Q($eVq0s^5b#q)+rhNH|>ei$9Z)ZlAl=QDReS634d4%EW3+mFTDRYv` zOCwG`Ug|OuJ7XVzx#m}ohjh-{PZUB)=*{qu4+_B@t#ep4tXfL)U~I7bp&{W*GK_oO zS_vHt+?weI%q$bi2px;at>U|aA&FL{$I8ho(ZDP~IFbX6L* z>tOO0%0KUrAE2avfk(g0cTR?JW~khwB1*7}t#Y*5*Q7bpZF`|sG@@zYXKnL`OF8lJ z>{t@-x?Hn1xco}rtFFN2=OCohK~`OI7j_t4IW>!~**h6)Y0JH)*U-`V5E-fbg8H=- zi>j`!xbZh^exH(=m)H2m`0>wHH2yiwJfSXgiR;@xWfCi7ucE~E|f}}-m}nO z)2(&SZ@Ak&U3Xd*cbLi5)*lW{D67&--Ahj19W6DdT5z#h zHF^C{Ekq-h+w4|(?(1)UXXJI6MA&S$FDZ{rEvKwV4e!2A$?H<*D;`___#Qvk z{LSdJQ@Qhw?;BY*$@!q9kVvC}D}y=ZOHY&@$go+gXC|rhkEK6*m+VEspx2)z8;)U= z;BlC0R|q=HV^ZCju{X5%Mn*(t>^px1gSOb-d56Yd32!nthdK%$tzD1m^r@Rr<4}yy zl5%2YifHWY#Pg`pQO6Y)7Cz`oAIP`TfAAn>Xg*5tE}YhH%Bp3Wwk=#-T3TUd5Oth^ z<47($`AlzWe=g7s*%S{D1V6jtz0$ADHSh~GBz68-n_`z+_bArl1zs5F@+C;i^pjV+ zQ(*ICo^vzJNcc!8C@91zN;y5XMGjd?FkaJ?UnyW*czn-Cxqj8e88tO67(urkABK(%ONctCf6{c&=ag?Q^b6mIobd`@;Qsj7C)syTms zr=48ed!dAbF*~j*|2W3)CbRT)f^SF2xWRN--}piCx^y8!ThzU5x$*#5oOc$>`~8Eh zIezx1pXsiMkfjj4#N&dY`Jo(>W}jo+@k-&r0Rgsih2!o(rkfNGhsxZRCtBNSy$m_S zy-t;_;E&zVA^*L{qf{Kkr(C8)PcBR4-<1BA&QIbHVt^xmCQaoZwC+gvf&5ddu)fTz z@9$QNQib=3KO4C?xfIma=lOkcm?^WkK|L@cJSb%8Qm!UOrBxvJCnqPL;pXm2y;E5&&3J|1vE8(+|h9yO8Pc zGL@7-!*kmj4)Of{^{aI88~0HT<+0I|!N-D6?T)<9F(G-I_k*U~U2>x0Tejw+ubZU({58$uX<(OH3;JzC78Mpb|AWF9$>uDeiin zmhAjoXK^>7Y51>R&=*9iRwuz&eRjQw&jZ0?6wlmog_l~kUvKiej25l2eKlp zgdGct1jzz~rYT#Vk*13R?3iDi7(}X_DqDIc{D~5?4pZE= zmRV4JYu~z<71_paSX>!n`i5VHkEi?D)T8eTjF}$}jFI^|f7a1v)PdT|QbE;O8=lsh zK#U`fd3c5T2{nyYnURC_8Ha!lIv-ZnCkFD}JBJakuuhH4X_7nQLQs?RO##3r54~&! zSGQ^A3rac#$;qEj8t&*dVHocf$fcTm%)%rn%_#(@e>H!lM1glP_4ZouyWhTE3xge~ zCoprHw-#l9aFGH~Fv#r@JBZ3Us*~rde3ib9`%M%gj#3Zf@%wVrm z4w6ns2cE&$czM}7&SSC1Kq z2j!^@$9e^6b}H4cReSupNObnds{dL6*J)85xvc7Mx*?S(sYmNyI5107DHskDcHaCi zAEkY-(dEKj%}mmko2HXb1_4D|uFtRZP8affQ0BLbxYYI?Ixai$hNSpQfcIBEDWqb! z@SzA{qJ{c{L6cw$bI0tMvO=)<=eLsOrLS+j-26>I#`%`m{;eR!ca&G(L39@Uw4^!( z9EM-CyD~}NF4Y+P^1J+R1n$!8*`T<+ld1fI`x|n#H?;bKw|v^isL*TRV)lH&hEe+L z9)6yX?&gaZ$_VcA)jB3u2RiaRB_)|}+|zZ$A~Im%d+wMuTK);A1V%``TyNM8CUsN7W?LR^7opn-J{XSZ^L1$!`6o>lpv_M}GQC20DT9p9=Xc zI;E;UNXu!*#w+^Db$n8;!p@3>rzzlu3^`3zFqIIxd!AqJOKYJLa^Hcb#$V>v9Ec2VY(q>jFl_>y-hoQdEEtLv!A-oeL{WR{GmT#_7qY z+T~yDh>MZH4Bw-~FTJD?q&4SPcgo@Xq@L6UwSABO;7e2wNS;inv!)ql;fo5Kq}f{D zuBIWqm^&WAK}%EWQ0%I%D1@+EoHo;Gy!p?1C|662`*2*Mg=h0&s6aR%1_Dn{I(V3b zcs*|GG)y?Us92!%{rRtBVtm z!Z`%@1o#bz+H7My#A2|ttgH|wq^5pRPHcw%ud6;Pk(bCyos_U}S6bu0X`0;}U(4JP>s>>?r{FYEjaC&J38|H;9zICPe^)~#_6yw8dWc3tQ`;zaK z_%K0yr;RO5w8fcQvNCa5pLX^ncAAu@H*F?}s{{z^SY;3?83=4*I8YjE(5SG{j*WkJKvWo?;;_}=)Jp*Jpq%htMig!0Fy8?NE(rX57$ z!6o@iR()Z_T82qeLGeTaT;f7BZA-t4Ac)y=J+_ADB5BK^+;=fGb*kFOzkPFZod)Ly z8%hlb#6@3k?b-js=U}zFZhz`Me=faXb|rPi@l4I6)UxI+R-U!ERd!QCKUE~%@Cctl z`k>#BHla9SMU>K{%3~hFS-XjHFPUf>hs1X=tT*)T$k`raP$&11n)rnvQ-?%M2FJ z;IlGWF~aNPuv6a`MBjNLo0JlvynGPu%TH33**-o9ddr8HhScz@lh9-&D@fg)6PKwr z;`1V?1oww!idSHBgfET4fCh*{o!LXqb!S?0SMb1z?Ng22ALnUza!J2bvOLbt6%H%) zDHaSKBGWUZ4(=k^s%|aQ4Dc&Oq@H?W?0R_y^C~*|vmpe-nB4~0Su@--!w)(dmM0v} zmB2l65e3S7JkT3c{_%wH^{Co|4%ibX+?mArI6fK5rcSF2#s{_4;UQ|=Tz@nh>E|0J zj^AG~cILkS8XWWL7c(vSy)Ji4w_dG!l|*}->La>cFTXld6S=nF2@OZz3A9rq!1ag- zvSIS3j@fg9>kfM49C1{>-4(^SFV%tqFnd9dhd|oLe_jPYC-@6@2yW-&rY}yjsxnhvRAAt+P(MK z`G_xN#48UxBzD-IQ?~FYzbNH2-3>0viZCkTBislgAE`%af_L?+7adX+ zYu=%6M@?iv%_#ifJ{yKmF(&!*$dj&o^9+xL1Pa=;^@3F4C@t#D=g$`33IxH>171py zH<&4U#=iD?r`dTf*B(yTHTRd%Ml0#;a)?eKhtkiZKMCvYrPxwO?hgwq;$>UVA_yA=kqI7r z?Yf%Ft&wbm5IHoLrA{DaWSsB_{bIc7wIdc>zLa=~)M5+ml|s7b5ZowVv7yA_S0IU; zPYAdh>z7TOx2`t&cma?K4OF1QyKi+39V8M^Oj~t^6Or21VkRP0MOdap00vVxOsXF6 zs6{J^AB7^2+tFMa7hf~NSd95O#bP16iAXWtwbo)ryo#FQh;h&V<+=Ke$%a3-8tL_K z3@2D4+|QZC+uX-a;vq2rQugBY1pokJ;c@jb{h?UF5Cs zawr6cV0cE5n1qpPN9h+U3FeI&Iqnx{4U~e#5Fm(xH1l(Z;{9o-tf&!J;2lf@G2ndV z>ey3G3e)tAB#&qdMUVw6w|@8y4sTk~2SIQ#FPOzMyrCzl#bF-k2cs2bP1!`RgV0e9 z*dxfx&Y&{~J@k;0yx|mp74xzqn**V*ehEQ#y59c}KH%~$3bZU(PAume@l`raa>O7w zzFlCpb{#fTo@sNGgZd~cKj6N2_fl;!_A|XL2GdgQyW-)P-c(^C;6Vt^G z9HH5!t+5J$>=Cx#xR!o@Z>XFK=36qUrAT1{m8X1dXa1_{&S&cQ&EGnuZJw zpU#AB;atg56Y<{0Q$o^j4Gpj7Q*{b$yE6^@=UP+J)8i=-)$3%Pew~r4%d>e8vP-as z6FCu_4=dN>zQF;~UY(qzk9wb^q-60}$a~jBWrNb2{J`O+PLBi>ie`E2?Sj|FIN7QM z_Mj)ngxO&0dwoI3q$xEisRx{B^X_ZKVPW*L-nr#ls8@D8(lxg$EiLWi)z@eE z_>@&t#;?A)%0ii#o*sGDnB>tdJajxY{HtPFD{iwZLG>Y`HtIc3vHfm1?VSOZJTx!$}7 zYqNb_y}eUwTPBU6{(*r@P@G2i+_?znQSaVnf@fd!cNar|^18>PJS?}Z#8Ju6%Uat{k0 zFo`IBe*QPUM2LXwx?w1$o#-n9k4vB(yU$32P?mSf$*{fX;6NyqBFvJl+J5}7tv%uN z>bTJF8V0Km7i~tt1>Dne1QBpsH-yO6KG%u#(Q7?B`OX$Ws-6Vu;t7wtDA%6+dn0f^Fa!N9m{nbky12ku-26sLi+|y zhzMY7%p{*uf~+C~Bl0&-(ne99v`0eLC%2}6Fo@@q5FwQ6THUj7Xa|u|H@N{!M#j56 zK`y34E~`ciIpDbOf71#}qW1kyb;Kly7nj9xzFKQUN;r`l524diPiDk=!U}Zv0rmhz zQZ}FRH)W5D6_Mh(Yb`6&PcZ!NkmBNn8J#nUVRUTI0I5{&VnNc?3=eq2oql*MKB$OC z3`|Gl*02Y&JzJ-|#I%|KBRh9!UYXz;LXN1lzsG{imNvguX+uN>ibDR-UqjCQ&0js|HdaTN&Xw3#F8T{HG&0RUcSO&2qht{EP_eH!7CLLn41%2NPqkJ6_1<}SHX-O<}xIS93J(jZ>AFW2@p!%Nx|+1s%3 zu!XmQT+lpNaO3^mdiwi#cr2KBpe1zo_EQPbZz6J9`=O*HqVlAjoRVxl070zC1nskT zu=r_Q4%Vl{9&OT_0&-PcOKg_%si9lCwzX=fTZ;9=LZz#OjZ}-3M_iL#H?pY3$9`~ENK_)fO zPky`>t13#<`%Qr8@2{s?9HG)Ia0S{buz*SsgSs>`NCwDFKKKw(e6mj_{b3MdKllju z9>ot8Z?)AeXrluU_5pT+OW-!J4txrs@&E2A8FHfkyQd`7C3Vo){~7)zV8i_e{rr8R zrJD1tll=vOC^O`mvMyFTZ9P5t4h*vW_SPC*BI|V!VUUot;_$%JYukM#0T=+h z{LxUYZ@;n8p!?1ke*mJv)x6^L7e>?k?OV#|{R5KBw6t0DmI84Xdq50?v^r?))mNT{ zavko)w1bK=WXuwe$Ljo{mf%mQ##v~K;HpSaw_cInBgs4uh_w1c0?dAs!oc(X1Z!I+ zrKjtGRt6yCAymNl0A0 zw98|#6>Tx4mKGMr{83;aH)%~6qG`s7+>IXmGn5rrn`esH@&Urh)) zJUSKujDyp{Ajf29b{p%k8XDi1UQ6yQw*jmvhpXETU`;}Vqm~kkTsLBOZF{{|a`2zQbLWoR zUW#5Z0>Q_X+5Dla>kWojVuIw9lmx~1qmIQ~N04^vR_&~nX`&F1_U_&RWJ5@7O<(Z$ zVw;@mS(qjQv%QH$5>F$lYE|+N9!x`Qjo}eVi}BZa@yGk1Wgezn?Q_hRhBx5P_7F$Z z<7|i-yN~b5RQ+6V7GwG;YMCD%Y@o_12t7SpskGtHvH86KUZ3#Z-ki1)(0a7G8S2Vz{8Z zR}c4r0(h_1k^H;x2og_V9@cuq>!agF=!LZhb zTD{oN^CuiRS3h7LK6r4{U+v>nn+&k`4_bwLZ*T9}vuDXylBgfOY>B-R(*nW-upm}; zgxu>YP(q^G$Fl9khUI1ZYxw({c0ei6!*yT~0bUJ_zTV!eevFgWjEi-Wu5%dsi;Nr} ztT7ih4L&6#v^iq-hq1rqfY$fN$4+aw7gh7c?VmvaBs+}C#J>%fc5(cBxEz<1%m?N1 zYFhmn+d_c6?bKj}?@tT3k{6!$^#|}{A;UkvLXbX|zls$7$bkD_bp`J}@5}eUU;Xbt zjY08gNjqEH6219L;~!8vK$S(x)&;Hrx_>RWr&(s^q-B2Hl z6#ubf$4nw0-FMkhmCW2w70W{7O)j+77HxEm(mA=*G0M;^bkm#|u0paxn{ABmsH6z7{-J0Sk@)!qkCh6pzBRWP5fmb!Y5!57RZIkF=%U$V3dnht8x zjY8omi-!+OhM$sx)D=Y+D#~pY1p$z6RAf}`(`Qw_0}KV_iT32*#Om`|(sKI5mfzCo zSXV*3%7UXYcmY-5N!f#$q-y8;!IJ1ddh`eiAnyX+(TCFU=$-R`Q$7VF(OY08qs1-X zacjDi>Y*bk8uj7Mr8W6rb5%`E4Xk?R-9Mg7&5}`C7#ts#L@88YWW)O8j8|{KQvpC$yP;n6@-GKdT&oFK;UmrSg^A)TM)3A}S*%#}0z#H(8`^Kp`fN zU9gE$^-4FNA5})zN%PvZZ(Io<&KiDwPDo0FmcK2BVq8GX6Xz`;$*SGH>C$+C4qr$^ zp5tt9Ewe}eFIzJT3Ghnjy#x^f;0=m8bJ%krbQ?Rn+uM(KqQFlxP-w@2kKHjM5$O53 z1hwuHii)&6;J?kMq5}uJ{a@+(mdK*T2!^QuM=Xr zLz9yMYN6ssGfnGVV4$=t9!r=Dc$J>Pddy`v@b!Th`<;3CD7y~S@P##&fE2zYPGq^G zwKdD4?|k`?3Xpv(RB(R=qU!eEIAB4!H%#9V+42v7?tc0y+@GABglgdx3$@JiD=y6L z>m#5@CHJBQ=s0)&yad1`$cNAa-ECqr-YUm@g6t42&+WG%A+%(N zppun7cwnZX4mqF)y$q+dxd9az49acbhXC43`1FZar=VrTz~-=l3R=9*7X)rd`L;1Y zURU^bu~SCdq*2-X*Vf^+fu6Qtg3WvZi;-V3GH`0=Cl|bl1LPDTDJk~3jq0>Mkf`_SA7ZxGCwM!y47Kwf@ z?)sVL4kJuBMAxwgJTOV85gF@NSz5SMR2P-9_Zve;*0u&L*FXzp6#fna6$CS!NXgF5 zj*hPQxq$j_U{za(64EDR)wUQ~{)18s)E;^r`l|yGzH63mc7S#o{o@LX|AJ+I zLFLxI=|U;WcYwJbM#sgC!6H!*U_kUVfsZ#EP_d5>iO>Fn1CFBpCNLt&#hBhSk29Pz zZ*P1r1nHlf#tp&VbpfZZvnz(a4G#Xjv~j=bLr;5q+}?I)nl@y)ep_B%&dtpwY*!mt zScT>t$)G$$=S$S162#i)#X(b{cdw*mlobIE0QC$B&6^<}8zG~kM(LvHoF@L#m3B|2 zVI^2W_C3ZS-gPrQIe8aQeh1N5l9_1@7(?!aLpxez?bWMSptg$!EU7Nd=C-}s^X$_1 z*a5$&Gw`OzVqlb4-Bd>kBqaZ6Zy#H5mKg)Vq6?+PQD1GJW$|p{M?c#_9dLYx@jEsO z)}krOV5Gsw(EDMAc31NOYB_AJ&cZ!_ooMFS;G=QxIzSs9Z%&Bb+S(v4cbaNXLNB;j zfqo&q&ZQL1mVFLs%+RhLKuX++l8xWtFyNb-nvnP#3L+n@+moy)`~uW=-fFPFzn_uh zh0MM2rU=lVAZN?|d?n4>DA()E(BFfsw_Q}Dw7zkVE6p)$iwBW;-`IFk(r&ooNtw4a zkv&XRG(vec57PazjeWfy_I>{T%NBImWmgZF2}oLd;qo<@I4>vXI^3a=YxDDJMpwfT zbcp{MqmFI;Y0!6;`K}-_d;150zrg5+7Q%DK7Ubz{f8i3UPG@GY{-Cj>cRXzE>~gZR z(G7+C@3W^*!!g>Jw?p&#Irm>L)Gm7$O&m92JSN*3&jv}uyFF{;r}hR>`xAt5jOql4 z=Zi~?LWTR{ro!t$wq!m7cXt#-PHLPafI$EWtO8a$e$G6|>tTO^+TKK?Q1f;r^DbEA zo0bG(fS~n3dBLNcAtTTO3Rm`9u7QMQU|`VY>r&u|XrJ~}zi|T)lWN&&ch+5S9Gti8 zzkT~QCo39cfMWw0ZrG7E;8(OnJxajv4=thyks!c9Pyce+UpwyMBwSOXsG#r&q&-?P z6TOrHA|{)1phDqDLMfmvc=~!hM--1<$vWtiPRZ|0O?r9e9k2t-fl=FWDJc&Y$LeKe zWi?^gkd-L`dJsLyFtj^6lzX^3P+26Ytjrx0=aBoBg`8Zi;p2Mn(FX(sphO7X3iMjp zU%}eTCw!>f=K-<~{rIs69YGD?awbS&KT|hULPVm4@wrUR>R|>S`vAYztw6w(h zXv`l5b90XqOat%(fMP72i1h_v@WCX??Q@r-R8(_5FfGgCYfy1FrL30;bjjC0e-^*$j#u%s+s!vFPnCpZhEunwmNXHL;(D zhKk|nLM@Z)!-dgmfCS{8ci{yftdzvWVIS1G#3{En>7rvlXa*F2W!wJS|9b_q>#;HA V;c()a_x|1~$STXEUom+4zX1N`pFIEo literal 0 HcmV?d00001 diff --git a/sensing/autoware_pointcloud_preprocessor/docs/image/noise_timestamp_offset.drawio.svg b/sensing/autoware_pointcloud_preprocessor/docs/image/noise_timestamp_offset.drawio.svg new file mode 100644 index 0000000000000..bf5d604d2fb94 --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/docs/image/noise_timestamp_offset.drawio.svg @@ -0,0 +1,2023 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 0.01 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 0.05 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 0.09 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+ reference +
stamp
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 0 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 20 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 40 +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+ reference +
stamp
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ minus offset 20 ms +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ minus offset 40 ms +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + +
+
+
-5ms
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+10ms
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
5
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
-5
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
-5
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
-10
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
5
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
10
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + +
+
+
+ minus offset 40 ms +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
-15
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
-5
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
5
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
15
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + +
+
+
-15ms
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ minus offset 80 ms +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
-10
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
10
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
5
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
-5
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + +
+
+
+5ms
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+10ms
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
10
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
-10
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
-10
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
10
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
15
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
-15
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + +
+
+
-15ms
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ ideal timestamp +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+ first arrive pointcloud +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+ reference timestamp +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
real timestamp
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+ possible reference timestamp +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+ possible timestamp +
for non-first pointcloud
+
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + +
+
+
+ timestamp of non-first pointcloud +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ lidar_timestamp_offset: [0.0, 0.04, 0.08] +
+ + lidar_timestamp_noise_window: [0.005, 0.01, 0.015] +
+
+
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ + Case 2 + +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ + Case 1 + +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 0.01 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 0.05 +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ 0.09 +
+
+
+
+ +
+
+
+
+
+
+
+
diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp new file mode 100644 index 0000000000000..13604569df9a8 --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp @@ -0,0 +1,89 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#pragma once + +#include "combine_cloud_handler.hpp" + +#include +#include +#include + +namespace autoware::pointcloud_preprocessor +{ + +class PointCloudConcatenateDataSynchronizerComponent; +class CombineCloudHandler; + +struct CollectorInfoBase +{ + virtual ~CollectorInfoBase() = default; +}; + +struct NaiveCollectorInfo : public CollectorInfoBase +{ + double timestamp; + + explicit NaiveCollectorInfo(double timestamp = 0.0) : timestamp(timestamp) {} +}; + +struct AdvancedCollectorInfo : public CollectorInfoBase +{ + double timestamp; + double noise_window; + + explicit AdvancedCollectorInfo(double timestamp = 0.0, double noise_window = 0.0) + : timestamp(timestamp), noise_window(noise_window) + { + } +}; + +class CloudCollector +{ +public: + CloudCollector( + std::shared_ptr && ros2_parent_node, + std::shared_ptr & combine_cloud_handler, int num_of_clouds, + double timeout_sec, bool debug_mode); + bool topic_exists(const std::string & topic_name); + bool process_pointcloud( + const std::string & topic_name, sensor_msgs::msg::PointCloud2::SharedPtr cloud); + void concatenate_callback(); + + ConcatenatedCloudResult concatenate_pointclouds( + std::unordered_map topic_to_cloud_map); + + std::unordered_map + get_topic_to_cloud_map(); + + [[nodiscard]] bool concatenate_finished() const; + + void set_info(std::shared_ptr collector_info); + [[nodiscard]] std::shared_ptr get_info() const; + void show_debug_message(); + +private: + std::shared_ptr ros2_parent_node_; + std::shared_ptr combine_cloud_handler_; + rclcpp::TimerBase::SharedPtr timer_; + std::unordered_map topic_to_cloud_map_; + uint64_t num_of_clouds_; + double timeout_sec_; + bool debug_mode_; + bool concatenate_finished_{false}; + std::mutex concatenate_mutex_; + std::shared_ptr collector_info_; +}; + +} // namespace autoware::pointcloud_preprocessor diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/collector_matching_strategy.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/collector_matching_strategy.hpp new file mode 100644 index 0000000000000..c314b24a07921 --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/collector_matching_strategy.hpp @@ -0,0 +1,81 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#pragma once + +#include "cloud_collector.hpp" + +#include + +#include + +#include +#include +#include +#include +#include +#include + +namespace autoware::pointcloud_preprocessor +{ + +struct MatchingParams +{ + std::string topic_name; + double cloud_timestamp; + double cloud_arrival_time; +}; + +class CollectorMatchingStrategy +{ +public: + virtual ~CollectorMatchingStrategy() = default; + + [[nodiscard]] virtual std::optional> match_cloud_to_collector( + const std::list> & cloud_collectors, + const MatchingParams & params) const = 0; + virtual void set_collector_info( + std::shared_ptr & collector, const MatchingParams & matching_params) = 0; +}; + +class NaiveMatchingStrategy : public CollectorMatchingStrategy +{ +public: + explicit NaiveMatchingStrategy(rclcpp::Node & node); + [[nodiscard]] std::optional> match_cloud_to_collector( + const std::list> & cloud_collectors, + const MatchingParams & params) const override; + void set_collector_info( + std::shared_ptr & collector, const MatchingParams & matching_params) override; +}; + +class AdvancedMatchingStrategy : public CollectorMatchingStrategy +{ +public: + explicit AdvancedMatchingStrategy(rclcpp::Node & node, std::vector input_topics); + + [[nodiscard]] std::optional> match_cloud_to_collector( + const std::list> & cloud_collectors, + const MatchingParams & params) const override; + void set_collector_info( + std::shared_ptr & collector, const MatchingParams & matching_params) override; + +private: + std::unordered_map topic_to_offset_map_; + std::unordered_map topic_to_noise_window_map_; +}; + +std::shared_ptr parse_matching_strategy(rclcpp::Node & node); + +} // namespace autoware::pointcloud_preprocessor diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp new file mode 100644 index 0000000000000..fa8c58aa74c11 --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp @@ -0,0 +1,110 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#pragma once + +#include +#include +#include +#include +#include +#include + +// ROS includes +#include "autoware/point_types/types.hpp" + +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +namespace autoware::pointcloud_preprocessor +{ +using autoware::point_types::PointXYZIRC; +using point_cloud_msg_wrapper::PointCloud2Modifier; + +struct ConcatenatedCloudResult +{ + sensor_msgs::msg::PointCloud2::SharedPtr concatenate_cloud_ptr{nullptr}; + std::optional> + topic_to_transformed_cloud_map; + std::unordered_map topic_to_original_stamp_map; +}; + +class CombineCloudHandler +{ +private: + rclcpp::Node & node_; + + std::string output_frame_; + bool is_motion_compensated_; + bool publish_synchronized_pointcloud_; + bool keep_input_frame_in_synchronized_pointcloud_; + std::unique_ptr managed_tf_buffer_{nullptr}; + + std::deque twist_queue_; + + /// @brief RclcppTimeHash structure defines a custom hash function for the rclcpp::Time type by + /// using its nanoseconds representation as the hash value. + struct RclcppTimeHash + { + std::size_t operator()(const rclcpp::Time & t) const + { + return std::hash()(t.nanoseconds()); + } + }; + + static void convert_to_xyzirc_cloud( + const sensor_msgs::msg::PointCloud2::SharedPtr & input_cloud, + sensor_msgs::msg::PointCloud2::SharedPtr & xyzirc_cloud); + + void correct_pointcloud_motion( + const std::shared_ptr & transformed_cloud_ptr, + const std::vector & pc_stamps, + std::unordered_map & transform_memo, + std::shared_ptr transformed_delay_compensated_cloud_ptr); + +public: + CombineCloudHandler( + rclcpp::Node & node, std::string output_frame, bool is_motion_compensated, + bool publish_synchronized_pointcloud, bool keep_input_frame_in_synchronized_pointcloud, + bool has_static_tf_only); + void process_twist( + const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr & twist_msg); + void process_odometry(const nav_msgs::msg::Odometry::ConstSharedPtr & odometry_msg); + + ConcatenatedCloudResult combine_pointclouds( + std::unordered_map & topic_to_cloud_map); + + Eigen::Matrix4f compute_transform_to_adjust_for_old_timestamp( + const rclcpp::Time & old_stamp, const rclcpp::Time & new_stamp); + + std::deque get_twist_queue(); +}; + +} // namespace autoware::pointcloud_preprocessor diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp new file mode 100644 index 0000000000000..654593e317ad9 --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp @@ -0,0 +1,124 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#pragma once + +#include +#include +#include +#include +#include +#include + +// ROS includes +#include "cloud_collector.hpp" +#include "collector_matching_strategy.hpp" +#include "combine_cloud_handler.hpp" + +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +namespace autoware::pointcloud_preprocessor +{ +class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node +{ +public: + explicit PointCloudConcatenateDataSynchronizerComponent(const rclcpp::NodeOptions & node_options); + ~PointCloudConcatenateDataSynchronizerComponent() override = default; + void publish_clouds( + ConcatenatedCloudResult && concatenated_cloud_result, + std::shared_ptr collector_info); + void manage_collector_list(); + std::list> get_cloud_collectors(); + void add_cloud_collector(const std::shared_ptr & collector); + +private: + struct Parameters + { + bool use_naive_approach; + bool debug_mode; + bool has_static_tf_only; + double rosbag_length; + int maximum_queue_size; + double timeout_sec; + bool is_motion_compensated; + bool publish_synchronized_pointcloud; + bool keep_input_frame_in_synchronized_pointcloud; + bool publish_previous_but_late_pointcloud; + std::string synchronized_pointcloud_postfix; + std::string input_twist_topic_type; + std::vector input_topics; + std::string output_frame; + std::string matching_strategy; + } params_; + + double current_concatenate_cloud_timestamp_{0.0}; + double latest_concatenate_cloud_timestamp_{0.0}; + bool drop_previous_but_late_pointcloud_{false}; + bool publish_pointcloud_{false}; + bool is_concatenated_cloud_empty_{false}; + std::shared_ptr diagnostic_collector_info_; + std::unordered_map diagnostic_topic_to_original_stamp_map_; + + std::shared_ptr combine_cloud_handler_; + std::list> cloud_collectors_; + std::unique_ptr collector_matching_strategy_; + std::mutex cloud_collectors_mutex_; + + // default postfix name for synchronized pointcloud + static constexpr const char * default_sync_topic_postfix = "_synchronized"; + + // subscribers + std::vector::SharedPtr> pointcloud_subs_; + rclcpp::Subscription::SharedPtr twist_sub_; + rclcpp::Subscription::SharedPtr odom_sub_; + + // publishers + rclcpp::Publisher::SharedPtr concatenated_cloud_publisher_; + std::unordered_map::SharedPtr> + topic_to_transformed_cloud_publisher_map_; + std::unique_ptr debug_publisher_; + + std::unique_ptr> stop_watch_ptr_; + diagnostic_updater::Updater diagnostic_updater_{this}; + + void cloud_callback( + const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, const std::string & topic_name); + void twist_callback(const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr input); + void odom_callback(const nav_msgs::msg::Odometry::ConstSharedPtr input); + + static std::string format_timestamp(double timestamp); + void check_concat_status(diagnostic_updater::DiagnosticStatusWrapper & stat); + std::string replace_sync_topic_name_postfix( + const std::string & original_topic_name, const std::string & postfix); +}; + +} // namespace autoware::pointcloud_preprocessor diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp deleted file mode 100644 index 6164e85c35717..0000000000000 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp +++ /dev/null @@ -1,197 +0,0 @@ -// Copyright 2023 TIER IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2009, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage, Inc. nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - * $Id: concatenate_data.cpp 35231 2011-01-14 05:33:20Z rusu $ - * - */ - -#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CONCATENATE_AND_TIME_SYNC_NODELET_HPP_ -#define AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CONCATENATE_AND_TIME_SYNC_NODELET_HPP_ - -#include -#include -#include -#include -#include -#include -#include - -// ROS includes -#include "autoware/point_types/types.hpp" - -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include - -namespace autoware::pointcloud_preprocessor -{ -using autoware::point_types::PointXYZIRC; -using point_cloud_msg_wrapper::PointCloud2Modifier; - -/** \brief @b PointCloudConcatenateDataSynchronizerComponent is a special form of data - * synchronizer: it listens for a set of input PointCloud messages on the same topic, - * checks their timestamps, and concatenates their fields together into a single - * PointCloud output message. - * \author Radu Bogdan Rusu - */ -class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node -{ -public: - typedef sensor_msgs::msg::PointCloud2 PointCloud2; - - /** \brief constructor. */ - explicit PointCloudConcatenateDataSynchronizerComponent(const rclcpp::NodeOptions & node_options); - - /** \brief constructor. - * \param queue_size the maximum queue size - */ - PointCloudConcatenateDataSynchronizerComponent( - const rclcpp::NodeOptions & node_options, int queue_size); - - /** \brief Empty destructor. */ - virtual ~PointCloudConcatenateDataSynchronizerComponent() {} - -private: - /** \brief The output PointCloud publisher. */ - rclcpp::Publisher::SharedPtr pub_output_; - /** \brief Delay Compensated PointCloud publisher*/ - std::map::SharedPtr> - transformed_raw_pc_publisher_map_; - - /** \brief The maximum number of messages that we can store in the queue. */ - int maximum_queue_size_ = 3; - - double timeout_sec_ = 0.1; - - bool publish_synchronized_pointcloud_; - bool keep_input_frame_in_synchronized_pointcloud_; - std::string synchronized_pointcloud_postfix_; - - std::set not_subscribed_topic_names_; - - /** \brief A vector of subscriber. */ - std::vector::SharedPtr> filters_; - - rclcpp::Subscription::SharedPtr sub_twist_; - rclcpp::Subscription::SharedPtr sub_odom_; - - rclcpp::TimerBase::SharedPtr timer_; - diagnostic_updater::Updater updater_{this}; - - const std::string input_twist_topic_type_; - - /** \brief Output TF frame the concatenated points should be transformed to. */ - std::string output_frame_; - - /** \brief The flag to indicate if only static TF are used. */ - bool has_static_tf_only_; - - /** \brief Input point cloud topics. */ - // XmlRpc::XmlRpcValue input_topics_; - std::vector input_topics_; - - std::unique_ptr managed_tf_buffer_{nullptr}; - - std::deque twist_ptr_queue_; - - std::map cloud_stdmap_; - std::map cloud_stdmap_tmp_; - std::mutex mutex_; - - std::vector input_offset_; - std::map offset_map_; - - Eigen::Matrix4f computeTransformToAdjustForOldTimestamp( - const rclcpp::Time & old_stamp, const rclcpp::Time & new_stamp); - std::map combineClouds( - sensor_msgs::msg::PointCloud2::SharedPtr & concat_cloud_ptr); - void publish(); - - void convertToXYZIRCCloud( - const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, - sensor_msgs::msg::PointCloud2::SharedPtr & output_ptr); - void setPeriod(const int64_t new_period); - void cloud_callback( - const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_ptr, - const std::string & topic_name); - void twist_callback(const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr input); - void odom_callback(const nav_msgs::msg::Odometry::ConstSharedPtr input); - void timer_callback(); - - void checkConcatStatus(diagnostic_updater::DiagnosticStatusWrapper & stat); - std::string replaceSyncTopicNamePostfix( - const std::string & original_topic_name, const std::string & postfix); - - /** \brief processing time publisher. **/ - std::unique_ptr> stop_watch_ptr_; - std::unique_ptr debug_publisher_; -}; - -} // namespace autoware::pointcloud_preprocessor - -// clang-format off -#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__CONCATENATE_DATA__CONCATENATE_AND_TIME_SYNC_NODELET_HPP_ // NOLINT -// clang-format on diff --git a/sensing/autoware_pointcloud_preprocessor/launch/concatenate_and_time_sync_node.launch.xml b/sensing/autoware_pointcloud_preprocessor/launch/concatenate_and_time_sync_node.launch.xml new file mode 100644 index 0000000000000..f553c15f01210 --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/launch/concatenate_and_time_sync_node.launch.xml @@ -0,0 +1,11 @@ + + + + + + + + + + + diff --git a/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json new file mode 100644 index 0000000000000..c3758d05a8349 --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/schema/concatenate_and_time_sync_node.schema.json @@ -0,0 +1,163 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Concatenate and Time Synchronize Node", + "type": "object", + "definitions": { + "concatenate_and_time_sync_node": { + "type": "object", + "properties": { + "debug_mode": { + "type": "boolean", + "default": false, + "description": "Flag to enables debug mode to display additional logging information." + }, + "has_static_tf_only": { + "type": "boolean", + "default": false, + "description": "Flag to indicate if only static TF is used." + }, + "rosbag_length": { + "type": "number", + "default": 10.0, + "minimum": 0.0, + "description": " This value determine if the rosbag has started from the beginning again. The value should be set smaller than the actual length of the bag." + }, + "maximum_queue_size": { + "type": "integer", + "default": "5", + "minimum": 1, + "description": "Maximum size of the queue for the Keep Last policy in QoS history." + }, + "timeout_sec": { + "type": "number", + "default": "0.1", + "minimum": 0.001, + "description": "Timer's timeout duration in seconds when collectors are created. Collectors will concatenate the point clouds when timeout_sec reaches zero." + }, + "is_motion_compensated": { + "type": "boolean", + "default": true, + "description": "Flag to indicate if motion compensation is enabled." + }, + "publish_synchronized_pointcloud": { + "type": "boolean", + "default": true, + "description": "Flag to indicate if synchronized point cloud should be published." + }, + "keep_input_frame_in_synchronized_pointcloud": { + "type": "boolean", + "default": true, + "description": "Flag to indicate if input frame should be kept in synchronized point cloud." + }, + "publish_previous_but_late_pointcloud": { + "type": "boolean", + "default": false, + "description": "Flag to indicate if a concatenated point cloud should be published if its timestamp is earlier than the previous published concatenated point cloud." + }, + "synchronized_pointcloud_postfix": { + "type": "string", + "default": "pointcloud", + "description": "Postfix for the topic name of the synchronized point cloud." + }, + "input_twist_topic_type": { + "type": "string", + "enum": ["twist", "odom"], + "default": "twist", + "description": "Type of the input twist topic." + }, + "input_topics": { + "type": "array", + "items": { + "type": "string", + "minLength": 1 + }, + "default": ["cloud_topic1", "cloud_topic2", "cloud_topic3"], + "minItems": 2, + "description": "List of input point cloud topics." + }, + "output_frame": { + "type": "string", + "default": "base_link", + "minLength": 1, + "description": "Output frame." + }, + "matching_strategy": { + "type": "object", + "properties": { + "type": { + "type": "string", + "enum": ["naive", "advanced"], + "default": "advanced", + "description": "Set it to `advanced` if you can synchronize your LiDAR sensor; otherwise, set it to `naive`." + }, + "lidar_timestamp_offsets": { + "type": "array", + "items": { + "type": "number", + "minimum": 0.0 + }, + "default": [0.0, 0.0, 0.0], + "minItems": 2, + "description": "List of LiDAR timestamp offsets in seconds (relative to the earliest LiDAR timestamp). The offsets should be provided in the same order as the input topics." + }, + "lidar_timestamp_noise_window": { + "type": "array", + "items": { + "type": "number", + "minimum": 0.0 + }, + "default": [0.01, 0.01, 0.01], + "minItems": 2, + "description": "List of LiDAR timestamp noise windows in seconds. The noise values should be specified in the same order as the input_topics." + } + }, + "required": ["type"], + "dependencies": { + "type": { + "oneOf": [ + { + "properties": { "type": { "const": "naive" } }, + "not": { + "required": ["lidar_timestamp_offsets", "lidar_timestamp_noise_window"] + } + }, + { + "properties": { "type": { "const": "advanced" } }, + "required": ["lidar_timestamp_offsets", "lidar_timestamp_noise_window"] + } + ] + } + } + } + }, + "required": [ + "debug_mode", + "has_static_tf_only", + "rosbag_length", + "maximum_queue_size", + "timeout_sec", + "is_motion_compensated", + "publish_synchronized_pointcloud", + "keep_input_frame_in_synchronized_pointcloud", + "publish_previous_but_late_pointcloud", + "synchronized_pointcloud_postfix", + "input_twist_topic_type", + "input_topics", + "output_frame", + "matching_strategy" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/concatenate_and_time_sync_node" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp new file mode 100644 index 0000000000000..63ee23d204788 --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/cloud_collector.cpp @@ -0,0 +1,156 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp" + +#include "autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp" +#include "autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp" + +#include + +#include +#include +#include +#include + +namespace autoware::pointcloud_preprocessor +{ + +CloudCollector::CloudCollector( + std::shared_ptr && ros2_parent_node, + std::shared_ptr & combine_cloud_handler, int num_of_clouds, + double timeout_sec, bool debug_mode) +: ros2_parent_node_(std::move(ros2_parent_node)), + combine_cloud_handler_(combine_cloud_handler), + num_of_clouds_(num_of_clouds), + timeout_sec_(timeout_sec), + debug_mode_(debug_mode) +{ + const auto period_ns = std::chrono::duration_cast( + std::chrono::duration(timeout_sec_)); + + timer_ = + rclcpp::create_timer(ros2_parent_node_, ros2_parent_node_->get_clock(), period_ns, [this]() { + std::lock_guard concatenate_lock(concatenate_mutex_); + if (concatenate_finished_) return; + concatenate_callback(); + }); +} + +void CloudCollector::set_info(std::shared_ptr collector_info) +{ + collector_info_ = std::move(collector_info); +} + +std::shared_ptr CloudCollector::get_info() const +{ + return collector_info_; +} + +bool CloudCollector::topic_exists(const std::string & topic_name) +{ + return topic_to_cloud_map_.find(topic_name) != topic_to_cloud_map_.end(); +} + +bool CloudCollector::process_pointcloud( + const std::string & topic_name, sensor_msgs::msg::PointCloud2::SharedPtr cloud) +{ + std::lock_guard concatenate_lock(concatenate_mutex_); + if (concatenate_finished_) return false; + + // Check if the map already contains an entry for the same topic. This shouldn't happen if the + // parameter 'lidar_timestamp_noise_window' is set correctly. + if (topic_to_cloud_map_.find(topic_name) != topic_to_cloud_map_.end()) { + RCLCPP_WARN_STREAM_THROTTLE( + ros2_parent_node_->get_logger(), *ros2_parent_node_->get_clock(), + std::chrono::milliseconds(10000).count(), + "Topic '" << topic_name + << "' already exists in the collector. Check the timestamp of the pointcloud."); + } + topic_to_cloud_map_[topic_name] = cloud; + if (topic_to_cloud_map_.size() == num_of_clouds_) { + concatenate_callback(); + } + + return true; +} + +bool CloudCollector::concatenate_finished() const +{ + return concatenate_finished_; +} + +void CloudCollector::concatenate_callback() +{ + if (debug_mode_) { + show_debug_message(); + } + + // All pointclouds are received or the timer has timed out, cancel the timer and concatenate the + // pointclouds in the collector. + timer_->cancel(); + + auto concatenated_cloud_result = concatenate_pointclouds(topic_to_cloud_map_); + + ros2_parent_node_->publish_clouds(std::move(concatenated_cloud_result), collector_info_); + + concatenate_finished_ = true; +} + +ConcatenatedCloudResult CloudCollector::concatenate_pointclouds( + std::unordered_map topic_to_cloud_map) +{ + return combine_cloud_handler_->combine_pointclouds(topic_to_cloud_map); +} + +std::unordered_map +CloudCollector::get_topic_to_cloud_map() +{ + return topic_to_cloud_map_; +} + +void CloudCollector::show_debug_message() +{ + auto time_until_trigger = timer_->time_until_trigger(); + std::stringstream log_stream; + log_stream << std::fixed << std::setprecision(6); + log_stream << "Collector's concatenate callback time: " + << ros2_parent_node_->get_clock()->now().seconds() << " seconds\n"; + + if (auto advanced_info = std::dynamic_pointer_cast(collector_info_)) { + log_stream << "Advanced strategy:\n Collector's reference time min: " + << advanced_info->timestamp - advanced_info->noise_window + << " to max: " << advanced_info->timestamp + advanced_info->noise_window + << " seconds\n"; + } else if (auto naive_info = std::dynamic_pointer_cast(collector_info_)) { + log_stream << "Naive strategy:\n Collector's timestamp: " << naive_info->timestamp + << " seconds\n"; + } + + log_stream << "Time until trigger: " << (time_until_trigger.count() / 1e9) << " seconds\n"; + + log_stream << "Pointclouds: ["; + std::string separator = ""; + for (const auto & [topic, cloud] : topic_to_cloud_map_) { + log_stream << separator; + log_stream << "[" << topic << ", " << rclcpp::Time(cloud->header.stamp).seconds() << "]"; + separator = ", "; + } + + log_stream << "]\n"; + + RCLCPP_INFO(ros2_parent_node_->get_logger(), "%s", log_stream.str().c_str()); +} + +} // namespace autoware::pointcloud_preprocessor diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/collector_matching_strategy.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/collector_matching_strategy.cpp new file mode 100644 index 0000000000000..50058df3d91af --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/collector_matching_strategy.cpp @@ -0,0 +1,121 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp" + +#include +#include + +#include +#include +#include +#include +#include + +namespace autoware::pointcloud_preprocessor +{ + +NaiveMatchingStrategy::NaiveMatchingStrategy(rclcpp::Node & node) +{ + RCLCPP_INFO(node.get_logger(), "Utilize naive matching strategy"); +} + +std::optional> NaiveMatchingStrategy::match_cloud_to_collector( + const std::list> & cloud_collectors, + const MatchingParams & params) const +{ + std::optional smallest_time_difference = std::nullopt; + std::shared_ptr closest_collector = nullptr; + + for (const auto & cloud_collector : cloud_collectors) { + if (!cloud_collector->topic_exists(params.topic_name)) { + auto info = cloud_collector->get_info(); + if (auto naive_info = std::dynamic_pointer_cast(info)) { + double time_difference = std::abs(params.cloud_arrival_time - naive_info->timestamp); + if (!smallest_time_difference || time_difference < smallest_time_difference) { + smallest_time_difference = time_difference; + closest_collector = cloud_collector; + } + } + } + } + + if (closest_collector != nullptr) { + return closest_collector; + } + return std::nullopt; +} + +void NaiveMatchingStrategy::set_collector_info( + std::shared_ptr & collector, const MatchingParams & matching_params) +{ + auto info = std::make_shared(matching_params.cloud_arrival_time); + collector->set_info(info); +} + +AdvancedMatchingStrategy::AdvancedMatchingStrategy( + rclcpp::Node & node, std::vector input_topics) +{ + auto lidar_timestamp_offsets = + node.declare_parameter>("matching_strategy.lidar_timestamp_offsets"); + auto lidar_timestamp_noise_window = + node.declare_parameter>("matching_strategy.lidar_timestamp_noise_window"); + + if (lidar_timestamp_offsets.size() != input_topics.size()) { + throw std::runtime_error( + "The number of topics does not match the number of timestamp offsets."); + } + if (lidar_timestamp_noise_window.size() != input_topics.size()) { + throw std::runtime_error( + "The number of topics does not match the number of timestamp noise window."); + } + + for (size_t i = 0; i < input_topics.size(); i++) { + topic_to_offset_map_[input_topics[i]] = lidar_timestamp_offsets[i]; + topic_to_noise_window_map_[input_topics[i]] = lidar_timestamp_noise_window[i]; + } + + RCLCPP_INFO(node.get_logger(), "Utilize advanced matching strategy"); +} + +std::optional> AdvancedMatchingStrategy::match_cloud_to_collector( + const std::list> & cloud_collectors, + const MatchingParams & params) const +{ + for (const auto & cloud_collector : cloud_collectors) { + auto info = cloud_collector->get_info(); + if (auto advanced_info = std::dynamic_pointer_cast(info)) { + auto reference_timestamp_min = advanced_info->timestamp - advanced_info->noise_window; + auto reference_timestamp_max = advanced_info->timestamp + advanced_info->noise_window; + double time = params.cloud_timestamp - topic_to_offset_map_.at(params.topic_name); + if ( + time < reference_timestamp_max + topic_to_noise_window_map_.at(params.topic_name) && + time > reference_timestamp_min - topic_to_noise_window_map_.at(params.topic_name)) { + return cloud_collector; + } + } + } + return std::nullopt; +} + +void AdvancedMatchingStrategy::set_collector_info( + std::shared_ptr & collector, const MatchingParams & matching_params) +{ + auto info = std::make_shared( + matching_params.cloud_timestamp - topic_to_offset_map_.at(matching_params.topic_name), + topic_to_noise_window_map_[matching_params.topic_name]); + collector->set_info(info); +} + +} // namespace autoware::pointcloud_preprocessor diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp new file mode 100644 index 0000000000000..d68218314830b --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/combine_cloud_handler.cpp @@ -0,0 +1,336 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp" + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +namespace autoware::pointcloud_preprocessor +{ + +CombineCloudHandler::CombineCloudHandler( + rclcpp::Node & node, std::string output_frame, bool is_motion_compensated, + bool publish_synchronized_pointcloud, bool keep_input_frame_in_synchronized_pointcloud, + bool has_static_tf_only) +: node_(node), + output_frame_(std::move(output_frame)), + is_motion_compensated_(is_motion_compensated), + publish_synchronized_pointcloud_(publish_synchronized_pointcloud), + keep_input_frame_in_synchronized_pointcloud_(keep_input_frame_in_synchronized_pointcloud), + managed_tf_buffer_( + std::make_unique(&node_, has_static_tf_only)) +{ +} + +void CombineCloudHandler::process_twist( + const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr & twist_msg) +{ + geometry_msgs::msg::TwistStamped msg; + msg.header = twist_msg->header; + msg.twist = twist_msg->twist.twist; + + // If time jumps backwards (e.g. when a rosbag restarts), clear buffer + if (!twist_queue_.empty()) { + if (rclcpp::Time(twist_queue_.front().header.stamp) > rclcpp::Time(msg.header.stamp)) { + twist_queue_.clear(); + } + } + + // Twist data in the queue that is older than the current twist by 1 second will be cleared. + auto cutoff_time = rclcpp::Time(msg.header.stamp) - rclcpp::Duration::from_seconds(1.0); + + while (!twist_queue_.empty()) { + if (rclcpp::Time(twist_queue_.front().header.stamp) > cutoff_time) { + break; + } + twist_queue_.pop_front(); + } + + twist_queue_.push_back(msg); +} + +void CombineCloudHandler::process_odometry( + const nav_msgs::msg::Odometry::ConstSharedPtr & odometry_msg) +{ + geometry_msgs::msg::TwistStamped msg; + msg.header = odometry_msg->header; + msg.twist = odometry_msg->twist.twist; + + // If time jumps backwards (e.g. when a rosbag restarts), clear buffer + if (!twist_queue_.empty()) { + if (rclcpp::Time(twist_queue_.front().header.stamp) > rclcpp::Time(msg.header.stamp)) { + twist_queue_.clear(); + } + } + + // Twist data in the queue that is older than the current twist by 1 second will be cleared. + auto cutoff_time = rclcpp::Time(msg.header.stamp) - rclcpp::Duration::from_seconds(1.0); + + while (!twist_queue_.empty()) { + if (rclcpp::Time(twist_queue_.front().header.stamp) > cutoff_time) { + break; + } + twist_queue_.pop_front(); + } + + twist_queue_.push_back(msg); +} + +std::deque CombineCloudHandler::get_twist_queue() +{ + return twist_queue_; +} + +void CombineCloudHandler::convert_to_xyzirc_cloud( + const sensor_msgs::msg::PointCloud2::SharedPtr & input_cloud, + sensor_msgs::msg::PointCloud2::SharedPtr & xyzirc_cloud) +{ + xyzirc_cloud->header = input_cloud->header; + + PointCloud2Modifier output_modifier{ + *xyzirc_cloud, input_cloud->header.frame_id}; + output_modifier.reserve(input_cloud->width); + + bool has_valid_intensity = + std::any_of(input_cloud->fields.begin(), input_cloud->fields.end(), [](const auto & field) { + return field.name == "intensity" && field.datatype == sensor_msgs::msg::PointField::UINT8; + }); + + bool has_valid_return_type = + std::any_of(input_cloud->fields.begin(), input_cloud->fields.end(), [](const auto & field) { + return field.name == "return_type" && field.datatype == sensor_msgs::msg::PointField::UINT8; + }); + + bool has_valid_channel = + std::any_of(input_cloud->fields.begin(), input_cloud->fields.end(), [](const auto & field) { + return field.name == "channel" && field.datatype == sensor_msgs::msg::PointField::UINT16; + }); + + sensor_msgs::PointCloud2Iterator it_x(*input_cloud, "x"); + sensor_msgs::PointCloud2Iterator it_y(*input_cloud, "y"); + sensor_msgs::PointCloud2Iterator it_z(*input_cloud, "z"); + + if (has_valid_intensity && has_valid_return_type && has_valid_channel) { + sensor_msgs::PointCloud2Iterator it_i(*input_cloud, "intensity"); + sensor_msgs::PointCloud2Iterator it_r(*input_cloud, "return_type"); + sensor_msgs::PointCloud2Iterator it_c(*input_cloud, "channel"); + + for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z, ++it_i, ++it_r, ++it_c) { + PointXYZIRC point; + point.x = *it_x; + point.y = *it_y; + point.z = *it_z; + point.intensity = *it_i; + point.return_type = *it_r; + point.channel = *it_c; + output_modifier.push_back(std::move(point)); + } + } else { + for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z) { + PointXYZIRC point; + point.x = *it_x; + point.y = *it_y; + point.z = *it_z; + output_modifier.push_back(std::move(point)); + } + } +} + +void CombineCloudHandler::correct_pointcloud_motion( + const std::shared_ptr & transformed_cloud_ptr, + const std::vector & pc_stamps, + std::unordered_map & transform_memo, + std::shared_ptr transformed_delay_compensated_cloud_ptr) +{ + Eigen::Matrix4f adjust_to_old_data_transform = Eigen::Matrix4f::Identity(); + rclcpp::Time current_cloud_stamp = rclcpp::Time(transformed_cloud_ptr->header.stamp); + for (const auto & stamp : pc_stamps) { + if (stamp >= current_cloud_stamp) continue; + + Eigen::Matrix4f new_to_old_transform; + if (transform_memo.find(stamp) != transform_memo.end()) { + new_to_old_transform = transform_memo[stamp]; + } else { + new_to_old_transform = + compute_transform_to_adjust_for_old_timestamp(stamp, current_cloud_stamp); + transform_memo[stamp] = new_to_old_transform; + } + adjust_to_old_data_transform = new_to_old_transform * adjust_to_old_data_transform; + current_cloud_stamp = stamp; + } + pcl_ros::transformPointCloud( + adjust_to_old_data_transform, *transformed_cloud_ptr, *transformed_delay_compensated_cloud_ptr); +} + +ConcatenatedCloudResult CombineCloudHandler::combine_pointclouds( + std::unordered_map & topic_to_cloud_map) +{ + ConcatenatedCloudResult concatenate_cloud_result; + + std::vector pc_stamps; + for (const auto & [topic, cloud] : topic_to_cloud_map) { + pc_stamps.emplace_back(cloud->header.stamp); + } + std::sort(pc_stamps.begin(), pc_stamps.end(), std::greater()); + const auto oldest_stamp = pc_stamps.back(); + + std::unordered_map transform_memo; + + // Before combining the pointclouds, initialize and reserve space for the concatenated pointcloud + concatenate_cloud_result.concatenate_cloud_ptr = + std::make_shared(); + + // Reserve space based on the total size of the pointcloud data to speed up the concatenation + // process + size_t total_data_size = 0; + for (const auto & [topic, cloud] : topic_to_cloud_map) { + total_data_size += cloud->data.size(); + } + concatenate_cloud_result.concatenate_cloud_ptr->data.reserve(total_data_size); + + for (const auto & [topic, cloud] : topic_to_cloud_map) { + // convert to XYZIRC pointcloud if pointcloud is not empty + auto xyzirc_cloud = std::make_shared(); + convert_to_xyzirc_cloud(cloud, xyzirc_cloud); + + auto transformed_cloud_ptr = std::make_shared(); + managed_tf_buffer_->transformPointcloud(output_frame_, *xyzirc_cloud, *transformed_cloud_ptr); + + concatenate_cloud_result.topic_to_original_stamp_map[topic] = + rclcpp::Time(cloud->header.stamp).seconds(); + + // compensate pointcloud + std::shared_ptr transformed_delay_compensated_cloud_ptr; + if (is_motion_compensated_) { + transformed_delay_compensated_cloud_ptr = std::make_shared(); + correct_pointcloud_motion( + transformed_cloud_ptr, pc_stamps, transform_memo, transformed_delay_compensated_cloud_ptr); + } else { + transformed_delay_compensated_cloud_ptr = transformed_cloud_ptr; + } + + pcl::concatenatePointCloud( + *concatenate_cloud_result.concatenate_cloud_ptr, *transformed_delay_compensated_cloud_ptr, + *concatenate_cloud_result.concatenate_cloud_ptr); + + if (publish_synchronized_pointcloud_) { + if (!concatenate_cloud_result.topic_to_transformed_cloud_map) { + // Initialize the map if it is not present + concatenate_cloud_result.topic_to_transformed_cloud_map = + std::unordered_map(); + } + // convert to original sensor frame if necessary + bool need_transform_to_sensor_frame = (cloud->header.frame_id != output_frame_); + if (keep_input_frame_in_synchronized_pointcloud_ && need_transform_to_sensor_frame) { + auto transformed_cloud_ptr_in_sensor_frame = + std::make_shared(); + managed_tf_buffer_->transformPointcloud( + cloud->header.frame_id, *transformed_delay_compensated_cloud_ptr, + *transformed_cloud_ptr_in_sensor_frame); + transformed_cloud_ptr_in_sensor_frame->header.stamp = oldest_stamp; + transformed_cloud_ptr_in_sensor_frame->header.frame_id = cloud->header.frame_id; + + (*concatenate_cloud_result.topic_to_transformed_cloud_map)[topic] = + transformed_cloud_ptr_in_sensor_frame; + } else { + transformed_delay_compensated_cloud_ptr->header.stamp = oldest_stamp; + transformed_delay_compensated_cloud_ptr->header.frame_id = output_frame_; + (*concatenate_cloud_result.topic_to_transformed_cloud_map)[topic] = + transformed_delay_compensated_cloud_ptr; + } + } + } + concatenate_cloud_result.concatenate_cloud_ptr->header.stamp = oldest_stamp; + + return concatenate_cloud_result; +} + +Eigen::Matrix4f CombineCloudHandler::compute_transform_to_adjust_for_old_timestamp( + const rclcpp::Time & old_stamp, const rclcpp::Time & new_stamp) +{ + // return identity if no twist is available + if (twist_queue_.empty()) { + RCLCPP_WARN_STREAM_THROTTLE( + node_.get_logger(), *node_.get_clock(), std::chrono::milliseconds(10000).count(), + "No twist is available. Please confirm twist topic and timestamp. Leaving point cloud " + "untransformed."); + return Eigen::Matrix4f::Identity(); + } + + auto old_twist_it = std::lower_bound( + std::begin(twist_queue_), std::end(twist_queue_), old_stamp, + [](const geometry_msgs::msg::TwistStamped & x, const rclcpp::Time & t) { + return rclcpp::Time(x.header.stamp) < t; + }); + old_twist_it = old_twist_it == twist_queue_.end() ? (twist_queue_.end() - 1) : old_twist_it; + + auto new_twist_it = std::lower_bound( + std::begin(twist_queue_), std::end(twist_queue_), new_stamp, + [](const geometry_msgs::msg::TwistStamped & x, const rclcpp::Time & t) { + return rclcpp::Time(x.header.stamp) < t; + }); + new_twist_it = new_twist_it == twist_queue_.end() ? (twist_queue_.end() - 1) : new_twist_it; + + auto prev_time = old_stamp; + double x = 0.0; + double y = 0.0; + double yaw = 0.0; + for (auto twist_it = old_twist_it; twist_it != new_twist_it + 1; ++twist_it) { + const double dt = + (twist_it != new_twist_it) + ? (rclcpp::Time((*twist_it).header.stamp) - rclcpp::Time(prev_time)).seconds() + : (rclcpp::Time(new_stamp) - rclcpp::Time(prev_time)).seconds(); + + if (std::fabs(dt) > 0.1) { + RCLCPP_WARN_STREAM_THROTTLE( + node_.get_logger(), *node_.get_clock(), std::chrono::milliseconds(10000).count(), + "Time difference is too large. Cloud not interpolate. Please confirm twist topic and " + "timestamp"); + break; + } + + const double distance = (*twist_it).twist.linear.x * dt; + yaw += (*twist_it).twist.angular.z * dt; + x += distance * std::cos(yaw); + y += distance * std::sin(yaw); + prev_time = (*twist_it).header.stamp; + } + + Eigen::Matrix4f transformation_matrix = Eigen::Matrix4f::Identity(); + + float cos_yaw = std::cos(yaw); + float sin_yaw = std::sin(yaw); + + transformation_matrix(0, 3) = x; + transformation_matrix(1, 3) = y; + transformation_matrix(0, 0) = cos_yaw; + transformation_matrix(0, 1) = -sin_yaw; + transformation_matrix(1, 0) = sin_yaw; + transformation_matrix(1, 1) = cos_yaw; + + return transformation_matrix; +} + +} // namespace autoware::pointcloud_preprocessor diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp new file mode 100644 index 0000000000000..e168781c647ed --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_node.cpp @@ -0,0 +1,459 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp" + +#include "autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp" +#include "autoware/pointcloud_preprocessor/utility/memory.hpp" + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +namespace autoware::pointcloud_preprocessor +{ + +PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchronizerComponent( + const rclcpp::NodeOptions & node_options) +: Node("point_cloud_concatenator_component", node_options) +{ + // initialize debug tool + using autoware::universe_utils::DebugPublisher; + using autoware::universe_utils::StopWatch; + stop_watch_ptr_ = std::make_unique>(); + debug_publisher_ = std::make_unique(this, "concatenate_data_synchronizer"); + stop_watch_ptr_->tic("cyclic_time"); + stop_watch_ptr_->tic("processing_time"); + + // initialize parameters + params_.debug_mode = declare_parameter("debug_mode"); + params_.has_static_tf_only = declare_parameter("has_static_tf_only"); + params_.rosbag_length = declare_parameter("rosbag_length"); + params_.maximum_queue_size = static_cast(declare_parameter("maximum_queue_size")); + params_.timeout_sec = declare_parameter("timeout_sec"); + params_.is_motion_compensated = declare_parameter("is_motion_compensated"); + params_.publish_synchronized_pointcloud = + declare_parameter("publish_synchronized_pointcloud"); + params_.keep_input_frame_in_synchronized_pointcloud = + declare_parameter("keep_input_frame_in_synchronized_pointcloud"); + params_.publish_previous_but_late_pointcloud = + declare_parameter("publish_previous_but_late_pointcloud"); + params_.synchronized_pointcloud_postfix = + declare_parameter("synchronized_pointcloud_postfix"); + params_.input_twist_topic_type = declare_parameter("input_twist_topic_type"); + params_.input_topics = declare_parameter>("input_topics"); + params_.output_frame = declare_parameter("output_frame"); + + if (params_.input_topics.empty()) { + throw std::runtime_error("Need a 'input_topics' parameter to be set before continuing."); + } + if (params_.input_topics.size() == 1) { + throw std::runtime_error("Only one topic given. Need at least two topics to continue."); + } + + if (params_.output_frame.empty()) { + throw std::runtime_error("Need an 'output_frame' parameter to be set before continuing."); + } + + params_.matching_strategy = declare_parameter("matching_strategy.type"); + if (params_.matching_strategy == "naive") { + collector_matching_strategy_ = std::make_unique(*this); + } else if (params_.matching_strategy == "advanced") { + collector_matching_strategy_ = + std::make_unique(*this, params_.input_topics); + } else { + throw std::runtime_error("Matching strategy must be 'advanced' or 'naive'"); + } + + // Publishers + concatenated_cloud_publisher_ = this->create_publisher( + "output", rclcpp::SensorDataQoS().keep_last(params_.maximum_queue_size)); + + // Transformed Raw PointCloud2 Publisher to publish the transformed pointcloud + if (params_.publish_synchronized_pointcloud) { + for (auto & topic : params_.input_topics) { + std::string new_topic = + replace_sync_topic_name_postfix(topic, params_.synchronized_pointcloud_postfix); + auto publisher = this->create_publisher( + new_topic, rclcpp::SensorDataQoS().keep_last(params_.maximum_queue_size)); + topic_to_transformed_cloud_publisher_map_.insert({topic, publisher}); + } + } + + // Subscribers + if (params_.is_motion_compensated) { + if (params_.input_twist_topic_type == "twist") { + twist_sub_ = this->create_subscription( + "~/input/twist", rclcpp::QoS{100}, + std::bind( + &PointCloudConcatenateDataSynchronizerComponent::twist_callback, this, + std::placeholders::_1)); + } else if (params_.input_twist_topic_type == "odom") { + odom_sub_ = this->create_subscription( + "~/input/odom", rclcpp::QoS{100}, + std::bind( + &PointCloudConcatenateDataSynchronizerComponent::odom_callback, this, + std::placeholders::_1)); + } else { + throw std::runtime_error( + "input_twist_topic_type is invalid: " + params_.input_twist_topic_type); + } + } + + for (const std::string & topic : params_.input_topics) { + std::function callback = std::bind( + &PointCloudConcatenateDataSynchronizerComponent::cloud_callback, this, std::placeholders::_1, + topic); + + auto pointcloud_sub = this->create_subscription( + topic, rclcpp::SensorDataQoS().keep_last(params_.maximum_queue_size), callback); + pointcloud_subs_.push_back(pointcloud_sub); + } + RCLCPP_DEBUG_STREAM( + get_logger(), + "Subscribing to " << params_.input_topics.size() << " user given topics as inputs:"); + for (const auto & input_topic : params_.input_topics) { + RCLCPP_DEBUG_STREAM(get_logger(), " - " << input_topic); + } + + // Combine cloud handler + combine_cloud_handler_ = std::make_shared( + *this, params_.output_frame, params_.is_motion_compensated, + params_.publish_synchronized_pointcloud, params_.keep_input_frame_in_synchronized_pointcloud, + params_.has_static_tf_only); + + // Diagnostic Updater + diagnostic_updater_.setHardwareID("concatenate_data_checker"); + diagnostic_updater_.add( + "concat_status", this, &PointCloudConcatenateDataSynchronizerComponent::check_concat_status); +} + +std::string PointCloudConcatenateDataSynchronizerComponent::replace_sync_topic_name_postfix( + const std::string & original_topic_name, const std::string & postfix) +{ + std::string replaced_topic_name; + // separate the topic name by '/' and replace the last element with the new postfix + size_t pos = original_topic_name.find_last_of('/'); + if (pos == std::string::npos) { + // not found '/': this is not a namespaced topic + RCLCPP_WARN_STREAM( + get_logger(), + "The topic name is not namespaced. The postfix will be added to the end of the topic name."); + return original_topic_name + postfix; + } + + // replace the last element with the new postfix + replaced_topic_name = original_topic_name.substr(0, pos) + "/" + postfix; + + // if topic name is the same with original topic name, add postfix to the end of the topic name + if (replaced_topic_name == original_topic_name) { + RCLCPP_WARN_STREAM( + get_logger(), "The topic name " + << original_topic_name + << " have the same postfix with synchronized pointcloud. We use " + "the postfix " + "to the end of the topic name."); + replaced_topic_name = original_topic_name + default_sync_topic_postfix; + } + return replaced_topic_name; +} + +void PointCloudConcatenateDataSynchronizerComponent::cloud_callback( + const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, const std::string & topic_name) +{ + stop_watch_ptr_->toc("processing_time", true); + double cloud_arrival_time = this->get_clock()->now().seconds(); + manage_collector_list(); + + if (!utils::is_data_layout_compatible_with_point_xyzirc(*input_ptr)) { + RCLCPP_ERROR( + get_logger(), "The pointcloud layout is not compatible with PointXYZIRC. Aborting"); + + if (utils::is_data_layout_compatible_with_point_xyzi(*input_ptr)) { + RCLCPP_ERROR( + get_logger(), + "The pointcloud layout is compatible with PointXYZI. You may be using legacy code/data"); + } + + return; + } + + if (params_.debug_mode) { + RCLCPP_INFO( + this->get_logger(), " pointcloud %s timestamp: %lf arrive time: %lf seconds, latency: %lf", + topic_name.c_str(), rclcpp::Time(input_ptr->header.stamp).seconds(), cloud_arrival_time, + cloud_arrival_time - rclcpp::Time(input_ptr->header.stamp).seconds()); + } + + if (input_ptr->data.empty()) { + RCLCPP_WARN_STREAM_THROTTLE( + this->get_logger(), *this->get_clock(), 1000, "Empty sensor points!"); + } + + // protect cloud collectors list + std::unique_lock cloud_collectors_lock(cloud_collectors_mutex_); + + // For each callback, check whether there is a exist collector that matches this cloud + std::optional> cloud_collector = std::nullopt; + MatchingParams matching_params; + matching_params.topic_name = topic_name; + matching_params.cloud_arrival_time = cloud_arrival_time; + matching_params.cloud_timestamp = rclcpp::Time(input_ptr->header.stamp).seconds(); + + if (!cloud_collectors_.empty()) { + cloud_collector = + collector_matching_strategy_->match_cloud_to_collector(cloud_collectors_, matching_params); + } + + bool process_success = false; + if (cloud_collector.has_value()) { + auto collector = cloud_collector.value(); + if (collector) { + cloud_collectors_lock.unlock(); + process_success = cloud_collector.value()->process_pointcloud(topic_name, input_ptr); + } + } + + if (!process_success) { + auto new_cloud_collector = std::make_shared( + std::dynamic_pointer_cast(shared_from_this()), + combine_cloud_handler_, params_.input_topics.size(), params_.timeout_sec, params_.debug_mode); + + cloud_collectors_.push_back(new_cloud_collector); + cloud_collectors_lock.unlock(); + + collector_matching_strategy_->set_collector_info(new_cloud_collector, matching_params); + (void)new_cloud_collector->process_pointcloud(topic_name, input_ptr); + } +} + +void PointCloudConcatenateDataSynchronizerComponent::twist_callback( + const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr input) +{ + combine_cloud_handler_->process_twist(input); +} + +void PointCloudConcatenateDataSynchronizerComponent::odom_callback( + const nav_msgs::msg::Odometry::ConstSharedPtr input) +{ + combine_cloud_handler_->process_odometry(input); +} + +void PointCloudConcatenateDataSynchronizerComponent::publish_clouds( + ConcatenatedCloudResult && concatenated_cloud_result, + std::shared_ptr collector_info) +{ + // should never come to this state. + if (concatenated_cloud_result.concatenate_cloud_ptr == nullptr) { + RCLCPP_ERROR(this->get_logger(), "Concatenated cloud is a nullptr."); + return; + } + + if (concatenated_cloud_result.concatenate_cloud_ptr->data.empty()) { + RCLCPP_ERROR(this->get_logger(), "Concatenated cloud is an empty pointcloud."); + is_concatenated_cloud_empty_ = true; + } + + current_concatenate_cloud_timestamp_ = + rclcpp::Time(concatenated_cloud_result.concatenate_cloud_ptr->header.stamp).seconds(); + + if ( + current_concatenate_cloud_timestamp_ < latest_concatenate_cloud_timestamp_ && + !params_.publish_previous_but_late_pointcloud) { + // Publish the cloud if the rosbag replays in loop + if ( + latest_concatenate_cloud_timestamp_ - current_concatenate_cloud_timestamp_ > + params_.rosbag_length) { + publish_pointcloud_ = true; // Force publishing in this case + } else { + drop_previous_but_late_pointcloud_ = true; // Otherwise, drop the late pointcloud + } + } else { + // Publish pointcloud if timestamps are valid or the condition doesn't apply + publish_pointcloud_ = true; + } + + if (publish_pointcloud_) { + latest_concatenate_cloud_timestamp_ = current_concatenate_cloud_timestamp_; + auto concatenate_pointcloud_output = std::make_unique( + std::move(*concatenated_cloud_result.concatenate_cloud_ptr)); + concatenated_cloud_publisher_->publish(std::move(concatenate_pointcloud_output)); + + // publish transformed raw pointclouds + if ( + params_.publish_synchronized_pointcloud && + concatenated_cloud_result.topic_to_transformed_cloud_map) { + for (const auto & topic : params_.input_topics) { + // Get a reference to the internal map + if ( + (*concatenated_cloud_result.topic_to_transformed_cloud_map).find(topic) != + (*concatenated_cloud_result.topic_to_transformed_cloud_map).end()) { + auto transformed_cloud_output = std::make_unique( + *(*concatenated_cloud_result.topic_to_transformed_cloud_map).at(topic)); + topic_to_transformed_cloud_publisher_map_[topic]->publish( + std::move(transformed_cloud_output)); + } else { + RCLCPP_WARN( + this->get_logger(), + "transformed_raw_points[%s] is nullptr, skipping pointcloud publish.", topic.c_str()); + } + } + } + } + + diagnostic_collector_info_ = collector_info; + + diagnostic_topic_to_original_stamp_map_ = concatenated_cloud_result.topic_to_original_stamp_map; + diagnostic_updater_.force_update(); + + // add processing time for debug + if (debug_publisher_) { + const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); + const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); + debug_publisher_->publish( + "debug/cyclic_time_ms", cyclic_time_ms); + debug_publisher_->publish( + "debug/processing_time_ms", processing_time_ms); + + for (const auto & [topic, stamp] : concatenated_cloud_result.topic_to_original_stamp_map) { + const auto pipeline_latency_ms = (this->get_clock()->now().seconds() - stamp) * 1000; + debug_publisher_->publish( + "debug" + topic + "/pipeline_latency_ms", pipeline_latency_ms); + } + } +} + +void PointCloudConcatenateDataSynchronizerComponent::manage_collector_list() +{ + std::lock_guard cloud_collectors_lock(cloud_collectors_mutex_); + + for (auto it = cloud_collectors_.begin(); it != cloud_collectors_.end();) { + if ((*it)->concatenate_finished()) { + it = cloud_collectors_.erase(it); // Erase and move the iterator to the next element + } else { + ++it; // Move to the next element + } + } +} + +std::string PointCloudConcatenateDataSynchronizerComponent::format_timestamp(double timestamp) +{ + std::ostringstream oss; + oss << std::fixed << std::setprecision(9) << timestamp; + return oss.str(); +} + +void PointCloudConcatenateDataSynchronizerComponent::check_concat_status( + diagnostic_updater::DiagnosticStatusWrapper & stat) +{ + if (publish_pointcloud_ || drop_previous_but_late_pointcloud_) { + stat.add( + "concatenated_cloud_timestamp", format_timestamp(current_concatenate_cloud_timestamp_)); + + if ( + auto naive_info = std::dynamic_pointer_cast(diagnostic_collector_info_)) { + stat.add("first_cloud_arrival_timestamp", format_timestamp(naive_info->timestamp)); + } else if ( + auto advanced_info = + std::dynamic_pointer_cast(diagnostic_collector_info_)) { + stat.add( + "reference_timestamp_min", + format_timestamp(advanced_info->timestamp - advanced_info->noise_window)); + stat.add( + "reference_timestamp_max", + format_timestamp(advanced_info->timestamp + advanced_info->noise_window)); + } + + bool topic_miss = false; + + bool concatenation_success = true; + for (const auto & topic : params_.input_topics) { + bool input_cloud_concatenated = true; + if ( + diagnostic_topic_to_original_stamp_map_.find(topic) != + diagnostic_topic_to_original_stamp_map_.end()) { + stat.add( + topic + "/timestamp", format_timestamp(diagnostic_topic_to_original_stamp_map_[topic])); + } else { + topic_miss = true; + concatenation_success = false; + input_cloud_concatenated = false; + } + stat.add(topic + "/is_concatenated", input_cloud_concatenated); + } + + stat.add("cloud_concatenation_success", concatenation_success); + + int8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + std::string message = "Concatenated pointcloud is published and include all topics"; + + if (drop_previous_but_late_pointcloud_) { + if (topic_miss) { + level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + message = + "Concatenated pointcloud misses some topics and is not published because it arrived " + "too late"; + } else { + level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + message = "Concatenated pointcloud is not published as it is too late"; + } + } else { + if (is_concatenated_cloud_empty_) { + level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + message = "Concatenated pointcloud is empty"; + } else if (topic_miss) { + level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + message = "Concatenated pointcloud is published but misses some topics"; + } + } + + stat.summary(level, message); + + publish_pointcloud_ = false; + drop_previous_but_late_pointcloud_ = false; + is_concatenated_cloud_empty_ = false; + } else { + const int8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + const std::string message = + "Concatenate node launch successfully, but waiting for input pointcloud"; + stat.summary(level, message); + } +} + +std::list> +PointCloudConcatenateDataSynchronizerComponent::get_cloud_collectors() +{ + return cloud_collectors_; +} + +void PointCloudConcatenateDataSynchronizerComponent::add_cloud_collector( + const std::shared_ptr & collector) +{ + cloud_collectors_.push_back(collector); +} + +} // namespace autoware::pointcloud_preprocessor + +#include +RCLCPP_COMPONENTS_REGISTER_NODE( + autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent) diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp deleted file mode 100644 index b49e21b8f30be..0000000000000 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp +++ /dev/null @@ -1,718 +0,0 @@ -// Copyright 2020 Tier IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2009, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage, Inc. nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - * $Id: concatenate_data.cpp 35231 2011-01-14 05:33:20Z rusu $ - * - */ - -#include "autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp" - -#include "autoware/pointcloud_preprocessor/utility/memory.hpp" - -#include - -#include - -#include -#include -#include -#include -#include -#include - -#define DEFAULT_SYNC_TOPIC_POSTFIX \ - "_synchronized" // default postfix name for synchronized pointcloud - -////////////////////////////////////////////////////////////////////////////////////////////// - -namespace autoware::pointcloud_preprocessor -{ -PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchronizerComponent( - const rclcpp::NodeOptions & node_options) -: Node("point_cloud_concatenator_component", node_options), - input_twist_topic_type_(declare_parameter("input_twist_topic_type", "twist")) -{ - // initialize debug tool - { - using autoware::universe_utils::DebugPublisher; - using autoware::universe_utils::StopWatch; - stop_watch_ptr_ = std::make_unique>(); - debug_publisher_ = std::make_unique(this, "concatenate_data_synchronizer"); - stop_watch_ptr_->tic("cyclic_time"); - stop_watch_ptr_->tic("processing_time"); - } - - // Set parameters - { - output_frame_ = static_cast(declare_parameter("output_frame", "")); - if (output_frame_.empty()) { - RCLCPP_ERROR(get_logger(), "Need an 'output_frame' parameter to be set before continuing!"); - return; - } - has_static_tf_only_ = declare_parameter("has_static_tf_only", false); - declare_parameter("input_topics", std::vector()); - input_topics_ = get_parameter("input_topics").as_string_array(); - if (input_topics_.empty()) { - RCLCPP_ERROR(get_logger(), "Need a 'input_topics' parameter to be set before continuing!"); - return; - } - if (input_topics_.size() == 1) { - RCLCPP_ERROR(get_logger(), "Only one topic given. Need at least two topics to continue."); - return; - } - - // Optional parameters - maximum_queue_size_ = static_cast(declare_parameter("max_queue_size", 5)); - timeout_sec_ = static_cast(declare_parameter("timeout_sec", 0.1)); - - input_offset_ = declare_parameter("input_offset", std::vector{}); - if (!input_offset_.empty() && input_topics_.size() != input_offset_.size()) { - RCLCPP_ERROR(get_logger(), "The number of topics does not match the number of offsets."); - return; - } - - // Check if publish synchronized pointcloud - publish_synchronized_pointcloud_ = declare_parameter("publish_synchronized_pointcloud", true); - keep_input_frame_in_synchronized_pointcloud_ = - declare_parameter("keep_input_frame_in_synchronized_pointcloud", true); - synchronized_pointcloud_postfix_ = - declare_parameter("synchronized_pointcloud_postfix", "pointcloud"); - } - - // Initialize not_subscribed_topic_names_ - { - for (const std::string & e : input_topics_) { - not_subscribed_topic_names_.insert(e); - } - } - - // Initialize offset map - { - for (size_t i = 0; i < input_offset_.size(); ++i) { - offset_map_[input_topics_[i]] = input_offset_[i]; - } - } - - // tf2 listener - { - managed_tf_buffer_ = - std::make_unique(this, has_static_tf_only_); - } - - // Output Publishers - { - rclcpp::PublisherOptions pub_options; - pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); - pub_output_ = this->create_publisher( - "output", rclcpp::SensorDataQoS().keep_last(maximum_queue_size_), pub_options); - } - - // Subscribers - { - RCLCPP_DEBUG_STREAM( - get_logger(), "Subscribing to " << input_topics_.size() << " user given topics as inputs:"); - for (const auto & input_topic : input_topics_) { - RCLCPP_DEBUG_STREAM(get_logger(), " - " << input_topic); - } - - // Subscribe to the filters - filters_.resize(input_topics_.size()); - - // First input_topics_.size () filters are valid - for (size_t d = 0; d < input_topics_.size(); ++d) { - cloud_stdmap_.insert(std::make_pair(input_topics_[d], nullptr)); - cloud_stdmap_tmp_ = cloud_stdmap_; - - // CAN'T use auto type here. - std::function cb = std::bind( - &PointCloudConcatenateDataSynchronizerComponent::cloud_callback, this, - std::placeholders::_1, input_topics_[d]); - - filters_[d].reset(); - filters_[d] = this->create_subscription( - input_topics_[d], rclcpp::SensorDataQoS().keep_last(maximum_queue_size_), cb); - } - - if (input_twist_topic_type_ == "twist") { - auto twist_cb = std::bind( - &PointCloudConcatenateDataSynchronizerComponent::twist_callback, this, - std::placeholders::_1); - sub_twist_ = this->create_subscription( - "~/input/twist", rclcpp::QoS{100}, twist_cb); - } else if (input_twist_topic_type_ == "odom") { - auto odom_cb = std::bind( - &PointCloudConcatenateDataSynchronizerComponent::odom_callback, this, - std::placeholders::_1); - sub_odom_ = this->create_subscription( - "~/input/odom", rclcpp::QoS{100}, odom_cb); - } else { - RCLCPP_ERROR_STREAM( - get_logger(), "input_twist_topic_type is invalid: " << input_twist_topic_type_); - throw std::runtime_error("input_twist_topic_type is invalid: " + input_twist_topic_type_); - } - } - - // Transformed Raw PointCloud2 Publisher to publish the transformed pointcloud - if (publish_synchronized_pointcloud_) { - rclcpp::PublisherOptions pub_options; - pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); - - for (auto & topic : input_topics_) { - std::string new_topic = replaceSyncTopicNamePostfix(topic, synchronized_pointcloud_postfix_); - auto publisher = this->create_publisher( - new_topic, rclcpp::SensorDataQoS().keep_last(maximum_queue_size_), pub_options); - transformed_raw_pc_publisher_map_.insert({topic, publisher}); - } - } - - // Set timer - { - const auto period_ns = std::chrono::duration_cast( - std::chrono::duration(timeout_sec_)); - timer_ = rclcpp::create_timer( - this, get_clock(), period_ns, - std::bind(&PointCloudConcatenateDataSynchronizerComponent::timer_callback, this)); - } - - // Diagnostic Updater - { - updater_.setHardwareID("concatenate_data_checker"); - updater_.add( - "concat_status", this, &PointCloudConcatenateDataSynchronizerComponent::checkConcatStatus); - } -} - -std::string PointCloudConcatenateDataSynchronizerComponent::replaceSyncTopicNamePostfix( - const std::string & original_topic_name, const std::string & postfix) -{ - std::string replaced_topic_name; - // separate the topic name by '/' and replace the last element with the new postfix - size_t pos = original_topic_name.find_last_of("/"); - if (pos == std::string::npos) { - // not found '/': this is not a namespaced topic - RCLCPP_WARN_STREAM( - get_logger(), - "The topic name is not namespaced. The postfix will be added to the end of the topic name."); - return original_topic_name + postfix; - } else { - // replace the last element with the new postfix - replaced_topic_name = original_topic_name.substr(0, pos) + "/" + postfix; - } - - // if topic name is the same with original topic name, add postfix to the end of the topic name - if (replaced_topic_name == original_topic_name) { - RCLCPP_WARN_STREAM( - get_logger(), "The topic name " - << original_topic_name - << " have the same postfix with synchronized pointcloud. We use the postfix " - "to the end of the topic name."); - replaced_topic_name = original_topic_name + DEFAULT_SYNC_TOPIC_POSTFIX; - } - return replaced_topic_name; -} - -/** - * @brief compute transform to adjust for old timestamp - * - * @param old_stamp - * @param new_stamp - * @return Eigen::Matrix4f: transformation matrix from new_stamp to old_stamp - */ -Eigen::Matrix4f -PointCloudConcatenateDataSynchronizerComponent::computeTransformToAdjustForOldTimestamp( - const rclcpp::Time & old_stamp, const rclcpp::Time & new_stamp) -{ - // return identity if no twist is available - if (twist_ptr_queue_.empty()) { - RCLCPP_WARN_STREAM_THROTTLE( - get_logger(), *get_clock(), std::chrono::milliseconds(10000).count(), - "No twist is available. Please confirm twist topic and timestamp"); - return Eigen::Matrix4f::Identity(); - } - - // return identity if old_stamp is newer than new_stamp - if (old_stamp > new_stamp) { - RCLCPP_DEBUG_STREAM_THROTTLE( - get_logger(), *get_clock(), std::chrono::milliseconds(10000).count(), - "old_stamp is newer than new_stamp,"); - return Eigen::Matrix4f::Identity(); - } - - auto old_twist_ptr_it = std::lower_bound( - std::begin(twist_ptr_queue_), std::end(twist_ptr_queue_), old_stamp, - [](const geometry_msgs::msg::TwistStamped::ConstSharedPtr & x_ptr, const rclcpp::Time & t) { - return rclcpp::Time(x_ptr->header.stamp) < t; - }); - old_twist_ptr_it = - old_twist_ptr_it == twist_ptr_queue_.end() ? (twist_ptr_queue_.end() - 1) : old_twist_ptr_it; - - auto new_twist_ptr_it = std::lower_bound( - std::begin(twist_ptr_queue_), std::end(twist_ptr_queue_), new_stamp, - [](const geometry_msgs::msg::TwistStamped::ConstSharedPtr & x_ptr, const rclcpp::Time & t) { - return rclcpp::Time(x_ptr->header.stamp) < t; - }); - new_twist_ptr_it = - new_twist_ptr_it == twist_ptr_queue_.end() ? (twist_ptr_queue_.end() - 1) : new_twist_ptr_it; - - auto prev_time = old_stamp; - double x = 0.0; - double y = 0.0; - double yaw = 0.0; - for (auto twist_ptr_it = old_twist_ptr_it; twist_ptr_it != new_twist_ptr_it + 1; ++twist_ptr_it) { - const double dt = - (twist_ptr_it != new_twist_ptr_it) - ? (rclcpp::Time((*twist_ptr_it)->header.stamp) - rclcpp::Time(prev_time)).seconds() - : (rclcpp::Time(new_stamp) - rclcpp::Time(prev_time)).seconds(); - - if (std::fabs(dt) > 0.1) { - RCLCPP_WARN_STREAM_THROTTLE( - get_logger(), *get_clock(), std::chrono::milliseconds(10000).count(), - "Time difference is too large. Cloud not interpolate. Please confirm twist topic and " - "timestamp"); - break; - } - - const double dis = (*twist_ptr_it)->twist.linear.x * dt; - yaw += (*twist_ptr_it)->twist.angular.z * dt; - x += dis * std::cos(yaw); - y += dis * std::sin(yaw); - prev_time = (*twist_ptr_it)->header.stamp; - } - Eigen::AngleAxisf rotation_x(0, Eigen::Vector3f::UnitX()); - Eigen::AngleAxisf rotation_y(0, Eigen::Vector3f::UnitY()); - Eigen::AngleAxisf rotation_z(yaw, Eigen::Vector3f::UnitZ()); - Eigen::Translation3f translation(x, y, 0); - Eigen::Matrix4f rotation_matrix = (translation * rotation_z * rotation_y * rotation_x).matrix(); - return rotation_matrix; -} - -std::map -PointCloudConcatenateDataSynchronizerComponent::combineClouds( - sensor_msgs::msg::PointCloud2::SharedPtr & concat_cloud_ptr) -{ - // map for storing the transformed point clouds - std::map transformed_clouds; - - // Step1. gather stamps and sort it - std::vector pc_stamps; - for (const auto & e : cloud_stdmap_) { - transformed_clouds[e.first] = nullptr; - if (e.second != nullptr) { - if (e.second->data.size() == 0) { - continue; - } - pc_stamps.push_back(rclcpp::Time(e.second->header.stamp)); - } - } - if (pc_stamps.empty()) { - return transformed_clouds; - } - // sort stamps and get oldest stamp - std::sort(pc_stamps.begin(), pc_stamps.end()); - std::reverse(pc_stamps.begin(), pc_stamps.end()); - const auto oldest_stamp = pc_stamps.back(); - - // Step2. Calculate compensation transform and concatenate with the oldest stamp - for (const auto & e : cloud_stdmap_) { - if (e.second != nullptr) { - if (e.second->data.size() == 0) { - continue; - } - sensor_msgs::msg::PointCloud2::SharedPtr transformed_cloud_ptr( - new sensor_msgs::msg::PointCloud2()); - managed_tf_buffer_->transformPointcloud(output_frame_, *e.second, *transformed_cloud_ptr); - - // calculate transforms to oldest stamp - Eigen::Matrix4f adjust_to_old_data_transform = Eigen::Matrix4f::Identity(); - rclcpp::Time transformed_stamp = rclcpp::Time(e.second->header.stamp); - for (const auto & stamp : pc_stamps) { - const auto new_to_old_transform = - computeTransformToAdjustForOldTimestamp(stamp, transformed_stamp); - adjust_to_old_data_transform = new_to_old_transform * adjust_to_old_data_transform; - transformed_stamp = std::min(transformed_stamp, stamp); - } - sensor_msgs::msg::PointCloud2::SharedPtr transformed_delay_compensated_cloud_ptr( - new sensor_msgs::msg::PointCloud2()); - pcl_ros::transformPointCloud( - adjust_to_old_data_transform, *transformed_cloud_ptr, - *transformed_delay_compensated_cloud_ptr); - - // concatenate - if (concat_cloud_ptr == nullptr) { - concat_cloud_ptr = - std::make_shared(*transformed_delay_compensated_cloud_ptr); - } else { - pcl::concatenatePointCloud( - *concat_cloud_ptr, *transformed_delay_compensated_cloud_ptr, *concat_cloud_ptr); - } - // convert to original sensor frame if necessary - bool need_transform_to_sensor_frame = (e.second->header.frame_id != output_frame_); - if (keep_input_frame_in_synchronized_pointcloud_ && need_transform_to_sensor_frame) { - sensor_msgs::msg::PointCloud2::SharedPtr transformed_cloud_ptr_in_sensor_frame( - new sensor_msgs::msg::PointCloud2()); - managed_tf_buffer_->transformPointcloud( - e.second->header.frame_id, *transformed_delay_compensated_cloud_ptr, - *transformed_cloud_ptr_in_sensor_frame); - transformed_cloud_ptr_in_sensor_frame->header.stamp = oldest_stamp; - transformed_cloud_ptr_in_sensor_frame->header.frame_id = e.second->header.frame_id; - transformed_clouds[e.first] = transformed_cloud_ptr_in_sensor_frame; - } else { - transformed_delay_compensated_cloud_ptr->header.stamp = oldest_stamp; - transformed_delay_compensated_cloud_ptr->header.frame_id = output_frame_; - transformed_clouds[e.first] = transformed_delay_compensated_cloud_ptr; - } - - } else { - not_subscribed_topic_names_.insert(e.first); - } - } - concat_cloud_ptr->header.stamp = oldest_stamp; - return transformed_clouds; -} - -void PointCloudConcatenateDataSynchronizerComponent::publish() -{ - stop_watch_ptr_->toc("processing_time", true); - sensor_msgs::msg::PointCloud2::SharedPtr concat_cloud_ptr = nullptr; - not_subscribed_topic_names_.clear(); - - const auto & transformed_raw_points = - PointCloudConcatenateDataSynchronizerComponent::combineClouds(concat_cloud_ptr); - - // publish concatenated pointcloud - if (concat_cloud_ptr) { - auto output = std::make_unique(*concat_cloud_ptr); - pub_output_->publish(std::move(output)); - } else { - RCLCPP_WARN(this->get_logger(), "concat_cloud_ptr is nullptr, skipping pointcloud publish."); - } - - // publish transformed raw pointclouds - if (publish_synchronized_pointcloud_) { - for (const auto & e : transformed_raw_points) { - if (e.second) { - auto output = std::make_unique(*e.second); - transformed_raw_pc_publisher_map_[e.first]->publish(std::move(output)); - } else { - RCLCPP_WARN( - this->get_logger(), "transformed_raw_points[%s] is nullptr, skipping pointcloud publish.", - e.first.c_str()); - } - } - } - - updater_.force_update(); - - cloud_stdmap_ = cloud_stdmap_tmp_; - std::for_each(std::begin(cloud_stdmap_tmp_), std::end(cloud_stdmap_tmp_), [](auto & e) { - e.second = nullptr; - }); - // add processing time for debug - if (debug_publisher_) { - const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); - const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); - debug_publisher_->publish( - "debug/cyclic_time_ms", cyclic_time_ms); - debug_publisher_->publish( - "debug/processing_time_ms", processing_time_ms); - } - for (const auto & e : cloud_stdmap_) { - if (e.second != nullptr) { - if (debug_publisher_) { - const auto pipeline_latency_ms = - std::chrono::duration( - std::chrono::nanoseconds( - (this->get_clock()->now() - e.second->header.stamp).nanoseconds())) - .count(); - debug_publisher_->publish( - "debug" + e.first + "/pipeline_latency_ms", pipeline_latency_ms); - } - } - } -} - -/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// -void PointCloudConcatenateDataSynchronizerComponent::convertToXYZIRCCloud( - const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, - sensor_msgs::msg::PointCloud2::SharedPtr & output_ptr) -{ - output_ptr->header = input_ptr->header; - - PointCloud2Modifier output_modifier{ - *output_ptr, input_ptr->header.frame_id}; - output_modifier.reserve(input_ptr->width); - - bool has_valid_intensity = - std::any_of(input_ptr->fields.begin(), input_ptr->fields.end(), [](const auto & field) { - return field.name == "intensity" && field.datatype == sensor_msgs::msg::PointField::UINT8; - }); - - bool has_valid_return_type = - std::any_of(input_ptr->fields.begin(), input_ptr->fields.end(), [](const auto & field) { - return field.name == "return_type" && field.datatype == sensor_msgs::msg::PointField::UINT8; - }); - - bool has_valid_channel = - std::any_of(input_ptr->fields.begin(), input_ptr->fields.end(), [](const auto & field) { - return field.name == "channel" && field.datatype == sensor_msgs::msg::PointField::UINT16; - }); - - sensor_msgs::PointCloud2Iterator it_x(*input_ptr, "x"); - sensor_msgs::PointCloud2Iterator it_y(*input_ptr, "y"); - sensor_msgs::PointCloud2Iterator it_z(*input_ptr, "z"); - - if (has_valid_intensity && has_valid_return_type && has_valid_channel) { - sensor_msgs::PointCloud2Iterator it_i(*input_ptr, "intensity"); - sensor_msgs::PointCloud2Iterator it_r(*input_ptr, "return_type"); - sensor_msgs::PointCloud2Iterator it_c(*input_ptr, "channel"); - - for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z, ++it_i, ++it_r, ++it_c) { - PointXYZIRC point; - point.x = *it_x; - point.y = *it_y; - point.z = *it_z; - point.intensity = *it_i; - point.return_type = *it_r; - point.channel = *it_c; - output_modifier.push_back(std::move(point)); - } - } else { - for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z) { - PointXYZIRC point; - point.x = *it_x; - point.y = *it_y; - point.z = *it_z; - output_modifier.push_back(std::move(point)); - } - } -} - -void PointCloudConcatenateDataSynchronizerComponent::setPeriod(const int64_t new_period) -{ - if (!timer_) { - return; - } - int64_t old_period = 0; - rcl_ret_t ret = rcl_timer_get_period(timer_->get_timer_handle().get(), &old_period); - if (ret != RCL_RET_OK) { - rclcpp::exceptions::throw_from_rcl_error(ret, "Couldn't get old period"); - } - ret = rcl_timer_exchange_period(timer_->get_timer_handle().get(), new_period, &old_period); - if (ret != RCL_RET_OK) { - rclcpp::exceptions::throw_from_rcl_error(ret, "Couldn't exchange_period"); - } -} - -void PointCloudConcatenateDataSynchronizerComponent::cloud_callback( - const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_ptr, const std::string & topic_name) -{ - if (!utils::is_data_layout_compatible_with_point_xyzirc(*input_ptr)) { - RCLCPP_ERROR( - get_logger(), "The pointcloud layout is not compatible with PointXYZIRC. Aborting"); - - if (utils::is_data_layout_compatible_with_point_xyzi(*input_ptr)) { - RCLCPP_ERROR( - get_logger(), - "The pointcloud layout is compatible with PointXYZI. You may be using legacy code/data"); - } - - return; - } - - std::lock_guard lock(mutex_); - sensor_msgs::msg::PointCloud2::SharedPtr xyzirc_input_ptr(new sensor_msgs::msg::PointCloud2()); - auto input = std::make_shared(*input_ptr); - if (input->data.empty()) { - RCLCPP_WARN_STREAM_THROTTLE( - this->get_logger(), *this->get_clock(), 1000, "Empty sensor points!"); - } else { - // convert to XYZIRC pointcloud if pointcloud is not empty - convertToXYZIRCCloud(input, xyzirc_input_ptr); - } - - const bool is_already_subscribed_this = (cloud_stdmap_[topic_name] != nullptr); - const bool is_already_subscribed_tmp = std::any_of( - std::begin(cloud_stdmap_tmp_), std::end(cloud_stdmap_tmp_), - [](const auto & e) { return e.second != nullptr; }); - - if (is_already_subscribed_this) { - cloud_stdmap_tmp_[topic_name] = xyzirc_input_ptr; - - if (!is_already_subscribed_tmp) { - auto period = std::chrono::duration_cast( - std::chrono::duration(timeout_sec_)); - try { - setPeriod(period.count()); - } catch (rclcpp::exceptions::RCLError & ex) { - RCLCPP_WARN_THROTTLE(get_logger(), *get_clock(), 5000, "%s", ex.what()); - } - timer_->reset(); - } - } else { - cloud_stdmap_[topic_name] = xyzirc_input_ptr; - - const bool is_subscribed_all = std::all_of( - std::begin(cloud_stdmap_), std::end(cloud_stdmap_), - [](const auto & e) { return e.second != nullptr; }); - - if (is_subscribed_all) { - for (const auto & e : cloud_stdmap_tmp_) { - if (e.second != nullptr) { - cloud_stdmap_[e.first] = e.second; - } - } - std::for_each(std::begin(cloud_stdmap_tmp_), std::end(cloud_stdmap_tmp_), [](auto & e) { - e.second = nullptr; - }); - - timer_->cancel(); - publish(); - } else if (offset_map_.size() > 0) { - timer_->cancel(); - auto period = std::chrono::duration_cast( - std::chrono::duration(timeout_sec_ - offset_map_[topic_name])); - try { - setPeriod(period.count()); - } catch (rclcpp::exceptions::RCLError & ex) { - RCLCPP_WARN_THROTTLE(get_logger(), *get_clock(), 5000, "%s", ex.what()); - } - timer_->reset(); - } - } -} - -void PointCloudConcatenateDataSynchronizerComponent::timer_callback() -{ - using std::chrono_literals::operator""ms; - timer_->cancel(); - if (mutex_.try_lock()) { - publish(); - mutex_.unlock(); - } else { - try { - std::chrono::nanoseconds period = 10ms; - setPeriod(period.count()); - } catch (rclcpp::exceptions::RCLError & ex) { - RCLCPP_WARN_THROTTLE(get_logger(), *get_clock(), 5000, "%s", ex.what()); - } - timer_->reset(); - } -} - -void PointCloudConcatenateDataSynchronizerComponent::twist_callback( - const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr input) -{ - // if rosbag restart, clear buffer - if (!twist_ptr_queue_.empty()) { - if (rclcpp::Time(twist_ptr_queue_.front()->header.stamp) > rclcpp::Time(input->header.stamp)) { - twist_ptr_queue_.clear(); - } - } - - // pop old data - while (!twist_ptr_queue_.empty()) { - if ( - rclcpp::Time(twist_ptr_queue_.front()->header.stamp) + rclcpp::Duration::from_seconds(1.0) > - rclcpp::Time(input->header.stamp)) { - break; - } - twist_ptr_queue_.pop_front(); - } - - auto twist_ptr = std::make_shared(); - twist_ptr->header = input->header; - twist_ptr->twist = input->twist.twist; - twist_ptr_queue_.push_back(twist_ptr); -} - -void PointCloudConcatenateDataSynchronizerComponent::odom_callback( - const nav_msgs::msg::Odometry::ConstSharedPtr input) -{ - // if rosbag restart, clear buffer - if (!twist_ptr_queue_.empty()) { - if (rclcpp::Time(twist_ptr_queue_.front()->header.stamp) > rclcpp::Time(input->header.stamp)) { - twist_ptr_queue_.clear(); - } - } - - // pop old data - while (!twist_ptr_queue_.empty()) { - if ( - rclcpp::Time(twist_ptr_queue_.front()->header.stamp) + rclcpp::Duration::from_seconds(1.0) > - rclcpp::Time(input->header.stamp)) { - break; - } - twist_ptr_queue_.pop_front(); - } - - auto twist_ptr = std::make_shared(); - twist_ptr->header = input->header; - twist_ptr->twist = input->twist.twist; - twist_ptr_queue_.push_back(twist_ptr); -} - -void PointCloudConcatenateDataSynchronizerComponent::checkConcatStatus( - diagnostic_updater::DiagnosticStatusWrapper & stat) -{ - for (const std::string & e : input_topics_) { - const std::string subscribe_status = not_subscribed_topic_names_.count(e) ? "NG" : "OK"; - stat.add(e, subscribe_status); - } - - const int8_t level = not_subscribed_topic_names_.empty() - ? diagnostic_msgs::msg::DiagnosticStatus::OK - : diagnostic_msgs::msg::DiagnosticStatus::WARN; - const std::string message = not_subscribed_topic_names_.empty() - ? "Concatenate all topics" - : "Some topics are not concatenated"; - stat.summary(level, message); -} -} // namespace autoware::pointcloud_preprocessor - -#include -RCLCPP_COMPONENTS_REGISTER_NODE( - autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent) diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py new file mode 100644 index 0000000000000..3d15eecf0101c --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_component.py @@ -0,0 +1,909 @@ +#!/usr/bin/env python3 + +# Copyright 2024 TIER IV, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import random +import struct +import time +from typing import List +from typing import Tuple +import unittest + +from geometry_msgs.msg import TransformStamped +from geometry_msgs.msg import TwistWithCovarianceStamped +import launch +import launch.actions +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode +import launch_testing +import numpy as np +import pytest +import rclpy +from rclpy.qos import QoSDurabilityPolicy +from rclpy.qos import QoSHistoryPolicy +from rclpy.qos import QoSProfile +from rclpy.qos import QoSReliabilityPolicy +from rclpy.time import Time +from sensor_msgs.msg import PointCloud2 +from sensor_msgs.msg import PointField +from sensor_msgs_py import point_cloud2 +from std_msgs.msg import Header +from tf2_ros.static_transform_broadcaster import StaticTransformBroadcaster + +INPUT_LIDAR_TOPICS = [ + "/test/sensing/lidar/left/pointcloud", + "/test/sensing/lidar/right/pointcloud", + "/test/sensing/lidar/top/pointcloud", +] +FRAME_ID_LISTS = [ + "left_lidar", + "right_lidar", + "top_lidar", +] + +TIMEOUT_SEC = 0.2 +TIMESTAMP_OFFSET = [0.0, 0.04, 0.08] +TIMESTAMP_NOISE = 0.01 # 10 ms + +NUM_OF_POINTS = 3 +MILLISECONDS = 1000000 + + +STANDARD_TOLERANCE = 1e-4 +COARSE_TOLERANCE = TIMESTAMP_NOISE * 2 + +GLOBAL_SECONDS = 10 +GLOBAL_NANOSECONDS = 100000000 + +# Set to True if you want to check the output of the component tests. +DEBUG = False + + +@pytest.mark.launch_test +def generate_test_description(): + nodes = [] + + nodes.append( + ComposableNode( + package="autoware_pointcloud_preprocessor", + plugin="autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", + name="test_concatenate_node", + remappings=[ + ("~/input/twist", "/test/sensing/vehicle_velocity_converter/twist_with_covariance"), + ("output", "/test/sensing/lidar/concatenated/pointcloud"), + ], + parameters=[ + { + "debug_mode": False, + "has_static_tf_only": False, + "rosbag_length": 0.0, + "maximum_queue_size": 5, + "timeout_sec": TIMEOUT_SEC, + "is_motion_compensated": True, + "publish_synchronized_pointcloud": True, + "keep_input_frame_in_synchronized_pointcloud": True, + "publish_previous_but_late_pointcloud": True, + "synchronized_pointcloud_postfix": "pointcloud", + "input_twist_topic_type": "twist", + "input_topics": INPUT_LIDAR_TOPICS, + "output_frame": "base_link", + "matching_strategy.type": "advanced", + "matching_strategy.lidar_timestamp_offsets": TIMESTAMP_OFFSET, + "matching_strategy.lidar_timestamp_noise_window": [ + TIMESTAMP_NOISE, + TIMESTAMP_NOISE, + TIMESTAMP_NOISE, + ], + } + ], + extra_arguments=[{"use_intra_process_comms": True}], + ) + ) + + container = ComposableNodeContainer( + name="test_concatenate_data_container", + namespace="pointcloud_preprocessor", + package="rclcpp_components", + executable="component_container", + composable_node_descriptions=nodes, + output="screen", + ) + + return launch.LaunchDescription( + [ + container, + # Start tests right away - no need to wait for anything + launch_testing.actions.ReadyToTest(), + ] + ) + + +def create_header(timestamp: Time, frame_id_index: int, is_base_link: bool) -> Header: + header = Header() + header.stamp = timestamp + + if is_base_link: + header.frame_id = "base_link" + else: + header.frame_id = FRAME_ID_LISTS[frame_id_index] + return header + + +def create_points() -> List[Tuple[float, float, float]]: + return [(1.0, 0.0, 0.0), (0.0, 1.0, 0.0), (0.0, 0.0, 1.0)] + + +def create_fields() -> ( + Tuple[List[int], List[int], List[int], List[float], List[float], List[float], List[int]] +): + # The values of the fields do not influence the results. + intensities = [255] * NUM_OF_POINTS + return_types = [1] * NUM_OF_POINTS + channels = [1] * NUM_OF_POINTS + azimuths = [0.0] * NUM_OF_POINTS + elevations = [0.0] * NUM_OF_POINTS + distances = [1.0] * NUM_OF_POINTS + timestamps = [0] * NUM_OF_POINTS + return intensities, return_types, channels, azimuths, elevations, distances, timestamps + + +def get_pointcloud_msg( + timestamp: Time, is_generate_points: bool, frame_id_index: int, is_base_link: bool +) -> PointCloud2: + header = create_header(timestamp, frame_id_index, is_base_link) + points = create_points() + intensities, return_types, channels, azimuths, elevations, distances, timestamps = ( + create_fields() + ) + + pointcloud_data = bytearray() + + if is_generate_points: + for i in range(NUM_OF_POINTS): + pointcloud_data += struct.pack("fff", points[i][0], points[i][1], points[i][2]) + pointcloud_data += struct.pack("B", intensities[i]) + pointcloud_data += struct.pack("B", return_types[i]) + pointcloud_data += struct.pack("H", channels[i]) + pointcloud_data += struct.pack("f", azimuths[i]) + pointcloud_data += struct.pack("f", elevations[i]) + pointcloud_data += struct.pack("f", distances[i]) + pointcloud_data += struct.pack("I", timestamps[i]) + + fields = [ + PointField(name="x", offset=0, datatype=PointField.FLOAT32, count=1), + PointField(name="y", offset=4, datatype=PointField.FLOAT32, count=1), + PointField(name="z", offset=8, datatype=PointField.FLOAT32, count=1), + PointField(name="intensity", offset=12, datatype=PointField.UINT8, count=1), + PointField(name="return_type", offset=13, datatype=PointField.UINT8, count=1), + PointField(name="channel", offset=14, datatype=PointField.UINT16, count=1), + PointField(name="azimuth", offset=16, datatype=PointField.FLOAT32, count=1), + PointField(name="elevation", offset=20, datatype=PointField.FLOAT32, count=1), + PointField(name="distance", offset=24, datatype=PointField.FLOAT32, count=1), + PointField(name="time_stamp", offset=28, datatype=PointField.UINT32, count=1), + ] + + pointcloud_msg = PointCloud2( + header=header, + height=1, + width=NUM_OF_POINTS, + is_dense=True, + is_bigendian=False, + point_step=32, # 3*4 + 1 + 1 + 2 + 4 + 4 + 4 + 4 = 32 bytes per point + row_step=32 * NUM_OF_POINTS, + fields=fields, + data=pointcloud_data, + ) + + return pointcloud_msg + + +def generate_transform_msg( + parent_frame: str, + child_frame: str, + x: float, + y: float, + z: float, + qx: float, + qy: float, + qz: float, + qw: float, +) -> TransformStamped: + tf_msg = TransformStamped() + tf_msg.header.stamp = Time(seconds=GLOBAL_SECONDS, nanoseconds=GLOBAL_NANOSECONDS).to_msg() + tf_msg.header.frame_id = parent_frame + tf_msg.child_frame_id = child_frame + tf_msg.transform.translation.x = x + tf_msg.transform.translation.y = y + tf_msg.transform.translation.z = z + tf_msg.transform.rotation.x = qx + tf_msg.transform.rotation.y = qy + tf_msg.transform.rotation.z = qz + tf_msg.transform.rotation.w = qw + return tf_msg + + +def generate_static_transform_msgs() -> List[TransformStamped]: + tf_top_lidar_msg = generate_transform_msg( + parent_frame="base_link", + child_frame=FRAME_ID_LISTS[0], + x=0.0, + y=0.0, + z=5.0, + qx=0.0, + qy=0.0, + qz=0.0, + qw=1.0, + ) + + tf_right_lidar_msg = generate_transform_msg( + parent_frame="base_link", + child_frame=FRAME_ID_LISTS[1], + x=0.0, + y=5.0, + z=5.0, + qx=0.0, + qy=0.0, + qz=0.0, + qw=1.0, + ) + + tf_left_lidar_msg = generate_transform_msg( + parent_frame="base_link", + child_frame=FRAME_ID_LISTS[2], + x=0.0, + y=-5.0, + z=5.0, + qx=0.0, + qy=0.0, + qz=0.0, + qw=1.0, + ) + + return [tf_top_lidar_msg, tf_right_lidar_msg, tf_left_lidar_msg] + + +def generate_twist_msg() -> TwistWithCovarianceStamped: + twist_header = Header() + twist_header.stamp = Time(seconds=GLOBAL_SECONDS, nanoseconds=GLOBAL_NANOSECONDS).to_msg() + twist_header.frame_id = "base_link" + twist_msg = TwistWithCovarianceStamped() + twist_msg.header = twist_header + twist_msg.twist.twist.linear.x = 1.0 + + return twist_msg + + +def get_output_points(cloud_msg) -> np.ndarray: + points_list = [] + for point in point_cloud2.read_points(cloud_msg, field_names=("x", "y", "z")): + points_list.append([point[0], point[1], point[2]]) + points = np.array(points_list, dtype=np.float32) + return points + + +class TestConcatenateNode(unittest.TestCase): + @classmethod + def setUpClass(cls): + # Init ROS at once + rclpy.init() + + @classmethod + def tearDownClass(cls): + # Shutdown ROS at once + rclpy.shutdown() + + def setUp(self): + self.node = rclpy.create_node("test_concat_node") + tf_msg = generate_static_transform_msgs() + self.tf_broadcaster = StaticTransformBroadcaster(self.node) + self.tf_broadcaster.sendTransform(tf_msg) + self.msg_buffer = [] + self.twist_publisher, self.pointcloud_publishers = self.create_pub_sub() + + def tearDown(self): + self.node.destroy_node() + + def callback(self, msg: PointCloud2): + self.msg_buffer.append(msg) + + def create_pub_sub(self): + # QoS profile for sensor data + sensor_qos = QoSProfile( + history=QoSHistoryPolicy.KEEP_LAST, + depth=10, + reliability=QoSReliabilityPolicy.BEST_EFFORT, + durability=QoSDurabilityPolicy.VOLATILE, + ) + # Publishers + twist_publisher = self.node.create_publisher( + TwistWithCovarianceStamped, + "/test/sensing/vehicle_velocity_converter/twist_with_covariance", + 10, + ) + + pointcloud_publishers = {} + for idx, input_lidar_topic in enumerate(INPUT_LIDAR_TOPICS): + pointcloud_publishers[idx] = self.node.create_publisher( + PointCloud2, + input_lidar_topic, + qos_profile=sensor_qos, + ) + + # create subscriber + self.msg_buffer = [] + self.node.create_subscription( + PointCloud2, + "/test/sensing/lidar/concatenated/pointcloud", + self.callback, + qos_profile=sensor_qos, + ) + + return twist_publisher, pointcloud_publishers + + def test_1_normal_inputs(self): + """Test the normal situation when no pointcloud is delayed or dropped. + + This can test that + 1. Concatenate works fine when all pointclouds are arrived in time. + 2. The motion compensation of concatenation works well. + """ + time.sleep(1) + global GLOBAL_SECONDS + + twist_msg = generate_twist_msg() + self.twist_publisher.publish(twist_msg) + + for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS): + pointcloud_seconds = GLOBAL_SECONDS + pointcloud_nanoseconds = GLOBAL_NANOSECONDS + frame_idx * MILLISECONDS * 40 # add 40 ms + pointcloud_timestamp = Time( + seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds + ).to_msg() + pointcloud_msg = get_pointcloud_msg( + timestamp=pointcloud_timestamp, + is_generate_points=True, + frame_id_index=frame_idx, + is_base_link=False, + ) + self.pointcloud_publishers[frame_idx].publish(pointcloud_msg) + time.sleep(0.01) + + rclpy.spin_once(self.node, timeout_sec=0.1) + + self.assertEqual( + len(self.msg_buffer), + 1, + "The number of concatenate pointcloud has different number as expected.", + ) + + expected_pointcloud = np.array( + [ + [1.08, -5, 5], + [0.08, -4, 5], + [0.08, -5, 6], + [1.04, 5, 5], + [0.04, 6, 5], + [0.04, 5, 6], + [1, 0, 5], + [0, 1, 5], + [0, 0, 6], + ], + dtype=np.float32, + ) + + concatenate_cloud = get_output_points(self.msg_buffer[0]) + + if DEBUG: + print("concatenate_cloud: ", concatenate_cloud) + + self.assertTrue( + np.allclose(concatenate_cloud, expected_pointcloud, atol=1e-3), + "The concatenation node have weird output", + ) + + self.assertEqual( + self.msg_buffer[0].header.frame_id, + "base_link", + "The concatenate pointcloud frame id is not base_link", + ) + + GLOBAL_SECONDS += 1 + + def test_2_normal_inputs_with_noise(self): + """Test the normal situation when no pointcloud is delayed or dropped. Additionally, the pointcloud's timestamp is not ideal which has some noise. + + This can test that + 1. Concatenate works fine when pointclouds' timestamp has noise. + """ + time.sleep(1) + global GLOBAL_SECONDS + + twist_msg = generate_twist_msg() + self.twist_publisher.publish(twist_msg) + + for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS): + noise = random.uniform(-10, 10) * MILLISECONDS + pointcloud_seconds = GLOBAL_SECONDS + pointcloud_nanoseconds = ( + GLOBAL_NANOSECONDS + frame_idx * MILLISECONDS * 40 + noise + ) # add 40 ms and noise (-10 to 10 ms) + pointcloud_timestamp = Time( + seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds + ).to_msg() + pointcloud_msg = get_pointcloud_msg( + timestamp=pointcloud_timestamp, + is_generate_points=True, + frame_id_index=frame_idx, + is_base_link=False, + ) + self.pointcloud_publishers[frame_idx].publish(pointcloud_msg) + time.sleep(0.01) + + rclpy.spin_once(self.node, timeout_sec=0.1) + + self.assertEqual( + len(self.msg_buffer), + 1, + "The number of concatenate pointcloud has different number as expected.", + ) + + expected_pointcloud = np.array( + [ + [1.08, -5, 5], + [0.08, -4, 5], + [0.08, -5, 6], + [1.04, 5, 5], + [0.04, 6, 5], + [0.04, 5, 6], + [1, 0, 5], + [0, 1, 5], + [0, 0, 6], + ], + dtype=np.float32, + ) + + concatenate_cloud = get_output_points(self.msg_buffer[0]) + if DEBUG: + print("concatenate_cloud: ", concatenate_cloud) + + self.assertTrue( + np.allclose(concatenate_cloud, expected_pointcloud, atol=2e-2), + "The concatenation node have weird output", + ) + + def test_3_abnormal_null_pointcloud(self): + """Test the abnormal situation when a pointcloud is empty. + + This can test that + 1. The concatenate node ignore empty pointcloud and concatenate the remain pointcloud. + """ + time.sleep(1) + global GLOBAL_SECONDS + + twist_msg = generate_twist_msg() + self.twist_publisher.publish(twist_msg) + + for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS): + pointcloud_seconds = GLOBAL_SECONDS + pointcloud_nanoseconds = GLOBAL_NANOSECONDS + frame_idx * MILLISECONDS * 40 # add 40 ms + pointcloud_timestamp = Time( + seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds + ).to_msg() + + if frame_idx == len(INPUT_LIDAR_TOPICS) - 1: + pointcloud_msg = get_pointcloud_msg( + timestamp=pointcloud_timestamp, + is_generate_points=False, + frame_id_index=len(INPUT_LIDAR_TOPICS) - 1, + is_base_link=False, + ) + else: + pointcloud_msg = get_pointcloud_msg( + timestamp=pointcloud_timestamp, + is_generate_points=True, + frame_id_index=frame_idx, + is_base_link=False, + ) + + self.pointcloud_publishers[frame_idx].publish(pointcloud_msg) + time.sleep(0.01) + + time.sleep(TIMEOUT_SEC) # timeout threshold + rclpy.spin_once(self.node, timeout_sec=0.1) + + self.assertEqual( + len(self.msg_buffer), + 1, + "The number of concatenate pointcloud has different number as expected.", + ) + + expected_pointcloud = np.array( + [ + [1.04, 5, 5], + [0.04, 6, 5], + [0.04, 5, 6], + [1, 0, 5], + [0, 1, 5], + [0, 0, 6], + ], + dtype=np.float32, + ) + + concatenate_cloud = get_output_points(self.msg_buffer[0]) + if DEBUG: + print("concatenate_cloud: ", concatenate_cloud) + + self.assertTrue( + np.allclose(concatenate_cloud, expected_pointcloud, atol=1e-3), + "The concatenation node have weird output", + ) + + GLOBAL_SECONDS += 1 + + def test_4_abnormal_null_pointcloud_and_drop(self): + """Test the abnormal situation when a pointcloud is empty and other pointclouds are dropped. + + This can test that + 1. The concatenate node publish an empty pointcloud. + """ + time.sleep(1) + global GLOBAL_SECONDS + + twist_msg = generate_twist_msg() + self.twist_publisher.publish(twist_msg) + + pointcloud_seconds = GLOBAL_SECONDS + pointcloud_nanoseconds = GLOBAL_NANOSECONDS + pointcloud_timestamp = Time( + seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds + ).to_msg() + + pointcloud_msg = get_pointcloud_msg( + timestamp=pointcloud_timestamp, + is_generate_points=False, + frame_id_index=0, + is_base_link=False, + ) + + self.pointcloud_publishers[0].publish(pointcloud_msg) + time.sleep(0.01) + + time.sleep(TIMEOUT_SEC) # timeout threshold + rclpy.spin_once(self.node, timeout_sec=0.1) + + self.assertEqual( + len(self.msg_buffer), + 1, + "The number of concatenate pointcloud has different number as expected.", + ) + + GLOBAL_SECONDS += 1 + + def test_5_abnormal_multiple_pointcloud_drop(self): + """Test the abnormal situation when multiple pointclouds were dropped (only one pointcloud arrive). + + This can test that + 1. The concatenate node concatenates the single pointcloud after the timeout. + """ + time.sleep(1) + global GLOBAL_SECONDS + + twist_msg = generate_twist_msg() + self.twist_publisher.publish(twist_msg) + + pointcloud_seconds = GLOBAL_SECONDS + pointcloud_nanoseconds = GLOBAL_NANOSECONDS + pointcloud_timestamp = Time( + seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds + ).to_msg() + + pointcloud_msg = get_pointcloud_msg( + timestamp=pointcloud_timestamp, + is_generate_points=True, + frame_id_index=0, + is_base_link=False, + ) + + self.pointcloud_publishers[0].publish(pointcloud_msg) + time.sleep(0.01) + + time.sleep(TIMEOUT_SEC) # timeout threshold + rclpy.spin_once(self.node, timeout_sec=0.1) + + self.assertEqual( + len(self.msg_buffer), + 1, + "The number of concatenate pointcloud has different number as expected.", + ) + + expected_pointcloud = np.array( + [ + [1, 0, 5], + [0, 1, 5], + [0, 0, 6], + ], + dtype=np.float32, + ) + + concatenate_cloud = get_output_points(self.msg_buffer[0]) + if DEBUG: + print("concatenate_cloud: ", concatenate_cloud) + + self.assertTrue( + np.allclose(concatenate_cloud, expected_pointcloud, atol=1e-3), + "The concatenation node have weird output", + ) + + def test_6_abnormal_single_pointcloud_drop(self): + """Test the abnormal situation when a pointcloud was dropped. + + This can test that + 1. The concatenate node concatenate the remain pointcloud after the timeout. + """ + time.sleep(1) + global GLOBAL_SECONDS + + twist_msg = generate_twist_msg() + self.twist_publisher.publish(twist_msg) + + for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS[:-1]): + pointcloud_seconds = GLOBAL_SECONDS + pointcloud_nanoseconds = GLOBAL_NANOSECONDS + frame_idx * MILLISECONDS * 40 # add 40 ms + pointcloud_timestamp = Time( + seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds + ).to_msg() + pointcloud_msg = get_pointcloud_msg( + timestamp=pointcloud_timestamp, + is_generate_points=True, + frame_id_index=frame_idx, + is_base_link=False, + ) + self.pointcloud_publishers[frame_idx].publish(pointcloud_msg) + time.sleep(0.02) + + time.sleep(TIMEOUT_SEC) # timeout threshold + rclpy.spin_once(self.node, timeout_sec=0.1) + + # Should receive only one concatenate pointcloud + self.assertEqual( + len(self.msg_buffer), + 1, + "The number of concatenate pointcloud has different number as expected.", + ) + + expected_pointcloud = np.array( + [ + [1.04, 5, 5], + [0.04, 6, 5], + [0.04, 5, 6], + [1, 0, 5], + [0, 1, 5], + [0, 0, 6], + ], + dtype=np.float32, + ) + + concatenate_cloud = get_output_points(self.msg_buffer[0]) + if DEBUG: + print("concatenate_cloud: ", concatenate_cloud) + + self.assertTrue( + np.allclose(concatenate_cloud, expected_pointcloud, atol=1e-3), + "The concatenation node have weird output", + ) + + GLOBAL_SECONDS += 1 + + def test_7_abnormal_pointcloud_delay(self): + """Test the abnormal situation when a pointcloud was delayed after the timeout. + + This can test that + 1. The concatenate node concatenate the remain pointcloud after the timeout. + 2. The concatenate node will publish the delayed pointcloud after the timeout. + """ + time.sleep(1) + global GLOBAL_SECONDS + + twist_msg = generate_twist_msg() + self.twist_publisher.publish(twist_msg) + + for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS[:-1]): + pointcloud_seconds = GLOBAL_SECONDS + pointcloud_nanoseconds = GLOBAL_NANOSECONDS + frame_idx * MILLISECONDS * 40 # add 40 ms + pointcloud_timestamp = Time( + seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds + ).to_msg() + pointcloud_msg = get_pointcloud_msg( + timestamp=pointcloud_timestamp, + is_generate_points=True, + frame_id_index=frame_idx, + is_base_link=False, + ) + self.pointcloud_publishers[frame_idx].publish(pointcloud_msg) + time.sleep(0.02) + + time.sleep(TIMEOUT_SEC) # timeout threshold + rclpy.spin_once(self.node, timeout_sec=0.1) + + pointcloud_seconds = GLOBAL_SECONDS + pointcloud_nanoseconds = ( + GLOBAL_NANOSECONDS + (len(INPUT_LIDAR_TOPICS) - 1) * MILLISECONDS * 40 + ) # add 40 ms + pointcloud_timestamp = Time( + seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds + ).to_msg() + pointcloud_msg = get_pointcloud_msg( + timestamp=pointcloud_timestamp, + is_generate_points=True, + frame_id_index=len(INPUT_LIDAR_TOPICS) - 1, + is_base_link=False, + ) + + self.pointcloud_publishers[len(INPUT_LIDAR_TOPICS) - 1].publish(pointcloud_msg) + + time.sleep(TIMEOUT_SEC) # timeout threshold + rclpy.spin_once(self.node, timeout_sec=0.1) + + # Should receive only one concatenate pointcloud + self.assertEqual( + len(self.msg_buffer), + 2, + "The number of concatenate pointcloud has different number as expected.", + ) + + expected_pointcloud1 = np.array( + [ + [1.04, 5, 5], + [0.04, 6, 5], + [0.04, 5, 6], + [1, 0, 5], + [0, 1, 5], + [0, 0, 6], + ], + dtype=np.float32, + ) + + concatenate_cloud1 = get_output_points(self.msg_buffer[0]) + if DEBUG: + print("concatenate_cloud 1: ", concatenate_cloud1) + + self.assertTrue( + np.allclose(concatenate_cloud1, expected_pointcloud1, atol=1e-3), + "The concatenation node have weird output", + ) + + expected_pointcloud2 = np.array( + [ + [1, -5, 5], + [0, -4, 5], + [0, -5, 6], + ], + dtype=np.float32, + ) + + concatenate_cloud2 = get_output_points(self.msg_buffer[1]) + if DEBUG: + print("concatenate_cloud 2: ", concatenate_cloud2) + + self.assertTrue( + np.allclose(concatenate_cloud2, expected_pointcloud2, atol=1e-3), + "The concatenation node have weird output", + ) + + GLOBAL_SECONDS += 1 + + def test_8_abnormal_pointcloud_drop_continue_normal(self): + """Test the abnormal situation when a pointcloud was dropped. Afterward, next iteration of pointclouds comes normally. + + This can test that + 1. The concatenate node concatenate the remain pointcloud after the timeout. + 2. The concatenate node concatenate next iteration pointclouds when all of the pointcloud arrived. + """ + time.sleep(1) + global GLOBAL_SECONDS + + twist_msg = generate_twist_msg() + self.twist_publisher.publish(twist_msg) + + for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS[:-1]): + pointcloud_seconds = GLOBAL_SECONDS + pointcloud_nanoseconds = GLOBAL_NANOSECONDS + frame_idx * MILLISECONDS * 40 # add 40 ms + pointcloud_timestamp = Time( + seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds + ).to_msg() + pointcloud_msg = get_pointcloud_msg( + timestamp=pointcloud_timestamp, + is_generate_points=True, + frame_id_index=frame_idx, + is_base_link=False, + ) + self.pointcloud_publishers[frame_idx].publish(pointcloud_msg) + time.sleep(0.01) + + time.sleep(TIMEOUT_SEC) + rclpy.spin_once(self.node) + + next_global_nanosecond = GLOBAL_NANOSECONDS + 100 * MILLISECONDS + for frame_idx, _ in enumerate(INPUT_LIDAR_TOPICS): + pointcloud_seconds = GLOBAL_SECONDS + pointcloud_nanoseconds = ( + next_global_nanosecond + frame_idx * MILLISECONDS * 40 + ) # add 40 ms + pointcloud_timestamp = Time( + seconds=pointcloud_seconds, nanoseconds=pointcloud_nanoseconds + ).to_msg() + pointcloud_msg = get_pointcloud_msg( + timestamp=pointcloud_timestamp, + is_generate_points=True, + frame_id_index=frame_idx, + is_base_link=False, + ) + self.pointcloud_publishers[frame_idx].publish(pointcloud_msg) + time.sleep(0.01) + + rclpy.spin_once(self.node) + + self.assertEqual( + len(self.msg_buffer), + 2, + "The number of concatenate pointcloud has different number as expected.", + ) + + expected_pointcloud1 = np.array( + [ + [1.04, 5, 5], + [0.04, 6, 5], + [0.04, 5, 6], + [1, 0, 5], + [0, 1, 5], + [0, 0, 6], + ], + dtype=np.float32, + ) + + concatenate_cloud1 = get_output_points(self.msg_buffer[0]) + if DEBUG: + print("concatenate_cloud 1: ", concatenate_cloud1) + + self.assertTrue( + np.allclose(concatenate_cloud1, expected_pointcloud1, atol=1e-3), + "The concatenation node have weird output", + ) + + expected_pointcloud2 = np.array( + [ + [1.08, -5, 5], + [0.08, -4, 5], + [0.08, -5, 6], + [1.04, 5, 5], + [0.04, 6, 5], + [0.04, 5, 6], + [1, 0, 5], + [0, 1, 5], + [0, 0, 6], + ], + dtype=np.float32, + ) + + concatenate_cloud2 = get_output_points(self.msg_buffer[1]) + if DEBUG: + print("concatenate_cloud 2: ", concatenate_cloud2) + + self.assertTrue( + np.allclose(concatenate_cloud2, expected_pointcloud2, atol=1e-3), + "The concatenation node have weird output", + ) + + GLOBAL_SECONDS += 1 diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp new file mode 100644 index 0000000000000..bc3c7e9538c84 --- /dev/null +++ b/sensing/autoware_pointcloud_preprocessor/test/test_concatenate_node_unit.cpp @@ -0,0 +1,539 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +// Note: To regenerate the ground truth (GT) for the expected undistorted point cloud values, +// set the "debug_" value to true to display the point cloud values. Then, +// replace the expected values with the newly displayed undistorted point cloud values. + +#include "autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp" +#include "autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp" +#include "autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp" + +#include + +#include +#include + +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +class ConcatenateCloudTest : public ::testing::Test +{ +protected: + void SetUp() override + { + rclcpp::NodeOptions node_options; + // Instead of "input_topics", other parameters are not used. + // They just helps to setup the concatenate node + node_options.parameter_overrides( + {{"debug_mode", false}, + {"has_static_tf_only", false}, + {"rosbag_length", 0.0}, + {"maximum_queue_size", 5}, + {"timeout_sec", 0.2}, + {"is_motion_compensated", true}, + {"publish_synchronized_pointcloud", true}, + {"keep_input_frame_in_synchronized_pointcloud", true}, + {"publish_previous_but_late_pointcloud", false}, + {"synchronized_pointcloud_postfix", "pointcloud"}, + {"input_twist_topic_type", "twist"}, + {"input_topics", std::vector{"lidar_top", "lidar_left", "lidar_right"}}, + {"output_frame", "base_link"}, + {"matching_strategy.type", "advanced"}, + {"matching_strategy.lidar_timestamp_offsets", std::vector{0.0, 0.04, 0.08}}, + {"matching_strategy.lidar_timestamp_noise_window", std::vector{0.01, 0.01, 0.01}}}); + + concatenate_node_ = std::make_shared< + autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent>( + node_options); + combine_cloud_handler_ = + std::make_shared( + *concatenate_node_, "base_link", true, true, true, false); + + collector_ = std::make_shared( + std::dynamic_pointer_cast< + autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent>( + concatenate_node_->shared_from_this()), + combine_cloud_handler_, number_of_pointcloud, timeout_sec, collector_debug_mode); + + // Setup TF + tf_broadcaster_ = std::make_shared(concatenate_node_); + tf_broadcaster_->sendTransform(generate_static_transform_msgs()); + + // Spin the node for a while to ensure transforms are published + auto start = std::chrono::steady_clock::now(); + auto timeout = std::chrono::milliseconds(100); + while (std::chrono::steady_clock::now() - start < timeout) { + rclcpp::spin_some(concatenate_node_); + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + } + } + + static geometry_msgs::msg::TransformStamped generate_transform_msg( + const std::string & parent_frame, const std::string & child_frame, double x, double y, double z, + double qx, double qy, double qz, double qw) + { + rclcpp::Time timestamp(timestamp_seconds, timestamp_nanoseconds, RCL_ROS_TIME); + geometry_msgs::msg::TransformStamped tf_msg; + tf_msg.header.stamp = timestamp; + tf_msg.header.frame_id = parent_frame; + tf_msg.child_frame_id = child_frame; + tf_msg.transform.translation.x = x; + tf_msg.transform.translation.y = y; + tf_msg.transform.translation.z = z; + tf_msg.transform.rotation.x = qx; + tf_msg.transform.rotation.y = qy; + tf_msg.transform.rotation.z = qz; + tf_msg.transform.rotation.w = qw; + return tf_msg; + } + + static sensor_msgs::msg::PointCloud2 generate_pointcloud_msg( + bool generate_points, bool is_lidar_frame, const std::string & topic_name, + const rclcpp::Time & stamp) + { + sensor_msgs::msg::PointCloud2 pointcloud_msg; + pointcloud_msg.header.stamp = stamp; + pointcloud_msg.header.frame_id = is_lidar_frame ? topic_name : "base_link"; + pointcloud_msg.height = 1; + pointcloud_msg.is_dense = true; + pointcloud_msg.is_bigendian = false; + + if (generate_points) { + std::array points = {{ + Eigen::Vector3f(10.0f, 0.0f, 0.0f), // point 1 + Eigen::Vector3f(0.0f, 10.0f, 0.0f), // point 2 + Eigen::Vector3f(0.0f, 0.0f, 10.0f), // point 3 + }}; + + sensor_msgs::PointCloud2Modifier modifier(pointcloud_msg); + modifier.setPointCloud2Fields( + 10, "x", 1, sensor_msgs::msg::PointField::FLOAT32, "y", 1, + sensor_msgs::msg::PointField::FLOAT32, "z", 1, sensor_msgs::msg::PointField::FLOAT32, + "intensity", 1, sensor_msgs::msg::PointField::UINT8, "return_type", 1, + sensor_msgs::msg::PointField::UINT8, "channel", 1, sensor_msgs::msg::PointField::UINT16, + "azimuth", 1, sensor_msgs::msg::PointField::FLOAT32, "elevation", 1, + sensor_msgs::msg::PointField::FLOAT32, "distance", 1, sensor_msgs::msg::PointField::FLOAT32, + "time_stamp", 1, sensor_msgs::msg::PointField::UINT32); + + modifier.resize(number_of_points); + + sensor_msgs::PointCloud2Iterator iter_x(pointcloud_msg, "x"); + sensor_msgs::PointCloud2Iterator iter_y(pointcloud_msg, "y"); + sensor_msgs::PointCloud2Iterator iter_z(pointcloud_msg, "z"); + sensor_msgs::PointCloud2Iterator iter_t(pointcloud_msg, "time_stamp"); + + for (size_t i = 0; i < number_of_points; ++i) { + *iter_x = points[i].x(); + *iter_y = points[i].y(); + *iter_z = points[i].z(); + *iter_t = 0; + ++iter_x; + ++iter_y; + ++iter_z; + ++iter_t; + } + } else { + pointcloud_msg.width = 0; + pointcloud_msg.row_step = 0; + } + + return pointcloud_msg; + } + + static std::vector generate_static_transform_msgs() + { + // generate defined transformations + return { + generate_transform_msg("base_link", "lidar_top", 5.0, 5.0, 5.0, 0.683, 0.5, 0.183, 0.499), + generate_transform_msg("base_link", "lidar_left", 1.0, 1.0, 3.0, 0.278, 0.717, 0.441, 0.453)}; + generate_transform_msg("base_link", "lidar_right", 1.0, 1.0, 3.0, 0.278, 0.717, 0.441, 0.453); + } + + std::shared_ptr + concatenate_node_; + std::shared_ptr combine_cloud_handler_; + std::shared_ptr collector_; + std::shared_ptr tf_broadcaster_; + + static constexpr int32_t timestamp_seconds{10}; + static constexpr uint32_t timestamp_nanoseconds{100'000'000}; + static constexpr size_t number_of_points{3}; + static constexpr float standard_tolerance{1e-4}; + static constexpr int number_of_pointcloud{3}; + static constexpr float timeout_sec{0.2}; + static constexpr bool collector_debug_mode{false}; // For showing collector information + bool debug_{false}; // For the Unit test +}; + +//////////////////////////////// Test combine_cloud_handler //////////////////////////////// +TEST_F(ConcatenateCloudTest, TestProcessTwist) +{ + auto twist_msg = std::make_shared(); + twist_msg->header.stamp = rclcpp::Time(10, 0); + twist_msg->twist.twist.linear.x = 1.0; + twist_msg->twist.twist.angular.z = 0.1; + + combine_cloud_handler_->process_twist(twist_msg); + + ASSERT_FALSE(combine_cloud_handler_->get_twist_queue().empty()); + EXPECT_EQ(combine_cloud_handler_->get_twist_queue().front().twist.linear.x, 1.0); + EXPECT_EQ(combine_cloud_handler_->get_twist_queue().front().twist.angular.z, 0.1); +} + +TEST_F(ConcatenateCloudTest, TestProcessOdometry) +{ + auto odom_msg = std::make_shared(); + odom_msg->header.stamp = rclcpp::Time(10, 0); + odom_msg->twist.twist.linear.x = 1.0; + odom_msg->twist.twist.angular.z = 0.1; + + combine_cloud_handler_->process_odometry(odom_msg); + + ASSERT_FALSE(combine_cloud_handler_->get_twist_queue().empty()); + EXPECT_EQ(combine_cloud_handler_->get_twist_queue().front().twist.linear.x, 1.0); + EXPECT_EQ(combine_cloud_handler_->get_twist_queue().front().twist.angular.z, 0.1); +} + +TEST_F(ConcatenateCloudTest, TestComputeTransformToAdjustForOldTimestamp) +{ + // If time difference between twist msg and pointcloud stamp is more than 100 miliseconds, return + // Identity transformation. case 1: time difference larger than 100 miliseconds + rclcpp::Time pointcloud_stamp1(10, 100'000'000, RCL_ROS_TIME); + rclcpp::Time pointcloud_stamp2(10, 210'000'000, RCL_ROS_TIME); + auto twist_msg1 = std::make_shared(); + twist_msg1->header.stamp = rclcpp::Time(9, 130'000'000, RCL_ROS_TIME); + twist_msg1->twist.twist.linear.x = 1.0; + twist_msg1->twist.twist.angular.z = 0.1; + combine_cloud_handler_->process_twist(twist_msg1); + + auto twist_msg2 = std::make_shared(); + twist_msg2->header.stamp = rclcpp::Time(9, 160'000'000, RCL_ROS_TIME); + twist_msg2->twist.twist.linear.x = 1.0; + twist_msg2->twist.twist.angular.z = 0.1; + combine_cloud_handler_->process_twist(twist_msg2); + + Eigen::Matrix4f transform = combine_cloud_handler_->compute_transform_to_adjust_for_old_timestamp( + pointcloud_stamp1, pointcloud_stamp2); + + // translation + EXPECT_NEAR(transform(0, 3), 0.0, standard_tolerance); + EXPECT_NEAR(transform(1, 3), 0.0, standard_tolerance); + + EXPECT_NEAR(transform(0, 0), 1.0, standard_tolerance); + EXPECT_NEAR(transform(0, 1), 0.0, standard_tolerance); + EXPECT_NEAR(transform(1, 0), 0.0, standard_tolerance); + EXPECT_NEAR(transform(1, 1), 1.0, standard_tolerance); + + std::ostringstream oss; + oss << "Transformation matrix from cloud 2 to cloud 1:\n" << transform; + + if (debug_) { + RCLCPP_INFO(concatenate_node_->get_logger(), "%s", oss.str().c_str()); + } + + // case 2: time difference smaller than 100 miliseconds + rclcpp::Time pointcloud_stamp3(11, 100'000'000, RCL_ROS_TIME); + rclcpp::Time pointcloud_stamp4(11, 150'000'000, RCL_ROS_TIME); + auto twist_msg3 = std::make_shared(); + twist_msg3->header.stamp = rclcpp::Time(11, 130'000'000, RCL_ROS_TIME); + twist_msg3->twist.twist.linear.x = 1.0; + twist_msg3->twist.twist.angular.z = 0.1; + combine_cloud_handler_->process_twist(twist_msg3); + + auto twist_msg4 = std::make_shared(); + twist_msg4->header.stamp = rclcpp::Time(11, 160'000'000, RCL_ROS_TIME); + twist_msg4->twist.twist.linear.x = 1.0; + twist_msg4->twist.twist.angular.z = 0.1; + combine_cloud_handler_->process_twist(twist_msg4); + + transform = combine_cloud_handler_->compute_transform_to_adjust_for_old_timestamp( + pointcloud_stamp3, pointcloud_stamp4); + + // translation + EXPECT_NEAR(transform(0, 3), 0.0499996, standard_tolerance); + EXPECT_NEAR(transform(1, 3), 0.000189999, standard_tolerance); + + // rotation, yaw = 0.005 + EXPECT_NEAR(transform(0, 0), 0.999987, standard_tolerance); + EXPECT_NEAR(transform(0, 1), -0.00499998, standard_tolerance); + EXPECT_NEAR(transform(1, 0), 0.00499998, standard_tolerance); + EXPECT_NEAR(transform(1, 1), 0.999987, standard_tolerance); + + oss.str(""); + oss.clear(); + oss << "Transformation matrix from cloud 4 to cloud 3:\n" << transform; + + if (debug_) { + RCLCPP_INFO(concatenate_node_->get_logger(), "%s", oss.str().c_str()); + } +} + +//////////////////////////////// Test cloud_collector //////////////////////////////// + +TEST_F(ConcatenateCloudTest, TestSetAndGetNaiveCollectorInfo) +{ + auto naive_info = std::make_shared(); + naive_info->timestamp = 15.0; + + collector_->set_info(naive_info); + auto collector_info_new = collector_->get_info(); + + auto naive_info_new = + std::dynamic_pointer_cast( + collector_info_new); + ASSERT_NE(naive_info_new, nullptr) << "Collector info is not of type NaiveCollectorInfo"; + + EXPECT_DOUBLE_EQ(naive_info_new->timestamp, 15.0); +} + +TEST_F(ConcatenateCloudTest, TestSetAndGetAdvancedCollectorInfo) +{ + auto advanced_info = std::make_shared(); + advanced_info->timestamp = 10.0; + advanced_info->noise_window = 0.1; + collector_->set_info(advanced_info); + auto collector_info_new = collector_->get_info(); + auto advanced_info_new = + std::dynamic_pointer_cast( + collector_info_new); + ASSERT_NE(advanced_info_new, nullptr) << "Collector info is not of type AdvancedCollectorInfo"; + + // Validate the values + auto min = advanced_info_new->timestamp - advanced_info_new->noise_window; + auto max = advanced_info_new->timestamp + advanced_info_new->noise_window; + EXPECT_DOUBLE_EQ(min, 9.9); + EXPECT_DOUBLE_EQ(max, 10.1); +} + +TEST_F(ConcatenateCloudTest, TestConcatenateClouds) +{ + rclcpp::Time top_timestamp(timestamp_seconds, timestamp_nanoseconds, RCL_ROS_TIME); + rclcpp::Time left_timestamp(timestamp_seconds, timestamp_nanoseconds + 40'000'000, RCL_ROS_TIME); + rclcpp::Time right_timestamp(timestamp_seconds, timestamp_nanoseconds + 80'000'000, RCL_ROS_TIME); + sensor_msgs::msg::PointCloud2 top_pointcloud = + generate_pointcloud_msg(true, false, "lidar_top", top_timestamp); + sensor_msgs::msg::PointCloud2 left_pointcloud = + generate_pointcloud_msg(true, false, "lidar_left", left_timestamp); + sensor_msgs::msg::PointCloud2 right_pointcloud = + generate_pointcloud_msg(true, false, "lidar_right", right_timestamp); + + sensor_msgs::msg::PointCloud2::SharedPtr top_pointcloud_ptr = + std::make_shared(top_pointcloud); + sensor_msgs::msg::PointCloud2::SharedPtr left_pointcloud_ptr = + std::make_shared(left_pointcloud); + sensor_msgs::msg::PointCloud2::SharedPtr right_pointcloud_ptr = + std::make_shared(right_pointcloud); + + std::unordered_map topic_to_cloud_map; + topic_to_cloud_map["lidar_top"] = top_pointcloud_ptr; + topic_to_cloud_map["lidar_left"] = left_pointcloud_ptr; + topic_to_cloud_map["lidar_right"] = right_pointcloud_ptr; + + auto [concatenate_cloud_ptr, topic_to_transformed_cloud_map, topic_to_original_stamp_map] = + collector_->concatenate_pointclouds(topic_to_cloud_map); + + // test output concatenate cloud + // No input twist, so it will not do the motion compensation + std::array expected_pointcloud = { + {Eigen::Vector3f(10.0f, 0.0f, 0.0f), Eigen::Vector3f(0.0f, 10.0f, 0.0f), + Eigen::Vector3f(0.0f, 0.0f, 10.0f), Eigen::Vector3f(10.0f, 0.0f, 0.0f), + Eigen::Vector3f(0.0f, 10.0f, 0.0f), Eigen::Vector3f(0.0f, 0.0f, 10.0f), + Eigen::Vector3f(10.0f, 0.0f, 0.0f), Eigen::Vector3f(0.0f, 10.0f, 0.0f), + Eigen::Vector3f(0.0f, 0.0f, 10.0f)}}; + + size_t i = 0; + std::ostringstream oss; + oss << "Concatenated pointcloud:\n"; + + sensor_msgs::PointCloud2Iterator iter_x(*concatenate_cloud_ptr, "x"); + sensor_msgs::PointCloud2Iterator iter_y(*concatenate_cloud_ptr, "y"); + sensor_msgs::PointCloud2Iterator iter_z(*concatenate_cloud_ptr, "z"); + + for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z, ++i) { + oss << "Concatenated point " << i << ": (" << *iter_x << ", " << *iter_y << ", " << *iter_z + << ")\n"; + EXPECT_FLOAT_EQ(*iter_x, expected_pointcloud[i].x()); + EXPECT_FLOAT_EQ(*iter_y, expected_pointcloud[i].y()); + EXPECT_FLOAT_EQ(*iter_z, expected_pointcloud[i].z()); + } + + if (debug_) { + RCLCPP_INFO(concatenate_node_->get_logger(), "%s", oss.str().c_str()); + } + + // test concatenate cloud has the oldest pointcloud's timestamp + EXPECT_FLOAT_EQ( + top_timestamp.seconds(), rclcpp::Time(concatenate_cloud_ptr->header.stamp).seconds()); + + // test separated transformed cloud + std::array expected_top_pointcloud = { + {Eigen::Vector3f(10.0f, 0.0f, 0.0f), Eigen::Vector3f(0.0f, 10.0f, 0.0f), + Eigen::Vector3f(0.0f, 0.0f, 10.0f)}}; + std::array expected_left_pointcloud = { + {Eigen::Vector3f(10.0f, 0.0f, 0.0f), Eigen::Vector3f(0.0f, 10.0f, 0.0f), + Eigen::Vector3f(0.0f, 0.0f, 10.0f)}}; + std::array expected_right_pointcloud = { + {Eigen::Vector3f(10.0f, 0.0f, 0.0f), Eigen::Vector3f(0.0f, 10.0f, 0.0f), + Eigen::Vector3f(0.0f, 0.0f, 10.0f)}}; + + oss.clear(); + oss.str(""); + i = 0; + + sensor_msgs::PointCloud2Iterator top_pc_iter_x( + *(topic_to_transformed_cloud_map.value().at("lidar_top")), "x"); + sensor_msgs::PointCloud2Iterator top_pc_iter_y( + *(topic_to_transformed_cloud_map.value().at("lidar_top")), "y"); + sensor_msgs::PointCloud2Iterator top_pc_iter_z( + *(topic_to_transformed_cloud_map.value().at("lidar_top")), "z"); + + for (; top_pc_iter_x != top_pc_iter_x.end(); + ++top_pc_iter_x, ++top_pc_iter_y, ++top_pc_iter_z, ++i) { + oss << "Top point " << i << ": (" << *top_pc_iter_x << ", " << *top_pc_iter_y << ", " + << *top_pc_iter_z << ")\n"; + EXPECT_FLOAT_EQ(*top_pc_iter_x, expected_top_pointcloud[i].x()); + EXPECT_FLOAT_EQ(*top_pc_iter_y, expected_top_pointcloud[i].y()); + EXPECT_FLOAT_EQ(*top_pc_iter_z, expected_top_pointcloud[i].z()); + } + + if (debug_) { + RCLCPP_INFO(concatenate_node_->get_logger(), "%s", oss.str().c_str()); + } + + oss.clear(); + oss.str(""); + i = 0; + sensor_msgs::PointCloud2Iterator left_pc_iter_x( + *(topic_to_transformed_cloud_map.value().at("lidar_left")), "x"); + sensor_msgs::PointCloud2Iterator left_pc_iter_y( + *(topic_to_transformed_cloud_map.value().at("lidar_left")), "y"); + sensor_msgs::PointCloud2Iterator left_pc_iter_z( + *(topic_to_transformed_cloud_map.value().at("lidar_left")), "z"); + + for (; left_pc_iter_x != left_pc_iter_x.end(); + ++left_pc_iter_x, ++left_pc_iter_y, ++left_pc_iter_z, ++i) { + oss << "Left point " << i << ": (" << *left_pc_iter_x << ", " << *left_pc_iter_y << ", " + << *left_pc_iter_z << ")\n"; + EXPECT_FLOAT_EQ(*left_pc_iter_x, expected_left_pointcloud[i].x()); + EXPECT_FLOAT_EQ(*left_pc_iter_y, expected_left_pointcloud[i].y()); + EXPECT_FLOAT_EQ(*left_pc_iter_z, expected_left_pointcloud[i].z()); + } + + if (debug_) { + RCLCPP_INFO(concatenate_node_->get_logger(), "%s", oss.str().c_str()); + } + + oss.clear(); + oss.str(""); + i = 0; + sensor_msgs::PointCloud2Iterator right_pc_iter_x( + *(topic_to_transformed_cloud_map.value().at("lidar_right")), "x"); + sensor_msgs::PointCloud2Iterator right_pc_iter_y( + *(topic_to_transformed_cloud_map.value().at("lidar_right")), "y"); + sensor_msgs::PointCloud2Iterator right_pc_iter_z( + *(topic_to_transformed_cloud_map.value().at("lidar_right")), "z"); + + for (; right_pc_iter_x != right_pc_iter_x.end(); + ++right_pc_iter_x, ++right_pc_iter_y, ++right_pc_iter_z, ++i) { + oss << "Right point " << i << ": (" << *right_pc_iter_x << ", " << *right_pc_iter_y << ", " + << *right_pc_iter_z << ")\n"; + EXPECT_FLOAT_EQ(*right_pc_iter_x, expected_right_pointcloud[i].x()); + EXPECT_FLOAT_EQ(*right_pc_iter_y, expected_right_pointcloud[i].y()); + EXPECT_FLOAT_EQ(*right_pc_iter_z, expected_right_pointcloud[i].z()); + } + + if (debug_) { + RCLCPP_INFO(concatenate_node_->get_logger(), "%s", oss.str().c_str()); + } + + // test original cloud's timestamps + EXPECT_FLOAT_EQ(top_timestamp.seconds(), topic_to_original_stamp_map["lidar_top"]); + EXPECT_FLOAT_EQ(left_timestamp.seconds(), topic_to_original_stamp_map["lidar_left"]); + EXPECT_FLOAT_EQ(right_timestamp.seconds(), topic_to_original_stamp_map["lidar_right"]); +} + +TEST_F(ConcatenateCloudTest, TestProcessSingleCloud) +{ + concatenate_node_->add_cloud_collector(collector_); + + rclcpp::Time timestamp(timestamp_seconds, timestamp_nanoseconds, RCL_ROS_TIME); + sensor_msgs::msg::PointCloud2 top_pointcloud = + generate_pointcloud_msg(true, false, "lidar_top", timestamp); + sensor_msgs::msg::PointCloud2::SharedPtr top_pointcloud_ptr = + std::make_shared(top_pointcloud); + collector_->process_pointcloud("lidar_top", top_pointcloud_ptr); + + auto topic_to_cloud_map = collector_->get_topic_to_cloud_map(); + EXPECT_EQ(topic_to_cloud_map["lidar_top"], top_pointcloud_ptr); + EXPECT_FALSE(collector_->concatenate_finished()); + concatenate_node_->manage_collector_list(); + EXPECT_FALSE(concatenate_node_->get_cloud_collectors().empty()); + + // Sleep for timeout seconds (200 ms) + std::this_thread::sleep_for(std::chrono::milliseconds(200)); + rclcpp::spin_some(concatenate_node_); + + // Collector should concatenate and publish the pointcloud, also delete itself. + EXPECT_TRUE(collector_->concatenate_finished()); + concatenate_node_->manage_collector_list(); + EXPECT_TRUE(concatenate_node_->get_cloud_collectors().empty()); +} + +TEST_F(ConcatenateCloudTest, TestProcessMultipleCloud) +{ + concatenate_node_->add_cloud_collector(collector_); + + rclcpp::Time top_timestamp(timestamp_seconds, timestamp_nanoseconds, RCL_ROS_TIME); + rclcpp::Time left_timestamp(timestamp_seconds, timestamp_nanoseconds + 40'000'000, RCL_ROS_TIME); + rclcpp::Time right_timestamp(timestamp_seconds, timestamp_nanoseconds + 80'000'000, RCL_ROS_TIME); + sensor_msgs::msg::PointCloud2 top_pointcloud = + generate_pointcloud_msg(true, false, "lidar_top", top_timestamp); + sensor_msgs::msg::PointCloud2 left_pointcloud = + generate_pointcloud_msg(true, false, "lidar_left", left_timestamp); + sensor_msgs::msg::PointCloud2 right_pointcloud = + generate_pointcloud_msg(true, false, "lidar_right", right_timestamp); + + sensor_msgs::msg::PointCloud2::SharedPtr top_pointcloud_ptr = + std::make_shared(top_pointcloud); + sensor_msgs::msg::PointCloud2::SharedPtr left_pointcloud_ptr = + std::make_shared(left_pointcloud); + sensor_msgs::msg::PointCloud2::SharedPtr right_pointcloud_ptr = + std::make_shared(right_pointcloud); + + collector_->process_pointcloud("lidar_top", top_pointcloud_ptr); + collector_->process_pointcloud("lidar_left", left_pointcloud_ptr); + collector_->process_pointcloud("lidar_right", right_pointcloud_ptr); + + EXPECT_TRUE(collector_->concatenate_finished()); + concatenate_node_->manage_collector_list(); + EXPECT_TRUE(concatenate_node_->get_cloud_collectors().empty()); +} + +int main(int argc, char ** argv) +{ + ::testing::InitGoogleTest(&argc, argv); + rclcpp::init(argc, argv); + int ret = RUN_ALL_TESTS(); + rclcpp::shutdown(); + return ret; +} From daf9ccd5ec31d0a536d62b7e00aa3c78cacc95ed Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Tue, 21 Jan 2025 19:36:34 +0900 Subject: [PATCH 265/334] feat(workflows): bump version workflow (#9990) --- .github/workflows/bump-version-pr.yaml | 80 ++++++++++++++++++++++++++ 1 file changed, 80 insertions(+) create mode 100644 .github/workflows/bump-version-pr.yaml diff --git a/.github/workflows/bump-version-pr.yaml b/.github/workflows/bump-version-pr.yaml new file mode 100644 index 0000000000000..5f3a931e90494 --- /dev/null +++ b/.github/workflows/bump-version-pr.yaml @@ -0,0 +1,80 @@ +name: bump-version-pr + +on: + workflow_dispatch: + inputs: + version_part: + description: Which part of the version number to bump? + required: true + default: minor + type: choice + options: + - major + - minor + - patch + +jobs: + bump-version-pr: + runs-on: ubuntu-22.04 + steps: + - name: Check out repository + uses: actions/checkout@v4 + with: + ref: humble + fetch-depth: 0 + + - name: Generate token + id: generate-token + uses: actions/create-github-app-token@v1 + with: + app-id: ${{ secrets.APP_ID }} + private-key: ${{ secrets.PRIVATE_KEY }} + + - name: Set git config + uses: autowarefoundation/autoware-github-actions/set-git-config@v1 + with: + token: ${{ steps.generate-token.outputs.token }} + + - name: Setup Python 3.x + uses: actions/setup-python@v5 + with: + python-version: 3.x + + - name: Install dependencies + run: pip3 install -U catkin_tools + shell: bash + + - name: Bump version from humble branch + id: bump-version-from-humble-branch + run: | + git checkout -b tmp/bot/bump_version_base + git fetch origin main + git merge origin/main + catkin_generate_changelog -y + git add * + git commit -m "update CHANGELOG.rst" + catkin_prepare_release -y --bump ${{ inputs.version_part }} --no-push + version=$(git describe --tags) + echo "version=${version}" >> $GITHUB_OUTPUT + shell: bash + + - name: Create target branch + run: | + git checkout origin/main + git checkout -b chore/bot/bump_version + git merge tmp/bot/bump_version_base + git push origin chore/bot/bump_version --force + shell: bash + + - name: Create PR + id: create-pr + run: > + gh + pr + create + --base=main + --body="Bump version to ${{ steps.bump-version-from-humble-branch.outputs.version }}" + --title="chore: bump version to ${{ steps.bump-version-from-humble-branch.outputs.version }}" + --head=chore/bot/bump_version + env: + GH_TOKEN: ${{ steps.generate-token.outputs.token }} From bbf7f6669f69a308a3ae12aabceda193ee2d535e Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Tue, 21 Jan 2025 20:57:19 +0900 Subject: [PATCH 266/334] fix(tier4_perception_launch): rearrange roi based cluster pipeline (#9938) Signed-off-by: badai-nguyen --- .../detector/camera_lidar_detector.launch.xml | 47 ++++++++++++------- 1 file changed, 30 insertions(+), 17 deletions(-) diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml index 004e9c6dc75ba..ff890b5940f8a 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml @@ -56,20 +56,33 @@ - - - - - + + - + - - + + + + + + + + + + @@ -187,15 +200,6 @@ - - - - - - - - - @@ -250,6 +254,15 @@ + + + + + + + + + From 2c9a5874a98d4901170918f155f2064ea54057e0 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Tue, 21 Jan 2025 21:10:14 +0900 Subject: [PATCH 267/334] feat(tensorrt_yolox): add launch for tlr model (#9828) * feat(tensorrt_yolox): add launch for tlr model Signed-off-by: badai-nguyen * chore: typo Signed-off-by: badai-nguyen * docs: update readme and description Signed-off-by: badai-nguyen * style(pre-commit): autofix --------- Signed-off-by: badai-nguyen Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- perception/autoware_tensorrt_yolox/README.md | 22 ++++++++---- .../yolox_traffic_light_detector.param.yaml | 35 +++++++++++++++++++ .../yolox_traffic_light_detector.launch.xml | 24 +++++++++++++ 3 files changed, 75 insertions(+), 6 deletions(-) create mode 100644 perception/autoware_tensorrt_yolox/config/yolox_traffic_light_detector.param.yaml create mode 100644 perception/autoware_tensorrt_yolox/launch/yolox_traffic_light_detector.launch.xml diff --git a/perception/autoware_tensorrt_yolox/README.md b/perception/autoware_tensorrt_yolox/README.md index cc7113e7dfcee..b211219e60ac6 100644 --- a/perception/autoware_tensorrt_yolox/README.md +++ b/perception/autoware_tensorrt_yolox/README.md @@ -4,6 +4,8 @@ This package detects target objects e.g., cars, trucks, bicycles, and pedestrians and segment target objects such as cars, trucks, buses and pedestrian, building, vegetation, road, sidewalk on a image based on [YOLOX](https://github.com/Megvii-BaseDetection/YOLOX) model with multi-header structure. +Additionally, the package also supports traffic light detection by switching onnx file which target classes listed on respective `label_file`. Currently 0: `unknown`, 1: `car_traffic_light` and 2: `pedestrian_traffic_light`. + ## Inner-workings / Algorithms ### Cite @@ -22,12 +24,12 @@ Zheng Ge, Songtao Liu, Feng Wang, Zeming Li, Jian Sun, "YOLOX: Exceeding YOLO Se ### Output -| Name | Type | Description | -| ---------------- | -------------------------------------------------- | ------------------------------------------------------------------- | -| `out/objects` | `tier4_perception_msgs/DetectedObjectsWithFeature` | The detected objects with 2D bounding boxes | -| `out/image` | `sensor_msgs/Image` | The image with 2D bounding boxes for visualization | -| `out/mask` | `sensor_msgs/Image` | The semantic segmentation mask | -| `out/color_mask` | `sensor_msgs/Image` | The colorized image of semantic segmentation mask for visualization | +| Name | Type | Description | +| ---------------- | -------------------------------------------------- | ----------------------------------------------------------------------------------------------------- | +| `out/objects` | `tier4_perception_msgs/DetectedObjectsWithFeature` | The detected objects or traffic light with 2D bounding boxes | +| `out/image` | `sensor_msgs/Image` | The image with 2D bounding boxes for visualization | +| `out/mask` | `sensor_msgs/Image` | The semantic segmentation mask (only effective for semseg model) | +| `out/color_mask` | `sensor_msgs/Image` | The colorized image of semantic segmentation mask for visualization (only effective for semseg model) | ## Parameters @@ -45,6 +47,14 @@ The label contained in detected 2D bounding boxes (i.e., `out/objects`) will be - BICYCLE - MOTORCYCLE +or + +- UNKNOWN +- CAR_TRAFFIC_LIGHT +- PEDESTRIAN_TRAFFIC_LIGHT + +for traffic light detector onnx model. + If other labels (case insensitive) are contained in the file specified via the `label_file` parameter, those are labeled as `UNKNOWN`, while detected rectangles are drawn in the visualization result (`out/image`). diff --git a/perception/autoware_tensorrt_yolox/config/yolox_traffic_light_detector.param.yaml b/perception/autoware_tensorrt_yolox/config/yolox_traffic_light_detector.param.yaml new file mode 100644 index 0000000000000..4982204892488 --- /dev/null +++ b/perception/autoware_tensorrt_yolox/config/yolox_traffic_light_detector.param.yaml @@ -0,0 +1,35 @@ +# cspell: ignore semseg +/**: + ros__parameters: + + model_path: "$(var data_path)/tensorrt_yolox/$(var model_name).onnx" + label_path: "$(var data_path)/tensorrt_yolox/car_ped_tl_detector_labels.txt" + score_threshold: 0.35 + nms_threshold: 0.7 + + precision: "fp16" # Operation precision to be used on inference. Valid value is one of: [fp32, fp16, int8]. + calibration_algorithm: "Entropy" # Calibration algorithm to be used for quantization when precision==int8. Valid value is one of: [Entropy, (Legacy | Percentile), MinMax]. + dla_core_id: -1 # If positive ID value is specified, the node assign inference task to the DLA core. + quantize_first_layer: false # If true, set the operating precision for the first (input) layer to be fp16. This option is valid only when precision==int8. + quantize_last_layer: false # If true, set the operating precision for the last (output) layer to be fp16. This option is valid only when precision==int8. + profile_per_layer: false # If true, profiler function will be enabled. Since the profile function may affect execution speed, it is recommended to set this flag true only for development purpose. + clip_value: 6.0 # If positive value is specified, the value of each layer output will be clipped between [0.0, clip_value]. This option is valid only when precision==int8 and used to manually specify the dynamic range instead of using any calibration. + preprocess_on_gpu: true # If true, pre-processing is performed on GPU. + gpu_id: 0 # GPU ID to select CUDA Device + calibration_image_list_path: "" # Path to a file which contains path to images. Those images will be used for int8 quantization. + + + # default params of tensorrt_yolox package, only effective for semseg model + color_map_path: "$(var data_path)/tensorrt_yolox/semseg_color_map.csv" + is_roi_overlap_segment: false + overlap_roi_score_threshold: 0.3 + is_publish_color_mask: false + roi_overlay_segment_label: + UNKNOWN : false + CAR : false + TRUCK : false + BUS : false + MOTORCYCLE : false + BICYCLE : false + PEDESTRIAN : false + ANIMAL: false diff --git a/perception/autoware_tensorrt_yolox/launch/yolox_traffic_light_detector.launch.xml b/perception/autoware_tensorrt_yolox/launch/yolox_traffic_light_detector.launch.xml new file mode 100644 index 0000000000000..67aae61b54376 --- /dev/null +++ b/perception/autoware_tensorrt_yolox/launch/yolox_traffic_light_detector.launch.xml @@ -0,0 +1,24 @@ + + + + + + + + + + + + + + + + + + + + + + + + From 7102e72d48627154a9b54e07481ab7478b741c65 Mon Sep 17 00:00:00 2001 From: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Date: Tue, 21 Jan 2025 21:35:43 +0900 Subject: [PATCH 268/334] feat(motion_velocity_planner)!: add _universe suffix to autoware_motion_velocity_planner_common and autoware_motion_velocity_planner_node (#9942) Signed-off-by: Ryohsuke Mitsudome --- codecov.yaml | 4 ++-- .../motion_planning/motion_planning.launch.xml | 2 +- planning/.pages | 2 +- .../CMakeLists.txt | 2 +- .../package.xml | 2 +- .../src/dynamic_obstacle_stop_module.hpp | 4 ++-- .../src/object_filtering.hpp | 2 +- .../test/test_object_filtering.cpp | 2 +- .../CMakeLists.txt | 2 +- .../package.xml | 2 +- .../src/obstacle_velocity_limiter.hpp | 2 +- .../src/obstacle_velocity_limiter_module.hpp | 4 ++-- .../src/obstacles.hpp | 2 +- .../test/test_collision_distance.cpp | 2 +- .../CMakeLists.txt | 2 +- .../package.xml | 2 +- .../src/calculate_slowdown_points.hpp | 2 +- .../src/filter_predicted_objects.hpp | 2 +- .../src/out_of_lane_collisions.hpp | 2 +- .../src/out_of_lane_module.cpp | 2 +- .../src/out_of_lane_module.hpp | 4 ++-- .../CHANGELOG.rst | 6 +++--- .../CMakeLists.txt | 2 +- .../collision_checker.hpp | 6 +++--- .../planner_data.hpp | 8 ++++---- .../plugin_module_interface.hpp | 6 +++--- .../velocity_planning_result.hpp | 6 +++--- .../package.xml | 2 +- .../src/collision_checker.cpp | 2 +- .../test/test_collision_checker.cpp | 2 +- .../CHANGELOG.rst | 6 +++--- .../CMakeLists.txt | 2 +- .../README.md | 8 ++++---- .../config/motion_velocity_planner.param.yaml | 0 .../MotionVelocityPlanner-InternalInterface.drawio.svg | 0 .../docs/set_stop_velocity.drawio.svg | 0 .../launch/motion_velocity_planner.launch.xml | 4 ++-- .../package.xml | 4 ++-- .../schema/motion_velocity_planner.schema.json | 0 .../src/node.cpp | 0 .../src/node.hpp | 10 +++++----- .../src/planner_manager.cpp | 2 +- .../src/planner_manager.hpp | 4 ++-- .../srv/LoadPlugin.srv | 0 .../srv/UnloadPlugin.srv | 0 .../test/src/test_node_interface.cpp | 2 +- 46 files changed, 66 insertions(+), 66 deletions(-) rename planning/motion_velocity_planner/{autoware_motion_velocity_planner_common => autoware_motion_velocity_planner_common_universe}/CHANGELOG.rst (97%) rename planning/motion_velocity_planner/{autoware_motion_velocity_planner_common => autoware_motion_velocity_planner_common_universe}/CMakeLists.txt (89%) rename planning/motion_velocity_planner/{autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common => autoware_motion_velocity_planner_common_universe/include/autoware/motion_velocity_planner_common_universe}/collision_checker.hpp (91%) rename planning/motion_velocity_planner/{autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common => autoware_motion_velocity_planner_common_universe/include/autoware/motion_velocity_planner_common_universe}/planner_data.hpp (94%) rename planning/motion_velocity_planner/{autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common => autoware_motion_velocity_planner_common_universe/include/autoware/motion_velocity_planner_common_universe}/plugin_module_interface.hpp (90%) rename planning/motion_velocity_planner/{autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common => autoware_motion_velocity_planner_common_universe/include/autoware/motion_velocity_planner_common_universe}/velocity_planning_result.hpp (83%) rename planning/motion_velocity_planner/{autoware_motion_velocity_planner_common => autoware_motion_velocity_planner_common_universe}/package.xml (95%) rename planning/motion_velocity_planner/{autoware_motion_velocity_planner_common => autoware_motion_velocity_planner_common_universe}/src/collision_checker.cpp (97%) rename planning/motion_velocity_planner/{autoware_motion_velocity_planner_common => autoware_motion_velocity_planner_common_universe}/test/test_collision_checker.cpp (98%) rename planning/motion_velocity_planner/{autoware_motion_velocity_planner_node => autoware_motion_velocity_planner_node_universe}/CHANGELOG.rst (98%) rename planning/motion_velocity_planner/{autoware_motion_velocity_planner_node => autoware_motion_velocity_planner_node_universe}/CMakeLists.txt (95%) rename planning/motion_velocity_planner/{autoware_motion_velocity_planner_node => autoware_motion_velocity_planner_node_universe}/README.md (94%) rename planning/motion_velocity_planner/{autoware_motion_velocity_planner_node => autoware_motion_velocity_planner_node_universe}/config/motion_velocity_planner.param.yaml (100%) rename planning/motion_velocity_planner/{autoware_motion_velocity_planner_node => autoware_motion_velocity_planner_node_universe}/docs/MotionVelocityPlanner-InternalInterface.drawio.svg (100%) rename planning/motion_velocity_planner/{autoware_motion_velocity_planner_node => autoware_motion_velocity_planner_node_universe}/docs/set_stop_velocity.drawio.svg (100%) rename planning/motion_velocity_planner/{autoware_motion_velocity_planner_node => autoware_motion_velocity_planner_node_universe}/launch/motion_velocity_planner.launch.xml (88%) rename planning/motion_velocity_planner/{autoware_motion_velocity_planner_node => autoware_motion_velocity_planner_node_universe}/package.xml (94%) rename planning/motion_velocity_planner/{autoware_motion_velocity_planner_node => autoware_motion_velocity_planner_node_universe}/schema/motion_velocity_planner.schema.json (100%) rename planning/motion_velocity_planner/{autoware_motion_velocity_planner_node => autoware_motion_velocity_planner_node_universe}/src/node.cpp (100%) rename planning/motion_velocity_planner/{autoware_motion_velocity_planner_node => autoware_motion_velocity_planner_node_universe}/src/node.hpp (94%) rename planning/motion_velocity_planner/{autoware_motion_velocity_planner_node => autoware_motion_velocity_planner_node_universe}/src/planner_manager.cpp (98%) rename planning/motion_velocity_planner/{autoware_motion_velocity_planner_node => autoware_motion_velocity_planner_node_universe}/src/planner_manager.hpp (93%) rename planning/motion_velocity_planner/{autoware_motion_velocity_planner_node => autoware_motion_velocity_planner_node_universe}/srv/LoadPlugin.srv (100%) rename planning/motion_velocity_planner/{autoware_motion_velocity_planner_node => autoware_motion_velocity_planner_node_universe}/srv/UnloadPlugin.srv (100%) rename planning/motion_velocity_planner/{autoware_motion_velocity_planner_node => autoware_motion_velocity_planner_node_universe}/test/src/test_node_interface.cpp (99%) diff --git a/codecov.yaml b/codecov.yaml index 726b675d7ff1d..13054e15f0c99 100644 --- a/codecov.yaml +++ b/codecov.yaml @@ -243,7 +243,7 @@ component_management: - planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/** - planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/** - planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/** - - planning/motion_velocity_planner/autoware_motion_velocity_planner_common/** - - planning/motion_velocity_planner/autoware_motion_velocity_planner_node/** + - planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/** + - planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/** #### sampling_based_planner - planning/sampling_based_planner/autoware_bezier_sampler/** 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 555e8da787013..2d5177d4252d8 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 @@ -119,7 +119,7 @@ - + diff --git a/planning/.pages b/planning/.pages index 424f83cf47611..900019198fab8 100644 --- a/planning/.pages +++ b/planning/.pages @@ -61,7 +61,7 @@ nav: - 'About Surround Obstacle Checker': planning/autoware_surround_obstacle_checker - 'About Surround Obstacle Checker (Japanese)': planning/autoware_surround_obstacle_checker/surround_obstacle_checker-design.ja - 'Motion Velocity Planner': - - 'About Motion Velocity Planner': planning/motion_velocity_planner/autoware_motion_velocity_planner_node/ + - 'About Motion Velocity Planner': planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/ - 'Available Modules': - 'Dynamic Obstacle Stop': planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/ - 'Out of Lane': planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/CMakeLists.txt b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/CMakeLists.txt index 896db96fd573d..4d055e9fff223 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/CMakeLists.txt +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/CMakeLists.txt @@ -3,7 +3,7 @@ project(autoware_motion_velocity_dynamic_obstacle_stop_module) find_package(autoware_cmake REQUIRED) autoware_package() -pluginlib_export_plugin_description_file(autoware_motion_velocity_planner_node plugins.xml) +pluginlib_export_plugin_description_file(autoware_motion_velocity_planner_node_universe plugins.xml) ament_auto_add_library(${PROJECT_NAME} SHARED DIRECTORY src diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/package.xml index 1063abfb61bbb..c13aedc3292ee 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/package.xml @@ -13,7 +13,7 @@ ament_cmake_auto autoware_cmake autoware_motion_utils - autoware_motion_velocity_planner_common + autoware_motion_velocity_planner_common_universe autoware_perception_msgs autoware_planning_msgs autoware_route_handler diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.hpp index 82a6d790bebe7..a678e7657a6c3 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.hpp @@ -19,8 +19,8 @@ #include "types.hpp" #include -#include -#include +#include +#include #include #include diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/object_filtering.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/object_filtering.hpp index 6024cde019489..33abb19074099 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/object_filtering.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/object_filtering.hpp @@ -17,7 +17,7 @@ #include "types.hpp" -#include +#include #include diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/test/test_object_filtering.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/test/test_object_filtering.cpp index 5993f81c7a8f1..419b5d9e46bd1 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/test/test_object_filtering.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/test/test_object_filtering.cpp @@ -14,7 +14,7 @@ #include "../src/object_filtering.hpp" -#include +#include #include #include diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/CMakeLists.txt b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/CMakeLists.txt index 6ff39738137b3..0bd6bf6c5decc 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/CMakeLists.txt +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/CMakeLists.txt @@ -3,7 +3,7 @@ project(autoware_motion_velocity_obstacle_velocity_limiter_module) find_package(autoware_cmake REQUIRED) autoware_package() -pluginlib_export_plugin_description_file(autoware_motion_velocity_planner_node plugins.xml) +pluginlib_export_plugin_description_file(autoware_motion_velocity_planner_node_universe plugins.xml) ament_auto_add_library(${PROJECT_NAME} SHARED DIRECTORY src diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/package.xml index e608e158b3ffe..9d3796c041299 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/package.xml @@ -15,7 +15,7 @@ autoware_grid_map_utils autoware_lanelet2_extension autoware_motion_utils - autoware_motion_velocity_planner_common + autoware_motion_velocity_planner_common_universe autoware_perception_msgs autoware_planning_msgs autoware_planning_test_manager diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter.hpp index b0cdb1f802e0f..ad746fb2a7b7e 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter.hpp @@ -19,7 +19,7 @@ #include "parameters.hpp" #include "types.hpp" -#include +#include #include #include diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.hpp index 65e24c2dff349..54f9c5c12e59e 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.hpp @@ -17,8 +17,8 @@ #include "parameters.hpp" -#include -#include +#include +#include #include #include #include diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacles.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacles.hpp index a98d92994f497..aff99140744e4 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacles.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacles.hpp @@ -18,7 +18,7 @@ #include "parameters.hpp" #include "types.hpp" -#include +#include #include #include diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/test/test_collision_distance.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/test/test_collision_distance.cpp index 023ae83774917..926b730dcc3dd 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/test/test_collision_distance.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/test/test_collision_distance.cpp @@ -15,7 +15,7 @@ #include "../src/distance.hpp" #include "../src/obstacles.hpp" #include "../src/types.hpp" -#include "autoware/motion_velocity_planner_common/planner_data.hpp" +#include "autoware/motion_velocity_planner_common_universe/planner_data.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" #include diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/CMakeLists.txt b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/CMakeLists.txt index b96ca3017a031..f6301974552be 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/CMakeLists.txt +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/CMakeLists.txt @@ -3,7 +3,7 @@ project(autoware_motion_velocity_out_of_lane_module) find_package(autoware_cmake REQUIRED) autoware_package() -pluginlib_export_plugin_description_file(autoware_motion_velocity_planner_node plugins.xml) +pluginlib_export_plugin_description_file(autoware_motion_velocity_planner_node_universe plugins.xml) ament_auto_add_library(${PROJECT_NAME} SHARED DIRECTORY src diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml index f0f663355821c..8e32ca0219526 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml @@ -17,7 +17,7 @@ autoware_cmake autoware_motion_utils - autoware_motion_velocity_planner_common + autoware_motion_velocity_planner_common_universe autoware_perception_msgs autoware_planning_msgs autoware_route_handler diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp index bd757a551515e..fccde78e1a9f2 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp @@ -17,7 +17,7 @@ #include "types.hpp" -#include +#include #include #include diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.hpp index 3b2ae11718810..d59c8eae59427 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.hpp @@ -17,7 +17,7 @@ #include "types.hpp" -#include +#include #include diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.hpp index f0e0360ef1c15..a670b828aa828 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_collisions.hpp @@ -17,7 +17,7 @@ #include "types.hpp" -#include +#include #include #include diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp index ab69218ea9668..814af37aaa800 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp @@ -24,7 +24,7 @@ #include #include -#include +#include #include #include #include diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp index 0e73994dd73a7..b6eb03f5f0469 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp @@ -18,8 +18,8 @@ #include "types.hpp" #include -#include -#include +#include +#include #include #include diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/CHANGELOG.rst b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/CHANGELOG.rst similarity index 97% rename from planning/motion_velocity_planner/autoware_motion_velocity_planner_common/CHANGELOG.rst rename to planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/CHANGELOG.rst index 50db2374baedc..b6f0fe9f9dd86 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/CHANGELOG.rst +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/CHANGELOG.rst @@ -1,6 +1,6 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package autoware_motion_velocity_planner_common -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_motion_velocity_planner_common_universe +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.40.0 (2024-12-12) ------------------- diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/CMakeLists.txt b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/CMakeLists.txt similarity index 89% rename from planning/motion_velocity_planner/autoware_motion_velocity_planner_common/CMakeLists.txt rename to planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/CMakeLists.txt index ffc06aa8cc2f8..70098f42a4939 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/CMakeLists.txt +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(autoware_motion_velocity_planner_common) +project(autoware_motion_velocity_planner_common_universe) find_package(autoware_cmake REQUIRED) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/collision_checker.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/include/autoware/motion_velocity_planner_common_universe/collision_checker.hpp similarity index 91% rename from planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/collision_checker.hpp rename to planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/include/autoware/motion_velocity_planner_common_universe/collision_checker.hpp index bf471c62af969..3b135225c01cf 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/collision_checker.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/include/autoware/motion_velocity_planner_common_universe/collision_checker.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__COLLISION_CHECKER_HPP_ -#define AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__COLLISION_CHECKER_HPP_ +#ifndef AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__COLLISION_CHECKER_HPP_ +#define AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__COLLISION_CHECKER_HPP_ #include @@ -66,4 +66,4 @@ class CollisionChecker }; } // namespace autoware::motion_velocity_planner -#endif // AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__COLLISION_CHECKER_HPP_ +#endif // AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__COLLISION_CHECKER_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/include/autoware/motion_velocity_planner_common_universe/planner_data.hpp similarity index 94% rename from planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp rename to planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/include/autoware/motion_velocity_planner_common_universe/planner_data.hpp index 07c8e1580e4f0..4d4917f23496c 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/include/autoware/motion_velocity_planner_common_universe/planner_data.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_ -#define AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_ +#ifndef AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__PLANNER_DATA_HPP_ +#define AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__PLANNER_DATA_HPP_ #include -#include +#include #include #include #include @@ -166,4 +166,4 @@ struct PlannerData }; } // namespace autoware::motion_velocity_planner -#endif // AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_ +#endif // AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__PLANNER_DATA_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/include/autoware/motion_velocity_planner_common_universe/plugin_module_interface.hpp similarity index 90% rename from planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp rename to planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/include/autoware/motion_velocity_planner_common_universe/plugin_module_interface.hpp index c650e324de16a..a01b39646e6e2 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/include/autoware/motion_velocity_planner_common_universe/plugin_module_interface.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__PLUGIN_MODULE_INTERFACE_HPP_ -#define AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__PLUGIN_MODULE_INTERFACE_HPP_ +#ifndef AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__PLUGIN_MODULE_INTERFACE_HPP_ +#define AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__PLUGIN_MODULE_INTERFACE_HPP_ #include "planner_data.hpp" #include "velocity_planning_result.hpp" @@ -61,4 +61,4 @@ class PluginModuleInterface } // namespace autoware::motion_velocity_planner -#endif // AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__PLUGIN_MODULE_INTERFACE_HPP_ +#endif // AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__PLUGIN_MODULE_INTERFACE_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/velocity_planning_result.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/include/autoware/motion_velocity_planner_common_universe/velocity_planning_result.hpp similarity index 83% rename from planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/velocity_planning_result.hpp rename to planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/include/autoware/motion_velocity_planner_common_universe/velocity_planning_result.hpp index 7b41bf0ee9e3e..d3dfa7a270a16 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/velocity_planning_result.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/include/autoware/motion_velocity_planner_common_universe/velocity_planning_result.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__VELOCITY_PLANNING_RESULT_HPP_ -#define AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__VELOCITY_PLANNING_RESULT_HPP_ +#ifndef AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__VELOCITY_PLANNING_RESULT_HPP_ +#define AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__VELOCITY_PLANNING_RESULT_HPP_ #include @@ -45,4 +45,4 @@ struct VelocityPlanningResult }; } // namespace autoware::motion_velocity_planner -#endif // AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__VELOCITY_PLANNING_RESULT_HPP_ +#endif // AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__VELOCITY_PLANNING_RESULT_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/package.xml similarity index 95% rename from planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml rename to planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/package.xml index 2fc682e695f6b..098d261210583 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/package.xml @@ -1,7 +1,7 @@ - autoware_motion_velocity_planner_common + autoware_motion_velocity_planner_common_universe 0.40.0 Common functions and interfaces for motion_velocity_planner modules diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/src/collision_checker.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/src/collision_checker.cpp similarity index 97% rename from planning/motion_velocity_planner/autoware_motion_velocity_planner_common/src/collision_checker.cpp rename to planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/src/collision_checker.cpp index f16c23efcb14c..f2f930a9adf73 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/src/collision_checker.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/src/collision_checker.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware/motion_velocity_planner_common/collision_checker.hpp" +#include "autoware/motion_velocity_planner_common_universe/collision_checker.hpp" #include #include diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/test/test_collision_checker.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/test/test_collision_checker.cpp similarity index 98% rename from planning/motion_velocity_planner/autoware_motion_velocity_planner_common/test/test_collision_checker.cpp rename to planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/test/test_collision_checker.cpp index d2a4a4560a430..79d8519189b21 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/test/test_collision_checker.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/test/test_collision_checker.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware/motion_velocity_planner_common/collision_checker.hpp" +#include "autoware/motion_velocity_planner_common_universe/collision_checker.hpp" #include diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/CHANGELOG.rst b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/CHANGELOG.rst similarity index 98% rename from planning/motion_velocity_planner/autoware_motion_velocity_planner_node/CHANGELOG.rst rename to planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/CHANGELOG.rst index 4a6dc3095391f..1bafc41dc8f18 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/CHANGELOG.rst +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/CHANGELOG.rst @@ -1,6 +1,6 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package autoware_motion_velocity_planner_node -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_motion_velocity_planner_node_universe +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.40.0 (2024-12-12) ------------------- diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/CMakeLists.txt b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/CMakeLists.txt similarity index 95% rename from planning/motion_velocity_planner/autoware_motion_velocity_planner_node/CMakeLists.txt rename to planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/CMakeLists.txt index 0af4da6fd4426..cd9403ec73fe7 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/CMakeLists.txt +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(autoware_motion_velocity_planner_node) +project(autoware_motion_velocity_planner_node_universe) find_package(autoware_cmake REQUIRED) find_package(rosidl_default_generators REQUIRED) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/README.md b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/README.md similarity index 94% rename from planning/motion_velocity_planner/autoware_motion_velocity_planner_node/README.md rename to planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/README.md index c65593497b8d5..ef09e856eb72b 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/README.md +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/README.md @@ -37,10 +37,10 @@ This means that to stop before a wall, a stop point is inserted in the trajector ## Services -| Name | Type | Description | -| ------------------------- | -------------------------------------------------------- | ---------------------------- | -| `~/service/load_plugin` | autoware_motion_velocity_planner_node::srv::LoadPlugin | To request loading a plugin | -| `~/service/unload_plugin` | autoware_motion_velocity_planner_node::srv::UnloadPlugin | To request unloaded a plugin | +| Name | Type | Description | +| ------------------------- | ----------------------------------------------------------------- | ---------------------------- | +| `~/service/load_plugin` | autoware_motion_velocity_planner_node_universe::srv::LoadPlugin | To request loading a plugin | +| `~/service/unload_plugin` | autoware_motion_velocity_planner_node_universe::srv::UnloadPlugin | To request unloaded a plugin | ## Node parameters diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/config/motion_velocity_planner.param.yaml b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/config/motion_velocity_planner.param.yaml similarity index 100% rename from planning/motion_velocity_planner/autoware_motion_velocity_planner_node/config/motion_velocity_planner.param.yaml rename to planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/config/motion_velocity_planner.param.yaml diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/docs/MotionVelocityPlanner-InternalInterface.drawio.svg b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/docs/MotionVelocityPlanner-InternalInterface.drawio.svg similarity index 100% rename from planning/motion_velocity_planner/autoware_motion_velocity_planner_node/docs/MotionVelocityPlanner-InternalInterface.drawio.svg rename to planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/docs/MotionVelocityPlanner-InternalInterface.drawio.svg diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/docs/set_stop_velocity.drawio.svg b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/docs/set_stop_velocity.drawio.svg similarity index 100% rename from planning/motion_velocity_planner/autoware_motion_velocity_planner_node/docs/set_stop_velocity.drawio.svg rename to planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/docs/set_stop_velocity.drawio.svg diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/launch/motion_velocity_planner.launch.xml b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/launch/motion_velocity_planner.launch.xml similarity index 88% rename from planning/motion_velocity_planner/autoware_motion_velocity_planner_node/launch/motion_velocity_planner.launch.xml rename to planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/launch/motion_velocity_planner.launch.xml index 963394323caeb..ed831ef367de6 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/launch/motion_velocity_planner.launch.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/launch/motion_velocity_planner.launch.xml @@ -13,9 +13,9 @@ - + - + diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/package.xml similarity index 94% rename from planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml rename to planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/package.xml index 5f4c15e0f8ab9..43c9773ef11a3 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/package.xml @@ -1,7 +1,7 @@ - autoware_motion_velocity_planner_node + autoware_motion_velocity_planner_node_universe 0.40.0 Node of the motion_velocity_planner @@ -21,7 +21,7 @@ autoware_internal_debug_msgs autoware_map_msgs autoware_motion_utils - autoware_motion_velocity_planner_common + autoware_motion_velocity_planner_common_universe autoware_perception_msgs autoware_planning_factor_interface autoware_planning_msgs diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/schema/motion_velocity_planner.schema.json b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/schema/motion_velocity_planner.schema.json similarity index 100% rename from planning/motion_velocity_planner/autoware_motion_velocity_planner_node/schema/motion_velocity_planner.schema.json rename to planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/schema/motion_velocity_planner.schema.json diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/src/node.cpp similarity index 100% rename from planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp rename to planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/src/node.cpp diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/src/node.hpp similarity index 94% rename from planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp rename to planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/src/node.hpp index 4235971e76fca..826c740d85b76 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/src/node.hpp @@ -17,12 +17,12 @@ #include "planner_manager.hpp" -#include +#include #include #include #include -#include -#include +#include +#include #include #include @@ -47,8 +47,8 @@ namespace autoware::motion_velocity_planner { using autoware_map_msgs::msg::LaneletMapBin; -using autoware_motion_velocity_planner_node::srv::LoadPlugin; -using autoware_motion_velocity_planner_node::srv::UnloadPlugin; +using autoware_motion_velocity_planner_node_universe::srv::LoadPlugin; +using autoware_motion_velocity_planner_node_universe::srv::UnloadPlugin; using autoware_planning_msgs::msg::Trajectory; using TrajectoryPoints = std::vector; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/src/planner_manager.cpp similarity index 98% rename from planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.cpp rename to planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/src/planner_manager.cpp index 5bdf386479283..6d889343641a9 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/src/planner_manager.cpp @@ -25,7 +25,7 @@ namespace autoware::motion_velocity_planner MotionVelocityPlannerManager::MotionVelocityPlannerManager() : plugin_loader_( - "autoware_motion_velocity_planner_node", + "autoware_motion_velocity_planner_node_universe", "autoware::motion_velocity_planner::PluginModuleInterface") { } diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/src/planner_manager.hpp similarity index 93% rename from planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.hpp rename to planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/src/planner_manager.hpp index 0e3bd77180f6e..48f6a246c6456 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/src/planner_manager.hpp @@ -15,8 +15,8 @@ #ifndef PLANNER_MANAGER_HPP_ #define PLANNER_MANAGER_HPP_ -#include -#include +#include +#include #include #include diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/srv/LoadPlugin.srv b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/srv/LoadPlugin.srv similarity index 100% rename from planning/motion_velocity_planner/autoware_motion_velocity_planner_node/srv/LoadPlugin.srv rename to planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/srv/LoadPlugin.srv diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/srv/UnloadPlugin.srv b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/srv/UnloadPlugin.srv similarity index 100% rename from planning/motion_velocity_planner/autoware_motion_velocity_planner_node/srv/UnloadPlugin.srv rename to planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/srv/UnloadPlugin.srv diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/test/src/test_node_interface.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/test/src/test_node_interface.cpp similarity index 99% rename from planning/motion_velocity_planner/autoware_motion_velocity_planner_node/test/src/test_node_interface.cpp rename to planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/test/src/test_node_interface.cpp index 89a732ead861b..b4a95dc020ffd 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/test/src/test_node_interface.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/test/src/test_node_interface.cpp @@ -50,7 +50,7 @@ std::shared_ptr generateNode() const auto autoware_test_utils_dir = ament_index_cpp::get_package_share_directory("autoware_test_utils"); const auto motion_velocity_planner_dir = - ament_index_cpp::get_package_share_directory("autoware_motion_velocity_planner_node"); + ament_index_cpp::get_package_share_directory("autoware_motion_velocity_planner_node_universe"); const auto velocity_smoother_dir = ament_index_cpp::get_package_share_directory("autoware_velocity_smoother"); From d7914833515d6390bbc603963d1ee78792f7b271 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Tue, 21 Jan 2025 22:01:44 +0900 Subject: [PATCH 269/334] feat(autoware_path_smoother)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_path_smoother (#9910) * feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files planning/autoware_path_smoother Signed-off-by: vish0012 * Update planning/autoware_path_smoother/package.xml --------- Signed-off-by: vish0012 Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> --- .../include/autoware/path_smoother/type_alias.hpp | 4 ++-- planning/autoware_path_smoother/package.xml | 1 - .../scripts/calculation_time_plotter.py | 2 +- 3 files changed, 3 insertions(+), 4 deletions(-) diff --git a/planning/autoware_path_smoother/include/autoware/path_smoother/type_alias.hpp b/planning/autoware_path_smoother/include/autoware/path_smoother/type_alias.hpp index 5f79689d20875..5f14ebec8975e 100644 --- a/planning/autoware_path_smoother/include/autoware/path_smoother/type_alias.hpp +++ b/planning/autoware_path_smoother/include/autoware/path_smoother/type_alias.hpp @@ -15,6 +15,7 @@ #ifndef AUTOWARE__PATH_SMOOTHER__TYPE_ALIAS_HPP_ #define AUTOWARE__PATH_SMOOTHER__TYPE_ALIAS_HPP_ +#include "autoware_internal_debug_msgs/msg/float64_stamped.hpp" #include "autoware_internal_debug_msgs/msg/string_stamped.hpp" #include "autoware_planning_msgs/msg/path.hpp" #include "autoware_planning_msgs/msg/path_point.hpp" @@ -23,7 +24,6 @@ #include "geometry_msgs/msg/point.hpp" #include "nav_msgs/msg/odometry.hpp" #include "std_msgs/msg/header.hpp" -#include "tier4_debug_msgs/msg/float64_stamped.hpp" namespace autoware::path_smoother { @@ -37,8 +37,8 @@ using autoware_planning_msgs::msg::TrajectoryPoint; // navigation using nav_msgs::msg::Odometry; // debug +using autoware_internal_debug_msgs::msg::Float64Stamped; using autoware_internal_debug_msgs::msg::StringStamped; -using tier4_debug_msgs::msg::Float64Stamped; } // namespace autoware::path_smoother #endif // AUTOWARE__PATH_SMOOTHER__TYPE_ALIAS_HPP_ diff --git a/planning/autoware_path_smoother/package.xml b/planning/autoware_path_smoother/package.xml index 58bd970db541e..75b8786877707 100644 --- a/planning/autoware_path_smoother/package.xml +++ b/planning/autoware_path_smoother/package.xml @@ -27,7 +27,6 @@ rclcpp_components std_msgs tf2_ros - tier4_debug_msgs ament_cmake_ros ament_index_python diff --git a/planning/autoware_path_smoother/scripts/calculation_time_plotter.py b/planning/autoware_path_smoother/scripts/calculation_time_plotter.py index 3a18fc56f39bc..5450f919e5f9c 100755 --- a/planning/autoware_path_smoother/scripts/calculation_time_plotter.py +++ b/planning/autoware_path_smoother/scripts/calculation_time_plotter.py @@ -17,10 +17,10 @@ import argparse from collections import deque +from autoware_internal_debug_msgs.msg import StringStamped import matplotlib.pyplot as plt import rclpy from rclpy.node import Node -from tier4_debug_msgs.msg import StringStamped class CalculationCostAnalyzer(Node): From 79f9eccb835ab07142754ad8a1a7d66f0ece5ba7 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Tue, 21 Jan 2025 22:02:08 +0900 Subject: [PATCH 270/334] feat(autoware_obstacle_stop_planner)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_obstacle_stop_planner (#9906) feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files planning/autoware_obstacle_stop_planner Signed-off-by: vish0012 --- .../autoware_obstacle_stop_planner/package.xml | 2 +- .../src/adaptive_cruise_control.cpp | 2 +- .../src/adaptive_cruise_control.hpp | 7 ++++--- .../src/debug_marker.hpp | 4 ++-- .../autoware_obstacle_stop_planner/src/node.hpp | 16 ++++++++-------- 5 files changed, 16 insertions(+), 15 deletions(-) diff --git a/planning/autoware_obstacle_stop_planner/package.xml b/planning/autoware_obstacle_stop_planner/package.xml index ba6364a2b59ee..25332774366b0 100644 --- a/planning/autoware_obstacle_stop_planner/package.xml +++ b/planning/autoware_obstacle_stop_planner/package.xml @@ -21,6 +21,7 @@ autoware_cmake autoware_adapi_v1_msgs + autoware_internal_debug_msgs autoware_motion_utils autoware_perception_msgs autoware_planning_factor_interface @@ -41,7 +42,6 @@ tf2_eigen tf2_geometry_msgs tf2_ros - tier4_debug_msgs tier4_planning_msgs visualization_msgs diff --git a/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.cpp b/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.cpp index 82a4d5a7ec550..3154ce45972a3 100644 --- a/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.cpp +++ b/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.cpp @@ -181,7 +181,7 @@ AdaptiveCruiseController::AdaptiveCruiseController( param_.rough_velocity_rate = node_->declare_parameter(acc_ns + "rough_velocity_rate"); /* publisher */ - pub_debug_ = node_->create_publisher( + pub_debug_ = node_->create_publisher( "~/adaptive_cruise_control/debug_values", 1); } diff --git a/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.hpp b/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.hpp index ce57f585197ad..f4a11bc4314bd 100644 --- a/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.hpp +++ b/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.hpp @@ -17,10 +17,10 @@ #include +#include #include #include #include -#include #include #include @@ -58,7 +58,8 @@ class AdaptiveCruiseController const PredictedObject & target_object); private: - rclcpp::Publisher::SharedPtr pub_debug_; + rclcpp::Publisher::SharedPtr + pub_debug_; rclcpp::Node * node_; /* @@ -217,7 +218,7 @@ class AdaptiveCruiseController void registerQueToVelocity(const double vel, const rclcpp::Time & vel_time); /* Debug */ - mutable tier4_debug_msgs::msg::Float32MultiArrayStamped debug_values_; + mutable autoware_internal_debug_msgs::msg::Float32MultiArrayStamped debug_values_; enum DBGVAL { ESTIMATED_VEL_PCL = 0, ESTIMATED_VEL_OBJ = 1, diff --git a/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp b/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp index 72e2b52c287f1..3b8b57e7de4c6 100644 --- a/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp +++ b/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp @@ -17,9 +17,9 @@ #include #include +#include #include #include -#include #include #include @@ -41,7 +41,7 @@ using std_msgs::msg::Header; using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; -using tier4_debug_msgs::msg::Float32MultiArrayStamped; +using autoware_internal_debug_msgs::msg::Float32MultiArrayStamped; enum class PolygonType : int8_t { Vehicle = 0, Collision, SlowDownRange, SlowDown, Obstacle }; diff --git a/planning/autoware_obstacle_stop_planner/src/node.hpp b/planning/autoware_obstacle_stop_planner/src/node.hpp index fba24061896b6..ea8aed19bdcfd 100644 --- a/planning/autoware_obstacle_stop_planner/src/node.hpp +++ b/planning/autoware_obstacle_stop_planner/src/node.hpp @@ -29,6 +29,10 @@ #include #include +#include +#include +#include +#include #include #include #include @@ -36,10 +40,6 @@ #include #include #include -#include -#include -#include -#include #include #include #include @@ -81,13 +81,13 @@ using autoware::universe_utils::Point2d; using autoware::universe_utils::Polygon2d; using autoware::universe_utils::StopWatch; using autoware::vehicle_info_utils::VehicleInfo; +using autoware_internal_debug_msgs::msg::BoolStamped; +using autoware_internal_debug_msgs::msg::Float32MultiArrayStamped; +using autoware_internal_debug_msgs::msg::Float32Stamped; +using autoware_internal_debug_msgs::msg::Float64Stamped; using autoware_perception_msgs::msg::PredictedObjects; using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; -using tier4_debug_msgs::msg::BoolStamped; -using tier4_debug_msgs::msg::Float32MultiArrayStamped; -using tier4_debug_msgs::msg::Float32Stamped; -using tier4_debug_msgs::msg::Float64Stamped; using tier4_planning_msgs::msg::ExpandStopRange; using tier4_planning_msgs::msg::VelocityLimit; using tier4_planning_msgs::msg::VelocityLimitClearCommand; From b3c3f7a287cdf31f79c56f1746e641eeffddb322 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Tue, 21 Jan 2025 22:02:36 +0900 Subject: [PATCH 271/334] feat(autoware_obstacle_cruise_planner)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_obstacle_cruise_planner (#9905) feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files planning/autoware_obstacle_cruise_planner Signed-off-by: vish0012 --- .../pid_based_planner/cruise_planning_debug_info.hpp | 4 ++-- .../obstacle_cruise_planner/stop_planning_debug_info.hpp | 4 ++-- .../autoware/obstacle_cruise_planner/type_alias.hpp | 8 ++++---- planning/autoware_obstacle_cruise_planner/package.xml | 2 +- 4 files changed, 9 insertions(+), 9 deletions(-) diff --git a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/pid_based_planner/cruise_planning_debug_info.hpp b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/pid_based_planner/cruise_planning_debug_info.hpp index f2269aeaa2967..6feeb3d38b769 100644 --- a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/pid_based_planner/cruise_planning_debug_info.hpp +++ b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/pid_based_planner/cruise_planning_debug_info.hpp @@ -17,11 +17,11 @@ #include -#include "tier4_debug_msgs/msg/float32_multi_array_stamped.hpp" +#include "autoware_internal_debug_msgs/msg/float32_multi_array_stamped.hpp" #include -using tier4_debug_msgs::msg::Float32MultiArrayStamped; +using autoware_internal_debug_msgs::msg::Float32MultiArrayStamped; class CruisePlanningDebugInfo { diff --git a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/stop_planning_debug_info.hpp b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/stop_planning_debug_info.hpp index ef4f5d0eba808..1e1a4b75d6178 100644 --- a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/stop_planning_debug_info.hpp +++ b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/stop_planning_debug_info.hpp @@ -17,11 +17,11 @@ #include -#include "tier4_debug_msgs/msg/float32_multi_array_stamped.hpp" +#include "autoware_internal_debug_msgs/msg/float32_multi_array_stamped.hpp" #include -using tier4_debug_msgs::msg::Float32MultiArrayStamped; +using autoware_internal_debug_msgs::msg::Float32MultiArrayStamped; class StopPlanningDebugInfo { diff --git a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp index 31344903b6809..64156be9b7987 100644 --- a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp +++ b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp @@ -17,6 +17,8 @@ #include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" +#include "autoware_internal_debug_msgs/msg/float32_stamped.hpp" +#include "autoware_internal_debug_msgs/msg/float64_stamped.hpp" #include "autoware_perception_msgs/msg/predicted_object.hpp" #include "autoware_perception_msgs/msg/predicted_objects.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" @@ -26,8 +28,6 @@ #include "geometry_msgs/msg/twist_stamped.hpp" #include "nav_msgs/msg/odometry.hpp" #include "sensor_msgs/msg/point_cloud2.hpp" -#include "tier4_debug_msgs/msg/float32_stamped.hpp" -#include "tier4_debug_msgs/msg/float64_stamped.hpp" #include "tier4_planning_msgs/msg/stop_speed_exceeded.hpp" #include "tier4_planning_msgs/msg/velocity_limit.hpp" #include "tier4_planning_msgs/msg/velocity_limit_clear_command.hpp" @@ -37,6 +37,8 @@ #include using autoware::vehicle_info_utils::VehicleInfo; +using autoware_internal_debug_msgs::msg::Float32Stamped; +using autoware_internal_debug_msgs::msg::Float64Stamped; using autoware_perception_msgs::msg::ObjectClassification; using autoware_perception_msgs::msg::PredictedObject; using autoware_perception_msgs::msg::PredictedObjects; @@ -49,8 +51,6 @@ using geometry_msgs::msg::AccelWithCovarianceStamped; using geometry_msgs::msg::Twist; using nav_msgs::msg::Odometry; using sensor_msgs::msg::PointCloud2; -using tier4_debug_msgs::msg::Float32Stamped; -using tier4_debug_msgs::msg::Float64Stamped; using tier4_planning_msgs::msg::StopSpeedExceeded; using tier4_planning_msgs::msg::VelocityLimit; using tier4_planning_msgs::msg::VelocityLimitClearCommand; diff --git a/planning/autoware_obstacle_cruise_planner/package.xml b/planning/autoware_obstacle_cruise_planner/package.xml index 71c3b1fb1e0d5..807908de2d6dc 100644 --- a/planning/autoware_obstacle_cruise_planner/package.xml +++ b/planning/autoware_obstacle_cruise_planner/package.xml @@ -18,6 +18,7 @@ ament_cmake_auto autoware_cmake + autoware_internal_debug_msgs autoware_interpolation autoware_lanelet2_extension autoware_motion_utils @@ -38,7 +39,6 @@ std_msgs tf2 tf2_ros - tier4_debug_msgs tier4_metric_msgs tier4_planning_msgs visualization_msgs From 72fe7eb422ef23a91adeb8fdda8fc5da7ff82854 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Tue, 21 Jan 2025 22:02:49 +0900 Subject: [PATCH 272/334] feat(autoware_path_optimizer)!: tier4_debug_msgs changed to autoware-internal_debug_msgs in autoware_path_optimizer (#9907) * feat: tier4_debug_msgs changed to autoware-internal_debug_msgs in files planning/autoware_path_optimizer Signed-off-by: vish0012 * Update planning/autoware_path_optimizer/package.xml --------- Signed-off-by: vish0012 Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> --- .../include/autoware/path_optimizer/type_alias.hpp | 4 ++-- planning/autoware_path_optimizer/package.xml | 1 - .../scripts/calculation_time_plotter.py | 2 +- 3 files changed, 3 insertions(+), 4 deletions(-) diff --git a/planning/autoware_path_optimizer/include/autoware/path_optimizer/type_alias.hpp b/planning/autoware_path_optimizer/include/autoware/path_optimizer/type_alias.hpp index cf545d1a967e7..7f343c5a2a60f 100644 --- a/planning/autoware_path_optimizer/include/autoware/path_optimizer/type_alias.hpp +++ b/planning/autoware_path_optimizer/include/autoware/path_optimizer/type_alias.hpp @@ -15,6 +15,7 @@ #ifndef AUTOWARE__PATH_OPTIMIZER__TYPE_ALIAS_HPP_ #define AUTOWARE__PATH_OPTIMIZER__TYPE_ALIAS_HPP_ +#include "autoware_internal_debug_msgs/msg/float64_stamped.hpp" #include "autoware_internal_debug_msgs/msg/string_stamped.hpp" #include "autoware_planning_msgs/msg/path.hpp" #include "autoware_planning_msgs/msg/path_point.hpp" @@ -25,7 +26,6 @@ #include "geometry_msgs/msg/twist.hpp" #include "nav_msgs/msg/odometry.hpp" #include "std_msgs/msg/header.hpp" -#include "tier4_debug_msgs/msg/float64_stamped.hpp" #include "visualization_msgs/msg/marker_array.hpp" namespace autoware::path_optimizer @@ -43,8 +43,8 @@ using nav_msgs::msg::Odometry; using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; // debug +using autoware_internal_debug_msgs::msg::Float64Stamped; using autoware_internal_debug_msgs::msg::StringStamped; -using tier4_debug_msgs::msg::Float64Stamped; } // namespace autoware::path_optimizer #endif // AUTOWARE__PATH_OPTIMIZER__TYPE_ALIAS_HPP_ diff --git a/planning/autoware_path_optimizer/package.xml b/planning/autoware_path_optimizer/package.xml index 21ce487af6f4c..26e242c94902f 100644 --- a/planning/autoware_path_optimizer/package.xml +++ b/planning/autoware_path_optimizer/package.xml @@ -28,7 +28,6 @@ rclcpp_components std_msgs tf2_ros - tier4_debug_msgs tier4_planning_msgs visualization_msgs diff --git a/planning/autoware_path_optimizer/scripts/calculation_time_plotter.py b/planning/autoware_path_optimizer/scripts/calculation_time_plotter.py index 29dfccb533fbe..604aa1afeed18 100755 --- a/planning/autoware_path_optimizer/scripts/calculation_time_plotter.py +++ b/planning/autoware_path_optimizer/scripts/calculation_time_plotter.py @@ -17,10 +17,10 @@ import argparse from collections import deque +from autoware_internal_debug_msgs.msg import StringStamped import matplotlib.pyplot as plt import rclpy from rclpy.node import Node -from tier4_debug_msgs.msg import StringStamped class CalculationCostAnalyzer(Node): From 71f616d056ad9ca69efc918413d361e7c90f9b46 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Tue, 21 Jan 2025 22:05:47 +0900 Subject: [PATCH 273/334] feat(autoware_pure_pursuit)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_pure_pursuit (#9849) feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files control/autoware_pure_pursuit Signed-off-by: vish0012 --- .../autoware_pure_pursuit_lateral_controller.hpp | 5 +++-- control/autoware_pure_pursuit/package.xml | 2 +- .../autoware_pure_pursuit_lateral_controller.cpp | 7 ++++--- 3 files changed, 8 insertions(+), 6 deletions(-) diff --git a/control/autoware_pure_pursuit/include/autoware/pure_pursuit/autoware_pure_pursuit_lateral_controller.hpp b/control/autoware_pure_pursuit/include/autoware/pure_pursuit/autoware_pure_pursuit_lateral_controller.hpp index 16cb6471deb2c..f1ad63738df7c 100644 --- a/control/autoware_pure_pursuit/include/autoware/pure_pursuit/autoware_pure_pursuit_lateral_controller.hpp +++ b/control/autoware_pure_pursuit/include/autoware/pure_pursuit/autoware_pure_pursuit_lateral_controller.hpp @@ -42,11 +42,11 @@ #include #include "autoware_control_msgs/msg/lateral.hpp" +#include "autoware_internal_debug_msgs/msg/float32_multi_array_stamped.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "geometry_msgs/msg/twist_stamped.hpp" #include "nav_msgs/msg/odometry.hpp" -#include "tier4_debug_msgs/msg/float32_multi_array_stamped.hpp" #include // To be replaced by std::optional in C++17 @@ -115,7 +115,8 @@ class PurePursuitLateralController : public LateralControllerBase // Debug Publisher rclcpp::Publisher::SharedPtr pub_debug_marker_; - rclcpp::Publisher::SharedPtr pub_debug_values_; + rclcpp::Publisher::SharedPtr + pub_debug_values_; // Predicted Trajectory publish rclcpp::Publisher::SharedPtr pub_predicted_trajectory_; diff --git a/control/autoware_pure_pursuit/package.xml b/control/autoware_pure_pursuit/package.xml index 06500ddb32af0..5b61cc10af1f5 100644 --- a/control/autoware_pure_pursuit/package.xml +++ b/control/autoware_pure_pursuit/package.xml @@ -15,6 +15,7 @@ autoware_cmake autoware_control_msgs + autoware_internal_debug_msgs autoware_motion_utils autoware_planning_msgs autoware_trajectory_follower_base @@ -32,7 +33,6 @@ tf2_eigen tf2_geometry_msgs tf2_ros - tier4_debug_msgs visualization_msgs ament_lint_auto diff --git a/control/autoware_pure_pursuit/src/autoware_pure_pursuit/autoware_pure_pursuit_lateral_controller.cpp b/control/autoware_pure_pursuit/src/autoware_pure_pursuit/autoware_pure_pursuit_lateral_controller.cpp index f3a7bc3c1333d..d173cfe64d3e8 100644 --- a/control/autoware_pure_pursuit/src/autoware_pure_pursuit/autoware_pure_pursuit_lateral_controller.cpp +++ b/control/autoware_pure_pursuit/src/autoware_pure_pursuit/autoware_pure_pursuit_lateral_controller.cpp @@ -92,8 +92,9 @@ PurePursuitLateralController::PurePursuitLateralController(rclcpp::Node & node) // Debug Publishers pub_debug_marker_ = node.create_publisher("~/debug/markers", 0); - pub_debug_values_ = node.create_publisher( - "~/debug/ld_outputs", rclcpp::QoS{1}); + pub_debug_values_ = + node.create_publisher( + "~/debug/ld_outputs", rclcpp::QoS{1}); // Publish predicted trajectory pub_predicted_trajectory_ = node.create_publisher( @@ -118,7 +119,7 @@ double PurePursuitLateralController::calcLookaheadDistance( std::clamp(vel_ld + curvature_ld + lateral_error_ld, min_ld, param_.max_lookahead_distance); auto pubDebugValues = [&]() { - tier4_debug_msgs::msg::Float32MultiArrayStamped debug_msg{}; + autoware_internal_debug_msgs::msg::Float32MultiArrayStamped debug_msg{}; debug_msg.data.resize(TYPE::SIZE); debug_msg.data.at(TYPE::VEL_LD) = static_cast(vel_ld); debug_msg.data.at(TYPE::CURVATURE_LD) = static_cast(curvature_ld); From a3bd66faa1395367a83c4a2fc40d49cde65207aa Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Tue, 21 Jan 2025 22:44:43 +0900 Subject: [PATCH 274/334] feat(crosswalk): update judgle time against the stopped objects (#9988) Signed-off-by: yuki-takagi-66 --- .../src/scene_crosswalk.hpp | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index cc9b8733eb6b6..8601119df8344 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -197,14 +197,10 @@ class CrosswalkModule : public SceneModuleInterfaceWithRTC const bool is_object_away_from_path, const std::optional & ego_crosswalk_passage_direction) { - const bool is_stopped = vel < planner_param.stop_object_velocity; + const bool is_object_stopped = vel < planner_param.stop_object_velocity; // Check if the object can be ignored - if (is_stopped) { - if (collision_state == CollisionState::IGNORE) { - return; - } - + if (is_object_stopped && is_ego_yielding) { if (!time_to_start_stopped) { time_to_start_stopped = now; } @@ -215,7 +211,7 @@ class CrosswalkModule : public SceneModuleInterfaceWithRTC planner_param.timeout_set_for_no_intention_to_walk, distance_to_crosswalk); const bool intent_to_cross = (now - *time_to_start_stopped).seconds() < timeout_no_intention_to_walk; - if (is_ego_yielding && !intent_to_cross && is_object_away_from_path) { + if (!intent_to_cross && is_object_away_from_path) { collision_state = CollisionState::IGNORE; return; } @@ -223,6 +219,10 @@ class CrosswalkModule : public SceneModuleInterfaceWithRTC time_to_start_stopped = std::nullopt; } + if (is_object_stopped && collision_state == CollisionState::IGNORE) { + return; + } + // Compare time to collision and vehicle if (collision_point) { auto isVehicleType = [](const uint8_t label) { From 0ac858079e5356b37af744aef668952670cbc619 Mon Sep 17 00:00:00 2001 From: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Date: Tue, 21 Jan 2025 23:17:11 +0900 Subject: [PATCH 275/334] feat(autoware_mission_planner)!: feat(autoware_mission_planner_universe)!: add _universe suffix to package name (#9941) Signed-off-by: Ryohsuke Mitsudome --- codecov.yaml | 2 +- .../mission_planning.launch.xml | 6 +++--- launch/tier4_planning_launch/package.xml | 2 +- planning/.pages | 2 +- .../plugins/plugin_description.xml | 3 --- .../CHANGELOG.rst | 6 +++--- .../CMakeLists.txt | 10 +++++----- .../README.md | 0 .../config/mission_planner.param.yaml | 0 .../mission_planner_plugin.hpp | 10 +++++----- .../launch/goal_pose_visualizer.launch.xml | 2 +- .../launch/mission_planner.launch.xml | 6 +++--- .../media/architecture.drawio.svg | 0 .../media/goal_footprints.svg | 0 .../media/rerouting_safety.svg | 0 .../media/route_sections.svg | 0 .../package.xml | 4 ++-- .../plugins/plugin_description.xml | 3 +++ .../schema/mission_planner.schema.json | 0 .../goal_pose_visualizer.cpp | 6 +++--- .../goal_pose_visualizer.hpp | 4 ++-- .../src/lanelet2_plugins/default_planner.cpp | 7 ++++--- .../src/lanelet2_plugins/default_planner.hpp | 8 ++++---- .../lanelet2_plugins/utility_functions.cpp | 4 ++-- .../lanelet2_plugins/utility_functions.hpp | 4 ++-- .../src/mission_planner/arrival_checker.cpp | 4 ++-- .../src/mission_planner/arrival_checker.hpp | 4 ++-- .../src/mission_planner/mission_planner.cpp | 13 ++++++------ .../src/mission_planner/mission_planner.hpp | 6 +++--- .../src/mission_planner/route_selector.cpp | 10 +++++----- .../src/mission_planner/route_selector.hpp | 4 ++-- .../src/mission_planner/service_utils.cpp | 0 .../src/mission_planner/service_utils.hpp | 0 .../test_lanelet2_plugins_default_planner.cpp | 4 ++-- .../test/test_utility_functions.cpp | 20 +++++++++---------- 35 files changed, 78 insertions(+), 76 deletions(-) delete mode 100644 planning/autoware_mission_planner/plugins/plugin_description.xml rename planning/{autoware_mission_planner => autoware_mission_planner_universe}/CHANGELOG.rst (98%) rename planning/{autoware_mission_planner => autoware_mission_planner_universe}/CMakeLists.txt (81%) rename planning/{autoware_mission_planner => autoware_mission_planner_universe}/README.md (100%) rename planning/{autoware_mission_planner => autoware_mission_planner_universe}/config/mission_planner.param.yaml (100%) rename planning/{autoware_mission_planner/include/autoware/mission_planner => autoware_mission_planner_universe/include/autoware/mission_planner_universe}/mission_planner_plugin.hpp (83%) rename planning/{autoware_mission_planner => autoware_mission_planner_universe}/launch/goal_pose_visualizer.launch.xml (74%) rename planning/{autoware_mission_planner => autoware_mission_planner_universe}/launch/mission_planner.launch.xml (81%) rename planning/{autoware_mission_planner => autoware_mission_planner_universe}/media/architecture.drawio.svg (100%) rename planning/{autoware_mission_planner => autoware_mission_planner_universe}/media/goal_footprints.svg (100%) rename planning/{autoware_mission_planner => autoware_mission_planner_universe}/media/rerouting_safety.svg (100%) rename planning/{autoware_mission_planner => autoware_mission_planner_universe}/media/route_sections.svg (100%) rename planning/{autoware_mission_planner => autoware_mission_planner_universe}/package.xml (93%) create mode 100644 planning/autoware_mission_planner_universe/plugins/plugin_description.xml rename planning/{autoware_mission_planner => autoware_mission_planner_universe}/schema/mission_planner.schema.json (100%) rename planning/{autoware_mission_planner => autoware_mission_planner_universe}/src/goal_pose_visualizer/goal_pose_visualizer.cpp (88%) rename planning/{autoware_mission_planner => autoware_mission_planner_universe}/src/goal_pose_visualizer/goal_pose_visualizer.hpp (93%) rename planning/{autoware_mission_planner => autoware_mission_planner_universe}/src/lanelet2_plugins/default_planner.cpp (98%) rename planning/{autoware_mission_planner => autoware_mission_planner_universe}/src/lanelet2_plugins/default_planner.hpp (93%) rename planning/{autoware_mission_planner => autoware_mission_planner_universe}/src/lanelet2_plugins/utility_functions.cpp (98%) rename planning/{autoware_mission_planner => autoware_mission_planner_universe}/src/lanelet2_plugins/utility_functions.hpp (95%) rename planning/{autoware_mission_planner => autoware_mission_planner_universe}/src/mission_planner/arrival_checker.cpp (95%) rename planning/{autoware_mission_planner => autoware_mission_planner_universe}/src/mission_planner/arrival_checker.hpp (94%) rename planning/{autoware_mission_planner => autoware_mission_planner_universe}/src/mission_planner/mission_planner.cpp (98%) rename planning/{autoware_mission_planner => autoware_mission_planner_universe}/src/mission_planner/mission_planner.hpp (97%) rename planning/{autoware_mission_planner => autoware_mission_planner_universe}/src/mission_planner/route_selector.cpp (97%) rename planning/{autoware_mission_planner => autoware_mission_planner_universe}/src/mission_planner/route_selector.hpp (97%) rename planning/{autoware_mission_planner => autoware_mission_planner_universe}/src/mission_planner/service_utils.cpp (100%) rename planning/{autoware_mission_planner => autoware_mission_planner_universe}/src/mission_planner/service_utils.hpp (100%) rename planning/{autoware_mission_planner => autoware_mission_planner_universe}/test/test_lanelet2_plugins_default_planner.cpp (99%) rename planning/{autoware_mission_planner => autoware_mission_planner_universe}/test/test_utility_functions.cpp (95%) diff --git a/codecov.yaml b/codecov.yaml index 13054e15f0c99..46d6dd3b5f6b0 100644 --- a/codecov.yaml +++ b/codecov.yaml @@ -194,7 +194,7 @@ component_management: - planning/autoware_external_velocity_limit_selector/** - planning/autoware_freespace_planner/** - planning/autoware_freespace_planning_algorithms/** - - planning/autoware_mission_planner/** + - planning/autoware_mission_planner_universe/** # - planning/autoware_objects_of_interest_marker_interface/** - planning/autoware_obstacle_cruise_planner/** # - planning/autoware_obstacle_stop_planner/** diff --git a/launch/tier4_planning_launch/launch/mission_planning/mission_planning.launch.xml b/launch/tier4_planning_launch/launch/mission_planning/mission_planning.launch.xml index cd33e7517ddc3..c5c4debd80956 100644 --- a/launch/tier4_planning_launch/launch/mission_planning/mission_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/mission_planning/mission_planning.launch.xml @@ -1,11 +1,11 @@ - + - + - + diff --git a/launch/tier4_planning_launch/package.xml b/launch/tier4_planning_launch/package.xml index 0a6e9d7fce13a..0acb4738d8068 100644 --- a/launch/tier4_planning_launch/package.xml +++ b/launch/tier4_planning_launch/package.xml @@ -64,7 +64,7 @@ autoware_external_velocity_limit_selector autoware_freespace_planner autoware_glog_component - autoware_mission_planner + autoware_mission_planner_universe autoware_obstacle_cruise_planner autoware_obstacle_stop_planner autoware_path_optimizer diff --git a/planning/.pages b/planning/.pages index 900019198fab8..7444815cdd28a 100644 --- a/planning/.pages +++ b/planning/.pages @@ -39,7 +39,7 @@ nav: - 'About Freespace Planner': planning/autoware_freespace_planner - 'Algorithm': planning/autoware_freespace_planning_algorithms - 'RRT*': planning/autoware_freespace_planning_algorithms/rrtstar - - 'Mission Planner': planning/autoware_mission_planner + - 'Mission Planner': planning/autoware_mission_planner_universe - 'Motion Planning': - 'Path Optimizer': - 'About Path Optimizer': planning/autoware_path_optimizer diff --git a/planning/autoware_mission_planner/plugins/plugin_description.xml b/planning/autoware_mission_planner/plugins/plugin_description.xml deleted file mode 100644 index 488e6afd35df1..0000000000000 --- a/planning/autoware_mission_planner/plugins/plugin_description.xml +++ /dev/null @@ -1,3 +0,0 @@ - - - diff --git a/planning/autoware_mission_planner/CHANGELOG.rst b/planning/autoware_mission_planner_universe/CHANGELOG.rst similarity index 98% rename from planning/autoware_mission_planner/CHANGELOG.rst rename to planning/autoware_mission_planner_universe/CHANGELOG.rst index ed21313c96af2..ecbc1c4d7feef 100644 --- a/planning/autoware_mission_planner/CHANGELOG.rst +++ b/planning/autoware_mission_planner_universe/CHANGELOG.rst @@ -1,6 +1,6 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package autoware_mission_planner -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_mission_planner_universe +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.40.0 (2024-12-12) ------------------- diff --git a/planning/autoware_mission_planner/CMakeLists.txt b/planning/autoware_mission_planner_universe/CMakeLists.txt similarity index 81% rename from planning/autoware_mission_planner/CMakeLists.txt rename to planning/autoware_mission_planner_universe/CMakeLists.txt index 939903c2999ff..5c2445c9e2dcf 100644 --- a/planning/autoware_mission_planner/CMakeLists.txt +++ b/planning/autoware_mission_planner_universe/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(autoware_mission_planner) +project(autoware_mission_planner_universe) find_package(autoware_cmake REQUIRED) autoware_package() @@ -9,7 +9,7 @@ ament_auto_add_library(goal_pose_visualizer_component SHARED ) rclcpp_components_register_node(goal_pose_visualizer_component - PLUGIN "autoware::mission_planner::GoalPoseVisualizer" + PLUGIN "autoware::mission_planner_universe::GoalPoseVisualizer" EXECUTABLE goal_pose_visualizer ) @@ -21,12 +21,12 @@ ament_auto_add_library(${PROJECT_NAME}_component SHARED ) rclcpp_components_register_node(${PROJECT_NAME}_component - PLUGIN "autoware::mission_planner::MissionPlanner" + PLUGIN "autoware::mission_planner_universe::MissionPlanner" EXECUTABLE mission_planner ) rclcpp_components_register_node(${PROJECT_NAME}_component - PLUGIN "autoware::mission_planner::RouteSelector" + PLUGIN "autoware::mission_planner_universe::RouteSelector" EXECUTABLE route_selector ) @@ -34,7 +34,7 @@ ament_auto_add_library(${PROJECT_NAME}_lanelet2_plugins SHARED src/lanelet2_plugins/default_planner.cpp src/lanelet2_plugins/utility_functions.cpp ) -pluginlib_export_plugin_description_file(autoware_mission_planner plugins/plugin_description.xml) +pluginlib_export_plugin_description_file(autoware_mission_planner_universe plugins/plugin_description.xml) if(BUILD_TESTING) ament_add_ros_isolated_gtest(test_${PROJECT_NAME} diff --git a/planning/autoware_mission_planner/README.md b/planning/autoware_mission_planner_universe/README.md similarity index 100% rename from planning/autoware_mission_planner/README.md rename to planning/autoware_mission_planner_universe/README.md diff --git a/planning/autoware_mission_planner/config/mission_planner.param.yaml b/planning/autoware_mission_planner_universe/config/mission_planner.param.yaml similarity index 100% rename from planning/autoware_mission_planner/config/mission_planner.param.yaml rename to planning/autoware_mission_planner_universe/config/mission_planner.param.yaml diff --git a/planning/autoware_mission_planner/include/autoware/mission_planner/mission_planner_plugin.hpp b/planning/autoware_mission_planner_universe/include/autoware/mission_planner_universe/mission_planner_plugin.hpp similarity index 83% rename from planning/autoware_mission_planner/include/autoware/mission_planner/mission_planner_plugin.hpp rename to planning/autoware_mission_planner_universe/include/autoware/mission_planner_universe/mission_planner_plugin.hpp index 837ea15a55486..17287db8c8b90 100644 --- a/planning/autoware_mission_planner/include/autoware/mission_planner/mission_planner_plugin.hpp +++ b/planning/autoware_mission_planner_universe/include/autoware/mission_planner_universe/mission_planner_plugin.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__MISSION_PLANNER__MISSION_PLANNER_PLUGIN_HPP_ -#define AUTOWARE__MISSION_PLANNER__MISSION_PLANNER_PLUGIN_HPP_ +#ifndef AUTOWARE__MISSION_PLANNER_UNIVERSE__MISSION_PLANNER_PLUGIN_HPP_ +#define AUTOWARE__MISSION_PLANNER_UNIVERSE__MISSION_PLANNER_PLUGIN_HPP_ #include @@ -24,7 +24,7 @@ #include -namespace autoware::mission_planner +namespace autoware::mission_planner_universe { class PlannerPlugin @@ -45,6 +45,6 @@ class PlannerPlugin virtual void clearRoute() = 0; }; -} // namespace autoware::mission_planner +} // namespace autoware::mission_planner_universe -#endif // AUTOWARE__MISSION_PLANNER__MISSION_PLANNER_PLUGIN_HPP_ +#endif // AUTOWARE__MISSION_PLANNER_UNIVERSE__MISSION_PLANNER_PLUGIN_HPP_ diff --git a/planning/autoware_mission_planner/launch/goal_pose_visualizer.launch.xml b/planning/autoware_mission_planner_universe/launch/goal_pose_visualizer.launch.xml similarity index 74% rename from planning/autoware_mission_planner/launch/goal_pose_visualizer.launch.xml rename to planning/autoware_mission_planner_universe/launch/goal_pose_visualizer.launch.xml index a376bd1da7e58..c6266e71aabbd 100644 --- a/planning/autoware_mission_planner/launch/goal_pose_visualizer.launch.xml +++ b/planning/autoware_mission_planner_universe/launch/goal_pose_visualizer.launch.xml @@ -2,7 +2,7 @@ - + diff --git a/planning/autoware_mission_planner/launch/mission_planner.launch.xml b/planning/autoware_mission_planner_universe/launch/mission_planner.launch.xml similarity index 81% rename from planning/autoware_mission_planner/launch/mission_planner.launch.xml rename to planning/autoware_mission_planner_universe/launch/mission_planner.launch.xml index c15874118011a..ec20ed0a1318c 100644 --- a/planning/autoware_mission_planner/launch/mission_planner.launch.xml +++ b/planning/autoware_mission_planner_universe/launch/mission_planner.launch.xml @@ -2,10 +2,10 @@ - + - + @@ -16,7 +16,7 @@ - + diff --git a/planning/autoware_mission_planner/media/architecture.drawio.svg b/planning/autoware_mission_planner_universe/media/architecture.drawio.svg similarity index 100% rename from planning/autoware_mission_planner/media/architecture.drawio.svg rename to planning/autoware_mission_planner_universe/media/architecture.drawio.svg diff --git a/planning/autoware_mission_planner/media/goal_footprints.svg b/planning/autoware_mission_planner_universe/media/goal_footprints.svg similarity index 100% rename from planning/autoware_mission_planner/media/goal_footprints.svg rename to planning/autoware_mission_planner_universe/media/goal_footprints.svg diff --git a/planning/autoware_mission_planner/media/rerouting_safety.svg b/planning/autoware_mission_planner_universe/media/rerouting_safety.svg similarity index 100% rename from planning/autoware_mission_planner/media/rerouting_safety.svg rename to planning/autoware_mission_planner_universe/media/rerouting_safety.svg diff --git a/planning/autoware_mission_planner/media/route_sections.svg b/planning/autoware_mission_planner_universe/media/route_sections.svg similarity index 100% rename from planning/autoware_mission_planner/media/route_sections.svg rename to planning/autoware_mission_planner_universe/media/route_sections.svg diff --git a/planning/autoware_mission_planner/package.xml b/planning/autoware_mission_planner_universe/package.xml similarity index 93% rename from planning/autoware_mission_planner/package.xml rename to planning/autoware_mission_planner_universe/package.xml index e7cf974b2ba25..73da68c792d6f 100644 --- a/planning/autoware_mission_planner/package.xml +++ b/planning/autoware_mission_planner_universe/package.xml @@ -1,9 +1,9 @@ - autoware_mission_planner + autoware_mission_planner_universe 0.40.0 - The autoware_mission_planner package + The autoware_mission_planner_universe package Takagi, Isamu Kosuke Takeuchi Ryohsuke Mitsudome diff --git a/planning/autoware_mission_planner_universe/plugins/plugin_description.xml b/planning/autoware_mission_planner_universe/plugins/plugin_description.xml new file mode 100644 index 0000000000000..51d560bdfb6c3 --- /dev/null +++ b/planning/autoware_mission_planner_universe/plugins/plugin_description.xml @@ -0,0 +1,3 @@ + + + diff --git a/planning/autoware_mission_planner/schema/mission_planner.schema.json b/planning/autoware_mission_planner_universe/schema/mission_planner.schema.json similarity index 100% rename from planning/autoware_mission_planner/schema/mission_planner.schema.json rename to planning/autoware_mission_planner_universe/schema/mission_planner.schema.json diff --git a/planning/autoware_mission_planner/src/goal_pose_visualizer/goal_pose_visualizer.cpp b/planning/autoware_mission_planner_universe/src/goal_pose_visualizer/goal_pose_visualizer.cpp similarity index 88% rename from planning/autoware_mission_planner/src/goal_pose_visualizer/goal_pose_visualizer.cpp rename to planning/autoware_mission_planner_universe/src/goal_pose_visualizer/goal_pose_visualizer.cpp index 62a718279a4da..3299646332917 100644 --- a/planning/autoware_mission_planner/src/goal_pose_visualizer/goal_pose_visualizer.cpp +++ b/planning/autoware_mission_planner_universe/src/goal_pose_visualizer/goal_pose_visualizer.cpp @@ -14,7 +14,7 @@ #include "goal_pose_visualizer.hpp" -namespace autoware::mission_planner +namespace autoware::mission_planner_universe { GoalPoseVisualizer::GoalPoseVisualizer(const rclcpp::NodeOptions & node_options) : Node("goal_pose_visualizer", node_options) @@ -34,7 +34,7 @@ void GoalPoseVisualizer::echo_back_route_callback( goal_pose.pose = msg->goal_pose; pub_goal_pose_->publish(goal_pose); } -} // namespace autoware::mission_planner +} // namespace autoware::mission_planner_universe #include -RCLCPP_COMPONENTS_REGISTER_NODE(autoware::mission_planner::GoalPoseVisualizer) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::mission_planner_universe::GoalPoseVisualizer) diff --git a/planning/autoware_mission_planner/src/goal_pose_visualizer/goal_pose_visualizer.hpp b/planning/autoware_mission_planner_universe/src/goal_pose_visualizer/goal_pose_visualizer.hpp similarity index 93% rename from planning/autoware_mission_planner/src/goal_pose_visualizer/goal_pose_visualizer.hpp rename to planning/autoware_mission_planner_universe/src/goal_pose_visualizer/goal_pose_visualizer.hpp index 3737597556ce4..33fa5795cca26 100644 --- a/planning/autoware_mission_planner/src/goal_pose_visualizer/goal_pose_visualizer.hpp +++ b/planning/autoware_mission_planner_universe/src/goal_pose_visualizer/goal_pose_visualizer.hpp @@ -20,7 +20,7 @@ #include #include -namespace autoware::mission_planner +namespace autoware::mission_planner_universe { class GoalPoseVisualizer : public rclcpp::Node { @@ -35,5 +35,5 @@ class GoalPoseVisualizer : public rclcpp::Node const autoware_planning_msgs::msg::LaneletRoute::ConstSharedPtr msg); }; -} // namespace autoware::mission_planner +} // namespace autoware::mission_planner_universe #endif // GOAL_POSE_VISUALIZER__GOAL_POSE_VISUALIZER_HPP_ diff --git a/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.cpp b/planning/autoware_mission_planner_universe/src/lanelet2_plugins/default_planner.cpp similarity index 98% rename from planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.cpp rename to planning/autoware_mission_planner_universe/src/lanelet2_plugins/default_planner.cpp index 50a6becf2e124..acd2b75fa2e21 100644 --- a/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.cpp +++ b/planning/autoware_mission_planner_universe/src/lanelet2_plugins/default_planner.cpp @@ -41,7 +41,7 @@ #include #include -namespace autoware::mission_planner::lanelet2 +namespace autoware::mission_planner_universe::lanelet2 { void DefaultPlanner::initialize_common(rclcpp::Node * node) @@ -383,8 +383,9 @@ void DefaultPlanner::clearRoute() route_handler_.clearRoute(); } -} // namespace autoware::mission_planner::lanelet2 +} // namespace autoware::mission_planner_universe::lanelet2 #include PLUGINLIB_EXPORT_CLASS( - autoware::mission_planner::lanelet2::DefaultPlanner, autoware::mission_planner::PlannerPlugin) + autoware::mission_planner_universe::lanelet2::DefaultPlanner, + autoware::mission_planner_universe::PlannerPlugin) diff --git a/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.hpp b/planning/autoware_mission_planner_universe/src/lanelet2_plugins/default_planner.hpp similarity index 93% rename from planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.hpp rename to planning/autoware_mission_planner_universe/src/lanelet2_plugins/default_planner.hpp index ef5f34d4a3697..5af96e976ef8b 100644 --- a/planning/autoware_mission_planner/src/lanelet2_plugins/default_planner.hpp +++ b/planning/autoware_mission_planner_universe/src/lanelet2_plugins/default_planner.hpp @@ -15,7 +15,7 @@ #ifndef LANELET2_PLUGINS__DEFAULT_PLANNER_HPP_ #define LANELET2_PLUGINS__DEFAULT_PLANNER_HPP_ -#include +#include #include #include #include @@ -29,7 +29,7 @@ #include -namespace autoware::mission_planner::lanelet2 +namespace autoware::mission_planner_universe::lanelet2 { struct DefaultPlannerParameters @@ -40,7 +40,7 @@ struct DefaultPlannerParameters bool check_footprint_inside_lanes; }; -class DefaultPlanner : public mission_planner::PlannerPlugin +class DefaultPlanner : public mission_planner_universe::PlannerPlugin { public: DefaultPlanner() : vehicle_info_(), is_graph_ready_(false), param_(), node_(nullptr) {} @@ -101,6 +101,6 @@ class DefaultPlanner : public mission_planner::PlannerPlugin Pose refine_goal_height(const Pose & goal, const RouteSections & route_sections); }; -} // namespace autoware::mission_planner::lanelet2 +} // namespace autoware::mission_planner_universe::lanelet2 #endif // LANELET2_PLUGINS__DEFAULT_PLANNER_HPP_ diff --git a/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.cpp b/planning/autoware_mission_planner_universe/src/lanelet2_plugins/utility_functions.cpp similarity index 98% rename from planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.cpp rename to planning/autoware_mission_planner_universe/src/lanelet2_plugins/utility_functions.cpp index 40bccd118965f..fd6e40ab0566e 100644 --- a/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.cpp +++ b/planning/autoware_mission_planner_universe/src/lanelet2_plugins/utility_functions.cpp @@ -25,7 +25,7 @@ #include #include -namespace autoware::mission_planner::lanelet2 +namespace autoware::mission_planner_universe::lanelet2 { autoware::universe_utils::Polygon2d convert_linear_ring_to_polygon( autoware::universe_utils::LinearRing2d footprint) @@ -158,4 +158,4 @@ geometry_msgs::msg::Pose get_closest_centerline_pose( return convertBasicPoint3dToPose(refined_point, lane_yaw); } -} // namespace autoware::mission_planner::lanelet2 +} // namespace autoware::mission_planner_universe::lanelet2 diff --git a/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.hpp b/planning/autoware_mission_planner_universe/src/lanelet2_plugins/utility_functions.hpp similarity index 95% rename from planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.hpp rename to planning/autoware_mission_planner_universe/src/lanelet2_plugins/utility_functions.hpp index 36a2e17fb5ff0..233c8ef08ec23 100644 --- a/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.hpp +++ b/planning/autoware_mission_planner_universe/src/lanelet2_plugins/utility_functions.hpp @@ -29,7 +29,7 @@ #include -namespace autoware::mission_planner::lanelet2 +namespace autoware::mission_planner_universe::lanelet2 { using RouteSections = std::vector; @@ -64,5 +64,5 @@ geometry_msgs::msg::Pose get_closest_centerline_pose( const lanelet::ConstLanelets & road_lanelets, const geometry_msgs::msg::Pose & point, autoware::vehicle_info_utils::VehicleInfo vehicle_info); -} // namespace autoware::mission_planner::lanelet2 +} // namespace autoware::mission_planner_universe::lanelet2 #endif // LANELET2_PLUGINS__UTILITY_FUNCTIONS_HPP_ diff --git a/planning/autoware_mission_planner/src/mission_planner/arrival_checker.cpp b/planning/autoware_mission_planner_universe/src/mission_planner/arrival_checker.cpp similarity index 95% rename from planning/autoware_mission_planner/src/mission_planner/arrival_checker.cpp rename to planning/autoware_mission_planner_universe/src/mission_planner/arrival_checker.cpp index 41502d8c3c2c3..37e31a77ab5d5 100644 --- a/planning/autoware_mission_planner/src/mission_planner/arrival_checker.cpp +++ b/planning/autoware_mission_planner_universe/src/mission_planner/arrival_checker.cpp @@ -20,7 +20,7 @@ #include -namespace autoware::mission_planner +namespace autoware::mission_planner_universe { ArrivalChecker::ArrivalChecker(rclcpp::Node * node) : vehicle_stop_checker_(node) @@ -72,4 +72,4 @@ bool ArrivalChecker::is_arrived(const PoseStamped & pose) const return vehicle_stop_checker_.isVehicleStopped(duration_); } -} // namespace autoware::mission_planner +} // namespace autoware::mission_planner_universe diff --git a/planning/autoware_mission_planner/src/mission_planner/arrival_checker.hpp b/planning/autoware_mission_planner_universe/src/mission_planner/arrival_checker.hpp similarity index 94% rename from planning/autoware_mission_planner/src/mission_planner/arrival_checker.hpp rename to planning/autoware_mission_planner_universe/src/mission_planner/arrival_checker.hpp index d2e9a7408b791..9c339fae8ed07 100644 --- a/planning/autoware_mission_planner/src/mission_planner/arrival_checker.hpp +++ b/planning/autoware_mission_planner_universe/src/mission_planner/arrival_checker.hpp @@ -22,7 +22,7 @@ #include #include -namespace autoware::mission_planner +namespace autoware::mission_planner_universe { class ArrivalChecker @@ -44,6 +44,6 @@ class ArrivalChecker autoware::motion_utils::VehicleStopChecker vehicle_stop_checker_; }; -} // namespace autoware::mission_planner +} // namespace autoware::mission_planner_universe #endif // MISSION_PLANNER__ARRIVAL_CHECKER_HPP_ diff --git a/planning/autoware_mission_planner/src/mission_planner/mission_planner.cpp b/planning/autoware_mission_planner_universe/src/mission_planner/mission_planner.cpp similarity index 98% rename from planning/autoware_mission_planner/src/mission_planner/mission_planner.cpp rename to planning/autoware_mission_planner_universe/src/mission_planner/mission_planner.cpp index b806feded9802..58a081a6d6a2b 100644 --- a/planning/autoware_mission_planner/src/mission_planner/mission_planner.cpp +++ b/planning/autoware_mission_planner_universe/src/mission_planner/mission_planner.cpp @@ -32,13 +32,14 @@ #include #include -namespace autoware::mission_planner +namespace autoware::mission_planner_universe { MissionPlanner::MissionPlanner(const rclcpp::NodeOptions & options) : Node("mission_planner", options), arrival_checker_(this), - plugin_loader_("autoware_mission_planner", "autoware::mission_planner::PlannerPlugin"), + plugin_loader_( + "autoware_mission_planner_universe", "autoware::mission_planner_universe::PlannerPlugin"), tf_buffer_(get_clock()), tf_listener_(tf_buffer_), odometry_(nullptr), @@ -52,8 +53,8 @@ MissionPlanner::MissionPlanner(const rclcpp::NodeOptions & options) minimum_reroute_length_ = declare_parameter("minimum_reroute_length"); allow_reroute_in_autonomous_mode_ = declare_parameter("allow_reroute_in_autonomous_mode"); - planner_ = - plugin_loader_.createSharedInstance("autoware::mission_planner::lanelet2::DefaultPlanner"); + planner_ = plugin_loader_.createSharedInstance( + "autoware::mission_planner_universe::lanelet2::DefaultPlanner"); planner_->initialize(this); const auto durable_qos = rclcpp::QoS(1).transient_local(); @@ -671,7 +672,7 @@ bool MissionPlanner::check_reroute_safety( accumulated_length, safety_length); return false; } -} // namespace autoware::mission_planner +} // namespace autoware::mission_planner_universe #include -RCLCPP_COMPONENTS_REGISTER_NODE(autoware::mission_planner::MissionPlanner) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::mission_planner_universe::MissionPlanner) diff --git a/planning/autoware_mission_planner/src/mission_planner/mission_planner.hpp b/planning/autoware_mission_planner_universe/src/mission_planner/mission_planner.hpp similarity index 97% rename from planning/autoware_mission_planner/src/mission_planner/mission_planner.hpp rename to planning/autoware_mission_planner_universe/src/mission_planner/mission_planner.hpp index 18f0d3a9c259d..10288e18c8b2a 100644 --- a/planning/autoware_mission_planner/src/mission_planner/mission_planner.hpp +++ b/planning/autoware_mission_planner_universe/src/mission_planner/mission_planner.hpp @@ -18,7 +18,7 @@ #include "arrival_checker.hpp" #include "autoware/universe_utils/ros/polling_subscriber.hpp" -#include +#include #include #include #include @@ -45,7 +45,7 @@ #include #include -namespace autoware::mission_planner +namespace autoware::mission_planner_universe { using autoware_adapi_v1_msgs::msg::OperationModeState; @@ -150,6 +150,6 @@ class MissionPlanner : public rclcpp::Node pub_processing_time_; }; -} // namespace autoware::mission_planner +} // namespace autoware::mission_planner_universe #endif // MISSION_PLANNER__MISSION_PLANNER_HPP_ diff --git a/planning/autoware_mission_planner/src/mission_planner/route_selector.cpp b/planning/autoware_mission_planner_universe/src/mission_planner/route_selector.cpp similarity index 97% rename from planning/autoware_mission_planner/src/mission_planner/route_selector.cpp rename to planning/autoware_mission_planner_universe/src/mission_planner/route_selector.cpp index ad7daba18dece..b628f90794a44 100644 --- a/planning/autoware_mission_planner/src/mission_planner/route_selector.cpp +++ b/planning/autoware_mission_planner_universe/src/mission_planner/route_selector.cpp @@ -20,7 +20,7 @@ #include #include -namespace autoware::mission_planner::uuid +namespace autoware::mission_planner_universe::uuid { std::array generate_random_id() @@ -40,9 +40,9 @@ UUID generate_if_empty(const UUID & uuid) return result; } -} // namespace autoware::mission_planner::uuid +} // namespace autoware::mission_planner_universe::uuid -namespace autoware::mission_planner +namespace autoware::mission_planner_universe { RouteInterface::RouteInterface(rclcpp::Clock::SharedPtr clock) @@ -309,7 +309,7 @@ ResponseStatus RouteSelector::resume_main_route(ClearRoute::Request::SharedPtr r throw std::logic_error("route_selector: unknown main route request"); } -} // namespace autoware::mission_planner +} // namespace autoware::mission_planner_universe #include -RCLCPP_COMPONENTS_REGISTER_NODE(autoware::mission_planner::RouteSelector) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::mission_planner_universe::RouteSelector) diff --git a/planning/autoware_mission_planner/src/mission_planner/route_selector.hpp b/planning/autoware_mission_planner_universe/src/mission_planner/route_selector.hpp similarity index 97% rename from planning/autoware_mission_planner/src/mission_planner/route_selector.hpp rename to planning/autoware_mission_planner_universe/src/mission_planner/route_selector.hpp index 3e52f6962c47e..4b631c05c1f88 100644 --- a/planning/autoware_mission_planner/src/mission_planner/route_selector.hpp +++ b/planning/autoware_mission_planner_universe/src/mission_planner/route_selector.hpp @@ -28,7 +28,7 @@ #include #include -namespace autoware::mission_planner +namespace autoware::mission_planner_universe { using autoware_common_msgs::msg::ResponseStatus; @@ -107,6 +107,6 @@ class RouteSelector : public rclcpp::Node ResponseStatus resume_main_route(ClearRoute::Request::SharedPtr req); }; -} // namespace autoware::mission_planner +} // namespace autoware::mission_planner_universe #endif // MISSION_PLANNER__ROUTE_SELECTOR_HPP_ diff --git a/planning/autoware_mission_planner/src/mission_planner/service_utils.cpp b/planning/autoware_mission_planner_universe/src/mission_planner/service_utils.cpp similarity index 100% rename from planning/autoware_mission_planner/src/mission_planner/service_utils.cpp rename to planning/autoware_mission_planner_universe/src/mission_planner/service_utils.cpp diff --git a/planning/autoware_mission_planner/src/mission_planner/service_utils.hpp b/planning/autoware_mission_planner_universe/src/mission_planner/service_utils.hpp similarity index 100% rename from planning/autoware_mission_planner/src/mission_planner/service_utils.hpp rename to planning/autoware_mission_planner_universe/src/mission_planner/service_utils.hpp diff --git a/planning/autoware_mission_planner/test/test_lanelet2_plugins_default_planner.cpp b/planning/autoware_mission_planner_universe/test/test_lanelet2_plugins_default_planner.cpp similarity index 99% rename from planning/autoware_mission_planner/test/test_lanelet2_plugins_default_planner.cpp rename to planning/autoware_mission_planner_universe/test/test_lanelet2_plugins_default_planner.cpp index 8da26ab851bb4..bbe3b6c40fe47 100644 --- a/planning/autoware_mission_planner/test/test_lanelet2_plugins_default_planner.cpp +++ b/planning/autoware_mission_planner_universe/test/test_lanelet2_plugins_default_planner.cpp @@ -40,7 +40,7 @@ using geometry_msgs::msg::Pose; using RoutePoints = std::vector; // inherit DefaultPlanner to access protected methods and make wrapper to private methods -struct DefaultPlanner : public autoware::mission_planner::lanelet2::DefaultPlanner +struct DefaultPlanner : public autoware::mission_planner_universe::lanelet2::DefaultPlanner { // todo(someone): create tests with various kinds of maps void set_default_test_map() { route_handler_.setMap(autoware::test_utils::makeMapBinMsg()); } @@ -83,7 +83,7 @@ class DefaultPlannerTest : public ::testing::Test const auto autoware_test_utils_dir = ament_index_cpp::get_package_share_directory("autoware_test_utils"); const auto mission_planner_dir = - ament_index_cpp::get_package_share_directory("autoware_mission_planner"); + ament_index_cpp::get_package_share_directory("autoware_mission_planner_universe"); options.arguments( {"--ros-args", "--params-file", autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", "--params-file", diff --git a/planning/autoware_mission_planner/test/test_utility_functions.cpp b/planning/autoware_mission_planner_universe/test/test_utility_functions.cpp similarity index 95% rename from planning/autoware_mission_planner/test/test_utility_functions.cpp rename to planning/autoware_mission_planner_universe/test/test_utility_functions.cpp index da44a2ad17cf0..a531900d69dc1 100644 --- a/planning/autoware_mission_planner/test/test_utility_functions.cpp +++ b/planning/autoware_mission_planner_universe/test/test_utility_functions.cpp @@ -25,16 +25,16 @@ #include -using autoware::mission_planner::lanelet2::convert_linear_ring_to_polygon; -using autoware::mission_planner::lanelet2::convertBasicPoint3dToPose; -using autoware::mission_planner::lanelet2::convertCenterlineToPoints; -using autoware::mission_planner::lanelet2::exists; -using autoware::mission_planner::lanelet2::get_closest_centerline_pose; -using autoware::mission_planner::lanelet2::insert_marker_array; -using autoware::mission_planner::lanelet2::is_in_lane; -using autoware::mission_planner::lanelet2::is_in_parking_lot; -using autoware::mission_planner::lanelet2::is_in_parking_space; -using autoware::mission_planner::lanelet2::project_goal_to_map; +using autoware::mission_planner_universe::lanelet2::convert_linear_ring_to_polygon; +using autoware::mission_planner_universe::lanelet2::convertBasicPoint3dToPose; +using autoware::mission_planner_universe::lanelet2::convertCenterlineToPoints; +using autoware::mission_planner_universe::lanelet2::exists; +using autoware::mission_planner_universe::lanelet2::get_closest_centerline_pose; +using autoware::mission_planner_universe::lanelet2::insert_marker_array; +using autoware::mission_planner_universe::lanelet2::is_in_lane; +using autoware::mission_planner_universe::lanelet2::is_in_parking_lot; +using autoware::mission_planner_universe::lanelet2::is_in_parking_space; +using autoware::mission_planner_universe::lanelet2::project_goal_to_map; using autoware::vehicle_info_utils::VehicleInfo; using geometry_msgs::msg::Pose; From f36d0728cab4abdf72c6d6b2257fea4550eee939 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Wed, 22 Jan 2025 09:37:16 +0900 Subject: [PATCH 276/334] feat(autoware_goal_distance_calculator)!: tier4_debug_msgs to autoware_internal_debug_msgs for autoware_goal_distance_calculator (#9833) Signed-off-by: vish0012 --- common/autoware_goal_distance_calculator/Readme.md | 12 ++++++------ .../goal_distance_calculator_node.hpp | 2 +- common/autoware_goal_distance_calculator/package.xml | 2 +- .../src/goal_distance_calculator_node.cpp | 11 ++++++----- 4 files changed, 14 insertions(+), 13 deletions(-) diff --git a/common/autoware_goal_distance_calculator/Readme.md b/common/autoware_goal_distance_calculator/Readme.md index 28a1e2fada086..77a71bb23c2bc 100644 --- a/common/autoware_goal_distance_calculator/Readme.md +++ b/common/autoware_goal_distance_calculator/Readme.md @@ -17,12 +17,12 @@ This node publishes deviation of self-pose from goal pose. ### Output -| Name | Type | Description | -| ------------------------ | --------------------------------------- | ------------------------------------------------------------- | -| `deviation/lateral` | `tier4_debug_msgs::msg::Float64Stamped` | publish lateral deviation of self-pose from goal pose[m] | -| `deviation/longitudinal` | `tier4_debug_msgs::msg::Float64Stamped` | publish longitudinal deviation of self-pose from goal pose[m] | -| `deviation/yaw` | `tier4_debug_msgs::msg::Float64Stamped` | publish yaw deviation of self-pose from goal pose[rad] | -| `deviation/yaw_deg` | `tier4_debug_msgs::msg::Float64Stamped` | publish yaw deviation of self-pose from goal pose[deg] | +| Name | Type | Description | +| ------------------------ | --------------------------------------------------- | ------------------------------------------------------------- | +| `deviation/lateral` | `autoware_internal_debug_msgs::msg::Float64Stamped` | publish lateral deviation of self-pose from goal pose[m] | +| `deviation/longitudinal` | `autoware_internal_debug_msgs::msg::Float64Stamped` | publish longitudinal deviation of self-pose from goal pose[m] | +| `deviation/yaw` | `autoware_internal_debug_msgs::msg::Float64Stamped` | publish yaw deviation of self-pose from goal pose[rad] | +| `deviation/yaw_deg` | `autoware_internal_debug_msgs::msg::Float64Stamped` | publish yaw deviation of self-pose from goal pose[deg] | ## Parameters diff --git a/common/autoware_goal_distance_calculator/include/autoware/goal_distance_calculator/goal_distance_calculator_node.hpp b/common/autoware_goal_distance_calculator/include/autoware/goal_distance_calculator/goal_distance_calculator_node.hpp index f6f617292ab15..60d33b6ddc7af 100644 --- a/common/autoware_goal_distance_calculator/include/autoware/goal_distance_calculator/goal_distance_calculator_node.hpp +++ b/common/autoware_goal_distance_calculator/include/autoware/goal_distance_calculator/goal_distance_calculator_node.hpp @@ -22,9 +22,9 @@ #include #include +#include #include #include -#include #include diff --git a/common/autoware_goal_distance_calculator/package.xml b/common/autoware_goal_distance_calculator/package.xml index 903d77515f262..9b36f0a40dd52 100644 --- a/common/autoware_goal_distance_calculator/package.xml +++ b/common/autoware_goal_distance_calculator/package.xml @@ -10,12 +10,12 @@ ament_cmake autoware_cmake + autoware_internal_debug_msgs autoware_planning_msgs autoware_universe_utils geometry_msgs rclcpp rclcpp_components - tier4_debug_msgs ament_lint_auto autoware_lint_common diff --git a/common/autoware_goal_distance_calculator/src/goal_distance_calculator_node.cpp b/common/autoware_goal_distance_calculator/src/goal_distance_calculator_node.cpp index c00a2e9bb452d..0e38dfc170f2e 100644 --- a/common/autoware_goal_distance_calculator/src/goal_distance_calculator_node.cpp +++ b/common/autoware_goal_distance_calculator/src/goal_distance_calculator_node.cpp @@ -18,7 +18,7 @@ #include #include -#include +#include #include #include @@ -100,12 +100,13 @@ void GoalDistanceCalculatorNode::onTimer() using autoware::universe_utils::rad2deg; const auto & deviation = output.goal_deviation; - debug_publisher_.publish( + debug_publisher_.publish( "deviation/lateral", deviation.lateral); - debug_publisher_.publish( + debug_publisher_.publish( "deviation/longitudinal", deviation.longitudinal); - debug_publisher_.publish("deviation/yaw", deviation.yaw); - debug_publisher_.publish( + debug_publisher_.publish( + "deviation/yaw", deviation.yaw); + debug_publisher_.publish( "deviation/yaw_deg", rad2deg(deviation.yaw)); RCLCPP_INFO_THROTTLE( this->get_logger(), *this->get_clock(), 1000, From b132a88a52c0cc2023d3cecf52f712c45bf2c3ca Mon Sep 17 00:00:00 2001 From: TetsuKawa <70682030+TetsuKawa@users.noreply.github.com> Date: Wed, 22 Jan 2025 14:27:12 +0900 Subject: [PATCH 277/334] fix(autoware_dummy_diag_publisher): add autowre prefix (#9958) * fic: add autoare_ prefix Signed-off-by: TetsuKawa * fix: add autoare_ prefix codeowner Signed-off-by: TetsuKawa * style(pre-commit): autofix --------- Signed-off-by: TetsuKawa Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .github/CODEOWNERS | 2 +- .../CHANGELOG.rst | 0 .../CMakeLists.txt | 4 ++-- .../README.md | 2 +- .../config/_empty.param.yaml | 0 .../config/dummy_diag_publisher.param.yaml | 0 .../config/extra.param.yaml | 0 .../dummy_diag_publisher_core.hpp | 9 ++++++--- .../launch/dummy_diag_publisher.launch.xml | 6 +++--- .../launch/dummy_diag_publisher_node.launch.xml | 13 +++++++++++++ .../package.xml | 2 +- .../src/dummy_diag_publisher_core.cpp | 8 ++++---- .../launch/dummy_diag_publisher_node.launch.xml | 13 ------------- 13 files changed, 31 insertions(+), 28 deletions(-) rename system/{dummy_diag_publisher => autoware_dummy_diag_publisher}/CHANGELOG.rst (100%) rename system/{dummy_diag_publisher => autoware_dummy_diag_publisher}/CMakeLists.txt (76%) rename system/{dummy_diag_publisher => autoware_dummy_diag_publisher}/README.md (96%) rename system/{dummy_diag_publisher => autoware_dummy_diag_publisher}/config/_empty.param.yaml (100%) rename system/{dummy_diag_publisher => autoware_dummy_diag_publisher}/config/dummy_diag_publisher.param.yaml (100%) rename system/{dummy_diag_publisher => autoware_dummy_diag_publisher}/config/extra.param.yaml (100%) rename system/{dummy_diag_publisher/include => autoware_dummy_diag_publisher/include/autoware}/dummy_diag_publisher/dummy_diag_publisher_core.hpp (86%) rename system/{dummy_diag_publisher => autoware_dummy_diag_publisher}/launch/dummy_diag_publisher.launch.xml (81%) create mode 100644 system/autoware_dummy_diag_publisher/launch/dummy_diag_publisher_node.launch.xml rename system/{dummy_diag_publisher => autoware_dummy_diag_publisher}/package.xml (95%) rename system/{dummy_diag_publisher => autoware_dummy_diag_publisher}/src/dummy_diag_publisher_core.cpp (96%) delete mode 100644 system/dummy_diag_publisher/launch/dummy_diag_publisher_node.launch.xml diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 526467d0e5e4f..7ee7e376111cc 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -217,7 +217,7 @@ system/default_ad_api_helpers/ad_api_visualizers/** isamu.takagi@tier4.jp ryohsu system/default_ad_api_helpers/automatic_pose_initializer/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp system/diagnostic_graph_aggregator/** isamu.takagi@tier4.jp system/diagnostic_graph_utils/** isamu.takagi@tier4.jp -system/dummy_diag_publisher/** fumihito.ito@tier4.jp tetsuhiro.kawaguchi@tier4.jp +system/autoware_dummy_diag_publisher/** fumihito.ito@tier4.jp tetsuhiro.kawaguchi@tier4.jp system/dummy_infrastructure/** ryohsuke.mitsudome@tier4.jp system/duplicated_node_checker/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp uken.ryu@tier4.jp system/hazard_status_converter/** isamu.takagi@tier4.jp diff --git a/system/dummy_diag_publisher/CHANGELOG.rst b/system/autoware_dummy_diag_publisher/CHANGELOG.rst similarity index 100% rename from system/dummy_diag_publisher/CHANGELOG.rst rename to system/autoware_dummy_diag_publisher/CHANGELOG.rst diff --git a/system/dummy_diag_publisher/CMakeLists.txt b/system/autoware_dummy_diag_publisher/CMakeLists.txt similarity index 76% rename from system/dummy_diag_publisher/CMakeLists.txt rename to system/autoware_dummy_diag_publisher/CMakeLists.txt index 794e7d35e1194..73e354b7d4d84 100644 --- a/system/dummy_diag_publisher/CMakeLists.txt +++ b/system/autoware_dummy_diag_publisher/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(dummy_diag_publisher) +project(autoware_dummy_diag_publisher) find_package(autoware_cmake REQUIRED) autoware_package() @@ -9,7 +9,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED ) rclcpp_components_register_node(${PROJECT_NAME} - PLUGIN "DummyDiagPublisher" + PLUGIN "autoware::dummy_diag_publisher::DummyDiagPublisher" EXECUTABLE ${PROJECT_NAME}_node ) diff --git a/system/dummy_diag_publisher/README.md b/system/autoware_dummy_diag_publisher/README.md similarity index 96% rename from system/dummy_diag_publisher/README.md rename to system/autoware_dummy_diag_publisher/README.md index 9704cc4af9bc5..759ae509c29a1 100644 --- a/system/dummy_diag_publisher/README.md +++ b/system/autoware_dummy_diag_publisher/README.md @@ -42,7 +42,7 @@ TBD. ### launch ```sh -ros2 launch dummy_diag_publisher dummy_diag_publisher.launch.xml +ros2 launch autoware_dummy_diag_publisher dummy_diag_publisher.launch.xml ``` ### reconfigure diff --git a/system/dummy_diag_publisher/config/_empty.param.yaml b/system/autoware_dummy_diag_publisher/config/_empty.param.yaml similarity index 100% rename from system/dummy_diag_publisher/config/_empty.param.yaml rename to system/autoware_dummy_diag_publisher/config/_empty.param.yaml diff --git a/system/dummy_diag_publisher/config/dummy_diag_publisher.param.yaml b/system/autoware_dummy_diag_publisher/config/dummy_diag_publisher.param.yaml similarity index 100% rename from system/dummy_diag_publisher/config/dummy_diag_publisher.param.yaml rename to system/autoware_dummy_diag_publisher/config/dummy_diag_publisher.param.yaml diff --git a/system/dummy_diag_publisher/config/extra.param.yaml b/system/autoware_dummy_diag_publisher/config/extra.param.yaml similarity index 100% rename from system/dummy_diag_publisher/config/extra.param.yaml rename to system/autoware_dummy_diag_publisher/config/extra.param.yaml diff --git a/system/dummy_diag_publisher/include/dummy_diag_publisher/dummy_diag_publisher_core.hpp b/system/autoware_dummy_diag_publisher/include/autoware/dummy_diag_publisher/dummy_diag_publisher_core.hpp similarity index 86% rename from system/dummy_diag_publisher/include/dummy_diag_publisher/dummy_diag_publisher_core.hpp rename to system/autoware_dummy_diag_publisher/include/autoware/dummy_diag_publisher/dummy_diag_publisher_core.hpp index 64e2e0426046d..e94085fcff560 100644 --- a/system/dummy_diag_publisher/include/dummy_diag_publisher/dummy_diag_publisher_core.hpp +++ b/system/autoware_dummy_diag_publisher/include/autoware/dummy_diag_publisher/dummy_diag_publisher_core.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef DUMMY_DIAG_PUBLISHER__DUMMY_DIAG_PUBLISHER_CORE_HPP_ -#define DUMMY_DIAG_PUBLISHER__DUMMY_DIAG_PUBLISHER_CORE_HPP_ +#ifndef AUTOWARE__DUMMY_DIAG_PUBLISHER__DUMMY_DIAG_PUBLISHER_CORE_HPP_ +#define AUTOWARE__DUMMY_DIAG_PUBLISHER__DUMMY_DIAG_PUBLISHER_CORE_HPP_ #include @@ -23,6 +23,8 @@ #include #include +namespace autoware::dummy_diag_publisher +{ struct DiagConfig { std::string hardware_id; @@ -75,5 +77,6 @@ class DummyDiagPublisher : public rclcpp::Node rclcpp::TimerBase::SharedPtr timer_; rclcpp::Publisher::SharedPtr pub_; }; +} // namespace autoware::dummy_diag_publisher -#endif // DUMMY_DIAG_PUBLISHER__DUMMY_DIAG_PUBLISHER_CORE_HPP_ +#endif // AUTOWARE__DUMMY_DIAG_PUBLISHER__DUMMY_DIAG_PUBLISHER_CORE_HPP_ diff --git a/system/dummy_diag_publisher/launch/dummy_diag_publisher.launch.xml b/system/autoware_dummy_diag_publisher/launch/dummy_diag_publisher.launch.xml similarity index 81% rename from system/dummy_diag_publisher/launch/dummy_diag_publisher.launch.xml rename to system/autoware_dummy_diag_publisher/launch/dummy_diag_publisher.launch.xml index ae4436fdc9a6d..0c5ec80815c94 100644 --- a/system/dummy_diag_publisher/launch/dummy_diag_publisher.launch.xml +++ b/system/autoware_dummy_diag_publisher/launch/dummy_diag_publisher.launch.xml @@ -1,6 +1,6 @@ - - + + @@ -26,7 +26,7 @@ - + diff --git a/system/autoware_dummy_diag_publisher/launch/dummy_diag_publisher_node.launch.xml b/system/autoware_dummy_diag_publisher/launch/dummy_diag_publisher_node.launch.xml new file mode 100644 index 0000000000000..4527c5fe21c01 --- /dev/null +++ b/system/autoware_dummy_diag_publisher/launch/dummy_diag_publisher_node.launch.xml @@ -0,0 +1,13 @@ + + + + + + + + + + + + + diff --git a/system/dummy_diag_publisher/package.xml b/system/autoware_dummy_diag_publisher/package.xml similarity index 95% rename from system/dummy_diag_publisher/package.xml rename to system/autoware_dummy_diag_publisher/package.xml index e6b0302216e14..d9e212f922102 100644 --- a/system/dummy_diag_publisher/package.xml +++ b/system/autoware_dummy_diag_publisher/package.xml @@ -1,7 +1,7 @@ - dummy_diag_publisher + autoware_dummy_diag_publisher 0.40.0 The dummy_diag_publisher ROS 2 package Fumihito Ito diff --git a/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp b/system/autoware_dummy_diag_publisher/src/dummy_diag_publisher_core.cpp similarity index 96% rename from system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp rename to system/autoware_dummy_diag_publisher/src/dummy_diag_publisher_core.cpp index 5d0e4ee0316cf..57473e1562620 100644 --- a/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp +++ b/system/autoware_dummy_diag_publisher/src/dummy_diag_publisher_core.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "dummy_diag_publisher/dummy_diag_publisher_core.hpp" +#include "autoware/dummy_diag_publisher/dummy_diag_publisher_core.hpp" #include #include @@ -24,7 +24,7 @@ #include -namespace +namespace autoware::dummy_diag_publisher { std::vector split(const std::string & str, const char delim) { @@ -36,7 +36,6 @@ std::vector split(const std::string & str, const char delim) } return elems; } -} // namespace std::optional DummyDiagPublisher::convertStrToStatus( const std::string & status_str) @@ -226,6 +225,7 @@ DummyDiagPublisher::DummyDiagPublisher(const rclcpp::NodeOptions & options) param_callback_handle_ = this->add_on_set_parameters_callback( std::bind(&DummyDiagPublisher::onSetParams, this, std::placeholders::_1)); } +} // namespace autoware::dummy_diag_publisher #include -RCLCPP_COMPONENTS_REGISTER_NODE(DummyDiagPublisher) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::dummy_diag_publisher::DummyDiagPublisher) diff --git a/system/dummy_diag_publisher/launch/dummy_diag_publisher_node.launch.xml b/system/dummy_diag_publisher/launch/dummy_diag_publisher_node.launch.xml deleted file mode 100644 index 9d9193fb5f7a7..0000000000000 --- a/system/dummy_diag_publisher/launch/dummy_diag_publisher_node.launch.xml +++ /dev/null @@ -1,13 +0,0 @@ - - - - - - - - - - - - - From 85240e1efc3dc25f81862c752189ac15cd738293 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 22 Jan 2025 15:00:00 +0900 Subject: [PATCH 278/334] feat(rviz): add new plugin to visualize planning factor (#9999) * feat(rviz): add new plugin to visualize planning factor Signed-off-by: satoshi-ota * feat(rviz): show safety factors Signed-off-by: satoshi-ota * chore: add maintainer Signed-off-by: satoshi-ota * feat: show detail Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../CMakeLists.txt | 26 +++ .../README.md | 1 + .../classes/PlanningFactorRvizPlugin.png | Bin 0 -> 18815 bytes .../package.xml | 33 +++ .../plugins.xml | 8 + .../src/planning_factor_rviz_plugin.cpp | 189 ++++++++++++++++++ .../src/planning_factor_rviz_plugin.hpp | 103 ++++++++++ 7 files changed, 360 insertions(+) create mode 100644 visualization/tier4_planning_factor_rviz_plugin/CMakeLists.txt create mode 100644 visualization/tier4_planning_factor_rviz_plugin/README.md create mode 100644 visualization/tier4_planning_factor_rviz_plugin/icons/classes/PlanningFactorRvizPlugin.png create mode 100644 visualization/tier4_planning_factor_rviz_plugin/package.xml create mode 100644 visualization/tier4_planning_factor_rviz_plugin/plugins.xml create mode 100644 visualization/tier4_planning_factor_rviz_plugin/src/planning_factor_rviz_plugin.cpp create mode 100644 visualization/tier4_planning_factor_rviz_plugin/src/planning_factor_rviz_plugin.hpp diff --git a/visualization/tier4_planning_factor_rviz_plugin/CMakeLists.txt b/visualization/tier4_planning_factor_rviz_plugin/CMakeLists.txt new file mode 100644 index 0000000000000..db1fa63c128fb --- /dev/null +++ b/visualization/tier4_planning_factor_rviz_plugin/CMakeLists.txt @@ -0,0 +1,26 @@ +cmake_minimum_required(VERSION 3.14) +project(tier4_planning_factor_rviz_plugin) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +find_package(Qt5 REQUIRED Core Widgets) +set(QT_LIBRARIES Qt5::Widgets) +set(CMAKE_AUTOMOC ON) +set(CMAKE_INCLUDE_CURRENT_DIR ON) +add_definitions(-DQT_NO_KEYWORDS) + +ament_auto_add_library(tier4_planning_factor_rviz_plugin SHARED + src/planning_factor_rviz_plugin.cpp +) + +target_link_libraries(tier4_planning_factor_rviz_plugin + ${QT_LIBRARIES} +) + +pluginlib_export_plugin_description_file(rviz_common plugins.xml) + +ament_auto_package( + INSTALL_TO_SHARE + icons +) diff --git a/visualization/tier4_planning_factor_rviz_plugin/README.md b/visualization/tier4_planning_factor_rviz_plugin/README.md new file mode 100644 index 0000000000000..7b65c89d5c22d --- /dev/null +++ b/visualization/tier4_planning_factor_rviz_plugin/README.md @@ -0,0 +1 @@ +# tier4_planning_factor_rviz_plugin diff --git a/visualization/tier4_planning_factor_rviz_plugin/icons/classes/PlanningFactorRvizPlugin.png b/visualization/tier4_planning_factor_rviz_plugin/icons/classes/PlanningFactorRvizPlugin.png new file mode 100644 index 0000000000000000000000000000000000000000..6a67573717ae18b6008e00077defb27256415663 GIT binary patch literal 18815 zcmc#)ig}7!VL~0BI3P>4u>jX{5WQyQGE==@gXiZcsv`yJ3)ShVHnpzyIKV zx%UIl!@PCQ*=Oy&*IwtGaAid)9L!gkAP@*gMjEOL0wKly`$K;YTnXsp8Ulf2BxRtY zY95&f%V-`irs2ZJD-E_>W|QJ#$f(lDGUzn9FhfdJ6ls+f7g13tl1h)8=nGVpD&-eU zEXJbkUMvxiN-bt%sdy?0Ws#;2U}Tww$D9k?tJrv3b90N4w6q7mY>Vu>j)cq`Gq>&g ztxVotd7x=_%0QrfCTU6#h!Tqc9R&LG1r-?ts`)>?Y`h5pRS_lWag8OXawfXJHk9@r zwSCxzbPRm-g9n1hq$!Q)8a9)#!i(M_cz&h|6vnpsyKVD7twGSL0-4KL6Q=BD1ZeP- zzfzYzWVM-q+?d)>KwJl;5;rOeaVP-p8?mb$R~c z!r4STVAB1bJ?W`Q1N^wk6a>;QVI%JxOu}Vf{^G|)Co3MGH{(9RMV<;nHU4Za)%KSC z`;I=`QN*K~)?CjlT%q3CJ0d$G%J_7^;$JI4Ms3f{6oyJDbjK_N!4ju2 z&$?3P$rm$WTureE-aq`r%H%qf&xx}1+^E65XE7*U*@ASHv#;8ex#{Xeuo?I&+x*og zCp;~E10-qE582|U!y4K~`SF#B31Gjpj3?LDSx6hf<#=NRr5x>o;P$^l9osYrEfL{WYjQydU9;g?K5#3k=W*FphTCuCHewl5&`Uu9F)(f>MMOxB>pE z88huBN|GrNq|eH~M(ELpl-tdZkMhs%;OV+^2?6{7^3=m>h4(Sn1AF4SLTeDL;O9g! zBWaM6c%X0DechlP8B_BUQ^1_B5ImG0q$&AGba@Q1!Sx#uv;b)FNlKJ%FF!gu4goAi z+jugMiX+lt3%Db%$x}1fa)yh%A&xxGW-Lle9BaRZcr(Jl8YJvmXVoM8b*d?nDn zr>xqjT|4gjOmgjyb!-I_L=1WSO(};jF5)F9(KK9k$6juv0YKyrQRHz_DK~8jI2)+w zm-Yt$QfvYLhOutzxp@d+SUG4qO=vJ%C2^D=7atD;N#3;^c;DQzmR&&!oPfkcBJT}x-4FY#kT02m@DxoqS-{xT|$ z3PAj4Y06h5S$bR{FjZhmf2ImPCOB3Cm{OLqda0jhqvfLSxmZ+?A2<^h+z64sYjMk*OaM^512bTNz1yJX#3oL;p>F~$69vB)J^K&J0kyCuHxo2qc9?N7 zpx^)Vh!`XhEMW3-8hQ#=jbwx3L_Yk3cspR5f1h~;US}c=&En=n$AFqJRa-Trw&}AF z#AgA`>wx2@JWAg4l9l5}1GY|0Z9CNsXNdgw(z**Vj@S4BOp0I}AA5Z|Zl~>Z3kVbj zqQ+>~?`j3P7S~|HAAK#cX8I@4)zn@Yx%DiDRJ@~c4bTC4ySPXJL&So)v8RA@6#{J%M_y$DCRzdd0*FPR zEH--gPG5+|{w5Yegr~;hMSkzb)vYj91mGV5xcRrf*}fIu`8(Gk(oJHQTMWSTlpe3W z7U|f@97Ozui1Pqn>xtK!34&Gp1$<#-lg>4RGs7K!6%!+v&|>f%Vhw^400u&sGY~q5 zJ^R2hK)+x%+?N_ujGMppd5=D@{V_pS_0HC2*7x*eApoKv>S`$MhIW>f zMXBEn^5P16FfqDGOxdOTX$;a&7%;G-28$P)$1&8Il!2^?K;(-9A|F432ZYVYM^|}I z3>OV1q`?mb9wc7}dJzwJ)_0FSe8o7Cm(><8hzS0{vBcWu7VZ9!xVd$!*%0qZqPEJb=%hJ$Z_L zz~Miu9bQOq9)39Df;+w>C4k8SnA^IR``!NH4|SUf61t|;@Y}Cs7L7w2kT8`ufki#> z(|*WcvwwZbRQK{xx%^U^9it@ui(i`PZ(a!{U!?$lf%er!QwQi?Jq@BTnXsQ0^KiZy z)@H)?s!l`=|Lg4jvo;>IFs7CP;9l8V4UpAo>sjIq#`%v=kuRv~Dh zsiW)pz26t!@MhZgf>?_yj35jsQu16~;-8_l{?rj9%$d(V-9L6Mv^t{|GGZ5-C`W&WqNh29e6d|hsvmvzE$*g zQmyMXe|TD_9?2}u%kdXf_x#(4xd=B4sAmzB{R*=+ZDMv*{0=ZZw`U z1zHnRLzGA%_kVvk=&UnLH`*nK6OLz)IZ+1RaP z$_a6)pzGO}t0_(S2EeN@?u0pWGf^QOT;Fy&fIf+061Vv&k6#eQ9E?CJbN7 zR~KK=eS#kf?q9C)BZqF)@T7l`iF(-E2|R4|?91b}4Ez)Kk2FyYsGq$iY-#*_u@~1} zergZr={EWSme9lc1Lvw@G~X6iq*U zJ>6TJJ1l)Wu8Wk+%I_jO@X>ttg#2Gtvr6H&5?wENhU3wfOD|1HK$EE0JWPIo?o%@w7QX>1z=lRIcDYmm^RdaH!J$U0qdKjR{v?Nj@k8=mLg z!QaffX+{G^hFLx>yzv{!{4I7+*?C}Mw;W;Akw&+^oGNB zKbo1D;RxOCe8*HY+Wq2Z{a&$bq>kL0E*5uqV%bZU97(Rgg}axR>R3#V{3&SGo$cMU zo>il+6}(CD_7>Sn+RG>LD*ZH>q}A^P_|jLN;2-ZSZ)e^-CR7g&UCtF)C)#ml2sjLp zna0G_?3W<_14PCTp7u%y`1jJLdPCb;WW==}ZA1fH$8?tCsR>bJF?vJ$I|J{? zlTYZ~d#P!IC7nc5MI zRsbBkP4l%D7PaBB{&6DKt4yR^NwBqPM*lr^I~U=AH?+LJ*&C$ZAXr^~8P$6rvc|OQ z@5*T^JLt$TP5T0t(=wiG^sXg zEd~AVuZVrio-s!T&LrqYTve>D*P81_=>7;qF3oJb%9-_$ zl7tF5{GK`$Y)Po@y_Df6U|SUSg7!xbv_*4yVe!Q#Ebc;ZcwoSK)rHUB2ho1zr!2(h z%dVk7oadz}SQ849EKz@)p|3b8py_+bZq+KNZ|#0KdDLC_ZhWXy#9XXyyOh3&D_KBd$d5r~dZ&@?gHCJhG5mniAQ@R>y{O zFvmlJ?JS~a-%K~9k;T?h@u&=-btl<6W(Mr?#p_#Nvx_0v`ilrR<$^+%&Dej}o4vNPn* z;owRb6rB0y*XFvkd6OhCQqGB6I?r)a!X@j6i&CJJ1K0a?>M~fR$7l@HLqkBtR{DNi z#>_e~=e6CHkiV3$L3^TB!NYiWD6Xr+?LjRJ218fc9?44c9VrfHEASeRf4u5=;4Pz2 zbmAarlXGC+<}+MNXuEB2%{j_j84W=YGt*J6aB$pdMP%f^yA?e@n6EWm{~fLLbbmH# zB#6dX=5Pv<(zsg%*jkAKL5r0knZM%tivqc1CatP(x82cXPdwWwcmjs-W@q|ImYY99 zYwlE~Y-hze~lk`x3mjPB!27mzk`xg^y;8^_L_ahVv6~)|t~mfqeU``w(TZ zxrTjOPssfK`oySR$6>Am1>m)tK+)!_P=0!6FfqlwTf!xubMJn*u$lh(uwJ8c<*Bgn zDIx;XIk9`S^Zs-&ZN{2BW%h21L^x#Hy{t&3#$u%2EIrNNs9uMGjS4;G4WkVIc79S?9<_)}5sGh^o2GGu01pfp6?z7wr_`sf6M}tS@hT zNCXk5MDOIEc)b#>BL5Byp4r;f?uV$qGqs%c8FpR1U>>e-v`u`iQ65*US#Q)pH|_z0GX?kiG%%(LOU!%Ckq@v`f@JK|pfX2{xiK)~<5soB5N zZ^n6hgiX)Z0q$xxBO+$zshAz%JT;G?R^ui!yaQF=CYolEefA_D418x5EBtuv6S_T# zt>8C5ZK^P2{Tk3jP{74C9i5Z*XB90Em|L^1Lp$Ty?ZVFx%zQ38_!1Hlo_wx*Jxm>5 z;cSTnM62^vnW0! zv(<%*u%dQ#ZEdDm`^UPysNb89-plAwdG@K0)y_jBD-qUQUN%)_5(TsN78%{K)f*=5FXVTI-5jC-M0r)_e2{Uu>Io;LFZ)WTSayCh zH$y%7yq?2_WZ>t-lJJ(ErM5;8)CMsVjU&indTZFQ!V%ji9)yN-+O%Xp_zMN?x2c&~ z$h26bQIZIOY$0|Hl-A{A>HW>D%Vl99Us^*}%6q+6(o_lL&Dq|Mo_&23{zG+CyVGoa zZdPuB-3?-rE;hgTQB^{1j%hnpE81vUZxe{q7+r62)9R zQjuMBfm(#Ms?@4Z$;Ik^iw9oWqRW`6isW|}$3~+7uuRp_uSRo5+uoV%o;%fYOqe&( z|2-;yrIE5RJ-g8wo6hVoIj1wlF#nl)eXp0d4XYB-b^eG|Cv?<)1s7iS_r5%WWTvIf z2b#SW2vI-|e@Dud15=%5ScGn5xI-4JpMXeprsukuG_&3pJ9vw|;{D{iSX$ZsyN-QS zIkazCCe z5tjTIqBD|W;A`f4 z(o2%2vBi}U($ZixbedSg2KMZ`WSTOQSc*AmMXpEHQN>d_Ts3UpJGs9*!n#G=T_Pyr zRXRI_^rJ$49%InZRr>IOdrQ?H&qWVYSv0t<)_MjA=@l6!>}m{uAv-nCbu4CkNL1I0 zszx2HgbeMhEPPFWT{;-iq%i3PmyXoFdjD&`g5k23{NZw;w9<>q|Iu^oZgl-bE6dSw z^mlKsUR{#$i%`XX%3&%n7Tqbvr-=iv3Vn!kYG;%8(aknQHmT914|hK(l9+ATj)ON8U+A7k}qtQoh z(o1n!2r2de-qqvX8LPa^T2)TVwotK{{5PUlaF}h}t$?CyJIDXX_j2AsLij`a@Rsi6 zT9`WmSJ@(5~J3(YDA@J|o3An#c=nA#EWWa`laHX*T$SjobapA&u?(UWP+Q{C%@7Q}QA^ zJNv{`cm#_$-9Pc`0QTcIA;7WaQ;?NPKQ)wA2wg2XAF*`a%1+DL{Ei|8qxs#0>_+qE zIygdQ6ZJGXrnY0=Ug)~OeO>jx(RvJib8E2<`5+hRj<=UQ`XSK&;bJyBjKUK-vv>=H zGCKa(@!Sj)ME<{YC-0A1b(Bqx63NF8LaQ+pwr7++?Y;83W-@6>tv_S?kk#VM|MVs2LY-DySvyPfa--K5g8|I^)y zxR)i5=c%cxpXe{y&Af@{;>*~{b02i&{aB_$54p;>&#@87qjme%iw$;g@1y3hdBV!k zZH`JGW7Tng^Ak~%}#;Q-2Kv@J$5 zPoiIQ%EmkU-JkTeJJ;0SF{mVKykranq(ebDsHb&e)<5FL`@L~x6=ryQdf$-7vCQ0< zVKw1(9v>zMv~Hr4MzS?k%k=W&z-eNFmOLHeG{ZZM>d@B7MqQoA_xwa^NGPaDE9_=G zqs6AdhWYsONzd@+OaTr-8XOBq(wvBuPJ?Raqs7jrj-Q(vB?55luOh~nXxNd`{VH~I zM;8yWZJr7r(}dDk^xNhxwsalXR!sA1N(T6xx8%3 z9i?;He4?%(U&RqXs^zm7y_}z_XZ`rKJWdqi+!lDPbqjFCc03mCyq$|H4*?12d18Xu zsc9-IL6-9k#5yU9z|37?M|bFc*A_tKQa1XE*M2$dVt-b%RtQm5BcL!+`EtBIz{=SB z>EVhR7s6-iy&6K2n(c0w;sbP}fDO(N@z^>W*1LXDq9TP$lSj^&IGFi{KpGIP-++mV zR2tI$TwO=$)6FcJ+Rs%5-rd7wzS5;BWefCwh}pkOiJM7&g&1R6o^Ft!tBsfjK$~LV zchl!;(BZ>dy(Cy;~wVJ*0yFzq6!EcXR5$rY?4gI54mUi2JbS2$QJGSQ5Xyxt;M>AF4Sv@28`bN@} zlqwK4bFtGi`_*QHwN9+3#N)ub$|i36r9T2zdP63$?>Q-i9luzG2$gB(w!3~+Q&2P3 ztg~7hwvPLAu**HR*1BKO`siW+cbQb!0_qL(aGzg2%;p*MKf-C??dsxN<>Sk(?%vrz zzc_PV+EeGDFeZ;i84*ZtW=H3=#2j|W^|ND<(N6Ys^vYL`H`p!um`KLX43QJ|#XvZ& z5VNDI>gv4*nZ&heTY8$rMpSG1;mfQ=IFry0%W*2X;r!dHgLxC(0(fUSoX7 zwNjEXD0t!s_`m5$=5BFW$;8yBAcYLBacVr_p>vrk2KwkD((ynWWJf^m6M0>Rs^j&K zcuG{Bb;k~FsXL?edF#}7S zHZDLmq@^Y_Y4fI*ecn|MwalQipJKC!`&+AEi=Oxumg^tYvS0s6v}&dED>#4Eap zAJNq9yf;-G>9>swxt+fKLmkVyKVy>_Z%8^@94F5{sE|(%yu=RF} zU|f+?>1X;0!Jp9#;p0r9dszlE)NBFz%Xb>g4B!|F;iIe%Rte_9u|W9MNnz3b-6obM zRP{c^sD1ZD1@8DThqDat@NK>7r_aG&(BpD|3!JTXho#kHn#b%IMn={-%208He(I{j z8s5K{sLB<8*d9?YNvdlAkE1Xq4M&^5V`}zED!eajyno=M;-hVhny2RT;+R}Z9r4hs zHg0|z%N0-eaMaHz%=Q`>bdt9ENtBg7zrZD9*0FRwt#|ss^{%z@XNh|0y-*Iz&V$F+ z5b1tlj^6+i1CSkW24b4a6t9GRb-61JetIWG3TakcE8lU{iJ1*WfY zhT3M?F_AEMwx8^2o>J9?B73d2M-Ao0yblIV=w|pGk7+ zChG0Dy~rHOK1Z}(>0iZDOF^?7HV2aYQZklSUv5SgTzl!7E#o4p(rOC24ScRx|^VD=~3JdRynp4w?)W(5A0 z)_C3;5w{#ut;AeK9af+D3$6?#Btje>?{BQL*L-vD2I8Ik7Vg!@QnLe zppa1pgsr!=`wq1_mTHZ}C3xl@K9Vf_gQQRAD_36GdaZ87H=x1+REu&}7i5gjPv`MP z?=NN3^VvFySA4Is?wUDmnv~`eOyF%d=CNUipe$ZOJ}FZgXz3+QW*Yt>xpMko-JL05 zks6_=q<8Zb!SRc%GSdhvd#^TbuH?h6Nef0sA3Wjvs`Q+zGw6AI#HO>wHLBBX;iyJI zFZ5A$b~Ji_KEX=v=l0q7@oKkklDfM5JEnZw<(BE1>)c*>-8TRsJgfKBDNYu#C!HGU zbLvbP6<#?=;4iU0T&Pb*LBnMo{A)%V&E)8oVNDoVfNMGIGqDC~Tscy8s*HW5h(C^+ zG%$nRO&>=ccGarn_c)}SF|TH0#$7Cx8+pN%20+veAhSU?RF1MOcSo&5t!{_L=^j!S zwpKQodunYpRvLi#(OCA4LtJoKXSCHK;j8k9qyr5?e~KQ|t>1+SXe) z>)&;E*Mlsb=gfL7YJkKP1nqI#dXEOw6i8@(OKrTvK3jR+J9~Xn-iY+EwA~bLWlsRR z23NE2O*dU)=1+e<1VW`GQj_6h3MbAnyDHL5QY*f|gl9W++|d2#xN2PS<3Ii9G|AA= zOQyQ5g5I}YLVzr($N9aHm+H&mo*)(pv+|j@cP5Nnz1nAZ%$JsKX2hLXNhUIS$$QnG z1AL<~%s^invTXLbb=gI`FD6^i`_j_7{ay3FG_nui=Feq_SET$RM11j`*GRQ*M5-@2 zd2E<{+liz^%K)8H_K-`#W19`%J018J8$M5t{XUL%67!Kv?T5Y6%HoSPfj9xo@SRNA zO&i%cnz)EbdPRxH)73v%VP9f)rk1ApgoAeZVYB+))9p8Bqd4&bBR~*`oNY>09O~N2 z!Rp>7KnHX=U8>;-697~ZJ_sN<+Irs|Hl_`;G1z694OixT`*V|Cz_YBGLc(tM@Kohm z>JD&MYd3Xf+B|B;lk$xwEPD9_~%=V(vx(C@a6Y-H$#=bfVOn57$&>rkwrVs4#bi zIXh7e(IM6w&y9tw+~I(;y6HV5=yM_(oXxC~r9=|;e>##2d}?n{dgmZtm$kdn2_X2$ zZn1&1c*eQwvMIIRLX^A-fxxJ(8WBPe?||LSuy z{t{iR`A!>-41uqe*4_8|FWHQLq|ffyeq*aJzDYNo!z||t!@KwR;k$ICGOlv)`wp!Q zFe7=&V)-C1g>f{5f5E>X@5^pc*;|x_)H3t0Wj(Hdf}t6f7dj;Lm3y|b61$Fgis3HI zZZTE=iadp@o=Y|={({-`cL3Mp!SitW{cQ0t++xA?d#mq<7jHsy-_FH#^te&BG6e9=TM4K?yE4$gLtJB{QzeetB zryUa6*x1vKi=Ur?^*FjI-@8jse%C$IlbLGM)=y!06b)*c>gqrMkCt)IoHxxwf;h>K zI$ZxUI0Qd&(@HM3+nD1SE<}@A-dyZ1FM9v|iBvCi@E-ah@k7-!4x7-5u`g+?MqO*l zm)P-Zzu$iR6iAlY+w9>D6kT>tx3it8Zf2XNw7OwQn=-dqz_;&l(OUI~)JrvPrtJfn zwVGJjkAIYJ@iHeSyf)eOw~G0ZJld2UGPIIZu3h{4455%Qbz6lZW74FexmYeYM;8aI z$K-h3Y^GFFCuw>-YX)_9?Ig^9A4wx1xQ2#eYVG!-LK}|bv$R8@eqlJgC_fD*}q9KhIE1f_i#O7_ zT)%x`)T#K2OJP6!v6Vb?t~cc+MQq6?;as!glC6mA<(e z<%lFRX`h0@1C67z0NHWh|ZjuVZ|V8t@FP@kIUYdtPp)2I9s3B_BXeBp}-ZP z5|l~AJ-|-~e7adHXKm6rZHQ~nBqb!qRwUhuE_?tsh^Kl=Hlz{jJv5 z%a`iA?S8PdtMf0~>M^6t2;7z3^z?rn(s|R}N+Jo!JO1-*rxQyqqw0F6X>RM!ACLOT zz2%2LmeJ%LT4#%}#EGCHI_{2UWy@EDyhONJs|(RvT?Z?St5 zJe~uJKn9oH8ehO#Qs>h$z{xbsOPOK-DR@vG_GmD%r#DqpIINVFeAg~=yeiV@S@ycUgHP|m(|5vgek*ZEH4RdwK{d$6jL>+4X z`4ChMuWjS9nJF{!ij95ygn<6)v21l;z0gZ@UjZab`9s9KK++(ZU}hS#jlPp@YHsdX+N+j<%}bAm_k9)T8@LAgyH4JzSyw>)>XO5eYZ-f(KZq4CZ8KAE}&p33a#nAw#ZL!zhkYZa0_fy&Jh12UfTAj4W?< z)O2(X-CC!M1+7n}8-n0j-m&cbyUhc#29lDYkyrH{#~wfcNz*@%?SyYHR3jK#qYkg` zfOxt;Xp>!NetI3?-j2$*c6E0peFJ1k0qtRyN~0J}eb0QIcI)6yPMaCaqc?e?=5%L0 z!wWTLgHwtNdLFYf->C5f&&TSGJKKO9egTz|q7H=dL_|bSuP9CLa~>76 znCtPqJkWLkR->ldp7iOcx({hE83#s3x$hnxA+ElF{8rgnRi*qnM5H$vfR4=(~l-hR-WQi)59iT6|TZNDzuRd5R$FCqNF)uguYRz#H!g{_d46@8|;6d)C31g+?wwl9UWUN!_7@iU(y8@`IP%@=plBH%=02yJ&ynGhwto!JlUOX z4ZlnR=UHTX(m73bJ`MY1G35^fepmv;GCh*P+1Gq7e{QeWW1q~jSlc~K9=z&1x!R5Sw+>Pg|4d7B*QMP1eov^xZ{boH28L>~l{Zhb#6){LZ zm@6K(L>wtG?EU!}!s|J9nZo{zoX5(&q`-6B*F~kgn1RWbz(S1+KjtWyba%eqCgn)S zFN@z*^(@_A3M$`75z6`%5E_kQVPm~8vUW(0-)Xpgi@MOw2BBVq0JDHsQp!G~mGIp` zt+g8jO^5Tn$1Dr}bH1cx#Vy}6vXegp0~5m=T_@{(WO?uY<)bNy2_cW;Z}e~9$_)RA z&R+=3N)8DzIPSQK_PD=ZR~&XP^$^GwPJke6@_WV`6v&1R5CO#>3rm*Q23Pe8MP7zS zN4FFUff1Z$-rRg+ zUOSJkl&izPHIn6>?4GZlL7(#}f01PSSIocavf%MkVJQEWW_pySvMFl!k06}^LD&vwY0rFM7Sdo{5 z!^6JOK>wyp&Wqx=>r``x(>dQU>14zTUKY_wnmZX{if`ugWtEtf5;FbfaR!RPMaJd=iiHkN)+{o zw=7_sEj@pbvWiNnS(}3oHAP5B$P(ALz1hl~T>aEY-XZhaZD8r8xs7nX)xEONDCjv; zOUTNmo&)Iqji8`liKzLOKAgKFJ{IZWuJ!WaoUryyAsQa}xqK??8(ZCEx7KBV%c+g} zKb}#TJ3DI#oj_gNy)Lv4->#&&w<8@3lV0qv{JbmRz6E=*>$kXAjlB;|IzAm_X;uCB zv75{DlZUCPX_L_PUzBOWE8nZ-zMA|iD#R`FU!}FRHDgRnO#Q#U-C^A-YHAzgg4T%^ zfT5UUrP9zgG!1;~y?UlKy%*}N2#Hw+^T|{6+|stQd7Vod9abu&XJ-I|3zTY{NPshIIhMP4(e)?%0Uv@SDj|pppr_Jb?SU%^oes09s*d=hLG% ze`5g7Pg|}#S=k6d+Fsg@%%xAxPEJlx7nk#=$7MiN?f*(I2$fs2BE8qna6zlDpw#AvWn%g%t!02^>Yj~m`Jc$>iH%XJ+e zZKMxoZxEm;V0$ox2?Us2H~)s3I>H<)HIzL9C2*B2%2% zuoz$qGG)~AC_jk0_89l)-w}Kjrep=sU*p1KA%bo<^)Jj!7x@I^8msO> z4>V)boi5cC6{?m%cYKi1zpQXO7Sj9MjcR~0ZwA;qj*h|~Zix)e+JeBwbFm_`UgUBj zgZ3CD_k(a;jH;dGQ*p3Bd%O`FzipXyFXu?vx-t zRRt(cFcEnGVV%fzDOH|TTM%e0EhS#yS{w_?&t<&+7NqhCIwh;+O2Q)sTsc~YfC3bU zq)x}416#3Ue7ioXI|D~PEaz~kUWr15fPZx;b=F9Tzwr0+<&|tGXq@ z-!p+0U!6Y(5C2L=UkFUuSvc=t6~zQS+H_VW)Q7oK9zW$`$z@cCY7+mxgHfQ2uQhZ-Bg6F)mmEz|j=0p4I}11k?as_b+mA%#j1I8iXEwQXk2s&yQGt+}5bJPGb zYs;@L`=D=*mVrBcjz(@?+%AG&0^6ZbXHPVwwQtYzgjukZEJ2bVC7?Lfli&RQ%4ql> zZ3Bjstq?yQBdHTP-^B*^9^)d5i0V_-08a5k6bqU|cZ>@XF)H;$15M;U%QGN@6}Z0a%$-dB3&%`n1N7*~lrtIJ9})K!Z&`SKbd?mA;INup)SGh_}|FuM4}K3U^9Fb8+f3I)=dOLQaPRBqE3YvwXIT1%t;9*xKkQh>Kn}+ z;Q<4<$i;f+^O`#E1n{wLZ`^)rpKs3y{DkQ8RNlH1vu<1qB`m4Ar|D>VgG6BuM+f>~Dm_|t=53>L+p^5?Ap9utF zppJ$KnZyZs@R1KmMUXW&i^`seS3FLP#h)k*_YGfPxP+Lf^-x z_sPQj+kVNDcrI(6;l2Q!R|cD$^7tp7bf7;!t@&f~h=LG73c#aHVNd&EsO|JDJ9OOx z4GDygnsW{dr3{vF5xpd#k62wqCZIlHJHXZfU5XlU_yV<>Rk0;H^GfkD(N zC8;^cd!U6lfJ^KX0@2Cm4 zd=8d)ev_63t*c7*w-JRN1{3v+Dme+gIiEr$x928QNy2pGAlduak_Nks{AB%r4d$fH zGhrW1qRbq8d%BIF&*L}E-fw%oD&cP&m%}Rqb%t5mz_v?@_2O7|JOgdKNWi}S@&06z zP{QC}7)~36DkZQSelp`cI3;!}dXmDmA1C4Sk2IJkXca2?Rq1CeU5pr=Z$Eb|MA79r zy57rE7PN*8KqGRYA39>(eT2c|(NGsfr{%mU54|>P>rf=dU$a zVl0M^67U>rcEgp*DN>+P_xfhO3&BA|ja^IR9nZ)3c|`h+cLeVW#xuq+3uv}nG%A6$ z#JM=Sf#pn?8f_ORN$Xqfs`b>*IN!zY+eSWe1i~INHf-G~8xDL(&1R?cv=sOgWv}k5 zvteF@Dw-i34yuxg_Ahk2WZ_t?;YIDiHl87$aT0m1go-04L)r0u>_1x^n=umxKkx@T zXKB)YVqzl*IYMPkmI~jo$xVn-{?=xiJ8`YE6AE&DmVLZJomVQhqu;I!nEhjZSW}A& z9aUJDnK_|~5?EL>2L>l;*|=qJIbzC{IPFmO%Mz2JRMpR3A?xzA_EP8?g@56F6FM$q zslHsKdNUki-|0=HpNsVPE(Hds%j;8TT#?q*MZ~(-<~C%b_A2|X}`fHdwvLeljj~n5@a2L|D4uGt&g#XQX&30uL+(&sRQi{`=)W|ELz*%Z{nK;cEHSxzI zsrA`<4Rz6Z8InRbWPpDMuP7)CHtM(&gT2jMVmcA6EvW4pd-}Qk^8M1f ztkSjGqJ~jOXiyi^+0T{nVA#S8`(S%RprmWLq)G}RWd2UQ3q_lH)oTEP+*uVvg!LsN zp4D^TqM1J4uq;@HeYBs!V3ZI;JIi2~d7$Bqe6W{zYP=5{*J{>)N}3r95vhNZ5{>PP zuI(%1IF+xoU4$(JU!{WLTR0_#*HMh#ml-ls=i#wjLt?A2l@z+gU?w4~g&W3HA^s`4 z4F}UB7IHlO-A+nWfeRdy@gjRdiHelQl{X=Mi%^&FKd0*<@l5nI+3Vc#h{rC$Kmoe- zvpZ3bMn*|-qZj5396y5q;CzC9kn7s`b9To2s502|i^nLOu-LIIk#*-sAS;X19xv|T z{0*ls}liCZmq|f?Z;8zxgGkM?Er0=gxe!}5B)Cfts%zx+KRG~>%xK$^Qwgd zxLTF&cv9bZ<-o^?!iTp33(@-}y0vl_)2I~G)HF}92jl3v=#<)O=E7Rmdy2oglf|Hk z9aQ(|WOUn)IJ?Ev)&Fx6bF6)kaLn)DLr)thofgM!&@~!rT^O7bt@e5Or7|3fA$%9Z zdcgKVh^j?@4Sr`l^A=M|1^Pj?Yjm{L@U2TTmvgF?=HwY>`I&p}76Dqk08?8TUT-A< znh@%m4Kr8Z2eAG|xkt@vbVWTWWo?7J*w`48u>8$6i$5I*42V{tPKX%OlI`)B z()!3ib)k>8#b55^e=w>k^6=B1ZbJ{JnSv5WmCH4hd6f6{<7;|@XRLCWiDm99yGhA{}Wd_r0D9El$(X5~ZD@6Yeq%JJ_WnN-%QoT_^& zls{`|J%9EnfAEk~Gyx};)G-ocS*iS3?;B@s#A40HNR)|D9E{SnkxmA^FH@JMsvova zX8&ayT=lAu;Am_z@Z2<%$ z6{BjEfS{w}t2VXwOJOAH%tlL96JNh1#=Wf*>*+C=wXQ*vNIs(oaU1*ElJg~AWBoz3 zYsEM6%XU&tu#eu|7g)PJi(C|&tXR}Xn&hnaxd#gx>+j>0Lv??-YpZnq{-}DCX85D* z_dAPe6Sn6vuwUIAo->ylZ}KI6nQVFL;mT@J6n=}jh-Pjuf%pEv++Pdkdj*Zwp7DBP zrhTtVw6{gZP)&6$66l-|HJ4w8%;eg~^EPs4nrqIew2C|SrN%S*vk{KJr_g;`Y{qKK za@>)WYnnH1$Y7g~H208STe0$q*DizuUr(^Zw@=B+o)Nq~aS$e4yGfT@>daH^DKIsz z)cwow6@MRvpi+T4eltCU8Nd3QQI$>-+ zFgW?Ai;?m(M6`3~3t0MUNoj|7dB1(@$eb{5jiAiUXxRcsX%N7syb8a-?5DbXQY&dt z%QtBuucYrm*1Dmz5?dn{A0>WU5x4YjETQ|M(8cAmSNvkb`2Ku7q`f}>zYyO<$8g@x zUzs*Gk#M%Gr7AVQ9ITO)uwuolOW^S4&Y0P4a>%SIVE2Gjj|O|=mQu{^v#Iu?g_u(5R=+V-wf&8^chyn4kgY80C{bYAldhLKCoo`h9f)w_=Um8!5STwbwF{_U3Tizp{AyHC84h8bs|GATle zy3F*$Rqlvr6MURu^<;ctoJ-C-Z#8oO_$tvow?$;EY1DOi-(^S-2TIzlGbRuwb&;-U z7yZw0dus6-cg1D}!{`%wA1C;jA;~pKJ=T-XVnJJKHRncn?@V?ZaEO-)De!(_{cb?PQZM`vF>be}<$+yB>x!n%iMG>Ka&r0;UkQJwE7Mk z$`Z}Z4DInTXYHvlPzHtdM7q)!O@~4(CDCwL6=&P!6H8`ZIu8IG){ebnFOOsgJi5#J zo*23$q%3OfclD3VJx10L$%S6mR#0O{Z-fm;yH{W~(%~1?#@9nDw|X-FV4WFNNE?u= zNsUpZB9>X39R6ko>B{E@palselu!fi@;2{*99+kw!vd7==a0k1U~mtD?VxZfC+5?F zS*Nm{8|Z%mvGF+lu?k#)zW_q@WO_h`!~-H-wk-C(55!&CS9;0~tCO{qo!|0Ld`A4R z!?{Ezel$sA7!Q>QFASC6a)j3Q9elimCP?JOd_Bc7+iW%D38BRl_}=XI4MruG!$~Y! z)#3G0Ing0FLqmnq)N|04xKy0c__kp$%3zYQ=jbnv1!pZF??**9r5!AA6QQz8HaBac z-)DvlmLg^;&QlPoDNzVPj2csI+Sp_GZ>Y~5tTw?OOsB`~G>Igi6#!z}vZxRn z_mZ3%^Wj5E=1-Gbo9g3YL(lz--KY}z4P9;Rev`lWf1j9yQ{VAp+Sf5=7Hy=={c`2yJadWY-BAQd=Lk{ z_R5BjK&)=KT9B)gLV{1>rb2!28ThgAIW#%qO5B*yF`N0*A1srvHd0v*yWIk#^?)Ts zM5jSs*i*xFz2D7|(i500ZVx1J5^<9kp}e$hGHAC2LutRtBH%ytYf07!h%N|p$O_p@ zM76*Ze2pGv`4>e77PC@W+j}V~VvZ$pJA7_u0J6SUt6#Bso7y)~k6x^LN|Y_7g&3t~ zc23kDyJ8C;xg3Hmb~#>n;^|83;U1180$1Uh7VPe5U0Yj3=xI`|HIDic);1 z%Zx)#tB~cm_w^{1mrymqhd`i6ceMi`P*4dL1i~7qi~&@l{y)Y0VJg~EDlzW{YoEjk QxT*u><#`b=z=h}h2b9~@i2wiq literal 0 HcmV?d00001 diff --git a/visualization/tier4_planning_factor_rviz_plugin/package.xml b/visualization/tier4_planning_factor_rviz_plugin/package.xml new file mode 100644 index 0000000000000..f1d2ce7df6ef4 --- /dev/null +++ b/visualization/tier4_planning_factor_rviz_plugin/package.xml @@ -0,0 +1,33 @@ + + + + tier4_planning_factor_rviz_plugin + 0.40.0 + The tier4_planning_factor_rviz_plugin package + Satoshi Ota + Mamoru Sobue + Shumpei Wakabayashi + Apache 2.0 + + ament_cmake + autoware_cmake + + qtbase5-dev + + autoware_motion_utils + autoware_universe_utils + autoware_vehicle_info_utils + rviz_common + rviz_default_plugins + tier4_planning_msgs + + libqt5-widgets + rviz2 + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/visualization/tier4_planning_factor_rviz_plugin/plugins.xml b/visualization/tier4_planning_factor_rviz_plugin/plugins.xml new file mode 100644 index 0000000000000..7e5b53d2b1d61 --- /dev/null +++ b/visualization/tier4_planning_factor_rviz_plugin/plugins.xml @@ -0,0 +1,8 @@ + + + + tier4_planning_factor_rviz_plugin + tier4_planning_msgs/msg/PlanningFactorArray + + + diff --git a/visualization/tier4_planning_factor_rviz_plugin/src/planning_factor_rviz_plugin.cpp b/visualization/tier4_planning_factor_rviz_plugin/src/planning_factor_rviz_plugin.cpp new file mode 100644 index 0000000000000..9530368421596 --- /dev/null +++ b/visualization/tier4_planning_factor_rviz_plugin/src/planning_factor_rviz_plugin.cpp @@ -0,0 +1,189 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "planning_factor_rviz_plugin.hpp" + +#include +#include +#include +#include + +#include + +namespace autoware::rviz_plugins +{ + +using autoware::motion_utils::createDeadLineVirtualWallMarker; +using autoware::motion_utils::createSlowDownVirtualWallMarker; +using autoware::motion_utils::createStopVirtualWallMarker; +using autoware::universe_utils::createDefaultMarker; +using autoware::universe_utils::createMarkerScale; + +namespace +{ + +std_msgs::msg::ColorRGBA convertFromColorCode(const uint64_t code, const float alpha) +{ + const float r = static_cast(code >> 16) / 255.0; + const float g = static_cast((code << 48) >> 56) / 255.0; + const float b = static_cast((code << 56) >> 56) / 255.0; + + return autoware::universe_utils::createMarkerColor(r, g, b, alpha); +} + +std_msgs::msg::ColorRGBA getGreen(const float alpha) +{ + constexpr uint64_t code = 0x00e676; + return convertFromColorCode(code, alpha); +} + +std_msgs::msg::ColorRGBA getRed(const float alpha) +{ + constexpr uint64_t code = 0xff3d00; + return convertFromColorCode(code, alpha); +} + +std_msgs::msg::ColorRGBA getGray(const float alpha) +{ + constexpr uint64_t code = 0xbdbdbd; + return convertFromColorCode(code, alpha); +} + +visualization_msgs::msg::Marker createArrowMarker( + const size_t id, const geometry_msgs::msg::Point & position, + const std_msgs::msg::ColorRGBA & color, const std::string & name, const double height_offset, + const double arrow_length = 1.0) +{ + const double line_width = 0.25 * arrow_length; + const double head_width = 0.5 * arrow_length; + const double head_height = 0.5 * arrow_length; + + auto marker = createDefaultMarker( + "map", rclcpp::Clock{RCL_ROS_TIME}.now(), name + "_arrow", id, + visualization_msgs::msg::Marker::ARROW, createMarkerScale(line_width, head_width, head_height), + color); + + geometry_msgs::msg::Point src, dst; + src = position; + src.z += height_offset + arrow_length; + dst = position; + dst.z += height_offset; + + marker.points.push_back(src); + marker.points.push_back(dst); + + return marker; +} + +visualization_msgs::msg::Marker createCircleMarker( + const size_t id, const geometry_msgs::msg::Point & position, + const std_msgs::msg::ColorRGBA & color, const std::string & name, const double radius, + const double height_offset, const double line_width = 0.1) +{ + auto marker = createDefaultMarker( + "map", rclcpp::Clock{RCL_ROS_TIME}.now(), name, id, visualization_msgs::msg::Marker::LINE_STRIP, + createMarkerScale(line_width, 0.0, 0.0), color); + + constexpr size_t num_points = 20; + for (size_t i = 0; i < num_points; ++i) { + geometry_msgs::msg::Point point; + const double ratio = static_cast(i) / static_cast(num_points); + const double theta = 2 * autoware::universe_utils::pi * ratio; + point.x = position.x + radius * autoware::universe_utils::cos(theta); + point.y = position.y + radius * autoware::universe_utils::sin(theta); + point.z = position.z + height_offset; + marker.points.push_back(point); + } + marker.points.push_back(marker.points.front()); + + return marker; +} + +visualization_msgs::msg::Marker createNameTextMarker( + const size_t id, const geometry_msgs::msg::Point & position, const std::string & name, + const double height_offset, const double text_size = 0.5) +{ + auto marker = createDefaultMarker( + "map", rclcpp::Clock{RCL_ROS_TIME}.now(), name + "_name_text", id, + visualization_msgs::msg::Marker::TEXT_VIEW_FACING, createMarkerScale(0.0, 0.0, text_size), + getGray(0.999)); + + marker.text = name; + + marker.pose.position = position; + marker.pose.position.z += height_offset; + + return marker; +} + +visualization_msgs::msg::MarkerArray createTargetMarker( + const size_t id, const geometry_msgs::msg::Point & position, + const std_msgs::msg::ColorRGBA & color, const std::string & name, + const double height_offset = 2.0, const double arrow_length = 1.0, const double line_width = 0.1) +{ + visualization_msgs::msg::MarkerArray marker_array; + marker_array.markers.push_back( + createArrowMarker(id, position, color, name, height_offset, arrow_length)); + marker_array.markers.push_back(createCircleMarker( + id, position, color, name + "_circle1", 0.5 * arrow_length, height_offset + 0.75 * arrow_length, + line_width)); + marker_array.markers.push_back(createCircleMarker( + id, position, color, name + "_circle2", 0.75 * arrow_length, + height_offset + 0.75 * arrow_length, line_width)); + marker_array.markers.push_back(createNameTextMarker( + id, position, name, height_offset + 1.5 * arrow_length, 0.5 * arrow_length)); + + return marker_array; +} +} // namespace + +void PlanningFactorRvizPlugin::processMessage( + const tier4_planning_msgs::msg::PlanningFactorArray::ConstSharedPtr msg) +{ + size_t i = 0L; + for (const auto & factor : msg->factors) { + const auto text = factor.module + (factor.detail.empty() ? "" : " (" + factor.detail + ")"); + + switch (factor.behavior) { + case tier4_planning_msgs::msg::PlanningFactor::STOP: + for (const auto & control_point : factor.control_points) { + const auto virtual_wall = createStopVirtualWallMarker( + control_point.pose, text, msg->header.stamp, i++, baselink2front_.getFloat()); + add_marker(std::make_shared(virtual_wall)); + } + break; + + case tier4_planning_msgs::msg::PlanningFactor::SLOW_DOWN: + for (const auto & control_point : factor.control_points) { + const auto virtual_wall = createSlowDownVirtualWallMarker( + control_point.pose, text, msg->header.stamp, i++, baselink2front_.getFloat()); + add_marker(std::make_shared(virtual_wall)); + } + break; + } + + for (const auto & safety_factor : factor.safety_factors.factors) { + const auto color = safety_factor.is_safe ? getGreen(0.999) : getRed(0.999); + for (const auto & point : safety_factor.points) { + const auto safety_factor_marker = createTargetMarker(i++, point, color, factor.module); + add_marker(std::make_shared(safety_factor_marker)); + } + } + } +} +} // namespace autoware::rviz_plugins + +// Export the plugin +#include // NOLINT +PLUGINLIB_EXPORT_CLASS(autoware::rviz_plugins::PlanningFactorRvizPlugin, rviz_common::Display) diff --git a/visualization/tier4_planning_factor_rviz_plugin/src/planning_factor_rviz_plugin.hpp b/visualization/tier4_planning_factor_rviz_plugin/src/planning_factor_rviz_plugin.hpp new file mode 100644 index 0000000000000..f2af16e3e06b1 --- /dev/null +++ b/visualization/tier4_planning_factor_rviz_plugin/src/planning_factor_rviz_plugin.hpp @@ -0,0 +1,103 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef PLANNING_FACTOR_RVIZ_PLUGIN_HPP_ +#define PLANNING_FACTOR_RVIZ_PLUGIN_HPP_ + +#include +#include +#include +#include +#include + +#include + +#include + +namespace autoware::rviz_plugins +{ + +using RosTopicDisplay = rviz_common::RosTopicDisplay; + +class PlanningFactorRvizPlugin +: public rviz_common::RosTopicDisplay +{ +public: + PlanningFactorRvizPlugin() + : marker_common_{this}, + baselink2front_{"Baselink To Front", 0.0, "Length between base link to front.", this}, + topic_name_{"planning_factors"} + { + } + + void onInitialize() override + { + RosTopicDisplay::RTDClass::onInitialize(); + marker_common_.initialize(this->context_, this->scene_node_); + QString message_type = QString::fromStdString( + rosidl_generator_traits::name()); + this->topic_property_->setMessageType(message_type); + this->topic_property_->setValue(topic_name_.c_str()); + this->topic_property_->setDescription("Topic to subscribe to."); + + const auto vehicle_info = + autoware::vehicle_info_utils::VehicleInfoUtils(*rviz_ros_node_.lock()->get_raw_node()) + .getVehicleInfo(); + baselink2front_.setValue(vehicle_info.max_longitudinal_offset_m); + } + + void load(const rviz_common::Config & config) override + { + RosTopicDisplay::Display::load(config); + marker_common_.load(config); + } + + void update(float wall_dt, float ros_dt) override { marker_common_.update(wall_dt, ros_dt); } + + void reset() override + { + RosTopicDisplay::reset(); + marker_common_.clearMarkers(); + } + + void clear_markers() { marker_common_.clearMarkers(); } + + void add_marker(visualization_msgs::msg::Marker::ConstSharedPtr marker_ptr) + { + marker_common_.addMessage(marker_ptr); + } + + void add_marker(visualization_msgs::msg::MarkerArray::ConstSharedPtr markers_ptr) + { + marker_common_.addMessage(markers_ptr); + } + + void delete_marker(rviz_default_plugins::displays::MarkerID marker_id) + { + marker_common_.deleteMarker(marker_id); + } + +private: + void processMessage( + const tier4_planning_msgs::msg::PlanningFactorArray::ConstSharedPtr msg) override; + + rviz_default_plugins::displays::MarkerCommon marker_common_; + + rviz_common::properties::FloatProperty baselink2front_; + + std::string topic_name_; +}; +} // namespace autoware::rviz_plugins + +#endif // PLANNING_FACTOR_RVIZ_PLUGIN_HPP_ From 374316bb20f537766fddbbc9ede755a0309c9765 Mon Sep 17 00:00:00 2001 From: TetsuKawa <70682030+TetsuKawa@users.noreply.github.com> Date: Wed, 22 Jan 2025 15:05:56 +0900 Subject: [PATCH 279/334] fix(tier4_system_launch): add autoware prefix to dummy diag publisher launcher (#9959) fix: add autoare_ to dummy_diag_publisher Signed-off-by: TetsuKawa --- launch/tier4_system_launch/launch/system.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/launch/tier4_system_launch/launch/system.launch.xml b/launch/tier4_system_launch/launch/system.launch.xml index 5090f9ab83293..0e0e0e78c1dba 100644 --- a/launch/tier4_system_launch/launch/system.launch.xml +++ b/launch/tier4_system_launch/launch/system.launch.xml @@ -113,7 +113,7 @@ - + From a24a335af7c3a5c31d93aab6598d1e403567336b Mon Sep 17 00:00:00 2001 From: mkquda <168697710+mkquda@users.noreply.github.com> Date: Wed, 22 Jan 2025 15:20:42 +0900 Subject: [PATCH 280/334] docs(lane_change): update lane change documentation (#9949) * update lane change requirements documentation Signed-off-by: mohammad alqudah * remove unused function getNumToPreferredLane Signed-off-by: mohammad alqudah * update candidate path generation documentation Signed-off-by: mohammad alqudah * update prepare phase and lane changing phase documentation Signed-off-by: mohammad alqudah * update longitudinal acceleration sampling documentation Signed-off-by: mohammad alqudah * add prepare duration sampling documentation Signed-off-by: mohammad alqudah * update candidate path validity and safety documentation Signed-off-by: mohammad alqudah * fix formatting Signed-off-by: mohammad alqudah * update image and fix formatting Signed-off-by: mohammad alqudah * add overtaking turn lane documentation Signed-off-by: mohammad alqudah * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> * add LC global flowchart to documentation Signed-off-by: mohammad alqudah * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> * reorganize lane change documentation Signed-off-by: mohammad alqudah * fix section title Signed-off-by: mohammad alqudah * add global flowchart description Signed-off-by: mohammad alqudah * add warning Signed-off-by: mohammad alqudah * apply pre-commit checks Signed-off-by: mohammad alqudah * fix spelling Signed-off-by: mohammad alqudah * edit some descriptions Signed-off-by: mohammad alqudah --------- Signed-off-by: mohammad alqudah Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> --- .../README.md | 789 +++++++++++------- .../lane_change-candidate_path_samples.png | Bin 246773 -> 0 bytes .../lane_change-intersection_turn_lane_1.png | Bin 0 -> 8152 bytes .../lane_change-intersection_turn_lane_2.png | Bin 0 -> 9243 bytes .../images/lane_change-lon_accel_sampling.png | Bin 0 -> 249998 bytes .../base_class.hpp | 2 - .../scene.hpp | 2 - .../src/scene.cpp | 7 - 8 files changed, 490 insertions(+), 310 deletions(-) delete mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/lane_change-candidate_path_samples.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/lane_change-intersection_turn_lane_1.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/lane_change-intersection_turn_lane_2.png create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/lane_change-lon_accel_sampling.png diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md index 40ddce904e435..ba90713a221d9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md @@ -1,24 +1,141 @@ # Lane Change design -The Lane Change module is activated when lane change is needed and can be safely executed. - -## Lane Change Requirement - -- As the prerequisite, the type of lane boundary in the HD map has to be one of the following: - - Dashed lane marking: Lane changes are permitted in both directions. - - Dashed marking on the left and solid on the right: Lane changes are allowed from left to right. - - Dashed marking on the right and solid on the left: Lane changes are allowed from right to left. - - `allow_lane_change` tags is set as `true` -- During lane change request condition - - The ego-vehicle isn’t on a `preferred_lane`. - - The ego-vehicle isn't approaching a traffic light. (condition parameterized) - - The ego-vehicle isn't approaching a crosswalk. (condition parameterized) - - The ego-vehicle isn't approaching an intersection. (condition parameterized) -- lane change ready condition - - Path of the lane change does not collide with other dynamic objects (see the figure below) - - Lane change candidate path is approved by an operator. - -## Generating Lane Change Candidate Path +The Lane Change module is activated when lane change is needed (Ego is not on preferred lane), and activation requirements are satisfied. + +## Lane Change Requirements + +### Prerequisites + +The type of lane boundary in the HD map has to be one of the following: + +- Dashed lane marking: Lane changes are permitted in both directions. +- Dashed marking on the left and solid on the right: Lane changes are allowed from left to right. +- Dashed marking on the right and solid on the left: Lane changes are allowed from right to left. +- `allow_lane_change` tags is set as `true` + +### Activation Conditions + +The lane change module will activate under the following conditions : + +- The ego-vehicle is NOT on a `preferred_lane`. +- Distance to start of `target_lane` is less than `maximum_prepare_length` +- The ego-vehicle is NOT close to a regulatory element: + - Distance to next regulatory element is greater than `maximum_prepare_length`. + - Considers distance to traffic light. (If param `regulation.traffic_light` is enabled) + - Considers distance to crosswalk. (If param `regulation.crosswalk` is enabled) + - Considers distance to intersection. (If param `regulation.intersection` is enabled) + +!!! warning + + If ego vehicle is stuck, lane change will be enabled near crosswalk/intersection. Ego is considered stuck if it stops more than `stuck_detection.stop_time`. Ego is considered to be stopping if its velocity is smaller than `stuck_detection.velocity`. + +The following figure illustrates the logic for checking if lane change is required: + +```plantuml +@startuml +skinparam defaultTextAlignment center +skinparam backgroundColor #WHITE + +start + +if (Is data available AND lanes available) then (no) + #LightPink:False; + stop +else (yes) +endif + +:Get distance to target lane start; + +if (Is dist to target lane start < max prepare dist) then (no) + #LightPink:False; + stop +else (yes) +endif + +:Get distance to next regulatory element; + +if (Is dist to next regulatory element < max prepare dist) then (yes) + #LightPink:False; + stop +else (no) +end if + +#LightGreen:True; +stop + +@enduml +``` + +### Ready Conditions + +- Valid lane change path is found. +- Lane change path is safe; does not collide with other dynamic objects. +- Lane change candidate path is approved by an operator. + +## Implementation + +Lane change module uses a sampling based approach for generating a valid and safe lane changing trajectory. The process for generating the trajectory includes object filtering, metrics sampling, candidate paths generation, and lastly candidate paths evaluation. +Additionally the lane change module is responsible for turn signal activation when appropriate, and inserting a stop point when necessary. + +### Global Flowchart + +The following diagram, illustrates the overall flow of the lane change module implementation. + +```plantuml +@startuml + +start + +#LightBlue:Update lane change data; +#LightBlue:Filter detected objects; +if (Is lane change required?) then (yes) + #LightBlue:Activate turn signal; + #LightBlue:Generate metrics samples; + if (Is valid metrics available) then (yes) + While (Can generate new candidate path?) is (TRUE) + if (Candidate path is valid & safe?) then (yes) + #LightBlue:Generate drivable area; + #LightBlue:Execute lane change path; + while (Can module transit to success state?) is (False) + if (Can module trasit to failure state?) then (yes) + if (Can cancel or abort?) then (yes) + #LightBlue:Cancel/Abort; + #Orange:Restart process; + stop + else (no) + endif + else (no) + endif + endwhile (True) + #LightGreen:SUCCESS; + stop + else (no) + endif + endwhile (FALSE) + else (no) + endif +else (no) +endif +#LightBlue:Insert stop point; +#LightBlue:Execute previous approved path; +#Orange:Restart process; +stop + +@enduml +``` + +The lane change module first updates the necessary data for lane change such as lanes information and transient data. Then filters the detected objects to be used for safety evaluation (see [Object Filtering](#object-filtering)). + +If the lane change requirements are met, the turn signal is activated and the lane change module will proceed to generating a candidate path. Lane change candidate paths are generated by sampling different metrics and evaluating the validity of the corresponding generated trajectory. More details can be found in [Generating Lane Change Candidate Path](#generating-lane-change-candidate-path); + +When a valid candidate path is generated, a safety evaluation is conducted to check for any risk of collision or hindrance. The details of the safety evaluation can be found in [Safety Checks](#safety-checks). + +Once a valid and safe candidate path is found, the drivable area is generated and the path is executed. While executing the lane change maneuver, the safety of the approved path is continuously monitored to ensure there is no chance of collision or other hindrance. If the approved path remains safe and completion checks are met (see [Lane Change Completion Checks](#lane-change-completion-checks)) the module will transit to **SUCCESS** state. +In case the approved path is deemed to be no longer safe, the lane change module will attempt to abort the lane change maneuver (see [Aborting Lane Change](#aborting-lane-change)). When the lane change maneuver is aborted successfully the module will transit to **FAILURE** state, and the process is restarted. + +If the lane change module fails to find a valid and safe candidate path, the module will continue executing the previously approved path and insert a stop point along the path where appropriate, for more details refer to [Stopping Behavior](#stopping-behavior). + +### Generating Lane Change Candidate Path The lane change candidate path is divided into two phases: preparation and lane-changing. The following figure illustrates each phase of the lane change candidate path. @@ -43,39 +160,62 @@ endif :Calculate prepare phase metrics; -:Start loop through prepare phase metrics; - -repeat - :Get prepare segment; - - if (Is LC start point outside target lanes range) then (yes) - if (Is found a valid path) then (yes) - #Orange:Return first valid path; - stop - else (no) - #LightPink:Return prev approved path; - stop - endif - else (no) - endif - - :Calculate shift phase metrics; - - :Start loop through shift phase metrics; - repeat - :Get candidate path; - note left: Details shown in the next chart - if (Is valid candidate path?) then (yes) - :Store candidate path; - if (Is candidate path safe?) then (yes) - #LightGreen:Return candidate path; - stop +if(Is near terminal AND frenet enabled) then (yes) + group Frenet Candidate Paths #Lavender + :Calculate frenet candidates; + :Start loop through frenet candidates; + repeat + :Get candidate path; + if (Is valid candidate path?) then (yes) + if (Is candidate path safe?) then (yes) + #LightGreen:Return candidate path; + stop + else (no) + if (Is first valid path) then (yes) + :Store candidate path; + else (no) + endif + endif + else (no) + endif + repeat while (Finished looping frenet candidates) is (FALSE) + end group +else (no) + group Path Shifter Candidate Paths #LightCyan + :Start loop through prepare phase metrics; + repeat + :Get prepare segment; + + if (Is LC start point outside target lanes range) then (yes) + if (Is found a valid path) then (yes) + #Orange:Return first valid path; + stop + else (no) + #LightPink:Return prev approved path; + stop + endif else (no) endif - else (no) - endif - repeat while (Finished looping shift phase metrics) is (FALSE) - repeat while (Is finished looping prepare phase metrics) is (FALSE) + + :Calculate shift phase metrics; + + :Start loop through shift phase metrics; + repeat + :Get candidate path; + note left: Details shown in the next chart + if (Is valid candidate path?) then (yes) + :Store candidate path; + if (Is candidate path safe?) then (yes) + #LightGreen:Return candidate path; + stop + else (no) + endif + else (no) + endif + repeat while (Finished looping shift phase metrics) is (FALSE) + repeat while (Is finished looping prepare phase metrics) is (FALSE) + endgroup +endif if (Is found a valid path) then (yes) #Orange:Return first valid path; @@ -89,7 +229,7 @@ stop @enduml ``` -While the following chart demonstrates the process of generating a valid candidate path. +The following chart demonstrates the process of generating a valid candidate path with path shifter method. ```plantuml @startuml @@ -126,37 +266,76 @@ endif @enduml ``` -### Preparation phase +#### Prepare Phase -The preparation trajectory is the candidate path's first and the straight portion generated along the ego vehicle's current lane. The length of the preparation trajectory is computed as follows. +The prepare phase is the first section of the lane change candidate path and the corresponding prepare segment consists of a subsection of the current reference path along the current lane. The length of the prepare phase trajectory is computed as follows. ```C++ -lane_change_prepare_distance = current_speed * lane_change_prepare_duration + 0.5 * deceleration * lane_change_prepare_duration^2 +prepare_distance = current_speed * prepare_duration + 0.5 * lon_acceleration * prepare_duration^2 ``` -During the preparation phase, the turn signal will be activated when the remaining distance is equal to or less than `lane_change_search_distance`. +The prepare phase trajectory is valid if: + +- The length of the prepare phase trajectory is greater than the distance to start of target lane +- The length of the prepare phase trajectory is less than the distance to terminal start point + +#### Lane-changing Phase -### Lane-changing phase +The lane-changing phase consists of the shifted path that moves ego from current lane to the target lane. Total duration of lane-changing phase is computed from the `shift_length`, `lateral_jerk` and `lateral_acceleration`. -The lane-changing phase consist of the shifted path that moves ego from current lane to the target lane. Total distance of lane-changing phase is as follows. Note that during the lane changing phase, the ego vehicle travels at a constant speed. +In principle, positive longitudinal acceleration is considered during lane-changing phase, and is computed as follows. ```C++ -lane_change_prepare_velocity = std::max(current_speed + deceleration * lane_change_prepare_duration, minimum_lane_changing_velocity) -lane_changing_distance = lane_change_prepare_velocity * lane_changing_duration +lane_changing_acceleration = std::clamp((max_path_velocity - initial_lane_changing_velocity) / lane_changing_time, + 0.0, prepare_longitudinal_acc); +``` + +Where `max_path_velocity` is the current path speed limit. + +!!! warning + + If the longitudinal acceleration of prepare phase is negative (slowing down), AND ego is near terminal, then the lane-changing longitudinal acceleration will also be negative and its value is decided by the parameter `lane_changing_decel_factor`. + +The lane changing distance is then computed as follows. + +```C++ +lane_changing_distance = initial_lane_changing_velocity * lane_changing_duration + 0.5 * lon_acceleration * lane_changing_duration^2 ``` The `backward_length_buffer_for_end_of_lane` is added to allow some window for any possible delay, such as control or mechanical delay during brake lag. -#### Multiple candidate path samples (longitudinal acceleration) +#### Sampling Multiple Candidate Paths + +In order to find a valid and safe lane change path it might be necessary to generate multiple candidate path samples. The lane change module does this by sampling one or more of: `prepare_duration`, `longitudinal_acceleration`, and `lateral_acceleration`. -Lane change velocity is affected by the ego vehicle's current velocity. High velocity requires longer preparation and lane changing distance. However we also need to plan lane changing trajectories in case ego vehicle slows down. -Computing candidate paths that assumes ego vehicle's slows down is performed by substituting predetermined deceleration value into `prepare_length`, `prepare_velocity` and `lane_changing_length` equation. +##### Prepare Duration Sampling -The predetermined longitudinal acceleration values are a set of value that starts from `longitudinal_acceleration = maximum_longitudinal_acceleration`, and decrease by `longitudinal_acceleration_resolution` until it reaches `longitudinal_acceleration = -maximum_longitudinal_deceleration`. Both `maximum_longitudinal_acceleration` and `maximum_longitudinal_deceleration` are calculated as: defined in the `common.param` file as `normal.min_acc`. +In principle, a fixed prepare duration is assumed when generating lane change candidate path. The default prepare duration value is determined from the min and max values set in the lane change parameters, as well as the duration of turn signal activation. +For example, when the lane change module first activates and turn signal is activated then prepare duration will be `max_prepare_duration`, as time passes and a path is still not approved, the prepare duration will decrease gradually down to `min_prepare_duration`. The formula is as follows. + +```C++ +prepare_duration = std::max(max_prepare_duration - turn_signal_duration, min_prepare_duration); +``` + +!!! note + + When the current ego velocity is lower than the `min_lane_change_velocity`, the `min_prepare_duration` is adjusted to ensure sufficient time for reaching `min_lane_change_velocity` assuming `max_longitudinal_acceleration`. + +!!! warning + + The value of the prepare duration impacts lane change cancelling behavior. A shorter prepare duration results in a smaller window in which lane change maneuver can be cancelled. See [Evaluating Ego Vehicle's Position to Prevent Abrupt Maneuvers](#evaluating-ego-vehicles-position-to-prevent-abrupt-maneuvers) for more details. + +When ego vehicles is close to the terminal start, we need to sample multiple prepare duration values to find a valid and safe path. In this case prepare duration values are sampled starting from `max_prepare_duration` down to `0.0` at a fixed time interval of `0.5 s`. + +##### Longitudinal Acceleration Sampling + +In principle, maximum longitudinal acceleration is assumed for generating lane change candidate path. +However in certain situations, we need to sample multiple longitudinal acceleration values to find a valid and safe candidate path. +The lower and upper bounds of the longitudinal acceleration sampled are determined from the values specified in the lane change parameters and common planner parameters, as follows ```C++ maximum_longitudinal_acceleration = min(common_param.max_acc, lane_change_param.max_acc) -maximum_longitudinal_deceleration = max(common_param.min_acc, lane_change_param.min_acc) +minimum_longitudinal_acceleration = max(common_param.min_acc, lane_change_param.min_acc) ``` where `common_param` is vehicle common parameter, which defines vehicle common maximum longitudinal acceleration and deceleration. Whereas, `lane_change_param` has maximum longitudinal acceleration and deceleration for the lane change module. For example, if a user set and `common_param.max_acc=1.0` and `lane_change_param.max_acc=0.0`, `maximum_longitudinal_acceleration` becomes `0.0`, and the lane change does not accelerate in the lane change phase. @@ -167,9 +346,7 @@ The `longitudinal_acceleration_resolution` is determine by the following longitudinal_acceleration_resolution = (maximum_longitudinal_acceleration - minimum_longitudinal_acceleration) / longitudinal_acceleration_sampling_num ``` -Note that when the `current_velocity` is lower than `minimum_lane_changing_velocity`, the vehicle needs to accelerate its velocity to `minimum_lane_changing_velocity`. Therefore, longitudinal acceleration becomes positive value (not decelerate). - -The chart illustrates the conditions under which longitudinal acceleration values are sampled. +The chart below illustrates the conditions under which longitudinal acceleration values are sampled. ```plantuml @startuml @@ -233,7 +410,7 @@ if (min_acc > max_acc) then (yes) :Return empty list; stop elseif (max_acc - min_acc < epsilon) then (yes) - :Return {0.0}; + :Return {min_acc}; stop else (no) :Calculate resolution; @@ -243,24 +420,27 @@ endif repeat if (sampled_values.back() < -epsilon AND next_value > epsilon) then (yes) :Insert 0.0 into sampled_values; + else (no) endif :Add sampled_acc to sampled_values; repeat while (sampled_acc < max_acc + epsilon) is (TRUE) +:Reverse sampled_values; :Return sampled_values; stop @enduml ``` -The following figure illustrates when `longitudinal_acceleration_sampling_num = 4`. Assuming that `maximum_deceleration = 1.0` then `a0 == 0.0 == no deceleration`, `a1 == 0.25`, `a2 == 0.5`, `a3 == 0.75` and `a4 == 1.0 == maximum_deceleration`. `a0` is the expected lane change trajectories should ego vehicle do not decelerate, and `a1`'s path is the expected lane change trajectories should ego vehicle decelerate at `0.25 m/s^2`. +The following figure illustrates when `longitudinal_acceleration_sampling_num = 4`. Assuming that `maximum_acceleration = 1.0` and `minimum_acceleration = 1.0` then `a0 == 1.0`, `a1 == 0.5`, `a2 == 0.0`, `a3 == -0.5` and `a4 == -1.0`. `a0` is the expected lane change trajectory when sampling is not required. -![path_samples](./images/lane_change-candidate_path_samples.png) +![path_samples](./images/lane_change-lon_accel_sampling.png) -Which path will be chosen will depend on validity and collision check. +Which path will be chosen depends on validity and safety checks. -#### Multiple candidate path samples (lateral acceleration) +##### Lateral Acceleration Sampling -In addition to sampling longitudinal acceleration, we also sample lane change paths by adjusting the value of lateral acceleration. Since lateral acceleration influences the duration of a lane change, a lower lateral acceleration value results in a longer lane change path, while a higher lateral acceleration value leads to a shorter lane change path. This allows the lane change module to generate a shorter lane change path by increasing the lateral acceleration when there is limited space for the lane change. +In addition to sampling longitudinal acceleration, we also sample lane change paths by varying the lateral acceleration. +Lateral acceleration affects the lane changing duration, a lower value results in a longer trajectory, while a higher value results in a shorter trajectory. This allows the lane change module to explore shorter trajectories through higher lateral acceleration when there is limited space for the lane change. The maximum and minimum lateral accelerations are defined in the lane change parameter file as a map. The range of lateral acceleration is determined for each velocity by linearly interpolating the values in the map. Let's assume we have the following map @@ -279,9 +459,190 @@ Within this range, we sample the lateral acceleration for the ego vehicle. Simil lateral_acceleration_resolution = (maximum_lateral_acceleration - minimum_lateral_acceleration) / lateral_acceleration_sampling_num ``` +#### Terminal Lane Change Path + +Depending on the space configuration around the Ego vehicle, it is possible that a valid LC path cannot be generated. If that happens, then Ego will get stuck at `terminal_start` and not be able to proceed. Therefore we introduced the terminal LC path feature; when ego gets near to the terminal point (dist to `terminal_start` is less than the maximum lane change length) a terminal lane changing path will be computed starting from the terminal start point on the current lane and connects to the target lane. The terminal path only needs to be computed once in each execution of LC module. If no valid candidate paths are found in the path generation process, then the terminal path will be used as a fallback candidate path, the safety of the terminal path is not ensured and therefore it can only be force approved. The following images illustrate the expected behavior without and with the terminal path feature respectively: + +![no terminal path](./images/lane_change-no_terminal_path.png) + +![terminal path](./images/lane_change-terminal_path.png) + +Additionally if terminal path feature is enabled and path is computed, stop point placement can be configured to be at the edge of the current lane instead of at the `terminal_start` position, as indicated by the dashed red line in the image above. + +#### Generating Path Using Frenet Planner + +!!! warning + + Generating path using Frenet planner applies only when ego is near terminal start + +If the ego vehicle is far from the terminal, the lane change module defaults to using the [path shifter](https://autowarefoundation.github.io/autoware.universe/main/planning/behavior_path_planner/autoware_behavior_path_planner_common/docs/behavior_path_planner_path_generation_design/). This ensures that the lane change is completed while the target lane remains a neighbor of the current lane. However, this approach may result in high curvature paths near the terminal, potentially causing long vehicles to deviate from the lane. + +To address this, the lane change module provides an option to choose between the path shifter and the [Frenet planner](https://autowarefoundation.github.io/autoware.universe/main/planning/sampling_based_planner/autoware_frenet_planner/). The Frenet planner allows for some flexibility in the lane change endpoint, extending the lane changing end point slightly beyond the current lane's neighbors. + +The following table provides comparisons between the planners + +